pax_global_header00006660000000000000000000000064145630166230014520gustar00rootroot0000000000000052 comment=0d5426b5851be80dd8e51470a0784a73565a3006 mrcal-2.4.1/000077500000000000000000000000001456301662300126225ustar00rootroot00000000000000mrcal-2.4.1/.gitattributes000066400000000000000000000000001456301662300155030ustar00rootroot00000000000000mrcal-2.4.1/.gitignore000066400000000000000000000005371456301662300146170ustar00rootroot00000000000000*~ *.d *.o *.so* *.docstring.h cscope* *.pyc *.orig *.i *.rej *generated* *GENERATED* core* debian/*.log debian/*.substvars debian/*-stamp debian/*.debhelper debian/files debian/*/ *.pickle test-gradients test/test-lensmodel-string-manipulation test/test-cahvor test/test-parser-cameramodel *.pod *GENERATED.* *.backup* *.fig.bak ltximg/ doc/out mrcal-2.4.1/CHOLMOD_factorization.docstring000066400000000000000000000054041456301662300205640ustar00rootroot00000000000000A basic Python interface to CHOLMOD SYNOPSIS from scipy.sparse import csr_matrix indptr = np.array([0, 2, 3, 6, 8]) indices = np.array([0, 2, 2, 0, 1, 2, 1, 2]) data = np.array([1, 2, 3, 4, 5, 6, 7, 8], dtype=float) Jsparse = csr_matrix((data, indices, indptr)) Jdense = Jsparse.toarray() print(Jdense) ===> [[1. 0. 2.] [0. 0. 3.] [4. 5. 6.] [0. 7. 8.]] bt = np.array(((1., 5., 3.), (2., -2., -8))) print(nps.transpose(bt)) ===> [[ 1. 2.] [ 5. -2.] [ 3. -8.]] F = mrcal.CHOLMOD_factorization(Jsparse) xt = F.solve_xt_JtJ_bt(bt) print(nps.transpose(xt)) ===> [[ 0.02199662 0.33953751] [ 0.31725888 0.46982516] [-0.21996616 -0.50648618]] print(nps.matmult(nps.transpose(Jdense), Jdense, nps.transpose(xt))) ===> [[ 1. 2.] [ 5. -2.] [ 3. -8.]] The core of the mrcal optimizer is a sparse linear least squares solver using CHOLMOD to solve a large, sparse linear system. CHOLMOD is a C library, but it is sometimes useful to invoke it from Python. The CHOLMOD_factorization class factors a matrix JtJ, and this method uses that factorization to efficiently solve the linear equation JtJ x = b. The usual linear algebra conventions refer to column vectors, but numpy generally deals with row vectors, so I talk about solving the equivalent transposed problem: xt JtJ = bt. The difference is purely notational. The class takes a sparse array J as an argument in __init__(). J is optional, but there's no way in Python to pass it later, so from Python you should always pass J. This is optional for internal initialization from C code. J must be given as an instance of scipy.sparse.csr_matrix. csr is a row-major sparse representation. CHOLMOD wants column-major matrices, so it see this matrix J as a transpose: the CHOLMOD documentation refers to this as "At". And the CHOLMOD documentation talks about factoring AAt, while I talk about factoring JtJ. These are the same thing. The factorization of JtJ happens in __init__(), and we use this factorization later (as many times as we want) to solve JtJ x = b by calling solve_xt_JtJ_bt(). This class carefully checks its input for validity, but makes no effort to be flexible: anything that doesn't look right will result in an exception. Specifically: - J.data, J.indices, J.indptr must all be numpy arrays - J.data, J.indices, J.indptr must all have exactly one dimension - J.data, J.indices, J.indptr must all be C-contiguous (the normal numpy order) - J.data must hold 64-bit floating-point values (dtype=float) - J.indices, J.indptr must hold 32-bit integers (dtype=np.int32) ARGUMENTS The __init__() function takes - J: a sparse array in a scipy.sparse.csr_matrix object mrcal-2.4.1/CHOLMOD_factorization_rcond.docstring000066400000000000000000000015061456301662300217500ustar00rootroot00000000000000Compute rough estimate of reciprocal of condition number SYNOPSIS b, x, J, factorization = \ mrcal.optimizer_callback(**optimization_inputs) rcond = factorization.rcond() Calls cholmod_rcond(). Its documentation says: Returns a rough estimate of the reciprocal of the condition number: the minimum entry on the diagonal of L (or absolute entry of D for an LDLT factorization) divided by the maximum entry. L can be real, complex, or zomplex. Returns -1 on error, 0 if the matrix is singular or has a zero or NaN entry on the diagonal of L, 1 if the matrix is 0-by-0, or min(diag(L))/max(diag(L)) otherwise. Never returns NaN; if L has a NaN on the diagonal it returns zero instead. ARGUMENTS - None RETURNED VALUE A single floating point value: an estimate of the reciprocal of the condition number mrcal-2.4.1/CHOLMOD_factorization_solve_xt_JtJ_bt.docstring000066400000000000000000000043651456301662300237500ustar00rootroot00000000000000Solves the linear system JtJ x = b using CHOLMOD SYNOPSIS from scipy.sparse import csr_matrix indptr = np.array([0, 2, 3, 6, 8]) indices = np.array([0, 2, 2, 0, 1, 2, 1, 2]) data = np.array([1, 2, 3, 4, 5, 6, 7, 8], dtype=float) Jsparse = csr_matrix((data, indices, indptr)) Jdense = Jsparse.toarray() print(Jdense) ===> [[1. 0. 2.] [0. 0. 3.] [4. 5. 6.] [0. 7. 8.]] bt = np.array(((1., 5., 3.), (2., -2., -8))) print(nps.transpose(bt)) ===> [[ 1. 2.] [ 5. -2.] [ 3. -8.]] F = mrcal.CHOLMOD_factorization(Jsparse) xt = F.solve_xt_JtJ_bt(bt) print(nps.transpose(xt)) ===> [[ 0.02199662 0.33953751] [ 0.31725888 0.46982516] [-0.21996616 -0.50648618]] print(nps.matmult(nps.transpose(Jdense), Jdense, nps.transpose(xt))) ===> [[ 1. 2.] [ 5. -2.] [ 3. -8.]] The core of the mrcal optimizer is a sparse linear least squares solver using CHOLMOD to solve a large, sparse linear system. CHOLMOD is a C library, but it is sometimes useful to invoke it from Python. The CHOLMOD_factorization class factors a matrix JtJ, and this method uses that factorization to efficiently solve the linear equation JtJ x = b. The usual linear algebra conventions refer to column vectors, but numpy generally deals with row vectors, so I talk about solving the equivalent transposed problem: xt JtJ = bt. The difference is purely notational. As many vectors b as we'd like may be given at one time (in rows of bt). The dimensions of the returned array xt will match the dimensions of the given array bt. Broadcasting is supported: any leading dimensions will be processed correctly, as long as bt has shape (..., Nstate) This function carefully checks its input for validity, but makes no effort to be flexible: anything that doesn't look right will result in an exception. Specifically: - bt must be C-contiguous (the normal numpy order) - bt must contain 64-bit floating-point values (dtype=float) ARGUMENTS - bt: a numpy array of shape (..., Nstate). This array must be C-contiguous and it must have dtype=float RETURNED VALUE The transpose of the solution array x, in a numpy array of the same shape as the input bt mrcal-2.4.1/LICENSE000066400000000000000000000262741456301662300136420ustar00rootroot00000000000000 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 APPENDIX: How to apply the Apache License to your work. To apply the Apache License to your work, attach the following boilerplate notice, with the fields enclosed by brackets "[]" replaced with your own identifying information. (Don't include the brackets!) The text should be enclosed in the appropriate comment syntax for the file format. We also recommend that a file or class name and description of purpose be included on the same "printed page" as the copyright notice for easier identification within third-party archives. Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. Government sponsorship acknowledged. 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. mrcal-2.4.1/Makefile000066400000000000000000000113011456301662300142560ustar00rootroot00000000000000include choose_mrbuild.mk include $(MRBUILD_MK)/Makefile.common.header # "0" or undefined means "false" # everything else means "true" # libelas stereo matcher. Available in Debian/non-free. I don't want to depend # on anything in non-free, so I default to not using libelas USE_LIBELAS ?= 0 # convert all USE_XXX:=0 to an empty string $(foreach v,$(filter USE_%,$(.VARIABLES)),$(if $(filter 0,${$v}),$(eval undefine $v))) # to print them all: $(foreach v,$(filter USE_%,$(.VARIABLES)),$(warning $v = '${$v}')) PROJECT_NAME := mrcal ABI_VERSION := 4 TAIL_VERSION := 0 VERSION := $(VERSION_FROM_PROJECT) LIB_SOURCES += \ mrcal.c \ mrcal-opencv.c \ mrcal-image.c \ stereo.c \ poseutils.c \ poseutils-opencv.c \ poseutils-uses-autodiff.cc \ triangulation.cc \ cahvore.cc ifneq (${USE_LIBELAS},) # using libelas LIB_SOURCES := $(LIB_SOURCES) stereo-matching-libelas.cc endif BIN_SOURCES += \ test-gradients.c \ test/test-cahvor.c \ test/test-lensmodel-string-manipulation.c \ test/test-parser-cameramodel.c LDLIBS += -ldogleg -lfreeimage ifneq (${USE_LIBELAS},) # using libelas LDLIBS += -lelas endif CFLAGS += --std=gnu99 CCXXFLAGS += -Wno-missing-field-initializers -Wno-unused-variable -Wno-unused-parameter -Wno-missing-braces $(patsubst %.c,%.o,$(shell grep -l '#include .*minimath\.h' *.c */*.c)): minimath/minimath_generated.h minimath/minimath_generated.h: minimath/minimath_generate.pl ./$< > $@.tmp && mv $@.tmp $@ EXTRA_CLEAN += minimath/minimath_generated.h DIST_INCLUDE += \ mrcal.h \ mrcal-image.h \ mrcal-internal.h \ basic-geometry.h \ poseutils.h \ triangulation.h \ mrcal-types.h \ stereo.h DIST_BIN := \ mrcal-calibrate-cameras \ mrcal-convert-lensmodel \ mrcal-show-distortion-off-pinhole \ mrcal-show-splined-model-correction \ mrcal-show-projection-uncertainty \ mrcal-show-projection-diff \ mrcal-reproject-points \ mrcal-reproject-image \ mrcal-graft-models \ mrcal-to-cahvor \ mrcal-from-cahvor \ mrcal-to-kalibr \ mrcal-from-kalibr \ mrcal-from-ros \ mrcal-show-geometry \ mrcal-show-valid-intrinsics-region \ mrcal-is-within-valid-intrinsics-region \ mrcal-triangulate \ mrcal-cull-corners \ mrcal-show-residuals-board-observation \ mrcal-show-residuals \ mrcal-stereo # generate manpages from distributed binaries, and ship them. This is a hoaky # hack because apparenly manpages from python tools is a crazy thing to want to # do DIST_MAN := $(addsuffix .1,$(DIST_BIN)) # if using an older mrbuild SO won't be defined, and we need it SO ?= so # parser cameramodel-parser_GENERATED.c: cameramodel-parser.re mrcal.h re2c $< > $@.tmp && mv $@.tmp $@ LIB_SOURCES += cameramodel-parser_GENERATED.c EXTRA_CLEAN += cameramodel-parser_GENERATED.c cameramodel-parser_GENERATED.o: CCXXFLAGS += -fno-fast-math ALL_NPSP_EXTENSION_MODULES := $(patsubst %-genpywrap.py,%,$(wildcard *-genpywrap.py)) ifeq (${USE_LIBELAS},) # not using libelas ALL_NPSP_EXTENSION_MODULES := $(filter-out elas,$(ALL_NPSP_EXTENSION_MODULES)) endif ALL_PY_EXTENSION_MODULES := _mrcal $(patsubst %,_%_npsp,$(ALL_NPSP_EXTENSION_MODULES)) %/: mkdir -p $@ ######### python stuff %-npsp-pywrap-GENERATED.c: %-genpywrap.py python3 $< > $@.tmp && mv $@.tmp $@ mrcal/_%_npsp$(PY_EXT_SUFFIX): %-npsp-pywrap-GENERATED.o libmrcal.$(SO) libmrcal.$(SO).${ABI_VERSION} $(PY_MRBUILD_LINKER) $(PY_MRBUILD_LDFLAGS) $(LDFLAGS) $< -lmrcal -o $@ ALL_NPSP_C := $(patsubst %,%-npsp-pywrap-GENERATED.c,$(ALL_NPSP_EXTENSION_MODULES)) ALL_NPSP_O := $(patsubst %,%-npsp-pywrap-GENERATED.o,$(ALL_NPSP_EXTENSION_MODULES)) ALL_NPSP_SO := $(patsubst %,mrcal/_%_npsp$(PY_EXT_SUFFIX),$(ALL_NPSP_EXTENSION_MODULES)) EXTRA_CLEAN += $(ALL_NPSP_C) # https://gcc.gnu.org/bugzilla/show_bug.cgi?id=95635 $(ALL_NPSP_O): CFLAGS += -Wno-array-bounds mrcal-pywrap.o: $(addsuffix .h,$(wildcard *.docstring)) mrcal/_mrcal$(PY_EXT_SUFFIX): mrcal-pywrap.o libmrcal.$(SO) libmrcal.$(SO).${ABI_VERSION} $(PY_MRBUILD_LINKER) $(PY_MRBUILD_LDFLAGS) $(LDFLAGS) $< -lmrcal -lsuitesparseconfig -o $@ CFLAGS += -I/usr/include/suitesparse PYTHON_OBJECTS := mrcal-pywrap.o $(ALL_NPSP_O) # In the python api I have to cast a PyCFunctionWithKeywords to a PyCFunction, # and the compiler complains. But that's how Python does it! So I tell the # compiler to chill $(PYTHON_OBJECTS): CFLAGS += -Wno-cast-function-type $(PYTHON_OBJECTS): CFLAGS += $(PY_MRBUILD_CFLAGS) # The python libraries (compiled ones and ones written in python) all live in # mrcal/ DIST_PY3_MODULES := mrcal all: mrcal/_mrcal$(PY_EXT_SUFFIX) $(ALL_NPSP_SO) EXTRA_CLEAN += mrcal/*.$(SO) include Makefile.doc include Makefile.tests include $(MRBUILD_MK)/Makefile.common.footer mrcal-2.4.1/Makefile.doc000066400000000000000000000114321456301662300150270ustar00rootroot00000000000000# -*- Makefile -*- # To use the latest tag in the documentation, run # # VERSION_USE_LATEST_TAG=1 make ## I generate a single mrcal-python-api-reference.html for ALL the Python code. ## This is large DOC_HTML += doc/out/mrcal-python-api-reference.html doc/out/mrcal-python-api-reference.html: $(wildcard mrcal/*.py) $(patsubst %,mrcal/%$(PY_EXT_SUFFIX),$(ALL_PY_EXTENSION_MODULES)) libmrcal.so.$(ABI_VERSION) | doc/out/ python3 doc/pydoc.py -w mrcal > $@.tmp && mv $@.tmp $@ DOC_ALL_FIG := $(wildcard doc/*.fig) DOC_ALL_SVG_FROM_FIG := $(patsubst doc/%.fig,doc/out/figures/%.svg,$(DOC_ALL_FIG)) DOC_ALL_PDF_FROM_FIG := $(patsubst doc/%.fig,doc/out/figures/%.pdf,$(DOC_ALL_FIG)) doc: $(DOC_ALL_SVG_FROM_FIG) $(DOC_ALL_PDF_FROM_FIG) $(DOC_ALL_SVG_FROM_FIG): doc/out/figures/%.svg: doc/%.fig | doc/out/figures/ fig2dev -L svg $< $@ $(DOC_ALL_PDF_FROM_FIG): doc/out/figures/%.pdf: doc/%.fig | doc/out/figures/ fig2dev -L pdf $< $@ ## I'd like to place docs for each Python submodule in a separate .html (instead ## of a single huge mrcal-python-api-reference.html). Here's an attempt at at ## that. This works, but needs more effort: ## ## - top level mrcal.html is confused about what it contains. It has all of ## _mrcal and _poseutils for some reason ## - cross-submodule links don't work # # doc-reference: \ # $(patsubst mrcal/%.py,doc/mrcal.%.html,$(filter-out %/__init__.py,$(wildcard mrcal/*.py))) \ # $(patsubst %,doc/out/mrcal.%.html,$(ALL_PY_EXTENSION_MODULES)) \ # doc/out/mrcal.html # doc/out/mrcal.%.html: \ # mrcal/%.py \ # $(patsubst %,mrcal/%$(PY_EXT_SUFFIX),$(ALL_PY_EXTENSION_MODULES)) \ # libmrcal.so.$(ABI_VERSION) # doc/pydoc.py -w mrcal.$* > $@.tmp && mv $@.tmp $@ # doc/out/mrcal.%.html: mrcal/%$(PY_EXT_SUFFIX) # doc/pydoc.py -w mrcal.$* > $@.tmp && mv $@.tmp $@ # doc/out/mrcal.html: \ # $(wildcard mrcal/*.py) \ # $(patsubst %,mrcal/%$(PY_EXT_SUFFIX),$(ALL_PY_EXTENSION_MODULES)) \ # libmrcal.so.$(ABI_VERSION) # doc/pydoc.py -w mrcal > $@.tmp && mv $@.tmp $@ # .PHONY: doc-reference DOC_ALL_CSS := $(wildcard doc/*.css) DOC_ALL_CSS_TARGET := $(patsubst doc/%,doc/out/%,$(DOC_ALL_CSS)) doc: $(DOC_ALL_CSS_TARGET) $(DOC_ALL_CSS_TARGET): doc/out/%.css: doc/%.css | doc/out/ cp $< doc/out DOC_ALL_ORG := $(wildcard doc/*.org) DOC_ALL_HTML_TARGET := $(patsubst doc/%.org,doc/out/%.html,$(DOC_ALL_ORG)) DOC_HTML += $(DOC_ALL_HTML_TARGET) # This ONE command creates ALL the html files, so I want a pattern rule to indicate # that. I want to do: # %/out/a.html %/out/b.html %/out/c.html: %/a.org %/b.org %/c.org $(addprefix %,$(patsubst doc/%,/%,$(DOC_ALL_HTML_TARGET))): $(addprefix %,$(patsubst doc/%,/%,$(DOC_ALL_ORG))) emacs --chdir=doc -l mrcal-docs-publish.el --batch --eval '(load-library "org")' --eval '(org-publish-all t nil)' $(DOC_ALL_HTML_TARGET): doc/mrcal-docs-publish.el | doc/out/ $(DIST_MAN): %.1: %.pod pod2man --center="mrcal: camera projection, calibration toolkit" --name=MRCAL --release="mrcal $(VERSION)" --section=1 $< $@ %.pod: % $(MRBUILD_BIN)/make-pod-from-help $< > $@.tmp && cat footer.pod >> $@.tmp && mv $@.tmp $@ EXTRA_CLEAN += $(DIST_MAN) $(patsubst %.1,%.pod,$(DIST_MAN)) # I generate a manpage. Some perl stuff to add the html preamble MANPAGES_HTML := $(patsubst %,doc/out/%.html,$(DIST_BIN)) doc/out/%.html: %.pod | doc/out/ pod2html --noindex --css=mrcal.css --infile=$< | \ perl -ne 'BEGIN {$$h = `cat doc/mrcal-preamble-GENERATED.html`;} if(!/(.*)(.*)/s) { print; } else { print "$$1 $$h $$2"; }' > $@.tmp && mv $@.tmp $@ DOC_HTML += $(MANPAGES_HTML) $(DOC_HTML): doc/mrcal-preamble-GENERATED.html # If the git HEAD moves, I regenerate the preamble. It contains a version string # that uses the git info. This still isn't complete. A new git tag SHOULD # trigger this to be regenerated, but it doesn't. I'll do that later doc/mrcal-preamble-GENERATED.html: doc/mrcal-preamble-TEMPLATE.html $(and $(wildcard .git),.git/$(shell cut -d' ' -f2 .git/HEAD)) < $< sed s/@@VERSION@@/$(VERSION)/g > $@.tmp && mv $@.tmp $@ EXTRA_CLEAN += doc/mrcal-preamble-GENERATED.html # Documentation uses the latest tag only to denote the version. This will only # work properly after a 'make clean' (If you "make", everything is built without # VERSION_USE_LATEST_TAG=1; then when you "make doc", the products built without # VERSION_USE_LATEST_TAG=1 are used). Beware doc: VERSION_USE_LATEST_TAG=1 doc: $(DOC_HTML) .PHONY: doc # the whole output documentation directory EXTRA_CLEAN += doc/out # Convenience rules. Don't blindly use these if you aren't Dima and you aren't # using his machine publish-doc: doc rsync --exclude '*~' --exclude external -avu doc/out/ mrcal.secretsauce.net:/var/www/mrcal/docs-latest-release publish-doc-external: rsync -avu ../mrcal-doc-external/ mrcal.secretsauce.net:/var/www/mrcal/docs-2.3/external .PHONY: publish-doc publish-doc-external mrcal-2.4.1/Makefile.tests000066400000000000000000000117671456301662300154370ustar00rootroot00000000000000# -*- Makefile -*- # The test suite no longer runs in parallel, but it ALWAYS tries to run all the # tests, even without 'make -k' TESTS := \ test/test-pywrap-functions.py \ test/test-pylib-projections.py \ test/test-poseutils.py \ test/test-cameramodel.py \ test/test-poseutils-lib.py \ test/test-projections.py \ test/test-projection--special-cases.py__pinhole \ test/test-projection--special-cases.py__stereographic \ test/test-projection--special-cases.py__lonlat \ test/test-projection--special-cases.py__latlon \ test/test-gradients.py \ test/test-py-gradients.py \ test/test-cahvor \ test/test-optimizer-callback.py \ test/test-basic-sfm.py \ test/test-basic-calibration.py \ test/test-surveyed-calibration.py \ test/test-surveyed-calibration.py__--distance__8 \ test/test-surveyed-calibration.py__--oversample__10 \ test/test-surveyed-calibration.py__--do-sample \ test/test-surveyed-calibration.py__--do-sample__--distance__8 \ test/test-surveyed-calibration.py__--do-sample__--oversample__10 \ test/test-projection-uncertainty.py__--fixed__cam0__--model__opencv4__--do-sample \ test/test-projection-uncertainty.py__--fixed__frames__--model__opencv4__--do-sample__--Nsamples__200 \ test/test-projection-uncertainty.py__--fixed__cam0__--model__splined \ test/test-linearizations.py \ test/test-lensmodel-string-manipulation \ test/test-CHOLMOD-factorization.py \ test/test-projection-diff.py \ test/test-graft-models.py \ test/test-convert-lensmodel.py \ test/test-stereo.py \ test/test-solvepnp.py \ test/test-match-feature.py \ test/test-triangulation.py \ test/test-uncertainty-broadcasting.py__--q-calibration-stdev__0.3__--q-observation-stdev__0.3__--q-observation-stdev-correlation__0.5 \ test/test-parser-cameramodel \ test/test-extrinsics-moved-since-calibration.py \ test/test-broadcasting.py \ test/test-compute-chessboard-corners-parsing.py \ test/test-rectification-maps.py \ test/test-save-load-image.py \ test/test-worst_direction_stdev.py # triangulation-uncertainty tests. Lots and lots of tests to exhaustively try # out different scenarios BASE := test/test-triangulation-uncertainty.py__--do-sample__--model__opencv4__--observed-point__-40__0__200__--Ncameras__3__--cameras__2__1__--q-observation-stdev-correlation__0.6 TESTS_TRIANGULATION_UNCERTAINTY := \ $(foreach stabilization,__--stabilize-coords NONE, \ $(foreach fixed,cam0 frames, \ $(foreach only,observation calibration, \ $(BASE)$(if $(filter NONE,$(stabilization)),,$(stabilization))__--fixed__$(fixed)__--q-$(only)-stdev__0.5))) # Both sets of noise. Looking at different camera BASE := test/test-triangulation-uncertainty.py__--do-sample__--model__opencv4__--Ncameras__2__--cameras__1__0__--q-observation-stdev__0.5__--q-calibration-stdev__0.5 # Different amounts of correlation and near/far TESTS_TRIANGULATION_UNCERTAINTY := $(TESTS_TRIANGULATION_UNCERTAINTY) \ $(foreach stabilization,__--stabilize-coords NONE, \ $(foreach fixed,cam0 frames, \ $(foreach corr,0.1 0.9, \ $(foreach where,near far, \ $(BASE)$(if $(filter NONE,$(stabilization)),,$(stabilization))__--fixed__$(fixed)__--q-observation-stdev-correlation__$(corr)__--observed-point__$(if $(filter near,$(where)),-2__0__10,-40__0__200))))) TESTS_external_data := test/test-stereo-range.py # TESTS_TRIANGULATION_UNCERTAINTY not included in TESTS yet, so TESTS_NOSAMPLING # includes none of those TESTS_NOSAMPLING := $(foreach t,$(TESTS),$(if $(filter --do-sample,$(subst __, ,$t)),,$t)) TESTS := $(TESTS) $(TESTS_TRIANGULATION_UNCERTAINTY) # TESTS_external_data is not included in any other set, and must be requested # explicitly # Define the set for each "make test-xxx" command TESTS_all := $(TESTS) TESTS_nosampling := $(TESTS_NOSAMPLING) TESTS_triangulation_uncertainty := $(TESTS_TRIANGULATION_UNCERTAINTY) # "test-all" is the full set of tests # "test-nosampling" excludes the very time-consuming tests # "test-external-data" is everything that needs data other than what's in the repo TESTS_ALL_TARGETS := test-all test-nosampling test-triangulation-uncertainty test-external-data $(TESTS_ALL_TARGETS): all @FAILED=""; $(foreach t,$(TESTS_$(subst -,_,$(patsubst test-%,%,$@))),echo "========== RUNNING: $(subst __, ,$t)"; $(subst __, ,$t) || FAILED="$$FAILED $t"; ) test -z "$$FAILED" || echo "SOME TEST SETS FAILED: $$FAILED !"; test -z "$$FAILED" && echo "ALL TEST SETS PASSED!" .PHONY: $(TESTS_ALL_TARGETS) test: @echo "Which test set should we run? I know about '$(TESTS_ALL_TARGETS)'" >> /dev/stderr; false .PHONY: test mrcal-2.4.1/README.org000066400000000000000000000022601456301662300142700ustar00rootroot00000000000000* SYNOPSIS #+BEGIN_EXAMPLE $ mrcal-calibrate-cameras --focal 2000 --outdir /tmp --object-spacing 0.01 --object-width-n 10 '/tmp/left*.png' '/tmp/right*.png' ... lots of output as the solve runs ... Wrote /tmp/camera0-0.cameramodel Wrote /tmp/camera0-1.cameramodel #+END_EXAMPLE And now we have a calibration! * SUMMARY =mrcal= is a generic toolkit built to solve the calibration and SFM-like problems we encounter at NASA/JPL. Functionality related to these problems is exposed as a set of C and Python libraries and some commandline tools. * DESCRIPTION Extensive documentation is available at http://mrcal.secretsauce.net/ * INSTALLATION Install and/or building instructions are on the [[http://mrcal.secretsauce.net/install.html]["Building or installing" page]]. * REPOSITORY https://www.github.com/dkogan/mrcal/ * AUTHOR Dima Kogan (=dima@secretsauce.net=) * LICENSE AND COPYRIGHT Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. Government sponsorship acknowledged. All rights reserved. Licensed under the Apache License, Version 2.0 (the "License"); You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 mrcal-2.4.1/_rectification_maps.docstring000066400000000000000000000002661456301662300205460ustar00rootroot00000000000000Construct image transformation maps to make rectified images This is an internal function. You probably want mrcal.rectification_maps(). See the docs for that function for details. mrcal-2.4.1/_rectified_resolution.docstring000066400000000000000000000002661456301662300211240ustar00rootroot00000000000000Compute the resolution to be used for the rectified system This is an internal function. You probably want mrcal.rectified_resolution(). See the docs for that function for details. mrcal-2.4.1/_rectified_system.docstring000066400000000000000000000002471456301662300202440ustar00rootroot00000000000000Build rectified models for stereo rectification This is an internal function. You probably want mrcal.rectified_system(). See the docs for that function for details. mrcal-2.4.1/analyses/000077500000000000000000000000001456301662300144415ustar00rootroot00000000000000mrcal-2.4.1/analyses/dancing/000077500000000000000000000000001456301662300160445ustar00rootroot00000000000000mrcal-2.4.1/analyses/dancing/dance-study.py000077500000000000000000001766001456301662300206530ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Simulates different chessboard dances to find the best technique We want the shortest chessboard dances that produce the most confident results. In a perfect world would put the chessboard in all the locations where we would expect to use the visual system, since the best confidence is obtained in regions where the chessboard was observed. However, due to geometric constraints it is sometimes impossible to put the board in the right locations. This tool clearly shows that filling the field of view produces best results. But very wide lenses require huge chessboards, displayed very close to the lens in order to fill the field of view. This means that using a wide lens to look out to infinity will always result in potentially too little projection confidence. This tool is intended to find the kind of chessboard dance to get good confidences by simulating different geometries and dances. We arrange --Ncameras cameras horizontally, with an identity rotation, evenly spaced with a spacing of --camera-spacing meters. The left camera is at the origin. We show the cameras lots of dense chessboards ("dense" meaning that every camera sees all the points of all the chessboards). The chessboard come in two clusters: "near" and "far". Each cluster is centered straight ahead of the midpoint of all the cameras, with some random noise on the position and orientation. The distances from the center of the cameras to the center of the clusters are given by --range. This tool solves the calibration problem, and generates uncertainty-vs-range curves. Each run of this tool generates a family of this curve, for different values of Nframes-far, the numbers of chessboard observations in the "far" cluster. This tool scans some parameter (selected by --scan), and reports the uncertainty-vs-range for the different values of this parameter (as a plot and as an output vnl). If we don't want to scan any parameter, and just want a single uncertainty-vs-range plot, don't pass --scan. ''' import sys import argparse import re import os def parse_args(): def positive_float(string): try: value = float(string) except: raise argparse.ArgumentTypeError("argument MUST be a positive floating-point number. Got '{}'".format(string)) if value <= 0: raise argparse.ArgumentTypeError("argument MUST be a positive floating-point number. Got '{}'".format(string)) return value def positive_int(string): try: value = int(string) except: raise argparse.ArgumentTypeError("argument MUST be a positive integer. Got '{}'".format(string)) if value <= 0 or abs(value-float(string)) > 1e-6: raise argparse.ArgumentTypeError("argument MUST be a positive integer. Got '{}'".format(string)) return value parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--icam-uncertainty', default = 0, type=int, help='''Which camera to use for the uncertainty reporting. I use the left-most one (camera 0) by default''') parser.add_argument('--camera-spacing', default = 0.3, type=float, help='How many meters between adjacent cameras in our synthetic world') parser.add_argument('--object-spacing', default="0.077", type=str, help='''Width of each square in the calibration board, in meters. If --scan object_width_n, this is used as the spacing for the SMALLEST width. As I change object_width_n, I adjust object_spacing accordingly, to keep the total board size constant. If --scan object_spacing, this is MIN,MAX to specify the bounds of the scan. In that case object_width_n stays constant, so the board changes size''') parser.add_argument('--object-width-n', type=str, help='''How many points the calibration board has per horizontal side. If both are omitted, we default the width and height to 10 (both must be specified to use a non-default value). If --scan object_width_n, this is MIN,MAX to specify the bounds of the scan. In that case I assume a square object, and ignore --object-height-n. Scanning object-width-n keeps the board size constant''') parser.add_argument('--object-height-n', type=int, help='''How many points the calibration board has per vertical side. If both are omitted, we default the width and height to 10 (both must be specified to use a non-default value). If --scan object_width_n, this is ignored, and set equivalent to the object width''') parser.add_argument('--observed-pixel-uncertainty', type=positive_float, default = 1.0, help='''The standard deviation of x and y pixel coordinates of the input observations I generate. The distribution of the inputs is gaussian, with the standard deviation specified by this argument. Note: this is the x and y standard deviation, treated independently. If each of these is s, then the LENGTH of the deviation of each pixel is a Rayleigh distribution with expected value s*sqrt(pi/2) ~ s*1.25''') parser.add_argument('--lensmodel', required=False, type=str, help='''Which lens model to use for the simulation. If omitted, we use the model given on the commandline. We may want to use a parametric model to generate data (model on the commandline), but a richer splined model to solve''') parser.add_argument('--skip-calobject-warp-solve', action='store_true', default=False, help='''By default we assume the calibration target is slightly deformed, and we compute this deformation. If we want to assume that the chessboard shape is fixed, pass this option. The actual shape of the board is given by --calobject-warp''') parser.add_argument('--calobject-warp', type=float, nargs=2, default=(0.002, -0.005), help='''The "calibration-object warp". These specify the flex of the chessboard. By default, the board is slightly warped (as is usually the case in real life). To use a perfectly flat board, specify "0 0" here''') parser.add_argument('--show-geometry-first-solve', action = 'store_true', help='''If given, display the camera, chessboard geometry after the first solve, and exit. Used for debugging''') parser.add_argument('--show-uncertainty-first-solve', action = 'store_true', help='''If given, display the uncertainty (at infinity) and observations after the first solve, and exit. Used for debugging''') parser.add_argument('--write-models-first-solve', action = 'store_true', help='''If given, write the solved models to disk after the first solve, and exit. Used for debugging. Useful to check fov_x_deg when solving for a splined model''') parser.add_argument('--which', choices=('all-cameras-must-see-full-board', 'some-cameras-must-see-full-board', 'all-cameras-must-see-half-board', 'some-cameras-must-see-half-board'), default='all-cameras-must-see-half-board', help='''What kind of random poses are accepted. Default is all-cameras-must-see-half-board''') parser.add_argument('--fixed-frames', action='store_true', help='''Optimize the geometry keeping the chessboard frames fixed. This reduces the freedom of the solution, and produces more confident calibrations. It's possible to use this in reality by surverying the chessboard poses''') parser.add_argument('--ymax', type=float, default = 10.0, help='''If given, use this as the upper extent of the uncertainty plot.''') parser.add_argument('--uncertainty-at-range-sampled-min', type=float, help='''If given, use this as the lower bound of the ranges we look at when evaluating projection confidence''') parser.add_argument('--uncertainty-at-range-sampled-max', type=float, help='''If given, use this as the upper bound of the ranges we look at when evaluating projection confidence''') parser.add_argument('--explore', action='store_true', help='''Drop into a REPL at the end''') parser.add_argument('--scan', type=str, default='', choices=('range', 'tilt_radius', 'Nframes', 'Ncameras', 'object_width_n', 'object_spacing', 'num_far_constant_Nframes_near', 'num_far_constant_Nframes_all'), help='''Study the effect of some parameter on uncertainty. The parameter is given as an argument ot this function. Valid choices: ('range','tilt_radius','Nframes','Ncameras', 'object_width_n', 'object_spacing', 'num_far_constant_Nframes_near', 'num_far_constant_Nframes_all'). Scanning object-width-n keeps the board size constant''') parser.add_argument('--scan-object-spacing-compensate-range-from', type=float, help=f'''Only applies if --scan object-spacing. By default we vary the object spacings without touching anything else: the chessboard grows in size as we increase the spacing. If given, we try to keep the apparent size constant: as the object spacing grows, we increase the range. The nominal range given in this argument''') parser.add_argument('--range', default = '0.5,4.0', type=str, help='''if --scan num_far_...: this is "NEAR,FAR"; specifying the near and far ranges to the chessboard to evaluate. if --scan range this is "MIN,MAX"; specifying the extents of the ranges to evaluate. Otherwise: this is RANGE, the one range of chessboards to evaluate''') parser.add_argument('--tilt-radius', default='30.', type=str, help='''The radius of the uniform distribution used to sample the pitch and yaw of the chessboard observations, in degrees. The default is 30, meaning that the chessboard pitch and yaw are sampled from [-30deg,30deg]. if --scan tilt_radius: this is TILT-MIN,TILT-MAX specifying the bounds of the two tilt-radius values to evaluate. Otherwise: this is the one value we use''') parser.add_argument('--roll-radius', type=float, default=20., help='''The synthetic chessboard orientation is sampled from a uniform distribution: [-RADIUS,RADIUS]. The pitch,yaw radius is specified by the --tilt-radius. The roll radius is selected here. "Roll" is the rotation around the axis normal to the chessboard plane. Default is 20deg''') parser.add_argument('--x-radius', type=float, default=None, help='''The synthetic chessboard position is sampled from a uniform distribution: [-RADIUS,RADIUS]. The x radius is selected here. "x" is direction in the chessboard plane, and is also the axis along which the cameras are distributed. A resonable default (possibly range-dependent) is chosen if omitted. MUST be None if --scan num_far_...''') parser.add_argument('--y-radius', type=float, default=None, help='''The synthetic chessboard position is sampled from a uniform distribution: [-RADIUS,RADIUS]. The y radius is selected here. "y" is direction in the chessboard plane, and is also normal to the axis along which the cameras are distributed. A resonable default (possibly range-dependent) is chosen if omitted. MUST be None if --scan num_far_...''') parser.add_argument('--z-radius', type=float, default=None, help='''The synthetic chessboard position is sampled from a uniform distribution: [-RADIUS,RADIUS]. The z radius is selected here. "z" is direction normal to the chessboard plane. A resonable default (possibly range-dependent) is chosen if omitted. MUST be None if --scan num_far_...''') parser.add_argument('--Ncameras', default = '1', type=str, help='''How many cameras oberve our synthetic world. By default we just have one camera. if --scan Ncameras: this is NCAMERAS-MIN,NCAMERAS-MAX specifying the bounds of the camera counts to evaluate. Otherwise: this is the one Ncameras value to use''') parser.add_argument('--Nframes', type=str, help='''How many observed frames we have. Ignored if --scan num_far_... if --scan Nframes: this is NFRAMES-MIN,NFRAMES-MAX specifying the bounds of the frame counts to evaluate. Otherwise: this is the one Nframes value to use''') parser.add_argument('--Nframes-near', type=positive_int, help='''Used if --scan num_far_constant_Nframes_near. The number of "near" frames is given by this argument, while we look at the effect of adding more "far" frames.''') parser.add_argument('--Nframes-all', type=positive_int, help='''Used if --scan num_far_constant_Nframes_all. The number of "near"+"far" frames is given by this argument, while we look at the effect of replacing "near" frames with "far" frames.''') parser.add_argument('--Nscan-samples', type=positive_int, default=8, help='''How many values of the parameter being scanned to evaluate. If we're scanning something (--scan ... given) then by default the scan evaluates 8 different values. Otherwise this is set to 1''') parser.add_argument('--hardcopy', help=f'''Filename to plot into. If omitted, we make an interactive plot. This is passed directly to gnuplotlib''') parser.add_argument('--terminal', help=f'''gnuplot terminal to use for the plots. This is passed directly to gnuplotlib. Omit this unless you know what you're doing''') parser.add_argument('--extratitle', help=f'''Extra title string to add to a plot''') parser.add_argument('--title', help=f'''Full title string to use in a plot. Overrides the default and --extratitle''') parser.add_argument('--set', type=str, action='append', help='''Extra 'set' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('--unset', type=str, action='append', help='''Extra 'unset' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('model', type = str, help='''Baseline camera model. I use the intrinsics from this model to generate synthetic data. We probably want the "true" model to not be too crazy, so this should probably by a parametric (not splined) model''') args = parser.parse_args() if args.title is not None and args.extratitle is not None: print("--title and --extratitle are mutually exclusive", file=sys.stderr) sys.exit(1) return args args = parse_args() if args.object_width_n is None and \ args.object_height_n is None: args.object_width_n = "10" args.object_height_n = 10 elif not ( args.object_width_n is not None and \ args.object_height_n is not None) and \ args.scan != 'object_width_n': raise Exception("Either --object-width-n or --object-height-n are given: you must pass both or neither") # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README import numpy as np import numpysane as nps import gnuplotlib as gp import copy import os.path # I import the LOCAL mrcal scriptdir = os.path.dirname(os.path.realpath(__file__)) sys.path[:0] = f"{scriptdir}/../..", import mrcal def split_list(s, t): r'''Splits a comma-separated list None -> None "A,B,C" -> (A,B,C) "A" -> A ''' if s is None: return None,0 l = [t(x) for x in s.split(',')] if len(l) == 1: return l[0],1 return l,len(l) def first(s): r'''first in a list, or the value if a scalar''' if hasattr(s, '__iter__'): return s[0] return s def last(s): r'''last in a list, or the value if a scalar''' if hasattr(s, '__iter__'): return s[-1] return s controllable_args = \ dict( tilt_radius = dict(_type = float), range = dict(_type = float), Ncameras = dict(_type = int), Nframes = dict(_type = int), object_spacing = dict(_type = float), object_width_n = dict(_type = int) ) for a in controllable_args.keys(): l,n = split_list(getattr(args, a), controllable_args[a]['_type']) controllable_args[a]['value'] = l controllable_args[a]['listlen'] = n if any( controllable_args[a]['listlen'] > 2 for a in controllable_args.keys() ): raise Exception(f"All controllable args must have either at most 2 values. {a} has {controllable_args[a]['listlen']}") controllable_arg_0values = [ a for a in controllable_args.keys() if controllable_args[a]['listlen'] == 0 ] controllable_arg_2values = [ a for a in controllable_args.keys() if controllable_args[a]['listlen'] == 2 ] if len(controllable_arg_2values) == 0: controllable_arg_2values = '' elif len(controllable_arg_2values) == 1: controllable_arg_2values = controllable_arg_2values[0] else: raise Exception(f"At most 1 controllable arg may have 2 values. Instead I saw: {controllable_arg_2values}") if re.match("num_far_constant_Nframes_", args.scan): if args.x_radius is not None or \ args.y_radius is not None or \ args.z_radius is not None: raise Exception("--x-radius and --y-radius and --z-radius are exclusive with --scan num_far_...") # special case if 'Nframes' not in controllable_arg_0values: raise Exception(f"I'm scanning '{args.scan}', so --Nframes must not have been given") if 'range' != controllable_arg_2values: raise Exception(f"I'm scanning '{args.scan}', so --range must have 2 values") if args.scan == "num_far_constant_Nframes_near": if args.Nframes_all is not None: raise Exception(f"I'm scanning '{args.scan}', so --Nframes-all must not have have been given") if args.Nframes_near is None: raise Exception(f"I'm scanning '{args.scan}', so --Nframes-near must have have been given") else: if args.Nframes_near is not None: raise Exception(f"I'm scanning '{args.scan}', so --Nframes-near must not have have been given") if args.Nframes_all is None: raise Exception(f"I'm scanning '{args.scan}', so --Nframes-all must have have been given") else: if args.scan != controllable_arg_2values: # This covers the scanning-nothing-no2value-anything case raise Exception(f"I'm scanning '{args.scan}', the arg given 2 values is '{controllable_arg_2values}'. They must match") if len(controllable_arg_0values): raise Exception(f"I'm scanning '{args.scan}', so all controllable args should have some value. Missing: '{controllable_arg_0values}") if args.scan == '': args.Nscan_samples = 1 Nuncertainty_at_range_samples = 80 uncertainty_at_range_sampled_min = args.uncertainty_at_range_sampled_min if uncertainty_at_range_sampled_min is None: uncertainty_at_range_sampled_min = first(controllable_args['range']['value'])/10. uncertainty_at_range_sampled_max = args.uncertainty_at_range_sampled_max if uncertainty_at_range_sampled_max is None: uncertainty_at_range_sampled_max = last(controllable_args['range']['value']) *10. uncertainty_at_range_samples = \ np.logspace( np.log10(uncertainty_at_range_sampled_min), np.log10(uncertainty_at_range_sampled_max), Nuncertainty_at_range_samples) # I want the RNG to be deterministic np.random.seed(0) model_intrinsics = mrcal.cameramodel(args.model) calobject_warp_true_ref = np.array(args.calobject_warp) def solve(Ncameras, Nframes_near, Nframes_far, object_spacing, models_true, # q.shape = (Nframes, Ncameras, object_height, object_width, 2) # Rt_ref_board.shape = (Nframes, 4,3) q_true_near, Rt_ref_board_true_near, q_true_far, Rt_ref_board_true_far, fixed_frames = args.fixed_frames): q_true_near = q_true_near [:Nframes_near] Rt_ref_board_true_near = Rt_ref_board_true_near[:Nframes_near] if q_true_far is not None: q_true_far = q_true_far [:Nframes_far ] Rt_ref_board_true_far = Rt_ref_board_true_far [:Nframes_far ] else: q_true_far = np.zeros( (0,) + q_true_near.shape[1:], dtype = q_true_near.dtype) Rt_ref_board_true_far = np.zeros( (0,) + Rt_ref_board_true_near.shape[1:], dtype = Rt_ref_board_true_near.dtype) calobject_warp_true = calobject_warp_true_ref.copy() Nframes_all = Nframes_near + Nframes_far Rt_ref_board_true = nps.glue( Rt_ref_board_true_near, Rt_ref_board_true_far, axis = -3 ) # Dense observations. All the cameras see all the boards indices_frame_camera = np.zeros( (Nframes_all*Ncameras, 2), dtype=np.int32) indices_frame = indices_frame_camera[:,0].reshape(Nframes_all,Ncameras) indices_frame.setfield(nps.outer(np.arange(Nframes_all, dtype=np.int32), np.ones((Ncameras,), dtype=np.int32)), dtype = np.int32) indices_camera = indices_frame_camera[:,1].reshape(Nframes_all,Ncameras) indices_camera.setfield(nps.outer(np.ones((Nframes_all,), dtype=np.int32), np.arange(Ncameras, dtype=np.int32)), dtype = np.int32) indices_frame_camintrinsics_camextrinsics = \ nps.glue(indices_frame_camera, indices_frame_camera[:,(1,)], axis=-1) # If not fixed_frames: we use camera0 as the reference cordinate system, and # we allow the chessboard poses to move around. Else: the reference # coordinate system is arbitrary, but all cameras are allowed to move # around. The chessboards poses are fixed if not fixed_frames: indices_frame_camintrinsics_camextrinsics[:,2] -= 1 q = nps.glue( q_true_near, q_true_far, axis = -5 ) # apply noise q += np.random.randn(*q.shape) * args.observed_pixel_uncertainty # The observations are dense (in the data every camera sees all the # chessboards), but some of the observations WILL be out of bounds. I # pre-mark those as outliers so that the solve doesn't do weird stuff # Set the weights to 1 initially # shape (Nframes, Ncameras, object_height_n, object_width_n, 3) observations = nps.glue(q, np.ones( q.shape[:-1] + (1,) ), axis = -1) # shape (Ncameras, 1, 1, 2) imagersizes = nps.mv( nps.cat(*[ m.imagersize() for m in models_true ]), -2, -4 ) # mark the out-of-view observations as outliers observations[ np.any( q < 0, axis=-1 ), 2 ] = -1. observations[ np.any( q-imagersizes >= 0, axis=-1 ), 2 ] = -1. # shape (Nobservations, Nh, Nw, 2) observations = nps.clump( observations, n = 2 ) intrinsics = nps.cat( *[m.intrinsics()[1] for m in models_true] ) # If not fixed_frames: we use camera0 as the reference cordinate system, and # we allow the chessboard poses to move around. Else: the reference # coordinate system is arbitrary, but all cameras are allowed to move # around. The chessboards poses are fixed if fixed_frames: extrinsics = nps.cat( *[m.extrinsics_rt_fromref() for m in models_true] ) else: extrinsics = nps.cat( *[m.extrinsics_rt_fromref() for m in models_true[1:]] ) if len(extrinsics) == 0: extrinsics = None if nps.norm2(models_true[0].extrinsics_rt_fromref()) > 1e-6: raise Exception("models_true[0] must sit at the origin") imagersizes = nps.cat( *[m.imagersize() for m in models_true] ) optimization_inputs = \ dict( # intrinsics filled in later extrinsics_rt_fromref = extrinsics, frames_rt_toref = mrcal.rt_from_Rt(Rt_ref_board_true), points = None, observations_board = observations, indices_frame_camintrinsics_camextrinsics = indices_frame_camintrinsics_camextrinsics, observations_point = None, indices_point_camintrinsics_camextrinsics = None, # lensmodel filled in later calobject_warp = copy.deepcopy(calobject_warp_true), imagersizes = imagersizes, calibration_object_spacing = object_spacing, verbose = False, # do_optimize_extrinsics filled in later # do_optimize_intrinsics_core filled in later do_optimize_frames = False, do_optimize_intrinsics_distortions = True, do_optimize_calobject_warp = False, # turn this on, and reoptimize later, if needed do_apply_regularization = True, do_apply_outlier_rejection = False) if args.lensmodel is None: lensmodel = model_intrinsics.intrinsics()[0] else: lensmodel = args.lensmodel Nintrinsics = mrcal.lensmodel_num_params(lensmodel) if re.search("SPLINED", lensmodel): # These are already mostly right, So I lock them down while I seed the # intrinsics optimization_inputs['do_optimize_extrinsics'] = False # I pre-optimize the core, and then lock it down optimization_inputs['lensmodel'] = 'LENSMODEL_STEREOGRAPHIC' optimization_inputs['intrinsics'] = intrinsics[:,:4].copy() optimization_inputs['do_optimize_intrinsics_core'] = True stats = mrcal.optimize(**optimization_inputs) print(f"## optimized. rms = {stats['rms_reproj_error__pixels']}", file=sys.stderr) # core is good. Lock that down, and get an estimate for the control # points optimization_inputs['do_optimize_intrinsics_core'] = False optimization_inputs['lensmodel'] = lensmodel optimization_inputs['intrinsics'] = nps.glue(optimization_inputs['intrinsics'], np.zeros((Ncameras,Nintrinsics-4),),axis=-1) stats = mrcal.optimize(**optimization_inputs) print(f"## optimized. rms = {stats['rms_reproj_error__pixels']}", file=sys.stderr) # Ready for a final reoptimization with the geometry optimization_inputs['do_optimize_extrinsics'] = True if not fixed_frames: optimization_inputs['do_optimize_frames'] = True else: optimization_inputs['lensmodel'] = lensmodel if not mrcal.lensmodel_metadata_and_config(lensmodel)['has_core'] or \ not mrcal.lensmodel_metadata_and_config(model_intrinsics.intrinsics()[0])['has_core']: raise Exception("I'm assuming all the models here have a core. It's just lazy coding. If you see this, feel free to fix.") if lensmodel == model_intrinsics.intrinsics()[0]: # Same model. Grab the intrinsics. They're 99% right optimization_inputs['intrinsics'] = intrinsics.copy() else: # Different model. Grab the intrinsics core, optimize the rest optimization_inputs['intrinsics'] = nps.glue(intrinsics[:,:4], np.zeros((Ncameras,Nintrinsics-4),),axis=-1) optimization_inputs['do_optimize_intrinsics_core'] = True optimization_inputs['do_optimize_extrinsics'] = True if not fixed_frames: optimization_inputs['do_optimize_frames'] = True stats = mrcal.optimize(**optimization_inputs) print(f"## optimized. rms = {stats['rms_reproj_error__pixels']}", file=sys.stderr) if not args.skip_calobject_warp_solve: optimization_inputs['do_optimize_calobject_warp'] = True stats = mrcal.optimize(**optimization_inputs) print(f"## optimized. rms = {stats['rms_reproj_error__pixels']}", file=sys.stderr) return optimization_inputs def observation_centroid(optimization_inputs, icam): r'''mean pixel coordinate of all non-outlier points seen by a given camera''' ifcice = optimization_inputs['indices_frame_camintrinsics_camextrinsics'] observations = optimization_inputs['observations_board'] # pick the camera I want observations = observations[ifcice[:,1] == icam] # ignore outliers q = observations[ (observations[...,2] > 0), :2] return np.mean(q, axis=-2) def eval_one_rangenear_tilt(models_true, range_near, range_far, tilt_radius, object_width_n, object_height_n, object_spacing, uncertainty_at_range_samples, Ncameras, Nframes_near_samples, Nframes_far_samples): # I want the RNG to be deterministic np.random.seed(0) uncertainties = np.zeros((len(Nframes_far_samples), len(uncertainty_at_range_samples)), dtype=float) radius_cameras = (args.camera_spacing * (Ncameras-1)) / 2. x_radius = args.x_radius if args.x_radius is not None else range_near*2. + radius_cameras y_radius = args.y_radius if args.y_radius is not None else range_near*2. z_radius = args.z_radius if args.z_radius is not None else range_near/10. # shapes (Nframes, Ncameras, Nh, Nw, 2), # (Nframes, 4,3) q_true_near, Rt_ref_board_true_near = \ mrcal.synthesize_board_observations(models_true, object_width_n = object_width_n, object_height_n = object_height_n, object_spacing = object_spacing, calobject_warp = calobject_warp_true_ref, rt_ref_boardcenter = np.array((0., 0., 0., radius_cameras, 0, range_near,)), rt_ref_boardcenter__noiseradius = \ np.array((np.pi/180. * tilt_radius, np.pi/180. * tilt_radius, np.pi/180. * args.roll_radius, x_radius, y_radius, z_radius)), Nframes = np.max(Nframes_near_samples), which = args.which) if range_far is not None: q_true_far, Rt_ref_board_true_far = \ mrcal.synthesize_board_observations(models_true, object_width_n = object_width_n, object_height_n = object_height_n, object_spacing = object_spacing, calobject_warp = calobject_warp_true_ref, rt_ref_boardcenter = np.array((0., 0., 0., radius_cameras, 0, range_far,)), rt_ref_boardcenter__noiseradius = \ np.array((np.pi/180. * tilt_radius, np.pi/180. * tilt_radius, np.pi/180. * args.roll_radius, range_far*2. + radius_cameras, range_far*2., range_far/10.)), Nframes = np.max(Nframes_far_samples), which = args.which) else: q_true_far = None Rt_ref_board_true_far = None for i_Nframes_far in range(len(Nframes_far_samples)): Nframes_far = Nframes_far_samples [i_Nframes_far] Nframes_near = Nframes_near_samples[i_Nframes_far] optimization_inputs = solve(Ncameras, Nframes_near, Nframes_far, object_spacing, models_true, q_true_near, Rt_ref_board_true_near, q_true_far, Rt_ref_board_true_far) models_out = \ [ mrcal.cameramodel( optimization_inputs = optimization_inputs, icam_intrinsics = icam ) \ for icam in range(Ncameras) ] model = models_out[args.icam_uncertainty] if args.show_geometry_first_solve: mrcal.show_geometry(models_out, show_calobjects = True, wait = True) sys.exit() if args.show_uncertainty_first_solve: mrcal.show_projection_uncertainty(model, observations= True, wait = True) sys.exit() if args.write_models_first_solve: for i in range(len(models_out)): f = f"/tmp/camera{i}.cameramodel" if os.path.exists(f): input(f"File {f} already exists, and I want to overwrite it. Press enter to overwrite. Ctrl-c to exit") models_out[i].write(f) print(f"Wrote {f}") sys.exit() # shape (N,3) # I sample the center of the imager pcam_samples = \ mrcal.unproject( observation_centroid(optimization_inputs, args.icam_uncertainty), *model.intrinsics(), normalize = True) * \ nps.dummy(uncertainty_at_range_samples, -1) uncertainties[i_Nframes_far] = \ mrcal.projection_uncertainty(pcam_samples, model, what='worstdirection-stdev') return uncertainties output_table_legend = 'range_uncertainty_sample Nframes_near Nframes_far Ncameras range_near range_far tilt_radius object_width_n object_spacing uncertainty' output_table_fmt = '%f %d %d %d %f %f %f %d %f %f' output_table_icol__range_uncertainty_sample = 0 output_table_icol__Nframes_near = 1 output_table_icol__Nframes_far = 2 output_table_icol__Ncameras = 3 output_table_icol__range_near = 4 output_table_icol__range_far = 5 output_table_icol__tilt_radius = 6 output_table_icol__object_width_n = 7 output_table_icol__object_spacing = 8 output_table_icol__uncertainty = 9 output_table_Ncols = 10 output_table = np.zeros( (args.Nscan_samples, Nuncertainty_at_range_samples, output_table_Ncols), dtype=float) output_table[:,:, output_table_icol__range_uncertainty_sample] += uncertainty_at_range_samples if re.match("num_far_constant_Nframes_", args.scan): Nfar_samples = args.Nscan_samples if args.scan == "num_far_constant_Nframes_near": Nframes_far_samples = np.linspace(0, args.Nframes_near//4, Nfar_samples, dtype=int) Nframes_near_samples = Nframes_far_samples*0 + args.Nframes_near else: Nframes_far_samples = np.linspace(0, args.Nframes_all, Nfar_samples, dtype=int) Nframes_near_samples = args.Nframes_all - Nframes_far_samples models_true = \ [ mrcal.cameramodel(intrinsics = model_intrinsics.intrinsics(), imagersize = model_intrinsics.imagersize(), extrinsics_rt_toref = np.array((0,0,0, i*args.camera_spacing, 0,0), dtype=float) ) \ for i in range(controllable_args['Ncameras']['value']) ] # shape (args.Nscan_samples, Nuncertainty_at_range_samples) output_table[:,:, output_table_icol__uncertainty] = \ eval_one_rangenear_tilt(models_true, *controllable_args['range']['value'], controllable_args['tilt_radius']['value'], controllable_args['object_width_n']['value'], args.object_height_n, controllable_args['object_spacing']['value'], uncertainty_at_range_samples, controllable_args['Ncameras']['value'], Nframes_near_samples, Nframes_far_samples) output_table[:,:, output_table_icol__Nframes_near] += nps.transpose(Nframes_near_samples) output_table[:,:, output_table_icol__Nframes_far] += nps.transpose(Nframes_far_samples) output_table[:,:, output_table_icol__Ncameras] = controllable_args['Ncameras']['value'] output_table[:,:, output_table_icol__range_near] = controllable_args['range']['value'][0] output_table[:,:, output_table_icol__range_far] = controllable_args['range']['value'][1] output_table[:,:, output_table_icol__tilt_radius ] = controllable_args['tilt_radius']['value'] output_table[:,:, output_table_icol__object_width_n ] = controllable_args['object_width_n']['value'] output_table[:,:, output_table_icol__object_spacing ] = controllable_args['object_spacing']['value'] samples = Nframes_far_samples elif args.scan == "range": Nframes_near_samples = np.array( (controllable_args['Nframes']['value'],), dtype=int) Nframes_far_samples = np.array( (0,), dtype=int) models_true = \ [ mrcal.cameramodel(intrinsics = model_intrinsics.intrinsics(), imagersize = model_intrinsics.imagersize(), extrinsics_rt_toref = np.array((0,0,0, i*args.camera_spacing, 0,0), dtype=float) ) \ for i in range(controllable_args['Ncameras']['value']) ] Nrange_samples = args.Nscan_samples range_samples = np.linspace(*controllable_args['range']['value'], Nrange_samples, dtype=float) for i_range in range(Nrange_samples): output_table[i_range,:, output_table_icol__uncertainty] = \ eval_one_rangenear_tilt(models_true, range_samples[i_range], None, controllable_args['tilt_radius']['value'], controllable_args['object_width_n']['value'], args.object_height_n, controllable_args['object_spacing']['value'], uncertainty_at_range_samples, controllable_args['Ncameras']['value'], Nframes_near_samples, Nframes_far_samples)[0] output_table[:,:, output_table_icol__Nframes_near] = controllable_args['Nframes']['value'] output_table[:,:, output_table_icol__Nframes_far] = 0 output_table[:,:, output_table_icol__Ncameras] = controllable_args['Ncameras']['value'] output_table[:,:, output_table_icol__range_near] += nps.transpose(range_samples) output_table[:,:, output_table_icol__range_far] = -1 output_table[:,:, output_table_icol__tilt_radius ] = controllable_args['tilt_radius']['value'] output_table[:,:, output_table_icol__object_width_n ] = controllable_args['object_width_n']['value'] output_table[:,:, output_table_icol__object_spacing ] = controllable_args['object_spacing']['value'] samples = range_samples elif args.scan == "tilt_radius": Nframes_near_samples = np.array( (controllable_args['Nframes']['value'],), dtype=int) Nframes_far_samples = np.array( (0,), dtype=int) models_true = \ [ mrcal.cameramodel(intrinsics = model_intrinsics.intrinsics(), imagersize = model_intrinsics.imagersize(), extrinsics_rt_toref = np.array((0,0,0, i*args.camera_spacing, 0,0), dtype=float) ) \ for i in range(controllable_args['Ncameras']['value']) ] Ntilt_rad_samples = args.Nscan_samples tilt_rad_samples = np.linspace(*controllable_args['tilt_radius']['value'], Ntilt_rad_samples, dtype=float) for i_tilt in range(Ntilt_rad_samples): output_table[i_tilt,:, output_table_icol__uncertainty] = \ eval_one_rangenear_tilt(models_true, controllable_args['range']['value'], None, tilt_rad_samples[i_tilt], controllable_args['object_width_n']['value'], args.object_height_n, controllable_args['object_spacing']['value'], uncertainty_at_range_samples, controllable_args['Ncameras']['value'], Nframes_near_samples, Nframes_far_samples)[0] output_table[:,:, output_table_icol__Nframes_near] = controllable_args['Nframes']['value'] output_table[:,:, output_table_icol__Nframes_far] = 0 output_table[:,:, output_table_icol__Ncameras] = controllable_args['Ncameras']['value'] output_table[:,:, output_table_icol__range_near] = controllable_args['range']['value'] output_table[:,:, output_table_icol__range_far] = -1 output_table[:,:, output_table_icol__tilt_radius] += nps.transpose(tilt_rad_samples) output_table[:,:, output_table_icol__object_width_n ] = controllable_args['object_width_n']['value'] output_table[:,:, output_table_icol__object_spacing ] = controllable_args['object_spacing']['value'] samples = tilt_rad_samples elif args.scan == "Ncameras": Nframes_near_samples = np.array( (controllable_args['Nframes']['value'],), dtype=int) Nframes_far_samples = np.array( (0,), dtype=int) N_Ncameras_samples = args.Nscan_samples Ncameras_samples = np.linspace(*controllable_args['Ncameras']['value'], N_Ncameras_samples, dtype=int) for i_Ncameras in range(N_Ncameras_samples): Ncameras = Ncameras_samples[i_Ncameras] models_true = \ [ mrcal.cameramodel(intrinsics = model_intrinsics.intrinsics(), imagersize = model_intrinsics.imagersize(), extrinsics_rt_toref = np.array((0,0,0, i*args.camera_spacing, 0,0), dtype=float) ) \ for i in range(Ncameras) ] output_table[i_Ncameras,:, output_table_icol__uncertainty] = \ eval_one_rangenear_tilt(models_true, controllable_args['range']['value'], None, controllable_args['tilt_radius']['value'], controllable_args['object_width_n']['value'], args.object_height_n, controllable_args['object_spacing']['value'], uncertainty_at_range_samples, Ncameras, Nframes_near_samples, Nframes_far_samples)[0] output_table[:,:, output_table_icol__Nframes_near] = controllable_args['Nframes']['value'] output_table[:,:, output_table_icol__Nframes_far] = 0 output_table[:,:, output_table_icol__Ncameras] += nps.transpose(Ncameras_samples) output_table[:,:, output_table_icol__range_near] = controllable_args['range']['value'] output_table[:,:, output_table_icol__range_far] = -1 output_table[:,:, output_table_icol__tilt_radius] = controllable_args['tilt_radius']['value'] output_table[:,:, output_table_icol__object_width_n ] = controllable_args['object_width_n']['value'] output_table[:,:, output_table_icol__object_spacing ] = controllable_args['object_spacing']['value'] samples = Ncameras_samples elif args.scan == "Nframes": Nframes_far_samples = np.array( (0,), dtype=int) models_true = \ [ mrcal.cameramodel(intrinsics = model_intrinsics.intrinsics(), imagersize = model_intrinsics.imagersize(), extrinsics_rt_toref = np.array((0,0,0, i*args.camera_spacing, 0,0), dtype=float) ) \ for i in range(controllable_args['Ncameras']['value']) ] N_Nframes_samples = args.Nscan_samples Nframes_samples = np.linspace(*controllable_args['Nframes']['value'], N_Nframes_samples, dtype=int) for i_Nframes in range(N_Nframes_samples): Nframes = Nframes_samples[i_Nframes] Nframes_near_samples = np.array( (Nframes,), dtype=int) output_table[i_Nframes,:, output_table_icol__uncertainty] = \ eval_one_rangenear_tilt(models_true, controllable_args['range']['value'], None, controllable_args['tilt_radius']['value'], controllable_args['object_width_n']['value'], args.object_height_n, controllable_args['object_spacing']['value'], uncertainty_at_range_samples, controllable_args['Ncameras']['value'], Nframes_near_samples, Nframes_far_samples)[0] output_table[:,:, output_table_icol__Nframes_near]+= nps.transpose(Nframes_samples) output_table[:,:, output_table_icol__Nframes_far] = 0 output_table[:,:, output_table_icol__Ncameras] = controllable_args['Ncameras']['value'] output_table[:,:, output_table_icol__range_near] = controllable_args['range']['value'] output_table[:,:, output_table_icol__range_far] = -1 output_table[:,:, output_table_icol__tilt_radius] = controllable_args['tilt_radius']['value'] output_table[:,:, output_table_icol__object_width_n ] = controllable_args['object_width_n']['value'] output_table[:,:, output_table_icol__object_spacing ] = controllable_args['object_spacing']['value'] samples = Nframes_samples elif args.scan == "object_width_n": Nframes_near_samples = np.array( (controllable_args['Nframes']['value'],), dtype=int) Nframes_far_samples = np.array( (0,), dtype=int) models_true = \ [ mrcal.cameramodel(intrinsics = model_intrinsics.intrinsics(), imagersize = model_intrinsics.imagersize(), extrinsics_rt_toref = np.array((0,0,0, i*args.camera_spacing, 0,0), dtype=float) ) \ for i in range(controllable_args['Ncameras']['value']) ] Nsamples = args.Nscan_samples samples = np.linspace(*controllable_args['object_width_n']['value'], Nsamples, dtype=int) # As I move the width, I adjust the spacing to keep the total board size # constant. The object spacing in the argument applies to the MIN value of # the object_width_n. W = (controllable_args['object_width_n']['value'][0]-1) * controllable_args['object_spacing']['value'] object_spacing = W / samples for i_sample in range(Nsamples): output_table[i_sample,:, output_table_icol__uncertainty] = \ eval_one_rangenear_tilt(models_true, controllable_args['range']['value'], None, controllable_args['tilt_radius']['value'], samples[i_sample], samples[i_sample], object_spacing[i_sample], uncertainty_at_range_samples, controllable_args['Ncameras']['value'], Nframes_near_samples, Nframes_far_samples)[0] output_table[:,:, output_table_icol__Nframes_near] = controllable_args['Nframes']['value'] output_table[:,:, output_table_icol__Nframes_far] = 0 output_table[:,:, output_table_icol__Ncameras] = controllable_args['Ncameras']['value'] output_table[:,:, output_table_icol__range_near] = controllable_args['range']['value'] output_table[:,:, output_table_icol__range_far] = -1 output_table[:,:, output_table_icol__tilt_radius] = controllable_args['tilt_radius']['value'] output_table[:,:, output_table_icol__object_width_n ]+= nps.transpose(samples) output_table[:,:, output_table_icol__object_spacing ]+= nps.transpose(object_spacing) elif args.scan == "object_spacing": Nframes_near_samples = np.array( (controllable_args['Nframes']['value'],), dtype=int) Nframes_far_samples = np.array( (0,), dtype=int) models_true = \ [ mrcal.cameramodel(intrinsics = model_intrinsics.intrinsics(), imagersize = model_intrinsics.imagersize(), extrinsics_rt_toref = np.array((0,0,0, i*args.camera_spacing, 0,0), dtype=float) ) \ for i in range(controllable_args['Ncameras']['value']) ] Nsamples = args.Nscan_samples samples = np.linspace(*controllable_args['object_spacing']['value'], Nsamples, dtype=float) # As I move the spacing, I leave object_width_n, letting the total board # size change. The object spacing in the argument applies to the MIN value # of the object_width_n. for i_sample in range(Nsamples): r = controllable_args['range']['value'] if args.scan_object_spacing_compensate_range_from: r *= samples[i_sample]/args.scan_object_spacing_compensate_range_from output_table[i_sample,:, output_table_icol__uncertainty] = \ eval_one_rangenear_tilt(models_true, r, None, controllable_args['tilt_radius']['value'], controllable_args['object_width_n']['value'], args.object_height_n, samples[i_sample], uncertainty_at_range_samples, controllable_args['Ncameras']['value'], Nframes_near_samples, Nframes_far_samples)[0] output_table[:,:, output_table_icol__Nframes_near] = controllable_args['Nframes']['value'] output_table[:,:, output_table_icol__Nframes_far] = 0 output_table[:,:, output_table_icol__Ncameras] = controllable_args['Ncameras']['value'] output_table[:,:, output_table_icol__range_far] = -1 output_table[:,:, output_table_icol__tilt_radius] = controllable_args['tilt_radius']['value'] output_table[:,:, output_table_icol__object_width_n ] = controllable_args['object_width_n']['value'] output_table[:,:, output_table_icol__object_spacing ]+= nps.transpose(samples) if args.scan_object_spacing_compensate_range_from: output_table[:,:, output_table_icol__range_near] += controllable_args['range']['value'] * nps.transpose(samples/samples[0]) else: output_table[:,:, output_table_icol__range_near] = controllable_args['range']['value'] else: # no --scan. We just want one sample Nframes_near_samples = np.array( (controllable_args['Nframes']['value'],), dtype=int) Nframes_far_samples = np.array( (0,), dtype=int) models_true = \ [ mrcal.cameramodel(intrinsics = model_intrinsics.intrinsics(), imagersize = model_intrinsics.imagersize(), extrinsics_rt_toref = np.array((0,0,0, i*args.camera_spacing, 0,0), dtype=float) ) \ for i in range(controllable_args['Ncameras']['value']) ] output_table[0,:, output_table_icol__uncertainty] = \ eval_one_rangenear_tilt(models_true, controllable_args['range']['value'], None, controllable_args['tilt_radius']['value'], controllable_args['object_width_n']['value'], args.object_height_n, controllable_args['object_spacing']['value'], uncertainty_at_range_samples, controllable_args['Ncameras']['value'], Nframes_near_samples, Nframes_far_samples)[0] output_table[:,:, output_table_icol__Nframes_near] = controllable_args['Nframes']['value'] output_table[:,:, output_table_icol__Nframes_far] = 0 output_table[:,:, output_table_icol__Ncameras] = controllable_args['Ncameras']['value'] output_table[:,:, output_table_icol__range_near] = controllable_args['range']['value'] output_table[:,:, output_table_icol__range_far] = -1 output_table[:,:, output_table_icol__tilt_radius] = controllable_args['tilt_radius']['value'] output_table[:,:, output_table_icol__object_width_n ] = controllable_args['object_width_n']['value'] output_table[:,:, output_table_icol__object_spacing ] = controllable_args['object_spacing']['value'] samples = None if isinstance(controllable_args['range']['value'], float): guides = [ f"arrow nohead dashtype 3 from {controllable_args['range']['value']},graph 0 to {controllable_args['range']['value']},graph 1" ] else: guides = [ f"arrow nohead dashtype 3 from {r},graph 0 to {r},graph 1" for r in controllable_args['range']['value'] ] guides.append(f"arrow nohead dashtype 3 from graph 0,first {args.observed_pixel_uncertainty} to graph 1,first {args.observed_pixel_uncertainty}") title = args.title if args.scan == "num_far_constant_Nframes_near": if title is None: title = f"Scanning 'far' observations added to a set of 'near' observations. Have {controllable_args['Ncameras']['value']} cameras, {args.Nframes_near} 'near' observations, at ranges {controllable_args['range']['value']}." legend_what = 'Nframes_far' elif args.scan == "num_far_constant_Nframes_all": if title is None: title = f"Scanning 'far' observations replacing 'near' observations. Have {controllable_args['Ncameras']['value']} cameras, {args.Nframes_all} total observations, at ranges {controllable_args['range']['value']}." legend_what = 'Nframes_far' elif args.scan == "Nframes": if title is None: title = f"Scanning Nframes. Have {controllable_args['Ncameras']['value']} cameras looking out at {controllable_args['range']['value']:.2f}m." legend_what = 'Nframes' elif args.scan == "Ncameras": if title is None: title = f"Scanning Ncameras. Observing {controllable_args['Nframes']['value']} boards at {controllable_args['range']['value']:.2f}m." legend_what = 'Ncameras' elif args.scan == "range": if title is None: title = f"Scanning the distance to observations. Have {controllable_args['Ncameras']['value']} cameras looking at {controllable_args['Nframes']['value']} boards." legend_what = 'Range-to-chessboards' elif args.scan == "tilt_radius": if title is None: title = f"Scanning the board tilt. Have {controllable_args['Ncameras']['value']} cameras looking at {controllable_args['Nframes']['value']} boards at {controllable_args['range']['value']:.2f}m" legend_what = 'Random chessboard tilt radius' elif args.scan == "object_width_n": if title is None: title = f"Scanning the calibration object density, keeping the board size constant. Have {controllable_args['Ncameras']['value']} cameras looking at {controllable_args['Nframes']['value']} boards at {controllable_args['range']['value']:.2f}m" legend_what = 'Number of chessboard points per side' elif args.scan == "object_spacing": if title is None: if args.scan_object_spacing_compensate_range_from: title = f"Scanning the calibration object spacing, keeping the point count constant, and letting the board grow. Range grows with spacing. Have {controllable_args['Ncameras']['value']} cameras looking at {controllable_args['Nframes']['value']} boards at {controllable_args['range']['value']:.2f}m" else: title = f"Scanning the calibration object spacing, keeping the point count constant, and letting the board grow. Range is constant. Have {controllable_args['Ncameras']['value']} cameras looking at {controllable_args['Nframes']['value']} boards at {controllable_args['range']['value']:.2f}m" legend_what = 'Distance between adjacent chessboard corners' else: # no --scan. We just want one sample if title is None: title = f"Have {controllable_args['Ncameras']['value']} cameras looking at {controllable_args['Nframes']['value']} boards at {controllable_args['range']['value']:.2f}m with tilt radius {controllable_args['tilt_radius']['value']}" if args.extratitle is not None: title = f"{title}: {args.extratitle}" if samples is None: legend = None elif samples.dtype.kind == 'i': legend = np.array([ f"{legend_what} = {x}" for x in samples]) else: legend = np.array([ f"{legend_what} = {x:.2f}" for x in samples]) np.savetxt(sys.stdout, nps.clump(output_table, n=2), fmt = output_table_fmt, header= output_table_legend) plotoptions = \ dict( yrange = (0, args.ymax), _with = 'lines', _set = guides, unset = 'grid', title = title, xlabel = 'Range (m)', ylabel = 'Expected worst-direction uncertainty (pixels)', hardcopy = args.hardcopy, terminal = args.terminal, wait = not args.explore and args.hardcopy is None) if legend is not None: plotoptions['legend'] = legend if args.set: gp.add_plot_option(plotoptions, _set = args.set) if args.unset: gp.add_plot_option(plotoptions, _unset = args.unset) gp.plot(uncertainty_at_range_samples, output_table[:,:, output_table_icol__uncertainty], **plotoptions) if args.explore: import IPython IPython.embed() sys.exit() mrcal-2.4.1/analyses/extrinsics-stability.py000077500000000000000000000123511456301662300212150ustar00rootroot00000000000000#!/usr/bin/env python3 import sys import numpy as np import numpysane as nps import gnuplotlib as gp import mrcal def compute_Rt_implied_01(*models): lensmodels = [model.intrinsics()[0] for model in models] intrinsics_data = [model.intrinsics()[1] for model in models] # v shape (...,Ncameras,Nheight,Nwidth,...) # q0 shape (..., Nheight,Nwidth,...) v,q0 = \ mrcal.sample_imager_unproject(60, None, *models[0].imagersize(), lensmodels, intrinsics_data, normalize = True) distance = (1.0, 100.) focus_center = None focus_radius = 500 if distance is None: atinfinity = True distance = np.ones((1,), dtype=float) else: atinfinity = False distance = nps.atleast_dims(np.array(distance), -1) distance = nps.mv(distance.ravel(), -1,-4) if focus_center is None: focus_center = (models[0].imagersize() - 1.)/2. implied_Rt10 = \ mrcal.implied_Rt10__from_unprojections(q0, # shape (len(distance),Nheight,Nwidth,3) v[0,...] * distance, v[1,...], atinfinity = atinfinity, focus_center = focus_center, focus_radius = focus_radius) return mrcal.invert_Rt(implied_Rt10) models_filenames = sys.argv[1:5] models = [mrcal.cameramodel(f) for f in models_filenames] pairs = ( ( models[0],models[1]), ( models[2],models[3]) ) # The "before" extrinsic transformation m0,m1 = pairs[0] Rt01 = mrcal.compose_Rt( m0.extrinsics_Rt_fromref(), m1.extrinsics_Rt_toref()) # The "after" extrinsics transformation. I remap both cameras into the "before" # space, so that we're looking at the extrinsics transformation in the "before" # coord system. This will allow us to compare before and after # # Rt_implied__0before_0after Rt_0after_1after Rt_implied__1after_1before Rt_implied__0before_0after = compute_Rt_implied_01(pairs[0][0], pairs[1][0]) Rt_implied__1after_1before = compute_Rt_implied_01(pairs[1][1], pairs[0][1]) m0,m1 = pairs[1] Rt_0after_1after = \ mrcal.compose_Rt( m0.extrinsics_Rt_fromref(), m1.extrinsics_Rt_toref()) Rt01_after_extrinsicsbefore = \ mrcal.compose_Rt( Rt_implied__0before_0after, Rt_0after_1after, Rt_implied__1after_1before ) # I have the two relative transforms. If camera0 is fixed, how much am I moving # camera1? Rt_1before_1after = mrcal.compose_Rt(mrcal.invert_Rt(Rt01), Rt01_after_extrinsicsbefore) r_1before_1after = mrcal.r_from_R(Rt_1before_1after[:3,:]) t_1before_1after = Rt_1before_1after[3,:] magnitude = nps.mag(t_1before_1after) direction = t_1before_1after/magnitude angle = nps.mag(r_1before_1after) axis = r_1before_1after/angle angle_deg = angle*180./np.pi np.set_printoptions(precision=2) print(f"translation: {magnitude*1000:.2f}mm in the direction {direction}") print(f"rotation: {angle_deg:.3f}deg around the axis {axis}") for i in range(len(models)): m = models[i] qcenter,dq_dv,_ = mrcal.project(np.array((0,0,1.)), *m.intrinsics(), get_gradients=True) # I now do a simple thing. I have v=[0,0,1] so dq_dv[:,2]=0. A small pitch # gives me dv = (0,sinth,costh) ~ (0,th,1). So dq = dq_dv[:,1]*th + # dq_dv[:,2] = dq_dv[:,1]*th so for a pitch: mag(dq/dth) = mag(dq_dv[:,1]). # Similarly for a yaw I have mag(dq_dv[:,0]). I find the worst one, and call # it good. I can do that because dq_dv will be diagonally dominant, and the # diagonal elements will be very similar. mrcal.rectified_resolution() does # this resolution__pix_per_rad = np.max(nps.transpose(nps.mag(dq_dv[:,:2]))) resolution__pix_per_deg = resolution__pix_per_rad * np.pi/180. if 0: # More complicated, but probably not better. And not completed # # As the camera rotates, v shifts: rotate(v,r) ~ v + dv/dr dr, so the # projection shifts to q + dq/dv dv = q + dq/dv dv/dr dr # # Rodrigues rotation formula. th = mag(r), axis = normalize(r) = r/th # # rotate(r,v) = v cos(th) + cross(axis, v) sin(th) + axis axist v (1 - cos(th)) # # If th is small: # # rotate(r,v) = v + cross(axis, v) th # = v + [ axis1*v2-axis2*v1 axis2*v0-axis0*v2 axis0*v1-axis1*v0] th # # v = [0,0,1] so # # rotate(r,v) = v + [ axis1 axis0 0] th # = v + [ r1 r0 0 ] # # So dv_dr = np.array(((0,1,0), (1,0,0), (0,0,0))) dq_dr = nps.matmult(dq_dv,dv_dr) # I have dq_dr2 = 0, so lets ignore it dq_dr01 = dq_dr[:,:2] # Can finish this now print(f"Camera {i} has a resolution of {1./resolution__pix_per_deg:.3f} degrees per pixel at the center") mrcal-2.4.1/analyses/mrcal-reoptimize000077500000000000000000000136431456301662300176610ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Loads a model, and re-runs the optimization problem used to generate it This is useful to analyze the solve. We can generate perfect chessboard observations, corrupted with perfect nominal noise to validate the idea that differences observed with mrcal-show-projection-diff should be predictive by the uncertainties reported by mrcal-show-projection-uncertainty IF the dominant source of error is calibration-time sampling error. By default we write the resulting model to disk into a file INPUTMODEL-reoptimized.cameramodel. If --explore, we instead drop into a REPL. ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--model-intrinsics', help='''By default, all the nominal data comes from the MODEL given in the positional argument. If --model-intrinsics is given, the intrinsics only come from this other model. These are applied only to the ONE model in icam_intrinsics''') parser.add_argument('--perfect', action= 'store_true', help='''Make perfect observations and add perfect noise''') parser.add_argument('--verbose', action = 'store_true', help='''If given, reoptimize verbosely''') parser.add_argument('--skip-outlier-rejection', action='store_true', help='''Reoptimize with no outlier rejection''') parser.add_argument('--revive-outliers', action='store_true', help='''Un-mark the outliers''') parser.add_argument('--force', '-f', action='store_true', default=False, help='''By default existing models on disk are not overwritten. Pass --force to overwrite them without complaint''') parser.add_argument('--outdir', type=lambda d: d if os.path.isdir(d) else \ parser.error(f"--outdir requires an existing directory as the arg, but got '{d}'"), help='''Directory to write the output into. If omitted, we use the directory of the input model''') parser.add_argument('--explore', action = 'store_true', help='''If given, we don't write the reoptimized model to disk, but drop into a REPL instead ''') parser.add_argument('model', type=str, help='''The input camera model. If "-", we read standard input and write to standard output. We get the frame poses and extrinsics from this model. If --model-intrinsics isn't given, we get the intrinsics from this model as well''') args = parser.parse_args() return args args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README # I import the LOCAL mrcal sys.path[:0] = f"{os.path.dirname(os.path.realpath(__file__))}/..", import mrcal import numpy as np import numpysane as nps import time model = mrcal.cameramodel(args.model) if args.model == '-': # Input read from stdin. Write output to stdout file_output = sys.stdout else: if args.outdir is None: filename_base,extension = os.path.splitext(args.model) file_output = f"{filename_base}-reoptimized{extension}" else: f,extension = os.path.splitext(args.model) directory,filename_base = os.path.split(f) file_output = f"{args.outdir}/{filename_base}-reoptimized{extension}" if os.path.exists(file_output) and not args.force: print(f"ERROR: '{file_output}' already exists. Not overwriting this file. Pass -f to overwrite", file=sys.stderr) sys.exit(1) optimization_inputs = model.optimization_inputs() if args.perfect: if args.model_intrinsics is not None: model_intrinsics = mrcal.cameramodel(args.model_intrinsics) if model_intrinsics.intrinsics()[0] != model.intrinsics()[0]: print("At this time, --model-intrinsics MUST use the same lens model as the reference model", file=sys.stderr) sys.exit(1) optimization_inputs['intrinsics'][model.icam_intrinsics()] = \ model_intrinsics.intrinsics()[1] mrcal.make_perfect_observations(optimization_inputs) ######### Reoptimize optimization_inputs['verbose'] = args.verbose optimization_inputs['do_apply_outlier_rejection'] = not args.skip_outlier_rejection if args.revive_outliers: for what in ('observations_board','observations_point'): observations = optimization_inputs[what] print(f"Original solve has {np.count_nonzero(observations[...,2] <= 0)} outliers in {what}. Reviving them") print("") observations[observations[...,2] <= 0, 2] = 1. mrcal.optimize(**optimization_inputs) model = mrcal.cameramodel(optimization_inputs = optimization_inputs, icam_intrinsics = model.icam_intrinsics()) if not args.explore: note = \ "generated on {} with {}\n". \ format(time.strftime("%Y-%m-%d %H:%M:%S"), ' '.join(mrcal.shellquote(s) for s in sys.argv)) model.write(file_output, note=note) if isinstance(file_output, str): print(f"Wrote '{file_output}'", file=sys.stderr) sys.exit(0) print("") print("Done. The results are in the 'model' and 'optimization_inputs' variables") print("") import IPython IPython.embed() mrcal-2.4.1/analyses/mrcal-reproject-to-chessboard000077500000000000000000000157501456301662300222230ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Reproject calibration images to show just the chessboard in its nominal coordinates SYNOPSIS D=../mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity; analyses/mrcal-reproject-to-chessboard \ --image-directory $D/images \ --outdir /tmp/frames-splined \ $D/splined.cameramodel Outliers are highlighted. This is useful to visualize calibration errors. A perfect solve would display exactly the same calibration grid with every frame. In reality, we see the small errors in the calibration, and how they affect the individual chessboard corner observations. The intent of this tool is to be able to see any unmodeled chessboard deformations. It's not yet clear if this tool can do that effectively ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--image-path-prefix', help='''If given, we prepend the given prefix to the image paths. Exclusive with --image-directory''') parser.add_argument('--image-directory', help='''If given, we extract the filenames from the image paths in the solve, and use the given directory to find those filenames. Exclusive with --image-path-prefix''') parser.add_argument('--outdir', type=lambda d: d if os.path.isdir(d) else \ parser.error(f"--outdir requires an existing directory as the arg, but got '{d}'"), default='.', help='''Directory to write the output into. If omitted, we use the current directory''') parser.add_argument('--resolution-px-m', default = 1000, type = float, help='''The resolution of the output image in pixels/m. Defaults to 1000''') parser.add_argument('--force', '-f', action='store_true', default=False, help='''By default existing files are not overwritten. Pass --force to overwrite them without complaint''') parser.add_argument('model', type=str, help='''The input camera model. We use its optimization_inputs''') args = parser.parse_args() if args.image_path_prefix is not None and \ args.image_directory is not None: print("--image-path-prefix and --image-directory are mutually exclusive", file=sys.stderr) sys.exit(1) return args args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README import numpy as np import numpysane as nps import cv2 import mrcal try: model = mrcal.cameramodel(args.model) except Exception as e: print(f"Couldn't load camera model '{args.model}': {e}", file=sys.stderr) sys.exit(1) optimization_inputs = model.optimization_inputs() if optimization_inputs is None: print("The given model MUST have the optimization_inputs for this tool to be useful", file=sys.stderr) sys.exit(1) object_height_n,object_width_n = optimization_inputs['observations_board'].shape[1:3] object_spacing = optimization_inputs['calibration_object_spacing'] # I cover a space of N+1 squares wide/tall: N-1 between all the corners + 1 on # either side. I span squares -1..N inclusive Nx = int(args.resolution_px_m * object_spacing * (object_width_n + 1) + 0.5) Ny = int(args.resolution_px_m * object_spacing * (object_height_n + 1) + 0.5) # shape (Nframes,6) rt_ref_frame = optimization_inputs['frames_rt_toref'] rt_cam_ref = optimization_inputs['extrinsics_rt_fromref'] ifcice = optimization_inputs['indices_frame_camintrinsics_camextrinsics'] observations = optimization_inputs['observations_board'] lensmodel = optimization_inputs['lensmodel'] intrinsics_data = optimization_inputs['intrinsics'] imagepaths = optimization_inputs.get('imagepaths') if imagepaths is None: print("The given model MUST have the image paths for this tool to be useful", file=sys.stderr) sys.exit(1) # shape (Ny,Nx,3) p_frame = \ mrcal.ref_calibration_object(object_width_n,object_height_n, object_spacing, x_corner0 = -1, x_corner1 = object_width_n, Nx = Nx, y_corner0 = -1, y_corner1 = object_height_n, Ny = Ny, calobject_warp = optimization_inputs['calobject_warp']) for i in range(len(ifcice)): iframe, icamintrinsics, icamextrinsics = ifcice[i] p_ref = \ mrcal.transform_point_rt(rt_ref_frame[iframe], p_frame) if icamextrinsics >= 0: p_cam = \ mrcal.transform_point_rt(rt_cam_ref[icamextrinsics], p_ref) else: p_cam = p_ref # shape (Ny,Nx,2) q = mrcal.project(p_cam, lensmodel, intrinsics_data[icamintrinsics]).astype(np.float32) imagepath = imagepaths[i] if args.image_path_prefix is not None: imagepath = f"{args.image_path_prefix}/{imagepath}" elif args.image_directory is not None: imagepath = f"{args.image_directory}/{os.path.basename(imagepath)}" try: image = mrcal.load_image(imagepath, bits_per_pixel = 24, channels = 3) except: print(f"Couldn't read image at '{imagepath}'", file=sys.stderr) sys.exit(1) image_out = mrcal.transform_image(image,q) # shape (Ny,Nx) weight = observations[i,:,:,2] mask_outlier = weight<=0 # Mark all the outliers for iy,ix in np.argwhere(mask_outlier): # iy,ix index corners. I need to convert the to pixels in my image # I have pixels = linspace(-1,object_width_n,Nx) # So: qx = (ix+1)*(Nx-1) / (object_width_n +1) qy = (iy+1)*(Ny-1) / (object_height_n+1) # Red circle around the outlier red = (0,0,255) cv2.circle(image_out, center = np.round(np.array((qx,qy))).astype(int), radius = 10, color = red, thickness = 2) imagepath_out = f"{args.outdir}/{os.path.basename(imagepath)}" if not args.force and os.path.exists(imagepath_out): print("File already exists: '{imagepath_out}'. Not overwriting; pass --force to overwrite. Giving up.", file=sys.stderr) sys.exit(1) mrcal.save_image(imagepath_out, image_out) print(f"Wrote '{imagepath_out}'") mrcal-2.4.1/analyses/mrcal-show-model-resolution.py000077500000000000000000000136211456301662300223740ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Display the imager resolution''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--gridn', type=int, default = (60,40), nargs = 2, help='''How densely we should sample the imager. By default we use a 60x40 grid''') parser.add_argument('--cbmin', type=float, default=0, help='''Minimum range of the colorbar''') parser.add_argument('--cbmax', type=float, help='''Maximum range of the colorbar''') parser.add_argument('--title', type=str, default = None, help='''Title string for the plot''') parser.add_argument('--hardcopy', type=str, help='''Write the output to disk, instead of making an interactive plot''') parser.add_argument('--terminal', type=str, help=r'''gnuplotlib terminal. The default is good almost always, so most people don't need this option''') parser.add_argument('--set', type=str, action='append', help='''Extra 'set' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('--unset', type=str, action='append', help='''Extra 'unset' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('model', type=str, help='''Camera model''') args = parser.parse_args() return args args = parse_args() import numpy as np import numpysane as nps import gnuplotlib as gp import mrcal def mean_resolution__rad_pixel(q, model): r'''Find the mean resolution in rad/pixel at q v = unproject(q). Let a rotation R = [u0 u1 v] dq = dqdv dv = dqdv R Rt dv I have about dv normal to v (the space spanned by (u0,u1)), so let's assume that v is in this space: inner(dv,v) = 0 Rt dv = [u0t dv] = [a] [u1t dv] [b] [ 0 ] [0] Let ab = [a b]t dq = M ab where M = dqdv [u0 u1]. M is (2,2) norm2(dq) = abt MtM ab minmax(norm2(dq)) = eig(MtM) dq = sqrt(eig(MtM)) pixels/rad ''' v = mrcal.unproject(q, *model.intrinsics(), normalize = True) _,dq_dv,_ = mrcal.project(v, *model.intrinsics(), get_gradients = True) # Use R_aligned_to_vector(). Add broadcasting to that function? @nps.broadcast_define( ( (3,), ), (3,3) ) def rotation_any_v_to_z(v): r'''Return any rotation matrix that maps the given unit vector v to [0,0,1]''' z = v if np.abs(v[0]) < .9: x = np.array((1,0,0), dtype=float) else: x = np.array((0,1,0), dtype=float) x -= nps.inner(x,v)*v x /= nps.mag(x) y = np.cross(z,x) return nps.cat(x,y,z) # shape (...,3,3) Rt = rotation_any_v_to_z(v) # shape (...,2,2) M = nps.matmult(dq_dv, nps.transpose(Rt)[...,:,:2]) # Let MtM = (a b). If l is an eigenvalue then # (b c) # # (a-l)*(c-l) - b^2 = 0 --> l^2 - (a+c) l + ac-b^2 = 0 # # --> l = (a+c +- sqrt( a^2 + 2ac + c^2 - 4ac + 4b^2)) / 2 = # = (a+c +- sqrt( a^2 - 2ac + c^2 + 4b^2)) / 2 = # = (a+c)/2 +- sqrt( (a-c)^2/4 + b^2) a = nps.inner(M[...,:,0], M[...,:,0]) b = nps.inner(M[...,:,0], M[...,:,1]) c = nps.inner(M[...,:,1], M[...,:,1]) sqrt_discriminant = np.sqrt( (a-c)*(a-c)/4 + b*b) l0 = (a+c)/2 + sqrt_discriminant l1 = (a+c)/2 - sqrt_discriminant resolution_pix_rad_max = np.sqrt(l0) # real in case roundoff error makes l1<0 resolution_pix_rad_min = np.real(np.sqrt(l1)) # The resolution is an ellipse (different directions could have different # resolutions). Here I assume it's a circle, and take the average of the # axis lengths resolution_pix_rad = (resolution_pix_rad_min + resolution_pix_rad_max)/2 return 1./resolution_pix_rad plot_options = dict(hardcopy = args.hardcopy, terminal = args.terminal) if args.set is not None: plot_options['set'] = args.set if args.unset is not None: plot_options['unset'] = args.unset if args.title is not None: plot_options['title'] = args.title def openmodel(f): try: return mrcal.cameramodel(f) except Exception as e: print(f"Couldn't load camera model '{f}': {e}", file=sys.stderr) sys.exit(1) model = openmodel(args.model) W,H = model.imagersize() q = np.ascontiguousarray( \ nps.mv( nps.cat(*np.meshgrid( np.linspace(0, W-1, args.gridn[0]), np.linspace(0, H-1, args.gridn[1]) )), 0,-1) ) resolution__deg_pixel = mean_resolution__rad_pixel(q, model) * 180./np.pi if args.cbmax is None: # ceil 2-digit base-10 args.cbmax = np.max(resolution__deg_pixel) base10_floor = np.power(10., np.floor(np.log10(args.cbmax))) args.cbmax = np.ceil(args.cbmax / base10_floor) * base10_floor curve_options = \ mrcal.visualization._options_heatmap_with_contours( # update these plot options plot_options, contour_min = args.cbmin, contour_max = args.cbmax, imagersize = model.imagersize(), gridn_width = args.gridn[0], gridn_height = args.gridn[1]) gp.plot( (resolution__deg_pixel, curve_options), **plot_options, wait = args.hardcopy is None) mrcal-2.4.1/analyses/noncentral/000077500000000000000000000000001456301662300166045ustar00rootroot00000000000000mrcal-2.4.1/analyses/noncentral/trace-noncentral-ray.py000077500000000000000000000043041456301662300232120ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Visualize noncentrality of a model Given a model and query pixel this function - Computes a ray from the camera center to the unprojection at infinity - Samples different distances along this ray - Projects them, and visualizes the difference projection from the sample point As we get closer to the camera, stronger and stronger noncentral effects are observed ''' import sys import numpy as np import numpysane as nps import gnuplotlib as gp import re import mrcal model_filename = sys.argv[1] qref = np.array((100,100), dtype=float) model = mrcal.cameramodel(model_filename) lensmodel,intrinsics_data = model.intrinsics() if not mrcal.lensmodel_metadata_and_config(lensmodel)['noncentral']: print("The given model isn't noncentral. Nothing to do", file=sys.stderr) sys.exit(1) if not re.match('^LENSMODEL_CAHVORE_', lensmodel): print("This is only implemented for CAHVORE today", file=sys.stderr) sys.exit(1) # Special-case to centralize CAHVORE intrinsics_data_centralized = intrinsics_data.copy() intrinsics_data_centralized[-3:] = 0 v_at_infinity = \ mrcal.unproject(qref, lensmodel, intrinsics_data_centralized, normalize = True) if 0: # another thing to do is to compute deltaz # dz is a function of th # pc = p - [0,0,dz] # tan(th) = pxy / (pz - dz) # q = project_central(pc) # At infinity pz >> dz -> tan(th) = pxy/pz # At p I have q = project_central(pc) # unproject_central(q) = k*pc # p - k*pc = [0,0,dz] d = 0.2 p = v_at_infinity*d q = mrcal.project (p, lensmodel, intrinsics_data) vc = mrcal.unproject(q, lensmodel, intrinsics_data_centralized, normalize = True) k01 = p[:2]/vc[:2] dz = p[2] - k01*vc[2] import IPython IPython.embed() sys.exit() Ndistances = 100 d = np.linspace(0.01, 10., Ndistances) # shape (Ndistances, 3) p = nps.dummy(d, -1) * v_at_infinity # shape (Ndistances, 2) q = mrcal.project(p, *model.intrinsics()) # shape (Ndistances,) qshift = nps.mag(q - qref) gp.plot( d, qshift, _with = 'linespoints', xlabel = 'Distance (m)', ylabel = 'Pixel shift (pixels)', wait = True ) mrcal-2.4.1/analyses/outlierness/000077500000000000000000000000001456301662300170155ustar00rootroot00000000000000mrcal-2.4.1/analyses/outlierness/outlierness-test.py000077500000000000000000000443331456301662300227320ustar00rootroot00000000000000#!/usr/bin/env python3 '''This is a set of simple experiments to test the outlier-rejection and sensitivity logic''' import sys import os import numpy as np import numpysane as nps import gnuplotlib as gp usage = "Usage: {} order Npoints noise_stdev".format(sys.argv[0]) if len(sys.argv) != 4: print usage sys.exit(1) try: order = int( sys.argv[1]) # order. >= 1 N = int( sys.argv[2]) # This many points in the dataset noise_stdev = float(sys.argv[3]) # The dataset is corrupted thusly except: print usage sys.exit(1) if order < 1 or N <= 0 or noise_stdev <= 0: print usage sys.exit(1) Nquery = 70 # This many points for post-fit uncertainty-evaluation reference_equation = '0.1*(x+0.2)**2. + 3.0' def report_mismatch_relerr(a,b, what): relerr = np.abs(a-b) / ( (a+b)/2.) if relerr > 1e-6: print "MISMATCH for {}: relerr = {}, a = {}, b = {},".format(what,relerr,a,b); def report_mismatch_abserr(a,b, what): abserr = np.abs(a-b) if abserr > 1e-6: print "MISMATCH for {}: abserr = {}, a = {}, b = {},".format(what,abserr,a,b); def model_matrix(q, order): r'''Returns the model matrix S for particular domain points Here the "order" is the number of parameters in the fit. Thus order==2 means "linear" and order==3 means "quadratic"" ''' q = nps.atleast_dims(q,-1) return nps.transpose(nps.cat(*[q ** i for i in range(order)])) def func_reference(q): '''Reference function: reference_equation Let's say I care about the range [0..1]. It gets less linear as I get further away from 0 ''' # needs to manually match 'reference_equation' above return 0.1 * (q+0.2)*(q+0.2) + 3.0 def func_hypothesis(q, b): '''Hypothesis based on parameters ''' S = model_matrix(q, len(b)) return nps.matmult(b, nps.transpose(S)) def compute_outliernesses(J, x, jq, k_dima, k_cook): '''Computes all the outlierness/Cook's D metrics I have 8 things I can compute coming from 3 yes/no choices. These are all very similar, with two pairs actually coming out identical. I choose: - Are we detecting outliers, or looking at effects of a new query point? - Dima's outlierness factor or Cook's D - Look ONLY at the effect on the other variables, or on the other variables AND self? If we're detecting outliers, we REMOVE measurements from the dataset, and see what happens to the fit. If we're looking at effects of a new query point, we see what happend if we ADD measurements Dima's outlierness factor metric looks at what happens to the cost function E = norm2(x). Specifically I look at (norm2(x_before) - norm(x_after))/Nmeasurements Cook's D instead looks at (norm2(x_before - x_after)) * k for some constant k. Finally, we can decide whether to include the effects on the measurements we're adding/removing, or not. Note that here I only look at adding/removing SCALAR measurements ============= This is similar-to, but not exactly-the-same-as Cook's D. I assume the least squares fit optimizes a cost function E = norm2(x). The outlierness factor I return is f = 1/Nmeasurements (E(outliers and inliers) - E(inliers only)) For a scalar measurement, this solves to k = xo^2 / Nmeasurements B = 1.0/(jt inv(JtJ) j - 1) f = -k * B (see the comment in dogleg_getOutliernessFactors() for a description) Note that my metric is proportional to norm2(x_io) - norm2(x_i). This is NOT the same as Cook's distance, which is proportional to norm2(x_io - x_i). It's not yet obvious to me which is better There're several slightly-different definitions of Cook's D and of a rule-of-thumb threshold floating around on the internet. Wikipedia says: D = norm2(x_io - x_i)^2 / (Nstate * norm2(x_io)/(Nmeasurements - Nstate)) D_threshold = 1 An article https://www.nature.com/articles/nmeth.3812 says D = norm2(x_io - x_i)^2 / ((Nstate+1) * norm2(x_io)/(Nmeasurements - Nstate -1)) D_threshold = 4/Nmeasurements Here I use the second definition. That definition expands to k = xo^2 / ((Nstate+1) * norm2(x_io)/(Nmeasurements - Nstate -1)) B = 1.0/(jt inv(JtJ) j - 1) f = k * (B + B*B) ''' Nmeasurements,Nstate = J.shape # The A values for each measurement Aoutliers = nps.inner(J, nps.transpose(np.linalg.pinv(J))) Aquery = nps.inner(jq, nps.transpose(np.linalg.solve(nps.matmult(nps.transpose(J),J), nps.transpose(jq)))) def dima(): k = k_dima k = 1 # Here the metrics are linear, so self + others = self_others def outliers(): B = 1.0 / (Aoutliers - 1.0) return dict( self = k * x*x, others = k * x*x*(-B-1), self_others = k * x*x*(-B )) def query(): B = 1.0 / (Aquery + 1.0) return dict( self = k * ( B*B), others = k * (B-B*B), self_others = k * (B)) return dict(outliers = outliers(), query = query()) def cook(): k = k_cook k = 1 # Here the metrics maybe aren't linear (I need to think about it), so # maybe self + others != self_others. I thus am not returning the "self" # metric def outliers(): B = 1.0 / (Aoutliers - 1.0) return dict( self_others = k * x*x*(B+B*B ) , others = k * x*x*(-B-1)) def query(): B = 1.0 / (Aquery + 1.0) return dict( self_others = k * (1-B) , others = k * (B-B*B)) return dict(outliers = outliers(), query = query()) return dict(cook = cook(), dima = dima()) def outlierness_test(J, x, f, outlierness, k_dima, k_cook, i=0): r'''Test the computation of outlierness I have an analytical expression for this computed in compute_outliernesses(). This explicitly computes the quantity represented by compute_outliernesses() to make sure that that analytical expression is correct ''' # I reoptimize without measurement i E0 = nps.inner(x,x) J1 = nps.glue(J[:i,:], J[(i+1):,:], axis=-2) f1 = nps.glue(f[:i ], f[(i+1): ], axis=-1) b1 = nps.matmult( f1, nps.transpose(np.linalg.pinv(J1))) x1 = nps.matmult(b1, nps.transpose(J1)) - f1 E1 = nps.inner(x1,x1) report_mismatch_relerr( (E0-E1) * k_dima, outlierness['self_others'][i], "self_others outlierness computed analytically, explicitly") report_mismatch_relerr( (E0-x[i]*x[i] - E1) * k_dima, outlierness['others'][i], "others outlierness computed analytically, explicitly") def CooksD_test(J, x, f, CooksD, k_dima, k_cook, i=0): r'''Test the computation of Cook's D I have an analytical expression for this computed in compute_outliernesses(). This explicitly computes the quantity represented by compute_outliernesses() to make sure that that analytical expression is correct ''' # I reoptimize without measurement i Nmeasurements,Nstate = J.shape J1 = nps.glue(J[:i,:], J[(i+1):,:], axis=-2) f1 = nps.glue(f[:i ], f[(i+1): ], axis=-1) b1 = nps.matmult( f1, nps.transpose(np.linalg.pinv(J1))) x1 = nps.matmult(b1, nps.transpose(J)) - f dx = x1-x report_mismatch_relerr( nps.inner(dx,dx) * k_cook, CooksD['self_others'][i], "self_others CooksD computed analytically, explicitly") report_mismatch_relerr( (nps.inner(dx,dx) - dx[i]*dx[i]) * k_cook, CooksD['others'][i], "others CooksD computed analytically, explicitly") def outlierness_query_test(J,b,x, f, query,fquery_ref, outlierness_nox, k_dima, k_cook, i=0): r'''Test the concept of outlierness for querying hypothetical data fquery_test = f(q) isn't true here. If it WERE true, the x of the query point would be 0 (we fit the model exactly), so the outlierness factor would be 0 also ''' # current solve E0 = nps.inner(x,x) query = query [i] fquery_ref = fquery_ref[i] # I add a new point, and reoptimize fquery = func_hypothesis(query,b) xquery = fquery - fquery_ref jquery = model_matrix(query, len(b)) J1 = nps.glue(J, jquery, axis=-2) f1 = nps.glue(f, fquery_ref, axis=-1) b1 = nps.matmult( f1, nps.transpose(np.linalg.pinv(J1))) x1 = nps.matmult(b1, nps.transpose(J1)) - f1 E1 = nps.inner(x1,x1) report_mismatch_relerr( (x1[-1]*x1[-1]) * k_dima, outlierness_nox['self'][i]*xquery*xquery, "self query-outlierness computed analytically, explicitly") report_mismatch_relerr( (E1-x1[-1]*x1[-1] - E0) * k_dima, outlierness_nox['others'][i]*xquery*xquery, "others query-outlierness computed analytically, explicitly") report_mismatch_relerr( (E1 - E0) * k_dima, outlierness_nox['self_others'][i]*xquery*xquery, "self_others query-outlierness computed analytically, explicitly") def CooksD_query_test(J,b,x, f, query,fquery_ref, CooksD_nox, k_dima, k_cook, i=0): r'''Test the concept of CooksD for querying hypothetical data fquery_test = f(q) isn't true here. If it WERE true, the x of the query point would be 0 (we fit the model exactly), so the outlierness factor would be 0 also ''' # current solve Nmeasurements,Nstate = J.shape query = query [i] fquery_ref = fquery_ref[i] # I add a new point, and reoptimize fquery = func_hypothesis(query,b) xquery = fquery - fquery_ref jquery = model_matrix(query, len(b)) J1 = nps.glue(J, jquery, axis=-2) f1 = nps.glue(f, fquery_ref, axis=-1) b1 = nps.matmult( f1, nps.transpose(np.linalg.pinv(J1))) x1 = nps.matmult(b1, nps.transpose(J1)) - f1 dx = x1[:-1] - x dx_both = x1 - nps.glue(x,xquery, axis=-1) report_mismatch_relerr( nps.inner(dx_both,dx_both)*k_cook, CooksD_nox['self_others'][i]*xquery*xquery, "self_others query-CooksD computed analytically, explicitly") report_mismatch_relerr( nps.inner(dx,dx)*k_cook, CooksD_nox['others'][i]*xquery*xquery, "others query-CooksD computed analytically, explicitly") def Var_df(J, squery, stdev): r'''Propagates noise in input to noise in f noise in input -> noise in params -> noise in f db ~ M dm where M = inv(JtJ)Jt df = df/db db df/db = squery Var(dm) = stdev^2 I -> Var(df) = stdev^2 squery inv(JtJ) Jt J inv(JtJ) squeryt = = stdev^2 squery inv(JtJ) squeryt This function broadcasts over squery ''' return \ nps.inner(squery, nps.transpose(np.linalg.solve(nps.matmult(nps.transpose(J),J), nps.transpose(squery)))) *stdev*stdev def histogram(x, **kwargs): h,edges = np.histogram(x, bins=20, **kwargs) centers = (edges[1:] + edges[0:-1])/2 return h,centers,edges[1]-edges[0] def generate_dataset(N, noise_stdev): q = np.random.rand(N) fref = func_reference(q) fnoise = np.random.randn(N) * noise_stdev f = fref + fnoise return q,f def fit(q, f, order): S = model_matrix(q, order) J = S b = nps.matmult( f, nps.transpose(np.linalg.pinv(S))) x = func_hypothesis(q,b) - f return b,J,x def test_order(q,f, query, order): # I look at linear and quadratic models: a0 + a1 q + a2 q^2, with a2=0 for the # linear case. I use plain least squares. The parameter vector is [a0 a1 a2]t. S # = [1 q q^2], so the measurement vector x = S b - f. E = norm2(x). J = dx/db = # S. # # Note the problem "order" is the number of parameters, so a linear model has # order==2 b,J,x = fit(q,f,order) Nmeasurements,Nstate = J.shape k_dima = 1.0/Nmeasurements k_cook = 1.0/((Nstate + 1.0) * nps.inner(x,x)/(Nmeasurements - Nstate - 1.0)) report_mismatch_abserr(np.linalg.norm(nps.matmult(x,J)), 0, "Jtx") squery = model_matrix(query, order) fquery = func_hypothesis(query, b) metrics = compute_outliernesses(J,x, squery, k_dima, k_cook) outlierness_test(J, x, f, metrics['dima']['outliers'], k_dima, k_cook, i=10) CooksD_test (J, x, f, metrics['cook']['outliers'], k_dima, k_cook, i=10) outlierness_query_test(J,b,x,f, query, fquery + 1.2e-3, metrics['dima']['query'], k_dima, k_cook, i=10 ) CooksD_query_test (J,b,x,f, query, fquery + 1.2e-3, metrics['cook']['query'], k_dima, k_cook, i=10 ) Vquery = Var_df(J, squery, noise_stdev) return \ dict( b = b, J = J, x = x, Vquery = Vquery, squery = squery, fquery = fquery, metrics = metrics, k_dima = k_dima, k_cook = k_cook ) q,f = generate_dataset(N, noise_stdev) query = np.linspace(-1,2, Nquery) stats = test_order(q,f, query, order) def show_outlierness(order, N, q, f, query, cooks_threshold, **stats): p = gp.gnuplotlib(equation='1.0 title "Threshold"', title = "Outlierness with order={} Npoints={} stdev={}".format(order, N, noise_stdev)) p.plot( (q, stats['metrics']['dima']['outliers']['self_others']/stats['dimas_threshold'], dict(legend="Dima's self+others outlierness / threshold", _with='points')), (q, stats['metrics']['dima']['outliers']['others']/stats['dimas_threshold'], dict(legend="Dima's others-ONLY outlierness / threshold", _with='points')), (q, stats['metrics']['cook']['outliers']['self_others']/cooks_threshold, dict(legend="Cook's self+others outlierness / threshold", _with='points')), (q, stats['metrics']['cook']['outliers']['others']/cooks_threshold, dict(legend="Cook's others-ONLY outlierness / threshold", _with='points'))) return p def show_uncertainty(order, N, q, f, query, cooks_threshold, **stats): coeffs = stats['b'] fitted_equation = '+'.join(['{} * x**{}'.format(coeffs[i], i) for i in range(len(coeffs))]) p = gp.gnuplotlib(equation='({})-({}) title "Fit error off ground truth; y2 axis +- noise stdev" axis x1y2'.format(reference_equation,fitted_equation), title = "Uncertainty with order={} Npoints={} stdev={}".format(order, N, noise_stdev), ymin=0, y2range = (-noise_stdev, noise_stdev), _set = 'y2tics' ) # p.plot( # (query, np.sqrt(stats['Vquery]), # dict(legend='expectederr (y2)', _with='lines', y2=1)), # (query, stats['metrics']['dima']['query']['self_others']*noise_stdev*noise_stdev / stats['dimas_threshold'], # dict(legend="Dima's self+others query / threshold", # _with='linespoints')), # (query, stats['metrics']['dima']['query']['others']*noise_stdev*noise_stdev / stats['dimas_threshold'], # dict(legend="Dima's others-ONLY query / threshold", # _with='linespoints')), # (query, stats['metrics']['cook']['query']['self_others']*noise_stdev*noise_stdev / cooks_threshold, # dict(legend="Cook's self+others query / threshold", # _with='linespoints')), # (query, stats['metrics']['cook']['query']['others']*noise_stdev*noise_stdev / cooks_threshold, # dict(legend="Cook's others-ONLY query / threshold", # _with='linespoints'))) p.plot( # (query, np.sqrt(Vquery), # dict(legend='Expected error due to input noise (y2)', _with='lines', y2=1)), (query, np.sqrt(stats['metrics']['dima']['query']['self'])*noise_stdev, dict(legend="Dima's self-ONLY; 1 point", _with='linespoints')), (query, np.sqrt(stats['metrics']['dima']['query']['others'])*noise_stdev, dict(legend="Dima's others-ONLY ALL {} points".format(Nquery), _with='linespoints')), # (query, np.sqrt(stats['metrics']['dima']['query']['others'])*noise_stdev * Nquery, # dict(legend="Dima's others-ONLY 1 point average", # _with='linespoints')), ) return p def show_fit (order, N, q, f, query, cooks_threshold, **stats): p = gp.gnuplotlib(equation='{} with lines title "reference"'.format(reference_equation), xrange=[-1,2], title = "Fit with order={} Npoints={} stdev={}".format(order, N, noise_stdev)) p.plot((q, f, dict(legend = 'input data', _with='points')), (query, stats['fquery'] + np.sqrt(stats['Vquery'])*np.array(((1,),(0,),(-1,),)), dict(legend = 'stdev_f', _with='lines'))) return p def show_distribution(outlierness): h,c,w = histogram(outlierness) raise Exception("not done") #gp.plot() # This is hoaky, but reasonable, I think. Some of the unscaled metrics are # identical between mine and Cook's expressions. So I scale Cook's 4/N threshold # to apply to me. Works ok. cooks_threshold = 4.0 / N stats['dimas_threshold'] = cooks_threshold / stats['k_cook'] * stats['k_dima'] # These all show interesting things; turn one of them on plots = [ show_outlierness (order, N, q, f, query, cooks_threshold, **stats), show_fit (order, N, q, f, query, cooks_threshold, **stats), show_uncertainty (order, N, q, f, query, cooks_threshold, **stats) ] for p in plots: if os.fork() == 0: p.wait() sys.exit() os.wait() # Conclusions: # # - Cook's 4/N threshold looks reasonable. # # - For detecting outliers my self+others metric is way too outlier-happy. It # makes most of the linear fit points look outliery # # - For uncertainty, Dima's self+others is the only query metric that's maybe # usable. It qualitatively a negated and shifted Cook's self+others mrcal-2.4.1/analyses/splines/000077500000000000000000000000001456301662300161165ustar00rootroot00000000000000mrcal-2.4.1/analyses/splines/README000066400000000000000000000033471456301662300170050ustar00rootroot00000000000000The test and validation tools used in the development of the b-spline interpolated models live here. First I wanted to come up with a surface parametrization scheme. I wanted to project the full almost-360deg view into some sort of 2D domain that is cartesian-ish. Then I would grid this cartesian 2D domain with a regular grid of control points, and I'd spline that. But does such a mapping exist? What is it? The show-fisheye-grid.py script exists for this purpose. It takes in an existing model, grids the imager, unprojects the points, and projects the vectors back to a number of common fisheye projections. I applied this to some wide models I had (their inaccurate OPENCV8 fits), and observed that the stereographic model works well here: a cartensian grid in the imager produces a cartesian-ish grid in the stereographic projection. The other projections look like they'd work also. The pinhole projection most notably does NOT work; its projections run off to infinity at the edges. Then I needed to find a surface representation, and the expressions. I'm using b-splines: they have nice continuity properties, and they have nice local support: so my jacobian will remain sparse. The bsplines.py script derives and validates the spline equations. fpbisp.py is a part of that. Then I implemented the spline equations in mrcal.c, and wanted to make sure the behavior was correct. This is done by the verify-interpolated-surface.py script. It produces a random splined model, projects it with mrcal, and visualizes the sparse control point surface with the dense sampled surface. The sampled surface should appear smooth, and should be guided by the control points. This tool is the first test that the mrcal projection is implemented correctly mrcal-2.4.1/analyses/splines/bsplines.py000077500000000000000000000371001456301662300203130ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Studies the 2d surface b-spline interpolation The expressions for the interpolated surface I need aren't entirely clear, so I want to study this somewhat. This script does that. I want to use b-splines to drive the generic camera models. These provide local support in the control points at the expense of not interpolating the control points. I don't NEED an interpolating spline, so this is just fine. Let's assume the knots lie at integer coordinates. I want a function that takes in - the control points in a neighborhood of the spline segment - the query point x, scaled to [0,1] in the spline segment This is all nontrivial for some reason, and there're several implementations floating around with slightly different inputs. I have - sample_segment_cubic() From a generic calibration research library: https://github.com/puzzlepaint/camera_calibration/blob/master/applications/camera_calibration/scripts/derive_jacobians.py in the EvalUniformCubicBSpline() function. This does what I want (query point in [0,1], control points around it, one segment at a time), but the source of the expression isn't given. I'd like to re-derive it, and then possibly extend it - splev_local() wraps scipy.interpolate.splev() - splev_translated() Followed sources of scipy.interpolate.splev() to the core fortran functions in fpbspl.f and splev.f. I then ran these through f2c, pythonified it, and simplified it. The result is sympy-able - splev_wikipedia() Sample implementation of De Boor's algorithm from wikipedia: https://en.wikipedia.org/wiki/De_Boor%27s_algorithm from EvalUniformCubicBSpline() in camera_calibration/applications/camera_calibration/scripts/derive_jacobians.py. translated to [0,1] from [3,4] ''' import sys import numpy as np import numpysane as nps import gnuplotlib as gp skip_plots = False import scipy.interpolate from scipy.interpolate import _fitpack def sample_segment_cubic(x, a,b,c,d): A = (-x**3 + 3*x**2 - 3*x + 1)/6 B = (3 * x**3/2 - 3*x**2 + 2)/3 C = (-3 * x**3 + 3*x**2 + 3*x + 1)/6 D = (x * x * x) / 6 return A*a + B*b + C*c + D*d def splev_local(x, t, c, k, der=0, ext=0): y = scipy.interpolate.splev(x, (t,c,k), der, ext) return y.reshape(x.shape) def splev_translated(x, t, c, k, l): # assumes that t[l] <= x <= t[l+1] # print(f"l = {l}") # print((t[l], x, t[l+1])) l += 1 # l is now a fortran-style index hh = [0] * 19 h__ = [0] * 19 h__[-1 + 1] = 1 i__1 = k for j in range(1,i__1+1): i__2 = j for i__ in range(1,i__2+1): hh[-1 + i__] = h__[-1 + i__] h__[-1 + 1] = 0 i__2 = j for i__ in range(1,i__2+1): li = l + i__ lj = li - j if t[-1 + li] != t[-1 + lj]: h__[-1 + i__] += (t[-1 + li] - x) * hh[-1 + i__] / (t[-1 + li] - t[-1 + lj]) h__[-1 + i__ + 1] = (x - t[-1 + lj]) * hh[-1 + i__] / (t[-1 + li] - t[-1 + lj]) else: h__[-1 + i__ + 1] = 0 sp = 0 ll = l - (k+1) i__2 = (k+1) for j in range(1,i__2+1): ll += 1 sp += c[-1 + ll] * h__[-1 + j] return sp # from https://en.wikipedia.org/wiki/De_Boor%27s_algorithm def splev_wikipedia(k: int, x: int, t, c, p: int): """Evaluates S(x). Arguments --------- k: Index of knot interval that contains x. x: Position. t: Array of knot positions, needs to be padded as described above. c: Array of control points. We will look at c[k-p .. k] p: Degree of B-spline. """ # make sure I never reference c out of bounds if k-p < 0: raise Exception("c referenced out of min bounds") if k >= len(c): raise Exception("c referenced out of max bounds") d = [c[j + k - p] for j in range(0, p+1)] for r in range(1, p+1): for j in range(p, r-1, -1): alpha = (x - t[j+k-p]) / (t[j+1+k-r] - t[j+k-p]) d[j] = (1 - alpha) * d[j-1] + alpha * d[j] return d[p] ############################################################################## # First I confirm that the functions from numpy and from wikipedia produce the # same results. I don't care about edge cases for now. I query an arbitrary # point N = 30 t = np.arange( N, dtype=int) k = 3 c = np.random.rand(len(t)) x = 4.3 # may have trouble exactly AT the knots. the edge logic isn't quite what I want l = np.searchsorted(np.array(t), x)-1 y0 = splev_local(np.array((x,)),t,c,k)[0] y1 = splev_translated(x, t, c, k, l) y2 = splev_wikipedia(l, x, t, c, k) print(f"These should all match: {y0} {y1} {y2}") print(f" err1 = {y1-y0}") print(f" err2 = {y2-y0}") ############################################################################## # OK, good. I want to make sure that the spline roughly follows the curve # defined by the control points. There should be no x offset or anything of that # sort N = 30 t = np.arange( N, dtype=int) k = 3 c = np.random.rand(len(t)) Npad = 10 x = np.linspace(Npad, N-Npad, 1000) ########### sample_segment_cubic() @nps.broadcast_define(((),), ()) def sample_cubic(x, cp): i = int(x//1) q = x-i try: return sample_segment_cubic(q, *cp[i-1:i+3]) except: return 0 y = sample_cubic(x, c) c2 = c.copy() c2[int(N//2)] *= 1.1 y2 = sample_cubic(x, c2) if not skip_plots: plot1 = gp.gnuplotlib(title = 'Cubic splines: response to control point perturbation', # hardcopy = '/tmp/cubic-spline-perturbations.svg', # terminal = 'svg size 800,600 noenhanced solid dynamic font ",12"' ) plot1.plot( (x, nps.cat(y,y2), dict(_with = np.array(('lines lc "blue"', 'lines lc "sea-green"')), legend = np.array(('Spline: baseline', 'Spline: tweaked one control point')))), (t[:len(c)], nps.cat(c,c2), dict(_with = np.array(('points pt 1 ps 1 lc "blue"', 'points pt 2 ps 1 lc "sea-green"')), legend= np.array(('Control points: baseline', 'Control points: tweaked one control point')))), (x, y-y2, dict(_with = 'lines lc "red"', legend = 'Difference', y2 = 1)), _xrange = (10.5,19.5), y2max = 0.01, ylabel = 'Spline value', y2label = 'Difference due to perturbation',) ########### sample_wikipedia() @nps.broadcast_define(((),), ()) def sample_wikipedia(x, t, c, k): return splev_wikipedia(np.searchsorted(np.array(t), x)-1,x,t,c,k) @nps.broadcast_define(((),), ()) def sample_wikipedia_integer_knots(x, c, k): t = np.arange(len(c) + k, dtype=int) l = int(x//1) offset = int((k+1)//2) return splev_wikipedia(l,x,t,c[offset:],k) if 1: y = sample_wikipedia_integer_knots(x,c,k) else: offset = int((k+1)//2) y = sample_wikipedia(x,t, c[offset:], k) if not skip_plots: plot2 = gp.gnuplotlib(title = 'sample_wikipedia') plot2.plot( (x, y, dict(_with='lines')), (t[:len(c)], c, dict(_with='linespoints pt 7 ps 2')) ) print("these two plots should look the same: we're using two implementation of the same algorithm to interpolate the same data") plot2.wait() plot1.wait() # Now I use sympy to get the polynomial coefficients from sample_wikipedia. # These should match the ones in sample_segment_cubic() import sympy c = sympy.symbols(f'c:{len(c)}') x = sympy.symbols('x') # Which interval we're in. Arbitrary. In the middle somewhere l = int(N//2) print("Should match A,B,C,D coefficients in sample_segment_cubic()") s = splev_wikipedia(l, # I want 'x' to be [0,1] within the interval, but this # function wants x in the whole domain x+l, np.arange( N, dtype=int), c, k).expand() print(s.coeff(c[12])) print(s.coeff(c[13])) print(s.coeff(c[14])) print(s.coeff(c[15])) print("Should also match A,B,C,D coefficients in sample_segment_cubic()") s = splev_translated(# I want 'x' to be [0,1] within the interval, but this # function wants x in the whole domain x+l, np.arange( N, dtype=int), c, k, l).expand() print(s.coeff(c[12])) print(s.coeff(c[13])) print(s.coeff(c[14])) print(s.coeff(c[15])) ######################################################### # Great. More questions. Here I have a cubic spline (k==3). And to evaluate the # spline value I need to have 4 control point values available, 2 on either # side. Piecewise-linear splines are too rough, but quadratic splines could work # (k==2). What do the expressions look like? How many neighbors do I need? Here # the control point values c represent the function value between adjacent # knots, so each segment uses 3 neighboring control points, and is defined in a # region [-0.5..0.5] off the center control point print("======================== k = 2") N = 30 t = np.arange( N, dtype=int) k = 2 # c[0,1,2] corresponds to is t[-0.5 0.5 1.5 2.5 ... c = np.random.rand(len(t)) x = 4.3 # may have trouble exactly AT the knots. the edge logic isn't quite what I want l = np.searchsorted(np.array(t), x)-1 y0 = splev_local(np.array((x,)),t,c,k)[0] y1 = splev_translated(x, t, c, k, l) y2 = splev_wikipedia(l, x, t, c, k) print(f"These should all match: {y0} {y1} {y2}") print(f" err1 = {y1-y0}") print(f" err2 = {y2-y0}") ############################################################################## # OK, good. I want to make sure that the spline roughly follows the curve # defined by the control points. There should be no x offset or anything of that # sort if not skip_plots: N = 30 t = np.arange( N, dtype=int) k = 2 c = np.random.rand(len(t)) Npad = 10 x = np.linspace(Npad, N-Npad, 1000) offset = int((k+1)//2) y = sample_wikipedia(x,t-0.5, c[offset:], k) xm = (x[1:] + x[:-1]) / 2. d = np.diff(y) / np.diff(x) plot1 = gp.gnuplotlib(title = 'k==2; sample_wikipedia') plot1.plot( (x, y, dict(_with='lines', legend='spline')), (xm, d, dict(_with='lines', y2=1, legend='diff')), (t[:len(c)], c, dict(_with='linespoints pt 7 ps 2', legend='control points'))) @nps.broadcast_define(((),), ()) def sample_splev_translated(x, t, c, k): l = np.searchsorted(np.array(t), x)-1 return splev_translated(x,t,c,k,l) y = sample_splev_translated(x,t-0.5, c[offset:], k) xm = (x[1:] + x[:-1]) / 2. d = np.diff(y) / np.diff(x) plot2 = gp.gnuplotlib(title = 'k==2; splev_translated') plot2.plot( (x, y, dict(_with='lines', legend='spline')), (xm, d, dict(_with='lines', y2=1, legend='diff')), (t[:len(c)], c, dict(_with='linespoints pt 7 ps 2', legend='control points'))) # These are the functions I'm going to use. Derived by the sympy steps # immediately after this def sample_segment_quadratic(x, a,b,c): A = (4*x**2 - 4*x + 1)/8 B = (3 - 4*x**2)/4 C = (4*x**2 + 4*x + 1)/8 return A*a + B*b + C*c @nps.broadcast_define(((),), ()) def sample_quadratic(x, cp): i = int((x+0.5)//1) q = x-i try: return sample_segment_quadratic(q, *cp[i-1:i+2]) except: return 0 y = sample_quadratic(x, c) xm = (x[1:] + x[:-1]) / 2. d = np.diff(y) / np.diff(x) plot3 = gp.gnuplotlib(title = 'k==2; sample_quadratic') plot3.plot( (x, y, dict(_with='lines', legend='spline')), (xm, d, dict(_with='lines', y2=1, legend='diff')), (t[:len(c)], c, dict(_with='linespoints pt 7 ps 2', legend='control points'))) plot3.wait() plot2.wait() plot1.wait() print("these 3 plots should look the same: we're using different implementation of the same algorithm to interpolate the same data") # ################################## # # OK, these match. Let's get the expression of the polynomial in a segment. This # # was used to construct sample_segment_quadratic() above # c = sympy.symbols(f'c:{len(c)}') # x = sympy.symbols('x') # l = int(N//2) # print("A,B,C for k==2 using splev_wikipedia()") # s = splev_wikipedia(l, # # I want 'x' to be [-0.5..0.5] within the interval, but this # # function wants x in the whole domain # x+l, # np.arange( N, dtype=int) - sympy.Rational(1,2), c, k).expand() # print(s) # print(s.coeff(c[13])) # print(s.coeff(c[14])) # print(s.coeff(c[15])) # # I see this: # # c13*x**2/2 - c13*x/2 + c13/8 - c14*x**2 + 3*c14/4 + c15*x**2/2 + c15*x/2 + c15/8 # # x**2/2 - x/2 + 1/8 # # 3/4 - x**2 # # x**2/2 + x/2 + 1/8 ############## compare cubic, quadratic # I now have nice expressions for quadratic and cubic interpolations. Both are # C1 continuous, but the cubic interpolation is C2 continuous too. How much do I # care? Let's at least compare them visually N = 30 t = np.arange( N, dtype=int) c = np.random.rand(len(t)) Npad = 10 x = np.linspace(Npad, N-Npad, 1000) y2 = sample_quadratic(x,c) y3 = sample_cubic( x,c) if not skip_plots: gp.plot( (x, nps.cat(y2,y3), dict(_with='lines', legend=np.array(('quadratic', 'cubic')))), (t[:len(c)], c, dict(_with='linespoints pt 7 ps 2', legend='control points')), title = "Comparing quadratic and cubic b-spline interpolation", wait = True) # Visually, neither looks better than the other. The quadratic spline follows # the control points closer. Looks like it's trying to match the slope at the # halfway point. Maybe that's bad, and the quadratic curve is too wiggly? We'll # see #################################################################### # Great. Final set of questions: how do you we make a 2D spline surface? The # generic calibration research library # (https://github.com/puzzlepaint/camera_calibration) Does a set of 1d # interpolations in one dimension, and then interpolates the 4 interpolated # values along the other dimension. Questions: # # Does order matter? I can do x and then y or y then x # # And is there a better way? scipy has 2d b-spline interpolation routines. Do # they do something better? # # ############### x-y or y-x? import sympy from sympy.abc import x,y cp = sympy.symbols('cp:4(:4)') # x then y xs = [sample_segment_cubic( x, cp[i*4 + 0], cp[i*4 + 1], cp[i*4 + 2], cp[i*4 + 3] ) for i in range(4)] yxs = sample_segment_cubic(y, *xs) # y then x ys = [sample_segment_cubic( y, cp[0*4 + i], cp[1*4 + i], cp[2*4 + i], cp[3*4 + i] ) for i in range(4)] xys = sample_segment_cubic(x, *ys) print(f"Bicubic interpolation. x-then-y and y-then-x difference: {(xys - yxs).expand()}") ########### Alright. Apparently either order is ok. Does scipy do something ########### different for 2d interpolation? I compare the 1d-then-1d ########### interpolation above to fitpack results: from fpbisp import fpbisp_ N = 30 t = np.arange( N, dtype=int) k = 3 cp = np.array(sympy.symbols('cp:40(:40)'), dtype=np.object).reshape(40,40) lx = 3 ly = 5 z = fpbisp_(t, t, k, cp, x+lx, lx, y+ly, ly) err = z - yxs print(f"Bicubic interpolation. difference(1d-then-1d, FITPACK): {err.expand()}") # Apparently chaining 1D interpolations produces identical results to what FITPACK is doing mrcal-2.4.1/analyses/splines/fpbisp.py000066400000000000000000000031561456301662300177600ustar00rootroot00000000000000r'''Translation of fpbpl and fpbisp from Fortran to Python The scipy source includes FITPACK, which implements b-spline interpolation. I converted its 2D surface interpolation routine (fpbisp) to C (via f2c), and then semi-manually to Python. I can then feed it sympy symbols, and get out analytical expressions, which are surprisingly difficult to find in a nice usable form on the internet. The original fpbisp implementation is at scipy/interpolate/fitpack/fpbisp.f The analysis that uses this conversion lives in bsplines.py ''' import sympy def fpbspl_(t, k, x, l): h__ = [None] * 100 hh = [None] * 100 h__[-1 + 1] = sympy.Integer(1) i__1 = k for j in range(1,i__1+1): i__2 = j for i__ in range(1,i__2+1): hh[i__ - 1] = h__[-1 + i__] h__[-1 + 1] = 0 i__2 = j for i__ in range(1,i__2+1): li = l + i__ lj = li - j f = hh[i__ - 1] / (t[li] - t[lj]) h__[-1 + i__] += f * (t[li] - x) h__[-1 + i__ + 1] = f * (x - t[lj]) return h__ # argx is between tx[lx] and tx[lx+1]. Same with y def fpbisp_(tx, ty, k, c, argx, lx, argy, ly): wx = [None] * 100 wy = [None] * 100 h__ = fpbspl_(tx, k, argx, lx) for j in range(1, (k+1)+1): wx[1 + j] = h__[j - 1] h__ = fpbspl_(ty, k, argy, ly) for j in range(1,(k+1)+1): wy[1 + j] = h__[j - 1] for i1 in range(1,(k+1)+1): h__[i1 - 1] = wx[1 + i1] sp = 0 for i1 in range(1,(k+1)+1): for j1 in range(1,(k+1)+1): sp += c[j1-1,i1-1] * h__[i1 - 1] * wy[1 + j1] return sp mrcal-2.4.1/analyses/splines/show-fisheye-grid.py000077500000000000000000000104421456301662300220310ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Evaluate 2D griddings of a camera view I'm interested in gridding the observation vectors for projection. These observation vectors have length-1, so they're 3D quantities that live in a 2D manifold. I need some sort of a 2D representation so that I can convert between this representation and the 3D vectors without worrying about constraints. I'd like a rectangular 2D gridding of observation vectors to more-or-less map to a gridding of projected pixel coordinates: I want both to be as rectangular as possible. This tool grids the imager, and plots the unprojected grid for a number of different 3d->2d schemes. I take in an existing camera mode, and I grid its imager. I unproject each pixel, and reproject back using the scheme I'm looking at. Most schemes are fisheye projections described at https://en.wikipedia.org/wiki/Fisheye_lens mrcal-show-distortion-off-pinhole --radial also compares a given model with fisheye projections ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('scheme', type=str, choices=('pinhole', 'stereographic', 'equidistant', 'equisolidangle', 'orthographic'), help='''Type of fisheye model to visualize. For a description of the choices see https://en.wikipedia.org/wiki/Fisheye_lens''') parser.add_argument('model', type=str, help='''Camera model to grid''') args = parser.parse_args() return args args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README import numpy as np import numpysane as nps import gnuplotlib as gp testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/../..", import mrcal @nps.broadcast_define(((3,),), (2,)) def project_simple(v, d): k = d[4:] fxy = d[:2] cxy = d[2:4] x,y = v[:2]/v[2] r2 = x*x + y*y r4 = r2*r2 r6 = r4*r2 a1 = 2*x*y a2 = r2 + 2*x*x a3 = r2 + 2*y*y cdist = 1 + k[0]*r2 + k[1]*r4 + k[4]*r6 icdist2 = 1./(1 + k[5]*r2 + k[6]*r4 + k[7]*r6) return np.array(( x*cdist*icdist2 + k[2]*a1 + k[3]*a2, y*cdist*icdist2 + k[2]*a3 + k[3]*a1 )) * fxy + cxy @nps.broadcast_define(((3,),), (2,)) def project_radial_numdenom(v, d): k = d[4:] fxy = d[:2] cxy = d[2:4] x,y = v[:2]/v[2] r2 = x*x + y*y r4 = r2*r2 r6 = r4*r2 a1 = 2*x*y a2 = r2 + 2*x*x a3 = r2 + 2*y*y return np.array((1 + k[0]*r2 + k[1]*r4 + k[4]*r6, 1 + k[5]*r2 + k[6]*r4 + k[7]*r6)) try: m = mrcal.cameramodel(args.model) except: print(f"Couldn't read '{args.model}' as a camera model", file=sys.stderr) sys.exit(1) W,H = m.imagersize() Nw = 40 Nh = 30 # shape (Nh,Nw,2) xy = \ nps.mv(nps.cat(*np.meshgrid( np.linspace(0,W-1,Nw), np.linspace(0,H-1,Nh) )), 0,-1) fxy = m.intrinsics()[1][0:2] cxy = m.intrinsics()[1][2:4] # shape (Nh,Nw,2) v = mrcal.unproject(np.ascontiguousarray(xy), *m.intrinsics()) v0 = mrcal.unproject(cxy, *m.intrinsics()) # shape (Nh,Nw) costh = nps.inner(v,v0) / (nps.mag(v) * nps.mag(v0)) th = np.arccos(costh) # shape (Nh,Nw,2) xy_rel = xy-cxy # shape (Nh,Nw) az = np.arctan2( xy_rel[...,1], xy_rel[..., 0]) if args.scheme == 'stereographic': r = np.tan(th/2.) * 2. elif args.scheme == 'equidistant': r = th elif args.scheme == 'equisolidangle': r = np.sin(th/2.) * 2. elif args.scheme == 'orthographic': r = np.sin(th) elif args.scheme == 'pinhole': r = np.tan(th) else: print("Unknown scheme {args.scheme}. Shouldn't happen. argparse should have taken care of it") mapped = xy_rel * nps.dummy(r/nps.mag(xy_rel),-1) gp.plot(mapped, tuplesize=-2, _with = 'linespoints', title = f"Gridded model '{args.model}' looking at pinhole unprojection with z=1", xlabel = f'Normalized {args.scheme} x', ylabel = f'Normalized {args.scheme} y', square = True, wait = True) mrcal-2.4.1/analyses/splines/verify-interpolated-surface.py000077500000000000000000000111511456301662300241140ustar00rootroot00000000000000#!/usr/bin/env python3 f'''Observe the interpolation grid implemented in the C code This is a validation of mrcal.project() ''' import sys import os import numpy as np import numpysane as nps import gnuplotlib as gp testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/../..", import mrcal order = 3 Nx = 11 Ny = 8 fov_x_deg = 200 # more than 180deg imagersize = np.array((3000,2000)) fxy = np.array((2000., 1900.)) cxy = (imagersize.astype(float) - 1.) / 2. # I want random control points, with some (different) bias on x and y controlpoints_x = np.random.rand(Ny, Nx) * 1 + 0.5 * np.arange(Nx)/Nx controlpoints_y = np.random.rand(Ny, Nx) * 1 - 0.9 * np.arange(Nx)/Nx # to test a delta function # controlpoints_y*=0 # controlpoints_y[4,5] = 1 # The parameters vector dimensions appear (in order from slowest-changing to # fastest-changing): # - y coord # - x coord # - fx/fy parameters = nps.glue( np.array(( fxy[0], fxy[1], cxy[0], cxy[1])), nps.mv(nps.cat(controlpoints_x,controlpoints_y), 0, -1).ravel(), axis = -1 ) # Now I produce a grid of observation vectors indexed on the coords of the # control-point arrays # The index into my spline. ixy has shape (Ny,Nx,2) and contains (x,y) rows Nw = Nx*5 Nh = Ny*5 x_sampled = np.linspace(1,Nx-2,Nh) y_sampled = np.linspace(1,Ny-2,Nw) ixy = \ nps.mv( nps.cat(*np.meshgrid( x_sampled, y_sampled )), 0,-1) ##### this has mostly been implemented in mrcal_project_stereographic() and ##### mrcal_unproject_stereographic() # Stereographic projection function: # p = xyz # rxy = mag(xy) # th = atan2(rxy, z) # u = tan(th/2) * 2. * xy/mag(xy) # q = (u + deltau) * fxy + cxy # # I look up deltau in the splined surface. The index of that lookup is linear # (and cartesian) with u # # So ixy = u * k + (Nxy-1)/2 # # ix is in [0,Nx] (modulo edges). one per control point # # Note that the same scale k is applied for both the x and y indices. The # constants set the center of the spline surface to x=0 and y=0 # # The scale k is set by fov_x_deg (this is at y=0): # # ix_margin = tan(-fov_x_deg/2/2) * 2. * k + (Nx-1)/2 ---> # k = (ix_margin - (Nx-1)/2) / (tan(fov_x_deg/2/2) * 2) # # I want to compute p from (ix,iy). p is unique up-to scale. So let me # arbitrarily set mag(xy) = 1. I define a new var # # jxy = tan(th/2) xy ---> # jxy = (ixy - (Nxy-1)/2) / (2k) # # jxy = tan(th/2) xy # = (1 - cos(th)) / sin(th) xy # = (1 - cos(atan2(1, z))) / sin(atan2(1, z)) xy # = (1 - z/mag(xyz)) / (1/mag(xyz)) xy = # = (mag(xyz) - z) xy = # # mag(jxy) = (mag(xyz) - z) # = sqrt(z^2+1) - z # # Let h = sqrt(z^2+1) + z -> # mag(jxy) h = 1 # h - mag(jxy) = 2z # ---> z = (h - mag(jxy)) / 2 = (1/mag(jxy) - mag(jxy)) / 2 if order == 3: # cubic splines. There's exactly one extra control point on each side past # my fov. So ix_margin = 1 ix_margin = 1 else: # quadratic splines. 1/2 control points on each side past my fov ix_margin = 0.5 k = (ix_margin - (Nx-1)/2) / (np.tan(-fov_x_deg*np.pi/180./2/2) * 2) jxy = (ixy - (np.array( (Nx, Ny), dtype=float) - 1.)/2.) / k / 2. mjxy = nps.mag(jxy) z = (1./mjxy - mjxy) / 2. xy = jxy / nps.dummy(mjxy, -1) # singular at the center. Do I care? p = nps.glue(xy, nps.dummy(z,-1), axis=-1) mxy = nps.mag(xy) # Bam. I have applied a stereographic unprojection to get 3D vectors that would # stereographically project to given spline grid locations. I use the mrcal # internals to project the unprojection, and to get the focal lengths it ended # up using. If the internals were implemented correctly, the dense surface of # focal lengths should follow the sparse surface of spline control points lensmodel_type = f'LENSMODEL_SPLINED_STEREOGRAPHIC_order={order}_Nx={Nx}_Ny={Ny}_fov_x_deg={fov_x_deg}' q = mrcal.project(np.ascontiguousarray(p), lensmodel_type, parameters) th = np.arctan2( nps.mag(p[..., :2]), p[..., 2]) uxy = p[..., :2] * nps.dummy(np.tan(th/2)*2/nps.mag(p[..., :2]), -1) deltau = (q-cxy) / fxy - uxy deltaux,deltauy = nps.mv(deltau, -1,0) gp.plot3d( (deltauy, dict( _with='lines', using=f'($1*{x_sampled[1]-x_sampled[0]}+{x_sampled[0]}):($2*{y_sampled[1]-y_sampled[0]}+{y_sampled[0]}):3' )), (controlpoints_y, dict( _with='points pt 7 ps 2' )), xlabel='x control point index', ylabel='y control point index', title='Deltau-y', squarexy=True, ascii=True, wait=True) mrcal-2.4.1/analyses/triangulation/000077500000000000000000000000001456301662300173215ustar00rootroot00000000000000mrcal-2.4.1/analyses/triangulation/study.py000077500000000000000000000277161456301662300210630ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Study the precision and accuracy of the various triangulation routines''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--Nsamples', type=int, default=100000, help='''How many random samples to evaluate. 100000 by default''') group = parser.add_mutually_exclusive_group(required = True) group.add_argument('--ellipses', action='store_true', help='''Display the ellipses and samples in the xy plane''') group.add_argument('--ranges', action='store_true', help='''Display the distribution of the range''') parser.add_argument('--samples', action='store_true', help='''If --ellipses, plot the samples ALSO. Usually this doesn't clarify anything, so the default is to omit them''') parser.add_argument('--cache', type=str, choices=('read','write'), help=f'''A cache file stores the recalibration results; computing these can take a long time. This option allows us to or write the cache instead of sampling. The cache file is hardcoded to a cache file (in /tmp). By default, we do neither: we don't read the cache (we sample instead), and we do not write it to disk when we're done. This option is useful for tests where we reprocess the same scenario repeatedly''') parser.add_argument('--observed-point', type = float, nargs = 3, default = ( 5000., 300., 2000.), help='''The camera0 coordinate of the observed point. Default is ( 5000., 300., 2000.)''') parser.add_argument('--title', type=str, default = None, help='''Title string for the plot. Overrides the default title. Exclusive with --extratitle''') parser.add_argument('--extratitle', type=str, default = None, help='''Additional string for the plot to append to the default title. Exclusive with --title''') parser.add_argument('--hardcopy', type=str, help='''Write the output to disk, instead of an interactive plot''') parser.add_argument('--terminal', type=str, help=r'''gnuplotlib terminal. The default is good almost always, so most people don't need this option''') parser.add_argument('--set', type=str, action='append', help='''Extra 'set' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('--unset', type=str, action='append', help='''Extra 'unset' directives to gnuplotlib. Can be given multiple times''') args = parser.parse_args() if args.title is not None and \ args.extratitle is not None: print("--title and --extratitle are exclusive", file=sys.stderr) sys.exit(1) return args args = parse_args() import numpy as np import numpysane as nps import gnuplotlib as gp import pickle import os.path # I import the LOCAL mrcal scriptdir = os.path.dirname(os.path.realpath(__file__)) sys.path[:0] = f"{scriptdir}/../..", import mrcal ############ bias visualization # # I simulate pixel noise, and see what that does to the triangulation. Play with # the geometric details to get a sense of how these behave model0 = mrcal.cameramodel( intrinsics = ('LENSMODEL_PINHOLE', np.array((1000., 1000., 500., 500.))), imagersize = np.array((1000,1000)) ) model1 = mrcal.cameramodel( intrinsics = ('LENSMODEL_PINHOLE', np.array((1100., 1100., 500., 500.))), imagersize = np.array((1000,1000)) ) # square camera layout t01 = np.array(( 1., 0.1, -0.2)) R01 = mrcal.R_from_r(np.array((0.001, -0.002, -0.003))) Rt01 = nps.glue(R01, t01, axis=-2) p = np.array(args.observed_point) q0 = mrcal.project(p, *model0.intrinsics()) sigma = 0.1 cache_file = "/tmp/triangulation-study-cache.pickle" if args.cache is None or args.cache == 'write': v0local_noisy, v1local_noisy,v0_noisy,v1_noisy,_,_,_,_ = \ mrcal.synthetic_data. \ _noisy_observation_vectors_for_triangulation(p,Rt01, model0.intrinsics(), model1.intrinsics(), args.Nsamples, sigma = sigma) p_sampled_geometric = mrcal.triangulate_geometric( v0_noisy, v1_noisy, t01 ) p_sampled_lindstrom = mrcal.triangulate_lindstrom( v0local_noisy, v1local_noisy, Rt01 ) p_sampled_leecivera_l1 = mrcal.triangulate_leecivera_l1( v0_noisy, v1_noisy, t01 ) p_sampled_leecivera_linf = mrcal.triangulate_leecivera_linf( v0_noisy, v1_noisy, t01 ) p_sampled_leecivera_mid2 = mrcal.triangulate_leecivera_mid2( v0_noisy, v1_noisy, t01 ) p_sampled_leecivera_wmid2 = mrcal.triangulate_leecivera_wmid2(v0_noisy, v1_noisy, t01 ) q0_sampled_geometric = mrcal.project(p_sampled_geometric, *model0.intrinsics()) q0_sampled_lindstrom = mrcal.project(p_sampled_lindstrom, *model0.intrinsics()) q0_sampled_leecivera_l1 = mrcal.project(p_sampled_leecivera_l1, *model0.intrinsics()) q0_sampled_leecivera_linf = mrcal.project(p_sampled_leecivera_linf, *model0.intrinsics()) q0_sampled_leecivera_mid2 = mrcal.project(p_sampled_leecivera_mid2, *model0.intrinsics()) q0_sampled_leecivera_wmid2 = mrcal.project(p_sampled_leecivera_wmid2, *model0.intrinsics()) range_sampled_geometric = nps.mag(p_sampled_geometric) range_sampled_lindstrom = nps.mag(p_sampled_lindstrom) range_sampled_leecivera_l1 = nps.mag(p_sampled_leecivera_l1) range_sampled_leecivera_linf = nps.mag(p_sampled_leecivera_linf) range_sampled_leecivera_mid2 = nps.mag(p_sampled_leecivera_mid2) range_sampled_leecivera_wmid2 = nps.mag(p_sampled_leecivera_wmid2) if args.cache is not None: with open(cache_file,"wb") as f: pickle.dump((v0local_noisy, v1local_noisy, v0_noisy, v1_noisy, p_sampled_geometric, p_sampled_lindstrom, p_sampled_leecivera_l1, p_sampled_leecivera_linf, p_sampled_leecivera_mid2, p_sampled_leecivera_wmid2, q0_sampled_geometric, q0_sampled_lindstrom, q0_sampled_leecivera_l1, q0_sampled_leecivera_linf, q0_sampled_leecivera_mid2, q0_sampled_leecivera_wmid2, range_sampled_geometric, range_sampled_lindstrom, range_sampled_leecivera_l1, range_sampled_leecivera_linf, range_sampled_leecivera_mid2, range_sampled_leecivera_wmid2), f) print(f"Wrote cache to {cache_file}") else: with open(cache_file,"rb") as f: (v0local_noisy, v1local_noisy, v0_noisy, v1_noisy, p_sampled_geometric, p_sampled_lindstrom, p_sampled_leecivera_l1, p_sampled_leecivera_linf, p_sampled_leecivera_mid2, p_sampled_leecivera_wmid2, q0_sampled_geometric, q0_sampled_lindstrom, q0_sampled_leecivera_l1, q0_sampled_leecivera_linf, q0_sampled_leecivera_mid2, q0_sampled_leecivera_wmid2, range_sampled_geometric, range_sampled_lindstrom, range_sampled_leecivera_l1, range_sampled_leecivera_linf, range_sampled_leecivera_mid2, range_sampled_leecivera_wmid2) = \ pickle.load(f) plot_options = {} if args.set is not None: plot_options['set'] = args.set if args.unset is not None: plot_options['unset'] = args.unset if args.hardcopy is not None: plot_options['hardcopy'] = args.hardcopy if args.terminal is not None: plot_options['terminal'] = args.terminal if args.ellipses: # Plot the reprojected pixels and the fitted ellipses data_tuples = \ [ *mrcal.utils._plot_args_points_and_covariance_ellipse( q0_sampled_geometric, 'geometric' ), *mrcal.utils._plot_args_points_and_covariance_ellipse( q0_sampled_lindstrom, 'lindstrom' ), *mrcal.utils._plot_args_points_and_covariance_ellipse( q0_sampled_leecivera_l1, 'lee-civera-l1' ), *mrcal.utils._plot_args_points_and_covariance_ellipse( q0_sampled_leecivera_linf, 'lee-civera-linf' ), *mrcal.utils._plot_args_points_and_covariance_ellipse( q0_sampled_leecivera_mid2, 'lee-civera-mid2' ), *mrcal.utils._plot_args_points_and_covariance_ellipse( q0_sampled_leecivera_wmid2,'lee-civera-wmid2' ), ] if not args.samples: # Not plotting samples. Get rid of all the "dots" I'm plotting data_tuples = [ t for t in data_tuples if \ not (isinstance(t[-1], dict) and \ '_with' in t[-1] and \ t[-1]['_with'] == 'dots') ] if args.title is not None: title = args.title else: title = 'Reprojected triangulated point' if args.extratitle is not None: title += ': ' + args.extratitle gp.plot( *data_tuples, ( q0, dict(_with = 'points pt 3 ps 2', tuplesize = -2, legend = 'Ground truth')), square = True, wait = 'hardcopy' not in plot_options, title = title, **plot_options) elif args.ranges: # Plot the range distribution range_ref = nps.mag(p) if args.title is not None: title = args.title else: title = "Range distribution" if args.extratitle is not None: title += ': ' + args.extratitle gp.plot( nps.cat( range_sampled_geometric, range_sampled_lindstrom, range_sampled_leecivera_l1, range_sampled_leecivera_linf, range_sampled_leecivera_mid2, range_sampled_leecivera_wmid2 ), legend = np.array(( 'range_sampled_geometric', 'range_sampled_lindstrom', 'range_sampled_leecivera_l1', 'range_sampled_leecivera_linf', 'range_sampled_leecivera_mid2', 'range_sampled_leecivera_wmid2' )), histogram=True, binwidth=200, _with='lines', _set = f'arrow from {range_ref},graph 0 to {range_ref},graph 1 nohead lw 5', wait = 'hardcopy' not in plot_options, title = title, **plot_options) else: raise Exception("Getting here is a bug") mrcal-2.4.1/autodiff.hh000066400000000000000000000313701456301662300147500ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #pragma once /* Automatic differentiation routines. Used in poseutils-uses-autodiff.cc. See that file for usage examples */ // Apparently I need this in MSVC to get constants #define _USE_MATH_DEFINES #include #include #include "strides.h" template struct vec_withgrad_t; template struct val_withgrad_t { double x; double j[NGRAD]; val_withgrad_t(double _x = 0.0) : x(_x) { for(int i=0; i operator+( const val_withgrad_t& b ) const { val_withgrad_t y = *this; y.x += b.x; for(int i=0; i operator+( double b ) const { val_withgrad_t y = *this; y.x += b; return y; } void operator+=( const val_withgrad_t& b ) { *this = (*this) + b; } val_withgrad_t operator-( const val_withgrad_t& b ) const { val_withgrad_t y = *this; y.x -= b.x; for(int i=0; i operator-( double b ) const { val_withgrad_t y = *this; y.x -= b; return y; } void operator-=( const val_withgrad_t& b ) { *this = (*this) - b; } val_withgrad_t operator-() const { return (*this) * (-1); } val_withgrad_t operator*( const val_withgrad_t& b ) const { val_withgrad_t y; y.x = x * b.x; for(int i=0; i operator*( double b ) const { val_withgrad_t y; y.x = x * b; for(int i=0; i& b ) { *this = (*this) * b; } val_withgrad_t operator/( const val_withgrad_t& b ) const { val_withgrad_t y; y.x = x / b.x; for(int i=0; i operator/( double b ) const { return (*this) * (1./b); } val_withgrad_t sqrt(void) const { val_withgrad_t y; y.x = ::sqrt(x); for(int i=0; i square(void) const { val_withgrad_t s; s.x = x*x; for(int i=0; i sin(void) const { const double s = ::sin(x); const double c = ::cos(x); val_withgrad_t y; y.x = s; for(int i=0; i cos(void) const { const double s = ::sin(x); const double c = ::cos(x); val_withgrad_t y; y.x = c; for(int i=0; i sincos(void) const { const double s = ::sin(x); const double c = ::cos(x); vec_withgrad_t sc; sc.v[0].x = s; sc.v[1].x = c; for(int i=0; i tan(void) const { const double s = ::sin(x); const double c = ::cos(x); val_withgrad_t y; y.x = s/c; for(int i=0; i atan2(val_withgrad_t& x) const { val_withgrad_t th; const val_withgrad_t& y = *this; th.x = ::atan2(y.x, x.x); // dth/dv = d/dv atan2(y,x) // = d/dv atan(y/x) // = 1 / (1 + y^2/x^2) d/dv (y/x) // = x^2 / (x^2 + y^2) / x^2 * (dy/dv x - y dx/dv) // = 1 / (x^2 + y^2) * (dy/dv x - y dx/dv) double norm2 = y.x*y.x + x.x*x.x; for(int i=0; i acos(void) const { val_withgrad_t th; th.x = ::acos(x); double dacos_dx = -1. / ::sqrt( 1. - x*x ); for(int i=0; i sinx_over_x(// To avoid recomputing it const val_withgrad_t& sinx) const { // For small x I need special-case logic. In the limit as x->0 I have // sin(x)/x -> 1. But I'm propagating gradients, so I need to capture // that. I have // // d(sin(x)/x)/dx = // (x cos(x) - sin(x))/x^2 // // As x -> 0 this is // // (cos(x) - x sin(x) - cos(x)) / (2x) = // (- x sin(x)) / (2x) = // -sin(x) / 2 = // 0 // // So for small x the gradient is 0 if(fabs(x) < 1e-8) return val_withgrad_t(1.0); return sinx / (*this); } }; template struct vec_withgrad_t { val_withgrad_t v[NVEC]; vec_withgrad_t() {} void init_vars(const double* x_in, int ivar0, int Nvars, int i_gradvec0 = -1, int stride = sizeof(double)) { // Initializes vector entries ivar0..ivar0+Nvars-1 inclusive using the // data in x_in[]. x_in[0] corresponds to vector entry ivar0. If // i_gradvec0 >= 0 then vector ivar0 corresponds to gradient index // i_gradvec0, with all subsequent entries being filled-in // consecutively. It's very possible that NGRAD > Nvars. Initially the // subset of the gradient array corresponding to variables // i_gradvec0..i_gradvec0+Nvars-1 is an identity, with the rest being 0 memset((char*)&v[ivar0], 0, Nvars*sizeof(v[0])); for(int i=ivar0; i= 0) v[i].j[i_gradvec0+i-ivar0] = 1.0; } } vec_withgrad_t(const double* x_in, int i_gradvec0 = -1, int stride = sizeof(double)) { init_vars(x_in, 0, NVEC, i_gradvec0, stride); } val_withgrad_t& operator[](int i) { return v[i]; } const val_withgrad_t& operator[](int i) const { return v[i]; } void operator+=( const vec_withgrad_t& x ) { (*this) = (*this) + x; } vec_withgrad_t operator+( const vec_withgrad_t& x ) const { vec_withgrad_t p; for(int i=0; i& x ) { (*this) = (*this) + x; } vec_withgrad_t operator+( const val_withgrad_t& x ) const { vec_withgrad_t p; for(int i=0; i operator+( double x ) const { vec_withgrad_t p; for(int i=0; i& x ) { (*this) = (*this) - x; } vec_withgrad_t operator-( const vec_withgrad_t& x ) const { vec_withgrad_t p; for(int i=0; i& x ) { (*this) = (*this) - x; } vec_withgrad_t operator-( const val_withgrad_t& x ) const { vec_withgrad_t p; for(int i=0; i operator-( double x ) const { vec_withgrad_t p; for(int i=0; i& x ) { (*this) = (*this) * x; } vec_withgrad_t operator*( const vec_withgrad_t& x ) const { vec_withgrad_t p; for(int i=0; i& x ) { (*this) = (*this) * x; } vec_withgrad_t operator*( const val_withgrad_t& x ) const { vec_withgrad_t p; for(int i=0; i operator*( double x ) const { vec_withgrad_t p; for(int i=0; i& x ) { (*this) = (*this) / x; } vec_withgrad_t operator/( const vec_withgrad_t& x ) const { vec_withgrad_t p; for(int i=0; i& x ) { (*this) = (*this) / x; } vec_withgrad_t operator/( const val_withgrad_t& x ) const { vec_withgrad_t p; for(int i=0; i operator/( double x ) const { vec_withgrad_t p; for(int i=0; i dot( const vec_withgrad_t& x) const { val_withgrad_t d; // initializes to 0 for(int i=0; i e = x.v[i]*v[i]; d += e; } return d; } vec_withgrad_t cross( const vec_withgrad_t& x) const { vec_withgrad_t c; c[0] = v[1]*x.v[2] - v[2]*x.v[1]; c[1] = v[2]*x.v[0] - v[0]*x.v[2]; c[2] = v[0]*x.v[1] - v[1]*x.v[0]; return c; } val_withgrad_t norm2(void) const { return dot(*this); } val_withgrad_t mag(void) const { val_withgrad_t l2 = norm2(); return l2.sqrt(); } void extract_value(double* out, int stride = sizeof(double), int ivar0 = 0, int Nvars = NVEC) const { for(int i=ivar0; i static vec_withgrad_t cross( const vec_withgrad_t& a, const vec_withgrad_t& b ) { vec_withgrad_t c; c.v[0] = a.v[1]*b.v[2] - a.v[2]*b.v[1]; c.v[1] = a.v[2]*b.v[0] - a.v[0]*b.v[2]; c.v[2] = a.v[0]*b.v[1] - a.v[1]*b.v[0]; return c; } template static val_withgrad_t cross_norm2( const vec_withgrad_t& a, const vec_withgrad_t& b ) { vec_withgrad_t c = cross(a,b); return c.norm2(); } template static val_withgrad_t cross_mag( const vec_withgrad_t& a, const vec_withgrad_t& b ) { vec_withgrad_t c = cross(a,b); return c.mag(); } mrcal-2.4.1/basic-geometry.h000066400000000000000000000021141456301662300157030ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #pragma once // A 2D point or vector // // The individual elements can be accessed via .x and .y OR the vector can be // accessed as an .xy[] array: // // mrcal_point2_t p = f(); // // Now p.x and p.xy[0] refer to the same value. typedef union { struct { double x,y; }; double xy[2]; } mrcal_point2_t; // A 3D point or vector // // The individual elements can be accessed via .x and .y and .z OR the vector // can be accessed as an .xyz[] array: // // mrcal_point3_t p = f(); // // Now p.x and p.xy[0] refer to the same value. typedef union { struct { double x,y,z; }; double xyz[3]; } mrcal_point3_t; // Unconstrained 6DOF pose containing a Rodrigues rotation and a translation typedef struct { mrcal_point3_t r,t; } mrcal_pose_t; mrcal-2.4.1/cahvore.cc000066400000000000000000000267231456301662300145720ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #include #include #include "autodiff.hh" extern "C" { #include "cahvore.h" } template static bool _project_cahvore_internals( // outputs vec_withgrad_t* pdistorted, // inputs const vec_withgrad_t& p, const val_withgrad_t& alpha, const val_withgrad_t& beta, const val_withgrad_t& r0, const val_withgrad_t& r1, const val_withgrad_t& r2, const val_withgrad_t& e0, const val_withgrad_t& e1, const val_withgrad_t& e2, const double cahvore_linearity) { // Apply a CAHVORE warp to an un-distorted point // Given intrinsic parameters of a CAHVORE model and a set of // camera-coordinate points, return the projected point(s) // This comes from cmod_cahvore_3d_to_2d_general() in // m-jplv/libcmod/cmod_cahvore.c // // The lack of documentation here comes directly from the lack of // documentation in that function. // I parametrize the optical axis such that // - o(alpha=0, beta=0) = (0,0,1) i.e. the optical axis is at the center // if both parameters are 0 // - The gradients are cartesian. I.e. do/dalpha and do/dbeta are both // NOT 0 at (alpha=0,beta=0). This would happen at the poles (gimbal // lock), and that would make my solver unhappy // So o = { s_al*c_be, s_be, c_al*c_be } vec_withgrad_t sca = alpha.sincos(); vec_withgrad_t scb = beta .sincos(); vec_withgrad_t o; o[0] = scb[1]*sca[0]; o[1] = scb[0]; o[2] = scb[1]*sca[1]; // Note: CAHVORE is noncentral: project(p) and project(k*p) do NOT // project to the same point // What is called "omega" in the canonical CAHVOR implementation is // called "zeta" in the canonical CAHVORE implementation. They're the // same thing // cos( angle between p and o ) = inner(p,o) / (norm(o) * norm(p)) = // zeta/norm(p) val_withgrad_t zeta = p.dot(o); // Basic Computations // Calculate initial terms vec_withgrad_t u = o*zeta; vec_withgrad_t ll = p - u; val_withgrad_t l = ll.mag(); // Calculate theta using Newton's Method val_withgrad_t theta = l.atan2(zeta); int inewton; for( inewton = 100; inewton; inewton--) { // Compute terms from the current value of theta vec_withgrad_t scth = theta.sincos(); val_withgrad_t theta2 = theta * theta; val_withgrad_t theta3 = theta * theta2; val_withgrad_t theta4 = theta * theta3; val_withgrad_t upsilon = zeta*scth[1] + l*scth[0] + (scth[1] - 1.0 ) * (e0 + e1*theta2 + e2*theta4) - (theta - scth[0]) * ( e1*theta*2.0 + e2*theta3*4.0); // Update theta val_withgrad_t dtheta = (zeta*scth[0] - l*scth[1] - (theta - scth[0]) * (e0 + e1*theta2 + e2*theta4)) / upsilon; theta -= dtheta; // Check exit criterion from last update if(fabs(dtheta.x) < 1e-8) break; } if(inewton == 0) { fprintf(stderr, "%s(): too many iterations\n", __func__); return false; } // got a theta // Check the value of theta if(theta.x * fabs(cahvore_linearity) > M_PI/2.) { fprintf(stderr, "%s(): theta out of bounds\n", __func__); return false; } // If we aren't close enough to use the small-angle approximation ... if (theta.x > 1e-8) { // ... do more math! val_withgrad_t linth = theta * cahvore_linearity; val_withgrad_t chi; if (cahvore_linearity < -1e-15) chi = linth.sin() / cahvore_linearity; else if (cahvore_linearity > 1e-15) chi = linth.tan() / cahvore_linearity; else chi = theta; val_withgrad_t chi2 = chi * chi; val_withgrad_t chi3 = chi * chi2; val_withgrad_t chi4 = chi * chi3; val_withgrad_t zetap = l / chi; val_withgrad_t mu = r0 + r1*chi2 + r2*chi4; vec_withgrad_t uu = o*zetap; vec_withgrad_t vv = ll * (mu + 1.); *pdistorted = uu + vv; } else *pdistorted = p; return true; } // Not meant to be touched by the end user. Implemented separate from mrcal.c so // that I can get automated gradient propagation with c++ extern "C" __attribute__ ((visibility ("hidden"))) bool project_cahvore_internals( // outputs mrcal_point3_t* __restrict pdistorted, double* __restrict dpdistorted_dintrinsics_nocore, double* __restrict dpdistorted_dp, // inputs const mrcal_point3_t* __restrict p, const double* __restrict intrinsics_nocore, const double cahvore_linearity) { if( dpdistorted_dintrinsics_nocore == NULL && dpdistorted_dp == NULL ) { // No gradients. NGRAD in all the templates is 0 vec_withgrad_t<0,3> pdistortedg; vec_withgrad_t<0,8> ig; ig.init_vars(intrinsics_nocore, 0,8, // ivar0,Nvars -1 // i_gradvec0 ); vec_withgrad_t<0,3> pg; pg.init_vars(p->xyz, 0,3, // ivar0,Nvars -1 // i_gradvec0 ); if(!_project_cahvore_internals(&pdistortedg, pg, ig[0], ig[1], ig[2], ig[3], ig[4], ig[5], ig[6], ig[7], cahvore_linearity)) return false; pdistortedg.extract_value(pdistorted->xyz); return true; } if( dpdistorted_dintrinsics_nocore == NULL && dpdistorted_dp != NULL ) { // 3 variables: p (3 vars) vec_withgrad_t<3,3> pdistortedg; vec_withgrad_t<3,8> ig; ig.init_vars(intrinsics_nocore, 0,8, // ivar0,Nvars -1 // i_gradvec0 ); vec_withgrad_t<3,3> pg; pg.init_vars(p->xyz, 0,3, // ivar0,Nvars 0 // i_gradvec0 ); if(!_project_cahvore_internals(&pdistortedg, pg, ig[0], ig[1], ig[2], ig[3], ig[4], ig[5], ig[6], ig[7], cahvore_linearity)) return false; pdistortedg.extract_value(pdistorted->xyz); pdistortedg.extract_grad (dpdistorted_dp, 0,3, // ivar0,Nvars 0, // i_gradvec0 sizeof(double)*3, sizeof(double), 3 // Nvars ); return true; } if( dpdistorted_dintrinsics_nocore != NULL && dpdistorted_dp == NULL ) { // 8 variables: alpha,beta,R,E (8 vars) vec_withgrad_t<8,3> pdistortedg; vec_withgrad_t<8,8> ig; ig.init_vars(intrinsics_nocore, 0,8, // ivar0,Nvars 0 // i_gradvec0 ); vec_withgrad_t<8,3> pg; pg.init_vars(p->xyz, 0,3, // ivar0,Nvars -1 // i_gradvec0 ); if(!_project_cahvore_internals(&pdistortedg, pg, ig[0], ig[1], ig[2], ig[3], ig[4], ig[5], ig[6], ig[7], cahvore_linearity)) return false; pdistortedg.extract_value(pdistorted->xyz); pdistortedg.extract_grad (dpdistorted_dintrinsics_nocore, 0,8, // i_gradvec0,N_gradout 0, // ivar0 sizeof(double)*8, sizeof(double), 3 // Nvars ); return true; } if( dpdistorted_dintrinsics_nocore != NULL && dpdistorted_dp != NULL ) { // 11 variables: alpha,beta,R,E (8 vars) + p (3 vars) vec_withgrad_t<11,3> pdistortedg; vec_withgrad_t<11,8> ig; ig.init_vars(intrinsics_nocore, 0,8, // ivar0,Nvars 0 // i_gradvec0 ); vec_withgrad_t<11,3> pg; pg.init_vars(p->xyz, 0,3, // ivar0,Nvars 8 // i_gradvec0 ); if(!_project_cahvore_internals(&pdistortedg, pg, ig[0], ig[1], ig[2], ig[3], ig[4], ig[5], ig[6], ig[7], cahvore_linearity)) return false; pdistortedg.extract_value(pdistorted->xyz); pdistortedg.extract_grad (dpdistorted_dintrinsics_nocore, 0,8, // i_gradvec0,N_gradout 0, // ivar0 sizeof(double)*8, sizeof(double), 3 // Nvars ); pdistortedg.extract_grad (dpdistorted_dp, 8,3, // ivar0,Nvars 0, // i_gradvec0 sizeof(double)*3, sizeof(double), 3 // Nvars ); return true; } fprintf(stderr, "Getting here is a bug. Please report\n"); assert(0); } mrcal-2.4.1/cahvore.h000066400000000000000000000016111456301662300144210ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #pragma once #include #include "basic-geometry.h" bool project_cahvore_internals( // outputs mrcal_point3_t* __restrict pdistorted, double* __restrict dpdistorted_dintrinsics_nocore, double* __restrict dpdistorted_dp, // inputs const mrcal_point3_t* __restrict p, const double* __restrict intrinsics_nocore, const double cahvore_linearity); mrcal-2.4.1/cameramodel-parser.re000066400000000000000000000437301456301662300167240ustar00rootroot00000000000000/* -*- c -*- */ // Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // Apparently I need this in MSVC to get constants #define _USE_MATH_DEFINES #include #include #include #include #include #include #include #include #include #include #include #include "mrcal.h" #include "util.h" #define DEBUG 0 // string defined by an explicit length. Instead of being 0-terminated typedef struct { const char* s; int len; } string_t; /*!re2c re2c:define:YYCTYPE = char; // No filling. All the data is available at the start re2c:yyfill:enable = 0; // I use @ tags re2c:flags:tags = 1; SPACE = [ \t\n\r]*; IGNORE = (SPACE | "#" .* "\n")*; // This FLOAT definition will erroneously accept "." and "" as a valid float, // but the strtod converter will then reject it FLOAT = "-"?[0-9]*("."[0-9]*)?([eE][+-]?[0-9]+)?; UNSIGNED_INT = "0"|[1-9][0-9]*; */ /*!stags:re2c format = 'static const char *@@;'; */ static bool string_is(const char* ref, string_t key) { int ref_strlen = strlen(ref); return ref_strlen == key.len && 0 == strncmp(key.s, ref, ref_strlen); } static bool read_string( // output stored here. If NULL, we try to read off // a string, but do not store it; success in the // return value, as usual string_t* out, const char** pYYCURSOR, const char* start_file, const char* what) { const char* YYMARKER; const char* YYCURSOR = *pYYCURSOR; while(true) { const char* s; const char* e; /*!re2c IGNORE "b"? ["'] @s [^\"']* @e ["'] { if(out != NULL) { out->s = s; out->len = (int)(e-s); } *pYYCURSOR = YYCURSOR; return true; } * { break; } */ } if(out != NULL) MSG("Didn't see the %s string at position %ld. Giving up.", what, (long int)(*pYYCURSOR - start_file)); return false; } static bool read_value( const char** pYYCURSOR, const char* start_file) { const char* YYMARKER; const char* YYCURSOR = *pYYCURSOR; const char* s, *e; while(true) { /*!re2c IGNORE @s FLOAT @e { // FLOAT regex erroneously matches empty strings and ".". I // explicitly check for those, and return a failure if( e == s ) return false; if( e == &s[1] && *s == '.') return false; break; } * { return false; } */ } *pYYCURSOR = YYCURSOR; return true; } typedef bool (ingest_generic_consume_ignorable_t)(void* out0, int i, const char** pYYCURSOR, const char* start_file, const char* what); static bool ingest_double_consume_ignorable(void* out0, int i, const char** pYYCURSOR, const char* start_file, const char* what) { const char* YYMARKER; const char* YYCURSOR = *pYYCURSOR; const char* s; const char* e; while(true) { /*!re2c IGNORE @s FLOAT @e IGNORE { break; } * { MSG("Error parsing double-precision value for %s at %ld", what, (long int)(*pYYCURSOR-start_file)); return false; } */ } if(out0 != NULL) { int N = e-s; char tok[N+1]; memcpy(tok, s, N); tok[N] = '\0'; char* endptr = NULL; ((double*)out0)[i] = strtod(tok, &endptr); if( N == 0 || endptr == NULL || endptr != &tok[N] || !isfinite(((double*)out0)[i])) { MSG("Error parsing double-precision value for %s at %ld. String: '%s'", what, (long int)(*pYYCURSOR-start_file), tok); return false; } } *pYYCURSOR = YYCURSOR; return true; } static bool ingest_uint_consume_ignorable(void* out0, int i, const char** pYYCURSOR, const char* start_file, const char* what) { const char* YYMARKER; const char* YYCURSOR = *pYYCURSOR; const char* s; const char* e; while(true) { /*!re2c IGNORE @s UNSIGNED_INT @e IGNORE { break; } * { MSG("Error parsing unsigned integer for %s at %ld", what, (long int)(*pYYCURSOR-start_file)); return false; } */ } if(out0 != NULL) { int N = e-s; char tok[N+1]; memcpy(tok, s, N); tok[N] = '\0'; int si = atoi(tok); if( N == 0 || si < 0 ) { MSG("Error parsing unsigned int for %s at %ld. String: '%s'", what, (long int)(*pYYCURSOR-start_file), tok); return false; } ((unsigned int*)out0)[i] = (unsigned int)si; } *pYYCURSOR = YYCURSOR; return true; } static bool read_list_values_generic( // output stored here. If NULL, we try to // read off the values, but do not store // them; success in the return value, as // usual void* out, ingest_generic_consume_ignorable_t* f, const char** pYYCURSOR, const char* start_file, const char* what, int Nvalues) { const char* YYMARKER; const char* YYCURSOR = *pYYCURSOR; while(true) { /*!re2c IGNORE [\[(] { break; } * { MSG("Didn't see the opening [/( for the %s at position %ld. Giving up.", what, (long int)(YYCURSOR - start_file)); return false; } */ } int i; for(i=0; i 0) { // closed inner ]. Trailing , afterwards is optional. I don't // bother checking for this thoroughly, so I end up erroneously // accepting expressions like [1,2,3][3,4,5]. But that's OK ; } continue; } * { MSG("Error reading a balanced list at %ld (unexpected value)", (long int)(YYCURSOR-start_file)); return false; } */ } MSG("Getting here is a bug"); return false; } // if len>0, the string doesn't need to be 0-terminated. If len<=0, the end of // the buffer IS indicated by a 0 byte mrcal_cameramodel_t* mrcal_read_cameramodel_string(const char *string, int len) { // This is lame. If the end of the buffer is indicated by the buffer length // only, I allocate a new padded buffer, and copy into it. Then this code // looks for a terminated 0 always. I should instead use the re2c logic for // fixed-length buffers (YYLIMIT), but that looks complicated const char* YYCURSOR = NULL; char* malloced_buf = NULL; if(len > 0) { malloced_buf = malloc(len+1); if(malloced_buf == NULL) { MSG("malloc() failed"); return NULL; } memcpy(malloced_buf, string, len); malloced_buf[len] = '\0'; YYCURSOR = malloced_buf; } else YYCURSOR = string; // Set the output structure to invalid values that I can check later mrcal_cameramodel_t cameramodel_core = {.rt_cam_ref[0] = DBL_MAX, .imagersize = {}, .lensmodel.type = MRCAL_LENSMODEL_INVALID }; mrcal_cameramodel_t* cameramodel_full = NULL; bool finished = false; const char* YYMARKER; const char* start_file = YYCURSOR; ///////// leading { while(true) { /*!re2c IGNORE "{" IGNORE { break; } * { MSG("Didn't see leading '{'. Giving up."); goto done; } */ } ///////// key: value while(true) { string_t key = {}; ///////// key: if(!read_string(&key, &YYCURSOR, start_file, "key")) goto done; while(true) { /*!re2c IGNORE ":" { break; } * { MSG("Didn't see expected ':' at %ld. Giving up.", (long int)(YYCURSOR-start_file)); goto done; } */ } #if defined DEBUG && DEBUG MSG("key: '%.*s'", key.len, key.s); #endif if( string_is("lensmodel", key) ) { if(cameramodel_core.lensmodel.type >= 0) { MSG("lensmodel defined more than once"); goto done; } // "lensmodel" has string values string_t lensmodel; if(!read_string(&lensmodel, &YYCURSOR, start_file, "lensmodel")) goto done; char lensmodel_string[lensmodel.len+1]; memcpy(lensmodel_string, lensmodel.s, lensmodel.len); lensmodel_string[lensmodel.len] = '\0'; if( !mrcal_lensmodel_from_name(&cameramodel_core.lensmodel, lensmodel_string) ) { MSG("Could not parse lensmodel '%s'", lensmodel_string); goto done; } } else if(string_is("intrinsics", key)) { if( cameramodel_full != NULL ) { MSG("intrinsics defined more than once"); goto done; } if(cameramodel_core.lensmodel.type < 0) { MSG("Saw 'intrinsics' key, before a 'lensmodel' key. Make sure that a 'lensmodel' key exists, and that it appears in the file before the 'intrinsics'"); goto done; } int Nparams = mrcal_lensmodel_num_params(&cameramodel_core.lensmodel); cameramodel_full = malloc(sizeof(mrcal_cameramodel_t) + Nparams*sizeof(double)); if(NULL == cameramodel_full) { MSG("malloc() failed"); goto done; } if( !read_list_values_generic(cameramodel_full->intrinsics, ingest_double_consume_ignorable, &YYCURSOR, start_file, "intrinsics", Nparams) ) goto done; } else if(string_is("extrinsics", key)) { if(cameramodel_core.rt_cam_ref[0] != DBL_MAX) { MSG("extrinsics defined more than once"); goto done; } if( !read_list_values_generic(cameramodel_core.rt_cam_ref, ingest_double_consume_ignorable, &YYCURSOR, start_file, "extrinsics", 6) ) goto done; } else if(string_is("imagersize", key)) { if(cameramodel_core.imagersize[0] > 0) { MSG("imagersize defined more than once"); goto done; } if( !read_list_values_generic(cameramodel_core.imagersize, ingest_uint_consume_ignorable, &YYCURSOR, start_file, "imagersize", 2) ) goto done; } else { // Some unknown key. Read off the data and continue // try to read a string... if(!read_value(&YYCURSOR, start_file) && !read_string(NULL, &YYCURSOR, start_file, "unknown") && !read_balanced_list(&YYCURSOR, start_file)) { MSG("Error parsing value for key '%.*s' at %ld", key.len, key.s, (long int)(YYCURSOR-start_file)); goto done; } } // Done with key:value. Look for optional trailing , and/or a }. We must // see at least some of those things. k:v k:v without a , in-between is // illegal bool closing_brace = false; const char* f; while(true) { /*!re2c IGNORE ("," | "}" | ("," IGNORE "}")) @f { if(f[-1] == '}') closing_brace = true; break; } * { MSG("Didn't see trailing , at %ld", (long int)(YYCURSOR-start_file)); goto done; } */ } if(closing_brace) { while(true) { /*!re2c IGNORE [\x00] { finished = true; goto done; } * { MSG("Garbage after trailing } at %ld. Giving up", (long int)(f-1 - start_file)); goto done; } */ } } } done: if(malloced_buf) free(malloced_buf); if(!finished) { free(cameramodel_full); return NULL; } // Done parsing everything! Validate and finalize if(!(cameramodel_core.lensmodel.type >= 0 && cameramodel_full != NULL && cameramodel_core.rt_cam_ref[0] != DBL_MAX && cameramodel_core.imagersize[0] > 0)) { MSG("Incomplete cameramodel. Need keys: lensmodel, intrinsics, extrinsics, imagersize"); free(cameramodel_full); return NULL; } memcpy(cameramodel_full, &cameramodel_core, sizeof(cameramodel_core)); return cameramodel_full; } mrcal_cameramodel_t* mrcal_read_cameramodel_file(const char* filename) { int fd = -1; char* string = NULL; mrcal_cameramodel_t* result = NULL; fd = open(filename, O_RDONLY); if(fd < 0) { MSG("Couldn't open(\"%s\")", filename); goto done; } struct stat st; if(0 != fstat(fd, &st)) { MSG("Couldn't stat(\"%s\")", filename); goto done; } // I mmap twice: // // 1. anonymous mapping slightly larger than the file size. These are all 0 // 2. mmap of the file. The trailing 0 are preserved, and the parser can use // the trailing 0 to indicate the end of file // // This is only needed if the file size is exactly a multiple of the page // size. If it isn't, then the remains of the last page are 0 anyway. string = mmap(NULL, st.st_size + 1, // one extra byte PROT_READ, MAP_ANONYMOUS | MAP_PRIVATE, -1, 0); if(string == MAP_FAILED) { MSG("Couldn't mmap(anonymous) right before mmap(\"%s\")", filename); goto done; } string = mmap(string, st.st_size, PROT_READ, MAP_FIXED | MAP_PRIVATE, fd, 0); if(string == MAP_FAILED) { MSG("Couldn't mmap(\"%s\")", filename); goto done; } result = mrcal_read_cameramodel_string(string, // 0 indicates EOF, not the file size 0); done: if(string != NULL && string != MAP_FAILED) munmap(string, st.st_size+1); if(fd >= 0) close(fd); return result; } void mrcal_free_cameramodel(mrcal_cameramodel_t** cameramodel) { free(*cameramodel); *cameramodel = NULL; } mrcal-2.4.1/choose_mrbuild.mk000066400000000000000000000014641456301662300161560ustar00rootroot00000000000000# Use the local mrbuild or the system mrbuild or tell the user how to download # it ifneq (,$(wildcard mrbuild/)) MRBUILD_MK=mrbuild MRBUILD_BIN=mrbuild/bin else ifneq (,$(wildcard /usr/include/mrbuild/Makefile.common.header)) MRBUILD_MK=/usr/include/mrbuild MRBUILD_BIN=/usr/bin else V := 1.8 SHA512 := 0d35dd2988a7ff74487d8cf9a259f208e4524d95ea392f063e31d05579ee7336a6ee4377b9a5e948694afbe46108da89e6a9afc0309a0b05851382a1f2fd038c URL := https://github.com/dkogan/mrbuild/archive/refs/tags/v$V.tar.gz TARGZ := mrbuild-$V.tar.gz cmd := wget -O $(TARGZ) ${URL} && sha512sum --quiet --strict -c <(echo $(SHA512) $(TARGZ)) && tar xvfz $(TARGZ) && ln -fs mrbuild-$V mrbuild $(error mrbuild not found. Either 'apt install mrbuild', or if not possible, get it locally like this: '${cmd}') endif mrcal-2.4.1/corresponding_icam_extrinsics.docstring000066400000000000000000000061511456301662300226630ustar00rootroot00000000000000Return the icam_extrinsics corresponding to a given icam_intrinsics SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() icam_intrinsics = m.icam_intrinsics() icam_extrinsics = \ mrcal.corresponding_icam_extrinsics(icam_intrinsics, **optimization_inputs) if icam_extrinsics >= 0: extrinsics_rt_fromref_at_calibration_time = \ optimization_inputs['extrinsics_rt_fromref'][icam_extrinsics] When calibrating cameras, each observations is associated with some camera intrinsics (lens parameters) and some camera extrinsics (geometry). Those two chunks of data live in different parts of the optimization vector, and are indexed independently. If we have stationary cameras, then each set of camera intrinsics is associated with exactly one set of camera extrinsics, and we can use this function to query this correspondence. If we have moving cameras, then a single physical camera would have one set of intrinsics but many different extrinsics, and this function call will throw an exception. Furthermore, it is possible that a camera's pose is used to define the reference coordinate system of the optimization. In this case this camera has no explicit extrinsics (they are an identity transfomration, by definition), and we return -1, successfully. In order to determine the camera mapping, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - icam_intrinsics: an integer indicating which camera we're asking about - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - Ncameras_intrinsics Ncameras_extrinsics - Nobservations_board - Nobservations_point optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details - indices_frame_camintrinsics_camextrinsics: array of dims (Nobservations_board, 3). For each observation these are an (iframe,icam_intrinsics,icam_extrinsics) tuple. icam_extrinsics == -1 means this observation came from a camera in the reference coordinate system. iframe indexes the "frames_rt_toref" array, icam_intrinsics indexes the "intrinsics_data" array, icam_extrinsics indexes the "extrinsics_rt_fromref" array All of the indices are guaranteed to be monotonic. This array contains 32-bit integers. RETURNED VALUE The integer reporting the index of the camera extrinsics in the optimization vector. If this camera is at the reference of the coordinate system, return -1 mrcal-2.4.1/doc/000077500000000000000000000000001456301662300133675ustar00rootroot00000000000000mrcal-2.4.1/doc/.dir-locals.el000066400000000000000000000022551456301662300160240ustar00rootroot00000000000000;;; Directory Local Variables ;; Useful to add links to a mrcal function or tool. These make the appropriate ;; text and an appropriate link ((org-mode . ((eval . (progn (defun insert-function (f) (interactive (list (read-string "Function: "))) (insert (format "[[file:mrcal-python-api-reference.html#-%1$s][=mrcal.%1$s()=]]" f))) (defun insert-tool (f) (interactive (list (read-string "Tool: "))) (insert (format "[[file:%1$s.html][=%1$s=]]" f))) (defun insert-file (f) (interactive (list (read-string "File: "))) (insert (format "[[https://www.github.com/dkogan/mrcal/blob/master/%1$s][=%1$s=]]" f))) (local-set-key (kbd "") 'insert-function) (local-set-key (kbd "") 'insert-tool) (local-set-key (kbd "") 'insert-file) ))))) mrcal-2.4.1/doc/c-api.org000066400000000000000000000542631456301662300151030ustar00rootroot00000000000000#+TITLE: mrcal C API #+OPTIONS: toc:t Internally, the [[file:python-api.org][Python functions]] use the mrcal C API. Only core functionality is available in the C API (the Python API can do some stuff that the C API cannot), but with time more and more stuff will be transitioned to a C-internal representation. Today, end-to-end dense stereo processing in C is possible. The C API consists of several headers: - [[https://www.github.com/dkogan/mrcal/blob/master/basic-geometry.h][=basic-geometry.h=]]: /very/ simple geometry structures - [[https://www.github.com/dkogan/mrcal/blob/master/poseutils.h][=poseutils.h=]]: pose and geometry functions - [[https://www.github.com/dkogan/mrcal/blob/master/triangulation.h][=triangulation.h=]]: triangulation routines - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal.h=]]: lens models, projections, optimization Most usages would simply =#include =, and this would include all the headers. This is a C (not C++) library, so [[https://en.wikipedia.org/wiki/X_Macro][X macros]] are used in several places for templating. mrcal is a research project, so the capabilities and focus are still evolving. Thus, the interfaces, /especially/ those in the C API are not yet stable. I do try to maintain stability, but this is not fully possible, especially in the higher-level APIs (=mrcal_optimize()= and =mrcal_optimizer_callback()=). For now, assume that each major release breaks both the API and the ABI. The migration notes for each release are described in the [[file:versions.org][relevant release notes]]. If you use the C APIs, shoot me an email to let me know, and I'll keep you in mind when making API updates. The best documentation for the C interfaces is the comments in the headers. I don't want to write up anything complete and detailed until I'm sure the interfaces are stable. The available functions are broken down into categories, and described in a bit more detail here. * Geometry structures We have 3 structures in [[https://www.github.com/dkogan/mrcal/blob/master/basic-geometry.h][=basic-geometry.h=]]: - =mrcal_point2_t=: a vector containing 2 double-precision floating-point values. The elements can be accessed individually as =.x= and =.y= or as an array =.xy[]= - =mrcal_point3_t=: exactly like =mrcal_point2_t=, but 3-dimensional. A vector containing 3 double-precision floating-point values. The elements can be accessed individually as =.x= and =.y= and =.z= or as an array =.xyz[]= - =mrcal_pose_t=: an unconstrained [[file:conventions.org::#pose-representation][6-DOF pose]]. Contains two sub-structures: - =mrcal_point3_t r=: a [[https://en.wikipedia.org/wiki/Axis%E2%80%93angle_representation#Rotation_vector][Rodrigues rotation]] - =mrcal_point3_t t=: a translation * Geometry functions A number of utility functions are defined in [[https://www.github.com/dkogan/mrcal/blob/master/poseutils.h][=poseutils.h=]]. Each routine has two forms: - A =mrcal_..._full()= function that supports a non-contiguous memory layout for each input and output - A convenience =mrcal_...()= macro that wraps =mrcal_..._full()=, and expects contiguous data. This has many fewer arguments, and is easier to call Each data argument (input or output) has several items in the argument list: - =double* xxx=: a pointer to the first element in the array - =int xxx_stride0=, =int xxx_stride1=, ...: the strides, one per dimension The strides are given in bytes, and work as expected. For a (for instance) 3-dimensional =xxx=, the element at =xxx[i,j,k]= would be accessible as #+begin_src c *(double*) &((char*)xxx)[ i*xxx_stride0 + j*xxx_stride1 + k*xxx_stride2 ] #+end_src There are convenience macros in [[https://www.github.com/dkogan/mrcal/blob/master/strides.h][=strides.h=]], so the above can be equivalently expressed as #+begin_src c P3(xxx, i,j,k) #+end_src These all have direct Python bindings. For instance the Python [[file:mrcal-python-api-reference.html#-rt_from_Rt][=mrcal.rt_from_Rt()=]] function wraps =mrcal_rt_from_Rt()= C function. The [[https://www.github.com/dkogan/mrcal/blob/master/poseutils.h][=poseutils.h=]] header serves as the listing of available functions. * Lens models The lens model structures are defined here: - =mrcal_lensmodel_type_t=: an enum decribing the lens model /type/. No [[file:lensmodels.org::#representation][configuration]] is stored here. - =mrcal_lensmodel_t=: a lens model type /and/ the [[file:lensmodels.org::#representation][configuration]] parameters. The configuration lives in a =union= supporting all the known lens models - =mrcal_lensmodel_metadata_t=: some [[file:lensmodels.org::#representation][metadata that decribes a model type]]. These are inherent properties of a particular model type; answers questions like: Can this model project behind the camera? Does it have an [[file:lensmodels.org::#core][intrinsics core]]? Does it have gradients implemented? The Python API describes a lens model with a [[file:lensmodels.org::#representation][string that contains the model type and the configuration]], while the C API stores the same information in a =mrcal_lensmodel_t=. * Camera models :PROPERTIES: :CUSTOM_ID: cameramodel-in-c :END: We can also represent a full camera model in C. This is a lens model with a pose and imager dimension: the full set of things in a [[file:cameramodels.org][=.cameramodel= file]]. The definitions appear in [[https://www.github.com/dkogan/mrcal/blob/master/mrcal-types.h][=mrcal-types.h=]]: #+begin_src c typedef struct { double rt_cam_ref[6]; unsigned int imagersize[2]; mrcal_lensmodel_t lensmodel; double intrinsics[0]; } mrcal_cameramodel_t; typedef union { mrcal_cameramodel_t m; struct { double rt_cam_ref[6]; unsigned int imagersize[2]; mrcal_lensmodel_t lensmodel; double intrinsics[4]; }; } mrcal_cameramodel_LENSMODEL_LATLON_t; ... #+end_src Note that =mrcal_cameramodel_t.intrinsics= has size 0 because the size of this array depends on the specific lens model being used, and is unknown at compile time. So it is an error to define this on the stack. *Do not do this*: #+begin_src c void f(void) { mrcal_cameramodel_t model; // ERROR } #+end_src If you need to define a known-at-compile-time model on the stack you can use the [[https://github.com/dkogan/mrcal/blob/88e4c1df1c8cf535516719c5d4257ef49c9df1da/mrcal-types.h#L338][lensmodel-specific cameramodel types]]: #+begin_src c void f(void) { mrcal_cameramodel_LENSMODEL_OPENCV8_t model; // OK } #+end_src This only exists for models that have a constant number of parameters; notably there is no =mrcal_cameramodel_LENSMODEL_SPLINED_STEREOGRAPHIC_t=. When reading a model from disk, mrcal dynamically allocates the right amount of memory, and returns a =mrcal_cameramodel_t*=. * Projections The fundamental functions for projection and unprojection are defined here. =mrcal_project()= is the main routine that implements the "forward" direction, and is available for every camera model. This function can return gradients in respect to the coordinates of the point being projected and/or in respect to the intrinsics vector. =mrcal_unproject()= is the reverse direction, and is implemented as a numerical optimization to reverse the projection operation. Naturally, this is much slower than =mrcal_project()=. Since =mrcal_unproject()= is implemented with a nonlinear optimization, it has no gradient reporting. The Python [[file:mrcal-python-api-reference.html#-unproject][=mrcal.unproject()=]] routine is higher-level, and it /does/ report gradients. The gradients of the forward =mrcal_project()= operation are used in this nonlinear optimization, so models that have no projection gradients defined do not support =mrcal_unproject()=. The Python [[file:mrcal-python-api-reference.html#-unproject][=mrcal.unproject()=]] routine still makes this work, using numerical differences for the projection gradients. Simple, special-case lens models have their own projection and unprojection functions defined: #+begin_src c void mrcal_project_pinhole(...); void mrcal_unproject_pinhole(...); void mrcal_project_stereographic(...); void mrcal_unproject_stereographic(...); void mrcal_project_lonlat(...); void mrcal_unproject_lonlat(...); void mrcal_project_latlon(...); void mrcal_unproject_latlon(...); #+end_src These functions do the same thing as the general =mrcal_project()= and =mrcal_unproject()= functions, but work much faster. * Layout of the measurement and state vectors The [[file:formulation.org][optimization routine]] tries to minimize the 2-norm of the measurement vector $\vec x$ by moving around the state vector $\vec b$. We select which parts of the optimization problem we're solving by setting bits in the =mrcal_problem_selections_t= structure. This defines - Which elements of the optimization vector are locked-down, and which are given to the optimizer to adjust - Whether we apply [[file:index.org::#Regularization][regularization]] to stabilize the solution - Whether the chessboard should be assumed flat, or if we should optimize [[file:formulation.org::#board-deformation][deformation]] factors Thus the state vector may contain any of - The lens parameters - The geometry of the cameras - The geometry of the observed chessboards and discrete points - The [[file:formulation.org::#board-deformation][chessboard shape]] The measurement vector may contain - The errors in observations of the chessboards - The errors in observations of discrete points - The penalties in the solved point positions - The [[file:formulation.org::#Regularization][regularization]] terms Given =mrcal_problem_selections_t= and a vector $\vec b$ or $\vec x$, it is useful to know where specific quantities lie inside those vectors. Here we have 4 sets of functions to answer such questions: - =int mrcal_state_index_THING()=: Returns the index in the state vector $\vec b$ where the contiguous block of values describing the THING begins. THING is any of - intrinsics - extrinsics - frames - points - calobject_warp If we're not optimizing the THING, return <0 - =int mrcal_num_states_THING()=: Returns the number of values in the contiguous block in the state vector $\vec b$ that describe the given THING. THING is any of - intrinsics - extrinsics - frames - points - calobject_warp - =int mrcal_measurement_index_THING()=: Returns the index in the measurement vector $\vec x$ where the contiguous block of values describing the THING begins. THING is any of - boards - points - regularization - =int mrcal_num_measurements_THING()=: Returns the number of values in the contiguous block in the measurement vector $\vec x$ that describe the given THING. THING is any of - boards - points - regularization * State packing The optimization routine works in the [[file:formulation.org::#state-packing][space of scaled parameters]], and several functions are available to pack/unpack the state vector $\vec b$: #+begin_src c void mrcal_pack_solver_state_vector(...); void mrcal_unpack_solver_state_vector(...); #+end_src * Optimization The mrcal [[file:formulation.org][optimization routines]] are defined in [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal.h=]]. There are two primary functions, each accessing a /lot/ of functionality, and taking /many/ arguments. At this time, the prototypes will likely change in each release of mrcal, so try not to rely on these being stable. - =mrcal_optimize()= is the entry point to the optimization routine. This function ingests the state, runs the optimization, and returns the optimal state in the same variables. The optimization routine tries out different values of the state vector by calling an optimization callback function to evaluate each one. - =mrcal_optimizer_callback()= provides access to the optimization callback function standalone, /without/ being wrapped into the optimization loop ** Helper structures This is correct as of mrcal 2.1. It may change in future releases. We define some structures to organize the input to these functions. Each observation has a =mrcal_camera_index_t= to identify the observing camera: #+begin_src c // Used to specify which camera is making an observation. The "intrinsics" index // is used to identify a specific camera, while the "extrinsics" index is used // to locate a camera in space. If I have a camera that is moving over time, the // intrinsics index will remain the same, while the extrinsics index will change typedef struct { // indexes the intrinsics array int intrinsics; // indexes the extrinsics array. -1 means "at coordinate system reference" int extrinsics; } mrcal_camera_index_t; #+end_src When solving a vanilla calibration problem, we have a set of stationary cameras observing a moving scene. By convention, in such a problem we set the reference coordinate system to camera 0, so that camera has no extrinsics. So in a vanilla calibration problem =mrcal_camera_index_t.intrinsics= will be in $[0, N_\mathrm{cameras})$ and =mrcal_camera_index_t.extrinsics= will always be =mrcal_camera_index_t.intrinsics - 1=. When solving a vanilla structure-from-motion problem, we have a set of moving cameras observing a stationary scene. Here =mrcal_camera_index_t.intrinsics= would be in $[0, N_\mathrm{cameras})$ and =mrcal_camera_index_t.extrinsics= would be specify the camera pose, unrelated to =mrcal_camera_index_t.intrinsics=. These are the limiting cases; anything in-between is allowed. A board observation is defined by a =mrcal_observation_board_t=: #+begin_src c // An observation of a calibration board. Each "observation" is ONE camera // observing a board typedef struct { // which camera is making this observation mrcal_camera_index_t icam; // indexes the "frames" array to select the pose of the calibration object // being observed int iframe; } mrcal_observation_board_t; #+end_src And an observation of a discrete point is defined by a =mrcal_observation_point_t=: #+begin_src c // An observation of a discrete point. Each "observation" is ONE camera // observing a single point in space typedef struct { // which camera is making this observation mrcal_camera_index_t icam; // indexes the "points" array to select the position of the point being // observed int i_point; // Observed pixel coordinates. This works just like elements of // observations_board_pool: // // .x, .y are the pixel observations // .z is the weight of the observation. Most of the weights are expected to // be 1.0. Less precise observations have lower weights. // .z<0 indicates that this is an outlier. This is respected on // input // // Unlike observations_board_pool, outlier rejection is NOT YET IMPLEMENTED // for points, so outlier points will NOT be found and reported on output in // .z<0 mrcal_point3_t px; } mrcal_observation_point_t; #+end_src Note that the details of the handling of discrete points may change in the future. We have =mrcal_problem_constants_t= to define some details of the optimization problem. These are similar to =mrcal_problem_selections_t=, but consist of numerical values, rather than just bits. Currently this structure contains valid ranges for interpretation of discrete points. These may change in the future. #+begin_src c // Constants used in a mrcal optimization. This is similar to // mrcal_problem_selections_t, but contains numerical values rather than just // bits typedef struct { // The minimum distance of an observed discrete point from its observing // camera. Any observation of a point below this range will be penalized to // encourage the optimizer to move the point further away from the camera double point_min_range; // The maximum distance of an observed discrete point from its observing // camera. Any observation of a point abive this range will be penalized to // encourage the optimizer to move the point closer to the camera double point_max_range; } mrcal_problem_constants_t; #+end_src The optimization function returns most of its output in the same memory as its input variables. A few metrics that don't belong there are returned in a separate =mrcal_stats_t= structure: #+begin_src c // This structure is returned by the optimizer, and contains some statistics // about the optimization typedef struct { // generated by an X-macro /* The RMS error of the optimized fit at the optimum. Generally the residual */ /* vector x contains error values for each element of q, so N observed pixels */ /* produce 2N measurements: len(x) = 2*N. And the RMS error is */ /* sqrt( norm2(x) / N ) */ double rms_reproj_error__pixels; /* How many pixel observations were thrown out as outliers. Each pixel */ /* observation produces two measurements. Note that this INCLUDES any */ /* outliers that were passed-in at the start */ int Noutliers; } mrcal_stats_t; #+end_src This contains some statistics describing the discovered optimal solution. * Camera model reading/writing :PROPERTIES: :CUSTOM_ID: cameramodel-io-in-c :END: A simple interface for reading/writing [[file:cameramodels.org][=.cameramodel=]] data from C is available: #+begin_src c // if len>0, the string doesn't need to be 0-terminated. If len<=0, the end of // the buffer IS indicated by a '\0' byte mrcal_cameramodel_t* mrcal_read_cameramodel_string(const char* string, int len); mrcal_cameramodel_t* mrcal_read_cameramodel_file (const char* filename); void mrcal_free_cameramodel(mrcal_cameramodel_t** cameramodel); bool mrcal_write_cameramodel_file(const char* filename, const mrcal_cameramodel_t* cameramodel); #+end_src This reads and write the [[#cameramodel-in-c][=mrcal_cameramodel_t= structures]]. Only the =.cameramodel= file format is supported by these C functions. The Python API supports more formats. * Images mrcal defines simple image types in [[https://www.github.com/dkogan/mrcal/blob/master/mrcal-image.h][=mrcal-image.h=]]: - =mrcal_image_int8_t= - =mrcal_image_uint8_t= - =mrcal_image_int16_t= - =mrcal_image_uint16_t= - =mrcal_image_int32_t= - =mrcal_image_uint32_t= - =mrcal_image_int64_t= - =mrcal_image_uint64_t= - =mrcal_image_float_t= - =mrcal_image_double_t= - =mrcal_image_bgr_t= These are the basic not-necessarily-contiguous arrays. The =bgr= type is used for color images: #+begin_src c typedef struct { uint8_t bgr[3]; } mrcal_bgr_t; #+end_src Simple accessor and manipulation functions are available for each of these types (replacing each =T= below): #+begin_src c T* mrcal_image_T_at(mrcal_image_T_t* image, int x, int y); const T* mrcal_image_T_at_const(const mrcal_image_T_t* image, int x, int y); mrcal_image_T_t mrcal_image_T_crop(mrcal_image_T_t* image, int x0, int y0, int w, int h); #+end_src And for =uint8_t=, =uint16_t= and =mrcal_bgr_t= we can also read and write image files: #+begin_src c bool mrcal_image_T_save (const char* filename, const mrcal_image_T_t* image); bool mrcal_image_T_load( mrcal_image_T_t* image, const char* filename); #+end_src These use the [[https://freeimage.sourceforge.io/][freeimage library]]. These functions aren't interesting, or better than any other functions you may have already. The declarations are in [[https://www.github.com/dkogan/mrcal/blob/master/mrcal-image.h][=mrcal-image.h=]], and the documentation lives there. * Heat maps mrcal can produce a colored visualization of any of the image types defined above: #+begin_src c bool mrcal_apply_color_map_T( mrcal_image_bgr_t* out, const mrcal_image_T_t* in, /* If true, I set in_min/in_max from the */ /* min/max of the input data */ const bool auto_min, const bool auto_max, /* If true, I implement gnuplot's default 7,5,15 mapping. */ /* This is a reasonable default choice. */ /* function_red/green/blue are ignored if true */ const bool auto_function, /* min/max input values to use if not */ /* auto_min/auto_max */ T in_min, /* will map to 0 */ T in_max, /* will map to 255 */ /* The color mappings to use. If !auto_function */ int function_red, int function_green, int function_blue); #+end_src * Dense stereo :PROPERTIES: :CUSTOM_ID: dense-stereo-in-c :END: A number of dense stereo routines are available. These make it possible to implement a full mrcal dense stereo pipeline in C; an [[https://github.com/dkogan/mrcal/blob/master/doc/examples/dense-stereo-demo/dense-stereo-demo.cc][example is provided]]. The available functions are declared in [[https://www.github.com/dkogan/mrcal/blob/master/stereo.h][=stereo.h=]]: - =mrcal_rectified_resolution()= computes the resolution of the rectified system from the resolution of the input. Usually =mrcal_rectified_system()= does this internally, and there's no reason to call it directly. The Python wrapper is [[file:mrcal-python-api-reference.html#-rectified_resolution][=mrcal.rectified_resolution()=]], and further documentation is in its docstring - =mrcal_rectified_system()= computes the geometry of the rectified system. The Python wrapper is [[file:mrcal-python-api-reference.html#-rectified_system][=mrcal.rectified_system()=]], and further documentation is in its docstring. - =mrcal_rectification_maps()= computes the image transformation maps used to compute the rectified images. To apply the maps, and actually remap the images, [[https://docs.opencv.org/4.6.0/da/d54/group__imgproc__transform.html#gab75ef31ce5cdfb5c44b6da5f3b908ea4][the OpenCV =cv::remap()= function]] can be used. The Python wrapper is [[file:mrcal-python-api-reference.html#-rectification_maps][=mrcal.rectification_maps()=]], and further documentation is in its docstring - =mrcal_stereo_range_sparse()=, =mrcal_stereo_range_dense()= compute ranges from disparities. The former function converts a set of discrete disparity values, while the latter function processes a whole disparity image * Triangulation A number of triangulation routines are available in [[https://www.github.com/dkogan/mrcal/blob/master/triangulation.h][=triangulation.h=]]. These estimate the position of the 3D point that produced a given pair of observations. mrcal-2.4.1/doc/cameramodels.org000066400000000000000000000164711456301662300165450ustar00rootroot00000000000000#+TITLE: Camera model representation in memory and on disk * Python interface Interfacing with camera models is done in Python with the [[file:mrcal-python-api-reference.html#cameramodel][=mrcal.cameramodel=]] class. This describes /one/ camera; a calibrated set of cameras is represented by multiple objects. Each object always contains - The =intrinsics=: lens parameters describing one of the [[file:lensmodels.org][lens models]] - The =extrinsics=: a pose of the camera in space. This pose is represented as a transformation between [[file:formulation.org::#world-geometry][some common /reference/ coordinate system]] and the camera coordinate system. The specific meaning of the reference coordinate system is arbitrary, but all the cameras in a calibrated set must be defined in respect to the one common reference. Each camera model object /may/ also contain: - The =optimization_inputs=: all the data used to compute the model initially. Used for the [[file:uncertainty.org][uncertainty computations]] and any after-the-fact analysis. - The =valid_intrinsics_region=: a contour in the imager where the projection behavior is "reliable". This is usually derived from the uncertainty plot, and used as a shorthand. It isn't as informative as the uncertainty plot, but such a valid-intrinsics contour is often convenient to have and to visualize. * C interface The [[file:c-api.org::#cameramodel-io-in-c][C API]] uses the [[https://github.com/dkogan/mrcal/blob/88e4c1df1c8cf535516719c5d4257ef49c9df1da/mrcal-types.h#L326][=mrcal_cameramodel_t= structure]] to represent a model. This contains just the bare minimum: - intrinsics (=mrcal_lensmodel_t lensmodel=, =double intrinsics[0]=) - extrinsics (=double rt_cam_ref[6]=) - imager size (=unsigned int imagersize[2]=) Note that the intrinsics data has size 0 because the size of this array depends on the specific lens model being used, and is unknown at compile time. So it is an error to define this on the stack. *Do not do this*: #+begin_src c void f(void) { mrcal_cameramodel_t model; // ERROR } #+end_src If you need to define a known-at-compile-time model on the stack you can use the [[https://github.com/dkogan/mrcal/blob/88e4c1df1c8cf535516719c5d4257ef49c9df1da/mrcal-types.h#L338][lensmodel-specific cameramodel types]]: #+begin_src c void f(void) { mrcal_cameramodel_LENSMODEL_OPENCV8_t model; // OK } #+end_src This only exists for models that have a constant number of parameters; notably there is no =mrcal_cameramodel_LENSMODEL_SPLINED_STEREOGRAPHIC_t=. When reading a model from disk, mrcal dynamically allocates the right amount of memory, and returns a =mrcal_cameramodel_t*=. The [[file:c-api.org::#cameramodel-io-in-c][C API]] has a simple interface for reading/writing =.cameramodel= data: #+begin_src c mrcal_cameramodel_t* mrcal_read_cameramodel_string(const char* string, int len); mrcal_cameramodel_t* mrcal_read_cameramodel_file (const char* filename); void mrcal_free_cameramodel(mrcal_cameramodel_t** cameramodel); bool mrcal_write_cameramodel_file(const char* filename, const mrcal_cameramodel_t* cameramodel); #+end_src * File formats :PROPERTIES: :CUSTOM_ID: cameramodel-file-formats :END: Several different file formats are supported: - =.cameramodel=: the mrcal-native format, consisting of a plain text representation of a Python =dict=. It supports /all/ the models, and is the /only/ format supported by the [[file:c-api.org::#cameramodel-io-in-c][C API]], and is the only format that contains the =optimization_inputs= and thus can be used for the [[file:uncertainty.org][uncertainty computations]]. - =.cahvor=: the legacy format available for compatibility with existing JPL tools. If you don't need to interoperate with tools that require this format, there's little reason to use it. - [[https://github.com/ethz-asl/kalibr][kalibr]] =.yaml=: the [[https://github.com/ethz-asl/kalibr/wiki/Yaml-formats][format used by the kalibr toolkit]]. Unlike =.cameramodel= files where one camera is described by one file, the =.yaml= files used by kalibr are intended to describe multiple cameras. Thus only partial support is available: we can convert to/from this format using the [[file:mrcal-to-kalibr.html][=mrcal-to-kalibr=]] and [[file:mrcal-from-kalibr.html][=mrcal-from-kalibr=]] tools respectively. At this time the set of models supported by both [[https://github.com/ethz-asl/kalibr][kalibr]] and mrcal contains [[file:lensmodels.org::#lensmodel-pinhole][=LENSMODEL_PINHOLE=]] and [[file:lensmodels.org::#lensmodel-opencv][=LENSMODEL_OPENCV4=]] only. - OpenCV/ROS =.yaml=: the [[https://wiki.ros.org/camera_calibration_parsers][format used by ROS and OpenCV]]. This supports [[file:lensmodels.org::#lensmodel-opencv][=LENSMODEL_OPENCV5=]] and [[file:lensmodels.org::#lensmodel-opencv][=LENSMODEL_OPENCV8=]]. This format can describe a stereo pair, but can /not/ describe an arbitrary set of N cameras. The reference coordinate system is at the left-rectified camera. The [[file:mrcal-python-api-reference.html#cameramodel][=mrcal.cameramodel=]] class will intelligently pick the correct file format based on the data (if reading) and the filename (if writing). The [[file:mrcal-to-cahvor.html][=mrcal-to-cahvor=]], [[file:mrcal-from-cahvor.html][=mrcal-from-cahvor=]], [[file:mrcal-to-kalibr.html][=mrcal-to-kalibr=]], [[file:mrcal-from-kalibr.html][=mrcal-from-kalibr=]] and [[file:mrcal-from-ros.html][=mrcal-from-ros=]] can convert between the different file formats. There's no =mrcal-to-ros= at this time because the behavior of such a tool isn't well-defined. Talk to me if this would be useful to you, to clarify what it should do, exactly. * Sample usages See the [[file:mrcal-python-api-reference.html#cameramodel][API documentation]] for usage details. ** Grafting two models A trivial example to - read two models from disk - recombine into a joint model that uses the lens parameters from one model with geometry from the other - write to disk #+begin_src python import mrcal model_for_intrinsics = mrcal.cameramodel('model0.cameramodel') model_for_extrinsics = mrcal.cameramodel('model1.cameramodel') model_joint = mrcal.cameramodel( model_for_intrinsics ) extrinsics = model_for_extrinsics.extrinsics_rt_fromref() model_joint.extrinsics_rt_fromref(extrinsics) model_joint.write('model-joint.cameramodel') #+end_src This is the basic operation of the [[file:mrcal-graft-models.html][=mrcal-graft-models= tool]]. ** Re-optimizing a model To re-optimize a model from its =optimization_inputs=: #+begin_src python import mrcal m = mrcal.cameramodel('camera.cameramodel') optimization_inputs = m.optimization_inputs() mrcal.optimize(**optimization_inputs) model_reoptimized = \ mrcal.cameramodel( optimization_inputs = m.optimization_inputs(), icam_intrinsics = m.icam_intrinsics() ) #+end_src Here we asked mrcal to re-optimize the data used to compute the given model originally. We didn't make any changes to the inputs, and we should already have an optimal solution, so this re-optimized model would be the same as the initial one. But we could tweak optimization problem before reoptimizing, and this would give us an nice way to observe the effects of those changes. We can add input noise or change the lens model or [[file:formulation.org::#Regularization][regularization terms]] or anything else. mrcal-2.4.1/doc/commandline-tools.org000066400000000000000000000107121456301662300175250ustar00rootroot00000000000000#+TITLE: mrcal commandline tools A number of commandline tools are available for common tasks, obviating the need to write any code. The available tools, with links to their manpages: * Calibration - [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras=]]: Calibrate N cameras. This is the main tool to solve "calibration" problems, and a [[file:how-to-calibrate.org][how-to page]] describes this specific use case. - [[file:mrcal-cull-corners.html][=mrcal-cull-corners=]]: Filters a =corners.vnl= on stdin to cut out some points. Used primarily for testing * Visualization :PROPERTIES: :CUSTOM_ID: commandline-tools-visualization :END: - [[file:mrcal-show-projection-diff.html][=mrcal-show-projection-diff=]]: visualize the difference in projection between N models - [[file:mrcal-show-projection-uncertainty.html][=mrcal-show-projection-uncertainty=]]: visualize the expected projection error due to uncertainty in the calibration-time input - [[file:mrcal-show-valid-intrinsics-region.html][=mrcal-show-valid-intrinsics-region=]]: visualize the region where a model's intrinsics are valid - [[file:mrcal-show-geometry.html][=mrcal-show-geometry=]]: show a visual representation of the geometry represented by some camera models on disk, and optionally, the chessboard observations used to compute that geometry - [[file:mrcal-show-distortion-off-pinhole.html][=mrcal-show-distortion-off-pinhole=]]: visualize the deviation of a specific lens model from a pinhole model - [[file:mrcal-show-splined-model-correction.html][=mrcal-show-splined-model-correction=]]: visualize the projection corrections defined by a splined model - [[file:mrcal-show-residuals-board-observation.html][=mrcal-show-residuals-board-observation=]]: visualize calibration residuals for one or more observations of a board - [[file:mrcal-show-residuals.html][=mrcal-show-residuals=]]: visualize calibration residuals in an imager * Camera model manipulation - [[file:mrcal-convert-lensmodel.html][=mrcal-convert-lensmodel=]]: Fits the behavior of one lens model to another - [[file:mrcal-graft-models.html][=mrcal-graft-models=]]: Combines the intrinsics of one cameramodel with the extrinsics of another - [[file:mrcal-to-cahvor.html][=mrcal-to-cahvor=]]: Converts a model stored in the native =.cameramodel= file format to the =.cahvor= format. This exists for compatibility only, and does not touch the data: any lens model may be used - [[file:mrcal-from-cahvor.html][=mrcal-from-cahvor=]]: Converts a model stored in the =.cahvor= file format to the =.cameramodel= format. This exists for compatibility only, and does not touch the data: any lens model may be used - [[file:mrcal-to-kalibr.html][=mrcal-to-kalibr=]]: Converts a model stored in the native =.cameramodel= file format to the =.yaml= format used by [[https://github.com/ethz-asl/kalibr][kalibr]]. - [[file:mrcal-from-kalibr.html][=mrcal-from-kalibr=]]: Converts a model stored in =.yaml= files used by [[https://github.com/ethz-asl/kalibr][kalibr]] to the =.cameramodel= format. - [[file:mrcal-from-ros.html][=mrcal-from-ros=]]: Converts a model stored in =.yaml= files used by [[https://www.ros.org/][ROS]] and [[https://opencv.org/][OpenCV]] to the =.cameramodel= format. * Reprojection - [[file:mrcal-reproject-image.html][=mrcal-reproject-image=]]: Given image(s) and lens model(s), produces a new set of images that observe the same scene with a different model. Several flavors of functionality are included here, such as undistortion-to-pinhole, re-rotation, and remapping to infinity. - [[file:mrcal-reproject-points.html][=mrcal-reproject-points=]]: Given two lens models and a set of pixel coodinates, maps them from one lens model to the other * Miscellaneous utilities - [[file:mrcal-is-within-valid-intrinsics-region.html][=mrcal-is-within-valid-intrinsics-region=]]: Augments a vnlog of pixel coordinates with a column indicating whether or not each point lies within the valid-intrinsics region * Stereo and triangulation - [[file:mrcal-stereo.html][=mrcal-stereo=]]: Dense stereo processing. Given pairs of images captured by a given pair of camera models, runs stereo matching to produce disparity and range images. - [[file:mrcal-triangulate.html][=mrcal-triangulate=]]: Sparse stereo processing. Given a pair of images captured by a given pair of camera models, reports the range to a queried feature and its sensitivities to all the inputs. Very useful in diagnosing accuracy issues in the intrinsics and extrinsics. mrcal-2.4.1/doc/conventions.org000066400000000000000000000240571456301662300164550ustar00rootroot00000000000000#+TITLE: mrcal conventions #+OPTIONS: toc:t * Terminology Some terms in the documentation and sources can have ambiguous meanings, so I explicitly define them here - *calibration*: the procedure used to compute the lens parameters and geometry of a set of cameras; or the result of this procedure. Usually this involves a stationary set of cameras observing a moving object. - [[file:formulation.org::#calibration-object][*calibration object*]] or *chessboard* or *board*: these are used more or less interchangeably. They refer to the known-geometry object observed by the cameras, with those observations used as input during calibration - *camera model*: this is used to refer to the intrinsics (lens parameters) and extrinsics (geometry) together - *confidence*: a measure of dispersion of some estimator. Higher confidence implies less dispersion. Used to describe the [[file:uncertainty.org][calibration quality]]. Inverse of *uncertainty* - *extrinsics*: the pose of a camera in respect to some fixed coordinate system - *frames*: in the context of [[file:formulation.org][mrcal's optimization]] these refer to an array of poses of the observed chessboards - *intrinsics*: the parameters describing the behavior of a lens. The pose of the lens is independent of the intrinsics - *measurements* or *residuals*: used more or less interchangeably. This is the vector whose norm the [[file:formulation.org][optimization algorithm]] is trying to minimize. mrcal refers to this as $\vec x$, and it primarily contains differences between observed and predicted pixel observations - *projection*: a mapping of a point in space in the camera coordinate system to a pixel coordinate where that point would be observed by a given camera - *pose*: a 6 degree-of-freedom vector describing a position and an orientation - *SFM*: structure from motion. This is the converse of "calibration": we observe a stationary scene from a moving camera to compute the geometry of the scene - *state*: the vector of parameters that the [[file:formulation.org][mrcal optimization algorithm]] moves around as it searches for the optimum. mrcal refers to this as $\vec b$ - *uncertainty*: a measure of dispersion of some estimator. Higher uncertainty implies more dispersion. Used to describe the [[file:uncertainty.org][calibration quality]]. Inverse of *confidence* - *unprojection*: a mapping of a pixel coordinate back to a point in space in the camera coordinate system that would produce an observation at that pixel. Unprojection is only unique up-to scale * Symbols ** Geometry - $\vec q$ is a 2-dimensional vector representing a pixel coordinate: $\left( x,y \right)$ - $\vec v$ is a 3-dimensional vector representing a /direction/ $\left( x,y,z \right)$ in space. $\vec v$ is unique only up-to-length. In a camera's coordinate system we have $\vec q = \mathrm{project}\left(\vec v \right)$ - $\vec p$ is a 3-dimensional vector representing a /point/ $\left( x,y,z \right)$ in space. Unlike $\vec v$, $\vec p$ has a defined range. Like $\vec v$ we have $\vec q = \mathrm{project}\left(\vec p \right)$ - $\vec u$ is a 2-dimensional vector representing a [[file:lensmodels.org::#lensmodel-stereographic][normalized stereographic projection]] ** Optimization :PROPERTIES: :CUSTOM_ID: symbols-optimization :END: The core of the [[file:formulation.org][mrcal calibration routine]] is a nonlinear least-squares optimization \[ \min_{\vec b} E = \min_{\vec b} \left \Vert \vec x \left( \vec b \right) \right \Vert ^2 \] Here we have - $\vec b$ is the vector of parameters being optimized. Earlier versions of mrcal used $\vec p$ for this, but it clashed with $\vec p$ referring to points in space, which wasn't always clear from context. Some older code or documentation may still use $\vec p$ to refer to optimization state - $\vec x$ is the vector of /measurements/ describing the error of the solution at some hypothesis $\vec b$ - $E$ is the cost function being optimized. $E \equiv \left \Vert \vec x \right \Vert ^2$ - $\vec J$ is the /jacobian/ matrix. This is the matrix $\frac{ \partial \vec x }{ \partial \vec b }$. Usually this is large and sparse. * Camera coordinate system mrcal uses right-handed coordinate systems. No convention is assumed for the world coordinate system. The canonical /camera/ coordinate system has $x$ and $y$ as with pixel coordinates in an image: $x$ is to the right and $y$ is down. $z$ is then forward to complete the right-handed system of coordinates. * Transformation naming We describe transformations as mappings between a representation of a point in one coordinate system to a representation of the /same/ point in another coordinate system. =T_AB= is a transformation from coordinate system =B= to coordinate system =A=. These chain together nicely, so if we know the transformation between =A= and =B= and between =B= and =C=, we can transform a point represented in =C= to =A=: =x_A = T_AB T_BC x_C = T_AC x_C=. And =T_AC = T_AB T_BC=. * Pose representation :PROPERTIES: :CUSTOM_ID: pose-representation :END: Various parts of the toolkit have preferred representations of pose, and mrcal has functions to convert between them. Available representations are: - =Rt=: a (4,3) numpy array with a (3,3) rotation matrix concatenated with a (1,3) translation vector: \[ \begin{bmatrix} R \\ \vec t^T \end{bmatrix} \] This form is easy to work with, but there are implied constraints: most (4,3) numpy arrays are /not/ valid =Rt= transformations. - =rt=: a (6,) numpy array with a (3,) vector representing a [[https://en.wikipedia.org/wiki/Axis%E2%80%93angle_representation#Rotation_vector][Rodrigues rotation]] concatenated with another (3,) vector, representing a translation: \[ \left[ \vec r^T \quad \vec t^T \right] \] This form requires more computations to deal with, but has no implied constraints: /any/ (6,) numpy array is a valid =rt= transformation. Thus this is the form used inside the [[file:formulation.org][mrcal optimization routine]]. - =qt=: a (7,) numpy array with a (4,) vector representing a unit quaternion $\left(w,x,y,z\right)$ concatenated with another (3,) vector, representing a translation: \[ \left[ \vec q^T \quad \vec t^T \right] \] mrcal doesn't use quaternions anywhere, and this exists only for interoperability with other tools. Each of these represents a transformation =rotate(x) + t=. Since a pose represents a transformation between two coordinate systems, the toolkit generally refers to a pose as something like =Rt_AB=, which is an =Rt=-represented transformation to convert a point to a representation in the coordinate system =A= from a representation in coordinate system =B=. A Rodrigues rotation vector =r= represents a rotation of =length(r)= radians around an axis in the direction =r=. Converting between =R= and =r= is done via the [[https://en.wikipedia.org/wiki/Rodrigues%27_rotation_formula][Rodrigues rotation formula]]: using the [[file:mrcal-python-api-reference.html#-r_from_R][=mrcal.r_from_R()=]] and [[file:mrcal-python-api-reference.html#-R_from_r][=mrcal.R_from_r()=]] functions. For translating /poses/, not just rotations, use [[file:mrcal-python-api-reference.html#-rt_from_Rt][=mrcal.rt_from_Rt()=]] and [[file:mrcal-python-api-reference.html#-Rt_from_rt][=mrcal.Rt_from_rt()=]]. * Linear algebra mrcal follows the usual linear algebra convention of /column/ vectors. So rotating a vector using a rotation matrix is a matrix-vector multiplication operation: $\vec b = R \vec a$ where both $\vec a$ and $\vec b$ are column vectors. However, numpy prints vectors (1-dimensional objects), as /row/ vectors, so the code treats 1-dimensional objects as transposed vectors. In the code, the above rotation would be implemented equivalently: $\vec b^T = \vec a^T R^T$. The [[file:mrcal-python-api-reference.html#-rotate_point_R][=mrcal.rotate_point_R()=]] and [[file:mrcal-python-api-reference.html#-transform_point_Rt][=mrcal.transform_point_Rt()=]] functions handle this transparently. A similar issue is that numpy follows the linear algebra convention of indexing arrays with =(index_row, index_column)= and representing array sizes with =(height, width)=. This runs against the /other/ convention of referring to pixel coordinates as =(x,y)= and image dimensions as =(width, height)=. Whenever possible, mrcal places the =x= coordinate first (as in the latter), but when interacting directly with numpy, it must place the =y= coordinate first. /Usually/ =x= goes first. In any case, the choice being made is very clearly documented, so when in doubt, pay attention to the docs. When computing gradients mrcal places the dependent variables in the leading dimensions, and the independent variables in the trailing dimensions. So if we have $\vec b = R \vec a$, then \[ R = \frac{ \partial \vec b }{ \partial \vec a } = \left[ \begin{aligned} \frac{ \partial b_0 }{ \partial \vec a } \\ \frac{ \partial b_1 }{ \partial \vec a } \\ \frac{ \partial b_2 }{ \partial \vec a } \end{aligned} \right] = \left[ \frac{ \partial \vec b }{ \partial a_0 } \quad \frac{ \partial \vec b }{ \partial a_1 } \quad \frac{ \partial \vec b }{ \partial a_2 } \right] \] $\frac{ \partial b_i }{ \partial \vec a }$ is a (1,3) row vector and $\frac{ \partial \vec b }{ \partial a_i }$ is a (3,1) column vector. * Implementation The core of mrcal is written in C, but most of the API is currently available in Python only. The Python wrapping is done via the [[https://github.com/dkogan/numpysane/blob/master/README-pywrap.org][=numpysane_pywrap=]] library, which makes it simple to make consistent Python interfaces /and/ provides [[https://numpy.org/doc/stable/user/basics.broadcasting.html][broadcasting]] support. The Python layer uses [[https://numpy.org/][=numpy=]] and [[https://github.com/dkogan/numpysane/][=numpysane=]] heavily. All the plotting is done with [[https://github.com/dkogan/gnuplotlib][=gnuplotlib=]]. [[https://opencv.org/][OpenCV]] is used a bit, but /only/ in the Python layer, less and less over time (their C APIs are gone, and the C++ APIs are unstable). mrcal-2.4.1/doc/copyrights.org000066400000000000000000000044071456301662300163000ustar00rootroot00000000000000#+TITLE: Copyrights and licenses Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. Government sponsorship acknowledged. All rights reserved. Licensed under the Apache License, Version 2.0 (the "License"); You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 A number of free-software projects are included as source in the toolkit. These are: * [[https://github.com/dkogan/libminimath][libminimath]] mrcal uses some tiny-matrix linear algebra routines implemented by this library. This is a header-only library, so we're not "linking" to it. I'm not modifying the sources, so using the LGPL here is fine, and doesn't trigger the copyleft provisions. Copyright 2011 Oblong Industries. This library is distributed under the terms of the GNU LGPL * opencv projection The [[https://www.github.com/dkogan/mrcal/blob/master/mrcal-opencv.c][opencv projection function]] is a cut-down implementation from the OpenCV project. Distributed under an BSD-style license. Copyright (C) 2000-2008, Intel Corporation, all rights reserved. Copyright (C) 2009, Willow Garage Inc., all rights reserved. * =mrcal_r_from_R()= The [[https://www.github.com/dkogan/mrcal/blob/master/poseutils-opencv.c][=mrcal_r_from_R()= sources]] originated in the OpenCV project. Distributed under an BSD-style license. Copyright (C) 2000-2008, Intel Corporation, all rights reserved. Copyright (C) 2009, Willow Garage Inc., all rights reserved. * [[file:mrcal-python-api-reference.html#-quat_from_R][=mrcal.quat_from_R()=]] The [[https://www.github.com/dkogan/mrcal/blob/master/mrcal/_poseutils_scipy.py][=mrcal.quat_from_R()= sources]] came from scipy. Distributed under a BSD-style license. Copyright (c) 2001-2002 Enthought, Inc. 2003-2019, SciPy Developers. * pydoc [[https://www.github.com/dkogan/mrcal/blob/master/doc/pydoc.py][=doc/pydoc.py=]] is a copy of the sources in the Python project. This is used to extract the docstrings into the .html reference documentation. Minor modifications were made to fit with mrcal's code organization and html styling. Distributed under the PYTHON SOFTWARE FOUNDATION LICENSE VERSION 2. Copyright (c) 2001, 2002, 2003, 2004, 2005, 2006, 2007, 2008, 2009, 2010, 2011, 2012, 2013, 2014 Python Software Foundation; All Rights Reserved. mrcal-2.4.1/doc/data/000077500000000000000000000000001456301662300143005ustar00rootroot00000000000000mrcal-2.4.1/doc/data/README000066400000000000000000000005011456301662300151540ustar00rootroot00000000000000All images (board and views) are taken with - F22 - ISO1600 This allows fast shutter speeds to minimize motion blur and a big depth of field to minimize focus blur. The view of downtown is from the catwalk over Figueroa St. between 2nd and 3rd., looking S. At roughly 34.0558, -118.2539. Spacing between cameras: 7ft mrcal-2.4.1/doc/data/figueroa-overpass-looking-S/000077500000000000000000000000001456301662300216015ustar00rootroot00000000000000mrcal-2.4.1/doc/data/figueroa-overpass-looking-S/features.imgany.inputimage.vnl000066400000000000000000000207151456301662300275710ustar00rootroot00000000000000# x1 y1 x2 y2 2797.320834 2817.122168 2516.397326 2809.480939 2745.412449 2817.276777 2466.424937 2807.753364 3498.985683 3048.130530 3145.013906 3069.718464 3592.350428 3199.133514 3198.330034 3227.890159 4905.693042 2701.936035 4681.926645 2767.586994 2434.247258 2811.970419 2170.132988 2791.710076 3730.066112 3207.530405 3336.811932 3245.156052 2452.640555 2771.603588 2197.820494 2753.630116 4328.868094 2650.979423 4096.657287 2696.618361 3767.318480 3134.347557 3395.789230 3172.220122 3483.817362 3094.172913 3117.605605 3115.684005 3656.422647 3063.942469 3300.637299 3094.070411 3691.802597 3031.321826 3346.234850 3062.452762 1817.818460 2560.366416 1638.975124 2533.481899 2613.595171 3470.351539 2173.198731 3426.746511 2540.022187 2763.121854 2283.297707 2748.025846 2527.254718 3462.609402 2095.163809 3413.788442 3892.180131 3040.984626 3551.024146 3082.676696 2694.465421 3709.950822 2188.495744 3658.863688 3716.378392 3144.804033 3339.806903 3179.890912 3741.095485 3655.022688 3225.239518 3705.325082 4874.231404 2795.807919 4648.597533 2863.227763 5049.287623 2880.232487 4820.376166 2959.761653 3782.276973 3706.934586 3253.441635 3762.806798 4384.005176 2652.736098 4144.937807 2698.186773 3474.235763 2833.309137 3180.212854 2851.381747 3560.293635 2668.947875 3313.530662 2688.650739 4078.506177 2983.336012 3762.287854 3031.547994 2536.030989 3655.243306 2056.228421 3594.459583 3981.586581 3143.885375 3616.590556 3194.510187 2509.842608 3738.673199 2012.272528 3669.792424 3588.326048 3067.263473 3230.317974 3094.035288 2706.165027 3471.897956 2258.893409 3434.838746 1701.951685 2648.483490 1513.021920 2614.966244 2568.098052 3516.756483 2119.776396 3467.182543 3375.055448 2566.920512 3155.574880 2580.227377 4085.218633 3155.783624 3722.814205 3213.033498 3644.948617 3670.842182 3122.186061 3711.646810 1604.206593 2499.253672 1449.791963 2469.883446 2083.205537 3412.655339 1701.809198 3340.238383 2162.337989 3422.311853 1771.122114 3353.375947 2532.608994 3597.978315 2067.407520 3540.710163 2203.063677 2844.330228 1943.754995 2815.280661 2431.548721 3794.412642 1928.068455 3714.646541 2143.415522 3491.936763 1738.402497 3416.224594 2465.462981 3501.579210 2029.247411 3445.844205 2449.084604 3553.762878 2001.368174 3493.363826 2675.309121 3519.265128 2218.361721 3477.185357 3093.042574 2588.934750 2868.770603 2594.313442 1430.470255 2411.751408 1285.891960 2380.853939 2175.491770 2843.095393 1918.211278 2813.277839 2382.917631 3451.454903 1965.500967 3393.753503 2026.627328 3702.842321 1587.374878 3600.376466 3851.901166 3060.808614 3503.461195 3101.499261 2369.611260 3302.186843 1989.098186 3253.580457 2608.546981 3807.433070 2086.166772 3742.291986 1595.689720 3564.961417 1235.609698 3452.704594 1930.538636 3385.854740 1569.725018 3307.849541 2607.355859 2856.653652 2323.587176 2841.002189 1522.023024 3615.963175 1160.809399 3494.565521 2359.351383 3556.920926 1918.985578 3490.044475 4164.493970 3039.545314 3838.273781 3094.844984 1696.831326 3339.406693 1370.571436 3255.277960 2740.496068 3486.068150 2287.992991 3450.371126 4232.618904 3128.717810 3887.143102 3192.743818 4157.525519 3113.656565 3810.896293 3172.611992 4356.617989 3530.428084 3913.620250 3630.512786 2420.656668 3212.582756 2057.864595 3172.352534 1960.705983 3710.678106 1527.112568 3603.374397 2294.404108 3410.026788 1894.188419 3350.141014 2028.608665 3449.159707 1644.050918 3370.476177 2350.438952 3607.778386 1898.821744 3536.221616 2725.919046 3555.918054 2256.702400 3515.892476 2739.690971 2595.770667 2520.362443 2591.059743 2304.808671 3711.279550 1833.376506 3628.295964 2264.569646 3734.886621 1792.069300 3646.660428 4535.526160 3683.013752 4070.220566 3811.880529 1717.860594 3649.695132 1325.996209 3534.251227 3997.668493 3019.604957 3667.556010 3065.859565 2071.323928 3632.309230 1642.191190 3539.813389 2513.407369 3802.671186 2000.562338 3729.536767 1821.397937 3678.523314 1410.841144 3565.956635 3714.479894 2846.795550 3421.438802 2874.878572 2353.646682 3780.536161 1861.550163 3694.982873 2201.517636 2912.926817 1926.051453 2880.134552 5451.089926 2777.712350 5256.210561 2864.328293 1970.901162 3172.724004 1653.851849 3114.416511 2358.454094 2737.028150 2116.909462 2717.435187 2883.011728 3644.985868 2381.603875 3613.739207 5412.007185 2857.524383 5211.492868 2947.298402 1812.110604 3512.726140 1437.229853 3416.661063 4271.372218 3555.024271 3814.075090 3649.990985 2052.863460 3568.196106 1640.220791 3480.262080 1462.554682 3443.826744 1141.890729 3339.424269 4435.665692 3508.500848 4005.674339 3613.256216 2273.281371 2409.579063 2115.129726 2397.818998 1832.970339 3470.644151 1465.004416 3379.781044 4486.874030 3548.471851 4051.712136 3660.830669 1703.182027 3384.104704 1367.216303 3295.844045 1559.091597 3345.474140 1246.249224 3255.203602 2168.824393 2949.042035 1887.035058 2913.405398 1634.932780 3325.898410 1317.617331 3240.644387 4646.642966 3613.621995 4211.718512 3745.456373 1940.011704 3475.453976 1559.197668 3389.630690 1741.270930 3598.793463 1356.610471 3490.153683 2706.287077 3754.441330 2188.571562 3701.626312 3521.228559 3520.632067 3037.923555 3549.064254 1760.701881 3662.048442 1361.193831 3547.762316 4107.290054 2756.529126 3848.779387 2796.497473 5432.132065 2766.889806 5238.312330 2851.826100 1619.354668 3361.760990 1297.196623 3272.133740 2294.427385 2756.999741 2051.109869 2734.600441 2216.224007 3430.260441 1817.891903 3363.949318 4349.856021 2431.697738 4156.443447 2470.460195 2686.832665 3815.609171 2155.697898 3757.154626 1541.525618 3304.904567 1238.148251 3218.011342 4273.010062 2945.795528 3978.123775 3000.725690 3774.740745 2481.519871 3576.594456 2504.821160 1349.411935 2322.999889 1218.244821 2292.476433 4407.337928 2453.905590 4209.900497 2495.443294 2450.241632 3734.834665 1958.963424 3661.259357 4007.872808 3275.695145 3607.889513 3334.006990 4590.331868 3666.143935 4135.339660 3798.501343 1905.551257 3638.353893 1493.756552 3534.859315 2120.154812 3547.870233 1705.405149 3465.870685 1448.813526 3569.919386 1105.545293 3450.696712 2467.250163 2615.890454 2251.836526 2603.052272 2869.192382 3600.317757 2379.700249 3569.921282 2934.465258 2917.582982 2621.876869 2913.024776 4594.266788 3860.751438 4087.970058 4011.811700 1513.761981 3336.322209 1207.354205 3245.630051 2090.548901 2537.277324 1909.714690 2517.429421 1855.990583 3629.215213 1451.879528 3523.397671 2803.746154 2465.182085 2618.586361 2463.932697 3495.319011 3318.976311 3066.885098 3342.735788 1235.192994 2445.582679 1102.065916 2410.575734 3820.368322 3698.246868 3308.250732 3757.286013 2650.773337 3675.256811 2156.774044 3623.179768 1625.641071 2497.496251 1471.326372 2468.192675 3353.079663 2872.845268 3047.385880 2885.893018 4162.887776 2854.132549 3885.552464 2900.009772 2589.837931 2470.537916 2409.281928 2464.251451 3564.084749 2320.771490 3407.928089 2337.524983 4753.816893 2544.463455 4550.450915 2596.472129 1227.263850 2380.909443 1096.052485 2347.829836 5175.684647 2896.286071 4948.162643 2983.183791 4619.735150 3194.287540 4287.887130 3283.375283 2837.396490 3707.051855 2322.247823 3668.713450 1504.490469 3410.335386 1185.066886 3310.980764 1938.440894 2470.430652 1773.744296 2449.200131 3544.049578 3619.219293 3033.958423 3649.325864 1544.881775 3543.348119 1195.256034 3431.163897 4673.646775 3631.730868 4237.781317 3767.218060 2853.480575 2364.518992 2695.425164 2365.301328 4404.208774 3715.100077 3915.819285 3834.206134 2969.673316 2681.273959 2721.038995 2682.241886 4835.371422 2534.273503 4641.770169 2587.430493 2085.852605 3226.789004 1746.611074 3169.432938 4565.409798 3525.173531 4143.905262 3641.433450 2821.963962 3785.140750 2288.065779 3741.155271 2975.949697 2610.889985 2746.918065 2612.582795 2927.188621 2971.567609 2600.791114 2965.528398 5089.771204 2698.410882 4896.791842 2764.994721 3842.668489 3858.029023 3274.118317 3925.424886 2793.124072 3967.522737 2215.768119 3911.146696 2306.728089 3259.152837 1941.379817 3210.122382 3543.786980 3594.268116 3040.610712 3623.624493 4532.520949 3483.456836 4119.120988 3593.734187 3988.699840 2699.601328 3741.101120 2733.627107 1224.302115 2855.135663 1027.812510 2797.805281 1187.856779 2847.827156 985.553098 2787.561757 1485.040685 2897.213383 1266.373599 2844.271095 3012.161613 3501.609323 2541.957889 3486.105010 5266.122817 2917.711349 5042.698119 3009.327609 4196.486581 2763.796515 3939.579603 2807.032418 4520.593653 3535.396457 4092.257093 3649.398629 3575.942197 3768.184020 3025.241629 3803.332158 2014.431948 3783.239482 1558.538375 3671.330203 2900.854146 3166.777779 2522.513883 3154.563961 1518.292011 2505.465925 1344.014591 2470.345091 mrcal-2.4.1/doc/data/figueroa-overpass-looking-S/features.imgany.scale0.6.vnl000066400000000000000000000264151456301662300267450ustar00rootroot00000000000000# ID Feat1x Feat1y Feat2x Feat2y Corner1 Corr12 PkWidth Pln Reproj 2 2874.000 2514.000 2692.879 2515.956 15172 0.984 4.2 0 0.0347 4 2841.000 2515.000 2659.755 2516.678 12232 0.985 4.26 0 0.0368 6 3331.000 2691.000 3096.094 2695.828 10919 0.982 3.37 0 0.1 7 3406.000 2818.000 3134.504 2822.231 10698 0.969 3.32 0 0.274 9 4596.000 2587.000 4318.438 2600.560 9801 0.962 2.98 0 0.338 10 2638.000 2521.000 2454.576 2520.959 9706 0.981 4.74 0 0.0699 11 3508.000 2837.000 3229.332 2841.298 9610 0.981 4.02 0 0.312 12 2652.000 2492.000 2476.968 2491.978 9576 0.976 4.8 0 0.0195 13 3938.000 2458.000 3744.325 2470.967 9253 0.899 3.69 0 0.859 14 3529.000 2779.000 3266.512 2783.832 8923 0.985 4.29 0 0.288 15 3323.000 2726.000 3078.756 2730.855 8814 0.980 3.88 0 0.0536 18 3442.000 2713.000 3199.203 2718.146 8487 0.980 3.37 0 0.161 20 3465.000 2690.000 3228.516 2695.323 8403 0.985 4.21 0 0.224 22 2198.000 2380.000 2044.335 2374.320 8155 0.977 4.65 0 0.192 23 2726.000 3047.000 2391.308 3051.771 7792 0.982 4.57 0 0.0664 24 2710.000 2483.000 2537.713 2483.279 7510 0.976 4.81 0 0.0923 25 2663.000 3046.000 2328.005 3051.142 7119 0.979 5.17 0 0.252 26 3615.000 2715.000 3368.866 2720.780 6969 0.983 4.27 0 0.252 27 2770.000 3293.000 2364.806 3299.912 6954 0.974 6.15 0 0.254 28 3492.000 2783.000 3228.646 2787.594 6717 0.981 4.62 0 0.349 30 3575.000 3281.000 3170.652 3282.374 6680 0.983 4.63 0 0.0516 31 4573.000 2667.000 4297.646 2678.268 6679 0.990 5.29 0 0.265 32 4871.000 2803.000 4541.188 2811.609 6675 0.988 5.38 0 0.0932 33 3620.000 3350.000 3195.409 3350.701 6613 0.980 4.8 0 0.0413 34 3989.000 2465.000 3783.698 2476.126 6597 0.943 5.73 0 0.722 35 3305.000 2532.000 3115.669 2537.324 6528 0.937 1.87 0 0.144 36 3356.000 2422.000 3197.401 2428.709 6490 0.969 4.31 0 0.103 37 3758.000 2689.000 3516.242 2695.640 6445 0.986 5.46 0 0.323 38 2652.000 3245.000 2259.455 3252.198 6194 0.984 5.07 0 0.263 40 3698.000 2811.000 3423.146 2816.002 5998 0.990 4.48 0 0.31 41 2622.000 3344.000 2200.615 3352.333 5885 0.984 6.03 0 0.153 42 3394.000 2711.000 3152.578 2716.140 5877 0.975 3.76 0 0.0193 43 2793.000 3043.000 2459.744 3047.685 5840 0.986 4.72 0 0.114 45 2091.000 2454.000 1915.600 2448.235 5684 0.966 3.55 0 0.04 47 2689.000 3096.000 2340.044 3101.285 5529 0.980 5.16 0 0.0634 48 3234.000 2350.000 3097.469 2355.766 5525 0.976 3.93 0 0.108 49 3787.000 2836.000 3503.081 2841.009 5498 0.988 4.93 0 0.252 51 3497.000 3284.000 3093.011 3285.632 5338 0.986 4.25 0 0.194 53 2015.000 2352.000 1866.045 2343.335 5189 0.892 2.19 0 0.0503 56 2318.000 3052.000 1975.953 3057.608 4724 0.981 6.28 0 0.0616 58 2383.000 3049.000 2043.085 3054.354 4719 0.973 5.75 0 0.00644 60 2655.000 3183.000 2280.750 3189.369 4623 0.986 6.11 0 0.14 61 2475.000 2557.000 2279.774 2556.207 4541 0.966 6.69 0 0.0782 62 2550.000 3423.000 2104.742 3432.761 4495 0.981 6.54 0 0.0445 63 2356.000 3123.000 1994.172 3129.564 4470 0.980 5.32 0 0.000137 64 2613.000 3090.000 2265.190 3095.437 4412 0.982 4.94 0 0.0634 66 2595.000 3145.000 2230.797 3151.224 4273 0.983 6.1 0 0.153 68 2768.000 3091.000 2420.975 3095.848 4193 0.945 3.86 0 0.0606 69 3059.000 2361.000 2921.043 2364.737 4178 0.958 2.82 0 0.0945 70 1851.000 2301.000 1694.738 2289.561 4046 0.972 4.43 0 0.0898 71 2455.000 2558.000 2259.298 2557.107 3976 0.971 6.42 0 0.109 75 2555.000 3049.000 2218.191 3054.159 3777 0.982 5.58 0 0.0984 77 2206.000 3390.000 1762.875 3401.757 3700 0.976 8.09 0 0.343 78 3586.000 2727.000 3336.942 2732.840 3693 0.951 4.76 0 0.0389 79 2560.000 2911.000 2263.306 2914.367 3676 0.977 3.26 0 0.0553 81 2694.000 3417.000 2253.001 3425.295 3623 0.979 6.71 0 0.0179 82 1787.000 3352.000 1340.353 3366.337 3585 0.980 6.85 0 0.375 83 2188.000 3053.000 1842.181 3058.941 3548 0.976 7.96 0 0.102 84 2751.000 2546.000 2560.810 2547.160 3469 0.977 6.73 0 0.00419 85 1673.000 3451.000 1191.367 3469.506 3461 0.934 5.2 0 0.228 86 2524.000 3159.000 2154.894 3165.647 3398 0.966 5.65 0 0.136 90 3839.000 2747.000 3578.934 2753.359 3247 0.987 4.21 0 0.235 91 1971.000 3058.000 1618.481 3064.322 3243 0.975 6.83 0 0.032 94 2817.000 3055.000 2480.911 3059.230 3151 0.984 8.91 0 0.237 95 3915.000 2836.000 3627.823 2841.409 3117 0.981 5.5 0 0.169 96 3844.000 2810.000 3565.918 2815.444 3092 0.971 4.42 0 0.283 97 4143.000 3288.000 3721.757 3285.631 3084 0.981 6.05 0 0.195 98 2605.000 2829.000 2332.338 2831.708 3068 0.979 5.41 0 0.0362 100 2139.000 3418.000 1685.249 3431.352 2988 0.985 6.58 0 0.0482 103 2491.000 3019.000 2161.710 3024.204 2883 0.984 5.21 0 0.317 105 2264.000 3099.000 1906.577 3105.461 2856 0.978 6.84 0 0.0101 108 2510.000 3215.000 2124.397 3222.260 2845 0.980 5.59 0 0.0115 110 2803.000 3125.000 2446.709 3130.120 2840 0.971 5.05 0 0.0251 111 2841.000 2367.000 2702.180 2368.183 2834 0.967 5.81 0 0.0213 112 2456.000 3341.000 2032.698 3350.678 2823 0.976 5.71 0 0.233 113 2417.000 3377.000 1982.765 3387.201 2822 0.929 3.33 0 0.00576 114 4435.000 3572.000 3924.064 3562.746 2817 0.983 5.86 0 0.644 118 1899.000 3417.000 1437.230 3432.227 2758 0.983 5.84 0 0.293 120 3696.000 2709.000 3450.112 2715.320 2724 0.972 4.62 0 0.173 121 2265.000 3293.000 1851.215 3303.079 2722 0.977 9.34 0 0.105 124 2617.000 3422.000 2173.407 3431.300 2639 0.987 6.89 0 0.158 125 2004.000 3419.000 1545.069 3433.690 2629 0.974 6.96 0 0.00696 127 3469.000 2553.000 3271.701 2559.572 2617 0.984 5.86 0 0.0658 129 2486.000 3418.000 2041.564 3427.566 2588 0.981 6.4 0 0.463 131 2469.000 2608.000 2259.015 2607.607 2579 0.973 5.23 0 0.0259 135 5714.000 2861.000 5268.772 2868.780 2507 0.978 5.74 0 0.227 136 2260.000 2844.000 1978.217 2846.129 2504 0.982 5.09 0 0.0356 137 2590.000 2472.000 2420.389 2471.272 2494 0.980 5.79 0 0.0391 138 2915.000 3212.000 2534.417 3217.298 2476 0.976 3.11 0 0.0956 139 5650.000 2942.000 5210.898 2946.663 2475 0.961 7.15 0 0.203 140 2044.000 3218.000 1645.882 3227.603 2467 0.964 8.05 0 0.0976 142 4056.000 3290.000 3636.998 3288.287 2450 0.985 4.74 0 0.0801 144 2262.000 3223.000 1869.045 3231.481 2370 0.989 5.14 0 0.138 145 1668.000 3251.000 1247.379 3263.215 2355 0.963 8.42 0 0.407 148 4228.000 3289.000 3803.175 3286.210 2311 0.975 5.29 0 0.113 153 2544.000 2257.000 2434.335 2254.113 2236 0.967 5.52 0 0.229 157 2076.000 3165.000 1695.004 3173.158 2203 0.951 6.4 0 0.189 158 4307.000 3360.000 3859.730 3355.644 2203 0.966 4.62 0 0.134 159 1966.000 3104.000 1599.762 3111.314 2203 0.979 7.15 0 0.102 160 1819.000 3103.000 1448.095 3110.667 2199 0.969 6.58 0 0.158 161 2442.000 2638.000 2222.992 2638.022 2197 0.971 6.74 0 0.134 166 1909.000 3060.000 1553.553 3066.642 2064 0.972 8.62 0 0.0651 168 4560.000 3528.000 4055.238 3518.591 2027 0.979 4.43 0 0.772 170 2178.000 3145.000 1805.315 3152.477 1984 0.971 5.25 0 0.0832 171 1943.000 3343.000 1504.283 3356.230 1976 0.976 7.54 0 0.0971 172 2776.000 3344.000 2356.399 3351.115 1973 0.987 4.85 0 0.121 173 3381.000 3107.000 3028.554 3110.931 1962 0.894 3.83 0 0.471 174 1943.000 3418.000 1482.625 3433.032 1958 0.979 8.04 0 0.158 176 3758.000 2516.000 3562.106 2525.069 1939 0.952 4.01 0 0.173 177 5655.000 2837.000 5224.062 2846.010 1930 0.979 8.13 0 0.0843 183 1882.000 3103.000 1513.811 3110.274 1876 0.935 8.02 0 0.299 185 2545.000 2489.000 2370.105 2487.961 1839 0.967 6.08 0 0.000272 189 2426.000 3049.000 2086.575 3054.504 1733 0.983 5.42 0 0.171 191 3939.000 2299.000 3777.023 2314.583 1726 0.880 6.19 0 0.7 192 2756.000 3420.000 2314.572 3427.788 1708 0.986 5.67 0 0.00325 195 1811.000 3064.000 1451.073 3070.735 1678 0.961 7.21 0 0.0982 198 3923.000 2684.000 3678.256 2691.595 1667 0.965 4.71 0 0.274 199 3494.000 2305.000 3361.856 2314.277 1659 0.916 3.89 0 0.2 202 1771.000 2240.000 1621.437 2225.788 1655 0.967 3.74 0 0.168 205 3993.000 2319.000 3822.322 2335.238 1595 0.888 5.75 0 0.966 206 2574.000 3347.000 2150.958 3355.700 1574 0.987 8.66 0 0.128 207 3739.000 2933.000 3428.607 2936.667 1569 0.947 6.76 0 0.34 208 4505.000 3576.000 3989.656 3566.177 1557 0.963 5.36 0 0.861 209 2104.000 3342.000 1671.417 3353.940 1548 0.975 9.16 0 0.102 212 2326.000 3187.000 1945.466 3194.460 1519 0.882 3.19 0 0.193 213 1596.000 3421.000 1120.058 3439.329 1504 0.964 8.44 0 0.232 214 2667.000 2386.000 2522.650 2385.169 1498 0.975 5.59 0 0.103 216 2906.000 3165.000 2538.565 3170.175 1492 0.951 4.04 0 0.159 220 2960.000 2583.000 2758.696 2585.760 1431 0.943 3.72 0 0.0765 223 4635.000 3908.000 4021.444 3887.721 1396 0.902 6.55 0 0.309 225 1769.000 3107.000 1394.629 3115.402 1378 0.954 7.88 0 0.171 228 2411.000 2348.000 2275.024 2343.905 1333 0.959 7.1 0 0.0899 233 2056.000 3345.000 1621.167 3356.885 1284 0.988 8.61 0 0.452 236 2882.000 2283.000 2767.199 2284.349 1216 0.956 4.34 0 0.0285 237 3345.000 2914.000 3047.246 2917.707 1216 0.930 3.24 0 0.253 242 1628.000 2346.000 1460.264 2332.672 1186 0.973 5.15 0 0.0288 248 3652.000 3347.000 3237.653 3347.780 1136 0.914 8 0 0.128 249 2739.000 3257.000 2343.795 3264.537 1131 0.951 7.77 0 0.776 253 2035.000 2349.000 1888.264 2340.119 1104 0.889 2.67 0 0.325 255 3227.000 2556.000 3031.747 2560.389 1099 0.936 3.02 0 0.314 259 3814.000 2596.000 3597.096 2604.389 1076 0.945 3.79 0 0.178 260 2749.000 2289.000 2633.166 2288.691 1075 0.959 5.09 0 0.00513 265 3350.000 2197.000 3251.225 2205.336 1034 0.879 3.31 0 0.274 266 4369.000 2424.000 4147.130 2440.084 1021 0.892 2.45 0 0.369 273 1625.000 2295.000 1458.996 2281.076 993 0.926 9.16 0 0.519 276 5113.000 2870.000 4739.461 2877.096 981 0.982 5.66 0 0.142 282 4347.000 2992.000 3999.776 2994.521 943 0.859 3.63 0 0.4 286 2879.000 3282.000 2477.722 3287.917 933 0.921 5.96 0 0.107 289 1733.000 3195.000 1331.353 3205.189 915 0.976 9.65 0 0.413 290 2300.000 2310.000 2168.420 2304.304 912 0.951 4.71 0 0.0557 292 3409.000 3213.000 3026.285 3215.238 908 0.923 3.38 0 0.35 297 1733.000 3344.000 1286.795 3358.417 887 0.971 7.42 0 0.469 298 4612.000 3571.000 4093.391 3559.716 887 0.926 3.67 0 0.575 303 2913.000 2220.000 2816.222 2221.589 849 0.948 5.89 0 0.0585 308 4274.000 3555.000 3773.511 3547.086 840 0.946 4.89 0 0.102 311 2983.000 2421.000 2827.995 2423.995 835 0.933 9.38 0 0.133 319 4470.000 2427.000 4244.407 2444.124 792 0.900 2.74 0 0.249 322 2348.000 2876.000 2058.433 2878.876 785 0.938 4.32 0 0.0908 334 4400.000 3363.000 3947.366 3357.614 723 0.959 7.43 0 0.0616 341 2864.000 3374.000 2436.313 3380.384 712 0.941 8.39 0 0.067 350 2987.000 2375.000 2845.281 2377.822 676 0.918 3.45 0 0.0133 351 2955.000 2622.000 2742.944 2624.777 670 0.948 9.27 0 0.102 355 4884.000 2629.000 4597.668 2643.479 655 0.955 5.19 0 0.00882 359 3709.000 3561.000 3223.130 3560.207 648 0.970 5.57 0 0.769 360 2831.000 3615.000 2333.866 3624.609 646 0.911 9.58 0 0.659 361 2517.000 2879.000 2228.975 2882.067 645 0.895 2.53 0 0.0251 362 3406.000 3186.000 3031.001 3187.799 645 0.890 7.52 0 0.749 366 4339.000 3295.000 3908.576 3291.977 623 0.974 7.8 0 0.283 367 3660.000 2465.000 3481.428 2473.990 619 0.939 6.37 0 0.076 369 1544.000 2701.000 1276.406 2696.991 611 0.968 4.51 0 0.0888 371 1497.000 2703.000 1211.528 2698.953 607 0.951 4.24 0 0.0184 378 1845.000 2684.000 1600.843 2681.219 593 0.952 8.56 0 0.00907 379 3010.000 3064.000 2672.000 3067.716 588 0.937 3.93 0 0.351 383 5317.000 2938.000 4909.054 2942.686 587 0.987 5.54 0 0.15 385 3833.000 2530.000 3630.512 2539.334 580 0.956 3.69 0 0.273 389 4345.000 3357.000 3896.983 3352.598 573 0.959 4.79 0 0.255 397 3454.000 3390.000 3020.585 3392.031 539 0.928 8.67 0 0.236 400 2172.000 3499.000 1695.552 3512.586 536 0.863 5.08 0 0.845 401 2936.000 2771.000 2680.959 2774.295 535 0.956 9.85 0 0.0335 406 1932.000 2364.000 1752.355 2353.978 514 0.892 3.83 0 0.616 mrcal-2.4.1/doc/data/figueroa-overpass-looking-S/homography.initial.scale0.6.txt000066400000000000000000000002241456301662300274570ustar00rootroot000000000000001.06780825e+00 -3.11887689e-01 4.85218463e+02 4.84659653e-02 1.01030843e+00 -9.34182334e+01 1.61828748e-05 -7.38019356e-06 1.00000000e+00 6016 4016 mrcal-2.4.1/doc/data/figueroa-overpass-looking-S/opencv8-0.cameramodel000066400000000000000000013310071456301662300255200ustar00rootroot00000000000000# generated on 2020-11-14 21:49:59 with /home/dima/jpl/deltapose-lite/calibrate-extrinsics --skip-outlier-rejection --correspondences /proc/self/fd/15 --regularization t --seedrt01 0 0 0 2.1335999999999999 0 0 --cam0pose identity --observed-pixel-uncertainty 1 data/board/opencv8.cameramodel data/board/opencv8.cameramodel # # # Npoints_all Npoints_ranged Noutliers rms_err rms_err_reprojectiononly expected_err_yaw__rad range_uncertainty_1000m rms_err_optimization_range rms_err_range # # 81 0 0 0.5864956382518457 0.5972518353763385 0.0006951826725578303 325.84567147387764 - - # # ## WARNING: the range uncertainty of target at 1000m is 325.8. This is almost certainly too high. This solve is not reliable { 'lensmodel': 'LENSMODEL_OPENCV8', # intrinsics are fx,fy,cx,cy,distortion0,distortion1,.... 'intrinsics': [ 2073.872915, 2077.452267, 3004.686823, 1997.377253, 0.4791613797, 0.0266824914, 4.398264387e-05, -1.180073913e-05, 8.959722542e-05, 0.7666912469, 0.09633561231, 0.001407513313,], 'valid_intrinsics_region': [ [ 622, 0 ], [ 0, 634 ], [ 0, 2747 ], [ 207, 2958 ], [ 207, 3804 ], [ 415, 3804 ], [ 622, 4015 ], [ 830, 3804 ], [ 1037, 4015 ], [ 1244, 3804 ], [ 1452, 3804 ], [ 1659, 4015 ], [ 1867, 3804 ], [ 2696, 3804 ], [ 2904, 4015 ], [ 3111, 3804 ], [ 4563, 3804 ], [ 4771, 4015 ], [ 5185, 4015 ], [ 5185, 3804 ], [ 5600, 3381 ], [ 5808, 3592 ], [ 5808, 2536 ], [ 6015, 2324 ], [ 6015, 2113 ], [ 5808, 1902 ], [ 6015, 1691 ], [ 5808, 1479 ], [ 5808, 423 ], [ 5600, 211 ], [ 5600, 0 ], [ 5393, 211 ], [ 5185, 0 ], [ 2282, 0 ], [ 2074, 211 ], [ 1867, 211 ], [ 1659, 0 ], [ 1244, 0 ], [ 1244, 211 ], [ 1037, 423 ], [ 622, 423 ], [ 415, 211 ], [ 622, 0 ], ], # extrinsics are rt_fromref 'extrinsics': [ 0, 0, 0, 0, 0, 0,], 'imagersize': [ 6016, 4016,], 'icam_intrinsics': 0, # The optimization inputs contain all the data used to compute this model. # This contains ALL the observations for ALL the cameras in the solve. The uses of # this are to be able to compute projection uncertainties, to visualize the # calibration-time geometry and to re-run the original optimization for # diagnostics. This is a big chunk of data that isn't useful for humans to # interpret, so it's stored in binary, compressed, and encoded to ascii in # base-85. Modifying the intrinsics of the model invalidates the optimization # inputs: the optimum implied by the inputs would no longer match the stored # parameters. Modifying the extrinsics is OK, however: if we move the camera # elsewhere, the original solve can still be used to represent the camera-relative # projection uncertainties 'optimization_inputs': b'P)h>@6aWAK2mk;8AprP8D`%|$007_s000gE6aZ;%baH8Kb7^C9E^csn0RRvH-~a#s00000tpET300000o9q|r8xYCJP{vTLo|0OeT%>NLpl*|9p{}E#o|a!!Qk0k%pI?-c3KDlq%qdO?A9+gBDe+f?p7lRw-Z08mQ<1QY-O00;m803iTcY7!NLpl*|9p{}E#o|a!!Qk0k%pI?-c3KDlq%qdOp^Rf@bEoTGT=UxF+OvFo|Ap`Cx7T@`$9bIbc%J9;gk89DUf*~XhbxEI0V``~OQ!>>Vh4`fs2q?HJ79Cy$;HXs(d@31mG%GGwap!ztyk>McINl2SN@U;Do13*j!4Ofd5ir&AMdfw)zfEWyTDvaBFH9o8sz4F)Oj)+;JvxmxG-m-UV!=bybW&a?h%1IXMF(?OR0qDPO?i*&HF$qX{&q4Bu>GD^`p7`CVZ5!7R0eP9-wn(a7G6$uBdoXWG+eydedzb%dHorPJWqoRkUs5FHKtSR34%`oT-(Tuj?j8f*~To#0qA1D>6Qg4=f%V?w`WFBdNzkYJR3;2Z^wiKzzOYX_l{R(@xIp9&8PYp)N_&p>gLhNi}aN{sjzIiBp!fJ@V#8v4QsnB!wgN~#)!t@1y+L%tEgX}s2Qt;Q_Wg#3D%5=X#;!h8BQHnsxKq}bPenw9uUv-^Cg<`5Kqnc7`VZ-oCIoe>LOnt@H$|FriHlaV7qZ6MmX6=dZ|$-c~DEK0h%3P?k6gzJv#p44A3^3mBt^3XJR-nnRG`?wQJcelUM|3Qbi>#19Fk{uROql*_S+?JS0DlXQe>0XIg>vWMSPjKIaPuRC?3HH2kzJoV&)ark<1H##``IJV{abVXtTh472c1{=r#A{qVIqAr-&`n{eb3xBH3SN}y2DyxU6^_>My;%?3^%aM`CMv9(0nc7%f&sTpl3&4av3E;+Lsf>+4sH!d2+AQZ@XsHr>(ZtGM_->myvs`XmxP1;AzzM&n>{o@560wPlg-sB7P5Shz0M}3%mqvDmHFyOW4>vff{RCjDIYafz!~Nh>rzyI5_B5COe;oT5{`-|8dSo&I_6Eq9kkK^XrB^+?UzNS7kC&Uet*BuHk;GPB($b+1+Zj9q~A5`SeG3J)$U6q?&TN4lcY^(VcQdBH~?C6|XdwvI=BQW4R`to7jw#d@eB=>BJSn~k1}ZC8|Z$avta&6>SmDbRD^S$L7ncSyW-FaMEg5o%nCIcXJK57d-L`56{$lzLa9v(Kmr1s^}uts5tUVfeTinUn+W%@Mp|?L~OmfBh%V*Y)7&oc;UON_^+<@|RtzX;?FM%5v%|8ICOzPUET~*q%LluD}&>-*sSIZ?tDJCvlVSV@#qa7Bf|HMObeD_EhusDahysiMj>bK9Ud)>u>aMJ{-f(`+zTT!Xrk2l%oq4q2xwTrseE7%tpL@_KL^)KMlaA)V)dI5*ydoByvTMGqHJJe&I!tMyS#&i_~Wl;gb1CB71i+p54x4=I+q|4~nD}g$&u4b3t{yd7vE~-&`JiySg4M8A2t7YGn9e>R@~IMG2;>S-AbkZUmi^&ALWLZ2bPFsQ+I?2kMI?*}rVBhFr5*{XQ)!q!qnti{4d&6{=DdyrzwiMk_wN-++x(snub7csj8rRk0>duL^dF*XtO{(7>zi$EBqsB-wcC>b%~AOI>I&_d!Waqa2)CMA+H=bQr#+^WHbD7;QyIKL@*!z#&uc#k<@wEX$>Dj&<)wGM~EcQL8f8HmYR%pFSOuu919L%7wUwcE{f}i40Yn%E}!j$8h|}77w?@ZZw-c7qdqH4;)kq{=4xh9qbnEk1~@pu}F8Lc<&uD)W&N`@tcm~hL|_no4I?C8OxozHKh*bO!dNfN9X{KLH_EkVTfCNO?Zxwfp^y5`~BGwykzKkC+<)W4xc*mAm%m^ik(D)+O{*GW>?)LH6|9yY`F53K9itofa`UF$S`gq+#7u;(1V4RK)})-;tAVYNIvUIrL4pcmy`>%&+J8$sx?Q4(t40OF}dCC1{3a|?;6=W%z$mf3Fo1L085cFGfuZjFq5F6_}7|+)fo+EPu%Oln5$vSL-#vi@Fne*b9xJ~pKB1Y%q8z`k>&3&aH{Si+(gVt>&LR;}OyDX#E<3%Z8}7a#2WL2D13T@@WVlE?&2m&fNdH?UxhRdkNjeG-Vf&a&>MG+_Djz}zJw3&#@N-`)&i!OrdsQGp-r;B;4H-@a9SaEFnaKsF?R+{k6C$+${fC0hRXQ926?-rjOFSY(0s+IIml1|3jo+X7O8128{QH^i~I0nQN?449nDFr#FM&Pu3h-$q}9rUhVcu6(+Jg`?X_PDD8G)e*SPT@Hl@u@VcP`P9EMax6ynIvs)r)M@Qf|QMi}3*jjLjYg}bJl3{SQ6!0LY0_|%k62yy0U(h{G5>B3K;GSBKE>v8jkI3fwGO^nXQAL>PR$<@VA$~_Rx8SmxH(FK(e`8yh60zL~bcoKUXp|wZyb@eP6Hk{K9{IP-qfe(B*K0d0C)*J?;cqVZN9`{?yFTM%lr@`##KsvPX0)Ppu_ofM;QIk)DkjF37NxZ4=+K={N!-Zn8k}GA!~YNC}@_OD(6CKMII8bp`te#84Y?1A31a3e5anSQBXhJwa|FM?>K`2jSq%rq^Kyp_2Y0?atrS3WvUS8R`The?^d4q4g9b32*t~N5Z(6Ao-cM94fWOvYL+!&;J@!=1vUdIq2mR=2;>!AAgJNaT@0kw0{6+(KG^!-Kf(1GQ|Lq(3ohPH$M+Lj2OOjrsQ%Jj+N+<8q*1{`M-G<)pXA1|Ggtb+BI~`dc;h5C3{>)T`Z17D>9xoDBpsDhM>qp`C}>}%$)~x$9JKCxnCsj1f|+gB*PgTq%u7?BRa$Jp7Sq5DSPUz{W(dRVOAH%ms}$$`KyQXPm1T~1rfV!;gW`|umQBWMu)U%Q7s6F)EBok}kw;@Az1!k~sZi;PbLc1K+J+6Yt6x&G$s_Ck&P!WYNnJ`_1P{fobOWv*+H!m+Um>zQ@0?@`H^quy-zAgvJudrkOu$@apz4!PeGk}Tw!qR&|EZ9yj&FxaqMf-W&Z>r9T5u|+Il=uAW-2=%`Rs?1@*CNas-+(+HGR^?r;qHqhwemZC9r%`~}^h;|cACpjpIr`$}L?d+Tzk2U?k_8O5T&`MRC-z?KW={NR!MQu7p#oajcv`G*jq5rR#>`*08xkeJvkYSJ*OfigBtl?ad(K3oo~v6Zb*sxoO5X%6|Js{=IAT6VTvNR5K7zzs@;j8b!P~;#XZz?jM4zyuV$o1wspfpy{wFVYgg{FE-4dxwKnW9RV-$V!~@+or~d&z0n=sO{%S_n!|)bS^_xQ7Abd&ogZlMKoJ-ev$PH~sY&Uw`{xb`lJ}rcZaS`x)lSNy>lUnd?`DD1+p#uZd8*7X&%p=eCoqJCyRX}2_7lHkYiH%kwo7v?nc$f(_CpA*RHfn4n>4iI&9S4Zg}(DxXe$Pf{gQD~EZIFRzZ0#L?=WijF;Mwq<|?(SIv{JzefaN2D`vV)3vCye$Fl#FKTatA!k|}y3)0+OXt$%v^NcDT|4P=^^Jvt9`h_2T7X(_c_w*D0-5GOuN=9afXh2!Jb5zm21yzZu0{5OfsEtZEu=IJ2Qk~dhna%Ya(EWHX8Ct={BxD;XG4)`gs%hT78i6S*cTCZFtkTpaQ?K!-nr&FA%JGm%GN}B9j_k@VsEO|fme(!+JMwaO{H74GO4~Q|W7{`ZHMb5iFTH$ouDO-y)A`kZ*Ywd{naiyt+Y2+I~F>QfhFj%sfhUP{F=u~n{HTpCc8o%7tkq6@5CWF1E|X}CfB^mVPyezfoj=#o?KhH<{@iq0j@xH&;=dwX>~+Q~I_*igCvq>@=P(NsJ~ZjDkn)`yc)@)AEYy5UO|XXR15cu+Zb!+C&JkJCQKd7|^X!1wJ`;A>wB7VY3k+wqKrMxlGG=0m!nTa&JMb|D+CzdGZ7!@2KV0X?)wlloYlaMS0)A)eJlWYs0!*=g2+qbJn9hvjua{8>Tw@0r!m+@nzt;77okrk&G!LOWrBc6g5qwHgOBwPPwoNm#4(R3cug1L|%;(WoI6`W~Df;4vlRtNqse!6r;dpLxFF>)JoK_R)|&=hmu~Jvk$2$JY-0{lV`zR?~r7`mMr7R|oYIK7(gL+#4e$Fc7UQ^!0`K|k-zfIvybom^6Xu5AFC3Cmcu4^AXvb`1tq*xZX4X~yg09qH#Z3AiW7@=~L8GTaoIJ`iX&1|QVy3IdfE@%6&zt9yOxa9LmUirhF2h2Ke?PK+a`>7YUyipg!4I$l9W?gcY#1v&w51qd^_gUdi_Jn4~B?l36ccJT3?pGLmcGuqG3Fi`y5*}wb_BuqPL?eEu2K;ML!7xd~1s4LyO!!LdaPIYyt{d+r!#{>5te!apU2jta$SVq<3Q~DNaItLL;CXUOeiPXUK1`efN9|mFb-K>^+fiZO1wl;I9n2GItcCu#th~K_`Zg6@|#KA5#1;(X%kg;5QC^E1I^Op&%pzWWO7eJ*u(?#(13Lg{+GzDw*f>>U~RPU2&pskwp$-K@6OOK&nJH@-v^Vr+-;m_*z+pCh+Tvq&mz>Foy+mPkII!x;)9?$L-=`W;W3!5?d~C3j)BbUA9@s{c4ToEnbZAt=#qI#rt`mbS{EW)ab4-iA>NTIKEmK8-kRpF`Wzb73gz8x5^}S1PUu#eW`j3^gWp`CQ-WxAwT$>Xxhb~ZoA7Nd(|*xRaoWSZEC=2F-CNh^a$*bE@#E>qv3M9WaxCoB9OKoEVA5I36XDq2&u^oLwkB^%`poK&i>l+?XJ@>xYAELefUX5##NU+yh$td5;Cqdd~bv-<+W~>MZ>UgXXM_Mm3Rc5C!1_n>N#6*lpSYKi+=rm+T_N0_^@n#LR_K^cJDd6(b;1N4i#GLsN(BF_30h+-^B)jF-PhvaIC->tN)gaug=4B7hPSh6`m3_9WHSlAA}6g;Ji|i9yH!xEueq{gc>s*Ihvi6{=3z~Xe&NfP(;!pz_xmZhulvNUSg9A>OV25th+EP5!u#uFdIwP@IwM?5bO6S0UpFv%5stpb28Xk#laLpkf4DHH7lh>}N}gQmfxG_iO@(WRv4GdS+198Zguc8uu|_!wgTFN&btkalRO+UU37>o64VB-vP`edeX4EfaD378fS3T!5u0e3iF*(YADjmfZ=!j`at#5QfwHt1y0GFDzh^k#lvw2w_0u-gt>;{rJ|N^_$ou-pZxeJ4Ex=>*}1(R(i}yvs6C*=x`x>SQ_(RDo~wO3%^ZMKfmAHi*3ngbG_t~rn+9LZ_Q6r58<%p9HNne<)uX8?V^~~%cBdQvNnOmyHmWT_>>zQo$GIdN^+JcVSg7z2GAI<{V);2UQBLvR-cW0V2+JIq^5npIig)();1IY)+Vb3+k?41tH$epaPH6eZ$Oml9(`_}OlW`ZTOUao0{s=yjO1)W-S-cS3rU1}T*Iud*NG@5aX@bJg6uvuvGJwIq76$i~TYhT{Tr9(rpxcMEgTAa3)wK#lX9E1}~Jlt3GuD_FCN{_`XP{w1^4BBFWd#>QM%g-kG>rjwy?Olh8VqHo5{Kp}mlPS_yM8ikF{>$6Ca~Ag86}o(I#ov>+t#-|8GQ`c@7z({#hdNu!H=e2)hw0gGl@dE>$P-2yT-`APNnUTWQ&W5^&E{y|qJ$FE0PdI+#E#K=p-47QZq@TngKYZ7<^MqPlDQ+h2Z&r+;;AWRQU1f^>V9Gh~wN&>GMa|oBuC5t4aXUU;(E{L{;S{t#99HEg=*4?f=a^g#D^DpozJ-8@y$2Om{L%CCvN!4Y0hmlUNQh)h1$5x64+iXti852b7I`hyc}X-g`el$O6mtnLNbgwtg_g*P#~;aX&}Y$tdmn!CK?af4IOOsoC{tmrl$=Z{+xsd#^mliR0`1%qECwOOK;z^%H=)b)HDSQzM;M9JKP(|djyi`f$pCtrL`Eu&(kg#0cM0~TyMpcU|)@f?mlxk=_E(?L_4Ywt_eW3)cDFUK>Uh+?ptN*$)6XJ+nZeU}~}IqpsFH;M)wRg<;dR!wl+!i_9b7>G`j^}}Q@680>QRZiqJq3ysng+)RaWH7sR6D^Y9>%+bFCs*e4Q>$LIkmiK6A%crYG#P*N%)ZwcZbIVw=l6&IbUXW-S7v3jgcH_lhEL)}x`YYaZp7A26V7-nnc(D-SYrhJ;nj2&kO~zk10O#j&^Q_8-n=(+dT^5Z~n&p_UTj%R6g5B>I9$HLin;)T-uY1olH&SSZy8AVS!Ua&N#;&$KEet~@r(6@#tuYb1!2*K&D?+5yDkDrW0q)|Gq+5Gj8nG79y>WVH>eW^HL-K=zXctw}Ruk!AhsRWg>mz$1U8^ZJhmbd>K%*9i$70xC0GjIc+;sx&zD&`7$3xBy<4hOV6c@v_lU}#P1H*)PLI{wp@MRAM3srtI!T6rXM$;qMari?`fCdHZ_JqnE`^v<(v`hCB$4U6g=WvWRl7Q1yO?`@0j;WbD5^i?b8H(G?9QGfk#m^1Cs5$lU?BkqX9h1?myjVbpxBc7v=-0C6H?^0M{r4RA=pEQ3TZckblllY?EF>xH94~m4~i{FADtwFbL7b2iV8+m!?Mt3%OTXe>3SvUbtBN}6|P(K+OU%A=)`A5Xs0;#!#)El3JWxq;934ZWC&#uA`uymS0p-l$aNvUzCyx5_e0?DNY577iT0EqyqUGnmP)#3KRh@1|R?cP)h>@6aWAK2mk;8Aprd-3vzW(1OPzL1^^ZS6aa5xb7gXNVRUJ4ZgXE^Z((v|E^csn0RRvHK+pyN00000bx;HV00000l%07zRp0mjladBf3KbG%s$@ut%Bob9v8YHQq(mZ0NRkqTkYtW1^3K=!kfB$GGt&lk@^Z)rXKX+Jne-G=VAuI**CwVXmp2HdvA&j2;kLj#RX+z0E&5*eOz8u>IX8xEO@9lR9mFEn|qvFS#>MhMDjt*xN1yoXg4?hOmt&f^JEIh`2X=0Q9RF$f9PL){6s4SBpF=>G9dw6K20I*;J^pz`*XQvddTT(TWN5xtKe6f!&xq;U)W)Nav>e=IOs%X=m-o9e%W0-I{uYi@nL#MNW=xwNu+G8Mx2T`^fwgj~o%EoR{q0^U46@U#35@}Y~@21XJH2&akKJV{5cx8|D42O}ChNzM26et|rwX5W($DLT9t`Y5(cGMLN7KDWx=n8Sd<`RNOCp8v<2bX{AQ{VgZ2?}?3GxpTi>=JIb+ciUHcvS7w-%X)u$DEBx=-Z(ltH?u*hQ%h9TF^tO#)77k|t)+m}=^fLqgkR-y-{QOLmWWZopw6)H_h;l;!ACq9GYF`pcQ0OUh{t)EXOK@zCLq1BPkihgq+idQQKK;PSteH;GxJbch&VaU+U)joU7*r$WCB1(|R>#QKET!$@v?UV(`PpEe6x(ya7WD@JqUh0IGHe+y%SxBO~@iWxCn9-y$&I(!=iEN@GvofpF6@HMQkNtdQVr_N)=C9cS8!@o*ym`Q-Ed)S-RUysJZqij(}Huf$J7}MsazUT4a^pMj8Z`=AZttJete>{5GHZK1u__kflDBqSv{6`OPf+_<``!9$V_{*tdEEndZQ+uJvLzYo)h0wK1N);k`do}z;lH*(4L=3TTrQfiEPRJSdiaa4c+zT4#qw?~nGf8(D%FPwlb@vci@<*4&?>V4zeN;I%32)%l|6m?!Idwk>J2O7-yr5Uw!B$mrPzJR`SIvw6By?DcRi{o;M&96trFEe1DjL)t+8VOvUIInGke-IODHqh_K?@i+J?Hj4y-LWh<9QehW@g;@JSLg*7Z8D|+L(eHL#uW8zW6;mOC-3K;Ki<>_La3*H`l{k}zo~G??$>4SPUM%5cuwo{BVd;2kD2Y=*v|!{%?0wpGI`3zlZxa=yLd98+d8!%M&-TjWK~Ec~V0w4`gE`r#KVq!||5+yj@_QedOTI__f0vB^O!`59?w_hOV=dJGv-*3E(?uGLU7a~Cts@w;7?1wq7v=GOCIrk|;-z!!BI>UiPYj$_L4djRC&A`PsQ(`2=A6xYXt1cyLF-{X^7}b^BjGs-kh>&R($azL(v0h42X19RWKuruj9faGmlg4?EZ`&Wb6@4V1^yWr?>Dn^n;HdL-uqm-rj7a?ymG!7Hc+7B$D6IqyHWo&;{(43d)D9^JAVo4OSi~Uemu6_0P`V^7Jc}9LK)qUj8nN*QNGLyYfmsI`lp4xRJ3Q+qE;|j*tIWI-Co#D^mBwc2#zq(ds6j_tIL8pbMpUxcu-1L-p*6JUH~wH=z3^`iBc+E-h7g6sUe66>yt!P|cHf^w1#(;>2k7BEumABTT@!)rFBxMrkeKeeF18STnvJ9D?peR-;ILmHF@x^Ljb9t2toc-i33}~mHSm2ZC`cyIOF!wl%QeOT!J2@Y0TO5s6^f>$%|JaEHLx1x?c}<&Fdi+Ihe1>EC=gzMb=&$^Gb;<7_E_cit@|WwR!hEgcYAO22O|KL`^^PE5uGoC{__zyP?yTm0(?gF2QeK|cuet)cy!_)F0r@t?|I_3|9F#b!n&obUy=-%C%3cByAQ)x>F>yY2uAI1MVmjGppv@RiO^dZChbY>?ZksBG*ez9Ff2lW>RfR=$`CRw|2<QT6S?q<_#{N^!!Csy(0yFX&s?cr`>Bdda|7cUi?!(FX%*_-^-lND3jw=P|~5ATXRuos8_b%-IsKjzEC4X*&Fkt&H~A0GieN18j$e(m=fj@B}?PYVRR;(UAk<;ELF@GFQe0s)t0ePI_xo&w2?sX_9AsOMC1Q@p(~74FIGzwvlI`VIbrm3jFK2`E}(o@FVHI%nywP4P)0^HIgAi?78|r+<^O$!c{Py!B7NynYMj@#w5Tv!Qw#^xIzf^g09e&u};;mU@E@17YpS&$pufC#!}A%8oFgN3zV+C>He(tq^RDG+_e2uVH#31M^);k#_hheHJX4(y}vPB#p~2Cl)5_22tSqX}e>4`ceP3s^f!S^r@h`cR%fMCF)lb%#~ayMg04{?LYl*b?GZ^{z?cVAbYEx+JZ6EfAhnxX+z>PNF2>6P1=R}mwX#P_l!=1JMoq~U%H|GT1lCkDK>PtU}lhX#2oeSzdF&%s{V!!Q4Hd4%ol9eY$XBxNx=-LoA;tCXg2zd4Ama@cms0&csFlO)&cYzq}}kS^`k)HMX%iqZtRIe$I26{egfv+U;|H?nM2161rjg571y%~5%f5@SLz(c!_lZVk)w7=i9Yz>79OZI-ZeESl8#gx3FYX^=KV0Vn&-yax==k2G91C4xLo(D3E}cr739xm8o1Rj`EytdXOkK<@Y2bcMq*W&w`Ro}xDxWCQ!TDl`uj?b^g{i&u$>g}yG7x(A^DpFEYp9-~YnZUz@^Rc{`~Q4PlP)|>(0t^_f(xGr*Yne(xV&3eUCOzG{qOgwSmzPG@OydgAquF)n!AdhLtnAfHzjvR=`$aB^`Q0o6ePsVBQbhTb|@7#sHlsM~lk~k$-LNu&$S5fluL_Tjbcxu;arwaddpZN;_r45)L=bR9<7#U%}p^N)B9ty+!n5TLDL+N}L=xDi?WGQ2QA+iQCj~KB*w7Peti}ZivaFg!*T=zAt@f1jrp?&(%gnGWp4tolnpu+t-aQO5|)bq{bLaLP-0apjpPR*7|zqI*^+l(}X%N2W-haE=$L%irA}@up79BgW*=7bW|o7w4%Gkngv2nb0KEdEMy#6I~_&q0ysK%76ajO}gX1c3zomK!f^&r%Z$uQD@Vzo6WpF8vN07d|I{{b!zsk-FlirhZch>&4HPi*Hj-W%&rSyK$K;{Q?Fs6D6=c7*BlfudOU(-M=Bgj^&7WvVVw2o?DI?TOw=f-meUKgi(d?~To4A}Kf*<)66-=MW?#ZW2+z$fNP-hW8zo3FA74m|*qb6NKeprq6`<^TTvhEQX+j;b>w^5eej3wv4IUD!--usU?=}KqrmOi?G1{)4CtUtS<{;(N|F1IsjkWo-9zD*bPH>`ZgH?WNkzAC$;?1wx_217Fn-h7FfapDbTPoX-%RYH5=rc}$@l2aRRwlMbZ;e%o#wYNu|;RY!?&;%{Vlb3H>*67B8yF#Ou3ColilW0_1elA@2~bo9JrVJUG)!fz0f;;9`M(V@Hgl@39|Lux|6TbXkRd!%m}U>Vi-Lf*wg5?r28;Ftc*WiF7R*Z0`J0zSJAniF%*qitA3H!{FVp@AG=Fj%2;JLh$4e9nR+M3_D@+pRa4u6_mZQdg>e|M7>#_{NYX@mxs3=7+Srb9GASzHTmZ7)N^Jye(`pR7LC8R#*Op%gw@G{PjslDGG(2j8WVYwNOrXZIsY}?U0!SDh;@<;3I%R!$??kDcG8y%voU^g(u4jQG9THq9V{G9;5yN3ivh`0b<$rwBc9%SjCGi?N$G1^moi|vi@?2G3&Od_Uw6;5;{GNke5Z5;+C_zNx$pa#Q!7GQ;Pb5g{?_ft`RR2J-6rLOW}k4c-XY{i_bzGun@9nDHAq`mhQ8ue)Fe#{Un(qqIP@luw*9mh5@V7+QUZ*d34|FLbl&u_s5p==>zht=p?M%(^;Z@tcf0`1a(++5_nYWv*F#@Mid{FhA*xL)RCKGwLPiUKTS>+s;K=qvhE#QTP*WInofUtK>R`BSIPrh9t{I9IrGU;Gc`t|#q%0y_!taCW*mV>SAX`x>INB5u&2vGG!+ooza9f_e-nGKIT87am2yM=#!Todc)aO~J^F!$2MKpKo@If5*wRh=9B^H1+0v>tcV4rBayY5)KwbiuPn#9Bv2~mR$3L%Cy2?|>*z@4w>pSnMkTm!+>X<==0Yvc4T{ZOfSyFK~pn2M6~oT_9#c4lamY*zDhB`dH#6n`OBCGW8HW2XH8*(r(L>u-Zsn^tDVl4)lX%CJfE}k%VlX?{$pnQMXEF#`fMuWc<<&06!dkX^fnWrhyGP!Q42Eym(Pn=By2L@PDdzVRby}?;B{mFz}na&s`;^ZsMuiO!|9WneP0Fy9o=RSu%zOLjX*K-7j)aNjbwWbg0>M#8&Ie6q!JB>VFD&eo29B(Aom?E^|d3%t4N{rD_+M@KWCo&MTQPyzlXM5S3vz+vI;J@y`e+OwWNH5-^eQk*HFZ-F~FkGX{k>ew(G`^EuWJQG2w*l2+OMn+ogYOmUfID3kqFyT*KyLURFFb=c$+_6@)K~?7iWNI;Yw4%eKrSK;cOA)5qVC(?;ZGMV}(zW$x!M0$!+}e|qTRzg+|*UU~eZcn<0el}$gs^8^iK&5l?GKS6Hp-YoWpj}Enax>hX@LH#1M;wM6Bbm+F)yfM=W^>fzwrkgRKEK~g|gQsqDZ*gx?g)kF#BxL(KoWOSNBq!pc^-OpjZr-RAkA8!FX_s%uK`QL_xf6ShNB>SvL3$pPXOMoFKFi%j0)1LIJfd{=(_z|-N6`@~ScjRoZ^-dVY5&q6cf>AnxpBO}R)sArXf`olbM@y1E*ID_V?{cZ4QpgJTmP;{-&K1hHIc}pOzii#u^aPyw@r7n{Us_`-50;Ii=zeuj_IiiZ)`^Y)*K@9daphc?(}F*x$A^HuqA0r#$^@^Yz%KZG7!P#E9PYWas0`K6#nu#RXdSCkMbCHC-d)&!I1R}M9@EQ>Wq`?so?m6Hk3PzbrqILsr{j21o%}Sq^dR||0ueY{g=!~jI%HHzb-}oz9+XCkjZvnauWyl)TOkuTQCLjM!CIm&XY4Fj5=KM`4X7voJ=&$i7w&VHBd&bOZ7*Mu(tZ84W(?7LR71Lw-&D>txReI^5cQE#=iaGzp7s1WwTQ16nEKBlXLie=ws*~QK&sp@Ke({kzEYOzQ;cFj(K57zqBUh8xm-Vdd$Z9`aFLUeP@2P%{3M*$kRQ%wGe&ggytAOkkGhsX^jmz`fn1Ao4P6Q{2szwtWQ$@Mc0W_{n^W-f(3BzWP)r74MYNUOHd(|Lh>X1?Fj;!_N8kQ1T$-atP9w>>-L+?ZfXC7OgIG4H=mkcc`+-p_)h;Wj;hd9(fSxm)iavw<)d@7*PW^Klp7hsz>qROsGVy8UAhp7(NnIa^eZ0GlACvX~Qi-sp%=Q+)~vX!ZGMc#+44c}-D6Ddy{ipfvqT>vzhTv*MR8`pAXL-SK@&wFLnx;blh53&=}XwtbVYAYiuePx<5)I9VOdKG00ywQiJ?-Y%2$DSv=`@uO2m50djfy3-rSY!%e$CXzRQt2qrGedilcr6bP>POX{KOao_Q8;7Xvs584}@7}CHGS4dBRCDb`?j$eq`qOF#lstZOZy)iWelj1W|F%E=n*mE%rs@lVQ9oz>qU$XaCX*8+rPG+N6DSG~4&7(LhZFl2W}d@*&Drn!XgUG>XJt(e9Yvj-{C<-hhl8J16%BtvE|^0Ly7-;|`Os?*!fa7zSyqzWCGz?PdP(Z~4IuZEAN|%*M+327jmOHd*#FwP&)pkb=cL0^MY52zC1y|@MOm3$}Z$xh4$VA*^rVSlFsGl8(2wFabrZq~XOb4VY3)Tg)ClYBNa;d1}fl`h+{UC-BjZzujT!ETqIAKfyW%Oje$mHCHKz&E|v)riUCH*P*yKCqVxQJr_LPg{xghYgB~TW8A>aLxIB&;3aB6>=$i*RRYaz_Ys2eSS0g2Rn5ORcWLD&3_jm?_kyM%Om|&$wmGpO4{fj3g_yF#C6cYesjgLA#bebxbq#kuHManpuu_T^bBx+PWk({uau=&Fv3`@l-3%;<(z$B#@=kG>3~`dTUYh!KOa@ij^%`Z&A4XV0OC^9WE4Wo}S`_>rHCYHf^7&#sGVUT#Zu`_H%*OrAaHanXvkCJU`P2`8lzjkzFn<$g$2G(|L$~Z_3(&D?Mdw2-;bixK{yr<=$(D9Z0`1dSl&zlIfWD>x`7BOGuw=bAXj=OxuCSH0TrVO|RkESEKDS_F48k9puE+x^9KvO>zh{rR4^l0buQrlxGB82XJJ-9*UcRvP#T6}wv+qtBUs%)U!MgAS|I`5s@2#CZEncBamO44{bYv0u=E@#$H~70UyeP$c`{Nu4rJ&~0JX#75$(D@blg%55&ylrR@=4aFAV92u`C-t(`eiHdSGQ+b^RiF>Kc}MWX!UuF{Nv3prt73iWv&WEqa0CPF*4C*;hhTnRYdmAXnQX7enCVfMevIe%w(1xbq%DiMYs52u7i^ik-MN$vTLZHW+l-;Vx@`DcnnYiih61+dBW%UB7)qzI01?-YQQTBv`R)hgaZvcRA#xj)~CWQ>@0vf)M0CJB?3&ctW3eu7`Nmzc{~d3S+<;?}IVRx%2TR-Ep-%qegcogemQ7widvAk$G~flBPQg78XTjLm@Uw9OYBPh6q^qZK`9R+6&b&YxEOLm7+!BxcP5|?-s{|c5>*~z8sPkJ>+*`k5ItVpBd9W@Hb!zQm>zAElfOv9jXod#rrOF?Ex16Iny<XXb&Iyev2SaftC=lnS@mJYhoBi+YSQ2+P!%75OdGT`ZhzHZyYs9(r*p|jq525|O$4CtbMANQ|0?qN*0c4>E;@pAN0sjCXcH<_@2Q)kjp$l>w>&O!dtuPG3w{PbSu2>OHe`iJR%@}uTIBVhNd+zeZF^bfXEe;v2CrNNdmlWZwhp7)Px%7Plj=&;O9YOoXLW&k*N>uR-+#aIq>mg!9F%b3FNb;9>)FEg!FKpjV2Y+4qUwM7K{0P)Ak&zZaxAetdbJ@^pSJwP@-oDaLs+Tezb>YooG~Yu@XNG_d7K+`bL>{EWGQ#$VhNx6R&@3DUvEV=)#OA5=d@!Z?mKvCg|(3wd)!!n1%@Hhl4!M=9m*t9h$idVX*Dfi@~QmTr^TSd6~q;xcJd_5lJ;>N}^JHy~G^tSnhmN5J!w>;PMyeX#2i!Y6HWpuvFD*s~=v=tE>P7Zw-`(BWiiKh@C)`8$)f51*6yC{0Oc{6rA)XUj^HUdJ(jd3xJ^%@XuQF7$01{Gyq#(0N|e3JLTr@!ej#&QZzxxp63Nw>SEnv+D;xRd$o}{fZ4sb9<4;hQ0p%L!6xNe44r=O$PnL;A876C4mH_eBbH=@+n#Kbaph*C*J!wErtHa?s8(`4hjR#PgQjUXUzLQlGm@uOk{$RoXVtvrx;&nSXked&4Nb)XFD>K)41_5b`3&z>ez6hVe8F9x6-)r8khbiExZ!9Dy;*qHY9A6!fFLDj}&I(3U=mHwlEcM><;4M!*#CVIjW-1L7LYB3LOW}E)Z);0k*P+8Ge=A#vXZ^zW!xt)zoad_f=^5J9AwMqK9b?8|z`A!qKeY7Ghp46oKAjfBgqeCKWw|dgZw3YUO=m^2;OcoV$xy(1V23Q&mT)=+aHkQu)fP_rmfs&KdKu*fGqH%q4#-^aGf{sZ&NIq7O;i${x@>#)8zNAu(TeV!m5LE85F+A^p|E%2IQoyWIHY#}d9ybtb_1j&Bk(2K7iBWR@npAwXX|VNW)X&b2GOD@VzB&=+RYRyQlu!}>I(v7Mav{hq75w&6AMbq@R;ZR9*x=S64nEHlj4logeh0%YD)$eUdnT;6WXBvq2`+epC2apj`Zf~bcv&FcJoBN{kdce3&4c`xtXd>6UzB{bNvC2aFTKI~`ny&KCr$@adKS`)b-8oBOs_og{5bf7Fh92Bd8`p+FTOKAvUfTw?G^Q1Q9gKCRKigcN9+97w%;%w9((rsCHmGqOVS8O|=aTa|@tAB8sXCn(9v;9X(?a+s;aO$}ldX<31kMld6Vo|?|=Yd}}7iy_*)p|*rcpfbmp-vSKlf8Ql=x}Xbq}_Nva`7GVca3Z5aO}`|YOg)&UoPsOwcDKmhed7ol`Ka6)aggVA{R0t@t5=VtS;o{*?RTjRZMsr;G^OE65G|P_i#q)4Hhid^u5)}M1NI%s8>~U9~I8u44QfL9r_B1X|dt=g@}pyUH)#K_h{bur&stBaQ|84w0=7JieL%qnN5>vFmtJ*|5ZNp6(h{hKhNSwztR6{jlyd54~LRtn7ek;VPbt_2l|Jz){B&_7BL`NtEfVpXCKb;V6l2*A?C#XhpImGV@>+EinW)K^P`*kN5z8Bk9Eka3063;q08)^^u?F|t(U#ko#tKjq_va^@5JhUjoI?}3Ym%@Hw*|!TE1g?pD^-0bB?Q9JtiPjDr}1o75xC`J-A2PXmCJGG$BHd=Y67_vci)sH0XLV`*qz*+=pzh@My~71p2?<*I*rq+0w_%C9f}M-@bbo)?qrO>#a99GvP)4X`vnE*q?pXazeX8Sipbg)bATVus`?lU%#~ZEgJ&e;x~Tm#{O*7D*X9gi~#e@<0>kh=pVeKvX#8f5s)u*Tjt0six4w3U;&ifI^E+F5O@*=uLmJXcvGV?5u+Xv{0N`4~ezw6k^l~P!T;kxL}9|?xSJ|^aaiYxKP!D(Ydp{@_-j<0U4^Z4SS;-HUv|zS6#Cb2_lJem!Zh$2v^@y%ML*!VEYqqO<#&7shkmYrE3S0Mc&GEDy%`u|>?i)OsdV2)fPQm4NY~do4c}^|C-T$x$qo!1$kUH|~*Hkq=K?UB66!fn0RE^yNWUV&Z*R=5h2731Klezr815gZ)8zRs?d+KCZG|G;s8Ac6z}??i%s=1pg-*WCYn-)O_Zt+a!c^wE5EE?ZNgrw}sNUJSHJCBSVb=T}LFpQ@5mX_1I+uhC1^xVN>s~pJD+RU()zPBQ!GoE35{P&k*!y_!1>gw^!MFjKa&ofv1m&)fuY2TI%_e1DgydqpE+ED~F7Mn=kOv2-T-?T}omh_D?3XhH?Rv~{P5vh2@iw5~N?=I{T#^ZhhS+Jn6A_K6K2=F{O~r`f%5p1J`u?{Jc94mmEp^lUeuhxzVT^Urb(3kJL@w;R3~gnBOh_2ge7$^`aDmDO%Mc|0)daP6OOOyJC`Mz5d`*{S=bORRpA)>t=&tcEh-53`}$}5P$lY&%?&-VU4sT;TgFx9@zgg|+*{83-J!uUewe>F6uE@l+>7c8bcpNSIX*bVQ#Z59-(b1vt-fJ^T+McwJ0n65>*7fuwmv;+@)0oAa*jJEr5p{CD6BJv`gnKVG9C$8|`MNE7{?iPC17X9j)q!D)^Jx&FDR-fPXTQ+*Z$?`WYtUi)`ubOca@fzqEq1As3rN3lv0cPF2f1hb)DQ0D^=&;gD|Zx7f8_QPa%cWB;K!l(jy=uDg;RIDD!I=DqYvhvZpWbh2Oo#3{4TLTdsBj>ygB-fEm4*Q-|X2F>k-Y1(Qo|S|1wHYS@M-$bgNxb7&A+_q4cDfF&C1h<19ea*=RFDv*r@`8pnpig-I&6qe@%b1u~x`v_eI_Km&xTB2;0q-7qyYXS&=B|wHA~Q)gXv#mc_Sl5Ji~qpr;-SpJw=M|F?I$S>W?z?(Fw~eoQle^S-1gHcb6^Sz(bh`ms%V&L2|w$@!7>-N+kBSSNXRj6r)q&J%UDRy%(4<9W}w=Si*Ymw)@pBFvEgZBJOez?lZquMP<{$RNM}{fEreod4YeS`%P!t2Mn7T~;WQN?mL{;HLFcS=)TwG88fqsm0UGi_SCdR#kr;(TL)C%EiWJ9A#SZw!qd@ozjQ{J^!lK^dcf4S*&^a;QIx<6T;LV)lbt-C(6dG^6BJa%r2I1N-zK3MTu3^~2-p{{Hy4OS@5Dw`#Re8%JIHzq)bB|2{Q_HsP$JDco1J!O~{BW69dy$*XYZp}_=LPa#HcOvBjeHrgZrbfPG*AdO(f-1-el%xSK10Wq4(kH^8;6ULC(bt$9hYGMr!H97{U2}Aec2wcw5x{!ocEZ|O7X1AbZak4`@n=*-f?yhccE{2J?1Rj)WU)r2L%vYP(Hl1D}1E?7~^k^Op9E7g@9}ImV?sv7=LZ3`n%H*IbS$*u0AXpc|f(iaiA*=sJ_eR=J3>!_E)y8{WwH}V_OrN(|P>KrM*$>MX%9;tvd6E%MSEQ+xExk(RCT%*W>m!{5r-jx?n80avFKxiVZKG{te^9_saNOYA5Hvcisp~Y~soLGu{iAw6Z|p;-)zNRP-&Y#4f$a8fSw#`Jh<~qCZ(AvV>AZA%IhlAM)q%Mf=MgW=YT{#={>x{>^pIS&CIS4T`9dOZUyd^IlG^dHF?@4!dSNC@{3f^YVAy-aU{-hs(o~`+nwQyfJB%wRbb1?$i33EJ@TeczlJT1L?1R%)b8dGe7!}>IAa^7U{2McfbB1brJJpcEXj%OB&b^&pzjvA&hzO^si%dJeHU5weUefdbZl8`i6?>YGINOl(`r|uW=oe5YXCFl>=_f5lJ=e<%qF>r{=%KH}Cnl&WXNg{pMg6}rAKRRH#G0s|zgElQ#&g!+O{r|~O%3=liD$j+Zr9+2*X;y&Jb!Lx$5Wpfb6ci!*q8sZLY9q`9b<2ix4YsH=>B!zCuH{VNym#Brhkj$}c5VK>2`oqnFP&wbhg@pUz1IDHZ16B!DJy#jeMotV+f1=Zw2AjR`}|R-@;Zf|lJ>NT@7hIuLq5gg_FkR0G>CiWsAjew^^bpae7wVe4xD`u!aViBjb)c-HoT_88}%!udIwQ|qS&MM6gvhyeN-BkJcQiBiB)uop9za^je1fmRfY)mcViTF!^(*n*!{C@#vzrUpKnn&6GWn?X`cXa#dYWkDU#bi#w>OJODk$vl!f@AcFdMw{+tYhR#S~)!IWcfi_}EGZ8RnSBd+@7LuZ}Y24%Fjaa+>ppxx6Bjrxa$N0a3PXmtX(%{#a>gE8ReVA{8O^&|$6GP}p7h1eK7Bf9g>152Hje#fb}at%i`fj2q3et0^Yk+(K5~Eo^rW7<0xL0|Gw+@;%$(pQ33wlJzRz`L5gYzgdw1Mv!~Su)@8Y?qlL|?RsrOFu%*VA)nTFi9CSd;L`_C$Q>g|sQe}0==MNF*YEd7OfDrojHtA27mrSP#xO0k*eJ!{T&>81Va|L2%bM^9E>Q%a@7mFI3VZu8XnIqy&DA7g+Qd0}dgV!U0tI4j4D2~oNd-p6^q%g0&1kKW4yvYTc1Kf`{OvU1Q_OpaG4$p>eQXB~>OzVMFplO5ZiDkUi6I4o(c-PS<*Nr7R0X;4Q#a*(q1Ht8qVubRK;!W!hxk36F#ZqZ;C=fTs)e9GBZ9jZg0`0ighPyB_Vvef6~Jcx6BLRB!n?oz1xp?n4$deml-$Fo1yG%WUbR3Z~L%&5CfjAMSUIJo3waS985`W{O1d4<=7Z2m{fA~taPFO#Q!VzIjRPq#Y((kA7znOZmw&$%1zQv8X4rz;m5+&4kqa?#UUk-Uza&j9Z}g52gp;b4Cg4TM}Lt&!l_Z>*punCs_9hq0`_s<0T$zb5o^q`YHai54qA^)N`c+4$}oCoPNJ&4!FJOV-YJf4Wr;K}eGfls!`ReKwJJ+IM#d_30qg(AOseC~yS1$5w?UyhCWbS&FC^B0p2#Ho4Tym|J|aQeUg5CeYgZqC>*h(2K*OT#cpfeDed5}sD8Fi**S{O$jJG7HGZz17qd<2m!Ugkcs)>Y6V!JB;xhee|8N^0e|P(?gj$%#H;hI)iC~k=yNx*9W-cPHF!Ca=Qy12qn42K**0P{JSzqHz8BUDtPSaqnK=@pQiq%~&Q!LL^CQCJh}qn1?s+%Fog4fS!GO(i+oC&7Fwc_d=De3N6FB4UwksGPqA2e+OO6GFg}>IzBOo7nkDkCsY{x#?#Mm{&e7N8gSk-DA+8rl-<^yJV#1u~EkcUj$oG|8I5u4riV9uUGCwU1*vm@~SUOu4-xK!QXwCgTTMV&gP&adcdV1_AP0VhblSi5psnaDIOCG`4f@1&uhTNE1(V*1ok_&$Ye$*^3Mn9nByK|kmOdeD)$CqEYhFs;fk{$r<@U3YbNrZAH~Daob}8$A8uz@{A8D7uO#<9fEDo#h!hTaC6Nsh-ZQ{9zsKkCVY!9zNKN{j;4aptwOG4+fTGE?m}xd3@+_wO`HCJa{V~Y!dhk`RtjjJ0S@aD9lJ)^*I%Jc3+i|>e{*AZe=m$K+elq`-(%^YcuIoq!_S?kxpF@Y2rwUU(Xkt9)zMV&BOx!0G-2JXi6ZiS626EnUvD55V7xvrV=*PY$y~m9<5OP#InzIv0W%EmdR>si_-&-oHebY?$k!1({*B`!w{2rhjN3u_$a@oAjImJqS3{{&2tLQsjO!J4+ZdXfW-as^4lJ&S}rV`!qO58nbtc(GM_YB=9{6qyy)>J3nS)d?xu=C>>?|%TvAR$2fn!CCBqS`MTl-#sAmuc}KJU^_wTgCyqeBd@g0;y@qFV(GScGc9F3-ONE)r+5Q%wt(%(<2zSZeSJv4h6i)RVtD)sXM9;sK93y#v-cGG5Y9e?xl_n_-=VoGl3^H6UM7=QWpvUJ~E;B_|lArD+qu`96e#1|ElVUxm;K;Q05s$M86V!H1Ir*3qCKM_SeGHpWlv7pWxYO=RL|_=xfRr*9dX`I6($#uxN`5}2g(roFrMQ-mHF84jvO}LKSR!!W?Nz|K!D^@z281xc>EP-K1Du{oc6tx!T8p*lCL5=2nbuc>7EBqU1(ywI8KAeAAY)CcQO9-g(G=}SY$I8{;|m_vvgp#K*M(wg1&CiZGt@UG($wSg^t0?cMMw#!t+LXR?8e?yFKjzcF!Nt@}5An%+a56Z7|U;$L0mFLKWJ^XnGUAbst2sn(r%{F5Jcdpt>|0q1)FZ{v`2^1YDSKmR=EJL;?p9@^&kjt))9-%O%6pkLz5V|6YuV8WkXL!FiqvUhuSGU0Y^qv7?>7{7<}0Fl0$v+p;U9C!bV=j=ziD$Jg^?tG5OeZ_+M1>!P+^Bt^Mp7$b;*@=CyTbTt%_Fa9jEstk^X77>aUUELb_bFC`pQk<_R_&`ioRSUN(Q7OY&On|MtugOlNDjR3FB|&IQ?J;g|J&eIQZDq}%M?2*gM9uM`P=brdGK!MRmUgi(N|2|2gj)s`Sji+^c9@%<0~W+z*(;_x`}>_(|(0q8dS=XH}+PngH3$@Qzr|iO5D&b<*A9PS;$u#z4xE&k^|0$m+!B4Lmu(@#NuM7T)4Yz&$g4xkUu+65V}4x4@Ne>IP<0y`)A^L=%q}|YhLU|U%~l~Yq&lE2VAU_Rup0XaOTUB8)*~%O=(IRH=c7pw^`9A@|~yz`i+tJR(e)L7PQ*f?#YzH{B=4>=y%=aY)Bt@y((J>dD~0PsdJ5UU?W9n{=;7EpR9WRJVGrOhG~I~DsOqdS2Jtj$S`@oj-Ec-HkN{%GtR`E{&$}hIq>+37t!g>->4Jc_Y0Tc+3!KllM^b)c`NwF4#toxa&1+IwuN+8WI70sf7T<5Y9t*P8MA9yR2X?>~zSo|Fr6zjw&QC?l_!HbuL+muzpFmf<656rfz`|Yj$b*F9fbAa>R1vy>JbOP+g!J%J;)z{!Fks0JUIH)?q~py-yk3VTAL^2{dp?X;+P}PcWeg6tM>{1`_BLUgXjl@?%4e*Dj}d~y+c{4CB}2=)#u3h(S$z*jCY$O(YYm!4wiSzhPy;C{-|5;#ZScypd{?F*}}8laiMVVXK+>y9M7mb{Bb?z-;0U|-yU+!g|cFo$qxIFuVkK#&oIoJ_?~vMCvx|QjM+kl6ezw{leZ@VIj8>c$b-o*H{N~vczv~nT+`GTiz9w>brNA4x1~MS)AnAZ^L=cWt|ukb(RG?YpuDl0Q0$tHX6@v=igvNvTE4I?U2l%hmMN(v1t`n}Gp&$sKmfB*Ep^|(FX=UnI6d7bC|c|ET|T|S&=N@@GYkZK=0on{uWtQ+vi|ABx<;`r0M+Uw>7aPj`{m*@E2zJRgKRc*n^&T4>%D!==h`AjRW#peV26A~@F+#51cjd1F>(gBE?s8y4-I2qnHP)?}!vVUV`hC&I_65@Rxbu)czsW<^`_fA!e=R?GgDv#q+CIuA;7-sO-pVPyozyQA*Y(sO#*Ha&$gc2z4t8Rphx)zv^PD`pT{dnl|dUTHnBVBmVShEvD^{z9}FlC{=eRtTil!n1%yg!g)A9RIKQjO8>hL{q`9-N@7#&Nd3)nxVSlo#dsdiVPCCVF#bN62brsOGdZonb)5Enr|x5Eey}B^_=*|f4LS!3fZ_G`-=E&${1E4ui?sJ#kf&|emndc)&`Lo2l8x+&db5%8Q{P6mQRSL}|aF{FNpx*+{58;n0mMNp{munM{uZa3kcej_r()_+x`&n^3ZU3WLLGw?Jox*wh{;|(*$Uh$f{Ek;G+lK2h5qE34vjE0~JC1!L#ea4+)ZW=jR|rIZIqx;76Lo(CMhk&HrnhMw$uC6v{mvHsJrDYc^OmTz^nBv35?X!E@#i?t#OJoJw3PN9Zq3H=ooY6GpG(T%bZ>qwr{#Zn%)Frd@3|Nojwk#o)(>K1~Y#Nm>zyz0H2=IU0+Fx|NKsW|43+AA!r}Eezi;ubwy5w*{bX!*e=-bu;KvfK4PW%Z|jTUrUu{g#)BmP53%1_@<0CxiI;|w?(xhhl>w0-GqV%NKbg{cZ_Zu*_uNDP$IB?zAD>)V0Zj1v`L_2s&%{3WrdTBqT&6-gFB|h24SRK~0K)VbBzSJHv&@6-p-3G7fN%6N|LQ7aQR~NyutHu5fs;J+5Iac}XR}pw~TvceZK;7)oq|i$QV1*%q;f}HVv%gq(26W@gp@v^`EIgFOUX!Fq{j^j9<=6`M|r^V0rFG6lPvy453t)v2u9u3p^N{{^D;qCuxaZM$yKhDS`UgueO@BFjALLk0>A%9TUeKBvkG`9$LSB~~?-GSF3>ht%96+`5ukbSaeNcwNi2bAyJ>RZw^B&yZg{>e~16veO5Opg3nVwBZWcQ@^lL*}JS5sGs?hI(RKi9bmn*ZdG0rC~`IpR{O1mbt!7>46rI94tk*jxo`nwXs9^Kty@yYaqy1KAMqDpq?PDSon5MJj~d^g1n`e^eQD%eclZ^)uJOjSBF`ejz8sTeiKwm!AWCqG{QS(osKnxx4eGOD>#}7fN^9MLI{jKAu52p9j+sdo0cBvi|9J%YM%Y#^i&i%QlVM8&J=;^2>7=qpl-blx3^Vk@CK~^)I}PE`sCK4G|})&K}W6^SjUA^)90m&&v|aGgF&`u7f>S_}ePdIgX8!+$LtO95|`F@AJ>|sOvE?x$D*D0FghjTn=@geV?AWxaLBcti;AUbEG~3)X(#2>b`x;ZTej0a@2`FFVjZ(5ci?BVLvIaM|7O)&DPWccvazHaN#|2!rp_GZv3mL@7cq*^_4m}Z)**Eb_i3soal?)aV_iLcv_s#U@7gKQRqI-&(%lW8^^_RAZM>jY3FfL>rwxd(k5GYtNleOsm^i%4-jHo|a#fUs+Lw#{~QTc|+OJR=5sFyM?RGTa>06+eC@jfqH_xm4mT+x;-r1ejcHO2A7I+PYu1m+R!mATS5KKulaUZ-#gJUSrkxpWHWP2#hz`Z)zcgS;W8l7~&GKR0;A5I&v<#Ch-RBh(8w2@EB_$cN;<`q%7Fkbj7H<9%-m;GoFJuUS$)4pG;5bY&5U8rwv$wc>c9KFdq{VsP9by4C(Bj;EbBu$R)#TffBN_)7Q5GH@z`nAa(ejc0It82|bU2LsDt-l9Faloj>Cq*=E@Dxd8Le&fP=135%AVi2B)}$cmhte5i3@o88@ydi6f~_pLDnpw7c6`sq9B#GiSYf7iLZMaUK7cM`sczbpcxzNQ`ruKS7cx1P8umVn83JDX%)98c`OMEXjB=u_do9LE#=8`NKw!LA)gJeq$XUuC8%FP<7K2cpl$i#uq~kGX~R#=1Oc(-!q|C&k+k^^RIx^C5P`oKxx^>bFvJ<)x1l0MWu^P#kBfYs>-MnackSBsn45XeI`SP#7pYa{d0T&*9XuXuRnKEC#6-a9JJ3r9!=K6@%k-?*-mY*0FxiDcgw2ac>Z=u!qwyXa5KQ8)7lfqYfrTfzvC)^-XT4q;XKs$ZCoa{YJ$3dXIaX_MdFj0SFKK!BZY8BSk-&oB3!Q<8eUva|3lrsJB%N?yOk7&6VG`{T)qT|?|s|})QLPJlgp*>;82#~#Y@N`2ZH$ZSdz-Xcui0=T@1+&!@i!k#i<;|ZDuQ(QgM7^4c{IXn+iCdJhe-MH2%qqNR;VNJ}8+z3?4s1ii?g?xW1v7`naons~y0>~ky9*G}kx=WyW(T_Rh!^j)zIcm8qyk(FvlXk255{@V0q;=nx{q-Xy{h!{c^1Jzb+xDt*xLKFRFYuga`|udZ=#pWVdkU%z_MSORC5~_OKil(Dz7TZ01B`1lP;XbP%^Be@qWzBE2jF$A&x$cT<|>B4rS%IDcX0f+zTn$zVkNZtY|p1qPv6waTw_!U>iGd%JS35Si1QvTlmET9rvImRs<`fNvD(604sFE;s`p0Yc-p>qq#THTdXlBcSC54g^-3O9(9XHKZsB-4ojr#g-#S8imuTlg6|Uo(wfhd2O*(^X@~?I!bJQJfCCz0YbAu_mH%Zp4s3$pylx$t<0ZQLm{1)eD{nNuE-2@~=z2WWk?oDc>{z2{0cdCSKe4(t=DZji1c_6}H;{kt~KWH(zDKT$Goj9+0zcUC{D92mYdXe($w?>Es7=}Xman-$CZg@Vp`>CSOb;(Guw|-_LQj2+lMBl3}*-J1~smLxfit9D4A7O|G#JzjJ>R};?mqw+Z#cuG1S04I&i%E6=h&XMJ6~1sS?)r!F|=Sa^ug}V0P6;5~721CW|LcyB%I6u-o=duGwLP2kt`rMR0>e0DFOkb5FVb#|Jx5~Su`1y0IEqkuTz*i-G`;DZ$xnY--$FASJA+Vi}J76`g%dBwCQAEub`gX1>o*6;TNlf~!DOl}C>&t9bMap~HG_vD_VF0XJ5qELIjTA3LH11Ukf}{By=9;poe{8IzuXPN86AL$P_kPCtdC|1^%*5hwAnM=zjzztjMY;VPLlk(VtJpM&lIqw<9kO}#I0mGr=b9Bs?ebrasz8fuG`4^1cPApQ&b!Fb|0XNud=ZC)`ml=WILqEI9$FpS>R@DyWwgNsDY^Oa>`Fv)BWqf0tKP$C;Z38FR{?bHvOB26xVI%MAsB)7Y}kvukVmPjQZo<3b}2PiC`By9KCce>O`HZdFfb}Ns((r2Q;2jAB9?b4`+|53==y(1Q^W_$}pN#~D_sTWK6UE*MyrLKwRA=GaK*B>4D7!OQi&mZ`c_|U6WucRb65vGP7JCEt3PQ=BjS^h6i+WhSld@3tv$Z&!`u2?HEY_&0Vor~Qp1(#G*@Yi75!I$s5%k6)t#jwk9gIb~C5dD#J^e6-R}s;c>SVu6A4^C$o1$V)8;O_BX!T1i3MH=|@wzX&mM3**K-uZ-d_NDMe#^KoOL2c3RCgvY>y!LxM7+WZ>ic&4aoMqw7pRBqe>X(*^H?ggR^*Xg$=K{=08@r@ZR#`?LnOSYj-oUiyg|1WNPCy4{8``9-rfBiB%syLpAudepV`0Kw?#_?nO!&=9CGC};x3mZ!b9KVGsj3wHDR@?yFI`^!9diYyTovkw$p)WhDTv-Hl?K{tA#GM_$;oR^03LUtP)BbbR8A_8^_BU9P)_vb0X5K4qkU7<|g69`<5pk~3?B)q7YmQu=b3|RseWlF&NF6OvdzVWuyAtwfgttqwqM4XM9F60gibX=m8bu&Q#oD~TH;OgFlZx%~B13xIAu;cX>E(O<&CW+Ju6knst}Pv300#u@L@R6BPzBts6IR2jaYCJ=xD&UKvHpH#|$~<3{A~AWG1p+PynOI1DsRr0p{s{2+Q}&Va6H}JZe}5DXwr77_6Cvd-X3VRvlv^DQ0&>rIjqZ^02b=lnBQH^ab7Ym9{5jO=!hg>`eGms$nP&F7OHemxWQ`0C@`EbDhC{bWbpkn7F6@n29{?g$;-FiPI+5RceJl_{Ze8NCV?$kH!)+zY@4-OSWA-EQ4ACc1P&EuT-2G%g-%IkdF}|?le;)y--`@R@Q%kBF8B0GHHWm#H67+OEv8c1B7)&MBQQ(4vimaIl>i1e7rL?xjf#KPg!r`R+M@a_jv@1IkK}f8FXE`bFz#-73HY7I?Mlv*ZiK-%p=s&1=xBD#hJ77E=QbRfq)o8Ql2-6D%qJL(KH0qt6a+UKj;XuU8J8wf>wWq;Ha8(rWr3&QlTZ?+zDVqgN#~85KbIz7|CF->E^;NO7a~b}5^iO6j-}aj0R~($<|LkH%I`<^%J@KwjgfN}242JhmUl$jV#*m*3R#vZcOXEm+>(Lhi0=q-NSyOOztTJ+4#)&yc{)RBvljFf0M&icT-+!N5@+Ja^K3!t!s0*zUY2U0EP0JVls)71DXUkKsf5kxj{o4>vqNi5eN5RA1VHA^jJ;0-2dwA$l>^PP6~5j4#|+#c%xTu8;-w9FZ1yzYbuynI@vE@iTV=iM&jwx2#_pbeJ?|*kF8(gbzYJu3g$i+K>IG#B_B%dnA#Bod)ab~Gxnj*v8sFgup{&5kNxJ$dD6Km5eM+($p4<}9CBb&@{g(YddWb#sApRJuoBl!h6_{nSNWYte#^Q8tbSCUB;uJHJdqoT`f`q)X<*2yH2%s9$5*QTZgh6N3ehrAr@EX`|Mus7z>Ew9_&pypy?%eOZ0Z!|j&d^@ran=>F^O>VxkmzymCjERP2f~bpKHg&VOk_h}urC*+xL7h!oBB9}QGVErY{PK&KJo`&V%_y~gB8pA);j~!7pqBncC6pN@v?Y5{4ir{GU^J)JwM6@1i(YtzSqp3Q71S&AR`2_e`ojR9>IPzR@QsOqx2)e+LO|G^DgRvRV^7())c7Y@ckUEj&-y?yR+TPOo#`GZ+1CuBdAZ9J~rS}OonKw!!N&H!+KoFjb9ZQ?^{EuO6U`VpE&;H`lItpuG)h}%*vyxqQNs*WEuOC-3#QY6DTc(b--GryXvF-{a`kko%u%%sSn+(o0ddy5FE0}_rHA%>qz|O7ZO`877p7_a}DmB!@5{RKX|TvF(5OdVY{Oq>u8yJB-cN-h=Y1tk1^gPnL;`NDo?zJo3A#80&<7ra;2fD%y``7&Rfx|z|7RuxBz6EA2Xn6{s4e)%HXKZ5k8t+hAeey0q4vZUgRaWbX0yQn?*-rwd;XO>5!ydhBqyuNN|2Q$p;Xx%C(?*A=`yPqRD{JQ=%FCr)Jj8!zCHUe5l70s~i%Z;G8kJ*58V-5}QlIL5(o&Yu(yNxUcK>&}4gR@?n+Z=jvp+fOX)d}j$xkCsoA^5K1Xl-K9%DYFBu&#`uUNOeb>HcU)b)w;mD;S-W{%d-BBXZK*$NsIAd^iZvfSQ%H!L7={mj8rfOeXPXTPyLXa~RF*ITud>T@zbdfCaA;PUre(hBV)`k(b=c)_bL>OVJeqMc{AUvxWf?hkr~wf*~=@SNKGxEkL8a|kVd_?923zW2b_qBnYxko9#*OqM#H|Gx3qP-js^f&A?Q=0`{zMY}G40_5sBhvfF6PK%>`Z$PUPqVw;4=u}yA&FRFAAxqHOT~?q|hx1Qc?>OvfeMu@$<@_5@@V3cWS7^zlOAnee+`8zwxOTOCR&4_`qBV^TJ1Aw6kO9G0emC$Bqn+C-u#oZsSd1R}+>3^zQH%F1dW!b*)huz6Z;gdggWij~;?Pe;Ig0bV)EJ=nj-%=L?fgt7yC$!-v3TaMh-%J{5#xWN^|`}2KL5279;_Nd2v#tX8lWT$siP}kRG3sqqBhozxakyl@%K0Tkx&9pWcTqi%3E2$!P3Hfwy?&uDOB3|APC8elOukm}oJ2M7|I+|=U$X!vN9oJen#{uEyT-t@YW8&!m6Z0e}bb4nW5s4fXG%O!k_1YZv|9NzSXCBAD&tXi_JZcM%0?vGXa1zHKTji-7_Qw(G{A`*W8c_crc2eaRi#vR=k>WbO1G%g3f}d^OoDaxNg4w-F)UAJ5`5gZl0O>dSwsY=9?&4I|W7;1R3TKRTgiXGo-tg;jEZyfQuw)1-5-dd?o6o$wg()hQ_CA>UBNr`tcRE*64lqudjn?`NEN;etG$?_lSvYiUh+<_Cz~zLBrQ%X-1nttj84Z#{wx5Ch#T$MRW))fzMqQ6+VRtEWM;}u^@kE9>Op000fu0VTeb!F>=KwErk{w;ar9Mg%^`wxGGL++B(nvqYDa}+|E|14&rKzi~|6Jdv}f8$w;k93TO!~^y7%*jLQdtzm?rq6ojINX_Bt8_&b@5>_G-SyzH2{8UjR+q~~J8yRc{jL$c&^`ZvD&OljFbx-Z;*GV%2Dzjy%ZzTQySD0O2Hd9!~{#1l){))2k2tUPsE$)h}L^5*{RNi@?fA!?YRWe%YXCjxM2afs(6FXAfc%rWNZ*E5*`f2oNlKS~BKOh#r)E(kt)cab8&`zSxYN@j?tnKQR77Rx_5A+;r;GGSGm2#d+CzX*~I;$BpxDJNH&$_)v`ajVALZ-)R!+9~Fzj$0T|0b@dhA)~HzvYStB9HB>2dBT4zcT!oCr9k+aeDJe=W`Y76&k-NyhNjnINdv~sjT!wZMJnxhq4nhGw9-)tsTiExX{1o*#2AsKtMLH8m`3^e{cG_->hwx)Py^lzBAPK*~wVGqJIQjH{e%($Lu}bDsvdF$x|kG04Bz**+Q)kQz>xlR?ZxXS$ug0XGv&*p9*H*U!~qxVNH0_yG#l^-GXg~?gkrzyip0U^%#ET#RpzMsn-wvRg-4>1SJuN`B<^qXUJZP=ZVqGTk1^SqvJ*RL-FW^j_Zu$;9T^~{6qf_Zx`!tW2l5Pu5oKTi}yyX_3FPke{+=+Vx}4PMQ<3|jC_*~Dw`05zNxk97ohZklhr2f%g6(?@f`@nf!5&DNbIRAH^M)7%x2S7=ex`qv@9{Wez-Rn#SLV(!M*{9%ht!pdlzsC^;FKjpG%o(EnM8ChT&lLC;JylS@7S9Kr^Kv$(awR}<<5O+i(f#(gGvs1yBDij6MN`cTs_t|5en4hU>TS<|M?E~mWRkHu7D6l?nHG`!W3M(9R5Kn(gmj}nP8U*1eFNWapZhs&49_cWG)%w1>-aaatUoSB-5+TUxjSoOeXz$OizM1!*h2y9`wK?T@cM7Mo(qKEbA{!7tIdN&8hkEG*C`y$}}^tsn+-;s-CoCLYpw^C^F{0kAtKhfOJ1_!g^;dd^d@Cd1IZ;~Pv1V8Bj5#P5<4DWlbEIf-T*9<<#y*BRpf_^!okB=mSEf9SXCynsFL_BD_gA)*q53Y5goz&&=>m^AKAnG3V9z%O%S93D%UE~Mz0hM|z{m5eiBbhhHJc59T+r9RW564xGUM$Z#TNnSpl0jC~HHoaPp_tmPh-%%E53dg@|Px{89ovmX@nmTaF=mU$oKEa1I_Z<4f}^;po@EVhbgHaoP}sghq8P;ylY)TVe`QCl=j}5>(KhB)~&$#ROGt&9v#rp9wYAOW7C_6pWkSE4gLo>PnxP#~x7`=oui*UK{$hGK*5U$_%l2p%>_+bL-Vw;uKH~*9IqEbPlen>^?_gRBpc|NeYvvZaj{5O!hu&&%`_Q;6_CD%Ip8b{>EB1$HZ#4!N4WWKdt2IIXaWFixa1%VVitIQitjw_7(*7iu`fsd_sQ_EUez5!}dcOC=X?y{#1nDs2KXz9FcyU!Ghyk`oOq2BE;khWzG4*JLpNF&2VaR;el$px&ksEE(^d2tF@tG=>N!@>M(xS0C;FvkPTGOWP_k$T5BlY(pGOg=ZWpMR;oJ7K2Jf3BRP%6Egcp1=RbC4=$ZvBo)%tHX`NJo#BdUgyr1M!K5%5YdWOWT~UTuPs3?Qhh%1yzC5xw%<=?LjKubsQc_`M?4(-#&<>`1$Cl-LvNry5OLXOMe)A;t~Xv^wzB}icS1M2pCLDvGEjFIUoL`Pa-g$U7;&9=z|1KXQ*F|l+x1!Uzsp3Use`Zs=(`9k)2`*=`O{>AnBMG)kEzW&k#j-Njg$6K2248LWXT%FFMokV`YC1X!m*U`8%?IYUhBGK;nB*72%*zoOZvqyVQAOETx%p43+ZSNMOmLcc7^uCfRvpE8e9jPi@TZEiL)H8ifM**c|PNAuj$PX$5zKc$rjE6^=dv88kN;?0FS)*&5eg*kUYm4L8F_%{OD=aY9=?6#{1E*Mb<^d3Q96=mV0i6_}*9up{U4S2i}ZGxM6Z*g17q2w&)Y>`tny^OjGIu1wS$JWQGCWE4n##j(xPj8xwEL;2JxLh8TcomF8x#uEZ#&w?6tLy^a5^ROcl>@R*wHdRJ$Ni-0z(Q&1~b7g_(%%8{!_k_F_Qj6ljWs2_2lVaq7WmkG$Zu)5qrK)ExX<7WYKJ%dwYar^;I*;LV=-yd=Qon#Crif0oCU(*toXi-u@0mow|x|M#$Y0vyeG`azP!V~U5*-WGdk17!~b9}00r|I>+j_icR+K-ao-)i6Km)@g_L-?epvKMa0!yxUM$pA#|~Yw`v+Mz;Alb<{&FmP-2h_yd78;`XTjNwR*Ll^P5@RWUx4Jk&q=M&J8IgP-8tIOiSZ&1HcF&uTz;UZ19>q#K+fIUHGj>Ly8XZIHjQNK&sZ$>s$B6qR9TcXfVdl5!|_nB+ok6MlrZGJma@U(DBCStUJz&p~Gf!OhV&B7ks^il#mwo^43xaXHUZ=b1NKzm~n$%vu-h<;kla42Skqm=#y!lfbcOs9i-Nzg)6BG?MBD&p|^nMBag*;^ymje794LPr-}Q*ccRpH_a4`q-WW>KiN11CjTzRtmX`=66bSfHl_M7LOuOXME1M<=tgBu)6;%&UgZKjgO6$O%gs(!?bQ~v^nw^f90108GHdyuvK~m%SY6wcXb7fT@HaAA?k-8T|ypfTyFa8%#%nU{0*x~Jf^6rXfgMhLW?)p`w{i_Q_@%7P~YdCS25m7B>R>w^moCInXahNpY5FKX(q;7Q7_FL-0DU5A2yv8n6Sw^W}Y0tau%R?4zr_I$VH9_ez=_$sg!1vHqBFh!>P=(lwt_LLSQ+ecvUY>wj;xEd|_jw2fRXR%1RwMKnB{8>_@y)6@YtmIpx>h4~BxT@>vbb}Nxx6EHMGN-@-w$sZA8$ZGOa{KYek2BiA3MV0-s!Mp^Ae}81c@xgy^5ViRaVfknN55bIU8W~IyKl~w_y=`jpI%tt2MYGtQg;WC$Mh-_l5TSb!&T+Q-qY5|Iqb`SZDy39@+9^9Z8(XXLyOm9puo{JR-7gQ$T<({XW0Br;~|w_`O{;etbaP~e7Z#sI@a7SJ*a{A<>Qz-HLGF)ZM*hWOfAOyrsc|iIQ!!we9KS!^_bM};GuMiegu^#iM-1_FK~R1rCg`~6;J40voeC^2=dI%nqslvIetL=`-DA1J8dV%)BUMDN%XZ~H_rMup2%l=P30>s*Um3t(`Y}<-}om6@|v6?q*9R|#Cx(BULK5x^NclXE7eH-1c`$hO9P0X69}^>`Rl@4df&d#tQal>}V&`M&q{~ncmR8v;0YKeV1^v8>+(P(oBX@*CwR^2*x;5IFA2gr7ODYO7Y<7+Y@FKUY@0b6hGeQB4;we6^Hsltf-eTn91aLkYItnhxT`LP!?u!SUg#};xK4(eftIa3Nr`ydh0?`+Dk`!O}o11yD8J{yP--_=b+CRqDAkG`;0mCJmKIjdS`aX!WHRksEf@JB2<-Fb`Ki>UU#m%n*;f#L4vlkoD&WuQX*=Ef!NObo-Ezyq8#lxcZ;m3h!kT2t3H|mb|Q@7_@gXXcYdOGYv0*SklxxySvtr9@$&1kk)C+b?UPP^pYY+&r*BXv*V$bUNFm%Lu%0KW?#cxniuF0yva`>viFxG}jtTg-zx(ND$srZ>d8y2H`{ss#5&UaBOu$gYzQfF5-Orypjj-(iPOK+=}{~>&UIS4Bx-;mc}Gb6N|~%l@SP|Ys8qsu9Ey|nYW|;mBL`N^Z`-c3DoT#?LQtH6%EmmaJ%6I@)&Db^bxV1Sh$?l%e(p^^4sOwyF-J9iI5~`uzHCha#}LCk&u9qDV!K`-)Az0`h%YI)3Gh*VY$Wgw=>-Ru-YY0rh1|6@YDwv8DSz0meJ(t;3Uy*Xo|qF1qTMOOV>ZZR8Vp?8LiZwI7}#&j%Oe*(uL?hxs6~M>H=xJ^OiLnq(0iB?i|TIo^VSoY*E%TwCC85yAO;S{lIyU>7(g2w5K7H3Yy!3f$-B?g(3$!OjIk~Q;YzI?~x-VyODF&zrEhQlZgU%yuZKeeuSJew2yLQGxa?t`ZIhpB<0Uudno>ON}pCgUzXG#{A>L37v2voz$>>cLY5Bi>v%bZ-gcuMcx=s8VyH(R>kFGVcUj{C)aCX_?>@ZmZG#<$pT6~kqdf8FHrAk>>?Rh=1e*PT$>4sbtQ6XlRAR(O5etUY2gc$%YLRn@IELdg5kSod~VivL_yP92aK!(iIV1q5%nGrEz?7YJtj$BT)&Hl%S11dU`<+n1DgF)tGyF+&b+PNlsK;%PO1Q7L5ZA6d<85E9Tgc>agF4AP8FeqxeC8w;|D5xNy`m;BpDsl^#q>tQ=|B3z5@nSL9+JQ7QfoZB@97ZQ_u;-GatjrQEfr2ig2o3wsk{NSKS4b!$&SibnL)P3^CW*4(cfxwW;{%2%->$O6S;-p=Ea<5K!jU~oJTvk{lIkL|MQ-uimFx(_K54)b?W8YFRHz)e1oR&xgs=R-=lWvF|M}#Y58SZctveTtc1rKp@v7|)fZ1_T)qNY#PVG$JQ_h;9wEm&(EyykI2RlLy)T3a{8`Uq5ZID}(((XF0q3(a#y$`<#;U@Ko@EX`EG#3v&8d~(@cTulY-OO9tZ2>imHxG`NV|<-T)Nt#;&liD+n|>#acD@d9H}5ZW2EJ}DYukF9|E2vg`xusZ!r4?z>{B;uT7SNMTO?8n*uVSFwkpP_;&2*d-@rc{D({%Lsxc40uok-3xdh`a7=Ob{`S2Gz3`PaB_-@{7l(e|@!x1&&{18++Z5yXMOJ^L|qI`)4)@-AX0Z0Ve9ozLvA0`3IcD!tvkTvhDr3JO{Y`YkhAAGwRp$*W9^y*bTP+(KVbI3j3#@J|7phuhtt@ANqYv`XTDO#A}abd-(%hghgj(CF&fn)nA$91w)oWV7y8>>co5rA8=bw&7{Yk^*+WMQ(K-6QHCh?vRb-}zo8VkIFbEowck;l$&etTZaJ`ra3zs>$si~5R7GKI-PI`wcGA9>O{RVefI=d{5?kG?G@xPqP~O2abpmqzSwg@s5|q-Ef^+S!J$Fb%5ZnoOHw|DC`Q_Y*Msqw-`=7Awq`hpDWO3evbN?E`Pt{)O|$7^8F`InSHqw0A)Fx-3J7w&*ubi$$b-ceQ~pnP9Y@lwU>>|?AAFEc*}gumg-9XxOK*jsI=HDm`MQ$m6dJ|F_HXT8~p6Vw^6|T=R{}HBIF06PR@DHc&L~#3Lgtaov6?3!e#_SpTiC<LqKckkwT(c0{t&GrM*dFmCD~ADjW_^BOY(6CdA~Gc6^1@Ij{9uPRQQ&vy7wL-eW9j_`(5f&2!oc9Q=v(~EocRey-|Y->?Cob~Ve*1|WqpVEf_u`jvs674*m(*FJ^9rb;t?n}%`oIv!CE7YbyL}r@hM@HlUqJQ)6z<8)~NMX>;A@xru_*~x67Zw3HNZe@|XYbd)-KiyK7Q8|LI{olx}n@5wbuYP!E}85c57uJLk}uoZimIqM^8h6eaw{M3fi8ADtb4`zx{|Lpx4b2CpQCg&W&iW5(?h7Y?o6vp-{hz2$sNYr;Ft!3A^Ckv$QMA*7g}FFb)gG*ZP8@qpdLL*7?WSE|Wz^|k-NI;R%sHDidTL%!a-e$CrAm^&i~76zn&StT_)-Oys-c}LqnjRmzY+viJF>=nNOfkY`0rftI}FPEED}UqNp(~t)*l;r8x6kY0D;9|L@DHhe@(G=;pN@$MaKD#F!A=Xgt1sx-ire{CAnm(;^~Ac+e|noe$HA*+_Hg3F{J|}sLjLJ{djf@CuXKfV!?6X2^H9GhxJraAzzc}JSb`3ymwmKOWclbv+sCCUqAvHP!IXzP7!0R$HZlsK&R^l{_;fIw<`;d;j(Y5R$)fvZF<|qMtG{^->eOwli|VU52wqsaUFHPpy-v1!?>i>JqZhO5jayMCzDLf{=3ujM#_2-<`n7!No1@E5*utR;oTpi$P~YB~IJ9k}6YzhFir~sXeS%%@lC+*Xq()n-G2B8u_jJaaK`CDlczBen>pkjA(A+k^{P{i9OWn6|tddEDdnX-7e~KcH$)1S#E<0!pY2wDxg}?rfy9QLWMsBxkKWq&LelhRtT8G@F>1Z(R`^O%%s2iWH$52mE$+?lw^uz?$6G@{un~wp57MkEvPRx8+m!}nI-I*J9Y1g3+g9^hxsTuc0l;;es!Ww>}#0PT;NsQ-C=!Fd>Ut^A?v2IULbZRY4A=C>h`>{JIh%8!TpzhPS6(QuBRLJJrQ#ch7WZjLpN$rcQj!iTapk#tJ@rN26;>@dHUKZ1q!HhH5WeSMP4G#{nw<%gZ=e%hKVuMKXoTOnOtT7+lM^L_aDORFx+)zjO@37;F-zAhwkDzDXY_|!PT4WU@K+Mj%zA-og(d9o3lAxKt{(T-TV>qSoJgON{MDqTK#Y-OXRU_^)h^qYW=|L_w~I3Jb3;{)B&643x+&8o+kq@kjGXqrn`UJ6anxmej95M^3QRz;>@aFG4OCe*exNER5#-$OZ(5g@$hc#x`)*X$Ul!(JgBP)H-PRsHmj?;c;8o>xgvK;SVHBqY);24McE!w-b6SRh&a4pIHr5|CuZb8VxPv=>j%-t(%nQ}qdg{v&5xZ@42EZUciT1_BhN%j*AyR?jez(!k4H-1qArni!p7xC3=~fX-Tz36`wBktOPVAog)1&)X!5t3=6xAXnu7CExfP&nyh8swdZK{h`!PxUzKiH{)$e;9xSS~4>+3Oebs-5?bKIrrNy6Qw&D1MuJqXN%e+C6y1*$ZkoZuFyC%)ZA8PG?bqrLXziat+0SCj|!SMZ0!G^c8S^viOMk)_qyBPr|RaqU28?*k6pH0e^Y~D(tofk8oL>}NwV6$FxGM<)?+5Zi7QNl4?YXV#kd{5q5MXD=uV@})0;XIV?$(Y^mhIX!$&5d1D<^bhVfgPqpIR3>#$FGqlH(>1;_*Q)y?VO`O8WC~I2QuEQYd-n{?G&_~)a#ZA0H={3w@3BRp1W0fnv=01ke4@`;5CArqxRv)&)fcypr_i!!AI(Q!rgUfsxFuUY`ZktmaQhmt3RCE^*JLRI>Y+{~D2S!;uKG7|~4D=$L8$~k)G*Jx)R&qrIoNGF(`NLs!37~1*n;~l2byY3LU^xEmAPe}Qsr5~+d==#F3S7kX?CrJHSE?NEDxhIfz{wp_toKr;^&EdQj3U`&BTxE1ZJFhw4SymPp1>XH9vU^E=yIKyjNtgbiz|qF)vgHNHEyQ~l;XW#W+P;FpYvP}f-yr0u?%`e#xyhB|_Z&%{{7uRcQ-}4Hh)lr$-gLW>74_dQ#APnduFYj^c!{?IGb88c-j)ra0D<0)Iq5W!WxOT~f#KLsm9m8Yn$X81k4_sw*O#mW%fiDmBkzVdj7A7nB5j5Az#u4;Sm;ac%D{7rR(CW>!1^&}5&bY-0_PfASr$Hu*OQ;JtIqJ6?dV$={^mS?SsNb)bwEa2Y2d|i$M(Y*={^{&gK$%?~3`E`WlaEoS)Lrr1`#Bu+b&REaN>N`Kvm?{~Rt#8EC-lNi)bASn8a4bB2X#TbYn}|FK05r));%H##Qj=ay5%KmFK2W*zN>3lPuYr=4Jrx>IZWMYZRSaM({ao8pGL-6G5Q?JL}YI5(&dLY>8wMfC!gFYKA|TV0Wj`XWu;n)4e2;at)DmEum+XWc~PuEMyCqj^{^?3gX>UL{4vhYk8(c;`zIv{t2th|3M(#GoladqbLP_A#lkCKRxB^6PYQp!@YC08mD*;1m#ntk8*ecxxszNZM;N+{Y%k&;wINfH%Nv{JnD%z1yVdEfKLIiK_WJfG*jj4|_l?)zGRY4$+Dfh^<`zoj@Mv)o~&zY7~fEAj>38k6jEzVP^=un*Tyb~0;0phOX&U*up)5fh(J$s?LEAPc~e_H+-IFEm22*8+UtapTE`z9&N9R{(gb({FL~oFNpU4p`7SrJ<@>(Bs;=^q1ddgH4eFZt4W}}N(@A0H-w1sppS9CZ0n0Vnh1O0*N4h_oTMD@%Rb()CDg)75%B(NM|RvxlL!I>(+uy!y~v4tFE5*LI5kpGT^)j+7WY*uysa%7Vz>TXyF-y~|Lscl{^_R)KzyHgGou$#ANvl-KTHLp9;k_~KQPgk@-S~2Sc>aQDSSaMvbn}kC^TyVrMa!bMWg6}3Y=u7&K_$RUFPH->q%F~+O5p%TJH+^HWOM6oVYHNy^L>PmN#wgSkO&em$q+tItaqslQuc{;JzGjn-rgL;H`SSl1&qROx)1b*Ssg1_W7_+5`8S5Vf7KSjs)6Vu=`x-IRS+gYIQeLq2bkuIQaZfUVG_A$%R!iG%}PTVQ+awJtlJu5RMtrXzoY+`#a`){;zh^szb8CfNy3AJAPP=*hr>el@k{Ti$lLV3^Em+Lqvh@su${T#))2PU|o9>xOwY)tlwwgSR)wHh(bA&sKDrKg>NyM9+=(%Kf#(n^*o&zWS_7IXA{*esoNqG!hCPnlHQ~GLXlaUXD&^iG*vT$@4ZFG0tEGjac%UIM8~?tYTS*ady38R7?1tMC&`ZTMNC#uqw*f@gLDDK7Vf(2PaOM)KUbbiCrggH8{DmG_S@t}HxG{eV&{~)`p+ha?wnM_wo{Z?XLpzA~OC$Cv>O$u1sT^wa>!1(|0EO~!@Cz;l7^PE0<7jaG1z)*y1~ZdA(8LgkrVU&YD0bC7T24)Y6j#+rl)z!Rt3ZF!M8>E*%6DJd3-@&l=__eAwYc-&sOANq7wrw^U?6zd8V!XS@fHcZ}}NRm&PD}P@s}o9&80sSy~l*T6k_4GTW6?XzdJU6uHj~+mOqtsUCH?M=G*O%HaEH)qmyBdM(4$16u6*?x^#vlm>4FsU{Bzgdv%ddKWkZ|2_7B1ieyy>{_A7H4$Yn8dd%VS|CY#GSkT}#Yecfkj^zpwFc9ir>!MioN=uVC6-%O#5FT`N-0SzZ*5fXz{UDf{z~lgDQF3S`8W{lY(25FmRTlIsEu-2b-@`ue^s6;{a4>SePB?pmB^Y?y_`ty?@D;H_tJ!6BCT%#c@lYEvB-68>ig_Na7^)?o9IP_Oy_P)nWw?(-z{BTMd&}odE62qQ+Q|QV$o-aes$}2vC812EocwDd~@mr-hY>*`sqs#+~Ca5ah;emc<$-7T>Z?;t3I^6IKjWTF5#D&-ocPvxIX7uDf(E~c26;jRS_`uZds{^8G24Cm)^UFt})MBqAZ$IYPJYZ(fIMAMK%~Pc5}>oUUG#NNjrM4yWb1xHQu-p5@dJ#OTMqaIrctW3xWSvtnfRp)>g*usvXP-!gVww}Hd&kyk|oJhD$9B}ZPU41dGx&uO1;FPTXMbLt0BhZ}mr3L=5;FbQ%Oj08!4kQ0wP%ARR(?&nG6xY*)Fo*^t!bZ@s67|%Xs;$4mRpROZ~i!(Yy-r)VYbB@SskAKNYb@YS)Ek)CjF62aC@m)#&uujiKJzoLWwU)X3=UROzod0a36jDKVPTG)SXBp~LGX~>`tEOEaVx$zPSwzmDrmA;EU!0TeQ!R~GvczrS@+aE(8Sm$(X^{XYeK-AM5r<<#5rp$ktn+S%k8!%MF^|9U*%wNFCDj~B!8os1Of+xW6#|`X>(2(UV4R;0gqKIJjer%k4{H|UG0weDS=q9GN5h6e53}~w7>|FMQ;Y4<1X`V@bs>7=+|myXRjX2gYB}9G(sX%f)c4s$0~wN5GOIPUAeT=JA2KgWhYvlLC!>#{Uopg!#Ad9lftbfqu8RJ1GVPTxw~;G+I~Z_7`d0WNU;F60)`6|wK(xU%lSM8;S=SHEfglt$uCGuUhVP%j%DX4|!r?G6K#L#wXGg`s3t6Fye6A{gOZmYBD0F)VWunNpR^1lU^GXF`zK2*w2>!mPK18}gfp!0E6-s20%WfPcAGXPaYbKj_95O_nurpe5ABP3}v2|;EdL7S0fB%`fJO0rDR!+Hd75XB7|DOBG&QuRbniTe4z8`r_5W~&dH-6wQ>vpMV1@hR!g$)8Rp>W;l?fKw-x^v9O59-Z}B0=vjzsH(u$cJ{!c|AB82Na_*e!Yvx>y}SlB0oun^EJYcf7c)<^5$pa$sj!W`IzW?v|oG=cjn|h?U+M$Q>2D_)q{nYPYXxdP0*ec(TL{8i*mkF?uZjMVlL~Uy7_Wa=}k*i8qFQfMZIrHc<`vhsKXqp9X{BW_;qR-^R$#9-ne;wv7PZhZB-Ye#rUHXindlkAdB(J9e|v_4g>bCHaNtP!edbRVe!K4!ORrP*@1{`AB9$T3m1^`dHY+kI5S8bVzz0ur;#)xtDwNa59{Pz<}N&T_f}^qCPr+(}uPWFc68HXd8Lsg)5{ut###VLatP;?p@O74MM;9D}8?mZ&ZdSu4dUZU%-+f?we$#rK8Y@e`;xlOlk_Tb0VthR9?bdyfa*PZ?U_Q%9Xkf(Fyh1?|a855Q_2b0r)@%!BT%~bR;O&*h%|Gt~RNWY%UjtJyFQF~9c^;!eVMJB0uy1pDCk>+=vU3LYg`zbOuboB+YWEHifOWrUp=p5snN#|+DB6HcSgJAx^*%nqd^ezz_bKSY5aIiZ4TK#-7@+uz2>lc1RLzwuz=**4iT|~dL9ZM6T)35E8)dS?5%q;pkpHhLUr8@<~(2I!t#$4*_>rQOs8leBs`m}SO2JR3ZueMCOI?x+#2K>ux;lA=6%5rwR4>8AUo2DDAidL%BOF$nh2-aI;x6cO>9LMIa^V7}Gvd&#knG1r1)@5>%_2^@I^OJ(do`(Zb5536@eUF#%daI0l3qty7^*F13#Xn9SxzKx0-IF^FVQ#6%%0*@Z73xp#L{=;yin3AO?s$%`&?BQ0J0fYs=0=2(i;IWE(;5q{MiQMUDgoU7`LbEzuLUn=v*Pn5NM_XPQ3K)eAhxA?=&7gw*hhsh4bU-7gwH@=aTuX!|PrS@8ZnB_Wy>I-Zcha{GDAS>$*8+=jO~`$N&L=UaBQ(|K3i$KKuNLZPp>>3QrfT(_!pJWeMl625&uZ2a;f^8Fu7A89?K`ef07);iJRMQ*I4_Gx8v5?K5aY{@M_PCP&67LlN8?tz-96nes^05Ed2hrb~OyLw80Y18pVF_K4T1b?0yU}G80Ym?5_9pE2q0aTEvx21zasjuRI$YXqh-+2<_wJUh~~?8A5SGf49`;0a6$B|Uq&f&%lT5Fy*6HcQ#r;zasH^${0%aY#0MEx(e;0O;^xf#)b6VBzuwkN@Rz1u72q>&T#>Q`CGwEaDnQ^;fccPBn8PX}UucltJRo9u&I8q|(K&$*r%9YH)doIS`go3Pgk&X#COlx;%JT*o3^Dc}Mt%{uO!+m3v0kGkJzwHLg1RAN+6N4}h^+|H;X5H=+CZ8oz-enhJ>u}wD|EWb*BSzmzM()7x=(9vj+Zr;qXavZsWeblG*)bFE(jsJei8DZWU(PzJm>Kj3)qZhtUAXjxw-&}h!4I&R7%zJVgeXN|1>;8ze0T6Q%LUeGyYnxm^QF^=u?e&rML;l11d0@Jb6I?&WxiqN^`IjG)De@#wAo}PR(e=^woO(yLvqMS0cK1!TLITKvUD-Z)y1pC@-)(2fsqpuKnx{e&a-!etpE(LGKdr?Gz3aJVLsMRlJ`nS_FND+85#;?$6F6!CuT=a_lr7c~45^y0i%wZF=m^CAO@lak7x8a6=}G(lr!mOm;0H(Xx&XNJ6eKVGL~ebf>U)lL7?5k08H9VFj}de3TRNlQYy411?h^E_N`}MxtNP+Wr=HLHTM_c+Y2yML{Zyd7UDTf(M_=M#c{`VIfdV_rb}QT!L0_WPYb-Scg9FjW*z*2&pCQ$7Wxb0x+%4g5Ifv*18{Q{8Rnm-c!3hqv+0WF()761){-tdA(-W3cMeRN(-d{7^l_{+%0EqW*X({?xw^6Ef<)tuqp1-+3gsv`tm{&2(8V!w`H5}!aqW|oaV;QVnngHkehYpN%A@`-;=q2?z$BcnnL$RSJ69OcGfA-yHHwXEqoPXU>c1)6KVv(N!Xu9gP6V8;=e;ieWt7cf9UPUWx(vR^P`*^O1M(X*P4kCBmI2M{=*z^$#i6YLf|HMgn5~Ug^c+#rt1fTD?u2FAbWcpCwrAL?0mhqprph3IhEdAEncsBNL6!ZaYC$bgPOrT|bjE-=2%G8+*diE4|I~Comq%XK%I6`TB$P5y`KD_mRJ3;PiQMITRS2`J_g7W1OmtA;15`M}qYB&y>G480VmgcnfJD7Kr`nd0C9}NMEq*XjKvrb%gm%$gS;H-{?*tL5Teg&z0(Q-t|vixgaKucCJV2K~C&TbC7I-$B*o}eE{?2I@QPirs=uC^*ECphkY35Tlrf*wdcHn@NV-ejB~7YL;s;2K|sv0e?m9ULiC{32_~*^@KU`f%$$QhwtSmTz4v4ktnmK3CUza&yjQ1%j?aqmw0Y%*hP6!`fBLkdtoW^UZ2%kOd@TzH@;LWb-2|Gw5}K%TU3bEM9SbQrm5f0k7Z{i=Sawo~~zGa$}Se7Mk;-nSYlv$8q>+h|Ry-<_aEUe5jWzzGKrSS532=Cf_!Vmu=K$>q(g{xJ5iLu%<4^cmuP`0ZgR^j}JexfSHM$PYg?{djpp6bMX;G+OieE^^}Uft5QRVw@6W*WdGA>Mkfs$3mm{n~aZtasP14$yvMeWJMz=OsKhl-pmiW$?ZwG+SOiQjvo^!qNEFj!Vw)^!mULgGA(Q(wl92{Jh}EO=qsGaO9@BN$Gt7fgrzRJ!e=X@_$^>3|gw;AiHeIgIk%%pD}3m`SeG_9p;+TP0h%=c$8|oB@>}JMDoC)1-f{+yKBCPlfX#DYy;U2^UzqQ>qw7k(qKO8WvR?6I^X-T-J^-g0Q?RAzTKCN`&xZ3MkFqISioWNi{3x$ky{WA?AAB|an8K?74m-N^Hm)bPgtleIkcayF9$KlLeDV(hHjp3J3yCjrrh#8L#Z$ftoyc%|8he9%)n2%SRfiM3@;@2H6j;i%qpDIOn{(M>$h5Sp?6VV&a5?sslarbU1l-}`T1r4qLNppfgg$Gcl~not~Z|*KLz<10QJwFMdUGEURiqgLz@x{XyUzR|C$}WE3ETLv5&M9l!V7uaGXG{&N935CfO4-*5n@lT#4N5(YD_81_7YEfzMu$75ysyL~E^OXc(BhASaXQ>II0t?UoZ!Ai?zJ3?p5iw6#frXWah9L;3A9=I27t$5!lJzRlS>l~yN}DvaLMnNb<9*GvJTKisK)<@K`1Q%RbIEV?F_|ZCBg2&wAeHmO%Gt~4MZ}y?9zcgUJMyL58zikG8*P$tT_2k-4O&@2V75W_!+8Zr_sa|6usrf*OXFAcF^XHFmCLVa&?xEaK5+xRE8?%?NYm#8*y~kkaG0(hp<&ziyZ3IT!rg`ASG3g7A1=pro=P2~z=`$;lWKR66JDkF-3%lx`pjQ9;ks=OXI{K&v4>pJzR7z=xGvEj^5uPZxPScV)vJuSu9erNG10fa!1b?xmZcH-Owz{!ujUXiT#{&WZ7+ID`7cAAxta(_mlzdRpqq0VC_Xo4#}o^@Ua9IjtVM6xca4#i_d_DAD)ij6HVt{2-mKbh84@Th6_Gm1Q@qIecHSHC*q=tL+x?r3eC5-IoF5)%VelA77Ki-*TOaz-$OT4E3cch`!8nQjDkt`M!CHl)l9?}f{m37-vR_64;8k@~*UJFCMeUSgz~)V1@YO+-#s3b*Nt}c1oQs5C4@WB$cVavb#s6@r9*%<(dwyu_tU>O6d%wQfx@3^LvsX!u?mU#}E2Mdw1j(o5Oa5L(9^$b1@Fwc>;X8|i?DKT<0`?4?mw%mV51E3)LZki|PmzApcPV3c@H}IgX*+;?SKo8Lv_I7E*-r608g%`K{XDK657-q9rV}@R$J510)Rj1;h12>}-=LenAaaYlF4!>|JR;df81gaB*+fS3)(`5KPzx<2XX7sBoMbcZS?;dz$r`!Ij5_!Vk*^RsXPr-VN8>27G{TJi8%dq|Q-8;5G{W^-a8$ti+aoi9SrsEEYkqvoTmOhKub98@PHN34w7fzcJr)MbLBBOXgizTNw#eI#2XYrMWM1V!!fmO&rkvzJ=WI=RLmJ=Am~AT$VfO*IwkZ$Q{^}Hj1)Qpq)|N)uGdAkuyJ?n(OV&fUkTSdV#Z!i`+xQ{+v~%A?&?!-G0L(^pj41nKa5#D^Pa+{U*%-`P+BiwtdYm&>`D;S!X1CkrRC|c4&EnkftVwh!b*`RlW8psX<_S`uvAGbGRSaQ6`(H{5>2dDd(4TCnApvV%#F$76Xdi)oPz*k)P{h&1uj}qUDEgn8y7>VovDK0TSH2v_V>T0J(+CXA_6GbePcbDY&+PJbR1UXYVFm;K(oVIdA*F{4VNqYv*aLhh^pYH|jA9+IoVor{EDstlU!R6EuIQVU=!}t~SF}sDOl`lHXz~D>IH{S{5`*JSZHd#8rHL~D(uI=b!ra7DLe5&@K^{>wM#&geiD=FpSj{b1SWUI>>I)5Yj0-3K4gR=Eoz7|NMkEO*#nNUKaVAEQ6N2em>KP4VmT_(lA35Yp(%$s98BnAz7sZ=(+&o}@UqgLoDk%WEPsl|Ji=hr>oBEs4)ifv9rd#)2vRYv+j9whjJ0@j>C>)wAnKV6PSMqSnvy#rAr%aFSC)4QqyMnSk20JJp@3bPzJ|dcx_v4K_L85`Mvz?;?LwlPcaXulwPIfLEG+C3-M`~7dY$9s#}LKku5i<-RL!v)*BvURl<+O}2E%nSbu|{~W1Dp*eQetUp&&!(n#nTsu7>Zn6&Lq}12?1n`(eM{54!w+8%wd#SDSpHiF@L0N@9f{X8;ud=KDkW8B3+H@DMk2tq#+o}7ZFtdd3PZeGM|Kt@@pV@-Q|K>Pkp^p*idp)0HAujWx#~aS##p@?x`pg)vCP9&$>bz_+^04K(O1I({5kiQbYeQFXf{G7Z+xC=Gv1r^{E*UX{N=%?`vqGZpTh!8mI&OILhtbOXgN5{hf|FwT!s-(yKeK5*oR)x2UI#>vEYCoL={i1t1?Er{`K6x?vnm-@aX=A=Dctf!#9&+kQFT*FI!&fV?i9;KN%1F>Caidh9IYX&#g%TqOZ@BCFob@pS<4BC_x6|90sD0AKzM5c6env+(;KwnpuHFMOxJs-v(mbA@*hbZe~4?#p_M4K3FNC?FZTpJ$-}u=ta5mI;=hZp|JPM*WQtFm&NN}Jdv*dFdPYKTJP7K$wU7sTX%Eaoo{h4DilO1CEG1tUlh~7yYqGmr015ET<^7Byk0?vb*5l91(+@V_=(}{mlP4`i%TSjnZ_Z71Xx9@*FWj&e6EPWfP|>EKUD5#r+z+g?OFSBE4Zg|4aA!)5sqNUGlPc8w3`IMY|K)a6iyOil_F?#t7KVvuQ~06`r56evjMJ{yPRa+Y4SGKinwhes`ZX96l|ZOj<$L|G#m9Go;WAh{kXS=;jWz#k_jdVCq22W9iUGPV|H0z3TxvWfDy%Wyq5Lokh`C1jN07&RRRnVUi-#1&uD+N|7bd3exNglN(czKV@YzRw<4Lk#pO}EI81+8n@K#Yfwt1mwAIk`R|;at{>VXNwv$o8x6pR<7trJYrH=FyY$tj5DVZdos#3(Mc0?()%Y7BAtzY3yJPlE8v0nT?t<~oSWj9X>0n0mvCI$SvVr>pKqSay8X_VDF&d1!X>vkHAtaJ6$2&q}&;PkDm|4ga2aAo^-_XrUJg3T=PVNA;^mtMkwD(aj4mc-HciHJAcbF;d)2?~yAJjgX6sfH?mz9>DvnWiWAvn4E*>c02IzGozt263WpRZst0b0}y})&8^UWE(Vc$2)PWH3tW3;?ps$ZQro|9(4fL_i1M`)s2y<3iL4|KWu$`G&nxFyVKkeeN4(pLGp-40@Pk=KYCml_nibuQwAmxskFIHmjuysgjTICK2=76mF%ro{?O(B6MZ$Kq)j1_S1zlx0oN54^LCn2vV+nCt8Z#+;JV-PwhLcnbcbj2%qIrkqK|FjXUkAdvUz=&9()B|l8bqVuIR<#TUNMqCqK_Td_@kNbmw{UF_|aP^@^?CWpT~kph}M#5y8dJ4!zsndxk=zyA9M4>%Hl4{Ef=e}?kdRIL46!$E}hO-qx@%A1fF*T;#^dUZk|GzcMMO9nh!|dAdi^KW1JWFb?>?390UmlYPG|K80Q_+&Wy_K;UI9p;ozlJ#f#Sy{ns-8MZr6@4R=c-Fix5A`+ClM;~~Fq{~Z4Ua{Dzs+D1Q;!T4T3|2SQL+Uxh4Pl@u9;ecbUE8|l1tBB}%mNPSHkRUIc!WM(PtNC(K?NTeSJEo;{_%!-YovNPmK$|nr`W75Q{~`K?UGVY(>g~y+ThM>rEFqk7z@4OhE!||5?Gxc#*S>t+Up+oeGH>JSHz24HvoUyNQ>@8`40}Mg6hSHT^{{e09Su$={h^IA4FmeHC&pLB>Oj>ZYLOey3V|5c9s~d)Rq?PuanGuEdB(-!Sj%)-QQmmuv2{y2X#b@!T`?VDLY^{eE!4RfV;8DRL3};x1;RP_PN=kXb8;=b`aFp_`L3BVqZkr5pOR{DUBMBXnvo)vQp7;*L>ulSe+li^TdrR2Un5$T*3Qa_#5f#$Z7L5g?-?nvhJRX`N*}YdK{+~48^P=(LS+wPHO*VdA*Qa1ZZ;Xzf>1S*MB2V`*p{M82Fja{3(utT;UuiL(GvRIHNgzDx?j$%At|w@2w;t=2Td1!}woxM4E0jrhdPEm>MKKMgEB6)CU%i<3Rp+mgi9(?rUv%Sw5}u+6r`Q7nCyZAt(A3bX{}-+Vl4ma$+7NY1|90JvNMG-i+s!M1IugzCbv1!mu^Y6M0OlO2#d-aNxUWva;tn^7iAIN7W{xAt#&qk3ODnK72CJm$)erp0u!NGygzd#b3QDl&dYY737uWlB~_@E^yMXec?hNa_cv$e8cCxpso1R#4ftN9Ey!BzdD=)L5=zJJ()G=Y0hhM#tr$xftW)TN0-lLp*ZvOU`z3qB{K)c-=Rlk$wWb=yQ$H30KY25OVWgxRyBHXB&~gwZj%z;;tsS6wvV!8~-?KH{j5?ck9hYyuW6|K);%)4`fBZ6LGIYp1D-zx%awYP}?VA(tZ@zO%eFSrrjG3?-PFdnlqvAoh`jOpCKLt*=cA_)^@)S+sX*1M0KPc%BH}px_eTmq|H6`hSoEKNjw4MHGv+{iJu5QOt=l$mSSsBCh;A^0!9HT+bslK#?wuaCk0^`Y$JE>Qf9`e1nqeN}sx#$Ae)7rcIDv|$+!#zWMR?hg$B)+4L6;$I>U;NI^(Ef@yBOFz}sRbZTQ4ZYz7A0lbrYkddNb5dh&HP?&AK{8X+KKAJY1;ov-Gkg;(3UgBnptIfrq^yc4lt{pABo1GF!&nPZ&G81psPvj+p^gJ_y}2i@zu-|a!JO*o8twQjWBgYk$TR~HeIi-sRXMLc44$V06;g|0bJ{YtWaFhmC93~q0WIKrI*&)kb*`skWU1EINOzY5@0gEvnv^0`l{4!1OufvBIjt&4s|VGxcn+3HTm8mw?wlz1rGgn`Z|?#odCfo6w`2byNE$C)|L@-?X+sU*dHyDLB~d16$v*+zh^ezGPx?cGt9eFgSkdHstt>=cmN}jQZfV8wFxOUwd%L&T8}@or7BwkIW~~o=?M%ASbKx`|jvUg;Fa;mXaOF8T9TaJ)(Z^5PjSHqmh?p@;~~1D--67j^`M9;JQQ~*WW_cKz$qa>90d?IrI<;-psjx(q5B1w-w0C1m|-c$zEXWG;f;z2hT~XHMI3wo(8~lt)9c|4Dtn6g$A%gZ4{jZ=10#+gR}<;GHh(b%2#-*xKpuQ-hhf1a8Th35qHR^sqoiNTOS6PzKzhL^F>7AB{Qm_bLB)AX(2ua=pU=Sa#7korez6xi!Rpy;f59%~Ek)YrHFtSJSmxT@hq=+OZa&BsuhjB~)qK2eO4i7Aue|uclNSmB(XO5DUC4=gQrG0j|K^qGpkLV^nMt1EiKF!obe%+gJa}!QzE(0kRuK(MxlY&LOxNq7pePw$i9BbMxQ>2BX!2G{IuPZNMt{(+h&m22O-mqU6-5{N)9sJdzWbDZ!x5hFahjwwBY&8wclTVS2lz<+YL{U`kLp$#UsqM`2M5_p&H0V#d`#&Q({A}tcq@DH(X;Ew_3mj8yj>j$XAYm1o!o{VMVveM2gJgj?W(RXDv?jT5t{lDodiwIPof>w(XU=SzW-Ldf<&ADewVIJvs$v-xNR;C_HI;mse6dNG;;Qc9M>8%GiSQ(j&p2hpbe#-K};51&q%zeP^WYp6RI3KxY{*K69KU%?v)YvhOo!?xR93d`u~G$k7}#jIlC`kE|Wr8?w99oKz>Bv>~8b*9D}{fBixw~ar51Un6;$|dRM0;t!=Zc(pEgQCI2oZEDLVu^FO=Rs%TANQ%s*kru_#X8De{b^@l`TK4xgahx-k`S-(=B_8yOoZP(NatPp#bPNowf@i?nz{C+BCfl2#^X#5pb^7mu^ma569GwJY>L^g24rfa?xd&A9aL@&@AZNu(0_oBGJWr=o%Ic!ModsU^l^RDa=oo_!eTUbg4-mZXd4*Rkt*5>YU-)W}bE1zjJE=%b^{&&I(mZJv!Eejrb9n-@=$NQQ{`3e)l*bmyUDlP!N*Nbvf_rH4h!@Oz*A?Y*YEt!bb(xk;OguJ73~y99^7wGOoNxDtMhXJt@r;*rbl@LA+*j8r@F>k3=t^?7`Os4M+S=cVRvbvA`lePbfpDd7rTep+3ZW!eLaaENefrF@Y?Zz(Ch{8L^e8mvS(YfjSj!5}vk>M!+8BqLX2+39qfF$I3)eZSSc4*i7xO4Ex7VKVd;wvJ_#BbR)^bVHjt9hwiCRUX<~yvXgNJ_WG%yU_am+R)W;oK-03TJpm4zy5xf7-zPI-R>@Ze^~3rV0(2f#*>qAV(sJYp|IMu796f<)R9jHhO$s={0K7|^jAWmFADZt?TV7enU+*we3IA;*Yu5_x!8%Tj^U=f_sr6yyWW;V$tMGIa0Dbp0xX9##FkPT0^a9j3d76Wi(PF5ihh7NVT;fypzI6iZ{*MIQFZ@^S3_KoGj!_(_+=d66fNKJ2J*41?NXLkDwBhea-AWh~wOHWDtkWPSH>w_W5!UPR4A!(RRf%i`Nr*uc;=|&$T`owNzi-ENsy{oTmLT>tH%M+4r0=T7=aJ-2?Pcu3tkp4(G6?*kwEbEp+zUmb;ef&v=nr`=^LmbH89Ly>{rI-OkJ}ot`+r#tO)dg$ZtK@GQXj>GzT5e{^Z~b#>I7=;jfYRw-0SmTow$wDJ~6)?Z~H9|1`^Q4Tmm=iPbM2AfKIPoOpjP3J&(S6|Q)M{EC*Li_>r%ZEnc%G31v_KLzsVCWDZq<$fb!^d+u~6vvX~WXS1GiRPy3TTATAHAm=qFNi#)sDTl^l#*=fLfTz3qV@uz!iG_Fd#EjZf2Ky~AKe`G|EO4|-7#4}(t4bR@j#UU07pK<>0&eIMs|EQpbUQt!_q7n0`4CI=@$RK1M%a6WpJ1+R`*nj9vCPW1($6Yf*U)tf7+PhTM9geEiR?Oc)&RSR%vHzbptjze#n7jnN=*EhpX$iW4kSLjL8Fv^tG2f77TNtDkY>N3v*YCn{Me-vB3ianrn>JBgKyD*ptW)e23weL}@+)1?qwXpt3ssC!pX+5ShriIBOGftYa8jVgLHr%xqU--p{Jp76P~iF{BT^Wk=e%Og$@qOB6Nvq@3U2hA$JGJbRwuYaDSJ!_=>gv7$`0rAVc-MlO;!RTTk$?uwrv;rksJsqE>r84Wg%Btspe;@8V0OI{KoF9@%~;Lco&TFsoofI>$^8yAG3*{#%IM{V!`ReQR5ML^c<$0rDk8+6QNAek7PH7To<^_j}E6o*}Ib`I#cUABAp+xkV^yaQ_Zqpf1B4ct$E(X2g3da@6zSAB+%#)w0#rxCFb=LR-XWGEeBeHmZ=Yd~k3zk9f?&{D%jyuSSb77u}Fz~GBozpsn>uRh&R4K*~1xHVQ7Up2Zb$Qpto}GCV3o27>;pB(NcYk1=y26tLydIpMR(a?%M4#E@KdJDpC+|jCB>GJFlC?^sHz+XY6Eu1w8a+Xba#Wepp8@wuET3@aqbHQ#-Np9yyeBL<_WIfjKU`O?i|dcGvmf*`^zzp6;JOpB`*(9T2SakFNXXDl{P3xM;!dHt=Me29^*M%{v-H&Z4w;c#vN?Tiat;tMQ+#JLxRlViYumU=mU`C*KW578c2Vru|oOHQhWcOq}?3gOs$AQTSfzJDE^h;g2(c*fVeF9Mizx~@Mmp_@Nco*PC&Nu=2^xk%*PO&vl5{ODPm1W@0sRn<$^|6gw?KhPvL1&IDVCzoKH{l?#QyjGLJ`dogGV-j-hvZ1fVh1BPQ684xcbbdwjOKNq<1mb%>tRDH>wNA$jcte4ijl9<>6!WG;sDIE~9)&|HpAB1`FnX7z<(WeQucP3&gi6mNOUx(V>M@hF;zS%QT_JS%s-68Jr@qa9&1xmV#bvFcuY+wC`45eVft>MFNaJmJ!Ehb-yGEMRns{O6W0MTDl*vf2?Kj2&W$+~?>y%eRY~JztUv7YrtB1tgGwfFAD;MMacX6|g<&Xm*Sylg4>LK(NvyWWoV;+V=N`-iA4&Aw1#4gM3wCo6w(h01$HJR`rYEeZCN=_GaV=99*q|K_k1U@7I`06jALy*39=(s`W>K)$38B-+czi;-Ya~yf0ajf4j8cYqDpNhMAy`K*=&-grSRaw0#FvOEG_ePZ?^eL-GjuX#vOI2vjh0~`I6(3f^78QbTV#{p5-c!aL*(rTm9vL~05;8+n~#33H^s93wVuT!>>;A?S>a8)((yu__7Tly$)c~*o?#1s9hHLcN{Q1T^2UME4`0k%Vk0Q<;UwH+<#DM03YmbrN^w_eWS11(xYVSKQu%Z|3vm%La=n98?u9BNF`pCCf24>~=MFDeTeU#C8U;anOHt$(SMr?jhVaDwZ0-xI#eDh?@fXC6<4O##i18f?Yt#5?~(zX&vYI~?Lq$`>L`0(Wy9!RMb;uN^qh{EBKz-m1K{8duldt-`C#wgkS@=vhC;Z}qkK(qypMH+wyf;uaB#mD+5I<_uFwC@H{;93qhPG;{Cj^EyuV`I>2ofIaUlDsVA=6hOjyq-qR+X}t60+L|Q8^7UCwHQx%KlK6rQz~fiNrzpEqU#?!E9#SFMgfz<8I)RQ^qI!Gnmv7z8Nhn`dDnnDdcyKs#V6k$%Z669D!W^Bo>0AYuKMAFAoz1uTK(!NT$h#)tR6<2Gj8#NuHKXS0n|AY0a>w)Ph9db9t|CF=O16A;SfWy*-Jx=hj_o~=)?n2huyOQbcI|Np=-?P9tZEN;!=;w+6OEbX-w?!}>>f2vZussT#7CH|1Oe6mjWke3_h=swWo~A!->0Zz2PnX%n5}|!5>0rkY^6Kq-q+SfB(B`Hsm|~p7dAh_>GA(~E_akyXyJ10TgETNVG}yew8{>Bzzql|llmXvcR=nd{i5^AldsNnB!`{d332En%vu@)xG#rWq)2?30UO&uZZ;`y}F`F9$pFfFwjalxo$V;>q$UJrN@QNwI!8sOv%%1n(xmR+@;BffLD&{5VW6xj4ngt4wfHuGSAD%z@zk3q(&5izhCa51V`crQP&T|dNy;iR$9=F|!(A_LozH{%GF^9O4fHhg!S~wA21W28uW$ccAo7sA&VAn0zsFw;8cr4`F)y8wYq(=ADH@!Azwy-S!@TsWU+cg4#>Bx9DVYqr-{@n$jaLp_98QEYy;6Nggpm_-U|Ub80x?!d`WSi|Eq{?h2H6MG)w6}@X~cZH&JF4Cej&L`j~n^hf8Wl0;K+i@&Nq~0d(hubyDksu^2`O!6N*x`1sNO#yx3Nm*Epj4nfkT(-OMiy~w+5r1xK*1+Tfc~cpQdA_Urr*oB9rQ#R>wlqoe!6-)sP2?im6CWCP4fi&8BE6x;aWuobIU>;H}Xucg%kXiX|Sh|;m2|_0%ji@C%QS6DgPuhif6*X+#oQJF%A8Pa{u3<<@Qma^l|m7{JY2pbWVz>Nyh@wU(@Li@{ZSmBI}MPKo09Sjlg~AMK)|6;SJ--P`5ek@%239w0-|b5>#-AP6_a!FP)J(!u52R0vi8*usT#AC+e%4^D|(l{jI~nj&%7{iRydbwq!%hJ)3cmLtk=JVeLI{p8wxm&OYRiKV8Y{dm9c!osGFVdJ&P=+Nu==#GJRBaOB5gUbFpL8VfA*jpR3N$af}*uMt_70Q^1?wkmXaRzy9;>D**cKbd|Y!vi_7PgP9Q8fcDGD*#@qdNyIv2SMCaX1^MQhrs4Rigi#JAZ7u-~BxBkj`BaLD$#I?cwrgAJ`&5PtITNDP8^J8QbcfEnZPzPYkw5M1DhM1;bkLSg1I7Kql@7@{{|^Z+?_X09WSEX)#WC|F7K4Pj$~HLp8^EQvVEcqCe`q1_^dEeruXfM9*PaGreLmh5|(24l`x+83m$o+S&}*FrQQTjsd;JDz$mV3~M&*@SdyO^d32pekg2_2eki=pg$1(+ManvfN-9!;L1O^ZnUxOSlR&9htsbmyZL1PKi8AvV}Y2Pw2Kk%Z`@kj!cR`1?c2=fBEKcI;~2|qGOSRXT9{F%t55Xji@f4Q0_w7tb}d71QDNs7-F}V&X>li+WL_bU65F6BE|LLv_67VncMm;b{Jx$}>ueS*+h}}e8QnRTk{G{_>qsg}ZQ={k!^(CvOO*kTH{dlEHFdm(&mr|#_qk+g{-M$CcwVo9lc9MvLrk_mTE$He3h(6e@I}(AIM--8R@hI)f6*!Zc0)|9mFDr~EYmJ%E=_@3tttyuc1U?47c)qDW??#IeH-M`|%*7#RSeHO-POC+rPO$4Iv?@4Qn^ZkRYX73%T@b>(?|NVm)=jq>f|9s~m!@oZbX7AR~oxAN-9#Yzs21I`awF2ZOoE>wvnHf-hR#sqY3wnrO<=VBP`?7)PKX>3J^4PHIAh%t4;7|Pltc;5B^;f;`R&*nZR_A3#SJ!EOyPjK2Di*|DLbGdhFwV<&?`igbj0f`N{=f1Z7!NULbk~<8aG*Zuh6E$eyd;!+p(qs=m`_~t{)wDXtJ-2;6dAbUtBMr8G0vGi*ObR|(}0*eTKVxjP!tmue|Hl((U)7`X*_Ijj)`V^jvm#0Wm0H7Hwn^8Ud|<1V*iA#%KwUPS)>B{C0`MbSLjhh|GNt^WZ2Bz$ZFAy=ZSrs0-0fIX(0Tf_AR9b&l4k@rR>zkgT9F~4h+sqYYT9QFMfe6gL)5`F3ZgUwbPyhSkM=2VsyjpvMee%77n7b^zucg$lwJMj8!&F3p`jmCk*MDfS4H|SAUjelJC&q##m6aToP8IcqH>vD=xKq`L2?-OF^QRg?l*H?-s0df9juZ|wI;!)pI!DtHY+^skSJ*O^vzd`QfbfC={c!It}%rmT0(s+ji9~oS^||Jn&{wl2hO4>2Qkr0Ip1Tp9V?OOqtqD;NI@H=gT;9vghNGfPx%27`B&mNE7{v*bl$O@PDW}^RSw}_WvVFNhvBNiI65Cl%noT6(tl!DM>|9p+Q0#P-)aWp1FA*iISu=kVa{cNQyEPrI6p*=efS0d;k7t63W894c2gQ&x=gY+X~R5-={;&pqGyQbwrxSaa@LCO56mC+ckM~PVlUX-)G149nc4JoAlK}5a-WqSymc`+UN-VF6G?(6ufAB2JB)n+NdRMZCtmo*zi-sR*iJm*2a%HLXZAhsY9o|)xb*Y`#J!jO{Go7FL(GG&`!wifw{KfLwTrC)KdF;0Hzktx)P^_OiLNkIJnt=y!(MeAg{{(4eji>&gdm1U^wI?LE7RQhwChgHLY)-n|w%%AUy@i=Gt%j)$8~70#pX!Tti6kzp|E^LR^Y1?mz3FXwYx-32$bvVF2EkfS0exGk4DN5Y~PsUhv8ya<)e$@2@EqCr5ZAc-Q19JS9&`R47wI0#-hy3nx{b)t?rAUhEz!_6Yrdm#T1`#XIrsZf_OUzOJqIY-=O=MePxb8;qSpW<~iE;3cV8QcNM*q(KC(s{;Emf#6z{*eE1ASqX${qg9lvET16*7Y}Y`SJR<#U%`xrgwpRedrdM7}W1ntq)8#i-aLxn{&^$Am_~PjZs;a84aRaVsFhJLEV3G>;VnKI4C~9be?uO@(+x<1s@>gzJ3dE%`i{C0}fw}j_A(A>l1Zot4#mLhgTv<`;wNc-q;s~!C3wSsN0D5J?gum)RWE4M1Qu>e$<;NTQgeO-)}wZ`+|QY&LR4j734-k>HMIde|?c>9%mh7K46ct%Qe!fSsutUSBZlta*1H`Z~MYCLC6WhmCxT5J5fOTTji{Rd!)RDb2;&~1p%<&`m$4hWbwY5k!R}Ov;S_19Fm4A)NeZ!-|p=Wf%2zMJP({hKXV86r!D#!2D<%MmPoBbKdaauyipGO_dGLNpgf7XBO5>@Xp!*gqrskxF7$bzt)=HvOEkm=278=%g+32a1_YKFvB%jjmm?m1Ku%C0Hh@Ezx;fZ&?IFp44P^NecQQ+HyU6$>t?{decV}^ke_{PQ{#nP*@!gLZ8La56_7G*nnO*=lTDZ)Gwg;-|UY1SrH&b1X#47Poj->#&9I`^Q~*!^&EMoI)A<6Vv!hl^6FLD>GSB*s8Rdncds~3u2<^}>W9}YuvFfZ2t>)%XWjBS$To@3Pi_J+IK1^)APv7I`VG^NSRuQ^0F;;wDwOQ~14)oRRb?q5-jg^{4{t=Qq=fRM)jLICY-I|M2y(jM}dTYeV5|b)#mJCi2qQ>f!i+@h~`_tt=dGhrD!td*`WA-@D+cVqd`*jNI}r%Rhdpek43UM!DGd06FKkhfz46X*BFV{(a$|DN@d=(b3i|g|YDGeYrjBIO=1gCw#9vCctQXScmB^-0z#cAz6EIbTVu#Y_eWL(gRjs5kD_UgJ-+<6?*vNb#5~NSxil|czjiZB>QLdTab>yq_65S57xk6wodthSCM!tG0B$9Dwe;5q0PFW{!M7`+arY&b5hr?94fmg`|)IUk*@)$WpaQeg6KS6!r8Wc-ZUM+qL_gf4FM}cRai8+7v#6hXB-^2<5C-}we0y)Ep$%|i-UI;AI_l_qt5qh%iYzN5`i8)cvQ_Axkzwb!o?%G6i&XJg$nY|%6Wz>YjbH3THVk(tc08+=q=;Dwj&tUof3Ldp^4XdxkmEJXSpzVpi5IUr;&0b&h{643JZrje{CjRgz)aQ$yA+4v4zi0a9OY=a|1`45>t@x|M1&ZHt`KQPau$Xd4CWPL(ZcutlCZBKB=lf&~o*w_98KkaFfvu)+NIq7e9U;Z`3=O!gchkdeArD+#*L>H`BLt2MZE5C-MnA;)^PlcvoOQh4o6*m|Rc9K1bcRENt$^Nn(z@ShsTQ(^HvS5=)LQh!O|j+&+OL*b5i|7f!y>2o_gf54|Q3=SGKbV$^o&JPTiZPIt)yY9p7%Sk!0sv)L#`Z6QHbzZl>jxG9RWba$`+a?N1y=++GN73gx`DGnNM`JkigbcmVbT1X0AJPwH@|B}J@S#K&WX}w=(>AEXsavoiTR3-Wj1f9K=db^A?4ezAN+XB_I@bn)V4p8JiTK4Uj#JD&EEKW9ChM(wWuTtlyCRCU-dwrwnBl~vyx-}$HQEt{Xx-3a@#B7V7^q}8`l_8er$(P=D+2M;Poh0=`1OKRZ%EyX5+(TkobK!n5PqU_Oz}*^f?vy>*}gSe2}k*mpNqJg$Iekiz4Wl3wqdQsr#;#k+88@dR~(}?i+f?`YqU2AI0hWusIodY_jq0toEE3h>M@=^lSm{8#*N}84T`;15SU=1(*wZ{Io{jij#?uBXHxM!Y14|tlh5~uu_)-pIxLs%a!4|MdF-Y`9T_|uH!QwavCG6PhW8d1El4HV~^d%{lo!frBB`VEU+$=X?K5zuYaAZ(K`%x;Z99g-~BY)AKc_>;?|!U0ai6jvhvkXKX+Vi?oNn;CEPX=!9lpL^=0@|NV{+hWOP(1ZZ1YnGgZ?Yw^N9N#Az4{8AMJyu3I^@DkcGnT%GgWbx{xb|JX2$9QR|+97Wu-md+_RYu{$?1tLUvMP$&tKpU;yRWcq?B2b`QU*H2eLwa}BPPA@v(_c)(ksXA=oA*+2J;rK0Y+BuA&8I~tDPC}|H`hu05mG=EF)kKyExr9DKQ=)c%CJ0A3u?I$zskY|Y8fetn|p7`6jI+v7dI!pDAShp4h<{uN)9}z@O2zoTiJFP|o8AbVbKSYrSpj>>5DmMcRpMT(v&_*8cdnlz}-xv;}EWeXcr2dk$8>1(8FN%Q5m@413^YOmF8;?<1u0%q83r=T-iP=rg_hwaE-01uQClTAe5H!1pni98-Q85Oph8zakG1d7jIw=peyxHU7C3$5UdSIrJ|adah5M-XcQkQz^Zx)&e3R-s7Ud>=II+aVGP2b6O-E;2W0`vqL{-&4X&Sn$hs|!rOKq1@t4Q?L`ygjfLTpe<=)Z^z(Ve?oGyv;yHaGg@2Ly3ib8YzcWt+qTXj@4*E2^%6FsrM>71XSu`tA4##(bJKuh#!qL4ll%~x%zBgXw(fS@t2LjKvNOeIqe|lc}?Ys+4_owrRebML7iH~$|-w4RyTUb4|o%FdeZ#I+-M}kX&b8aFxslJ{4XSjpS*~*TL*^&dOdkIrC4r#{1n8#BiOHytF(XSy}Js$Q@LO1#Jq5nUj`nRvUCIXSC{>lq|@@oX?8U9S>!G;H)tZ0#NN%3pOZACoSU!vo5@9VN?AnH@97}%#~p`*hB!)Gzz!k$pf5=9>C=lN)qS`-JPa@%CL-oSlE%M&7LH-{4->f{BrOCOQD1h2oFCE=b7M4eQGGp>&j`#OL`e_C1aQ4-aOQaTR~sB7Ondd4f9QaR$-6&uB@5)t);P$7qqaK{}}3SkKe{GtBZ$<*Ml{Yrl^Z`1iMelCxM{shNOv$sB>A^cItkiaPmfS3sL{Q+P!lij0QuGdyg%XLtaWWs+*;DmH|Xxrh8+k-~O9ys^i1r^rx7;0`nFUH!lnnWske*5102ZIfMMOSt);$yj&ElYx$e#6NCD#ZQ2PVInls87haUmiu%VtOKNH7V!@$g?5-ARUyrCy3U-KxnT`XIyTec?&ikA#O9Y}0;)gi$65VR!r$8GD+)#L(-`s+_UzskgX9o>jBYj^-S|dl<`dgpaK9|AS-?5*IoU=mV*ZHCOEKZ%6K?mwJ)r0S^R7JqU6Uqh`{81lKejwW<90lL}`P!36byoYiZ^(ZMjRyJJ(-$aLc)fkdIdvC>_gT)RfNJn)@rFLsiCoc^zf>UJ_tgmGoS4C*^B=J13);4J%?^&pGo~7Wmy9V)5a<@Q;l6}ip;4`Mj<-GnTF+eEn4*iAT>?yTqeIkX|Cw_nbw#0JQdygcep6n?YqbL~<{z6rZ>`i#zywC$D#B~#4bhn=FKp*O-%`aRSs7VGlf3MDWDabRbH3u#qdP#*p1M8rTbWYHMe#N2EnGW5(TrN$~$O+alX>V4s=L-Z^?5RdhxSJDq)o3^ZikS?_o^N>Hl^LpTP)`Cr30BLF1Ajua*}2;q)^~O$J%RV+QW)kq36Pye$bSq(c7YZwz}4QXRV<<>)q`gKB{GN!K$to=&%PQx^YbK)z9ygmD3mr)e|Vs~0be1SM|4*6XD6gFECRBmz&e-*4{@u#-SP%Kb0R6q}-9nS9OE=LXdGel@PV<`4@usVmxC!%6uJ><_MZM?CaBSyQ|4Jo+rO;Qz4NFcJ2=y18P6R5yNgeA!xiW-@2rMAi{~^6xnHLy|#-?1RkTucL9?cMPoEW3ZeKHitU*%qH!xX|BHdweJxF4j%fcFptD1Ra>~+jW>noE8Nwjz2d3i$kBgBt+B#_+vnr@lkZz8h!emQaHoMjD@|Qc0{#mqt9W*!ucYO@zC>t`q4A03h2CSDZlG@6m|EClC0n?e0uzlm_r;FC0Pa?nL^4BO(>3eLr{Tu2;-tk|P7>K{jbNTQK^snn^P}Vyf3k%f&rN5>1FI|b{kDG8iGE;@=!xL4C*gggBl=8V|JJ6YIT^G|6fIY9qtDQkE1Oa&R3O%0MN?7V{P38s7JFQF`mu4vtb@o=$-BfeTI?Ad&fGJD`s>1vo3_l2fdePivzMjfJ`}M{Q|1#3oWA#Sk-Lh;Q&$FVjpyW##hD;?RW|T1TceN&M_jURpTlKXx8rZ{rN3f62f4WZCzWj)FvA{X6JQwxcPg$a-O>yvdNv*e-FLGDf2cDd&!UUMxAhgMu3w6I6S9#m}lYskluDe$Na?ZOPi#-!6R7jQ?J5eu<`fz-mDpw{Ap4`7Be!K{I>DzBr;zqwzPJc|Zd{WMQc$0#ZcQlL~x+k?q1Nr2b!@6P<_Po`o-eHX~sXn~@#Ory5K5?+jTJ~Y}0P>HM?GJ{KX#%A8>{e2$MV&bBZRVB)<_)LS-c+DY)P;t9q`<~?t!E0VQ2*H(J-gO|2JRc5yBPjN-OuLS&|WSE7zd53dRw5M^BG^lS%XZ_7oA*jOalAqRH$@iJmgCSDG5=AqZabjQnUFNsi&iXsGHXOh`i*fXI)fL6$8BQwkJw2L@vtFD_v7?C=MoCy*eIhqW)dpA)!hl0f@E$2Ypd*mf71>E}O*pT}kz!PV`%)+@x^o*4|nmM-^!>m#VFz!Mmf{{6+JSqn7#I?~N#>L(!aFM|DW+RO~-HiFAJ^7}w1@$Pz^^VoyUBTg0Zo!GO<8Uk#A*+Y1M4oh+hZ_svg(!lb$>n;^kLo{|{2ckH2Q+9c}4`l;P^_V0PZ^=;yI$cFS?;F5U!UH*<#xzXK6ga6toupjoDXfAK>eC#y}yDd9pN5L+m&bv_!1Tsl`5ypEjosMohgF>vShq@;f-l)ID9AMnitcI=c2xU@HrV{gagE$O+Rg=lx6yi-vUN{Tfe&@cPMXRo+DRvH$&ycd>0a>O`OAuw!wc8szg!(Grp!%EZL-cy|Gkb~5e(u|Gu;0x5{gWQl^Ec+oyirK_Umtl2`m7NB@n-(~Bq;8Q;}vyBpZ>PV=7p;$;K~Mu<0KBeJ;S@cqlyY&UUZ$;xr9Cy-aOmRCqW0HKTc~L;&I#;&-FO+D2@Tdxd#D99N&rKPJ_ULmFjatf=GNt)YVz=#K0GinIhU(^l7lTgra{a7Jl?*D_XJ8=Ys{2OO`%~10p};k^}m5bJ}yN>Qn-()NrzXzZZR8?2%ipxH$<-inhH7Rz;uf4PQ4000j&l?S7cO0)0l=j;k%Hp@NCUm{xio>T#u?)T;&Pkkauxcs+@))`ST^IB`+V`vhn5DRe>6p+-GfBK>UIf|GE75|_@mNWYg@)xdCoo*O&eQZF7jocj8C>0O)0Ka`FXlV;vWfA9O061@7K==PWph`-TsAE6z@rqyn)&xg`Vl0f{{AqjNJL@2Ml@$SA(Pc}2X(#aZ#-e9hF!B^SAfc)lFJo&W=#S8g3#jrzT8rR}*YNnmj^lCn7lx#huH=9UyW3VfHFRTIHSTEDv8O{*)Rg4C3+x9k$+qHSyd8kt9j=aJRD!$EZi715u~5{W{*)TJCOcTXP(zUsaV6@(jTtH})ie;y&KT`y^4{{$`+5_iG{$^GKObxPM2SM^J1}2IBj1u15X$iOzT;e`IUa9xL}e)c2e=efpq|25(#%1oHDyf0DF7W^^Y5Ud9!rOAMgyE|jwF(F7B+dlod>A4ESN)k=9OpHhIb>bCzfG32gG)>o?Hm#4$ddAG#|4kC92C4Cc?ycY+)QwpaAzT$qLoQ2JKE|~=QIP0-wIUjPDHxKusoXSL)Bgijpz6Et6Cs!^Z8Mdl_Ozpf#%3D~U=5)b=3X5d?bTk@JC+300aWp8rdg2yE2f2$lmu1b(fTFM)&1-(5e(QMaLxl_`TxCxShCU#V4Yx%#O$VlM`c~|WM(!eVN-w3QLBsglFZ|BPOI$D4osch#0~elrm8WW`2i7e+StFVNKL4^$r#hid)Xn>5BtrDAJLgpMQJ4RB+~Sx=GN}4@1lp2v7}$?r*IRq2z{sC)x3xn3(ktPy05=*)7Y9Uicc3nQZgj>BVR@7Ej*uhmI*3i88SKA`EB?XA{om*#6zcr`CS6eL&Mi*9W2;fJaA@=VdSH{8T_q4AeA4z?Dj6NQ+l1cz`<2(MVcH?!C_WP~c@BB$67jp5nqM0tRG5(Sz#~Iu3GxgZCyXx)vBw?tyA2c>IMkI5?|jgno#;qz<=a_$|ZFRicc3PE@;}da;EH@H>3frXkdcbx{dp8YFY`-_0o_Y_FGsR*7`|)Y)Ifk6z`g|Z^o^vX+U5&aLq>JNecA#^FHh(-Ew%*zJVFLY}-S%?V=*a{yy>#Q`Oav+4-gDt&?fyil|HE*illE1KKG6`C44rKr#v^mlk7e5z6YcF(;Cry{%F8~~jgPke%sNPedPmzIGVSOyZOe0w5Pv%K7VP?CO*-coW!1BA&PN6(53Owpj{8ejZtpTZ&w}Nv`a;@$o4n((C<%7W?tc7?l#4}-mzHc!eWFtxc`uDr*Yrv;CRmTn{{?$mDw6PXCb)5s_6AvT>9qmzkh!`*aL&#D|MMK{NPwx=&s=2=kk;Q${-tp3Pl92cCvvT%eOTw=*m1?-WFYRpa3T6!dORtS*PIGJj3jwF!cZr2dm`BLdLqB%Jt@D7$j4E*MhC#^w%FBs2wn`mK?oK0%$}=_Tyr_dWY`w29_Hg+v3LS(D1R?!;GC&YbN}gH_d0g_9x3OO{a!qWUW6kUM{-RQMt0FbJKmZ7W~P1i|luX46}+Zc2Hn`6ZKD7QCXx-_6>F=l%$8e!)tGe;+qkT4_AiZdpM=X~L7mIckB7lnC$GjlfpweK&g+hK=585Ro0bkR;Kpfnm$ERdOV@Pw`O9;K{e6ku+a5hdT0dkQjlF%Hq;-KPwpe)H4dyISjXFr6cppP7W$xwu4{&+T3&JhGx|2RfjiSi__IlgpA|@2(ogl4PtKub+Ni?MG!lfAp>$>#{_hIRCYCJr#&NlH;$pkFFrq!>69mR}o2LfNZ(b)${LAUr?OlA*jNFM2A?~1yU}S^JVSb@lz=v5+WT{6^42MU;Fc?|I#2WQ$sZ20x4fYZ9H>oXC`E{jd;7YAdi{5j~joSlLXxRU1xvYgmvjpgUuShUQ33e?Sfwp=%Jphb>7%gl*-AwyKx?MqVGVp01eV#b7h}QMSYNa*Kz?xI(U4z(tYkP>Yl#J`fps>^YppPv+J)Q*M0gt6>l@f1Z!eqvk`gBW~NzHC_M!lPn{ayxBfE|i$@wPumx$XmcElCfU5V$;e*Ju!OSNMV#Zv`z=;M$Ac9G?BiMbBT*-LI&pfnh!KR*f3+&-=~0MfUE`fQbcePejd-a~Q71Tf*7j@9*tj>NJX=`F`y^qW*hF{(*(_sPL?4YjAcQDet|+%O>h86;|e5JfpoA?;AFC18z^VzxNF#iy}KwUzH|NzH>bTeCmQ%-MNK+^p+g&xEag@ZW{>$MF~Ax?)w+{q`aw{ck8xEB!R%A1jm3lysz!#fYpWT$)KpKBHAm4_g(!Z|A+T{Hb2;vM&D0Gy(Q(7RR0JSf+pWjWbQ{lwSrN5ncrxzC+Ys})x78@&bI8;wxtYk3;2{RM9z`e_gw0w9TV(sEGUTTCiTT!g%4h1?z#2&IS-nx=(xlFeuHBig`ZTTf62?mJ;!D#qM7&QF7%OSbLK+K!*|xm|K()yK#xa9K{R50y7&9K{TLcVyx(9nM?{$k(q$j;eorZcY#|p*4obx=csQh>s}hR*L*(TyIGqaN9ZOwyKEWK(O*^atybh+rabf{&5$1>z^(|G`G9h=Z;W2}MnA1+w9r6!l|L=U0C32V8w@pu8%%MVwUG&@`1>~sflF!3;G*f|SOV~7xd~!XVqFP=~1K-9b38XjE_P+l3tgGhhArM2@4*d}Fk2bVVj)YMPi`Fu?0CUv46!a3h;jf9~plK38q_308Pb0pj?LU?y_T?q6csPl~Ca_~4}T`Ln2JKWRQ9pGX5mId{sgO{iyBN3~=!=^*yCcGR5AJu|Lk7Z-(ic)L0PER&*!eH|ly5^S6w%=QY;yfBlRAuQRwhvf>vj4H|p`wDz^2p6IlD(!4AKY9^nu_O&8+MV7M?wfM4u|HJMF^%lri#5~ZcoWjZZ=heV{!>l{qXQ*^4Oy>La4IV)KG}rK{-#+Z|)ZQnp+ZA=Ap@%iLY)&qJ+nOj@gu0x0Xw~^F2K;+|XE8+x`N~hOo;90`1uX-o_=8A&58J-SdY1*Iz#8|?-Gir)yH@M6I(ZMJLF0TUL7%J0U1!(>bNs;!kbmcLci}ALs}~{0eXsqqK;QWj7q1_3(f+!N!hG!Kc=`dJ0;wW=z4vgDV?zuT*dIsk4ncf9`|)!`;UW!AJsdoeeF$}fiKf>1?0Kf`xgpzsG}1n%&0pKYfefghI`wtUeB>ylyxQHuZA=Iah_oHQje37VO4G!F6yW3~$Rl5+d|#03GLs55PJ9Zi2~s`$4LL5I!E}(B+9w_L1Nmp6k=ZBRSy`~_shZb&MdS*#eHKaY^C@sSkuEcQ6R*=SvC@f`J#HOO+}QZ~9qJ}KPD<@NOM?>Ovi((tc>R<0m9tNn(Ls2LR!vV6>O_vlC1(csQ~pU^J%fBj)NdJOGeJH4WXAAv^g}#1mW!ppi}xF1DU+xZeMyw_Q(@xNI@z*GQXZ+sleU^`>Ch!16cizgoIvz*?|07xqVDg4KdJ8BezEMUM-=#|s=xWyQoMe{gHN-~*x&B~+1H;A$D>Z{OI6s?INX)Ap48`>zk%}T5FN@oiw>{rM7`JZ-hlrJ2FUp7EOSpp?h08sOD&qsjqm0OrSo1#pXYd|sA7XG&iRFIZ&J?Zt#qYw`&9VwO;5Ik)TbuAk}fowgX1Z&&Zs_~0W$R1hlg(9c)Gv7_oHqn1t#kb-MB~E_gs_D>@lEHK~4Bf-dR$wIy1-)^t(fB!cHh+LVbkLZ)g$y}2|h0E<+gUxjGX?$3gT6c*CjU(erSr^eK=iD{>`<-XF(nR7o`W)$c^V0cnQ|dH7D?=WH_1eq-24CJ?#5CRfov(T_4Gh6NH+58vsPp?`vl7JN^Enb?k$sX)@Y(B2)p-#es1ht$N*`#Q)cl6;ixJ99IDsK?Y3QJ=`v1arE$^HTgR`HQGl2dHPWpX_2`p;&{xXvPkVvJwq8=;=frmM{8_<8?5#J476)E7iH}68!d(`zNFY!%Fr*Zmx@ssuqdp|QPt|q3#pLd6&+|D9jg|}xX`})#gmH)W&97$ZiI#fZusc%7tm)~p`CY$4aA7xfxc$6sv7C$H{?GDEMzMj(KvH~7VAaXb&Z(zNX$cL6+qtz^MCmIX!B6meC%E}PioeEc+_-9xC!hD9!H%cM!ZyIE}zPtF4j_X&H`m=`3KQiF;YOQxBH;~6PGUBB_$!9~}Op{fGI=-H$FDi}Ch2GZo<#%k5>n>4mcXim%;NQx>6RvAO@Y;AUy+;#*HLvS)_HUrHz(WO<53e_~qz_KX`owL+O#MExDlVuWR7xkN$6Oowe+j0S)#Q8`kb3^`rTmX76JvMThDIs}8q*A#qOh(Op&i3{L*A*<;j86n;FGkYWPCgHxpbfbWfF1yPQ(V3%p|8vR^SALp0Rm%cwuf#KrUrgB}Vi@y1=%F#Xz9=b#1AaV86{tqBuOP)3ew&)+wk|1gJ>gE8+1?i)UcYYq+BLF1f*Hq1aS8q)7FzBZrDhpqaPT`y42YI^jMXDT(-T}4!AK%5IdxCmb#bEK0$jXjT3+qhbm%K-HiuWkj(bZ$Cl#)r$-R$bi(98Q*l)pr3`aj`YMdwr=&MEXcQCG+45YbS`iAl8D+ZG|2P_c^2~s{Y;z?`Xly*1~n>YhCe2=?d`GFRl28^Sz6=JdIf0hJmKSe164EAZ4TJqyKK7F4i_j@1{R<5iU^XoyKs7DP28c3W!BCIEZeu%nE$`2aMyDhfcg_PsUQ{303&3?aJYvzek^YL?DM%~=Dfx-Z>#K(Q14D^4crsDMe1SV9x`TJd}5dEj6+c;zwvp9LM;r-}e=);2J&TNii3}y~ki=j`sqO9LB25G<_`d6{zIVo>yMEQYJT{@hfP5YS_fgEzA=ibw-lbPTvc5U8S8~T5GSFq+_!~q%1Ubq^!eD(0dtN}~QAJ6T{I8B{=SpA!Z}sPC)&tZz|9PGAzkgr)KmRYa4lh^}@nAt3+z(2S*svP?(_8%Gg3qTzLOnfi{1fUe&pwJ6e$0U3*zq8P2gp|i`j2+=kJ4d>&6X3P8h9S?XOd;)vlk4A2<9;xxrXangTv;Bre89l^ZKS5oibe45^*{$)&GkHoW5;eurB>s{!f0IK`JcC_qVzoiS_54I@^vka1c7AZ*dRnqoTF?MB8FBK+wyeV;u{*h{&NBj>&@d7aNM#G$4Nj67(1J!hwb8`g2Le&{R9wbDUEe0f;)QrsUT>IT&F7(nDlmajnWlHO^)%`=M$;-QCmn?#XY>{*MR8N6Ttk;i7e9QO@>e>_|1FPREvg;6nAjgZIYANOAQJ1Gqej~TpL+<;s}^nZF|k^#H=3tczdLw(1q$^JzLvVh*CBc6X4uftjQ@y>xK30p2x`tZIhbS|Bqa>)Z?9w~AJ-`A*MWVd4l9hlBL_$EnxXD+_^S34EOfKSIgDf^sJFR+$bWEaGQ(&#$pp8cp3_4Y?oS+FSQ#?B-S)Q|O54wQ_fK=X^UqPlvh7uQf1*ITCnk#9857xir=$t&B0GGP8Z)|s3CP-jGWdVBoN1X;UvUt(KvAMn`O!+h_gayWV5TUQ}R)%_dz+NGWczSGg$%DIu3hdb&wenmAeZ=o*Zu#h!#j0pyIvc3^*s3%gxP2RaXlPEU32u?tB0Gj!P4^cVa5{Vgy7aiN2HB&VRajS`W#nM-YK)ReWL$Ul@1dQ@cQeik=Ch*I;TuM78qYVFtYI^a@29Q@xzWO5D>jRIfaxv$~D3;`u8vuh&-Xsov2UF`%!g5H61MX?B)583Xb2a~xEU*&WBPgkb<36!I^Pw;YqP&!HgGlEG-yeLmKqZk5XWuPLMpb3{&?fXbbW=mj@p~F5mi>%he;9p6r28Dw^UeTkqG3!Tj{C&#@0nT_1c_{kbrZsIbLAWX+C||Um@Zr)cPbahO?SbU*M^hnpmNBsZFB^E_LL>0@|iPW^y|6MnOG9PGK*lnL{X*iRhP!g0LyoYd`fw`^GOg=f322y#f8aX`UsCLLaXk)k$`&S^?o9TJi~!GKzMmR-g?QvbxRfV*MxOd#@N>jzLTa+%k?PKX7|O+&&~_Mra|>8Mj*g;U^I_mWVJG4#I%43wU1N`<827~7p4iF8}Lqt!{bNBwjDtK1Hw8|)b|aMOS%_Q7HQJnl%eWCJ{Y8Yt0->sK{PvMz8h$ODN@QmngQQGaw&^<1G&KJ3`d(D1)VS|7W=luPCt1Cl?5C9EW!@4NNSg^Sh9gzC|kd7U-LS3F-J=}H?5E?+<7bNw>%74g3?lLF8uswkp?oWl}MewkpL2JbXBe!eM*TqITX>#ScNoAXVEd_QO+M~OcEck~K96V7OUbQG({b*c=3`{JUEY+z=(xG$fDufM>4ppL%Dh0gfwhXX6{`kOQxExyR+18a$kr=BzVO!s{#r9aGmF70d3O?wA@Tr!KLe3OR>sbv&e3v%tEgZ~x=#r2fm*9%|x4DKOBpw#UH$^_nN10@bQ%K-BfI&E)e@Lt|xH)s^wjfRn=4;WHT~&s}^8=`;lImgeM;upb3*7&fP&Sx^(tWmBJ$?5bv)!0d=A-`AjJb>>s*BTz-K1s(w$eJFO{Dt8+(X?G);x3W6>BCDK4WyPG<31o?`{ZLTj$o=BtAv%avHDEOJAN1Yq-6m7?a3dYaKRd8*jaiUu?vzkhhMcpGJrPQ+&w*AYjcTU`dZ0^jbgs@Bh_e@<^VvCBL|Ib4XC>mY8^~|l)>pwt(}WLU0xVoIPH=JM7|CmX&vU8w8zJjM{!y;Zuu!}9T&YYoih)0Q9z$s#u6Jpdu2eF!I(@4sZULia@YH75?RofCXzyN$8o>Jrt+9XPd3PhaOI|u#(ll<+M??fxt#oYe+L{ljhcK8ewk#zRObmQQ<9W#Kguh-xSR<^?t9ISRH8mB|JLVy=rdr%S8-WJD*Sud7}21PKGP?LFSor2sLS+<1rKFzH|Nij+EbJT|DI_63c@8o)-J1v(e`sySP1PZl{32kAvNAq?|FQ@)RC}yQyGj=@Dk}2mNt?owz^!}hCWluZp6qrWJ333+9Qjvs1xUW)4yhc`l>$Gk3!^=_kZvG?Fz~P$!}9ujW_B4>B^~dtAhmC^Y<2q!pEfgtNmPB8B@=gkYjbLhC#}4CGrh|V_2Y(@})k+96#q@;$i}k*HVDKcKT|Y6{)YHj+DRo)l_iy^r=n(^m(v))vctcG?>~rm}5gaS7^()biJTH9SY62s(-zM{)zgTOz}+M_I3DjW-t2h{qjLG-zN)xdJiNOlIq)uIys|RIZz+qCPIIM`o^ypQl_+6@M&k(jDIVxU&WqJ&DK^-0bWPux#lcfzuHvy?AS^5RLJ_9G#c)L>sQ3So7;snP)>7-GqS+Cte0ck@7?K02cmDP-~_Hy9a8?a+0Ho=i2d{OZse$~<^#z!yR%`x^cuJGw@&@1Q!eU@mLAE4%U3;LQO{sqmfyXL6VosApvW|EKw$~$M80jdPyw(W#Z+-A;&uGX4^~=ev%rjp$8-E7^40lc73&k^Q$V7BRC~S=^3`4$iizabRLDKi<=okg9L2rZYstK`X;6M=@_orU!wq3>ioH2QeZ9fEduY`k)=}co0bQoN*}I%ry_Svx8?8CZqJ7Tzv7J@fa_XI3(DGCby+YRXL0JBEppNB%9X||6;dFp_F87K4eCMmLWfQ(rUE}v=;)66TZZ-x(u)S@7%qL_?|;@>Tq*%HgCJIUraxXP27|^3`to%L2#Cc_3hSear0`T-RcTgk-u>@`1=-|FVe0Ia5}Cm4+-BShBpX_zd!r%;Z5u<=Ip=NLuA@#*JY({jD-$&D-jzD~4|V;gH4k58WWk1gFD=icAYc7Bcl26{PY#4++s(gy1v!U3?dUPtlLtc&%#KyvM9yK^3KrFv=X2(FJdMZ|1Ae>=nh6Um`9JK=MA9oye1V+{GM|~`vvO6dhb*9GzjPYwdJrr-gm2J#NWkk=^)1&P*gsEI~4qnqvhqFemp?{X4Poi(&7QYPmOP~9$(NO4g=x=4%oC=%1*cmNLzN^`;pM{P~bii21NlS|pAb3NpQ$;}U+C)mj6que@l&9NN#_Aili%9cuJr$OqOIEzUp5cBuj4BUMxPX^?oIc0rGW9AQ^GGS(P!QEF`icORG^P2eHbB~GYwx?l-0_e2Jg&FRlktduQvG9=(q5vgWAN%{XeAK(QCOY)%Gf7K&EzV_qkTum(a&VUg_;erH@rys?R(*-b$J#Lb)EOOq5s_~hB?FXIS?w=(tl_+a@0-kQ?DB{bHRH^FV3X}b!%P+>&@(W>*O}g<2`)1ex;@E`r&h7D%5X|H`nh*zH)qg_(W$z8k8jumF2}DU%9l}CPpvFfMu_vqQmbZUtQjrt5tU;6HZYbEGtE^{))(t+q)tg>VK=nGZx|cQmCWfo~M6vVC%=XaRQmcj{1}PsW5W8^W@4~$XCSQ(Y+UGK;%Mkk?OLD^W)za{BQkDEfIO<-Uk`Ejh8dwaotwuT7BfJN4jSkw8gVIbu6p&kc;kVIF$B|<-qin3fuc7$WdBZs`gR7c|i09diw(Pf5Y5-J?Z&Se=bb#RzF^c=*#};V*&Ix*9c{Y5h1x7|B)zR|xZ`_u0fg^XW^_{ikFVZp`6W*N>wlF3`{#)q`A6FCJC{4JytFD6zL;e%Rwd~~|M+tD_uCQduEU*#dgRUA+|gMXVDjRP`1xn3S8MN#RJF*2(?kG^G;);B$2U({BUvElwpk!56Llhwa&vADRKg-@hBxw6Z@i1yj8PsC^$z}J$XEC8Y}iw5mk-J}d7evcME=!KgLKl(-=@HcnO)NhJ@NG!x;OLNYf{1H-BIntbkyHuJ^p>XF%6E0NceC0K;o`l%Wm}kOy``NIJ6mgDXd$W;-{Ml#uwg;j>n_!Wte63vo;GR{vTCm9!^#J^>HDkGNj3zC=n_YQnE5e8dQb`M3fSlA}Ujp6q(7Cc{PPw)Zn}O}W&klKXLliTj>X}UyCdpMn05@#J+A!6Go897N|hPeTUg-89T0v_IDSf>KI%5Ku`d^he)%@CxDL@L!KEe-re{TK+n*x!jo&A;>C&V8$vO^d59*@vx^Hto7Jy5m{+hzW$WaXz<+pNGC}0=wb2Ne%d8Yh``nGwgMNn@&zW(!l)V~>?y6vpR;i#jjWl!^wXHuQ5mZ>azO(%*97`IusaIt%YxvTc8aW^Eocaph#ltKxk-e;&7Ozn2f5)z#+f9+LW6{5|2eqPYMBw;9|qBKfb*neKm-FG!iJTbTjKEqv+b<;5;VuuJ#&iiVYFXUF3W->-h9PWB5e(L+0rMKAuAoJ^nWi{%-D`~JDtyrOQ!jLH56LxZ@Vo)q}ipr6kKA`eUQ0`8k~Lys5pj^)CD(c+;cOVOS?v-h#5*X2QnB<+7mGuIVs9JKz2CJ+n}&2;B9rH20I{{Sk8yd2*;A=_kW_d=>Zo>fOKi?bPYu>$GSNZ4m8`*x19<%Hb%h_+I5KlK*Fe`aO4lb0%~SJ(%eyK#HTy+C2W2D-Z6AMk(y}CDjjp@yIoKmIt1{cN}S4OX@S0SNP&9D357&JT+Iji!`pjN=3Ei7u;yF9dW*6o<>LeKMHmU58d!87`3WyQXkQJtw!BK2FzSvT{xH2U$k=NgFrRTxrRPlS8FlJf0c8WJF#4$0GuSsc-H14UlI8_-NuFB7}uaa;e>oe^b?kkqJZu2g6wP7$XA2Q51wZ5QzvK1=tCR*|+FnAJRv=#y{qHVrV}R?UMw{2mFy8lERp!(iTjpe*A$>2_13uAgYj?iP0_zi&vyTO#ephbA?!0GgxLBR^ZihPwZPj80694cHWP&pxNhkP}1Mr(6R2@NW5bB*VFBNr_k4RaGSW5C;EUI%{(piY0LD)V*^6Ku>)XEyCYov70;2w}l|I;-?Z=D+njC+9`-++)L5m3^PLNFWCi^CZ^k=L6@sYxw3Ha?A5=e8#WW6#y|uT0Q}FQ8|(Gxw{KtO!@iQWKtY(QGol#4{;PA`s0cVqkcZ2v+>4sD%3^A*%^%@N10u5`jwMMo1CxhMdGof>8(<-z<|VzZw9MfQGeOGru3~b6Hcc#Cgdm~N3BsdvXMK&0(*&XjyGKX#Rofe6Q&(jbWLMJ%A)0!Nm>{mTzf;$db(LYv>Ur^_4h_DYF_h2%SM;;{#no+C3+h5<#W62vUe52-=!OUGm}X9T2<@sdPPt`%HuI#^h;76yTVK7!XHIYp7r;Gwl;E9(D2qIpDQ%zj@h=XAPS<7&8=@J{`;u5LGS&M$rS?U^%KK(x!b!1s?II&~|4Z;N5duwg`RTAS)&Y>a!E=0Ng~%@f%9wV(68+T1Cmd;JsYV?Xqd-Q}DM+)oc&Tjqs)^=;_w*%_R3E0GucQVeW_3ZeY*Nr;S$NnkjeVaFZ)vv-=$TNeV@2-n^&VWD;D65e2#)-b$PaZMh>ir)I`?n$wc)I3`>esPg<@ze!_Njd4PF)Xc@lg-Ee0ZDn$NvKeUmt^&GlqK({cIS@lM<~iQnh6gZUt%|47hOhGb6^vz1q;0Av(pA80=&)m?IlK7YKb5V!?1Ob0Haoy2t_K!Nh%RVGdjXy*ZGwGU_Aia?%oP*Jr(JI9<>8$GR{0#&v5T%BMfC|<367E`4Vm3p?q+ZdA@QLDK4C0mR0jXs{nR*Uff!&g?6&$hBgl@DTIKB=Xo|QKs*03a*WwaDbWA+$F;LUXs66+h5BE5Mew9!=d&B~_&L|SJ2EzQh6)jneHBj}K>N8v_G-4amLZ5449TXM^Z}~?LWK9EO+N826(?%CV77V_0C&$67R~GApbY!&b+$JDSc;fjOz~Pd~j(JdwY>o??BYib#V6I`&*6Tf`ie1y;DEFfk+`7%{`S`@_YzdG<2^>-b=FI)?xf%vGoz~^GLpNKoQH`BrKL&7};f3!d2=R;x0WI&Td$^CvaQXhsG4U1C;m~evEo&9x1_LP1)<;eY!q5|-0-Q_8$i+n}BvyAHty$}u%3C2>$S26*APW3iZK;0d-SPf#HRc>lh?Rka&{KJ3FVf~V|@7bsnKAk7o}y7lF}RSdY&vOLJ)3C0JBe7iOBOz_;rQ+Ie4^3|F6kN1Mtv7qsl)MeKU%@}Naa9j5e!qO5Y2qGA|i+4*WO#r1{x(oW5|T>#$#jdwdQLB4vIlUyZJSvc8Gcy|}_$-@cbT%~sukk6gX^bbP58mbBFYEY%ZJ+Cia4Qr9Fu9$w}Ju=%;Axh`c1m^I6M{^SlS=6ulc&Kz&4E|JC~%EJzn$^=4`5KfP0z$P*H^XaCoCLjClVE*#r7vMIe7M!PSMXnjHZ2|juGr~r=n3cZ+MAkWBE2E>Z)He0t=3WXc;J#U9?t}W$o4+rdd~tnn#j$H=IIy|!zt5emjpf`=TtwAURT;&03R<`ETUVHc*#HCwe4vkoY&)(%)E*^5qI|Qrhs^;llt;zQa-%J@I@a*Gu%eRuS43Slh4cOqINsE`m6YFpk2_KAD<1u0LqeoFLVj%qJ}KZ1tA&*JdD?cbwf`yUj7yTa+xl`?o=t9{Hn#~xDPa6|5=l@Cz=U45)Zq^}5~9D)qkLC9Ce9ueBnDm2KcxVNas4(*JW&q+TUM~C=YqmO1zXlMLW=I!T^4AA@BRl7R|d4Q;=o94`fbvO8bYJVm5mE!7bIkk-iM}NGs2tJMbrtamO%^kXINc^ewayMyiOT6zZo5KQkKi6Z3%@fHRuA7B8{Z>;_u+E4gt&nPhAwr&Td)E4az@iK~)pI}0wn8uUtU{Zh1+Czc^Z7j$*I(#($5UKxpeC(}@Ed@a2@olpw&2yah!hnmj|2`0UmS?MscINMreiM{JnVchBAxz@Hr3bw0vx*>CE|^bAgp`NB_VnzSYAQt2d3WlqA?3OGt-tTbLx)qG7nUb!uAkQVxLN)yIsCBLUew(K?I-$Kw0~qw_NAw3q5V$b{-GL0Oqg+iM^_|Al^$9we)jyp{0>(?eoyr02_!Rd$2%i17c1)hHzSD;x8{A1~d)lKmFyiN5Ricgn-?!@7`tGAJ_{tU3}@{}n+%w_F4iGHd}0j?7UYm2~&81$uxe6npB51eOYyeJ;ZeUi{6DYk#0@FrCHtI^u-qZ$B!@o}#OsS0c~Yf(Y|!koz2;kudii;p!A!Mc2=Q#IoN*rcidUzxbeU%fToyNbu=*@M*LyX$qwd-iAmaJvqqg>Ol^UHOeClIOBh;Hs~+vj}@NZp5MoWWize7J{s>!#2r2kvp`nN^VpfI=)bC_4GdfmEe5Mtkr0d7m}k|WU8!8ZwFK1GU+yT7!}`IsGiLVm>QN^1G~RckPUJ;AF(?87@n6feexokTPH;7Lrh+&TNK!|R3N`Nj;K!zc#V`KDi%5C$^6x}z+~zZ&aZW*|=py8(?`J#;x_cPV64D{@?gQ$CKe4Tz3FDDB_Up{TIN%)ZCEjL@EGYI|wR(0M`mcyS@b;hC(3Q0Q*YW26U*Fd#QUaS^^}ceKC)MkDHP+V~Q^2EFMOu0#ULV@3ab>4|5%_y_Q{K3szH53`H1`22SeiZ`jxI;tM^bk;E1d=_G|jij$sk9)%y>C8$jbnm4oO-`7V6G3_FIiUV}R`Lg4c3pXb-Uu7SoxNdBwArAkUPWZ4HsjVZoJj)tFut|tu)=F7T$CTVMNZ^={0SEp9MiAX+HQ(GK-5i39AtxjZ7PIDL-7{;OWFvLkc`iSad+wgTz-uzmKS^6+yt2n=U5Y`1xo?SYOuErox^bqOpCX{Hv`;oq2lgX+Xqj?L5)Wr2gx9%tAVhe09ovybtXZbnctA?J{Sdtq}`TI!5Z>{%MK$wVh0$``_JAoR2(UD{|P-c?ApRN+_oc&&Pf9fc2l#Y#}zh96fI(QjGiN=o{}^x4&!%UGZCNFc|m86;efiy>uy)b-`Odp`FJA9vDc-6+!r*j8ASVY2Hxy(oI@2RFJz95K5k(ILUMCXi!Zla-C(3b}FopXnKE~4k6WDPjwHI{6c1T3{o5zFd(SNrdi{Q8Bs%?_<&`w?HUxP;6oO6BG^tne!eNcN&PR|USLxXWXdChWuwDYG7?|V5_I@I%qS)W^rd_tr>tkq&b<&L{P2QHxfp)CixL^Mw?gaoX3qYba;Z=6sSke6MBZWWZwiEpsQAqx2ekjH_&f(w0R|BH!hZA7{(&EZSDUE}=y+5wX-=B&9Qf;bl7uxAY@4dMeJS`{ZI_+bN6%(~#iFljpCd?lR^Ry&ovK-oKCyZ3k|5+Od9J^)4xD}GN9DJY!}-WjMBmS|yQ%;Ee*|*W-e%`@tHWq8ofynEh#VDTG1qNxA057MZQol~gB&%jgPVWw76Srb>-e>dBS(F>mhhmE^L<@?m=TarfxHyYf2VOC=X|GFEBvVZE%p($^B?z8EM|jhvGzLs&DclO>)f38Z$1=5E`QthhkbTaI+2&)pj-+EV%C1jsQKpy>(ssQxbJg~brIC~DxTnfLYh0nj#WM1se`=%$T>tE#Sbqk==&B-Kws4OJ_G16zgUg4@%le=jyG*cV?yM;uw4UtQIBV6Jlq(=0#k)EOR~BD@l~fTQ8%uc$%dPS{kK9EqW`L?&}N>`qhgT%qwwh%3*&=2rA~L56D5$dQtVNF|D`FN$mf{jQ3P;t?0e=S%6Wtqh3X~ez2~L0YqQhR!`)v@{#Gof)Pw`TzcwU>rUjWBtFBTbEjBviD`D{TsZo#_HMr0n;FOkNmj78xhC>eLpURUcVaQfK6J7DP=fv|{lC16gzlEWEN9tc)(c5>c^(nk-@S`KP$ctoMl!BbKU0I|>q7;iOyrIra@51s%bjOmqk&+CY27n>)cXdtC8FQbC;JsJNqybF$G-A5$zwo6*l~p`R>)T?dDkf{@Mc10vF4~6KPk^@hBbxHiUspO?;iWphdR;E|HL*n`24jF9ppxy;k+hwM68Noe7|e8^giS(UYWs93*1U3^Sj(eFh2Oq-1yOXuOcYAda-g#Ags}@KMC2_dIty8dZj5M#1i1VFPV8PqB=@qTb$TMq>>^iY{E*n_FQryc){;TxM7p}PQ7ek4-$j_6Ee>~8s>o6LcC_bkI`a8m^8hw(d^zsbF^(C%Flk+8`N&Q8M`Se@tsL;D=IP@D8^{!KaXDyG>Cg)d9w?TV~*FAIHnMj8dUf*tPU4h&}%;m}TWPta;>|Q5we!I^W&&U-_Ao4N>){^=jNSt}9$vF>B_T@W6;ug+aDOEHMb-z4;EUJk;<8w@^W8(09^)-kXx^$wU$zzP+|KJEeZh8}?YNBfJl4kog9vw_Idv`fbQohMPv{p9LmAmUxCNqwRU_1!M0TNZ)L(%Ff3zoPv~u_10&YpDO#H9REsmvHokZUq|5m%nnTx(w~VXORY*HRv$hIap*v>fcV}Nf)hTKvarZd+T4c|K-ZuYo^Z`P#3u(?BZUue_uSkmT{VM{`F3%x<{IysPC0(v~ev9I)!xq3K*jOL_dMSpDd7WPc4Zd=1=}lC+1u5-sA8yG1pO%#34z2wsuBEz6QZ8c_kyonJz{J?bwVJe2YkZJc=HQxN*}UbhxeAUIzK?CT+BBPAbijZHU3R?TVm=t}Bj)gJ2&7NWH{Ym$@xBa^X4RvdzteoNorWIr=r2+V4W_-?zyv>=I|npLebgzs_gCLt!h&*@sM*gh?w`_gR)6t$xP%QA8WKvXN3ExH*<1sWJvzle^#3zlXEmi)?cZ4v?ok4xi#8pUci%guGbbFcc$Jre#r=8y69ND3+o_wHzEyCsF%{Hzeks^LioB$J_{$af{j|w>3YX~UFCy~2y<_PxM_22*zZ-JSy}y<$-O~&>rlYTwYlB=Q9~N1zW5|Tv-b)j7!+odp$v)Ve_b~DIsx6DU$PtM^2YEK!rr9ytj8R{*f7*GzjU0}88r$^N9M@-m{ZTULS^{#n8q`EiA=kNZ{*Y`LrNGQF-gV{+a^r?ycC_hMRABz>z8s&9Ty*V+gTixX8dxP(Hm|lvo#>~>lg9aeKmTDys-aHAr;Y?L;CE-IL&(3p7~+gOsMN)C7!&EIuXZo7GX{HjWMK<`jJZQ?w00ePsZPAW5`|KoHAz`&Mbz#WkvUmD*pMkI(3QpXF{?ipf8i4_5A|!m1A$qrfSntIK=svJBIn~*`hM_DF>-={N?ot=Q{L{wcOI}cz1*bhu-Ke)&oa!-IVFT_NtP*-s`cn6~Z9&I;7C3;8n}+E|lyD+lwDbBKOtHI3}aKK$Bs|2U^pcb6WcaA!yH)RqRyLJhkbNppF)O)XVyXoIvymAGur%R=sDP=ENdjO+WH5GyG}^_=~UJ?C*kn)%7yvc8fI?&gL$&EWL^LIDVq_@7zj*kivS(y`5-}9p_+r-Ifk{Pkvr0=0kgA9L}DXGiJc#e_K%}`adgvVSv4d){s&I+PO1T(9t!Y2^&;&-G7kg03IbAPM$2N{eD8sjnoHK{J2sD_ZIeK-`d^vxbHtJeEv#XwHVTOY+rnjlpjuTi!ZSp4fCE`GO7G*Z*F7BntQUX%D`CtSu~tnwl!=(Wrm>c&F}1iFzFuZ7L9b7uF`Coohrg=Jt!zfDwL@<>HBU^8WccWFn`*TMa!-xqIDWL%qa%g`t_q9~NVJ4)AM#uD7qy5A@`%gtIXwGuiFXYxN?d@OMLxY~0wbMnK(0(GH=fE%efB(PmpZza%*A`D}X*t9Bo%4_Ts41iU9BeLqFpmk`0pUwu_nB+T#^HE;E@H01At5#_Kb!Sl=Mp|wZ)M8s6%W}^>y+iCaT)n)jpGJW*JvvEip>2}ZH;|61umO6cT;FE&~V|wPJQg#IdI5G_g5eNzkF{q%#R}KZ%Yaoph*lQ7(~Al5kJuNVZxyNXl|bn@>09d$pi2AvnK1v#`1Pf>83Vn5vjIpFjQP(ZSiH>lx}ITb-2R67^YV(-T&Br`~UP#-9CBMnLFqu&}C@1DamyA)b*=}q<-)JSqhdaeF`)DZKtj$`sc36p#l$|$@PU@$Sq~Es+-|H_uy{LWsMv?P^}6E6e}2+Iy*=o;kQT-tPbXF!dz8-rQwNiq$#m40UzcucILd@Y*SQaDa6%qiWOA#XtUeZ1ijCUlrBS-CZ(S&oXNs@>P|-sP6PrrLa;b>62J0^3})utasccRCpDy{rK`$Tt_WhN3V|ad*b6#>iL1T$AwGB|w}9&}2Jaiv{U|Y+N`p?}!p4+(QXdI}Ez-VE>2Oi~PSOKgwC98E0m~~F7{GKjKlF|t`6}wBT7IS$6XKL^*S=~+{i9p+mgWg2SiJT%e9?rQGu!|8oD;8DK-6P7%s_5Q*zKx$vyu(YeBXlWJdg+OGJcPRl@x=&#o-bzN#rYvPXGBorJVPe;(JpnH}VzX$N!X01YXyrNv-X!kg=6vuPt_(tPT@hvtS|dd}fY-{Ct?EsuHE_`@?quLnv&4h{amuD=CftYVBJRkSRts$D(7WyS{GVr#Q%_7|250+_jeUG5R{bSs7YJ<>D;@qKsiUw;cSFJn&XlH)@uQ*x|9f!`u`myx$sdd1EXoKmV_`<~PoJY_`oMFr0_>2fy$i{j``3M4zYV2k2KJ>H!qLv!V05wYuysQlBV;pG6Y2#n3J&aG8HU?&HG~jVIUnQGxz>QU6F6+F!Nz^emZuG%(9MArX5A?eEV~e@0S(f;B5(L37@GvT|9sm;z%wBJTE=k|s9ED$}ls`9ZA+J9d6L9*0S7MO1}Y4Z3+s=w2ww!OH*hMp*0QH5T7u1oqFk(RrP|C^ieJri~L9aXaSRN#H&)SfLv;;R$y-q>r>Ac^%-XvHGrs~K`5{0g#kAmUDYR*>@E_dUz$6z06I{;*C(+oAm-RX#tRlNs%EJMeW$Ju+}f1?e0B!JUfMUExftsT8Pn!=ueg^Dm)~rpn28;ky8dgM@H=WrJ~)YWTPKk6+ll$~Hxr9M@HLcM|HU{X(O>Sc5Cb*|%jiFB{u~%Ay{NUdaK3(N~K5%G{eaSUsO8=0mFUI1bLg0eVTLVgX{bRYZs85y**nGG5`vnQ~=j>CsmXg`dgbU%U0CfiXbK(?EZE;%22CkmH#X-k#f7gh*HruQ=5;VLvADw#={R5R3I?K#v#KCcaV{zbw@8=(7$4gcoPl5Vs5_o@9?@BawR$^Ne%>L6*~*Sf)PEKmS5_w|p63F3Z7l=-V$aL#LNxmV35s1x%^7hPif=l>bTbtIHjpO*@<;H+y^jLl2D@3%%dft~uC-}%E;x9{J^{km#~&+p}bBPZ*rPxj#7?;cUvJUjI`AUH+En=}{I-uZ-HbP|kqmTXBL#`o0;A2luU!gMI9dg5H=gZk;OtvS@PY;dt(*y<;MI^mD{rdR;G__z0-Z@~AV@C<%)+6gLD`~2jRYC_#@P0$UkLO}qWRg+{W^M2~*wi$KCWBTHdk#wLQH8H+qiTcLR;wo2rv*B=gvx(sz)T`q94TaE=XU{CfXU#{u6&IbjUe{P%!zvkp?o@&MS9^ogwq`-!k&Yr5zn4~;go@j>dk7zIq-Wc^#Rj5C@C3i4&J{1x?D_hq8L3>7BSVpc!42Ya3eH+8)otZE
    y&OmWvojL!kh9WzRb;P4!;5VvKhpE_g`#NwP&_}`98?7xloy~}@ornfy4Ce%dbxV6yE)yZ5B2E$lD^i!u%@VSWmz4x;5P<`TxQkqD?luiq5K3r*$1XS0sN3L0@S5`LVGUO9D_zcK!t-Y3gt$c16=n@zGGpgJu+7%A6|Ja`wWZ03@fQGhN=LOs7wVguD}$cxC<5w{4v(V+s5>*~*XUZ)!O8NA`)r+mdZ(^VLuYB>G$wepoO#qsM>}h8TQrMt&LdyLIs;uu&-EzeetP?}1d!eNa^=G5lqr2OelU>yU%!GR%GCOUCFwt(S*AmJsNtL;xgz}B^7f?L@MeLlHg{P@1nSYgf=6^>5eR(oYWOPtIE@YeJpq-#-8QfA@oI)Qt>Nwslw1AWG?nverh_m*=Fn-O6OZ(9>G`=2Eni;LmLpObB>jaQ6KIe6HL63&bYeu7UaR-ABDSxDMAk`}-{}sj&It#nmJ0s8jme6LE!s6ImcOZ9#3ENaS0t&dCSvSGu9^Eivz_e09TRJtzW(^iS%-RJ?w!mWZ?UWjYM<)$g4vjq67ZoYqxUXTl3Z{fF;nW8M@ocP7AzHQCRc|M|ZAqF?fSz&vfN(%Wmo5z1tXnTYn&5ovBS(`T2V?c)jjTc|L}GMdVewsb_%5uWSBNf~0fwLXp*`L)oAaXK1f!hy26$nsqvLG#_picQMY9{22RA+O8PvDuQn*Dl)NJs4Mz+9<)|r01-dQEJZzIi`KAUIuqt|4q&E-@V>x)UWP-J62+n0lrOcw^q}UXNGA0cT;BPz~xYf?;~4Lf4FGi+tGyuV7OB2>=#nsMgD5b7b#p+7~OgDh2%`sTZEYRo~>uVn&Iv4o0cL+5%ZN-QJB!bT7F`y73y*vu;_ou0%G3Ov`Esq)%9)GpItGq@NR4{dlqsF5s!R!B>{%-sc96G=5Y+3jCs4WIt5f>x=s#Cq5do{!a_SD19&5N#plbQ{&g+yBNeS2u;v`Nu8N_azVPhDBg+b);P57ei+rdzo{l^1{k;gHdAnv=Px;|Hb=^2-Zd}0tnOTR-#_pqjSLgY4kys`y_%rADLsGtqr9#8R-J2{}z_TSi+>})#X?1as{HNbo+Y>n?$27LWkSht|T1qMmU!%TJuP!o)_d3YU`|47xg`A^wjIYeuH51e#qWUw=q2BZ9k$eU{2RMH=YGyRlzqqeovqrK2daS&HxbjhduzA%{`iY{+Il_7#sH-g&?j1fy2Zr~?4NCJ+C(bVq7czl3-|tF8J4>4u@h{O}fgknUpsXzFM8BQ<9SK16rxc|jza=r9wQD)&B8HW7Gn*?S3EdWe{~?hUGx?ryS7G{nOAbjlA^!!rQIK1q@Fw>|1`zIW3O8OabjDYyt%C_0wjR3u${U}H@L%<{Cc;eL!vlZf@xH_yl$_oaSfIhPUsx2mWk@pWi|K>($vLXCt{}H;Q2ku}*eYwX?)ybI>T|f2E?O?m1)~1URRnqF6H|q!=TAO7%#G9AF&A}S>-Wu?jTAVd<>VI8f$Qjf@);>PLj%#0af`gTRyp)ULTayow)1sYSAr?I_J-*QrqK7*GA8g=WpDN3V0Ul4b37r21qc)O~Cp@IQumGEKWEbXs^S4ADQtQ38Ueu0OP@ZQH!^47hf98MW*UX)az!Vf}1A&Ux?h?_XVJnAcPjy)J&nnS9vizvflUGmLW)b1m~eP=KnoYww-wnD0c)#lAh04tpLL4)z^Hj^a13On?2J0q;j@m(SjS{T6C(&bO)-Vu5arl*YH{kSRNfIp!0^F;L~}&_wx-e3j#r-Enp}0j_o$J&7mHgJYk0yiagZDiC=M%SVt~DEoAlOT}}(_vK~Q%rfLI?i+(WHJs<&B6nzH-F%E62^lOrVoJ$}y+k654f5F6_ETkZHWb0F8?vgK@=%X6dfG4NPluVkl__JjxXwHyHtUis6Evo)t*`Y%KO5KI*cHKMEFk8t1e4|nud4cVm2ou&Hh1~Yr;+N3B=x!6_g5!?BCBb~(He{+T)FAOZ}KGt)_&14T;7e`(&b<%z!#nYo31~OnJ<7mHoR?mJI?~n`FEazLzgr1&-9%R&4aJcrKGC5eD~*_Ek%vPRy4nS4;(oAHw0%6y&QWi{QQI3Nv8$yPV`$QvVsD!Dp=kYjVJ0^EP?gSI9YVuFSK8!;=b)FOA)=qAuh2affYY(PUrWVN$=KXqzKq^`Gf*SYhzwE)Uez#||a0+Vfw2X+aq38<%~o8a&Mc9zUNkODZXEBw%|HPe?3;rp20^Sb>~#;&GjO3@Z_S2?lhFu0oxN>&4Zk!tFh0e=Z=+i?8S|Fz)`60TvhA=iE?4ojCu@cgz8M@e5ZI#Zf2v@Aq@|BO-p)P3k8jl2dVyo?Zm29jlGa$x7m#Kvr#AV@V{(k!sBc5#|~e_b$qrqf*RRv}unLcZx7kN_T={?;;_*KCadi1Ln9PHgK>i`-GRWOYgBp)K@5C*rH!3-aecF);t&0_Il(?eKd0j-=r{zHFN7W~CeyFE(RFCfwD*&q5XikI^>U-y|t@jNmf+DWBt{2oub=h$OF5hG5FzT_!_(I=5J3Dnt*2;=Lmu5nh?yO}d2ISgufQUaF--r76hnNK}oaZItU%$*y53@MCdb?2(j2-6tCN`g>_e@ikRi{Jo#t(`8WoYL|%bAqEZU%50C1~cEqE7U)IxxdIw{zn+|50Npw>;>Ve&e~GHI_&mJ`2IKrFmM2k9*1Gw&zM2N1=|_j3h@vk3d%~eKl>x;bReOJ@k^F%I*_SWTnQ$<`&H0Ha>I(>mMd>xzA@+CUXBXs<$^0!=Dn!s4-mL8)`NudfAaRKdxSGG?&4x|LIm>L+$1WsifqYRoQ|=Opf0T}{)-lP2x$Dm8_!gl~^yR6WT>v*lc|JeRLj91)kC5gn3W(g(D(iPeJ&QTw+hjol2K_{Vsxaz?X-jRETQY!{zrh`cb_Vk$YhUG@BUmflvc~xFxdsF(SHG4?p6qM=lovVV_Wmm0?(sCp^Je@>@J0Py_UbPM*%?r`%L%gtMWpoug9CNbLT-}selJ8w?bhQ@0`8WenX32EuQFMm+?NJL-oB{}}6SoH0PczSfBbKE?ucMKFhS}G^~QfV;x_qQ4SY0=N_KGx*?o}=`u>Mjl8ea#P@HTzS+guK{h)6E}|50x%1d>!Ev2Z_#+Avf3>lm{h`6-&OjwU1LV3d@0=q>>lyI%$Tr(^*YLizuh(YsextO;g{Ivd^alkdmde*M5wiUT6eADuCEB(^oR_Tp>dSU4AI)2X3PU_V>6H+UJu-@jTJ6t4A6TfAkqDKdl*6@u+fV}ka(#K<)Mi@}!nep8&A9bSs+XVS8f|B-@KIH7bDLIbou4$p}Ve#5`Ix`LK`nTU`Z9tB)Y?N{I5`?zH~;F48pwV9x+QFC>aAGwH_$L9Ms2VSvCDh~*uUa^*8@qJ;zB>z;5ll)E*T8>%ki=bvncaPa~)NchU8(fv4gWZg0Vg*siS45rs%vTJUZ?h<%b2DD=uxdV|u8;X&Uh72Wl>V1@krFX?`O;@ms}wHe6XN_^vN;7JVpXEuOi*8b^oW~IKswxiv*(sn80tiOu+Iuv5Ee5oRZij`F0GON43S(&91{%KS&Mq=NNma$4qu78-Tip{HtGVGPAN+X7XfX>IPL2t)N2Z7YT7r@Ka^dDxBufP&gZ}oJ)y&9LW5T0muMg4D}9|ayp{gffbcVwOOX6L7semI@lFNBeM<*c`l7ydb&3mcWk9B3>5$Vy)Ng9uvHumC1;jqNmkaqP=`_1e#~>HP^REONi=*CRaA@Uf&i6~~3kia#Z=pGS8*ih)rNKST3hlT)UzyCl4j&q5&(z*~{?b3aQU{dDotnt0l!rg-ToxETTcVFh#fA7j?q#sjS3+jdeAbugpQdBK%Zyl$k*EmsN|v=Xzl*=8-Wc1tvyLbedft`QL7Tyes?kI!t7@=8gBG&Yd(<_FUUZgFq-so*@^VDB9`o6O#|;pT=!kt4z|DSOz+#Q-Jf@Fw)f_^#gC%ktOU$gJ)~($1lA@UHfC6){0=pWM9gzU&vPmfG4%E3twx&Z_J{%V4uv#z!^`WTP;nlAwK-ATlj-&sI=u@%f1`YJB!%0pPbXQdpGJt|F?i26u9hGk(;1~`hI%fCXZJ%*u*&q87rbbW-7C61)Tv;2WuYaX`x=GyGVdp#e^thcR9lysP8*HD`-h#0z5oA^j9PkIi!6==hOCU$v_;BbxHZ0?aH>w$K=z&Bt!W$H3D^FPS{vWCJ=r4mj$A}X1?$3O$|Ad=N*%ysHeO8xZM1b4{f6ByWZ?TeMMnF&Z*xN_#RJLJg$Zu^}YD_UBeeN_;91wkvSjr4=)ey3&~?Z<)tO-_`hI2suZsjRlJ-DVxGrzvPgNVMBf{gLy6#&Tl{AuX@33OX%~0AI*{C%7IC8NP~+#w%dX}nGoiFRMa0@2b;=7+zIEstTnRoQ`N$4Ags20_vq*({Iiu%JiKw3)pC+{7b2<=xeRQ9o?icM{C+V35w_bTQ%>In}%k$O~{Ht;&>#3_oP+u=5xor9L0tk5L@;s#n^^cVI2aTUoV9VZb0u4LAK!w|B3T`r*icH~m7f>Wa8d!{yeA4p$~{uu_V*0Xa6!@XPKO=aax^k%HojqsSpyayNhH*`>jZ&wnM;ZlK;IDU;}8n*rbBz;we1>K{%S$(lXN0-_#z%TnZ=XucaIulDBx+fS0ORulCspF6W2^A!Nm|58{9^^AKAm&;>_=D?zmkX$Nkfp)Ngv+DyH!!cv$-KqzhdKiYjw>Pg1N$@16pgNB!t`GTX|cn|pAYZl9E@NjLup9vvQjPNkjXq$kLy6pCwv=@@yG0Hu?O?(Ga&fWVgvCeyq@Uy`N&P+?hLQq7HYl7BDKA;|kT9V$gOU#ieWJ0)khSnn7UrVB*cB$%TUlDHu}+BQ@ViUi-wZ0NFX>@^f_K{TKxVS@1GbL>aMa{-?C>)C;a{*-SJ>petlPDGu9glP)^FlY`+Gpj@4OqEOeOC?L`^yXW1sh&kcdC`46yTt0MlrGDgOo}2FA$*Joy{_@lm~1|@zyo!{|JBiu2*O0;$la*Bq{)5PX-|SPJTVf6?x?>!lyYHaN(yl3_K-|I>co83C(@kvI(Y9pwJzFKTA+H?envCvs34u7*7SaHub?gtnz<|z@~pllQgy=JYu&(t8VX1nXmYW9qQydKZ9OKj0kNPLexO7Wn%vvjkzEpl)7{s(ggPA7uliYqEhGeYopqS!maI+X+xDl_~ai=j^RhZkRy0z}?%TN(0puj&)^KvpWam>91sb48tJ-!kiV0k6q8&R`32mznz~9)8CV5UU;D;u!QVzpGPsKylsjg&V@)sp0A6xkVT+9_|q3-f<-oINM>z=}Y*zNiE^=GdddsJjK*QZ)}l!h`h6R2FE_@x@Y2Mihw9!Z!;M!(>VJ;oxkh78mbBXbR0!s+zUond{$#5c#Z_Ul{_uV@qhXX(hh9;1X?jQ9IhY@#c~?@N)c5jMgIYt~WiTy^G!EiHekSq`m8V5Pq$xA&n+bBS+FoOecNH-Z{;KD%Q!k!Ji2Se$*?3@f8Na|n8C+MuWJ`qm7R9WxHM$RwT?s-vaF6ViB1sxu(!t)5x|4@mV49DUQc$AU)-gmA#w53Tj75L6?x+dR&e%*LK3Qhlh5Uj2LnDz7*))RdkFZd?ndvS8^r_~zd>wEuDk_p9LziuR%msFoGN*Bx>0)_yt*xOZAreTqSDME{?uhuJ_bc&QkA1G%+lPsj~EjsO+c;75j<)PMHudq#8pI%9zQ^a82Xynl%}!#^Y3dh5KUw{1)Sf&)1vW?Zr*>>cKPd^Ybgk%5g^^1;RV7kz9ra|iOGzfDgXd2lQjt9J@lG;#*}6Ov?EEi?RxGGv$DO@hzohNIkbkOT4F>RDn6_!kKN<|{`I_uD`9o!OZNSs%yE!@1B;L@yo`zWq2Ih+|CC3+N|*Ezf;bRnG+R{==$Vn~+b$@)dh@FJwV}ObAJm7y0BlOkTQCk`4PM0{8xyMm~Gxd-#F}W7%_s^ukeBU$oUqOzeth*E9ESK@R$?jf-_w%J5P!%#45Bj<|uz7Dtzsu*8QfUe}R1BUw8hic^5!K1oAlYuy&@8QAwV+%sU)tc|7fy;{B8^RCaeKXyu4IYXsGuiXg4OgH&V@xtXYIQbyp7ObcXis#J&fM=+V3Xu-3Ijp>C(xKFsewzW#2p`Irn`)WZ*wpQFAa&X2w)ra^Y?$pdP4QD0eXtAC#NIsi0`&*9s`%_V0v1E(T^V}@(fA`>sK``p87uyZ`-t5eQr;URmU(-=vJvr&WY5(&si@ul1?K`c>08;6M3!!K)E`?{6Ap)YfEs3H*la6AMjHU!DB)$aT3&98{ib4}2wu`byn?rouF8P#_kAlRKA^q|wiA>85tap4BzSIBS|U#e56Q-|=3)Dt59_gw$%}VL2j{Zy2g;A5e}1g>3G)aH1D@Mz;qkl}C(k+j8jlr>hU-JT?|C@-18}{zDqj>G4_B3zymlPNxJT5@ju<4t*Q>is4s-v<=e@QrJ@24LMG9DJHIEB8q5m8bNXYEyP6O`)->5UZm>*X~)cy5q$$;X{N5-c8$S3AbsLIZeEZ|K%wP?#%)KOA$Lk>4)_tvR`Ne=g7;gry%liad$=sjZ@yU|S^b%!<31M{3*G>c>5d1^p-7tINxfgY&f;GpC~yV6U9N%JeSG7a~p8vzJdMf%WIicvV%*3x>JFf0Q?*0?`-thZpi8=9xZINQarV&nQV>Fh4$Y_MRyl&j1T1w@o(%`EVaP@@g_V3v^ZEHw;`vKE!!P{V&$%c$lmC@-q5Wqtsg01jvQp!KKn}w>bKkbr!cj42p)L6=64TZ=(LQuYK!mA*U7(Cs~f0*p3{Y=GQh=MkT_VpZRw$D`P&buPXJdxtZM>Bz_@45w{pA?;FHn`W41wkUq#RU|QPnN_dEwjZr>^_{+GZ<$EB=>1uSILDdrOV%6n?yduyLkkxSlbkGxbRjl{pq$`$T=r-??@l|iRbH>X9B&xutp^`cG&1Y-SS>Lf^mNJ3(Jd8eIu6VTmRvIf1j9p_iOC`#zzMBQKy|wshB#K1ipr>Peeug?CQ+z((hBjb5Hy$&sq3$esb+Pu2Y@?J^Cym+K&24UuwQ$vrsk!OUEzS_5t-(+?KT$T9)R*?R%kr&I_Wxa@b_4{QEHp+GQg4Xy~B6x~X!u$C5#2zqkEkiTcV*aM`ffTYs>(D|~9z5cvnmek_N%??x`_JfM#`bA9JeGO=E$wG#JU#ICq$$m72;{?*T#5JU+s2F+@I){!9Fio#L+MG^*$fdx7As2|KRN?liyf(V*ha?2VA!1K88NDo6TxyT;o9kYt6%}d^qY<{`V!t;(f^QN?>K0w>bWM*Be}gLF~>QEWQcLk3)1vPyG*x-Z||D(aI}l3qWe3>F{1xf{?$l0xaZ`-{bY{0!*>jy9VW+vqiMU0K{MvHHM6$<;QyKg@m+I`j@F_c5L&!0Ye`Eg1bnQvwTa}Yw;1_*B!HZ|98~n3|JeI+d1A=w<%Pp0R%4n9%p5pYu>(DMXH37}=Bqb`N$hJSmPmrTDp1SJvjj(i_`5);~p_#GIk}#bo$9-5ULjWBy}V#E&xSo=ZT?E!3*Td_lKV9BOR444!p+51R2}JnSUb!xlv`zR4D*FN>x0tmlEB0(WWz0v_p{EnJlTHrDbPBn{^r0m<^{2voO~Ckn(kTJp7R_8)=Y=C$IM}OM)H-DbsWBtD2&GH^r9COC~)%N(EK9$IxODmv>`l|k!f{Tr9GHi8UA>1{A-@9AF=QDTLr$TvP#2ZR8a^O!1QH<+N1N(NJ*)n&K!@DNt!|-z%U~@MkT`LVac$c);&Yj5w;{BghA4ebl)iwS%9kU@JtA}T$J^IONmf$mI=~3>_i{yTAA)k@WuECj4S@Ei~?Pq!O|2r?>)dv!|W|mI%T|+)DQ%4*%{sh6R7kzS9G93Te7wqi&?zb-zi1*?lTG$ueb*xqO;mHK3l^A*^FJtx3e#<3dQjN9VW)l~5*Q4F1D|zhGlXUPdFtW8v!~UYf%$cGgQWj|UDOzjmVZE#D@2|=ee{#T!c;F1E$7;E`dB6T9!SR@!Z;3wmIf*_Y>t2#!qm-;r6$#G`nX|tH2DQlvD=r8!=8@_++mpSVGE;Rw}bS17V4MrXHO3rGb3Hd-pIs9mWEc<<1JD{<)Y@8FG<0-<%Wqx!4)|bUp2JVV^5Dq&PV&%xZlGK1!N%3G3Kr2=yy7J+(Xov0__U9fl}sZZz@^s*t;ea>c{t%c{l%8A9$~w^zhjjcV#r#>&%U?{)2rUi2b$*Pa@>bzcCn~g8BW}5yiPu=_x?;#V^@_=Yy$9X1~W6>9FkZ>YU6QsH2E?K5rolmWUK)EyxS~XHU81yi$m@PKkG>>2Hw#DffDZA!ib>!jr<70owhU+x9%aNQR_-sbsBAeD9EwbJk2&lLBU9FNV&Aqn-Un_C@$xF#2?N+JAAZR@ng;%=v$A|VU*nIS8@vTzQDEh>AUo@Aftxs$ejk%QIo$9q-nV1fbZBEp;C9$QT+=J>{8YwfdkPP&KfxvZ9iW+ew56fALM)rbyUitj+rOo6d?BB7PZLV!SeRs;kU*Ch)&lWGUfY(s8DKj&jda$v2<15rmB>L@Q)`v5ap5?p*zW5@ZdL(%*#ipSBd(qs%;De89H6xz>je<`!3(b$)gD%S)6^l*B~v&%!=_9sL$H6Y&ZjmIf_fJVtyq0K3(o%?F(4{Lv0K4A^J#PByGnm%?Sq!oNXE)@%q>zoG4Ip%Au`lwlXq`ef%cC6g*4Bm`{&op2}YGBMG?Pu0Nz=jvO?uz9By_VC`pF`y|jqeYM#mc_PRw9m0z|CyF*<-aKuevS6-jCd4|Jwu^GieI`k+EcZ~(2IJ;kx2v9@pCpV=Yp-f&@$C!a>-9oD$*zYMT`?fRsKA3g7dZS!ppAKXw=wJU#kjV|E2F*|PdZAv^MMTO1pK2IJCPglzCQX#BFxhppJnx$`p-Tc^zF5tL<+!BA=$4S^9udVB8N|JNP~=LE*r}nkOMJCeuG#Bgc#47?kqwM^+t0=Ec-Iq{l+JrB8S)0DJcV&vVmEACbf!Vo;We5LytEXoUIS&%irSgle`LdJ63#FJhYzwi4XE2;%uuW8Di5smt2tjk58@kD+6Zn$a^w0>YU^qF+o1WJmx>f$#Ajl*hpd*>d7Un1^JNWXPOxy-}|$WL%IE_TfTfOeYjgch2oDKeDb?5YTnO)pT6_Q%8zq!VC9cc$1EV~0SeQ|VXkOxa?gis2oW_-*lv#N#dOD6)q5&CC$UDHcjl!gzc1CZWi|LhW#-`yNEPlE(kpdn;)za#(uup09@x4#Z?WTgw-Y;4PH5~otL+iFw?YIES8(2G~N1^}h>kMC-!f39w_qCoKJREeEpXz$XoUNeiI%I-U{=q~Cjx6|c3kKH1HXP3%(Djnk(D-G%x_Qk_}EiU15GmiZ-L$TN)BN?tdxxy877W3V`J2|>iFVbMO61~2DE$RfLOzpfE)J%BYZ@XHwAN2r3h%fK=;vCqJu%PX*6!Oe_x@YSGmaecnHEuC@8}-%9wV<)|ATsPZ_-nlq2{{w~Z>2|pd+)wkF;()3?01?WRT$rbw}0;v4@_at*$F2jpIx52Z*{q)!y2!fzehhIABn?PUpM^CgjMxU+QyeqC;T?(rVnZ5fc#Wgd5{Z-zM|TeEZ<53qTjaD2y(l#$C4r!Kn7Fif!S3Y{X?qwem+Xppuo3ftNvsx!TOc{aQ@NEJ_;BLAL!`%jXaOA62n}hc$n68sei43anfO_-r{VQZX|uY_05T+KUl|!gdlm3R2X}9L(R(+^8)3E?Ka6p88964HF|+7@`+mQ^o5vDv!_YDOqOH*VC2TlMId#$Bou*n8%Tj(<9Gv#Imi`L>e+#Qm3?N2sr!FACW`Fgua0Lu5GSsd)tS2P(8C!_^2Sp_Crv@cSIN&UQ%yB2Ki$V7?&w>&?HH0rB76MRs38Ke-$y>T1`U1y}z()Vbb@`eFW?JrCABVST?$O=;_W$mh0|&Z*^*B)B%g-;=+HLqGJ-ePw-#%$~pY_dAFF41TmRK#c-?$DBsOW~1G^*fKT`dN7I1P0OMBf`2BAb6W>|FhyNK+-J@|k_`o6vfnjA&`+-0Oxz5V&jl+(=hb1u|M|&#Z4xSay8Kdc}P=^~%*%}XfmPbhHO;aH`Q75bGd)!ueSAO#dQGbUbkQ~%j7C|3o!tEPbf?@5{CDab)}_UNr*tqhb75R6{t-?%&zT3gkq<-y2dbiDgQT6-3>CUAU;uQA$+#RhruP}OxUEjO5bPzpuqw%%~>Z|QW(%ZTIWI^=34N^EO6GV|KyF?+-#0z9m)Mtz73)#KmKba%j`qv(=ePfvqQarYG7S;S(B9!$-M&&b3X+BQ&q~VY$ag>0+`K9iAaUNB=;SQSU+c5!zntn*p!>w?n<8nL_X%BHqn*L-OW$mZ`CT&kr+3)4Y&d4%efdBI@+9h?mJf2_{Nu%I!-7Kp*+=Mi)&~cY!P>U$E`L1gCAnhxKhy3Ma1^XxM0-k4qTGI(6bNT$@aU?O~(Oc;zsjJ2#K{Wsp)~pY11!yGEGr&X;`bFn*c=dn87Ln;EDFZZzd@%1+6Ko#IwE`mIo3MILm^9``US|U(xH1AMd$HhSHUi+?@+iU)jwRKfZsI0z{w4i`}TBqTdyq+qa4J{qkfp!iJD@kg>YG#d|6g#g++8i=+MT@^?i$ZpK6C)g|kvm*9Fo(5clIYncp2e07ELXEDA#{v~(0H$4q11^4(1IUt{}F_rQKL771GRpO%~pOfiIN~QC1*!T8Fx1vr+)#URyw1WgSNqgdg1&~|HnUM`!GyWHsK5RjMYpmqo+Ur9B_sd0pujQhSYUK)5*VssfqjbjDk6p-fplFY}RwosbFP4-{$e@3ou6UafnUDxp{MPeoe_+1I*l_=oc2x?zyJ97?l4CBOSz)lom&|lH_tLd3iW}oz)`7~7G?gsSJ*JoCv<&$Kh2Hm1yO_g1Z@L(aeBurD+d`8`Ak(|7scjAFgoAW5(I3~y?0aGdrjZX(Z&f`<0ipAsR$K6(J^jt?x7u5%5O*cvVADqA_W2d>{oxlZ4nIJ_><4l)o-1PMWtI#Q&-La@OJE+UYi!Qs6-Wc(oUn{zuHT&>Es18N3|JF+NPh=M-!?9jwv|jzd1js`>74X;Oh(=EQJY2Kv?Wv&Uq8I;bF(En0KB9{Idg7`IaVoC3dtX9gxhIrNoZ(cW8@=|IdmzoLX3Ch0P?VueeGi`pH~Y!W$SR!)B2W3A;Gni4gtPRr4rNk}mje`ZMxb&)QHP*+qrsj^Aq>-Xb63zQj$IKNl|)={+-yd}6a!xOqCIK||j{<+WF-|Lpq<$ka!n89>Yj({M%(ri(}?_g>6`jK#bswKR|edtc|A1JZ3#`H>ttlh32AjwV5Zjj2Ov`C+(T3U7Ev3)+!^m|xWT9yt*Avcg3uQ1re^a=;z^#88*rzN=S-lGR6wpoKm?af%NIp1r=qIits=j2?2um+&X;!+N7)3r#RgdK_T>syCoLzwW%3tJRj_8yEE3licE~nTg=ywe_!Xi)%8(h3ZymMAL!*r-Q}<)wKUI&`oH;xb@<-!@^%56Inp#B&WC@$!8+LPTZ#!+-qXN(joB2ptK&brsyNr%^(;McRMhPhuQ=*~Fc*)HqDKE~EY-`c#PTp}>mGk%3$11dN~&P!f+6z%iFavWX6XrQmX!nAWE+D{2=+voO-1~Xc{_jas7d$qh-wB)B)aHyL)_wW+N?edJBd!t!#kjNYNj$!^XF5Q~ll$-{umcCdMYJ>VJMA&a&6@M1=y$TGE7sUMDzauc}%$!_cxo30nVdVKfd|AmaJu>*_=pQ(`GW4JQL+gqfZCeTuePS%up}x{8IsK{AkP5`y2J&&#QDX~Aq`a5X;Dclg>A_w6UOp9%gf4$X1HtC`|n7@T~3D~|{7w@+G_1{H>-gHyWD^_y!k-x2c-_mpKpm3-s~Z4c_Jr}gch`cC8mQ7>=dxX1ohiBz=CjSQ>rmKUuP4IB5oMXKevWr5=^N)Nn544rqe|?>xOZZt)3+%i1M;JVABAq@=s(u*E?UVo8`eatjC%TF9weSC?fRMvCQ~&9`SUOjeoDJkrJu;s$t}EIUvFT&<^8$T;>k-CSo!IcgTf=^rXJ*az3VU)T;=bt9p&gx^5<0WfQL8@x^|41aJ@jDgx^x?X)t!EViQ*h@>CDjv>%U8h6lA8mmk++oIF_}^5Wfo_qynecv$|KI<*(|(^KL0xRJBGnN2%(+?{Kevty%_iipW1UXn7vx6FFHvKCzdRk@e+5Etof-`O6=s^JLe!jnt>0&39{KjmA*^?<0GW$KO$S2efzuxlwkd>jZ=L9wGMLts3`|ZX?D3GzsUA5#ht|Map$T||0UB_5diF~4xkBkG*KuoDiiid`L)R>7}ZtXNU`1kl8i8ACvoFk0bXMmLcW5vEG>OVWtZ_wj>7WgGCo0F@{F*jia>j#JBK(O|fLxJMR!BND^xy^|LVBT5!Kn8UMaZj}KG8rCE1aJLlg6rjLLH3W6HWWDEl6UEV`e*5&4*oP=Z(9ptA45t{y-?k)6yNO4>tXzu%!=xbxaP+g6ndcB?zY`Z?-&#Jhm#CsZJva@uiz2sxN6YklN-m*{DS6m1iIqZ@#EUyl^GX|_%VJSn?iWM_hTeDRZyi$aM$=fnYn4C*f89>sDVGJKJBI+H#d>spPFd+>-g1^zUDY1)~Kb*+1Mc~|uMQQ7lMjXBN%pKL#;r+<_N_H7>4>sFwh=X}b}=52JCC!-csbQ^UValdYo_4|e?kj)lH{C{<=$^=>vRFKo-9JHVLFhmGwgM&N&4D!bJFK&s9Q=RmNZqYVhm*3eLZ-4&cU6c5x6J!ahg%}|j<&2q`@C36A?$a8#)KDg}slDvNnhCuED53+*nUvgd}sIfFcjIfB&7G&s9FM$k|lbytn{yDI~G=)l7N<(V>aW|$mxtDmGp_07pQ(-x?^FhIAHpa-US@{c(`BN(NZRAc7%tUU4t{bJZ^3M6w2kl2uUlH?wZy%&X{e>ehb7GL^(Yok6V>5IxpHRqIY>Padw;M?pd8L8mJn0q{Rm`U;0!4*t(U~Cl*GpO<7W0LUPO{R+gE{Q;*@yZV4|}(id|Ej~f=K==r+3uNy_j3mvi~O){Ir=8Bn6K7m@ZUahdVSFt`DRQC?GfTzIc-5aXMuG70nqjLvDOti*p-B3+-p=mpqPRz6j9vylY}ZhJJ&;QI@XgC&YX;+F=U&{eA!w^TL-_uk?5mD*N62Mk(a8QP5z<(PAQd2Pps1)Vf-JYVuL{5tZH<6YHl8bXKO>9x;BIr=bsxFX(Aw}b)AM?YhpzePSX%@uBC_cNiU*uFFeV$`pgZ~Ggn)!tk_PtqU6ZDg+1+9K#p;RF9+i)32owLY%F_%6KPPB?o*&8DtV(!n9?=)B^``U8XV&s$X;%e^N1Uf{7H{?hE;;0YL^oIQsXTb2byX$(m(H?ed7iImXZ1@-25?*wl2lR`zm_?crg2+jX9%Q+hTgy^TOEIzk;+D}IvC-~n=A$JHS!MBLX*Enbf6WjyYVp>HA$suijapG!v$`kANaxhc@$$^Jjvj%lKwq_#!4CREbl)cQ)pxpR=uik{Cq^0zRcspM(L3`iEGh#zULMC4)8NI0ulJD_Q>`J+g_r{5Ps@ey0fvC?3m0`V0Pfl|G+{a`%ZSdgexSiua`K#PTM`#Mtv1L*ZslXZU!_A^uBI4M}0-iKaQ7Y?f3O=s@ze=JVo@qgym`AA;ovkvJLY)!C|d!7Cf(N8QSz7^%Z@2bRPFqE-bBjGV4$->MK8%KrH2@u-|=DxS+n;aHVv4x)qguuW!j9>Z^u*aVi2nG$8JG%Y8x}rMW;SfayesYvZb_K|9bcRbjSCZZiYo`o>l-d4W2rZhH9b+W`i&1p5d}B%poflXv%uKS^+9kpA0Z8zc`XysmkOdf>@{Cjcc_h;zJS38=4@zMM39aFGgA)mpwklsNjn%2`tRlW0KPU*M7m#qZHj&*^v|9TvYxb`Ca1{%01at+dx+z}&kFH%>E9M}3X^S(x&b0bfq7oBv%B?IZ3Hck>2Pz#!hJtd|${Rn67!uSeczz{9X~V|gaV`6rSmq$G~y05NCA=??N)c0K-FohEDDs!Hh8_@Yj*OXT*ynn(en|CZ8x)CqgnS6z>~Nrmsr`ZHdNp&p28ERAAT(I9ijnZpmGk*CIvtd;MQ=&)RULC^tR)K_Wh2SuCrGGKY^nL~o=$hjo2cKi2V3?QESrdXrjM$ko#!k?u=mO?J;yttXS1JgsS?*J_2e}b?Z~HqMoV#(w+MJHuC^Sn&hhjQBid}Q;^H1dFzRxeN$e96yUOJK=;?NI?|HjYBgI#s|8n+xko*fOxRpJXX;ErHdxu*oi$zgHN2-Vtb2q;t5T@;G((0PuB)-;%os)?c#h2d#=YCYmWPANqIXW<*1-q@~KGlCi3aqeKwj$mIh;Kq7zN~Q9pc}TKGD8E*)$al(!$^xJP8y&ljfohz_Gi7QP!)L~g{qk6-=_Am$ZcHb-vVW|JPRi}T>2Ji|3}9qKFR1etebhq9p1c~<@sS&n;0D~`C028>I(+i1~uJv@dx+VGbpJ&Kt(?GHG-+nqg&m0g>l_8^J%_Sk{?SR%;W5pm``Qzg)`^1Qa~e_BL6@Lbw$!lQ+Gu*6;{=*xqDd;{Um2YbYul9E{O{BxX2fypAh%VcU!P@MddBLLF{ze&lmp)ynZfHUo%ugiVti^DG(%MIvPLAZE$;rSm!TRjJJevE9bG5dP?HY6!=@qdAGCUNfxUQ_pzSo@$Od-mP0sWhrVDxWPqQod?Ll`EhP@jWiXA_un`DkOSk$;_DhSR9N&wCj2{@<6KPY@x0Jx$4*#~20iIiiW8&12&x-nNvUCXpi20L60?3EF*?r$!l{_HkyglPVK4lwA*1o$)g88{R#U3dfeXbmq>Qz;d+4J1*I3ow1=UL{yBnlL`FMVdhaX$Eg=gir4r>L+yY~h}V2FPJ(aqD(LZ5puOVcbFvaZ8`}^i0s;nR^$Hv=FYB69+f0Rmr8phxmo`Hwn02%o^L?oK|H3?~t6&ehuW4A64+Zx{d*E^X#lWxH$Oi68d^WI}eCHd_F_SVe0520sg{75K;`-{y72bSGQ;4gk*lD0nx|()Jp8ndGfHjj{l`>;QAdrb3_<*&goQ%wYxU4boJl7(!Kt8Z|X&BLwER73K0FIOU&`SZ@tq_wJXXj-ME;w@%Og8Z>;!LBI3&cYn?`=YLq#kx*ZpbcE<<358rYL}?;dE;yvSP%(%S?E8zalD{eWIi2Wlek7OH|i+XuX%n|90PXc?PNx5K>h*TEoZ!}@*v#CZSXojo(~e&1si5FVPS)~*Vr_^_ax?!DJZ3b*|KDJXO8^9?(50!GsKQxYrH?POD%Xd!q7G**|0$o{G$8I#Zd67-#QsX&kPh7{!T#T#aJ&;F8gt7sAo-U;w^SbL1ft*a#ZL^#m~dQY%|vd8*7GMkOU(mfenNc;atkwln9bb4gtnE52QDo`T}rfH)+Xlw(HEhm0`Ke2I+?CiqDThn@V&+FR$;#Qu5vj3FH1)e`#+}+%nLKxrs-~pR2aH>vG{oh`iWIdLcsQP8oQsi#|n<~Q>~Lbq|eiV=u5ge2l;$-vozK*V}K-tU+&_V*O2BbSNwZk9uWOtRx6{vavs{bbo-S&Xv|F5ad|UxBi?xmZD&H-?5ER%*2pc)DOIy+EeSwG&695v$NZ*01Jm-2WN0jJt}5o}YsBZ>KQc8)f$LkH(uER{!=sq06fKti7d}~|kxG03MX+t{0NClBf!+}}s|bMz5yvGrSM$Yl4W5xjtWY(#owoV3W0p|`HmXdm^Teb~nc`u0*_$5~aM3XZwzOJ6yynakRz6X$E!CXmC+@F?$GJsPaP8PzcJ895NTZI2`!ys`=eR*T_!@sR2E=pCd(@sjn6Tm#Whi1(7IEPcqhFcETSF7hGHeMDILLD!tT$KodX$!p79zlPdby3sk#tUdwxkUbuWY_Md)@%&|jUJ=NLUvhBjaR(X9-;T<3bIgbO_5D@q&|?a4kI?o-h#?21zwgiNy+sAHy@$D+=OBj@DY63oEIq6|YG9r=2lW;4K1A;z9Zr5Taoekg`s$s=jDMLZ1H#6%E{De>2e+a5m7{kUFnj&ju*#h&Q;2`s$g%55L+UX%rQUImT1+{gS*#3`XeB=){i!vXb`O71PC;T4cH>h6yzBC;+9&WOXF~oRId|!K0v*DqexaH>|%xixA<=d5Zl7TdrQd5$Mdf=s-dVB8#1&BGNit{n=f9}|{yv>~kX?`>N8zoR*324eC{bta?tRdERqyTl)*?QdzVb>Y(sq~)WOf+()kP2QZX6M1e_log{_o0poun}5d=gb7bm@%Oo+*v-|$PCIj(K^n^U-!JH%K{jFW85I8IP@9T}I6G;65C#>(#fX1Czy5|~lBm8yY038mI)Q5$xVV$btgw4g2J_Z!(cG^A?K%QswRUG|m^I-JW**ecV$dmnUF@y=Xr=_$`aon>qdb%ZPsdPS+q;A`Mz8X2Jd2ZBRx+WX8vjSqt0IqkXJ%dp`S4l7xR&HBuhH+2KO>1xiEB`t-t!&;Vi+p~)$(1PUphEMDxZSgDk&?zO92fGz*hZO+15q(r%vEq_&>S?%n3H8;r_34wg=}aK*_uUaeo;S^Yy);tG2b=ENz9X-YXWG8mjvuCS;M3!?^sTuVCoi6sI#d})h6Ej($;`hP50@AGvH|JNFHv^fozmzd(?0F)WpP`>@JTzWtRZIsNjpp^C9Q6l1$IumD(iz}%Lu1zLD31FxLjh`9?s@Eaph{}UhuHr-mt=yAIv>Mc5cLC*CiXTk|Ce6`klVGeij4zS`5-UWVKJ})xfKgoIjN_UVbhgUH?FF2%q1@wnDvXbPk+>~Y=6}Uh=;8T~aXYi83SW_^ZJMkMA#%gwfA*N&3Ku7BSvuBS-YcT6$WhBt|T%ng6oBtYoI#KfX6OJm$Z0t_=(lisH*Zj@OwlPGoL^XA>DTa`1UhFwXD`UjE;Wdaw55A$uJXMluIOA`y(G>E{Ka)K0MbY#ZldnkHp#Op#85X;CIq4HikoAwRtKgjlQ4)ao_DXhrVK|5GCUV8W8hy9&zZanwC;?87dug@BN%M<=16?`bk&OqnR8!@Z(^dKMCvr(D*3|%;{JZiagO`0c5(MA0`lR0!MtQC4izP#hYkRx)KF5Fd;rOhcwkRs}-9GAaPXX&ouYEHzrBvyVt?Zzp5QO^Yfyh#W7g-FDx{+{AZx`Nse;une@T`%w4zhwFo)P)G3(eG}Mlpa44O*@&8i;pZXh`NoaukT{%|tacCc*PV-gy^0+6}0MWNfoTVF8{UbkJorn27|HA{t=?N`ni9!yoHcMBOSZf({)6GnNnev3^w;YHqmuH3Oa@qD(c@~ip0&;nSc_Sf@w6MiqPpTs?_TUmO8wc$O)F&}4Updr%Qiwrj(xL&j8sLxy#edT1NNdGj=`?ytLY*)nud5|;@&*CtZm-;Z3os{W|LOylg*j%`-@d-BL($Up?(R^d&PX%!_8xO*97ZVw&KCMj$)2F19yPGgC7Gn26g&JZN@yfzd0vkYg8Wm8b4llZ4~_~K;qgi?m#A#JkFjl{D9m%T81xeGs*|=#DO?IIXoX!QHtp5p2;WL{QP`Vj{55PLgCZQ+yc1vJn-(QFYeUIb6kqc_e$c!K}rnsIdNlP`&=*7(_m@MM}>4{%ohnyxD3rk=`b^>Z2wLX{Uke|akF)b0WFUg?ru7cd10mO#Q^3=9`Fu)9L*Z!sL#kpj$Ei^La|`oR^AlkbLQ+a$*{nDu<*TEC*jF)|LXI?JMUK)fIdqY=y;%C5p#vw$_k)w{fPU#NaS|Idf+OxmI4+QQ$|c{%%`0ryC(YQ&|t>T^R?76gQVL_SdiTfACM_l}5n9X6pfh}7fX<_yR|&Fp=SMFJgQ>B8kCDdb@K^zX*jXa*P%gK;_ffEoL7DXl$`2RBZ(1n~IadYQQSI;vlb3H{I8lv7$c>YRt>FQ)!tg5B(IdpfPqPwtoqOESp$Af~YK@d_T~L-bMX-BJL=+)I;Aj&tO+{C6K}3gGJNEs|4@kWZTG%2cf(DyYSNu9$R0ebrcXYGL6w8k})?SD3^x7m4f7$LE$G>F{X9gg`LI{q|%=$Dd%99)9+{lgnTOa`01^mQbbS0WohjA_h6cSM%UFFz@N_M)vJD3)pka-KtSvZMn|%sxiJ0zVI^VDv9Cw;|;s1SATb10b;-InT_uam#{YWzxA?V?`Vj@_i5AvE)6IA8gG%oR(r~IVF>2;=Pnz|B3b*R{;cDk{Bl?)*(x~oddX`#l<>L7at&hrs_c?O#734spV0kTG<+NDSH!!ciu+6;n+BY8GDm&Y+S1Zu(wh&p0p1^mT~S}X*=#(UzoP(Nb?lj0-iA8L)#Xn-lU@khg)*f&ywNVOU;TQ!)fG72cT0}39qm&>c17!ya^bkf>>HgsF`loN|8R2t2?`|ayx$r*A9cbx#S**0KpL!Faxqop73u-v9)ZkueDFPNF2_A~qJMYa=K{FTXTnVJME>vM_2+K5UI>{W7`;Cc>sp5>i&KBuUjbtN&({RhUC|F-ch~WfVQjwcp2BjBZ{*r-zqYTT!qMI1mp9vR^uNkWzi{FY4fsFV4)pnOyz{b~wStktfO#3teMLQ}6PyoZJ-9rMM3Wx?2c>;Mcu0MZBRnBv3f|i{2TYD&u|fZOG^NiZ{m`l$p?^UKWvh2=kzuf0r#EOD{>t^ysWoL~f=1DZ^Ja3*fMp&BpDvs1s&81#|ydTnNPbhUTlNuMF4AovM0J2$oUeu}(V3GhEW=x6zR+K-?dkzks7Z8(*z<$}I}J&i~^r#>v)ZhoAipG+1-RR`aC|#zW${@x@*`%r{~BMRUwI*%c9?tjfx>K}%j`a~mR`@RAb0CKo0oSqgfNl^~zG2NPeZ9xUBESl6X)j`@-3KX_#?D=s;X@$8pDZvJA=&-Sh;gtXYUU%#Y~o6qmSJN}Ofq4&P^w)wj_`ZJsxjuK>jzu~Jk2DUB2b=u^&?-9+L3XMEZ8wNPu4~B9dxTP~f1CPYjqkp1MR}k$1w;M2^F7D_nZ41m7TW?4Iv^|>#jAJt0{D;v`q+z$>zGNmS{9XR;OcCaV+dW!7y;1o{(dI%}RQ+|?m-`%bzv!R6xreX7tf@O8n>pqJyi!5x;xx^ZHol`|FSHtM#1c-m~9lpS9k5?X}NmBT)+3%-2J3J?=8VGuHmI=ka+f|`Hy2bPcpwtj`by{16yCM4(AE69~o+s!Os6@nUeG?UK~womZHENnZv11HzGc~70Zq~)l;DMqB`aMGUOF8v5x1zp3H>J-`h@~CFMo;ZdS6kk4}Qt<*&w~NqxO<9Z`05Xi8@5y38ik9o=l~q8A>N>+vUa@oF^-a(lRq|W`Ndf*KKN4oF~=SL=ARsqyTfF5Qo%x#D~xcqOjiI^i{g5Lkfsb!I0Dj1)WStj10`OlO^f@>s#(DT9yneh=rap@~gxq^;NSsr-1H@%I05ch(qnhg^Cf|QX#7Mtz^|clD_DazH889U)Gj_{>})zJxRjG5Mqy?CrMR>PLXZ?$(zJ`g)PW8b@U&fldm6m}mU&um@9*(6H;a9Ac-C=dFI=3@V7YH9HX<11P4=JbxHMLfv62)z4lI?Tx&M&@0zrtY&yA6hxokahL7|2MJB*tx~%AkD*Caas(`t=HA(Egz07I!=M$fTmhok!K$yRPOFM}tbf)#n_G+bp&)xj!XU@p4=u=JSXbhHLx|6J(xfS`qnQeXnH@Y)mVy~Jr_gUmu4mPV7NcT{Hk$$iBU?1X1=u1B<&4iy;rrxw%jv$|IJr@{8amKmHmq;p<&Qm+L%)8TDL#cvaB#Es)z+6mLq4Cp_tb0}RJaU=BpBEL~!`C9>}?u$6zjtXT4TRq8yGw;3ba5W&mTHUU{+=DfrnIn$*mn;!aqAoUR85J%G8S^jFkTQk+7n&LaDVnCpdrGoUMh?b@^$gjR=sc!gIo5ZebGJ1{sK?|LXXU*14fhRYZCeqdzFT!^)%61m9p6?Zt+k>P&jO&e>Rm3LKVBhsEdg3M+7k)VorkAhEfWWWKUyDd}HK`Fl><=xYK%em9QZF?U|IFkRdH0I~kNtLC5a&StP*i@@>v3)-TbCg83*tlQhe#P`fkJwfeFN!S>J8SyV|XMBZ2FGdEnJTFgIbTm`Sn@z*61{4j|#@q{U37d{R>i{w&VR915*AgN^JF069+z?AjQ!3?f3LDYDkNx(+Uf2`9GZXln`kJo_@VN=Sl!)-Lt+0OeeuKTa8M)JauX?UL+JU;QOyAMd0diyduLVszjg@u`dfcy-Gg0*dsm?5ib=EH)g@Kv*6ZrE5wI0Xtiq1juc=l+rByCDDo?Q*|WbZ3{zpZ8dH4?5Qi_?t6$bzrGeABdb^j(h=aj--Yc!F^^V;kILx6((%sErEY>@g0o~{6J;Of{2SS%Ai^YfUX=puKc^2OnmYelX?4y85%!c=RgNOssUQIVJ6C}Q?t-X_k^Mue_r*6uE8|^zz#o8f0(ic8kek;g=@iM<@cO%4SN5oLROG`Y=AsT|5#5@(TU-PXc33Q8xWe%nxZ*j49Z2zH`%C5%@4b)8GDJlRlw{MtaC6V|sY3IF}^j+p>EjQxiX8oAHd1I4ywMcOBWzgOv_Wi}YEw1=-+`waQjmw3%xRfi~G_IW#B?k>z<9g3n{=ZegP>u(%7B99>Nsy%q_T_!yX5*E((I$Dpsi`b`8i=+Y}mmYW*?O#$%&i^o?K{ACm(dsJN+5H|^VW#rO;(CvPif_z{ei*T)@++;f?0{=5f15n9d(Q46#QEdF7dx($W`U)C8mIG1+^QRnnSFFStIo{ti`1YhxtMdoqPt-G=TbB%l&-L$xog}TNF1G8MiKRlELiv>DAM|gHHHR8Nf!LMFx7HA7?N3Jw0fdAPJC0`Vktmg?ToK%;tEXpsf-uFsQ8Yi*t;17&^v9-n>aC$BA#+s+@53S0_Pd@XH(N3?fH*%Sw+QihN4M1JdrE;9KB}!nW{8j0NK@-rT_$9G5E~sP&7Ulx>fI)3S#UXiJo*`_zur>CpR$GKRN(Fq(tS(XH?(~>U7N9l2KUaNdD|C_^D6M^Qags7WyKR4H7L0`2mO81B;->3|kkdL;I5Je2KEjW@VoHE+pf$>R?&Hyq&iq4stbb$+r`@N4^rj&<4qmhqyrgGGDim3ZNFnww67-T$hG8bao#Y?xkdcr7urSzzUKsmYs>fbIU9sc*KTGoF}R3dWx%rsIb}bqWihCh)+l6L$7zmRCd36E*ZopHtfFdL3J8*obYyTUybcqHTBm#4Q*H#{e&3m%I?i*fINK$*wSDIpe$TM%+J(k%sj#Hbey8>UiMgBRlll~UP~Y@CNQWrlrNJDFFb~rr);a!8n*t{*Rexl3Vca*ZRTHVH$%KBDtSOCM824|V(Ta`ymj(3(VR{v$eb_c>iHJY5Xzcprd;Dk*C^-Euy^{viC+lVz>A26>D-y+yNQGoWvw-;B&n3vaimE5yzFtL#%M-^9B302|68N!*J3kq2GEEALN#}Y_4Ih~^Ih+d01!3E3RM5}2-ix^D(31`uX4S}jvA}qjB|n{g|1JfHz8p@ZIvKY?`Kxz(GQoiLKn3HFClI=kvAk3`y=!6MoGRo4FOC&I>YGi29Yg#-B>;Js!oT<}Pup1h;mJ**T^xw>&!bDfRNl)5`4hVi=1d^(I=`;(0dvxR;)PFP<@8ypKwhP^WLJ=?o-)N#q*)Xp%`&%)$}n9{Fx0edVJ1VjgsHOoHtlIlse2-$_Q#!K{f+8~ektTf84JwKWSay#GO`|$|zd114I`MZ@0F1v1jm9Ry8EY7|>xgeMZ4YxF&C~D)p+U0d6@3TTSyiV>VbV`4QrL6>-~R2xeUasbCg(Lbq{(q~9LW8rxx<4$Ggc&q{tp(y^ECskh3@0GGO8f!RSAPbDjdZtUx$K=HWRHGvdTy?4W0E|ZZ=&~}hZnkMBdq7%i7-u7hyk!K1e^(EAi8QcDf6;F9SE>rz84jGwo^r^+#wxd`|uDm8o8p4bFyN^PKY#AKgM>553H6NVZm-cl;6JL!1kEtD5#-{(Ld=jciHnlaC|PA$@03-^4$}Vfg)>S5qw+U~>5H^@uUV!7poaTlgRa2z`#tb4hxea}LdG`;iG-jw{K(IfnCu7-$AS?Wymf05;QWI8DtlnXH-3+7SdfwEl=2qwsS;hS;l*0d5`C^KCULxSlWD8X>eGQcUZ?oLNaBp$;8jB8p@9sxpS(ATIK=*39IY};fyPvEx86l)&pfl_MaQR12$~&#UyrnZDz?hj!k)G6qeVZKd-{&lM@fCw&el6r@XdRY^VkaKNr&JfpMh;Ou>3b1=OK*v%(1i`Thl^=Kl}yzIlmzebLW)=tv#E~*1b$`#d$*L;im>CLE*+;{u!aJMy3I1^+(G#l=9M!rPoa(^hxg0%uS9XHmYov-loxWY0TTVGf5G1jF!^mYY!Z^{P#Cs9^!ZeZQiqMd1he|YI||Jl&Is(R#C#6IPcD|DDL$-nTDq|=_|qqcA0F&$WL)%wH;@+*NtTDXmOGVFWyyW8qC?z0ej=%U(bpm?hzokr?&N1Q|c6qx~pen00AtfO9aa$9Y&OD0_3q8DVm8TGHsoQ2;m;GhDbPtbV@_Y;Gr&d$qbtR15tMzwi@l{H~hQXYD0%XU(s1kFOf$jtzD3Ip_~rU7Mza8q`rjOPm?``EmI(f@?BDc)KB)(%g>i52GSrW{Pm5!A4vU56eVuR%%MPcf^>6QGsblAgm+-!Ln|m2`N-7rb;A%^iO?_;ub6TRM9_IP;*rQLrR?&l5TvC==EHdIz7E(3)>rAGfo3)PnaFdlsO7({!-ls<2Lnqg7&_UB&3n^B>Lq(s+Ub5eM7&Tstt{5xOe_zcZmkVVi-%Da4J??cvp=0#QfyPaE@EB_d)wK3%4Po%v)1pE2V3Wbl27^qK7c`bE|wznW^+^4J%|sn-x;+u3re1;-jH&|I4GIs;5mMr3MpDI6)WZ;Zb4V`i$q!DrEHq_$m}KJ7Uv&Ruu3l*h`RojO^BOaXQ}$`1$1`Z)Wr|TuL%FpVnT<4b4$6dlIptc63=+lWzk`Fn&Z&EwaB|7+;=oiv3R5Mc}bn=1oV@c`;HqHZO?#(5`$~@$e=&G#D8$}{CWxqS2Zr}=SF-2znCuVmCk}>xvjq{BoUv8Mel@jPf|h3d@4NE8}T`|ZI(W-5ehL(mQpF?-a&O1>anK2R$nIA2~DrHj$(|TE=}qM2iOPJ$keDij(kB3wmH9nGLN=LY?AUNP6Z=^5d5FX0y**C8i@j#CgU|2k7j56BCl2dHJ*f^NtT4?A(m~j*#BRB!zo1Eeh$7x4l3meplj*oj4cvlbHcxYjVE5S&H%0Lu&Z%5+0UcS~y3pW)7(z-;Dxi&D~kh*~NM7i4du84!87zJasC3d1QDp&=}_l@$Y%^G}x`e{cCSC&J*F)x1D@>vLVoZSFzv~#7ApL~v=k90>>KhjQO{Wx=14)qJ+fh{M5>y)h4VQQ7a&7LwlPizHuJrZw3@Iukv~M3Yvql^UU2J|18W3`uqFVUARQy%)GOwY5?t%%$MQ;!XVxQ~BwQTtAx~x0u4$hN6M#tn%77qzqJ>TB!FzG#dukAZ}gbo}Vy_TQc@;`jKl_bu_Hky7&hRb8i+ZUu_{z^)dI$HTF4Gy(DeOz`3d5&?=j{f!b6sR*g)h5-UkJo#Cyx{JV1?Tyc`48>IeZy-e0^d2;(BStMwG;ZEu+FOJgJWxoRW{^i@72&gf%}7}WISz8snFqP`IRtv3V#2a?>SGm=h4}E`+E&B4<^FYSdzAk0qahzX`EEU{)Y2|m!1f}#DL2yS`UwkU>;19+iipVuM{{see(DDMHu(bz3V+Z@i-lVy*y5}#$f)cHF00P7GEYj7%xg#Pr>|E!MBCe{$H~oPBARQn~pqcorC4ot5!5PMhI~fBQM%+u4lg@D;o~wejLiRLjL0;)6u)?BpuS6YuE1y!hJ*HoVjET9f*48t+UZSRG7Yekr)H21-IA=B;h{bu-u>GW7Z5XJadG%&KT`Po-OB7Dp)1WF7Y7c6P}Iw9I!Ue0B)JT^L~-?1J_i(#OJtY!sWyFiay$7+?Rj)_xYN=RJc87tEn3w#`m-5!_xWFXzkS{$ghY#nBFh4VQN#T*zOkOQ6YRGx4KN}u&HqE&v??lp{`WCw?rcy2%b3q4e}+upzZ}!Ne1{m)oR-NG&jojJel~ed%025z2YK49S7{v>FH-lXeWubW;4^llA@T(JLn04wQ=JuOtLp#JNPWbrjDmIurc>d^I^UK^lK=l)_f&@S6%E*ZoV*YpyO(>_lRL73t@8r42Zb>bgW=5#*vWx!WyHW6d-iPS`sl{MEQnTm6I~FHP&st)0r6{waJQqh|l6BZ9m6l8L%|4q5sTp#3w3a;Y0m_447-oDYn!Cc?CtogK<+m6Pn@^ZmAqY9EkdaQI9O(JGUb={4nCcTCU1OrBY$9F4GuDK$4UrFni!lz4kuB@YgX@$(6)w;;9e2UxOJu%G$qQBOz!-#{_CFvhue6v8e{i@`Vqlkm)sS;QV>*{%-X^Y8vP@C^xtK#q)!g@4BYaS}D-~?Sgf%1=eM$&)WH*)|3i?j{K(SpYZ&kV3+c@HoI(CJ4$W$o`dt_DEFMR`q_tS{X>}kII^S6xF5eT~{s~KlQGQ4$B@sxI7eze8Bi=*=!p-28e6+otWZ8oLda{mh2y7u=S`p%8=h0bNNQ>HDH1Wi=Z|YBOi;O>{3XjGNHA!=t<;9d@h9U;`uQq~Z{pxz8oFCuo+ATVdP5ZOhdXi5bpnuDmd+PS=4>WckjdB-K-xJ9rKazkB!YPYmtx3F#ZlAFz^cxEYw*yO7T9I_i0}jY2TxS5mUp7T!9)>t)e*G5%Sj$J(k|&6#a@);WKUm}C`ly*ci&Q6HCK0lJDw7F>er-V);=D^MPH1?T38B|-pA>zBd~8KqL4&z;CR@jH?l8s+|JOf+&6KI|%eh)l#t8kP&zrzw3H;e$OjG3pQe1G=ai0=CL`JE2Kl{_CrV=+GNp5K>!!jS>q;foL6RYKf0i`}n3Kfr(uyQN0Dm*RZeS>2mhti=RfftD{vmLZ;Y9eTDM2~3#io9h3t3-LU6FS=Bvp9vgq2D;Y%L_8PS9ekM|k_m)A9<@jR8Nd9Fm-lrlo3}(%JU*%K%-tK*+DA(k0QD_EE~W51T8bd;7r1&0bv>yA#ufsx9TzPm9S`uy8eR=FVWTE_{?YL)3w;-qBNM5>23P0gL^Z)ZJU&xtzUXi}d(WvRQmCs^yaJ;zGZNP1#oJHDH^)-phZcfvvU9^ymj+fb#LK-<)EGL_WFutD{Pl<;*X5c7zSq=ON7dTRfRN+u9GNtUE@cFP~@&3?Zw3+8mk>E1kxaW-Ro!?4#Ya}uyi)CmSN^Mq)7c!4wzq+mZt;JC&XX!fB1AOEu^`rEUTuo^+pak;XIktX^WUpX23+l$vAh?zAEutbg~%`ZszY^pn>=lSzK#;&(8!6YjM-4ABc}@jRz;=921(O?(454^`}doOzs$$d@KoM_vPCokPo;S5_HI1KyTtpCO0MdBrjJfc>KGrwDV!DhNEnhsl70dk2isV{a*!0E(AEIz+hy5Lh0zAtJ0!f%G18L;4Ld-vmSh{MyQ)#oDG8L;>6P;1@o*qQHt?%=WS^m-=yyzO2BFdVt#@xlkHc#ClLq9e~*`{y~qG|y@s9T%=IJZ9_u_C$pU>r*&J;@++X{vQs*plJsZZ#$J-dZ$a5S8nr{j{ro;OTx9hPrsL!zO`P$Yk-VDfnR#%Z41-aH7{@k1X=8a*ptATW4po^H-JkFz#!g)Oz)-lL`vnJkvdc?lX4c{Nue75WcmBW}P%~1F99oNZLOA}$+Z?uD)^H;7D{IMAzVd-gs8X`{Ii>jTpy2-)Z@XpW_4s8=Z(X3SY=OrER%qIV2iJj6GM^#!P*Zki~f=Hh`j!&Rlj0@-!*Qvv%ipE5qeFIW=tUJ?o*E;&W7UdHrKkDFd{WnWXFg3uJw#7*R>DiKvMtlJ-7ZMzuNY2vK%6EV1mQt1HT~J=M_IrcK(n9x+bqi^3US)in?Yfb}1wa+NrTYrKEka*L-s<-hZZntFMIey;k(+ZX4e)R$0*5{$XAX#=GgS-1BzrV!%sosl>Pyh})!9vFY`01~esWz3eJL+*qss%{^C`kYzW&u5<(PRc-sa=UZ9hT`pJAc}E5FGwn66d6SfLfH=P%nvVR6*e^*9&Vhn;w&mkTFyEEaZ`Mf^u#0;A$*|7TMSLiE2{;+32&u^6z9hxq_{CtR{KfJ1@OXLS@yo8=jYYfIgqV77ZgTd~D;5UUlL3sIPtu$5~dG^Y5OeO|#WB=XCil?jvL*`Y)ZN7rf!Gi5MaQfMWUBc$buX?_QFpqk%?8h5;-g_aQgKPO(v>J1u|J3!kes{!^$V+P&Qi1#NPEY?d^po71ita0_vHWo5&qYI|bJ_h|+ZV~R#`{Z|HDW)E3$=^eYr?lMK**2w;xVaTp}DOrx64xo{7m+EHt!kYbKIHZoaPZGoLniECP3m3M4z^?QYH}nv9n2iq6s||(X~1My}lsBPtv({=8*A&F1>6Z>Q%d!V;p(0TdCTEweD8QHOO@)>3i4LoqSy>#DJ69)Y1;pI{i1zr7S&%0k19#T>r2J@ge$yJ8owJAxr(>I^sjD=a(ciA>jKBr5!w&uZY&GpLLik2eb)dPdbOV;!Wdd&hZ=|-j8iQp)=R--mp_=ZF~-R*6Wv>d64=?d!M%6$Kp}MeqdoJ##2eFWmP{7vVl&Go04-z95UVszK*;=2jV`8Zfmya#Q*T=R`OY5^xfKn33K_R%>7!BUse8*KCS(U36T-3Kem{!&-lz2B$xtmh{O4Bcf+`j(?PC#)4D6shyx-2_~REHIDh#YBhIy-@d>Ep;H$W-fJVTxM=a^qEr1b=dH|vaI3|4AQpMW+Bp9h0h1hdo#eD7Nx$^y(fbz%sIbmyzhH_F@~d5%^|pbU+0dxVjLr>496rpSa{Z)1hwuFBxy=#~hZ`ym?@ZpZ{Fq0;S&0I~foqLQNd7qn^z_fV*ZLZ9_`#a4``$2scy0nSdEjoPp?S7mmA6%BwKC{++Y<;TLnC~L$I-dSv!q6hwb=#iedqn7q+CvUZwK;uF4Z?ia;iHuWPVJeX$6CnGR>FRQgzod5KQvfvQqp&<9rH{6qm+>E`E+*uq@Ww_>(SIdxCGM~?E1Y|Bz=aw_Z{9Y4onbykeU;85bb9D_78lPvG@|jSYOu!_YJ{3UFURI4%CSk1~6^$``tEJz1_l*3;ywAvV9e}Z>X)5{@}1-?tlN*M*c?B?}?@5!h`Nx8{a%Zo|d>F^@Tbo6&`Lcq<+`M`0hI0SIzq>8-DFiS+t}d_n{Il<@ERRF+d>P>+rZD>H~}h$?kLe$p9JRz~?&LH~ckU@NZKZ6OMT^3-o7U-8-QtHKdRO4MXz|Jaj}JNBY5^xZu_m#yy<C$XVkW!4p<58fcb`)C?S@a7FqKzgdy}O1e!_Oyg8|JPu(8{)s_Y-)thaXyo`M)h#1wuwmkIbo15-D+ONj|-d%S$?4Xm*mEX;+kzT_Dv*0cN9?T`_B6hl`=$11fy;qjgl!AO9;c!wt^Vp1fjBR|uMGWL!(6UCgT#2fbA8|YlKP018H#u;VZuB!F$;}MU*S^Ot|9_w0)58f4Frk%~i6Q#bCve^y#c|9V+6czAxJ;H6w?eN8)uw+^+ndrd;RAg+dX-&}m1UhrbQZc)d883r${^cz*>Vp4B$pFMHy0K|A!+;HxmiQ@`d(lk_kRdaV{x|74>-{NkDVt~uViWWbTKaUrrBH-n`A;w+N_n+44gl%vmaakzLEn87i=$oRziMtG5MXI5Nkcl5r2QR*C6sMAub`R%39WQbiO9OrixV0_Luk4vrDd)*&v)OrFCkn<>VLeAvFB3XcUZ5E7C7mzhbotP@ZY={gOUkd^=}GF-XD)XnshR;q9Ypti+^8>l;eT~(}kY9C4zTJ3!eKs)uiqGF)hP=X(rn=^RNGZ)Dx>t>F^H0n8L{w4^d%kLa~#k7tMjajs+`izl107HI$a5C`!Nzl=&c6NrAi#!GRY5cO1@!a4ud;m7@No-`|o{Ts1gc`FAt^GQze>_k8F;ID+^;kF#;yxhL(>JQ{sD;tbNudtqbaPk#N?MFC&&b(Vg^VpOPYl()nDafxTD>fcntVw70F_+0f9GX@4*IXK+v+GZ^s}To|Ep?%f?=gVT$>{Au9AsGwvZ#ej$YyBj8*!lhr|0$!*7sTKh0xR06~*5FR6Vp<|^XQ+8Ou2)gT8>X_S2tyMg?wbB8E(cUBHqJGNUzN#J`#)Vmvwfo>8aK)_#P2_#j`CCj>(3&x*NLA*cW6vi3ha>L(m7OeVo%CGj{ezZYU(gv~Fq^#`w$rum}gwpzXIdJx4#uu78^!2}EDqIlIuGsD&q<-rybuHIr|fm!3qw9eLX4_Kucl5XluT-9*wWyOnyjVAt$ecww+EV8LgcpPvf8T;N?82Q+@S!i{I~IV!&B&X1iP57!e1Dzek@xwFFVx2>W9;3G@-tJJwOV~2Ye>O`*xK}Moe$T3%pYd1q~eDkA)z|;4SlWJ!4YPywfHfh{#r-i|7rO8PtIUJYGtbe64w<91RJl=C{432B%%{k_M!cov#(z{fv7{|4ZGh|3RFdB$FqMr}?t0Y?9sQH^1nEU-@EvE#oo04tP-@lv{2P}6xe#RG{qcvzApT!#QJP)2-7fNyd6Z?xHC;UJ}>hQ|VH*jC+LZ~8d^mG6mwmJ63apK|3_ej6^7yTU;r)%)XIxDLIw_2=71!{IRSaelRs3C1J0^G&f6HIXnC^S$M|Df%DjUlL#UoQ{UuaOp*jDEccx-)cog4Dess@W3P%{oCM&z+V3GSn$`bYkc+z=W~>Q`^pP*<00mDKv>>5&i}f+1e54*-taMQRh9Yz9G6w9%HE1|{;;T$|NJ&%9GB_+-8_FSgMg@m=8C~_5qcSAYeRuJPqya>`bk0-&)+^Ao@T_H+w%bDRYj7oxPwz9yAHYh3gUk(@!MvPUD5EZJbA2e6z^Yp-mrH=ZVb5I?=8DS>f2lX&uwlW>-pN)KG|QMkN%Lzx3(^fhv0IZUoP9wKM?y|DhoW|?IZ4+UrR~*o6oD?8=Un8LU;3@5AuO+&tkboGy`Gff#g)hWYT%VjD!V0FNMHGO#@X85z_j-(`=T~oN(wmwQxM!@tnSvvx!t!led*m>p&d4Zf&nu(#-WHmoaT!NA<<#NYGj;YTv4W@lG@NaZ1VIXmEQOApX)H?Zn^B{INjjXDGL#z0*@?VaeS%Ao7$Jyckboje_HMn#6-ZF2{b_4z&MOyVg`3UY!R=W3V&gQ$)9uV;;)Zc4%%8Z@R`I6!DhZ_eDdp883o%lOmHyCc5=b4rN8^53E!|^yb45~SdS}bK#@psSN{i$Id30=*>G2Dh|f4rJ+UTb(XG_*-L@j0QL9{8{;#UvKIWWNqt`k;NU*EW6CcX7b^)uh!V3hh<%3Rr=JHQpQZ4Y*R#ZW1@^et_X6AnGYhYtv`$pPe6kdKVH^^MC*Q@jrXB(nnLRO~xDj+2@$X`tkZ$lb0f=6N16wxxrbnmh_qLH}Acd_gXLlo0UmAQ<5<>g1yu5;LoCQ=y$7{)_P-pIc6_McF=LwFbae`O>X3dOO_P`M%nQ#7}{^e5tKb@?Z>j$YChZmj+0YYBrb3x|J_fKSP)0_7^9E3!|lVrA|y?;bnfE_|2~1Gk=pZ>~2*`}aGW_~gywK+?8+Rl_p0r!^+^s9VOvdZmn!`sR!oyWPgSFP*p(KteM8Lu&}yiE^pV#{tlH;@z<(m;dEky4m_vyg!22=RNITBM)JJjD^6*(wBQ=TX7xD{%8vWqR+h5MqF<;UB0a-84v+&s`E@4-*Mea@Me*zoPN>e8#3QaEq#baEt@jn=p1XQB^Pk_)E7&>@mb~{rbw-Z1*A(+$k-Y3Ff4AZi&9d;giu&d;9n^Em`D^e>YyB9cIN}Lf`4bBaH7|p>=cS_QryezMw4UGK}x@igcUY$Kqg#@rkK5>KI=H$4h!LZu!8Ip}b2DA8?=U!pW^eQmO&KTT`CWyAsDWRJ7#Vd){DRdWg);+l1pfs`sq@vI~oEgv|YV@-2?5)co%^dPX?Z{u%r`DNgF|CfWV!L_j3WyM4Ono*>4-MCLiI>OIl0m4Ay+YbC~a;=KG|dJKFrmYf!JyeAADsM{r(c=Z$7`u=xFMsgdSbQXf_J$JS`L$oi8Sj`zQFWk21P#W#jtH<_6C;{Bi4voRxJ2ni+o^O<>AVIEq9fTD>tYj0ZPeuq=hy}_j|!4MZ{XCfts_p`?3ftOcP7;N3R^sDeF+6g_?JdH?Dyzta3Jpk_~@YyYmt0$sCdH%KU8|Np^*#D~X{(U463lF9h5_@dX-f>(wdDMf&H#nN5Usj>LVf}2`-Ny0Ie^%H^*;No9@2UC4}&Xm=0pd>m*i33rcC_Ze#U0bBd^0CR5B$#lf(mwd`+f9Bt$yfYB~F%{ndT>+M=jv;F&$X*tP@hcalE739xX?H_3embtl8T*VE1)YL;L$QO0)mNcu3Z{9b{^S_9g3|_sObQ!}t^N4Ie)v5A@{n*&^`U1AO`Bs%%TZ>xp$WpACy|q&D%dT#o!oW0lS9!pFg|JGagu^$hZ>CyzqbZ4e8G<~*7B>HBCGSua+3xjho3%IK338EE&GdK6JUHwL~+&&^r&m{c!hJ{7+FMJ(*+TBD-%4DE_ikFQ3v_{L{T3kQofv|H9wcrMk(vvu>rJJC+)9Lm48grZs752g7aUt)jk_XOhn!4)s$SK-^$2I^k1p6_+{s(cf?{*z1R;XleDAU^i~(9|~MGaRp$$^FU+2i*-Hc)K{zzW=z`(SH_EpfhG6^zCIDj_Z%9`SGY2IM_M1#FvV8LT_c{TpZl&Kauj*8|~ZO3ZTLw9u8hudqMOv+Wi{G*T?cEK(x<>N|7UI4|&uy)N;xWh(5-_$BlT<+OEip>_rW3NwDHhnNdUNra5RQ_OpK+j|HO7n0*}bB9FPxX_-9n?ETP54YU(={M$?8f#?hRd=}cnC$*>ek0pSJ^3eIo^8b&QI{C5l)sB9+52eCbw!JGk0EqQ5M;r2xm1htB+SC;Ul7t{m2JQzDyMoq(A#D9#?k>!05xUhGRbg<_9X_EWy8$V2)X4{zNx83-9ALLYKdeP+JLJJ(k!;BW{C-ZPa;8^Uop!<*noCSh>xK&j?>`JkEW=kFaA_S+Q!zBlV@a<(IHT>WRE?~l$%=nHlW-~JWH6A~~xHkhff4N>eW{h=oF7j{(__$XlNFOo{8oc|q=;-TQUCFb_%WI~2?L!E!ITCz0+rF8{G*S9UE51RlR|zafd*!|m>2d{_5B#8|@OnF~I?`D94a6}hrV=P<1>1_-_L2c$k1E9TRR_V>raeC}6oMa41S@@d_4(EFr2pnTi$R|XBoMI9dsGq8C85z;FC`RzEaqmwJ`UP%Xl3DIDv26^Monj=o;8-jr+SgXi=H_oe29{uT~m7%b2Zm2kyGTuMcdrs+#k#P9@e#^w4QM~^ZkptU%-bccd_7pXzi^v-#?KTa%xJQH7)H%(EQOH}07iKEG_!a|=>Ej#f6Oj*Ca2JYPkz&PVVa>IdJ&l7e&@IKX6{a6si|;wzm+v4U7dgfGD%-Jqu`%=7v1+B-ltaa<^aReXc+w1dVb@6%*%1rn!XL*9?RxeXGl7MzXO7Y;bt88Y~144LF((8utir|Gu{EJ3_ri;55xPPIxo6MVz(y{dS;DxkzXCP`z4lh<{@~T&bVaLi1TERVbE;>)+oj6#+uCY>pR@?q`;Py59lyD7bjgEt10l?L-}B)8ZI-w}$poxEbwZH4A5L3Wx>b(_&5HjGYsf?R>}LA^#Q+wI4i%c0#AS!uTo-)_xBgOhbM}}4?t(z%nbFXG#EqCA9eI90=&hpv+65@)_g$@a>N1x=yAa=Tj#==i(U*7mdX-6B9+tm4T+4&+hCT`c8Ca-zVdW~aFQ`ypIa-?iEJ8QMR9#&S9c-!g$nsPCgVtF0#01$oZuF4TyIfILs#N>Q|5>wkKwXiY4WO&ec;c1N=lK7uShN%X_n(2e=GEl(}{ht|cz$#=&DUKgON`zB=V(Wo;EwfS#kDF=k)MIkTb9!sRh!57V|w}?Fyk%!zVdzzs7E)496gTZQnGvDu(y!?=ZV+33amyz-3MSfKp$GQ;~Zy@Rf9V0Q%V54u9D8DHherjhd&LimzOHvBBM+{W}4@1i+8H_)$p?99MuG|?%5q+d<^DGp(u7szSAaaDp@E+yu9;yS6j5h6F!w(Eb-i42Z5Q$o)2cb~LmT{Iyfap05lLUV-huT5#sYzO@1Of1Z_ElfV?KU41VjV!hjudlzkFkG7<3nnS{L2K`zLgMtXbm~O!v8Ev>5N7s1N+JFbYzmszm6QN%_WzsH+EVMuTZ@`SL4%7&k|Qqn9X@#lZDLjoy#%Vcci0f8<<&JzoZJTsJhv-mN|9#jc|}*@ojH>N%C8{eT!>WIFOIJzniEbFK%n>uMS}@&4K8d$)xE@iSLPk++}G&Febg9R_`hjoU?|5Pu@?O}!rhtX0SDWq*;k9RG61)M7ttym{spN}|ZGh`hvjMf88?#D$PwHGKQMGG$&Y>>8`MaA*Yi%#sUS`c4ZRAa7NgXt69w*X#GcHm91qu-0Qhr|=~5tK(<9F5j2%1zppXj&`JcFI%`rED(sY)}~3s-!4Y&)G475&~sL(Se1@Av)`k{Fkt(MIe4ET>N_h`DkDHj>rP^ZIPw-khhl9=6uXb4G)ez(bwXT*`l=Xc8ei|HVDbOuyUb!?#jCNyYNY);qF!3BzyesaMf$BUt}lA}^tZ+Pxq~saV~1=r&J(tuS?TlN^ZJDRirC+c91nmD^A)Xc-S9rmRD!BF{wf9*n+E3=n!bE8gPu1fM_H6AOpFtLA=RmN;`g@mfeX8-w##N!febknj11SuMV^^)~!hFN5E+-{)1y(lF>{J5KS>S48{ReXGY81!IBe%X;n%+AlaCSB$rcgT2eFn;tl#-Hr%I*~j7P;yY!B?2#`C-`n)!)p$=RTX(&23cqJ*ZvBU#1rcz!&~{{G0_`T9i46`0QE*E;OK%Q|r;WHK2^Gl4z?~h9slNx&emP}f-Hz&57`80ewfutiBE3B)jCkY0l|x$1-~-y(eoFrw5cSLY!vBl=-AWonf%TL-46|Ni^GxJXv(19H2;K05v~>n*59Be9%e^yjd7cx*-cR>xHrm<#-Nc4{jzFgl`4!twHG2Xv?k#@EuZZ`z`lCPmOsmn{>5BQQOy=PIclxxn^wmB+84Es|$2v?*(Eh8naOdak@c=q+=p(#num9NA$n!iNmhvc6tCS+1bpz$euLZn-&9e;tr<>HR^zpTer}YCLFdTSrH{bRDadqbLRK43DR~gczq9|o3B^pE`N>&QdfJh>lN`{iDD3Y0wnSt=^C!H=nDCYI5a6)I^7a`bU-4VKd8Q;81=p0?eBG}hhm1~MyLn1~9JE$9_aE@X^XjczE8v-!2wHk4dTTZ#UmZO2K&9e+G7#%y%Z?*ou@BeJxjC8&=4EdeD_A05U6S>Pds~+Vo^GOpyC-5C-2Gz55W_J8t_0=H?r_KWE;&>7ivJTjES{_U5iV2m54$G684+cGW7wjXtOn$kbBPmpL>vgjd)RX;Jg=^Dd%f==5#&1Bxe3T2#QODol~@SB?Dlm<2cDPA^mC0brzb-2giw*vPtY}w+@r8xgva{VVOwxz)%ah(UQc{u)|4!<(h_zY-I+&ydOIF7$4KCmThS|$+r*H!Z{ZvOlcGqu!;0YqO@+nJabQmMPYH_hG`o_{)XOz~emd6%|eX3l|m??d4Zr_^^D#SgP%`Db&j#25%ado7?k4*5!zDyJ}VD-pzJtT?r|Xl9_t;`lnFq-N|R{#5*_3Yb?YNkyienG+5B2+8_OdYjye=BF80U!is)BzMkN|d>s^;*Q}~MTk$z*601v;OT6ew^`ARFOz%<4^8J6d^8ht;G<0SU^iiy&IXdh^O3&%lfx@9!C3Z+KS&io@6c_vEHRl@y`qm^jDB(!f<8PCf9I^Um~$#dHnl+QiYw}KdBD-MnE^z9LeYz;FP-4xay^F$jR7zFp1wqV@2$R;BsT3db$V0*^_T3Datz`6Wd^zej`cfC#0}H}Exz@)hd9W=%t5c;eYyqFq6rro_$VIgwE00$Mo`%7~`t27c;W}X2k2lL?c=4ttK6AVOG}Ke3@$LSoo(P6|5AHk_M17r8{>H&4DR8qxUcZjQOF>CTx?*pn!B6-2nY-ViPV}Q`pF@Yx&len)JVRao3Vm0=LO|UpE+&dM4@~uP-eu<~?tZJ}+5DuSPD4Wc`ua@SXt)ncF+21fx#)*q3{38Hjp>t>=)h2;Y`-d($B4ytsdT2Xd5RUeywJK{_x8S|m%

    1oQJ4BTjFjAQCq4zTKl0)&>>9wDj5Lqq)yEIWJd}S9ZvteD89rpxfo^#6sX`33^aG*Yd?HP%>M8O+H^QutjV;(y@*YH2yl*0TlY-ycN|5n0|b;_)UK{v`A@pSg&96>-L9Kc%fSIEU_%%-|<-HPgrSf@&x&0udzgO-witS_U$w27sohA^lOpe=W%KI@``v3jPF@jM}5>7L2&qZ_V@#D^jk>&u`o&}C=%#0{Tm?@&&!b5sBl)ayU%i+uI;?nImJ&Q!QF$M}3L;P}Zu&41&ZZ5{GSWadrgr_&km>PY9hF?r;x=hvOr{QgCUI@#B~U-n>puYBcH`_hO3yT_Ob68n%(oZs%ZO+D@pOY**lFQW8o*8bhf4NwUO*$G(r!5{M%Aqpyj)m4xP0v3&zgjI7xr1bULj2d`TnzF!Ibf0j2T&jSNuwR%gN%Ms6YY{a)bl#sjyNNo_k(e?Dv@6Dei~Z@zr>UpX1aN!Ywp`vroy{a5|(A~>ELmkMF#)hO8T^2BQcHs;wjaCMGVpG|-*ot|GeKf&>MPZ=q^Dv$ykvAm8)cE~e!hh^^%zofy`v|D)&w{SeO+l2Ps+mHbhD>61{O+}uOfbYh^YcgSiXxXu66cu?)CSwcpO}1?oTfvejBfGJ&<*(eU#})T6um`65%8&=Nnq?9@2wks+bW^2b;ZyLVKM%}?Pgw{XcJ0*+GUui-G%g>2HcKk1AieR5o_QFjrQ|F)bj3ARU%%jvJi^|;=vjt6FPQ-Sxo*yJOC`rVHQU(`jVlN`IX6Zz+XI@j-bFCC8Tc^^_-fjZ4%-q{t884w?-kWj=x-Dk&ESN|g{&|n<6^dkiIdiM>ibbB@g{F*8GJrILLQA6jUzxls&OV?g|P2EqtXT4lWi69|&%JS_3aCzE}_EN38JjqPkaIbk3bK3fXETzdn#kqA$sAJc%Sqa0q1@m=d_%rupY8PFl(Yg=#M>Hle1@+SiZQ{My*@F8Cj{n?qcOfb@F?GpTrJm7Wxw(*`H40tEL90LD@n?XUy7*~VKIAK+4{`oD9R{Yp58HMPImfBs!so473^*>4^n0T|at`5_D><752NuuFkFLRd*HF$7d#~^TD8DHpBpi!;mAd$VjFDCl+*A2Adx8d~@AIeb#H^FikXAjoJ~tT0GtGNo>hmuNAVMT=g7JHA^iTNg?v?^XS)8LB@>RQ3Ww)DQ8mtb@{8s9Pd{r!Ys*!dn1CHEtjx4{5dZBz!lW(t!E{WBpr?sn8-itlCWqA^4EAttP}3@llwggWVm^@jxs@&?bmMNk(npBzcC7^f>fe#;35<$(F$dXcII=yr$bKc$y9BYn%OVCZj&3>hZ%#vK%lz;=X921?q>JX`LID1AzCq%Kzw$eC0iOyz9e2#^H;=k*-Ih`t{*MlY37FctHS07&P!!!aHh4hOVk+oYWt7g-|f3I;P9qTXPq69qlkXW=DnG)nfLg-oQv}&CRb9SKgNXZKTRIbqOA9YS#3-l-^~V^=gsHzFr2pxop)b(AazQK&=IU#gNaky6YN*Cih>G#!}&l~22!_4Ftqc3~#yvRRqW61iP`FWVXI+f6z>fo6``i&bM#W+sZNiR$Wvz{FK7C^p=6L0Nq;c*_Zo>JNN-+8&ffV98-jj2+_KXyCwRVjCTunSDUsEUJW&3;XxG+S2BdAD6Qg+!x#d{X8+u-w2kE;TDT3qQ_ui1-B|8{iYYC->_~QH%+cLBkM}rG7AwiVH56#abNaHO8lN_so-l*v2s-8^?L#?a3D__-L@qepdB^r#Mbx-^b9FbU4lX0#OPFN2iK=j2uP07y~PUGF-;m)Mb;XDhRXS*{($!8sdfKj=o-G$;q?mBc+QT%b#-~O=U|IL9t2NHm|eYfsFZm~9gr4mt+O#1Y;AHeaDbuXbbAm&3)ANfk|>1)&G_H;16ZagMF5qajtSb)ohb~+IAT}jC!<=imWiHKl;efi8wMil=C_x+jQ%g33p2RO`tIMfM0Ll<9rvM!~s6#3I4Z~J$FzCidjdaNsE27Yhe3-+j=ax|hxC9xGag?BdA=yoMlKq5oZcz4HVqy{tUB)#fck2ODNo<0^WOW+q9ZRBpib=noRX0Vk(?)WoHo=qxNMJ9Fkr&hS>LPwjH50P89Z-NDGT0iHeRbDj(kPzS65nSN8Ue465N018)I-O_7dYjHZce*Nkg>cqYy;V?Q#ssD6yq3FrR<2vh3GoWsr-nCN7=ltBIee~iI7DS&vvr(I}k5b?3z*~7;HoRYTrqGkZZ)E+Xy3^l&J)8a$r~dklGoFONp5~&vvs*A;llTAU|9^ftAz#S_)XZPin*_!aRx>Av;PJGClSTp_G`RPzCTI3-b?I`{!Yr`_=eW`2qrw-zB+TW1nM!*Zd{~`u*o?4{u6T4<=qua_m#6DXk&tWOB3p3ee*|exH#Op<8=)374ev5bw&KGi}pgkBJPKLlLW}TD^s8ngzJOy&rdV9C8faZu+(FFu2a_gcn=_l(KJX4JH9ho40Yb?X@tNPI$SIjEZKDyd4TY<>we7usj-lthy|$M6q8b|xXJ>dl(JZjDxA-p_H#YLX>2I8=7xmx9HwTq=@)@X1s3N4|QlU_O0fHVveBFVuI8kgtgR+rv8h?@j7^c+o*v$`*^L-r;d-?`7{q~&scf3}yUmo5JFGRDo_qFY|-Cu9QQ-|&@#JeE95Jn-HMUzjsL^5AEo;D5&x&)L?=p|GKSoqgU@%wMUl(6esfJ)dcpqudJ@AvX?lwrq2|6%YK01xF9{VO~xkD^b%VA_+{CAG`{khupZ(i+NRgJOw`Va6bJ$i{npBlnT#XmF6`X+?pM&b2`2hdBP(T>nkWyW^p6sq*CQfa4_kE$*M03`F0v?h`o92FDo&O$|JL?z#D7JP5}_yDxBPrc^rg7f!nJ!U6MgM4WP-PlxFqm!thCeeteFbA^}>Ghub$5J#?&(g)4gZ>G*xCTu)*d6(gCD{#U94fyiUY?a@y3Haf)prn$;aLLMXg!XEhl|Lyo6y;*zGVkOs!f-LyqbEP#BuFbo*=REw707Tl|^%3e5c@O5Bt|@T4TVU3h2IkE|%eQj;ccy`1$}+#HvB+al0ynvmMZEcn7hT%%5OvMo4Gu;nnIM}KlewE8If{sbmmHZ;628k%Sd!vDANsU9;u#Aj4jEn8rG)ymkp|moT?e6T?+uId6uxqE+ivtcG8k5@D3dM_;Ql*);7dsPWbLzLKZyE4%*0zQQsrrqU>wS2Ev!FJrH%``%Xo>!@(Gl!efVuQzIy9Bh_}2RLGOZh05hYaLR&yLk9$GQf_NR&+;-FNB-HjIuX0_!-SsPMUx^(U;MsAOjw#+Wpv@Pw^{b*tz(9=lvd^aRr=QP?uR&I2iEM|Y}P`_?eD3Pc~jDMH9sL4Hi_JXPLxycs%WQ04N!phnBTklEd#!MuiPQcMqbKZE68YWXF;?6Jdc(UoS&$-speS~Y}j&sS7E6=>X(XY)&}s-i`bVo)<^N#pnDB{`Nn~6;mY6qp{Nsn$i7}aWFOBZL&#SS!mbXD!XepFOi;ud?iu1ggVR37b-6Y|I>}$7Mi!&S&v2POubeG?W3iXIDl`YVyIR5WFTFL4rK%UJN-T_4bol(TK!7jx+pI9?MoRI(NMYE|v>nG6#eK<6d%rN@x3x(-N|tn<^qy;Q^u#ip!ECASQckeZ>m&O||V^|NVkjAnBKK+!*s$J8d=dUc^Siuz~#Sn4id3$9rBTv@qg8{$=X@lq8)0wdunp+^$3z>XM%^G=%d{_~E2Srof$BUY~-baGcxEcMWkL(!fOY)W-THl>Vo)e(QEMrjx#QcP1mZtS!r1xgwZO`kBi=Ku&m}78BehzyP8yZ0B)GzV3pd)jq?6&`_1S=XVC)KfjAi7&8`}2I6^niQ+FhP}c3U=2#?LTrs6WqL0Fd>TAYZrp1E_KVL0#4UTh?P?7i79Z6(f;=&FbC(#E&Nh}r276|P>wGqcd(;^2d5xkB_G;9W2#RE42?T7Zx$VB|B%t{1NINiM?^oN;aSXVvSpcaefROieg=k2Y~HyBdMjvIG!ntXU}VTBjJPjLjxmw{N95#?#BYd<3TK$n{r7X`6^L*czG}Hx)Np9@{^FSw)OL?PI#CK#J;Y_TuQ$!bG^k%8tHIxL~HS;rN~z&YfR(#b?IRL+2crBD(b}kF^35ZSh)WD-D9JuJ2lGne?7${{h6)wk(a*j;zg3_`^bKd8{8@Dk^w(+!qQJe=(ANvoPJXJzx2B2jV_1+ts!L#jx%yp!;`ojBSs0p9NaLxuNrlQV|D9}KTQUQX_tE=EDy3=zvt;m3!uciEKchsM}f5I2GCKKMQPOGv{L!GD>THDWn=VtS>=*);#lJH5(SN_H6hXNvQ|hwN>TPw-$St7yE9_%zx{5UE1A)mtUG^1%a&BLF2XZ+<(VgEwNZIV_OW_M^$(fxrM0Hu=Y!Yvx?Parj7sYUp*+83W<9wtD7i&Rotztd^h%|0pWM@Cld8rS`S&H+vrf5#*&=kj{4&j&4bOl3?Tb)S)v~IYej0}AQLp3CJrn$K)txTKoyp=VNk#^Y_n!Svzj+_4P4;n(zsEck@%}qWBoVfY+kcI?i=1#`QRHXi*{Sf}@ihDLQ{;ggdqcj3ZBK`cEtOqXVyF)XUQ>|oqr;tX?FfzI$OA+l5S^(^Xd9GbhkV9)YpA?+Ik1TZVpf|T8AhT`^mP*8vdQ~@*-F&QLpLAQ01l`we-Uw`3+F9n)K_+4N*E{uSNQTDth4eR4(M<*jtAkpAI1k3VE&5TWv^@9kPK%BirM+m$XC5G@152jN`om`d)qoUW1fn48yK85p~KJf;lIo&b?I#NIT!c}7~uKS*x8?wkIFsebvlg20{ifLqHUKcKC$iV>{n*8;m}BvTD~~y0yS~Uuk<*e*z@Yp-3*+!X_i}WSv=){b6to|_qUEymn3V}||C;Soo?#Ja_Or8Lr?;oB)(r@JAuXsxwC1~_}%TP?HzIcJT;;@P@PIy5MSC{Ikrb;)g3`+5q;9f07G0!qIX@^d@={`x9xMs6h6J->zl(I2}tC*t4t5P7!rwkYuaU=|NqFllb4i9dd_D6XSEBEw?YrEj^DVsJ1y{CbmMx_odrkYr#{+3#%vW=NqR)T(KlCdoO9`-wch)_0wBR_S55N1NppZiLANPvIaRv|#m)JB2vRQ1fdINGMxjuL&{qOugLVnBaqUYMM=R`ox`(4abV#3JOe7Qa`{~UQ18n6!g!EWyf?O-;`ep***4QJ%E=($_Oj`b2kOP{d&3qkqrv^j=iTMbp}zIEZCBlebWmAmxIeE0^&`9=kVg}pTnDkAiR-G*)`U9fu^BLN2FK8PJ#rxF!=l0>*O$!>;qg)N<&0l99LatkbFz@fw$J@0Jp-3X9^`t;qg3P~!mnq0c_>JR$rZkSjrlI3{_;|5ECe+;G@Uo2tUu1#UDZlYg3fgcjaK!@Z$y8`3{e^ozKmNWQ77^RTRx{lo3_y;!35;b>oq?+U{5AYUpvL1SB9eRdKheM@z+oF8YSPj?Ok=@U4Ay4R<^np6@Yq6-m@>OE7@@5O}WAoN?#|B4Xg=k9sPi4NA`RwWgT$yS)JK-XJD?xweo}A7_W)`dSOWkq@P37KhEjWzRdUP$P7jbEQ(>>TcX7McRc&Z+7H_Y)8LD$ZM=6fa^0JqeYQK!(_!hluR#YSQ0ISJa?0of1DXU@#l57|*Li0Mw4Z8Z{p~+!gSwDB*JcgxIMtC8HD2>k|D@jTk!8&R*OiSr+wR~zlYS#-LrGtPD<_eo$mgwN9O-{`uoF4+S?<-!RE=cPCv!nG&X4u)&Euy=X{2w%q!Y+F#6Hki0Xoc^^kH3WCe9n-3+j1>0do@U=A3?y^CPfh+vT4O7BsZ2&kCdTW1?S}8RvhQ4gB}U1)sj42tZd`XG*b4}>J>*W3m=LB!cPUx;d&pr{0&KD|GuS{FdyZ$n$B0PLxWxE_A}ZAk(b^ccx`TyoB>4MMd}LjPg&wZ$=f>^pgUBRf`0xyerVcoT`-0PyYy?HJkO)l-Gy2Fx?04B1N>&|S}E(f`aUz)fAHhLC4td2i(ROTe!iTYvxo~3RZCq%n{a;a+gLufDd2)-K$qfaYt(P;HB4Q6I|U|+Oq0pX#C0NKU%bGCG`Qn@J9=>Bzw2=LBr@PnL$OnLBgP9|#h8^}re}h}wWr1>t?;?(SSe92+`#~%&)Z@SzArCZF&r2i!h*SDUpF_hDg9sOMdwcPXTw}4pRLMH_`74@&V7(1&w&-XBPnc3pOO76jStIja)9s^>sp2PGvTkg+kgwzr3G%6>rnT9QXi^)DGAC~w?>~_gXfiEuirDIlS=M$H#>p(u9y3M9x=L-M%J4tAEfwD9e1+G{FDJtw60y({D$Xc*Dco+H=YTt5_wteYjFKyYt^ZRWxVIA_^g^YrxbDgMncz^chuSN!CU5oLOZ1&Ymf67XMhcPJ0BQtx%fZ6K=B+HTa~j)*%a^F$$YU|lNNJfc24DOY0CcYU7vT4wD8{3c|UtAo27VORR?-*hg&BD@3zZb9gKMx5xtM11Sy-F?vYWP!vvy_R_Q6M6ZQ%I^(?)U1()QmiP%&2Rc(1GBvVt$hQ8u9i&6d$PgFc0%z1}{cT~q{|Vop#mCN)c`Dahyk5U%O0HdhMQuxkBX?Vl$x4-->0ARH`^O!}*2i{ki~pZOTlv6luOQaf#16}kV8*Zs^lS6DLx6wjX@FP=v6_ug@!*ZyiINC+R%(5LhTD_ZA}R{fX>p$@59*DZ0JzYoNSWSO#I{A1vUlTT3}&@EaRy^sSNZdSTFY2ovb*f%HI$h+=VO`1O_b+dLJ>ppKg6%4oDkMx$+;(gWGdp1eOBnH~{t$lb^2gh%c{X?VpR3eBKER3-@ihkgExgXBBY4U#W9_PFREimul_2qjd!!aF*^(*5U_`PngvVNbO$NOEcO*(pyfqFrGSUt;*38iKC4$Y?QpNbDY7r$7M4YBb-8$?}Dzix6MZ|pZ4Xf=0xtqM^W(;8ClD&~Nh=gyBoL#Q)9ox8WK?j+eaB){iB<8RiU+aco1PK<=ZmJ0mAi!h&~$OC0Jxdb?3VY*jrI>u$vXHP2y?2g1Ro|mD%R!7_P;ng%4c&ailKn>TMx;|G=?oOq{ZN57Z^-1`?|LwACQOqPJ5P96DHq?oF?hYX~biQ45^TiB|gOVa8&v*B-;nln&yGPVf=h948h~#iU%Ivk~Tnp3*-?sr@Pax`#Z2sjLc;|cjkGUr;3=W-UcQAF4Loy>o(`L+$hqx}i`tWv2znH-d!SQ0sFV5f-`Y2d`I_{5~(Dl4fKPv=s85s?4BT!fBxV~EDb}Wntrj0GVgE~E7(_k=PG8~Ze3r&20dV%>s2D^y{0}cXJ$7+yg8e4k4nSafI!4J1IJ{O=~wm5U{f$8gw0^tidQ1zen!Dj8^!+A<7?ZGg8jVhC`9@h;CAA=<;Vj-^D_V<*mEBL+Ehb{LuB$503diUe;MBmBki!^xc^JrzyEIj_#x31##FEgNadcebw<|Z$Ao_N7(Zf#63+XlOsZ&3Z4ma}a!}`x+{=v|HkY6%^4&R!7J#jdI@tSzP*atDl=aTOLzAw9+Nok4HV?lOo>?K)cYj2Fwto?E*=;y|D7K){?ZEGWRhww|Vd5TMP>orr~*s)6J&@DP}-ni-z_wihrp#--R9ic9}3@ZD_3%jOS&zsg$Pb$OPS)@4CgR@VufL_jP5=VMF1d^wdp-$c_11*yFTrHo0%q;1G_#IrFQ+Q5pvbU;n$5zLWcB{XDu-oeOP?oYjNpQu>+Bx#QAtj|;c<+uh!ggYUVfTIr|7+7f}__ufj(w-D<|%U-8|P-$`4yIIH~E-wX(<1VGa(cvLxHKqP}q4dfJPHX7!-uafym>;dXC#tsP%Z;uDn9nS-TcOy5lYj(-myhwuUzeeh&9EqH>1(_hY<3KGyxRLqk&PjAYY~!xiMi`(dFfL63DvBy+g>2U$@=0dgq@4O%sAOxQ%#UC5W6_2ZU-z3vvv-ji$S1J4SiRafPUYxCWDQAK|a!cR=P4E7xY&dFoA}>@7$7v+c@p=0Y8?47xJY18A`qkWP%Rch1_fFwR1E+D+^`;!`cD3We#B!xW=BCIq&s0CHTT&VZ*>|4nETeGy+SA)z3-`ytxX%3(`d@MUxqght^214B;T33mQwqnK91&(InnnYnfAtF?HgtTLXF^=cZvO(XZG!_)?{d!&JF6s=$S8G~tu_5}Llyjsk@>1+u>#x2E9M~_~I-h<7bwLA`dBPShc<_KvjIvHagrl>Jz`uRyqL8l`qsf_tiP7*us%>A>JskhKc8}_~$VBj~Sfb&36}c<6Dc0;^Y%2K7p7ndc2KlO~NuBHWIUU@7NPRujjk=N5;@}B&nc!=aGSzw$a+I^XmDSeeELgm)*FrD~^*q<21*>Un$dF4-UVI1jiC-NbcX)7M)m#6o-v%hhcT8=3y@CryAJopDor!$)Xovkwi#lH*^4Z`2ab~mj>^T?d4Ze{;>?09tLk>Kf*7k0ea{`z%;kmLW^3}ax`nf&jDR4>9&P}}y^+g_WInrk7zl#iGkV}o3?t*MV2>O}s0Xb%U-yqXW{WPWBI7l^(nmHwzRTg;cV40yu$<~2qok+?qi?GoRsJfmu^mYT(RcCyySiL9(h9ajtX|hG0QLH`S@##$(5cw4m8`Oz^+y0^h4-FgZgSz#Dg*~aF0mh@r2)d*yCh)^=o)P;|;De3i2-G<*YPl@jkBN#6m6#vfja*-AD&H+MoEPd+>PuSZ~3lE=&+hneN&@3y&x2YtwhIA$;A_nt_MNOT@YzTZ02p?+#BGOGKThqun-v3w)9@W%aC3-@fMMhwR}rD0bDctoFn@9HrYAL{v5CVA?02X}uZOYwl0&8*<;v0AfE}H)TKm`imJd^UYWw{X(T{doadpvOjbz8!9hs4U@fr@tX7x-^U^QvN;wZhuBFDAJCWJLaW;EEn$>?bAek#m(}0qf|*CpTv1B?YWK^6{=956O_z*Z@v0`hsj;c%hfbIx;{}b6B<5u4cL%_taYC5W}go-4e76sCRSxlElFCDmwlmtalOPuYdbYTyG%@Z6NXTxmG>U_;lFV(xCy;xq9v!&%p(P2vn@s;?b{%{&tS5G_pY#z?@?^fQ81i_ZGh@gER;OgAy*PldaShewJWk+1g2UcMKcoeq*jBF_N%WapzpLep+!!nXIT&b;`E^SNPBS|iQu5*C!h0-uXUg|FD(q-{}*GAgsqeGdff7866v_>-vqGM)k9e;s3vCe)$JdE^vf7XWgxfSn$o$)3P7OfqypFbTrYW(C)$9cKQaEH5SXVvh3_dDj}qygbebd!!8b=}SI#Mz&8IJqvUZ^b<17MJmlfmZjKP&zs0Yw#!4H$4}_k%pS>iNa6Gyz?4Nf(ihH3)_!0q^J46Lb#shqK03)zs6Vxg_J5+ceByUEY(>;<1-b=HGU2L(VCvoBwra2NUGBj0HP-qfXT8$T_eB@l_-x91E=%{PxUDNmFy$6PdRGw+cM%}Jw+~@6-EFkJHBG02v{^|6C`^{HF%JY%0=G>bbydg6Rb_MJjpsOH99n(H1W0ao=5qGsxrMyrdv<|tcsz?Lr;EOF4XOMFoPTrYq)0qLpevYG&s1yCRUVLJ}(MPObGAAj%o$rnu-oKFzck?Z(k5Ky2e6N0Z+Q*1@eb3Z~uQfz{L|##Hh8h=muepyWtwx>j5#BMzg+qQ{!hg&`{mBOXH|rnzlKrfYsURc)U+aH4!#_*6@*BhsPgWu(++~ekxSkId|=ug!;ID@~lJg88FOpV*@2mm7Qz7-Qg+&ieK`-^7lu+Ivv3U`6X;v)$r`#I(0n$M#>V+&zc;NI3?gbV-$Hw{ZGE;YdJ1#Y}{XRsvPytp3hHx`oIOE4^?6?>csw5p_}QXKfl;ntg9jVO8=RX35kNG#b57ZT}s2u+VZWdn9!yZA2Jewd{sHY@uq_)o9qWV;TLj<&8ZDvQpVY!CwM*Db~VOp!vD0pi326qm9>UtFfQzAkS;Q+$s(ycfYb+TT7q%aI!|j46)2Kb!%-#%0yYw&8j0yAp7C*XvBkE!7s+nveA%^oi+=-3wVj?ng|*^RgOjoN@3!2)^U9Xs1!f-(Sfy+koj~zj>{{I-)1=D<9!{-f$>I2Ce10o1`8yY`P45UAc}eLn)@!CBk(vcxYC5Ao1z~(7`VZR4X9MpsOuO>0&urJ<^&?sekUjwmvCdqX0EBaCK)xRvA%|QH$oVXLf=>2_O_WCNCHBo~PGADb#j(g&Nv7+oZ}521>~5c&RW4o^a(}T5hpgY*U5fMnWq!q$BY!w>GrX&;!|#9cSNFJJ)mPkBu$cQ#57@oR?6_MN6nJmku)G9yr&Rv)Z9>^FBO)j0A*Jq=?6aeg^tTT1DxMcHZr7WsfBR#;L%t&W!HlH?=^v1be8q7-lM>XC3BeX>UPC8w{-5~vExl^PBI_dFdLm!-Ic$^(yw8R=l`aQ^|E*6AY11U99W$=rz?N4p>)R=HuteSX%~&p^FanH)!f^b{g4cSjTcX3vk46EVIMbv_T@W|2NEEfjyk05#8-TTzy#ZkdzBAs<2WZCG`(`mlMRK7pZKT^qh4a5>kxK=178(YG`CXy6=OOS1y((yHcyZ@FtIPgiE9&9yjn}F!@c7C!FKpHf@aT4i}(D(6weO-3oI0+x^S-jsnIsTQ%QDk3|_;ixf_B=tII4tc=CTt-<&KP;-ib8ywK>>^OlM$fy`CX@XO^BZZ+Fno3ZJ=<}2X)a$FZsAIcUyx0LV4sRudfbCAD?kyhmvyYJY&>-KOVaJF)oYrWvz6l_&V|)FD9MA#_^DKkF~L+U%~5b$Wg@kCU_zm^|aDHidr{b5_0!e#C~*Cl+^FZ&8k4G-kN<1qUuN8?_A|Qu^8X=`Hdv=fXZM`AY3)l;dRVJcLMfy$z#E|{M+#Qjli06DaE$MGPUN-8FjI-iZMbhA|@b+`lE0Jf2bqb4HbeR3J@QT3=)T3lI(%&~RVZLd>J(J6*o1V<2HD6|v{kttwQC}t1=~Zxp12ubRt#zjOB$&Rxac`8vd;bj(FS%)ldIP(?OYUG6Ty}5JpRbR)G11s5+W)UVg9UOC`M#_c{r5VaK>e!e<@s;Kl7Qi~M|R->@X)fmK;N~`hLD@e|HoUR?p?3}!iKZis5$Z5-?PUL$p@t)h43N39P_9I8N6~0rMvpWk;e~X>Jz7TbCU4MBd>3eg30QrjO+qCZ_lk6wRKY$#_?T++YMi{fiNlCkHQ<1a33+3{s;s|s?+=)T;gCdFCM(4Omi_#fYigrrH1jH>;re_FHgEZL%#YF+2XZrXF6nDb<&LfgXcATKz+@45byrqnCvuGg4gBTq`gK1<}A>c{yc#bNU2k;9iZj+vH$L0_Qvu5$oG1bI?jPl-HAOLb#a_TzC!#x7a|VJSQibW-gIof^KelXlohz$unMQ_YPo0DuqM7%CeQ#n86j?PK`0j=}xelS3^tWG|JaR9=NeyN+GC$lqANeXaU#n2{M+N|gxv}3G$4~Z=UCxA5-ec>~A@0B9Z5MTFihHxkeM1u|eM}Y~jLuGBbAa%9Y8^tI@S#rUJ#Xvh8dTH;<2b`6uM3@hDhon~oO*02e08I-z+~zAY$$6oi#$!?tA}Em`6pgwga3>b`thZx|FwaNCwZxJ5#IlVe@^h86w;qmlkRES8GFon+UM6FeDsIh-FCSOFy}JT=>1vd^ioSjpko%;=Q78K3Mu}v@o3FOJ#F|kbA2d&GuE++Wzv$33zK=TD|5cR*%d2y)=!crLWN1&c4_Lh??zG{rvDWqtkql*FV!|!i4)n7GrFjKBgI#oeE%5;CEphwTt>bkxtSdg#OtDy8gdlrKiHK5EsI`^ZKU+$JM!xb>&eCp(*L$L9eIZQ{dX{6kcV+h79Q``VIL6g#)iulKXaca-6OyR4Br{k9NET~rS`h03P>WS9Q^Mb6h$=}7ajg;}MazAl+EErZL9?z=cM_#)4Mf8DNP8^J;2=#4JL7jY_E2jYIr??C`iuA9@ODFdkM2yp#6ytaQ%#Ne9XCn{;o3zh`x&tb1)8`JUVTHgiS6?SMU1#VFNygw_ULxuCUGosfgP@=Zqp>y`5IGkj2LW#h8`+3X}1?i2TpAGB)gc!@P2(4$q6|^K!VE13`jx%}?twUN6!}FUx7*Lgk-0QN8`hA;l`)v<%++sbuARwzn3JfA84A)s9EAfpsbG`KKc|ew)FhteKKIK=d0oS&DIxTQWTh3Ui?Bn7UEZJv^_W?68I?&0NsFf6Z297Z>L4|WxOskWj5FDx8Xv*-}2d)WGMaP*grg_%(CG4oo()|6LFjobKJ(xD`dmM_|Q{cck#TACFtzE^(Gs(nj9K*cERxr$$k$o0r%2;LjyjH$=p$%*DI3mv=_)wap-wa3{915t4m`borKm_3Ib_UGX36NM9I#25nnEi;{ZguT@*1}k2!cbc_iB)@h;^5fA?e^1tfq1J5c1XasG6fLG7KorJyARB0;Nt#@rcJUSvJYrNAtP=^fK9duDK^TP_)Q}YeV5cy~1m!;#pjnWp;KyLyfZkJ?w$&hKwv2GblFFzlZu#6Q%DfJhDNd=<*K{ZR8W;eP%!*2Nc);V(Vq0en95oD($))aCQqTu>6iXJ(kaHXKzA%lgIDS)|f{Xhz>F})c+{N!7kgwimKHvO9f(0{J-itKqaGXZ2QF-+F20HjgE`T-fHTlb_E=@wIj|2zeX{qQ5~0rSIEEmyu*^ZVt5VpL$YcC+aWe9#nI(j|XFQ_ow3L&pOID{h7uFAExgE!3fleK4?=1dGE^-jW%{YsNboYJiljJ7I;4}^7yDg+0V7#_W!v0^0=Dz?|mg9B!mW~iBc3rrf5ZlG*KyO(43T^QX(=%B{XOr&*_YvMukj`MAD=vB1IxoRFYDDd!PHeckR#jpWEv`uVbHQowLtg&-?ve>sh-z$FqPVGoGx!7jfPP#;--S3=ntxs^T7j`1ysYW_8Dye7$s*I`{4S@~`cOB7yv#MK7Yha@`}GdVM4osz-zuYaBowwd199a8p+zESh2sl9NzJZ9e=kC3rLyxU?DNC-*1F`})|CABaEEpS3gpVHSUGvY{Z>7d=Y66JL_X0Ids*d6m-<7kJ~-QEtJ6?Gtsgqh}+2>HCnJl4v+wYFd}A@CxrG7|;w3_z8E+S+f_mg2UAPf((r>D=fXHhXE7fD3Q*;!O08@9;U}V|`XZ?D_cl>Vce;Y}M44Fgrg_QlS>k>M~?_#qc`o<4sO%CE@eM2tsyY9S~RoxwpxRj68>{;qeX#d42b2yIp^!NIAL|V^-`jMzsHF?xgT9J43?q7?Bl-#@B7pxG!)_O-*Rwx0kcN{F{?L<7y1%}r7rN9r-?~J+XsJryF%<{q)WI$3|u-%+d)J5d{#gW-Gcy-fOIiMWz&DkmrGP~$78aw=|<{aYPFW&FbaLt0-!|mx|+Yu*uF4)R|MpZ3lojBqUvCgk`DibO-eh$ogi~35^f78cCiOhfMQnq3}(!qi1ZEJODAd?S+#X4AzMAmZ{n9{-Jo9!lt@2EpW_gQw{H^>6AKJJD+=Cv`p(3q7X1N=8z1b9VYzIGU#%h3D6fY9qJ0-XIQ^UJK-O$w5kV1L2O$X6Bf-Hy`C(4{L`u*%?6^BrrrVw=_zaKUv6Wr&~+On%KE;mcbYMEjhxW@ho)4hOkHH1bx2-VQxh*jo1tznFd^tF^F)-U|O(x^i|@VZ@;iS=61iAQ_VfB)}3kDLvYfByKO9^>Nsz7fyyLhWkP&NG@S+`en!@6^5(DCcL6yT&pWqn`rFHfb8d$OZ{swuIpoJYOkjf&lv^pqY;-;hn%T4rVr`SVQHJ8&aDBA%P;f7OHo2cNv_Fc`cd|IXzp9*F4AW}efWmr4^H^`E2))Dcb~%q&DwOKlazBnJ89MGibqT!&q=KRnM>?6`Gm!}~A4byW?^9pH@E<8PkrG}sXq4_+tkbM^5X%3=(}P0I75pFCm#v3yjGrS!F#+(~p#K9K(6{9Z<{6r%dU;Oa4^zXF!kzI&IE3`vg#jkaow9(^zo2_^-hEU5G!kJFr~o<5m7V^q-A*UvWzZF76CZ0@|-?vE`Kg%+)L1*bT91pyQsYS#O5=zVxZ$k~I4lXI+!5C8M;frq%MihlVH#~3)XYwx2?caZ<)cj0oE6B9sbT4MR@kEpLs)>NNeHaC?&zp3>h>Z_3L6UM{aGJud#^TNFG`YKPyQl(DP!2Iv-0hbSmSE)zH4nLuTwttbX`DWBVKW8dPo_U`IE_zPpd0~jht`jh^Y+^wF=L>C~rHH>!KIQx;kqJkv11h$DM4a^V)zc^L=UJmddqq&UsOO%)KSLo3)P{Y+ntD)Q{joaLcm72j+_jNVm|27RirnwBxseQc$sfXmoKasDM}KDdSEhpkOMmtlrC+a;rqWm@N`rZj_&ErHAUQMv_@iP3!ZR@70mAv8x>gHoJ@#_iP}16IpSpfoVN@e7FTPI8BtzO&WCCv)(d1k-Ozl*cb5wtSY$=~uG2(aLnk60ce3)u7@?zf4PJ1U{fat@To-VN`_g_SfpMl4asTUcN4GDEfE^WGlbl>oFMTO>Il90i79N)iEVD{Sz4X|!f^#l85gfKGxE7R&uP4vl948R#g&E<;|AgS{4}{wt+GtMvu759Ex7!R~Px=WM5YG$A+^p;u^APuuHq`5!nFSjX#TT}|LcR1ruE6({6a(^`d^2?!h?Bmc#iI;3BA}u5>Hy+zUO%3_><;lel-)t|+JJa;a=?mEF&Z=vhgzS}M}6gBWUpzcMF$P~*Tn1%sIP9Eoi$pllLgbsh4C=v>&iLD#*&sXAZl>m+&VAxQ9L|htTaRTpL2~V$&@*3ryNRZA2MOh;JleLFJitc&LaXMo-;l@Q7xPFQHPun?Ca)DW`l9K(y=5r%!3M2uk~Cnvw@uR>@*AW;4bI%xEw(a^i7O<*+Q99Pjh>%E2@?W8{yacCv4PLANR-Cn)=aTYq)*;dWyc%+je@A1f33+QY(t`BT$Es^&)lo#Jcs}{swOW)FDS~y5gL_CgK?>B^$uK}nh7U#24BCf#JJQVtan@dqybah|M*&pzS<}7a#y=j7OYvJq&zT;aqV50cH3w<13of-UDCLKas8%maA=btbX4Fnc@1ymPxc$!=^}9dFPY91Uz$P9i1*`BEdE?wzgEP3w0Ak1E@6Y`y7)R|XzQ28Rx2f=b^z&wxqDGqbBsDzcx@lbiBdV#SbWOr6z$|GF#?vp0Ve^9k{{);V3iI~d?L-n3ehGT)Y1u4RsHWI|%)S@#SLtC1>K&Pb1b=t%kPQLue!;C%{G@7*@>Y(k$uy#>Zl1DLVJ(Tpm`u}+ke#dz@2#h+};bfQD2esCT1I_K=_ou3I$5IPc^x*ZXvM)lqiv=!E-)!%dK>Z`vm{go}FB&QiORmnnjrxkTU-ouN;D7ILD0S?7{l6p?W<}&?1{tBg>O8keD0NmQkh*EY4ZQvv3BgnCH)-H<{dY**U&NpO^d@yN2q$;8U~Q_et%Ksu#o!In$YFsdGT5|#L2mp^}|f4uS^e^;E#A=xwZd#4h!l#`{s`ZBmVX0w=1h7t^ntNDLKTSTU$?xDWLOxDa#fjPTnWMUBr4hCN?~4E=6CN<(8^;GT_t45-F}Q;$xm`+#GH)VXAk1#k)aDz1BOHaK8@=%xcya&U}YBSx0f69tqE{nDkGRK%K)s#|pU$)tyc+%Un<|k#jvoZY4pYc}17KAHIG`!`%h*W~akF$yJWm9r5+td9xnawPeC*;kJ_t*5d11R7WO0J#sGyi>hEqiq7LDoZ|!6Pxxd1o>?fRjJ7FYOkp(JS1nA}zKc&*lP@$HWEC|ZCO;VXc>FcKpjh#5ohUcqnMN`WV&xrAJ-ZF&)os?3LA=u><)Z`@2xt&W#Ckvr{h4mq(t;b8d=M>af6J`=iMZ8W7+8ro8*c5OM#L{nO6KpPWB(Ac4*I-CF#X;uGc8zE4Y$17sc9epAZ+kN&+*t?pzX_hrQ&;Qe-L+BLV|ZRtSv(cb!k`s(Z5OLd~kG&pAEaov-m&u{Oa`nxTQ4sEIxZ&fxT&*9hpwFd}YksSAR^St@Uhn!PB_YVWa8}-}PJVrbvXU9x|9wt0CpKH-;hdfFB*_F$JX${*S#8Y$&IbU+bhRyfQuHA_Ggwz}IU)gZ9$vUe3D&j+nq-P52B*MT3#aZjRQD2e$%!kWT`F+hhDE*j4eG#1@R+;cN`e;zU59$-LKlk1r8oY~iGTlq@TZk$v=IAs6CPm!K;5BX<&y!~B~n+*D+HWkVPsIQzg#0xG7Wq^jJK-u_9)K_G_^R=Xbnax{)BViO>_w;<#%NKN591(SUk_hS_>)_2@E;0-_eAx29I!b*Mx&E=D$2c~#2p?6zSi;X&^zGyst!V_Hhe(S}Ke9%dY&II}p$RwX%JntBC(JpX;uPZV_y|J;if2c&<=a#z$#q%T%XeKH8s?q2zP0$)%1i#aVM^dzB|-yKF=$STWvB9Yh5|Mj0ZX$M~C`2M}TC(U#y>1{Z9e=)wE@4GRR0XJIDbnG8SU1YaLEavAtCPWz(X4O2R=q0X8+?k)ufBdpi5I0yNZ*!#RpLJ90Axht()X;I?w{!?Qop)l^3)ENp9;_B0`kMvh?{9W1>X1)UI^CBDGT})|)%B4W)FJyz9&MQMnF*t|2~zUYFt2T1&)!{rhsEy~OV!1Ey+(ZFo&@jh18u6YK8MTP|{suaeJ83j}~>R$$(h5kn?d~m17>%_?_`5bP*RcFGqi&9mG6nDV-X2IgShUJGMLwrJRFI`u*Zj9r0Y*-lA%nb2W*#N3=~5#No^;4|f4(!*7~>-SB)hI>!3u|g>;tl>Lj;}JHYZ*(z?bb`a3BW1mlL(A>hE4KK{#{A?Z{S)>)CNt_M{RPJZ9N-$x!qm>CaXi$OevO_%+816#j+ou3@qq=$bx$a@$JeA8y~?J|mw4-@d5Lbbf?*>8#g94$HXw_4u=`nBPfVMUT&bFAZH~{vyg$KjnXSqX4uqaqAHMYz;u^ndcEE%*m=Y5x8h0P>H^-DqappdmU?rY^?Igvgi;Q=QEFG5Z6})+#(&xDJq=ijyR2C@R`g1|Z5_yK4b1J9TGQjTA7o#~^$nzEp+{yi&-XF(Pv_B*M;X!!5`)w8&Ez+U=I)gl=4wQdrCDsc+Jl}=6QFIIGr|?0Z1FcNMkA2>V@7i+Nzo&o$tCH;^1s)+D_H3aOM=u%DoxHZEwW7Xae|T+U&Pj(K6DAlX3VL-I&uD&)&d|%QZFK`bN-brQDjOQY5;h;w2?O;LZ;_yXvi%_?W_Kbg8qQHg&=A*eAD0NK-Rd+gFZDvEx0$bPiR>Vs?#(rETzV}$p{9s!t)F+ERP0HvANC48;b`Bl+*QN_;2Odi0pF4-YNB$P|^N%~)Wd1V;;RWg|>9eL&nDTTWWWn_L(fGbr>Xzd&=~>Wy{*B4O1^B*hou}eAwlknSFlF_w^N5rFr8nL&`93OlTMEbGepJF?i-~hjvEkC9oJ%xg#A8>NKiQ(dfzcjceD54byQdH*uH%q4JIF-v$>z5uU1W8I4gEy7I?=-RC}qT&Z#uNFxSwU0h+yi%uLF;-mP)_j9y{<~wB#rpvVnFFx;K?61QD3=x>dac{o(Odxw^Y>}L>;x@W@1K)Wg6JX9oyN{iMX_(-uI6;Gx_zIALLQbO!_0WZRdVMPp<9z>$eHc`<$-D1>5i*(;w2Y01F$nfvJ=v}Cb0=TnAmWXG9Xm``!y~z%ID{%;p=;Eh2|;6F@f~Wig=HD$yuHIQq-RXyDMKxw3i~zpAWZ!4Oa8NYhFx7eDcw!m0!PQ!40q0b5|{~-aEG1Q^rS_35VA@oIYxab?$Pz_SrwQU+An&p-#C>E8(be>$kfApNA{^MC-f58KCy5LK3D%XK8f8Unhi8h+49O;me`UaZy^4<^uV-x{7q$GGNcRkr(ivcT!$>y3BhFkkzcoPM%+8ykA3N8Sy#KpoPXCQ=eOg9DzrJM~Rz7#F$Du_@vFQ_mcP{A*2Gp1PWHq3TDl@KSB$zcgj760?B|Ztp7QjlM!WlPz%8cyl&nx#XG{n`=`-d{sZ(l6kMUEjXMx&_!dab^xe`%fOQMY#Y>2PF;88OXd1|eG6BgjefxO$I&sv@!z9y5YCMLiIaz1U_F^aw_G%i~j$%WjPtK{p%Fpry-Sog#UXT$0a8OhPBh{qW|`BK%E301ewOB#)1T*DV%#Eb>g`TYe~H{kttROHr9jlL}4w!g6MIg4=}O5V8Md<7Fizs0PvxJEg57F~AjrvVH0-_n{RUWoi{mm2glHQA6$YjH5Xfc#0_uQ$eqD;EAr4LZnksBz;i;BjD4&+csl6hHIjXR3`iZQ_EK<|BJ!Thu2(N)G9l?{oQmAF_3bllzJr#WSE`h1~Jia(KTn(Up0@B}f$5G_J?CJgWQ70H6(k5!S^b+!)6sdl2ynqSrXN@%BTjDoe>ld4&sUaDKQ$Zm0NGEaqMr(6Us2W=rM`V|bUbu>Cg@}c{2ULY^gFzGBENeH9ZvLqZFtQ@{xY_%>lc=00pCyhD(aIr7tWsBJDXTPwkRE)V}X2#$9qMJI_n?bzfXuC>2-|pm1V<5VKvhk9>|mQ>$m*GhG|=(jGSr_U-30%v^}1~pNG{Yi~5AY><{o)<3dL7qH0Z7#QFVwZvX6?mzSWv;``}rPKUv(~unpP%=p-9FT%+!^*&;six`fVxH5|B_S=J~WgZRMvNp04IK8xJPI&MYrKPTs-uvqc@epnGM>MPP#<@9*UKmAiTQC~^uxh!65kO`-peh(a>=rr>D+DMHK&Ef*4>_3P{RYX`!BEI*Le!(wy_Mpxo=jjN~VDitEf+_n>g&mx^rHU-D>}vSFxB>BZ+EV3;qQrfEK3rI`AMrr(51j3Ujw0)_0;b`)*oxwHYk4O)kVvmvQTsz=dKjfYju6T&Ni5hoJ<5|Fj(EUI(Vx=ZY;aCfebXF@c(pdyvv?r~R&HCmq=9mMa=))kDF%q>=IxF|eMPoWPMev?&+i#?Q0L5d(|*K|OoQfquZ7(xb?*<|w`7-bGa>l-D%%4-h?71$cfINV^c(KO>#Y5DRaEp{7T-@&hN9CZNyO`hEMUSPftk}K)+0{N5o=Lk!Sak8i5_Xhqh{Z^u|l|H`wvA&DbpR_l@fXX*#u@UrH<=W%A4f^O$@M3un^RYM}0-s`IPrEf$YzonSlC=^x3cLX7T;;EO(>6%6#+d;K_$<{#G-yH#zX^wYJQ?opI-&IU)j?58Yk%om^PIKMZ&$OdN*ku;Bwlyfw}y*lsoc+eWQcflZKpM2d^a11YZdf|?`zAIV|DCqj!W-iv?RgrB`^tEAxLzj%eI19j?(Ux0$pQb#gThc?>U~4ZA6(vbnNh3-ZL5->{lq>_0dEAJ(KhLjr}=%zuaBw$p6r{eAz3iT#(OQ@o~X##3dT11)4tMf)4ZSPhAf3C;JPSX4w#z^mL?Fk1|(_;Bl<_pXX5~#jlb)|6X{H2JSD%Nl~}Uf{eAFEo6gHU){6xezLiS0lcG%1C5ma)6<(aoJb||R#5G;D{ieASD%HI=dd^%PW1=&eQZPiJy%a9cK>0+USSt~k!#4G?CX}Q;y}ap2i4yDkmqEl1HWE+6MCs>!S0$#s6zsOs%p;u%Y_BUE?(F|nJ@N8_~`@Dli5&gwaxX-IO0M!-L0+rGvU2q^!4XE@pq)pVA(5eqr<&Frm;?&k-y}JgPY`gv-tBy&mIb1z*F>_L3~>B7<=^=$Ah+q~nb0qOz1Khj7Vkm+aFtbh4;>XP-xCl=D+M(79T(<_vH&I~DyG(uO9zel+$)F;Br-8#$9GT`(5_eXOn{#v}L^l!CIOdx$Y5{@DtpNWB)mwQ=IEL&>qDvo?yHm@F4d&Y*dbJ?~RV-T;d6kB^Kl>>I`cg*hpjrjAo786_zxghx6jC;lmb&LC}7I10f!rxwDk(>m?`99{8Q~3T@1`qzXzP+P418S@VmjqGf&*ofg_xw0S1BTC^@OAU?eJ6i?_V8>$7OdWRW2@9_#NQ`WNNiikgxQ`2+;_hCzHM7)pF3;Lf{LC6I_>WfC(lE*%-L{0Pd{@Vpl;d6*|D`!nF9hB%$XfwhQ!7Oq76uVORp_|EcnzlmH&OPN$o+&oUKS{LA3bJI@x4?#@XA@6(39zlwL0cyAbxX^Z$+;b3rt$)*f&t-yu5bY@NGbq4Nb9{+(r_j0y^L2>lUf}5%!72)FLK~23&*Oktt-Gi|0mUb({+ETz?%02PLVQqP@%`CWCIM;Bu|)`V5#P6PWjfz)WRex)FLOrhF0G`2hhtFG$w1UU3rXXaK{}B0PFI}3*WaA_>#+{;{N0eIW;Ba(p19(haFZsD32v*kMw;vp=f2JtT*_v_oXx(PlKO~`PZJV&dyWm9u01xtlo9`Syv6b0CJsCkR;FuAN4zP(__e_p6Ntx$DK`i8mAs5>r8)5&Deigb_&68!)mfUTn$9c^?0On;@Z%xWAuq0~-Q^MM&|=%YS9<$VhfKZD@pi{eE=&_StNB$6^R(6^HdJ|h?(EdYyl^ikeA320*|2(T@YA&+nD6F|?3HW};qjmUDHPxGbA#e*TLyS=JHsL>V~mmqkL+};-kk&W)kaU+)9C-bldYHlS-WrZ^z2VGdd2Hi??KZX2!YYhQw&K!NlS$bizp>!mhgTSvcK~B#7blzFr`&uK*W&ukal=-~-H`ywNG5P+^y;?qfUH};+eOLyqeAB1BXsB!xUJE;oicZcoWm5yfGd}I(aYi}`ii*Uw2AxQa#!=u1;rSbSxjEi(v@s@;`B?#?*qmaUu*c`j}8ZVTc4XPr1S}vxtS(BljTCC*#c0mrs%`9Q<)lXxUkbrA}}QcdAi0#7kQo~baH)}eW?uQ_uF^s&s&P|AmfVWTW2QX^%gR|qZfJbS5IlPur%gV&bXdZZ8i=36YlTsa>x6P^f~`vibEeLzMa@WpRa0iK1+H;TT}nL8)IN=Rx#q^FVAjBfNo9k6oQ*S!uC86Lz3@(i2lYvAdDOE@+p~ex`+55j-`V2Fqjt*#>`00r`-1YzOKX@bKlE7p0#NXWeMgyS$PGa;ldS_npP}CF@)EIj}*~c8k@-5yZ=jIc6i)9I)SEH0822#ovIb*0y*F7f$5ea6U+DC{<>%c#n+&IJpBDVUKz&tGd-C<}k_`CvHNLx(Qh#-Dd-s|Bgw8%p2&2cB@cOe3XlCF4m<0{XuQSyb;`NVv{d~6JAQKE19TB95A^!fvg1V$@EYSAb>J{FC`0Vn!x7W+r;LxhkHa4B&bH01|59=%r-@m$B8*!t_pa1@G=7Rg|pJ)E=qUf$6-EyhP+3+`iov;2u#B=-u(`M8r0I>`XDZ7CBYL(My&9HSEjNee+x{~70Q03fm-E=AqdX-aOR}LYbxYF=*lwcN=U7xdPH|1Qf$OfxzOKRxGc7gvOl)^)fQ9FI3WGc9#Z_K$o}@F%Tr*9yp5Ia57b@x!SNr0W@Z98zdhOr_0qt?rw4y2(7~_0bjw$N#BW)NO}zdp3&{0u@fpO4+e$>qlnKAf6jjBKBTm+Ji=QF#{^0WBb(DRuy}ntGo)S8WtZNFkp`1VJpSL3YN2;rii?#s8M?(ETR)sXNK8m04$4>=ug@_vIL|ZmouN=Jh{0r)cW*gnn8Is87>w_MD34ZoLMb}7%{&oA>kiur=?Z@eNG$aTQuCG`J3H~ycfTu?K;KJR%0{lC|fb3`OBut2`PYU+Y*7+0RkA|b6ZHbiYRtba<;jfoxOb~?{Euw`TZQB@<1YnIQ$mb!;rc>ZU2d+l?Ki(c~1#4sfri1c&v{50e*C*p4Wn^?DaY@PeSVlwh4eTFZ5;eqe#tNl{lh)b7DJTm)84sa$&G#q6k|NSST8#_Mb@aM|i+JSjQlx9>XyfYVSZ-*@Hru5ODtymRU9LWUh#^U>*6fv$2!Ko3ei9C|At7)N#3&yosE@6%BVh$XBnDU2Zh&qJj?BXzUB^UN2?~%`;^lzU0!!&p=oegIzGmQr*e(YqQuMMG>6tr#D?DIzc9{T$ZatNKU!(`j@uJx3C9s}j=J~BBly(d5F$2Y`hNM6|)o{|IVa>cTykrdx@&PwNwDY@`w-qL5Q=3;)lCc4FX2eD3BH@V^5P&CH%`F&t=DxsrR-n(z3{TkyEoS}W>q&*w95g$atON>kVy+~hw1c&cqrY?s3$+_N7!ntr+w(MrpT;xeUXRZ?Kg%1)@_b&G%?tAg~t*O#H=t^`mdz^>-N&la*TRgD-qH*U9rCwdTo~6jq%YlYv{);|Q>cE{2{POjn`h38#-@p}>Yr4w?D&{6JZy6omq&Sz6(xTQrkY^Xmpaidu;@~;-pIV{{m=qTwM%T!yC|FWybrte$0@T~5^8&*8>w0iT~AUr)A;_V*1oxGOfw>f&bOL7|z7#B^{R#i~=Pc@lc+s=cN@AZyFti-(k^wEd8t;G81cc^vDp9I7cd`sJob7^qC#Ms!i193&F0$aEIumMxl)F&(czDeR1-iw7H$LIzC)xrnd(^s!`i7zea_Z|I9EQu^%P*L4X7abYoQTA}7S#I0=&KmFXC4N+q6rwKkq+)29FMzVX3$ZL9*B`o+I`eRY>FbN@*zin#b=9g7#E&tTZVqnYz~lMFQAa5{>Z-}D$~y&I{+x~=SHug&YphlGXT!Sqz-N0X^Jtj#!l4Wi9^9)uGwPH@@i8FJv&@tE^HW;RpuXbI^{&i-YiWIK;eDv1$p5ciPXA}#gdqAeoQ!x^zF(FBMMWRe`rS~^upAXSUfyKF$ceu__Dsa@UrX8?F^vr?nuqd(DY}UCp&KHe|2k*SkMI6K*^hF+o9imh1rsB^n;}0De|GJ9=@ddY&kt#zV>gEQ-flOO?(l3F3zc2rI{|gnYvJo}KHW`#6}qce%B(`1zpv$<2BclA;5*b;q|a)(G&B3*_3`P+wWy`(rB2<3f;~<;Ac!s6$Rq78VnwWy6{1gjE7Ln6JCylp0KectFm5TD1!Enx6XM?&y^{uwAgFW#WJG6(Y=|Ie#j$a(bflxr~N3-Y;UO?>Vx0|%B)(4_zOd0NEFUtUDdgP4MY%KIqiIAlGWE|Evby1$r}7}qX$qtAik9N6?t!T9uEjEk&eSwO6>M8m|a$8|BTgRZi_=Zt1U&0)5`TocAc_H(U&z~j#atEA|wA6xJ0_ypuYhmEl=H0_1Pc=C(?byNTvvy%zgPq@ULS48pu*?3!hz{zINpDu3sP-hj_k+nBT_`^J&!vpMzTd(F*NMH(Jj(aN$!-M8$vI%Usdw6vgUJ8KX_>#doE(_-CVY1v#Si@EG1FrnTDd^ZLz_XV13xC6BGbgnh3~^dd0dLmQmBZihUc6-2)-dIx>24oucWR!AK-M{lE3pcioM}SLWu7GoXL!i=e7}D5I-Cw)HTA6NYe`Rj*%>bbp;14A>65BT>WfA7hPL%pV4=w6;!7E_2kH^#)s_84V@#=gksD|R8DO@Z4|tz>y%d@w{k`4y$UUG`_IUn37lpT8uEZ+Q-)!a)%B$ms+e>xOUw~%w*&5vh8me5#eJmoxY%%kp#$42707dCJxxef7UN_+jA-tj>8^^}XM(x_W*EPL!-a5x7HPsFSb-bwM>yrCNYq$mT57S9`2NI-qHQ2Z)A)S3>YkI}QcsIR=#S4(IfV!$qgk{TOIeb-yxyMocnSaA5`GFe$l9ecmN*oWR!HY~bYDt3&9IL$;fV`UwOKPR_q2=Q05Z*|^(%mo2W|1XDDqb?%r*&;Kt`RmpgPsGV{pJ59g+|6?=7`TG?K6a09>^B}XZjn5ED-ZFBjVksdd8zQ$X8z3@N7PpZmyTZBEJy=C;)nK*GViZzNw-n%<}AKXQCBbG720oWE-Nv?y?x()AJH&}}dFJB~7Z{e6bJqQ$^c!~n-23TvHf(Tlyw)U$dWr1Yndr>p`x+%oMZDQaK5Fzw5;%Jv@jW>aasGK|NCv;I>~+b%c%$xccHGnuSvvHK=$i>r`u^mI2br2Q1BQxhA|jnpM}3a$yVzXC1p7ZeX5T5g$bNkDNG{obVtM%8`7p%KvKH-HY{G#Lkt$zLoJZVlH@(QtkPF*F3qw1D5hs1M1f;TIL9mmi)j`DlzhusSSf34kFD-oY91$mdq&ZwJzb;N98ugWpw2QKMRW|fLHE}M8M;(%7b6{WHT^^AAQe27-A^VK_<8t7PWrWOzuXsL4&S#?U%!P}U>Jc5QP=}B{ax#Ot{JGVSH(_2NeU>H8_!F19N8dkiz)asLUp?DY)7>JU4Mjl45xYSKj$1vosfqL{bELEGgg1o}#$2`dsLBZZ>+c2zjp1oAIV{S01d0J6T!rno?J0Ff-V{HV?G^u%*RLQ2NxegD!v6$Oq$h^BuaTVtx#}XI`%TgT>dq6O1vgqk8&Y>q0o-`dPA4J{jXuE`7N}r)`W5mg_mjQtbAhaXnUjkAFDugq$+0U(F~>@cPLCw(Ybcu>$0uAoF%%z^ZH@QF@U;SX+K-}>7-6(f~JRtp11k_OvoSoB@KPey&TywPlDqlr>!j9^*mnolgQT`pCzBu}^mCmK->B6V6mp>e%gssz-$XUFYkdZqa%x*f=FD7f$X1lK}GkWpyJmo@V{}Y(TH-68ND|W^hFfz4i2J-Zalm*c>Xvj}AIrdqTyR>c)~>q+aUVaIW2%d3{C>KMSkzZ_ymh=8#P_=Mnb3}q>!`1u?htjaDrCY#Ri;NjrS8iJj4SWCv*E__X9qKEx&x`bPuIc^!yWap`zego0)s}b;S}S{~2zMbqNm5|0ur&+(`W5C3Z$teZ^v+@26ClW`RIfZOR;3)GbeaGcSD7XM%XllTUMPQD24Jt31Pd&*J-;6b0bxiwoE?!g?Ioc`MxZ@hQaf14HgQx^O}6=|M*`iXJ2V#UgF8`EwYZDc5;qa6L>ynTR*=r>cS%WxmhtE!r9{c#s#;>hWz4;`~0!B{}f>e5FVG9rS0I6{SJ5-I@y{&4d6eMI92oY4`B8O?ePI?jWLZ0rRy#%pN)+l@Iro)3$cbMIG|=;>$6wmVBrmx$1Jw8T$wMf7TShY(M+40A?NbQ{~>lJaX*vqrk2?h0xxie0p(%^uwiLSa>s@LqZ@Y>068a6;Q(b`On&T0Ol$#+9{qSHb~XJ!{8Ph8#-Hi}IKF(z#&}Bo&-VPf>XQQnuz%)p+VTj@FBX%sV#xJHzJr0`7Ez3AT~PGYt@CoAa7Di20TYai^wD3XJRPjcIk4rsspZafQ_Uag6Km<#p?-@8$E?%ln3~uFP9OYkv8X0vM29ER|Y^{1+XQe9+@r07DJUr)t8HzqVa>x?x5Egf5abuU5zWBEP#_XlH!^h%O(Hu`I=PJzIA)+UpS)hMKr)4Hq!3-**CAz?cVPLq|GwnlY|yXVo#G*c>=er7}g-2KkfsM=B#1J}=bQET;IolK+(>)<0xle|-k>|GMmbFxN02L_8I|ZO&1Ax(J08(3203&9YC7P<$jNSYLB_qg?>{9lk${ejr{NF28oxp#uJVNwHAMzKSDggwYDXjT6BY7oyY!xgOz_F*%S`clbao4}V8j#uN5)cV~m^(JvlT2QaRTcUcc=?(;xOvRj>;XZ0`MQ`cqd^CJiHm2ayX`y&7I(GD%9pNMr(z>YyVH{`j$xy?bXBoB@*Ub*eda?1JO%ePVo-SR=oOz3bxJK|zR2|hE2^1v)h4@+WnG$l3x(^m1Qj-%IhE8aS9R=|BOLDL?1#v_d`bl4Cmgu{j%LCEpy@Vc#zboM~G`5b&N|<%mWow>E}zeP|w)5damU(c}KV|&pQ`daBF3FaUX{MYr%G|GaeVY%A(Y2F)Q0lKFURXYbP-mykR^12$KGx?${awu*aO>hym`=*dt20maxU4=9I<>}$oj53JE~&4rY8S0X-qL_Ef!_<&5_P_Ta531+R-@-ISobmU)ZK`=be}3*WKg8LE_vQ^I&>`!HnFU;TkJu64u0Q_ODJ{hwYS8r$0YOMhN$S!Wy(I7TXnn9{A)zMNOZq_vl($Qp+}9}nKX#<6g048AWrs+KE9Rp&s=Y7)K~8lmwsy)V#1u@=0UytsM97E=ekd7VFUMG*bNKH9K*vp83H~ITnKo*CwiDt2W7Kn+khD>8#YIO`|xDV|DFR1mGI!?B_%!cjfj)$$we7C;B#c{qOBVcf0c3ZypmHce3|`h&%0HKzcIU%@NNA6^Hcj5Z`AeFQ|Wuxodfr$bTuue%*T1x@#p+$u{^kSN%(sJWj@aLi`%V|=jKD-CHV?we)D}cW3A?_zkny=p9_O+&|v^38&&w;_LuB(z|=-+OnKRmxCJ{MvS-nezT1>>5pvZSEAfLK?$*ro_`Fs`RQ;dX5q`S3-{-S7Yjgq(`5Ti8~%^JYAygrmA&hiDsy8`E$lk{8zW%sjGT84u9XKr+-G#Grs&4_z-JR3wDQ6E_kfSyX8c~JDeoH}o>Ty&Kk-G%{tr2ywa>BOpMJ(d)K{B=7H(0?DF9*jPz3`@U#I$-vt@6-6oBH{R|ZEZ`7v_2!L3BaLNNB>o-L-FTUlLrHT|MRA&~RHMJ7ym#^&YIdEu-l~>PEyx++ETS&|W5Py<*TM7B^`Rb%GJueS(8FSx=QT#=x?4Dk<8j51F!X2YgB@!!Pn#XE3jn;z!P(z_Ez?Nke4`@-9qJ>`g#{pT4)Tu{$8(BBb=`fA5=7m;xykC4w9u?CEbSf(`YB-W*GI;X{MqxjFy+cD?Fd67IgbZy3~COyiWLHqrEqZ0{zxMKG!>*dI^D6uX0+|zt;S=6(;X&CXf&mZ^{=oaw%F(v58b9gLezFJrTw1`;^Z`Z`UAEdKPH}ydQtZKez>P+#Kx@_w-a$uwYEC``6MCpUG2wGq1*HKQhh7?}ePhs_v4_-yiN=OgUd>3x4bR&4cQ(Ev$jv$g}HP&TCV{Td}57mcxttQqH+fF5W-KXpy)}9G3>(7U~w%?u%QsxGhH!2#kw-kWc)pPoqRfyNBOW1u5FMx8TxFxJbs1w3|8s-XB6#(grOb;>vwLvSGYw^}eT+eZo(VJ%R%E=74p5hvX!R4z%;X)?yTy3uN0Kn=+SKP{lAl^$hXcTWoSRCKGWJU3o*8}c0sq|a0Il~hMgMHR80dLXna_>K}@M~5LH_rs0{M+B3nxZFnks)vIpkCg*{ZstBJOHsFYZ`i!%8|laNzON(t45hxkE%mHNd>*JysMacffVkC*Km&7&eCX)86gx7CxbBr5=~IdOLHk2z(i&ydISZ1uj4#+wz&~eMOF8covsqib^?eq94)q3k)K|w_Gc~RsV!?8wMn}0}ynf4Md(;(vkxwVp)1L2h=%aADT~XE*uCgkeU-h=__nd)tZr<2b(7x`tl+U@vxA#r`xv?>q?`h#}6p=T}4V@^1dS|uCclWK=ubYTEC&cTnzXhR>gNT2ybs_F+*^q;=yLo(kiYnsoe3-2Vh;?PLkfgu~RlJTs<%QXoT5@4k&||NcixBUzEuL^GHV-UiUr(u}_%_@~yJ5I=O+JwOd9%e3*I2G5Ztqn9kKf$Osy-C?A1+eX($Fx!5CRSwI6IF={fA2%SACz6TL`W6NuJZvP@nJuOJtrey9P_X&_Di|iFv$6;7+n#$~BN{5{i&8!*e(C_dI#{+CM%vcK_zVPF+U>!^xIgia?`+JF|El=J&$o`lfyti~jllFPIY28(-$U$O?W6cS_{>k~zhgJlSg?yK{Qfnm&w+yg#HbU*q@NzEDm1@Adm~J^ehtTm#bA++{iPC+C`XtSjQzE8hKsdhB%Y)VX3Oi=gfMppm3W=Koy(_{}09FE1*Dx+V1K{7tqWih!(x`+rnjd0dTM*A}Ieic(S$rO4c%QCcF=K%)kvB8m(t(nzT^Yo3SGJfbtCBorztDw>f7g%S-^LcVh!@6$Tp`^WSCp7pz*)4s2J@3pSI_gdGoEo3^!qtmB?WyRp5s-L@<1$na6b{b1rM=@MnZXGm#9-eEBl=ZqC_auXdW~n9r1LR$V49{0K3ZrkkmrU~9-zDzNW3Esb_cARlYF9V;G8B`#20e9PF%so%kvn0Qw{?mtHK|M*Ty8b!-ygN`?zgVQ?DZbYe&kt?U*~OruUhUZP0(sYVYV3S}Lo$5oESk~1ir=NnDIqbdmkjeyeCjah!g)pL$GIG$z+11MCpI&k3l-IR7G{@H;KXIY2WQ%t^y=4T9NWr4h22UgJC7&h_^}^rqfU{Fd>fg7qwCLgss>Ji4|Va%TyZq4R9cbdKcAEhm5A*KPPHeA3QiC$5)u9amG{TNXpG{20#?c^vK%8ydPB;(6wZhPbjy26>4IKrv0bCJVK9C_+6zeiot`Xbew~UhZFUN(X90SX#?AqJ6<@Rql(!TU14N6rB(3FK?whDC`U~d%RCB_gF}x%hX9J`{(F=)6}zVZjk|{GI!nRz-hr7K2Xxz6Ymz(cb*oRdJ^jnMi9kuHBEki_kX?NhdS<4K)3M&VEZprj^r^AOs(wbh|7v#0O7>!?sZ;Q#Q!#|?vf*e3T3>08&iMhbnO?bMic4lMeXQ2dpER;R~gIw9VbKc$IK9LL_3dPV_V5i3W%y33qL=BcEk87B{^#{5P1j2?tyc5dH%&8%LOUWsJktBcsgv(?sKy$h?hcvYn$&JdA|ztwQ6Ml@cmSvfcRLH$r_tcx04GF4`!ScxEN5TEN}?lYl!_)#JM606uc5_U(XdY_xmzO16t3^Qz5CI+y8VJ#&P$w0*zDIRAAq|^3bPN?8CU(;@aJxY&00)ve?(uhv#^1D;=L%9HK!=dRf2T{gk=qZ=IouIwa6QcD4HhE?XS`h20_T;mtH4`bRx>#Q384_m0Y;1tqX1;_ld^l^7ohUE_zF$k4#4S^nr2zLy%$^`FDv$w1#G8o1rY_iB~w7ivzX0Fl4^>KuNTz2GMiK=+3cyPv-JJcN9Bm$%EfcOn(8>b2!*NgzKl8_*bd^z(mwSQvG{i2TX>`)II`$L{lt1CGD$!j80e!8DM2H=OlVhN<7;645w;Cp2iR5WSq+kM>H9!MY_AG}yoKVfvM88FTjPRb911v&BF@<9`2AD9$&cj}rSUG9-PPFsO+`-Z;V|z3|9Y3K0DscOS%g_5N}BSRXeP&X0|zPEe6IcCiY@{<=m5jhIBWCR^l<#QsORmkRW7&GPyHjh-Az?ucU36!hewlG40x)4lv!5N=s~+SCvnL3nd4RD4b@>Ghb`vEYL|`FBYR2Q%v;>YBt~Bs@yLIB3~nRJ(GTjFu#pI-9Id*6R&_ZIQ~0i9pmfz6mZ#}EFf)x_&e|NtS{=N`~QWS6UENRZ+*EB-f1zT^E#it+V~SV&R;_Xz*bI$@UExN|H$Hai1USooHUR!B~SnOz?26lS9L*Lj|TD;=GV2nm~=k-gM!ca(HQ5(%B;u-hP{Rk21Nx`!|i);{64Erzp>ILgAmv54E^$bwK(ah{(A^5AI@W~vEtR5FcJ%ycvB&_ZYt!h9237fz0{zxg$jgj%Il|0d33(t{zwYbfY80;+J!tJN$jdUn+c84XHcsM?Wb(Ymo)m*fY2d6xCr?}$`9$<@8mo1sPuE=<^4F$uurL%LOY9r|LU?!HJ5OlguVwYn+y+f*xA@l;&}9zOGl4sQ6Rw2;&sb9{JZrXO)s|8Qy6v7$E(p!)I|!={rTkZ0hcXWIG$#+U#fS)sG$4w@W)0f+8en2Rq{Hhkndn-^qB|w454$nemMF$Z+Y0T{VdsnL%Mn>CDY-ZANCHhZ?uO&nMCJnN!5dMyG)9$miEp$I`vhL3?+5iSkTYVf(N6S(^HHSlkJLO_{d3SBrkZ_SGl2fxH!R=q=slC(mz2;;g9a+JFMIYyo+;l<>{McL{z4iM_b{4@Xzw!re!%l>5p?fpU2`fIf9KoHse)?RJ8=5obLBBTCO#%owm>tm7*4<0#yP)|>HO{Mr>oWb$)Mi<*qgKj`OLDB4Otw6WSIWz_}GK#+-$E@Pdmp+`hNfW(&=Dlv>UBi6&Tk|3u@$FKN$Rr=WNeEw7je=x%02TIUsLgdArH-EuA;^QaF>UtdK7e{)OL+4EKyw%pNiIUrsB$)zLUW2D{??iEyUAfw|PEs{M!Q`(?g+Jr3v5K56~HfclWasOK`WLwjTsSN#xpzBd{zwgUa?mMAMgHeZ@-THhO$A35a~R({Y)Tu2v*Y`TsF8Nsp;MbxO_}yn1Q}Y&i7oo=$Ygz(TqH11SZ{hg+K0aa>ODKWZ&v5~#vT*zX-`})*H_tB4RxLu@hzHKqF4;CAtfSQkpbiEpW7ebHDEP?v(e1H|t8z&Q2En6Z*=Q&mvGpAktzkcj!91R#cc4^2PAMK4??eT*KL|&VI6^_3nNhs1uqXcr{#>59A(x>ZZ(`SkFnzp50+xv*=cVaTcyu=Ft!>$$*G-?}9@aJyv*qmJ^}Qse_{3Lkq~qe@^`i|4!{cH_{y_8<*bz|zlQ!$uMV6tRz|BvD48~6PsyJG4{OzZC-CLJZAb**v@Od^I&)WxY*DYwFKttSet5d(wUa*Pte#==Zu-#a`NAw9(-y+#n*{?oR8GWe|nEGf_xZiq@AD}VrM=0OWUKe;-Krn;Ohm~Vps+n}jMv{IN9{)&#kxg#7;!O9UQwi%Z|hP3J*eJ0-Z<=2JqvMa?fbumqJy9EB-%Li8p&Ull7$PfL-jlbXYHQZ*I5e2%Hq#ODlqy5%FeEg`_cDIIPKOwd@cGoE3{~!B#^&N%9g2*p@Z1CO%x6E^n4VZne@Ic_QF1m*ECT5Rd;)F;tupvi}=_@D0j3*=Xo#mHNDt$)k=JS9W8j;O2ERjsh2D7PcAeLi+{k6*B8L3L~%P!G5$e^ooyB!8>Mmu){v&X**8q2Hbi;g<(bh*PAu*`5dcIY6&;p?{SV($?9k)^iq8cY5(pq74dhHB6fWhr&&Y8s{=0v-X8nU{%FX;Jxx388Z_}r_-d&c&Hav}=#`SUqCvnhFHFt-gYKNY{CY=1Uu!tHe1CK#I8_I~JHO{ni?>nWyNOF`HuAunec}GJL)QAS5V-DsLNmo+&QA2tdSn<6`h-x4v+s3f8A2(mce{IfAiK;O`&#kh=3xBt){)XX3X@bM~7GVP?NJ#Q@RwCOOP`&My2UnG`A$2ht7h$)97L=ImO97O&F#YnkN@M1J?aDFVz2IaTxIkn&sM~HVN=)n*17j?0HHJCWE(K|d|*7^{^%oNuzXW1+wXY4x#zhZi-Ln^A{h4|$=-;kMY2qT>%nMnz2*DWaMFA3c{zvZANBiU8GU0j9$cHVpBayCW&Ih);Lol}SLf_bx`If;&8yiCt}(kY_xx0JGQX;F99Z|yxOl!nJl%5QgxquDfsZI0%krJGFICv_fYP4;#6963()BsJ^Xrqz{$4I%qPOJIqb0}>n<-z#3Qzk$SHGY0bUpIqCAS35zH|(L>w@%8Jvs#PL@9^Um`3?t^A_uTRQ-8;=F$bV#MZQXiv?s-Bl&Y3p`ro_9#^1Van?D+yY->NfX!83a4@_BKHTZn&%)@QbO`f6=fEt$dd^P4O3Ld13?fX;23v80%QIlIBq+$e`#o?x(bTE6r(?mJcw=eM@2_(E`S=EZ)0#9>cH6NSer5Y8+ay!@@2N&n4EUuc;?7%Yh;r~h)pd;g%~-p>M(5it6=&7mY5_Z?RAOTV_UM#1HCT_L-_6V5M&v6N9lFren^>h5mN=Z=Uq1H*Q*_zu;3OJZXtl$-9sH6bFv5dZEkFK-42@0^%b|GZnkp6$8uS4-7AyLVVbsu03)^I1XCwS}*(X2Jw+kNm=Z*BObmhrZ17{M|?sP??fJae;u;)1s^_S>OWp&G~k}oaRZ3@C*@4!{|{E_25r3^47~|WYa{#-2mAhjk}{o}puMQ7pg;`w-9+Cq2l_lN`CVyZ$;s63EMs@izWzvv(7GU@Ik*4nQP0c0S*flc&FHr)oQ?j3aQ}5FF`%;W#GTSTxQ;4JZ|Ryf#KM#I_HtGp#E1CjweC1Lt8mCB^$+3`o_?JD(t3Y5@=2R@oGEX1)A8MkhrKjHzYY46X#SB6%fe#e{@v2U8bXNA+aIr%?TU_r+xtr;4JQzXGp)B51GBuXySIn<^d*%cMe1zGKoOTD)Uw)q#a!44tdP#}S8Z{F?i?9l~M4@oXL_BMwUK+jeJGMlkAb9GLP|4#s?2;kq~qJobvqk9!~v!Gff-B|D;F;H#5IRx{#2)N7wGj{&XKmhFEH@jPK5W%r7q(3bRrV&mnbk&BUErT-YU)p!*OG&bM11*ef;*@o~^*)K%GhjQtG?I)05DO*3blhTiY36pX1{S%kx?0lIY1E`nEl&rJZi$8WAL5l7xd`m=AT{lO%do?SR1;ElZNu1}6+Y-ut>=Wuu_+KDF~NS`nN>twDZ8oMW;mTmkvksGnM1$ghf(l7E(%`hlW;PfGF##yf)k~4kq>lTFcY2*rLRYo1roe5i0AIXI#ObLES$Jh`0)gv&)oA;3S#Y(^f;H;aOLpx&&aR14M&&xoJoX~4e#Y%%^<%z8sdFvM@teA^?74{$ggrnj+rYjP63G<0ZB%OJm>6@!#UB*zx?A{m0UQ_3ElX^hy3B)(Nnv-mm|NrYsbLA?_a5%4Dz~X^LN)Gzan&r<;A_B)cxMU1F?8-8&~~w@Ob47=;>Vbz`zOpz~cw9=UdA|A!Wiyw00Qp@gux`smyba0F%>`pwo^1U%@{EQ4VJMscsjsSL)MF60m!Y2*1v@3eBhQser{)LE+2eHuLO8RM;E`7Vw_qX8!+|l{@1B>}A++(t-%b0_e-gUJE*Ap9+fD9tstEF{?M)spkNSmy`d_sxq0Y#!E*i#9T}hz7@6@xw(}42?o+NF5Ru~1@+rBwYp1`<3r^#WVWba-G9@<$lJh(0D9?G0yIBaL!+3^!aAQL8GK9kmLGINDh89^4SY<;MIVK@-HJG@^*rUoE-A2tM&$I^0%Xa&~MIE#d$KDGSYm;CI$$7ozr2+uZX&)vY}XL(DYb$auwq9X=bOWv35LAkGYf|??HSjEv>7L`X@kmh12@o^@z{wX+P7)S&5MO$@``wQywhQH_Gr%09=U+p1#eL4?x@(TrUfOLdlf_`>YX%vtr}1zxIcNelLe%rwHO8m}|i$u{;t=zYgXGKm4b&4-6YSdmv)hf+VsKa7PVmsS>hzJl}QtLrSSnLQp3Hr^*+6KB#<9NRlMCYu0`tJiV`{J?!muGw~uIbw6WNPLHzVIxOB{Nhe1^`Kt~8rAEk+!y1Ck%U{1ye3QG#1^Sdmvux=qy{Hj9Du_Oz!iO2{jSKH?HNu|V_{Kbej=5bY?%JL4GjTwMw{Pd=QIXb&BahveRc9;uVaGbdE_PJa2G0GUPab-#4tJn2X^=et%K0^&mKaoyF(CpA;<-C!-h2}LVbe8{my95gsnHMSgzfLJ#Et3{HCgK~+S?&fEaV8I>ep1c6(18eA0G$qT3M%-g4jFX-ToLd0qPVfhfd*v41RygJ+UqJ65m3c~TYp(8stc9zJAP?Ah}Qad6Rn7qjwi0(}0eA|jrR`!z4I9UAyr+-*6KN)~JizJ7;ua&b~3o)SSyI9V&OKTpCcp@pJbrP)$AM$H;SF@5Z>6W^z({jk7AaAOj82n$=jTKKkPbZUvoS8fe~jiOzyq4?T-oav6l{}pX3Ho;O9PVH#1e2IXh8Lop?D740OBaP1qt&^PtntcPB`&b-RXo)N|x%?-d_TwoH;>was-ueq*!~dE;^iZv5+~xeL!9D7=(S9Y1fviG>^b-v^*SC;E{;$&7;20ULgszek=>)&J)HWpXTdQ>0Cm)*(+=oxqclx+{U9r;#9ncoO;l8po3u{dAiBkq?ZdG#|2+O#zkFi+)Y+N1PXu49a~Uqym3x({Q5!o_BrhJMT{6Ai?ti^(=KipvOMHhL|-?7>L?JdJiOZa9Qyxy-(y4V{;`n3UAZvpDDsEmu>KoC{qZpQY8lJd6g>A^KF)E@cZlvkKP9L2okpIJ`|+Kbeoiu6xUy@{P%83-yc!+FMe9--bv=L9-k2K?!HeWBrorXDixoa!5YMX6=*_a)B=C#j+%VLGyo)4cF1t=A1m1220Gl|-yg=fz$;Zhi+`<8F1Ftz6Vy)GW)U4&k=C>sfcfB&&LM8SC&bo1b|mrY^Nc-mV{>InMJ;NLTAF7rmhHBGNSqXrmHpT@4ztM-ZpqW)v{G4iYBq_f*~iesVH_H7F(8RtnS^`q>iZ2G=W=r)hlONCGTy1s9G&9T)Q9uxqQPcy;g~c=|5o`uh+EzO`)%2{a4^&y+hCN&)F0FJS+x3_NVr>`%y(foQ@`?Edro&vMZ>1H3lXZf5r@?+nw%zdUKAx-T&R2*Ru-2S;M!2&)w&IFXxDw%d093NI@J#@$oY;qNGuhu@_!x=vh)pP@;qEGr)R!gbB9C_Oz+^V)4_SNt*hT}Sxgd;{e$01)Zsi?5GA4+`#c$5Dk$chaz%U&N^Fi<*Ovli7VEaS=p#NveNb3WDx0^xiL6La_EbAoSf4TXyr7-SzBMM%kY!}Lb2pPduyx)O&fFg{An@FDz9SRA%KMPqA$K(nI956@id%~~5IXoXWAQ-vKch{^DXS?86x7T{GjwR(4j>MCZyr&6&c!n7XRnJQ4#d7lxG|1#?ya{FanKr!P>&Z$0KSSfp))HGhb8mJCFKt#f(FO4xF$2qm)O_CtFC?}37!t!+*b6INw;(Cm7dLwWQMN(GE+RivNgIr`jV)F5?Qh)j1T7tL!aS9Dx+RcVia*8^aOhK0vY$7`@bN+BEmA2z8=;LtZRK}j{M|Rtp|`|V;T3kqB+QmR@CmB+{cp$3p9p%>(^M#*E5dKHrMWL1w8ESh)=1dQ*#)}?#J`@;_{Yb_(f(|GW5p5wATV7kl~+}Y@r$_cOrpPUiMX*zE-W&JC%7WoxX-^+10mC^UA%LRE9C9T>pdN~P}m+fdKQSOXb=w?JU>R!7@#GII0}ay9(JGcJuIOfVHF2#F-svXYh%_kbn7O!pN_vG$SYb#7Kx}igo%dgZ!#@?F+Hv^7Q?S+luOOUyN&l_I)cW>HD(1$95$eRAHW8{C0BX^1DgUkZ9J!bqnKue#OdO-67@5ayP}|0hmMF7`nT^23aWgkVu9$>^<4q|Jkbx%Su6oo?9lz?{{!P)O6z?0kaPb#Pg{>XA>@tSyl?g?kaG3@m(mHu?evdUlXTHEhQ9PZapYHwJ|A?xw5Ir?T||ce+<3&U3*^oWlc4%i$VQ&iI6wUdRYE;n)1j%kAhyK{aelqD^2PXQI9MBfH1G~b|IpJF7F^^2>`re@NsXs6CB^cWW1V$E?KtCU4@=DSw#+I7n$7h+c*9k*M!pN#`pS&QU_XS8@InowvI9L^1_lvFz_K6-RzW=-6mi(&srL;Kh#Tenj2Vwq+#HSuJ^avjpPyYr(+X%@h)>`pf1+3PfIN-%H_KKws}`ZM4_QY(zY->dc!BREPv3kBN&5{bwWJ3D%ZZ(J*dVB5S~b@w9WztaYJc9OGQ#jXU~7-7~K{W{)L6!)V&MVpE(aW4wpm_Gl*oueXGETM))aqTfvUpX7gi+c|Ll3~2ohYQ35YY7-YbQkeK>xKD04S6dq6+%hr)@v);^O}*?*g3gi$?_`;HyX7@c=Na~N(AE$?D{&v!0>p=?kKSSz1H?90EG7f(rIbB!f^neW^8JyAGUCACF_d^9&PBG)L!LP=udgOlDG{#!+<4-^OT>Z5Pmaq>`p2)j5QiV>Ttn^?$&9|+(qia0s_N1;?@Fh_B|0H&i$WX{o7R$9Aq|QO;@&H7$9Y18m!>r&m^SLq7Wv6^es%NV{^M~Z*lO@#drv>&P$(5pF19O{alb5Ji~K720Hu|!A`apr+z#q7=>|U}`LS-=kO2F2^`AT%#_!J2uscW8KM@H1S`jMdVV*nN>uTPV1k;Lkcg{UU92h)_H3f)$Z6MP*-d@+ifq83ELDXtcHQ*BBU`2f3^=Yt={-15(Mt(JqzL9g}AwhQpx$DR?#DUN&dF(}k`5o6dWHNA`OpdG-PYwJ;)$m=f4^ZYn`@Ft|(Ke~0K4&&Dina|%OgQKCc!DZB_9pgTcZyf3y4@AH8qh=V#m#4-B=~X6y@x=pQ(u>^Y?8N>n?071ys0+N@x)RT+=-Zt(zI`OvGgWlPSqFKP(}S});#fzuBve{_Tc;bzb32JbXLfWciK_@p&$`c!w6)WQ*7TKYgUm!wJ)6e!*x9OBkG^m)A^F^#nY#*%;G%kv8(0IU7i8n3zJk1(h$!E4|a9Oj11VsbIQwvDgWyA_7{J2tXDOfMbMCl9NRxgu^v-{Q`X=?wk4^bW+$f6c|2y0aPJ&lWevjP3*eBQ;Yi=yKg`UCH45Qj(KCqMFiNr1tZy4!xMAiqka<(Io~CWC!g(Qg}m+;0-|aQtHmK(=-?_il^}XU~_eT^E%G?$fdcS@#ehH-r1fR{D`ZwoYy<`x%@+SH7GgJ8Vpcb3$xY5_-t5YTHxI%O9r0$wyzEb8q9k(kxFif?XMmzIam$5I4~w7wdXi`u=@a@{Qv<7+-carYUrtjE5PUZ`I3l5eJL$D;B9viSRDb`LOtMjHlm>OzbKRlVMYt*y!qhroJ0pc?Z@lOa4n&{H`|*fR>8_E|ogx`fd@F4>DhKi54qfMSWltPbh?O3@djWaHY|`>|v-CKtE_@&%m;-SbX|3ITY$_4HJu^G|G8l1KS$}`XIx`tw+g+5YIfOWvO5A_-YE$aJzB$K{U-c%c&YY+7!-7^*Q@`7|UWj(+LT5-o>>Co9{K?`=X1!s5NHCjfmOIpi^Mq9M;HMgW|7$w@bl_7l;*+nJ{FeP!I_&NbTzw!P@p1MPTw9Y#rfu`aN+Jf89k=FM4LzJ+N4QoFv0rxfXs8m;r4ykg8Gvrm~;&p$Mw>qPTWWKjFMof(6ETmJH&zL2NrNH9Xi^}TkJBJ>emjqYd`Es2cpljOyK{|Lz^d+069rdS8tokH)~S2r8^`U-$Zch4rP=4jPFaV!^z<$tykD}O|3BTcTA(CL&&`|i+&E9&)J(_+6!Jw$^dcYgff$6w8w?>y6rrg2}%zq8zK$xcf=|#+yDBT2}eS|XxFbrK1Sp*`UYizR_G#`I9}vqn>EM+Pi-RMh{%STpX-n(5a&gMo8urSdF$jVexEtJr1_1^!evRY?Mh>l<70zLAk%wfl)BYth#uk$3dr2cAVQ0|;?nF$*TYQU<(ZVKiA5fj!!z!7Wq%g%Xvf>%A99?t^X~n^UtCR(zrTNl)Jvd$BR+RXe;lNV?d7<$4E;H~JO6H3vm{18N+AV|ckDE0w)?87@Z)&Y?*MJY?LhptL^UH4tWG|-@(e%n0sgVJpT~^TK_bm`N9!TPb9d1!htrk}5K!t|`0^+6sEV~OgO+^EfTylX-u6{^-xtnz|1Ph8CS2p9*ed@(9>vLZNfXPK7&%S!;xkV;tP~GelymX$^W{b*2bUsW3IBn!tkvrO_3@S2UH_Mxp5<#)oGC}J$;=p;&uu=R)GGqy@ZuS*ts^_gx8uNRX3QoL>-Vgu5efQO6mj@e(dEA$@p1g%{mf=vI^5pWY<@Bs@p)=B%jx|t9bV1ro^P*>_(bsVT4#A>0H2_Mu^PX;GHId!~C*VjZ5dCo%4YUv%Pnc~!`wJxqUJq20>Osd5-M3EgkkSLv{4c}wZ?o_=kl=NWz8E-(4j%2d}t%vX21Uy7~Y`!U%aaZn-OnB4U$4g5yd9rw^h9A=Y!ez(x$Z!h~tBbOt1u6tSGLz=l_Iv5-j^ZrXh9Cp?PaBX{>?*Ba>z2SfFvoLnlmsQRy>T;}G43}}&3}C6%YeL_m0}O=@P2UVJW=;U^mW9jUn#@$t4%G5g91ib@KvHzDy16Fug)K*N|==4P0^{j8)j-^g-lZGwaICcFp9#Db1EWX(Z%bS1dOu#BwCUQNxmVS*y^$^-Qt`>hY!momQS)A&YU4*jId_k$}jXXg-7Sj?lsJ63T#UWre0=(TJPz%8POh>Y1QebKpw;N#p}WnT+T5ED%czPl=--o@GwfSvUXFIWoiZE6>=ERoqnicb6`nSF;m&*A{2V`JVf8fY>(}GTj3b`do>1IiQ`Wo^weSdDku7>FjR1BzQRs_x^~WAJAANclKsiDir-m8HvzAzenUTZl~{4I6HXuR`4M{ajJ4vSET9l`FX$nPZGvKzi)rIWtB6b($%rAupW6r+o3O8hu365f8N_YBmRgRQBQGdAd8X5VwQ>gDz*8LWM^nLNc>2xd%g_uTrsbp?6X)7xcgsd7_UV9U+DnnM5;WKkB>le&6Z$`K#WwUTPAWb9fdYO>Q?sDqZ2;$I7y>tN%WoU$4kVe7gVEE|O?TgXfXTu{U=x<#k&wi3sW?LAGqQsP9wc6-1tVU2QrLW$TlsOy@Qu8?svH`*fmyF;52LsZNB4q>_0iG?eZvs@27KO4LaOvt=>r$c)pmj*=dZ#fC{)@H>Qy{h}oL6CywP*2ZiQ)oc?UYR7Y6n~Fh`vw7K|7~<38&2)YhDK1-7E|dd}4{qqp=0?svZ<1-cV9!AkEIhs^1J-BEJ+IpTt50@gI*90)iTvuu@1B^DkYGNY&gd_&*bZ^1EiVgID9d2zD2`|&4)o9TPV7`BoK=qND>#KbQ#6tCx{*B#ELzsx%cLLf@|8vP?VG}R-CPn7>Czj%;`{Q(-_T8PNQcwuCoYbcFzLW>>kAu7WdLz~%Mpt>sLpb+vb1I}>U6Y35r?gE4$-ZbG8y-Vs_KYCFSot19ak0{RD0E<5P~?A^oeltMrAS1bNtwFy&QIvZYUxF_BAfi?P7;vPl%b2hwNtk@H!hU@5Q@ss!+O6frCgCD)abE-+o2rcwkCI~O*@jY=5`AMep=VLZi*>E~Arumr^*7p_0EPB+iKNpC;BFhR;&w(XN!BOLC9@NO$eM&RJ`oZMPu&_dxd`4dqpKWL_eccvNrcnUC8@9WXiqXDDzWjRe=K`3ztaGu_3xA(-?{uofgA!nKzri6asO+5_28vA9u(eN?O;L4(>n3n%duBoEj_36YS;Bf{L9^ZR|Q2-*3v7-O8r(oEvY_tz~MEN4Z`KV;R%V1;+<)>1j~1R&-3xQ99(Y;^{JSs8I_4lxzC^aq9zB@>^kvp~k01Tm@eO}`MXa-c=yN!J5#t@9x0w2e&VTatl8=ls=?T=Y+c>D33!0l>+#21_l(%;H%j7+)JXkz`RX^XyK!Ct=q|VU!ES{(f9M=Id@QX1cq%NuhTK9PW#<-1-n6a|Di5#TB{PBNRPz_tr>#pW1V$ZIAbyvN{(WJ*6B%&G+hXxod5jC)w>C9@F35tqY9TYN0QCPRGBI9;qB)FvwDdEG&({XlC&~wNq2=4-wl7RPL5w)a*3V<~aZ9hqd?9(;TrpPZeCV3z09j0V?77cFN~^o`p;B_*U*jg^QG!)}56yQg0EMXYca`;-?x}BV^Q!w>!02NbzXMi?CCr-b1oB-4sm+#IDvk0TGT8o{%aNxeJ~a!qCZsJ-sEvxDF*_&6heG-(eDxG9^r<$P#m$AW8HDYr|a*$Gm;v4pffPSQQC<3ysXh~;OEVUn>lW>V!x3mFm%Bl=0keuCbX%EJ9L|&BBEb&1?RoG;CgPRDJB*LS{`&P~9>ggh6{IrZ!^QQLeQ{bo)cBv9G+o1VewBDxCPk(IK21i}|WJ#LNbV((eR(WMr#VexVLe1Z!qFU)CWq-XTkde;*SpoU>tGUY;i62ST+#(jQK5ygP)bjgCl3?`>!?glmwkIUJ!MN{ARfjHu$XWsul7pvixXf#`-))pI_%_oF_!ugGo;wjK5G&RA51T*j?4)eSPvFll70EWjYgopcd!8;3(s2d(6``Bs|1^uCH+%jS@(Q9K(8ZE$@ZcJ*kw`!s77Bss}%bF)-;NRtM84c~A^KkOEJvB`C!p~K2$ogjGz^T+DM*2q)hnB>_l{c(%;hk%rGFK&&PK)H_vj@5Ipi4!mqkar=VDul#$@{0TWq>&744QQh$mKJ1(bvC39Ef?ll#&mjap(9JTta^3S0Z!SMzR2=drEZPsGvU~@*aN%7XXn?!Ll0p)nQ39QQ3RNU?x0mAn+02m*{8xalDu@AB2u&%ssC=yYA|Q3>l0=CKQ!x5r_GE;}i=okr{Om{VV@J{}ikw1F?=}%@H5^tW+;qLV?lT8Xd(M)Lrinu|80Ik^*GC4Z^>cApa!tENRsg#{Fz-ANq|8F9Tkk+dzeJsYja29dW&|e$dH#8bO6Zw#oQuDz1yheZG4aHx$G9Q^#CM19(2E_2GWBFee!Z{qNJK&`#vXPwJ6@=u?;1h4|e1Eh|J#Aj8?eb=sLqXeatK{TU(yhw`_-udgBwoo@aY)@xFL@?&wY{vD>i9{LV!v}xeuJ2|y!_OE^+$92vL5x)*yk5W{!}>D*uKfMA90wc(hzr(g$BN9O4n{LM;w;LaGyEwt{8%DbE&T%N4=4IXWwVmh>;=4Sv_~!8||O;G&iiZC&NZN3meIKXqUFMJ?m6X2FCn4i}(=r5mn15kaa`;JIgdr2p!l@6o@~^cYU4^>V#ihwwklRh6MQR2;x~WRn+)w|^?${vqMi60vz=tdK5@rA#9{5d-#5PRpum82dYil$+KGJb=t2r3@AUjR?AK#F--eHGJr#WS`HRXW;XEN|NGg@e&})64jySOS7oFR#M}v*&_t&m+MH~X*2k+n{jd6ceErHert=t=mu+$QzEGk6(N$+B#A~$m~NccEj`0R^z`xW_9`|i?l$YiN_a0ul>A_a(k#is3uTkVp0qAu&GaADWoO^RM<_hIqn4XmfaTl#i0aWUH8oFCcK8AO8*KdcN-xFT-Eau2gBVZ`64a>On2)|T94ySs4mZ3`@5>Q8;D%@A%cBEy-*Dr@A&Q72QGzVT{1N``UHJqIs-Ks(E1bNN6GJ<(pWXa`25iAk5*|H9Jo6MY2RGg>0rLPJ@1&h*Cuo@Z^SeOIcjX)Z;YQ~zx>G7@^zTdPWH_s%-sY}TuX2Rx@0;lMPP}P9+P9IGf7O3PhDCqH?XnEfPV~jm+D3utnkDlZ%$fQxx6O!?X%rx2R>lsaeIi_1?CSw4a3wn|h%-gIf8C?lCu}q@8@yE>yBF=l^8)VAyrcV{H(41gB+*XvW2SVM{L`KOi2ZlyG%cNtr}Up6@IpJWzet`(hJ69!Y$-QUpHs7A^gE|18GPHG#Qmh8UE=;LSs!}bQC%S_$=ikY)w^qXQa97TBkh7Y8w>XPBl-bdpug|r`Xe_rq_NMSi|=cnLIWzJ4|tg&K2P+e^H@y#_wTOwJfSPTd6@Pu?!=&7O4Kd*K7E}Mbp%^7@OKElYPhWwQorTaaNV4lo&H86%E%I%SsJ{O5H>n`+EiM=#g8b@_j$uMUQ8DCri?x;=M?Y_!?GtovxEN-&a&~Y1j5tt-oJz>s$RNfq{X)<(WA68f_x$Kd1|8MyarI9Shjk|(2vM5o^FQn9?NDB{lND+Xe4)<=qeTZlRqsW7ER&~C4@XeokKXz{7s?QajWUheZ7ftUOm$Um$U+>5{sQx^P@(>WQtJ6#h(pDlI==(cRM>5Fd1fpKdG#QrSy_wDpNT$hKhL2*C-Rav{w@YWZ`f--+6}JT3oXjYh*aw+(!ij%giy<@48NSc)@Fw-aJK^^dztjDjU*vOhrucY=OI^v-f&zZ7H|1=ZbjyD~-nd`3o&rR^xkee&efp))*kAjoP@{i<_KQiE+im%`+Rd-15V7&craTek+qZIt123PV!4|c|p}>=fgXLDer7cg28GX%+1JQ4*&%ZhyNaxQQm%D2wH=w;^=?w=C3o@v++_g4-gg6ko`2iF%taDIbQK*6Tne`G|-U?74dWJ%y7Blfo{|gN@{uFreY_*FcJK7I&taN^`fC>h0{0*L|X3W_?OsBs(Lg)Ws6fe2`ddRQh<@XL7Z=pe?^NSA~nd+nn9M`<1ftdfHb#YZp_hQ2b``qh`!D4c4@zP?9?`3Q{m#PKGV7FuG)1@cSPVBGp>HK+ceq3!G7uxx~hs5-skzv2T=wX*k#3wsbw82Y`0z@3PkVd=Zn>U-!-lBl>x8BGzafpxPr>)=Rm8jrZpS(q95P3pPZ^IqFHY!v^m!DY7$JFO#`27!oKpKqM^#`ov#rY%gQ+suaK?yu#S4*mXjW`@=Rinf-7K3~SO>uQU#_>k)0gkgP$?z!YT<6k4w2$iAMVis~ebE&vwPkip{q?xteYrvB&kgG~`l|{v@qteA(gqz0oZ?JrpJwWRx7usg{YxVS4!frn6zpT_`)q6!nSPQAZo=F4b(JALIUCM8E)t+I{5c2ve|Gx*=$paS7xXx_t;O0;m8tKc)Cy%Tt|uix$ZLr%Mcl5XIrdsL6*KZrKn&wGk&l(Ln#{=C`9H3{Je;ccd%GxQNJu47QX*wYgETIosFWf}MM-I(LZ*~ZC`BTrSu+*R9?p?6BpMVYNg~mN3`vn8^zP^Qe690){h`Z!J?*p4+RuL0z2+y~$aAIySlg}KPr>WG-Uji-h${^ibB_N?!E!CrhaDpGVq#`ZzFM+@hEOrVA&bo-eCej|dYSJuRL-;>m#l#JtYy>9&5kqR)TWwqJ_+S^RyViqiv?}i}0K?5ieJB_FzbUtZ~R%#LdIP^p|kw@aOSPOZG2C{MxuLD{p?MpioL??G}-FG;Uv3*o<+ZVRieo^p&F#pP{K|Ky}a%wv!*`)q--qp6%vF-C%&k)k886*N9ShP_%~y`PsD!%Xj||=Xj%!?3NZsKHQ?U8l?J(@GhmA-5!1d@Eg0>bAl7{D`KzCe9Qy>^7WA`lCaPDxRgOLSCuG`HkMuD`vCFXIx(N@d?{g_lxrU1V|vcr{Z>uEhx_Mm)xAYLXyLpAKe_LlKWM;g=_FL?!P}h-dG$PxT66;rgt_s&8K*ZvUWhVM;I`B!+YklevXF%KyE0Sx=GxE{ngA-(iRAUF&cC+s5f5H9^ZZu@2;E4lX7=@()(^LL40Rmk(G1>1@Wsio=f;4PWn&TI@0j9bYG}kBI0vYpY028r@?aR-Q(5eh>wHN$cQ8cNZ74#2=XX$Ki@)GD2q&dpgae0!4$_ctw;G#d+qqWBkK_-bD*lS1P~ClCHt-m;!_*X|9w-*gKx6upWTf?JxJ=o-i)STi1oTUD-oVR=Fa?E$LZM}OI2I;;kj3)QZqB{8YS$9w*Cg@n_XEtt3|4r64r?io{Ic|%#mkIY0z_9BCQA<$@zZ8*?`()`SpK0l0_703d_%_(&W=z{IDW8AH2;t@R3<3Wa5!+kWa9#nIWm_rHYqE6RGT)a?g!o(3cQrJA1y&SoO-VoQ#^_VIi78!av1t`{WG_wwewgY_B6i)<*=$Kr%<9l1wVXaD(wZRzwA_vibBjOVSfO#wTK7I^r%pZqkz;I*f*jauCHp?X3p)~>eIF+QtpU1T(e$dznX?OSLf%2h|D{_S@JhR>In@oCn^RS%={l-wSc7Ao0>7uKeIgjy&KA>O?-?}!W#y}&J7+d2*NsR($_o2gN1Qx>ek8?;XYX;Gv~OUIv<8aMz0xZi1o!JALg_K1uNrMeEt3b^?T)!A8W_1q~N%@qWzC3#OXgi0?!*11beA0$TvcKY+&(3j{!79PZ+#rPZ7#zbyiVF`fgg-@7K)^{ZVm$3c63$(U9je$*bcj%4f!eA5^Xv1Fjo(9PUv{rhklgiSQ+PcTeqsAvDxKo!F69hw=%SF=()aBm<=1{~I6V1IaSChtTm1D8?8*bZ$Vok$%?UD_D4Uy9Iv+bQr`*0HCv5O5KRZ|qK{=0YXuKpr(VI1pMolvHM#J9J-Lb;LtmJQJ~ENO0*Ogo8qm{N-0<1w7QA7eeo(-d*S`=35!z^}fmeE27nTSDaOCDRVF!24{o^Xw+X``y0hK6C>g-en9w`uzdQGuqd0wuyrPNS=|{XOvIXFS}{7{V4FSP}k3lM1Hbn5Paz7_H)}_ucw_N{<;~)#Ru3F3hI3Gq0t-hwray=hey*;4MX{>oe}rFr>eXoj)oem(A%XV^PQ6~WK3J6&DpI%V|LU}6q)bbl@RLpmJ#+n+wu$LnQi?n_V#5KevJ=!Tyz`x((8e(I+YQ87-ieMXxBnq-@ViCo53vsj9ohRer?LFzV-K_7Vp{I$^&aPhDj(vzUMQ1RX`nQ=aT30`WxbEn}68L-lAahp=)PijsQLq6j_;_xqtQ#7#8mu=4&g81~-`)0Y57^od_Ut#-j#3?1Oq)%lG^xGXYpj!n0<pam^cAj^7MbJx-fMToD@Hhn>xD7Swdu~Pd)9h`vvX4htor4J_@sq(-m`D=VNRmnQt@ku$2@)WYjmjqNT2)n8Hkg4u`f8i6XvS6;j5X5---A$Lpl3>>fpNsTlW+uW~YT3unMhRi#07Eb=JQ2W@f}12^Li#aq8X9!389RZkY!XWp4(^)T-LTD`oZX9Wese;Kk6&vOzN-WW~6H8tP;n_r+D0z4GeZkAK9?fLQr8%5^Hy4Czmbe}>4kyF-cluxSm(FSYod|r9^tL*45yKaTE#74;iLFoM_pT#!;Xx~ZJKXcNK)h&4UKZp8}-!u(P|0^Z+&ZdwGWqd37B!`JO$P@E1Tba6^Uckc`T8uC@+WhgN<#=om;QyUd{OddmoO!l#tSQFF)jwC;&~x}uv+Lc`nA<3aSo5oAyzD5juo!9*BNFEg;VCcGx=IQ2E&B~YT+3wjGWQlrIOkFA2FhoRri)hfN*bQuT>nW`4{=hblzoo|jeNFy^c9p3+5aIrOz(X5Zj{6EYaYY4aQ0yNqu;Bt=ZW+Ke6rLq(TwfQix6OZyew&p!Jc{+c5}pd-$mRfB;VuOHGXfuyK!iDygfPoBDIDR_Osd&f%=`jt)aU1It5m%uLRYaB2MBQ`#UK(qTMyB=O@Zxkb{no?RpxLOOC#1jzpaF5!(8K2GT}n*J$KRH*}Jl%`6zmUVRD7qftJjueZ~CMyTIq8&N(kT0eYi_Or0h`lQsfiHMW;r*h_h@r9WvH}dxaNkQ-56Hz|jUPtgQtfGYT?1D2KLaQw=6<2Nf4#Y~3G-gI3WR;bPC4Sa#Ls=c&Dny29UsnD*0v*WIq2fw;&6@<*4b?-7x7Ojt@lj%LqX%ADbn7lh=*)YoVRTw4P;*NqGO2L+2np-Rz|}mO7A_`AYPxd@0x)NXV+_A?`jz;!k4%okYOR;|HAfjBL2FuIxm&B=Cg3CZp?ev#fXm@U@M!H#P5x>@KJ8Uear}i^V;sV;=cN5bN$f-&hAr_em#yi8~MqOP@9!D5fs?;JMO}pj<|-{+XZU%6l_0Uvhwj{#4R7DoK#ywL#f$o@uo3|PmFjyTfLYDE7d!v7Ky|+moR=R+FKdOnAQAtW;621kuu3?YZO@6vtjD^>CX`-^V#b^uy8!cOJ#91;v^qvay}m{N>gL30CAH4v!Plb%>R+h$2cjO3#_X}LG0Gwvs40+*O9p}yY^AA=XCTp=V-)7EbCesUrIqw+O}s8MdnS5kJsDjVMaqlBR@VR4eKkr&YVijsaP@{MRub5&syu$G&S23-j$SOwDaXoV2sMSIV8k+ng8n+;{NLAnVcfH$5pfb1{?RTFp7W<)BCdYaVNrw}1zUDy$`?FAet6DzkZQ}^ByYR2&`zc7X>Uek64fPee;!ldB%dSucP`?yzaRLrS)PV)74=<_`;bS)TSr|UvV{gi*L9~XR-=5xPlYO9iCy^SFB`@+%U5njTES%)5zGo|jzh!{=`EuJA9Qz$EW$@x(yHM|8BB>>Wo7=L?9dBK~2KxUcv@8g}11@!|6=ln+PS#U|I$kSf{seEI~$Ke)u6-LZ)QGB-Fm40(bPw{TZ217mL0nvc1H?-$7vxE{y?$rI1{fjo29_8Aj)X!Bvm@a`+$n~-M?{;IIppq39B6N+Zap2B{2B#-(N_x`Rc^xu5sFY584Rep0MxaVt68gdE{CwWfK)w%ana!0$j2>+Zr?A!!m_c;wao8~KpxbY#&i^JMzxM;5bcFM)8eV_Yh{$v6)pIvHM(5)Gk^K-f`>Y!ugnfx}asQA!zz-$@5Xj2@k+>q#*C>DDLn}{8SjQ(b8TEL7%fmxbawxc5{nc!%$XsJns~P*YjG^I3{En8oY!UyG^eM%B&JI%LK3Mr6;z^IT2G;+jK{iwWY_tyIhZN_AJUqmJNpdlxpO1XNa(lOqr5X$F{kk(RTcg}a{}4US-np>r{Ww7u%I8Mu>sd;i{rlcnBiVBh;>1r^8Y_UVUH7+Wsw2OeeyIJS_7)0G8}qYAZAP9WEs$UFL_mSj>*R%>Mf`79-~8V7Y#7IfZ{02|oFp=r`LUAS=l~ktxqj1V6GMD&K=_w??Hu1Qw5m!fLcbiD-{2L>Kvc!RCE>9s=MC-I9dVOc2!68cs<%1fnqezu$2PEFym{ivrmrIM{KFf0u7EF`$FY19@~b}wWq-df7C`ja=E=+Nq1?#4HaU(zlX(jLuZqlTzCOHiE@v-HIQw=Edl_-Uvz5hYaL8=kq;VecvN0K-)OXQvW!spC_eJvSw(1PLE?-Z>9FC~}3`IP4XK5-znkz3vUJFKgX7zw!gEQhMXy^=Q(Y}b7VIcO?yLw%ni!V_l7zH}azL(3NsizOdkxl(FK*QN&xzT<;Ek&j*uFj8|1O;>7>l)g=JZKe*x;;s*a}&ljsu!ntoVw2((BXFq8*bfZAGfBUWJYY;EV6?43pN5R@*();=0h>x>9czDuu8pynhFS&@f&+LAGo<{?jU)MAMc~qC%im3R74BQ$Yc;0du;*E0ucxRg!pgtxH-*pc0?j5pnrX;^EY^15;4-vm#rk?IVmJf>tP1v;C6nPh$_bEoVOaN0QO5D@WA;0>yaQ57}pD9Sbs3j>m26<84f}H`rlW1V1CEo3yg6I6FGo5~ie7NrwY4oa81Njp99hgT0DFb>|h5aIg|4d<^=vZ0zeF5@>N&BicM@2IbdeWgdc_!+|-S5Zs6bxWtxW|o48ZlURK>7kHa{4IW$>}$hg!L(sZboNrOYq^$rv(*((a58oF)vcb#PLBcrGDfTm*ai-l$LCRF%=YC8#G^Hjsoiaog9%j)1+Z#={CF!cIH_7a$hy>{=+h?sziA8+O`uRQ@m;T5`OHO(^-^H;Q7bLbV_Jg?Pi$Wb{q8_(XR%^3~XChF#F3H!dUGxPJ)$zdxS^^S@&^Rx~0{Xbz+&y(nhE#-@9TrYXwj`%k$iFZ}r+t9QiQ(jMzFqV2WL)=m?EN5!dM$|7^n%G`6BK0cv@eHvG2iR2A__aE|YI1T1*pT92ufO07C`8jOpZW_4bUw2{%;$6A@TSjuvH&T7)kZ)?pm&Q)nY|>=Hz}Z$Ot&wX`ZZ#t{YMgiCNatJ%AIet^^6M@_zU_85ckZ170_gdnI%Cl@%riW-<8tI*mIB%G5nE)JTOW1z(DPTb!)>#^#1ekPjz#jaB>)8kQXIDxh<#`7hAiLg~??qHIXwBKU(y$>X;lKPMaKatr4mJavqp9gkQ#oIe(uY`uYIhyUZo?z3VdtLO*J18_MU3zSbMxOB6V0&#cbai+b5_kZ;k5W(tNsYnXC%1>)x6&v;vx(?I5^w~iO#lT+&-|GdXNcegJq);FPi2G5t6oNT}V>BCpWL%e-Yp8MD=P9GU&ZPMO~_*MSZf~lKWc=qO(xQis>ZeB(j=Bj)k{~kGm^4v1|o_O;gK0KefXV7O!#MKi+qCYhYAl6wma{gM}Z(FZieAC6*3#k{Dx|`iX-ZGUtV3OWa@O6jt8iP2*|GZ9|{9+mn#|#Zl+zml|=AHR#PF$v;U~fu{he#gga+$om!qE)OAF%pblNIuxL;9)yMt2$5vE0G=_GDZiHPuHa#D=r$yY=3!>O!6=_B(3QoKbwBORRRdq@$d-pBPzW^p6jwtE4p^Y{m7-_hsM84M~NDj&tAYI#6zFS0rW5bfRF>^^yE_mB`;n-xeuupT8(AERd~5e5#C{M;d4Urkd)``rU-M@p+Z`AqQx9lQkhWs10$k3m+e!>7-%(v+?(gdJtdpW8hYc!*)oe0-0YlyHF(GtZZcAzd0OFJ~&M3`zYjTzOUCr*&gSf@1GZ%CbLEAEDV=TH?5`Mv!`ZhmILCgvZ*F|t7s56%|0$K!W#>y^gEXdXyD9N`ZSIB1ZTBZ5)O>8zpjEv9^)X#xMfENv#|By+9fxYkk^qs>e?a}mcMZsw09Na7d|vu^~>c0nR{Ovfq2;Cgq{4)0ywgH!-wjph%-#>#Yb|z&oRIT@k^U_EOmFFV9S^65$BI1-hSM4n^h_&hoKUe9^{MU4fc-@U%=T-wr3|L{ZmAKc(f_^ZdNS!e2x5FE^HOaS5zG5HC~;2e{F8){K!Fk!ka5^9G`JKq*iX0n4U=8M9#08oCsDpFPMKzgumU6l}z>H3+tDk>mlzVzad5dWWK@dCzyw(aD7$7gifmW?`6mbNdEm*Q@VF9p)=}1ZFki#_hV>?&#hU`b3#4X@6Pze$qh6JE{#+9vH*DkvoEatu_XiQUB}`-wWGf!tkN=dJ*R(v4zJj^Ar$o^p=SaeRyhA?XEoNbk~y^%$*i!CpOHwPqM%rlV={C3z4JaKa2^Nor#*SYhk0Z`!X~WyCUrmtzbGJe19KN6AJ8#g1O@YHAoCjscq1PeE|!-2HkyW;MJr~l3rG2o@ac>ux_9165XxuU%g$4OZ5ikYSrh$Xm56-E&kF`p&rDx*>>u(;BPqFoE*30ErN^u|u@~h-^0+>fupq3@5MZB~`|rnU9rWPCz9*T^F=;3V@-@3v1j2abf<}~sd-A5xt<@B8=D2o(E$aQ{X4=OsXV5_Otw}uU{VzAp=c+}}K!)Kr$!zbSsJU1FD@eAvj_6MuGaJY=O_`{5*!Ji34#={7g`z4hHiBJ+s3uQ_~+07xC)m}J~1L{E$?p}>$coVEh$_oqW+7d1?zf#l^?*Q0(PG3@+_(Lpp!4@`xHCWw>wj7V#;wj>%Yg2fkDhWDMfy6%O2_JbU|_0Q+Vtcz$iuyCr5jG}W}&cABjU9a%8kUQHAeD<^(HU6aR0Pa9(p&Tm=8tY3O?$g|OF)dyY>p7M;w+{dPll)YJG$eBs|!BKwUz*XVXW2;)c#aldhIv&rO7g5Ldq3ip+BOxF>^TNJbod%0`%(W`yeaXD+IHIqBXLdRZM(Ygh3arNBT#db7&d~v{|WiH}Gj(>A#VLkp&>8pL$H_a_bd^n#0g@*;7V_&1(9&_8THlGpNkLJgbXYM@bbK%Jz7GA3jT;V8dR+df$t$TJWH`|HyjeJ#lM(GFz8Usf>Oix4J(z;A<>aQ}+uJ0@ym~>Yp-d&RTYm*TTP7kB+@Gc;3AzS)3;RX#4oEG_>KY}=k&*gJ^hy3+$H}aoO*?`Yc3~Cy1i;C0W@UH96kBLh%klsgw4c3NH1RFszg4?(yIuHj?6%|g{X3C&rR+alV-z5Oho^$XpNr(J$?B?lJ{d%V%a*@UhJfce>Hk1+e3<0doU=!Jndnoc>vS*wS%c?1?@pezK@Vpa7i#`eoQFJtoR1!xnBMoR9eKj8M;Qh_uNWu}*s1ya1p1?hed}V*_U1LUp&#aLzP;480&brVGG1Koh<#(o{dGFgc~PVaBJtb;yXl|WIUaIp@aOfPkS~!uH?eIDN{88SgM1K}8-$^QUbVIob^RG1cz5Q_HQEo{&uUB_g^M(0ll?PBhWPfWv6abl%<|Wc^hn$Zq9#OES_RyBORw8pwpO3K6NHv>L|pW6ES8H;iw?TK!P3*fGbz4L=@xZg-V!}MPQAp1pDWM7fK);2dN`1SIN4BrR&%;mfuztim$I9%Pgv(N_dSh>5mU)gf!(m1=-2Xzo9c3HzC8iaOI5Aw#jmRr-Oa{Q|2V&m)0Pf>2S@(AVY_#BVx(`43DV4rTMw5k+&9huiSGl>H4Q9W-Cd_nv+UtiixiiX37wH%K$A%2H9sw&uvdw&gV9#7~JxsEUI@yq7kctnLH^0deQR9EU8Vqm;(zX$~-#J|ZrRvoI#0_nG>r-3;6KK2QLAx4C=PPN|}2_i0G4oopT>K-|#n$#!201`b{I>lgDAaiSNCn;9VI`Xd93V-k5$X)GKJHQc!;KqMY*Qf026z=z1YT?T`T5${~I_mxww020P*-y=O0c@c?!4ejB<<=Xo{e;ecav2wM`f-NYxaKqUsd%p+|^!W2~eLN+c556=D@lB&f-%lDqgO6TYp1cfRU)8&Es)`>Cr)#n+&TdAWDY~wxCdNQrEG=^-PlTs6nz1_983^*fw4h)C@-Fhb)|rLp*G6wz`y6qf4?iDhEak(y8;fd(?nK^2;-PyT1Tf|8!1NE}k#~`N+&QCZVSm(wc8o)jIWLu4X}G+uc8QHV@&Pg@@^>2Do3AK`=lry8g=UB046N{aRuK3L`I23YQq&MX&JMDdZIR=lzol%Co$}r94E)g;J#^v{k@;Lp4UcATVtdcM$q{|mZ%}x7BcJA9=#?RROC){8*UbA3t0PP(H%`ZbSJ0$>BubdYDQ(t5bZK(a@G_Z-;$B$@l-TMIf{*&nSlVttWGpuJ%xHHh9L%KTW9LNnOu0&fZb5j6d>NWKIN;+n5Bpx4vL6>NWDaRGK@7KdHABN21)kqTU@E<72^!W{bN1wTJ)Gg?)%1-+zeWTd~)z?`?q4_Y4|c~ddsU)M_nB)?1RcaL%ESYFpZmg{TuzpAYb}z6ZT=_4+f-V)>iCWhw@xFzVx0$1PdQ7sZlzfC{NP2ZlD<-2+z`RLb;LWmp)R^+sAJl?l;2McMnbl;>S96S!6z7+|t{b6a}jeW;`ldjC^LHy4#mm+X=LOX_yni+Bn!E9^>gWRPqiDb#z?m0Mje~=W|DDF~Yp%o0E~}kp5iCX$dho;#TjSvLmxn@?z>&Twg5ZoSt(ObYSfJp&a<-Pr;4710hRh?Blo!)|i+#Xc*mxok&t_d_;ah_*2B5yeq{0IZ)+zYAB%|?w2mFXz>^!=ZWbba|1{LQjvc?jfcS>LVov`=`UD<-BNxl@tE2m}Z=DQBKDORV_4apjKIk6|$^WKI22V7v;-&yUrkw>Is;-PHZ9z_vJ?nUnw#_cjwPc?SD5}$kG1z?7|`R!~ESlcdPkyJ{;Bf_QP}Xkv=@*(|iyALO%4jdK~d!$KgKQ_pNyK5Pty-vuH7RZis!thfJG(No58NKUX9w%s7eX_L})Gey1Oz;gZz78ozwx1EF6!WEv{C_qXQLfQc>t-<(QdV55Dp=BPH551IFBl)}K2(nWJe)gVuJSH4yInKlbQqz>@bC!s&8^V~POn_(e!{{)Q!3zW}DbE~c?%lR)-wzY^tE^rda)h6gMRSi2(0K_2~?Z@)u{$wod{9A3mTzJ>dT=wFpl0w8g!v(o>QPvHWulMB~2R11K_VdNb!zixx8{iK9}w9wyjg!;evZ-HxRVZY@rv2%UbscbKs_C`R%-tkkkgCkJyztNN5{aB3=&b`(6h)JFZOM!G{2AyTrm;v{OhPNtQvce*=PWUs>&5R8X#%3d2aFjY`}Wx!N{ZEf`->Z}N(VXLxnXQ{LPVPrNPV9u>vmD=O4PG%`LZl8QR4L`C1S71+WI~WHsUMr(91z6u$&1Ygn(I-X_LIw0eh*=Re*5iIzd4BeXWufCOksiKISRIm%-wK%TKsK0A5xn&wdd>;;h%4#Bk2VKh#KJ{H0cvvhhYY~TGeL~;ner}=TgGp^=PaQ)6+p9(ePKU-`@J;@l^yU)A7BF`at8^e5P=s4VvZg~lDGS6k+^7Q{e(VR{%$J6LxQpM>$tC3_Z1bVJalKj{Q}VfqXvHR@0^B90l?@vYQP=`o-CdzHp?okpic8f4s#-`W1V5J#~s%MnjY5ezyG@;@-LAMyqjlF^P}87MU|b<}YlT$(`F!zGI?DUB>Z{aUPvd87LTkP=DiITz_YwIA!j^!XCf7qnaHM*VCV@=x4--L4{3!Ym7zKZx~i2#o4)XelOk*9gElRoM?F{dS)tY>b{)g`WgA{)4+yS12+m5jQWxzBU0C_e1^<;;)+6A=F#HRO8bNd|H@FF5Aa*Qc&(!79ho-nw&Ga9#f|+0Yu-56N~P)g;abxffey{dVK}l$cIhrkS%N&UcN_5b6JO$=Ku{PcjuQ$wWqOM(WMgf^yRV2a#&m??QF1Dw&H2N*-tm`)v}~)e8E+6TSDN#w|5=Vt<|YNtS}Edx`(b-J&V~i=&mQUfY7p<=dElQi$3uA0Cn`cj;+Rs3)RDyb0{DDK^>Laj@+;CO^Mx!8ttAg_kB$|YcMntPS(7yE%KmVvTjOFyK_YA)!RyYSFeQ%7?*OdR_M}N`pwEKc$^|uv#xbfjYpuxV-bm^x5(f*Q*~~xP>KD$PA$Dk6S+AYAcWpr5`UA-Vr!#pJ7~K6FG1nCN9(=rG>!C)&uA}SsNMsledD9X)Y>9au<+#IA?mvPZNbWMhPA3qhYo0~old0qRBfRF8eDDaLrEpAzeyk*b2b-s`6XegaL<=)Wsh?{@fr?~40E$l1)T*QtL&M7frU`15vj~@$Bp2UCHRmk-A1G$WHbCmgJI@*(kaX#`lmA;|eg!yAr{;TsHg?_oQEv~kSJ$zw3%M(}JZzL|b`iB5WI?~1cC^zyu(1QZvXDSfM%Od`ZOzyc0=hF9}y>R5>q`kMbY4D0p(tUat@v`bCEeUbl{?`x(4J(oOHMb4djbMa+RK5rg+>|@N|KOVpaP%kdus6zCcs?v;g>lT*4&={d&f;S!esBK`SClg+=Hy$|d?4=Hh+>p8dEPHR3xxY>(ImvZZx;GlETo_`$a9hNX5?wzD|&uxI8DJ0gD-BY=OgYCZ6f6!Y>J;v^qs$OB5)-)U9^;$#~?)}SG1p#GLUClM!cwCC|OSlP_Hn|B)VxAh}}bo3c8@X;B!`x@fJ&n)+j0qcdl+qxokzHQIbSKm3u0_m$dqzG}+x7{<4FYIek*n_;WH6-eH(QyHEXCC}b&q1C^;)@}#c@V-riQjx5d1=mtc*~Np6qK!PSw8R!;wSl`t5W?a(97I*!er=*oT&y#=eKC@vN^7A$^X5og#EXXQc-G4G4aZ=y-RhtiI6)aj7?neGk-rJ0s0-=33cZ^6MlKhDeA4cce|sN%^p{M;LP>HUY_s7KRTSn+*hw~HC_y=^f$nr}6^^E{#Ir?QCuO-k3c_-+pca`R7ZOYA|t|I~#(sIZy_mpAecbxz~_uNyljRwl4Ctbr?+dSsC=eb*YqtRBmNvDw>{=?=)3e)kW085qle?VDE9H6g)$>jzQOLdr(5z@MJFFwPJCOUw4uiNC+YLhZ*KjWA!FH@9m?e8;Jkd~ki4J#Eu1pFUhSv20h#p#S>h_hZ#|>caJ8X~g6&3yCOXkL=Svu;FrZ=9{Uts=Ht092dlhhfdJGMx+^S?xb)vt>z%%GY*gqObJ;$>HD7Wh8@nvd$43PXp*LTR5-b!v$mlNak&Z&@;6mjGOI_v6>%{tFQ@Lp=WnIz8dv$b#@JJ_5LUURp`7nKI~U7z&#e#r5S(azB)nSMCen9M!BUL^n>pRK`H>U{dvliz_9CCrOnw;26Dwu{DJzAQxp=~pLafq7is-N6;Ut~89_a_suW3799ZdV5md=`tFg!KDoWA5m`prP2fS*D!GTmQfPSW-PUj3Q{+F&*1RYDDV(0Q-*}>98uBFr_d9AgA23kI?mASai#*ea*>L5BBMVQI?4G)RK%N=A``r8(Wj@elU0LDI$d@V__if+zlMid#JMB|niSW#WL247e2w;kHvW(O?tk)p@x?9&!uxr$w(;gyqlrGLu58{$2NKwBg9{djZjFDqQMlokkHRwIi{1=M&{Fv_F+YZnmv$mqnNFQ+$=X=cAeTGK+i_X44p0jY`D5Iyx7|6~YYi79>xpJKpo7ETzwDjnpD_`vD%GmjMV!KCM`@rQPl^Mt~U*1KN`Ao<`smod8$Cvlg+@f2*94UUwUhWzB8Z;Jg{9}3)Uc3mAY1aZ4P3#u&NQ4kR*wOH*N^2SwhZL@xx(2y6kxjyj$;2oixiRZ)RIoUmb-ylxPTg(y!py*XS#)Cl~J45nglvq6vB22n`_x}*8NmCtcwQ@+yPf4!uRfHT%WpXH3hzs%MbA0AWr57U*&k_FiydE3_<>O)S_A#pFLf&vsy7^N^8gYm|`JEq8DhyRFJX|0}IOy>1|G{OjeFQ~y|yNtxj1V2eC0Z*Of&yQBbqNvBM(n2kKDI_bV_w;K;U!YrLfB;a+7HpdMMOy$9fR}ZLo5x?lupQW#oIlfKe%+7Xr{rcQ*z6V?>ApJ5|KNaay&HV&^qI&aqr~L183m4q7n=$yA&6&~MfGpXod}o*6vdq#W@*k`EWSkECFoL)u4Okvb-io{5UH11UHW{%_8?D~R7)Fmgy@Ck2mO#bkDl!26Mm*!ZP0oQCKP+eb|jxz9_|<1_4LFtA$T{h+lguJ+*>k8}LD{$t>lcW7dPNMF0)F9y3xey|W>x@|y=NS+?aYx0q&V2#7C1xDM0`|wr2SN}@dNkQ}P%0nYJpr7Q#?TJTDzog)3M;6X+tN1TZDa)&Gy>XgbrRPx=e#G6M{2&YG9g}=?6OM7{|M*pNz=l9l79ukeV@CkDe=PAFdDR#!7EkT3bo)mdOiG0@VXHU7sElpD#1barBUBcS*=yCED41?p8bAjkuO{;?X1=CCEFfaSm7Bb&{`4ND3gYhOP({D0O@KEU*@e{!gAy)X}%)5}|3YquVJ7~Hr1#T7Hbn|^#CdAJH$=+Er`x3*ZLmJc&k`+sOCziJZgG1BW|2~#L{7UHVO~w-_xW!v#9I^-fw6~tO9bX^K=_&uk5l8cp=aBKr0Yhn!T6W9p{CLDkI;-bJTG&6(!V~#VW|pzPBrx!Eny$*T9F((~slnIvoL+WnU91#39Pu~XDtdR0V`4fNQ(v04^B=uit*Gx6}a@1Le2OkGiPS;Tv$@ABqmEID>gOYwXu7uVjf7Y3>aj*O*9+3aHF$!^#w-#!87U{pvre6A<6@MDgwk->-+xihNmHZ;pQt@rFSWi_UOU-!xG5r+Nj`4^?5wF@JV9-t`6jHR@N^{bkFi&o#O-Tpl$3vDr8TPgyILd9l-zaQ)$%xk0kq?tTR4*SS1L0XEzj1x@@+oSW~`gC;lZh^vHr%Hi2MAu32Wf=;OsoxGn;qe{Y)^wQ98+u0{K1F{d$A8*HFt1!_bJ`(rNLK`*Ac$kkjwG0JP!rs#mI}~V8<}S<4IsJaOZ`_HoPCj^>-7DB$HvAz0(#&k-W`$%@=fP&m=?G?oAc5#PEJxCsw+8&P@T*PhB9=w>dl2aKG2mA1`&TI8!S5a`@UHNKwJo-sCsy-dM=^h20lOn~N68-z|IiI73#A(qWT_`x$x()UIxrwd|-ruCb`Sd(VR|E7rk@!U*J+^t>eioXSMAz(d-QBmog;Ud#^ZCL&$%zp=`qqA6$Uo=G=lV?_!H0%Ww_^rw-hH^x|JKR}lAmRLesACPvH@6z%#=OJt!ui!S<_i_e9`zekALO6Yf8=8pKhw41Q-G6fQg97?Y1Ax`wJ?GzeF|B{nGk(UzweC#C+L=3kI(4Sem{h`{*qYNmMjggA$ZMBNJRW`CP^i5{k<(G&XN&AZ0m0xu|EaArDYEFIf#7nRl16|=TIIrRE%wU?2GvN0Z%%eIKI7R9hEi36YzXug8fLG9Z9{G$&Y7pwczp&&yS$N)FGt+X&U&rsAQp!0f75by3i2_IHcU+V$JrNUJ+T8t@((56eRyqHp9~7zgPtwoCoD@Y93&l*0t3Vck5vvp+*8LsaECGvZ0|pKIq?GGY8u{dl>s~;ef?Xr5hroq)?d8deb_EipId#~?~e}!7Mt0~PDA8%q`ys(!hdy_Co%qeuBl2>J&%U*S9EF~Nh0qed717P8F=im^iKaI#PvA?;>al$$h@q>A;_aRGrwc9O){(;k(qhZ7T4FfE9D!0O9oS=1rhZTh?D+ucfvV-HCC>6?rX%qUTNB;F@Xo%Yp1hR9j{NnKUufpBoC_R8%YINic5Is3Y@yV;>NUu5oW-tN~2IG(vaIl%Rorbz$H!Bt!HygB_IxNllnIr5p9-Ga20%1JQnY}&)si$wgHU#g0XVw2#2nqQ6DBgFkbq}r#BONPB~wq7_b;^$O}J)bZzCmBfo6#p;cw;#~bHxH!1RPKP@mW%gE>cgK*=7E*l9`!mt@-fn%cF7&?{A@^%a4W<6S6D9X&}G~^->_!^@~-20WnbR@rl84s^)~20-sRoXNQXV9f%FfE9fJJIBlL4*4tL%Lh-ob<2|-?DxMxtE{%{JCjtuj7Azw=HG@Ep>lLn^2Vx#9bOFYMnkvT9@B`kF4qr|t(h`=wyc^4EOS%S~$DH)p-)!AG9k%87H47lqClxkz~d1>rB6r3NHmyfR){ui`L|>g9pb=wC{n@_OwLJsR5X^s7u-jq)Ts&?1ZOtrt6w@w-X2f1;Hg8BkA9&M0d{c?x-^0xRsVVrGwgsa41GerY)it|pIXWqn3J9?{p!AMk;UsaJaB-nahD6TNhW1w7~oedJO<68&$AwZr_L#PJ{}Ep*hmgTa0HqiYf41>HQDCzG^1vKINI(WXb+X6~Y3OoH{8i$;hGC)B@}D%76j0jVJ6~o)Dax7T+31X6gms#7moQIk-}JXJ798K0H+lPGpMA*Zh538e*xvqE=a83{&paMn9L|Tb0ZON{6!5tioxQgjI#Xcd*DaR$UdU(uo%~+Nx8cG4jzxQ4NgBKb(Ml3JtdYy(mQ_J+>I4c7hR8r$EpI?c1zlfq6$BJqAYVNYpv;*Z&9R^c_A7&}eU#FRlxX0gbF&p-zfI@kN`1E$#xi3g#GpprXybe>4oWb&W;=PZ~m97!HBv_m2B&~9uRjLy*dTFxfeN>u9hvndv53bT4o|cS;q;4B+KtxBh@U$!=2}%34@y4OYIi?G{QlC-WbCnI)-IC_);AB1x-`MH&!Tynesd5)35mkF^9kbS^^a63=DAC;H%cnQI+3v_!5>Nl!?wnQQ^)~DVCd5DkxL4wrVNqvm3UoRu))(y*Jj`{6}G0sqpcKQX=hXsBIq`znJ=soG(1yvcq2K_^JsahJS)2KQ-Rhk?qNGM6J;PJB+p5j+DrPCm?XW8-i3wRyceH*7ZeL9q{*gazU3i+qBup>6jbVyH7=$Jeium4r`oxbZW29(9bISD!=mw7iY*<>{VRKMtl#mKpJ10NFH`Szs|p3ll8bgp>2kqNBu0OqxJywAo7%Rl)JG2yXpQJ5zOby|;>K+&nEERZ!?+Y_9Nx`;^YPqoWn!;F)C`sETl{-{^}$DT;iK>6qoZ{jFkpQzdOB>EbejL@3Gx@6zb94QVSwZV`qkcTct2;hOwo%qCif$nf9}5)M?E${XRzyG1p#Z#x<2H8M^5<}b9|Y=P(DPL6y(ueU8ndQ$@R`-#@?U^7t}Lvb*g_PNU*`{g8%g%In*sHOqVPi^2!9N&-VNScs~Z)P6@KwGU1wOwU~Z8a-Us(DOdey;IMqyZAUQPkBIf1_rWSTlAg*YWgOE2>#uZBD?B_N@0hzw!R%$RFJFGr{dsknhNo2eiy>qt!(wY|D37)||!@cNePOb9)C1)R#Tg@0iIG|8`bx-n;zz6M5{u8D<*1ylN2KCQ=GuGrEnM_zs1@tHF9Uo6Ux1r0%>K;t_i28^1=$*e`-dI1ru-B-6sQ6}?o$Rsr*l+gZ_+07TT>QI|10MS~s82p=GR~qpYRgIR9GZyyN>y0_sP$PT&3obt5&8nO`RNH4Z<+hWDah$l$Mgnal_Qw<>K^V(L&ga_ee(Gsn)|tp1CiCv~92Uuip1XPzxNt+nkM+LPKJd4>E>XSU!uX6)qwb!7!M%+d|q9GUMqKAwu(S0MEUSC7^28y{a}R?7aJ$bsptYsxwMQD+*4?rqHq%i`8|dQpJ>I-ei22ON4B+&I`#d(@5PjkCO7S`pB@a6)0fGU^#|{`j41Nxj`$>vH~gBl;(sUmb9(UdV*5O-cQ;ucM!hTaPrAITjDU3iAt2ZTL`FyNU&EGov3nN}~Ub(n*>Ptg$@wZal}_c6TZLZX6p<9a|k~!lN^_6=@otE*$vPl(q5t3gqRUw%-yrWkIvRy{g}R_`A$oF7sgLeg+I^Yp?D*b9|iBkI($pC_zAGbl;_t>B#52T-EW-hXAYVIuGaGMctUXZQ#uJPvrjhYVyv6Wys5ARZqQi9P6KJ^aA~Cmsf;tx^^>s)7%J+VNOAHHQ$!VTn6#1Fd=ZPX4*$_-FxCJ!SpG^;kd<^GspzzPfit4M#znm{sauUyi^w24)5LJy-t@riDy{QAvJ1RNplkFu>gtXD;j(0aGJj1wr)IfDi7ZxodLha*6iWLATJ8HeQl~wfK6V^A>|v$eYd?2nx0KSL)AO^C^qt#aJ}3K@V|4?R^&d1Wq$lop>#>S2uXj!(jqrVpYb+-=RdFJ|n2E+BY6k>Lwt~1ZQ>egXJ2k+d9ok9^j=cgK_A}l@zOtRWj8~6hG-oug1%Own`&M9s8lSUnw!Fj3WXh(pWP4%wX$B3O@0J?Toe)RsDbyBZyq{mJBbNt@A+v@%XrRhB{m%pXELGbxTk&o1)h8j(FN5Rhgfh6>K58uMqRYZ(Ae*;GaINnyAhvI|HKBST=Wgggm0Q!BKjxr`cJA{3UdW%utP}bh<_b&>YS9BNCPTNa+Mx_t|I@Tz(eGFLHUawv5{~1c*87vCIk3-EYteday899)H~%i~15f|o-caMPb|y3kN1gq)6!nbMESugvMdbWH+imZ;kEmz#rY^H&G-ZI)0nPMtJb5uxzOmbm%(3^Y6M6UKg@VGQ?n*woR?MEK{&u)hxZsg9G}!&@ZNFe4t7krn5a4{{iAY=(-v5dZ>B^(jdB+#c1KSs)?)vJ|Y%^&S6BbOq{i&@A{a}=TVB1U;Ic=Jw85tK)U?VSr#`QtXA7%d^~r*v5C#i!`h`~JU*Vv(;J+}foh|Jy3r5UkB{Ga-ccfYFAbd5`|LEjgn5NjzLJdgccew;|3RI}tt0e`F{TrCpk6Y_D7~!fLe5t!XLb-JsF$dCsyn^JSbm=^o?~ttl|nmHem1EMEa)h4KXl93ZJd_{?`VG}%7%K29ZGyEsG|z4l$}Jru|c8Y8fPIta_`6YgdA$f{X((9@`#)0Pn*}M`|tZ{8kChM2YJM!{;8{dRQ;5EPrKgxUz>du^=C+CQ%>Y!2E5G3^g4SC^(Pf~BrQz?@OFNWJ~0t7$ETZu=a{>iDTiD)rkLd&CtU$v^y{#5-O{Q)LCQLRbST#cN{FY2JPeLdN0YoAXy8uU=B|eM%Y)Jl=12YB_@XGvm!W8-e3=SRS?6)9?lAPkEaMUuAj_1F8cpNd$;+(-Y>s+XutEd*+DCPq?W8`T`r~BGL0&ubSwUmpSicYcgUEln8(67ZvB8#I{%dqEelAPmW4Pb#3{an}Cf~mq{aVJYF$Tr!Gl9xW9+gGj*|f`>^@n^OGVI;uI*yNXqIJTvP31KB3??&to*-ZD^{*s7k3QCiC>gn`rhoYUG6s-81N%!H@`f^N`O_x|_$zgK;>LT(O;Y$&f2<_+r@LYGi#FudH}Z-JLGn3|mv4Tu5AQSl>PfLzeJrT@D7t&PG3vAthJO|PZ#rDmQaW+81a;T3Z^wU^U(Eo~{yFZCULdFZUzH}Au=JYqA={V8_kDHT)jEa7?cZni4ta~(^J!j#G??IP%V_?|lV=erV6F0x)OCMrEVioSxiB@K*v%wh*ThY;X7c0#<*~#BGhPwge23rac)py{VXMoIXM#;1Gq*_wby`)j{;T&V$nV?OB-ZbZdQ5NGblDNxbhw-b__@b@ecFGSWx{p8Q$g(udCrS(hHMtnp@FIKs;lO=k*^q3k!>@lLsD(x3!#;$$8=eJuZhbHxbs(%5d4MwLfM6_GNeBF8Fr|6#Q^G}b8fC9(OyiLK1)7&D^Fd!l24CQY$l~afbx}pn|ttcsdMF?&@?DG;a2Olo+ob5e)?y+csk^NR5gBf2l+v&!4y56TX#ZbCVpi9d3rrKhBdcQ&*>w9u!3C`8_5Uh03UNwv&S1zKH>^);KhL_CY;E`9VAj2}tgIE?GVeb<4u8-=3!(_nj&$&h~)@>Jaxx4QZ?NQu>*=;e*~>DZrM{`O=#$cc%b=v%&l?+`uf0HS9l{0X75YOyXnGnj+xQ%RVJPe58!xn8z1Vf=l9A}K1dQE-CHxflBe#?iHK^Be;o~;75@BjxZY!&*Qt5ww8YZk!a-kIi2z*pxqVYy7-Rmc8UL;OO$K#FdhZpL2w2G6e`Ix%^Z0m5FU2Gi-28EKtKH+{XI>h0)Kq7}fhbK`m*bA(&bbwxNFJb`>p7AT0VO?FZmfAZY)pcto(xdid*0E9)sKOzPb+e)h*Rq?4->Em}OZOeQEU?A5WbVWHl1p{s_<4dXA6(c51au>`^A%a>)PrxgYJ%t#_=(8mj|rjCzdvxAFiB7+FJUi#Fi+-YJEa?r+%KeqNehsFRy_7KqE=$%KBIWT!+9>L{h;t9c8zk?&FdR1?$hsH3>`!DrLQ&RZ4m95W^ENch7cI+W(x>AjLjIwXQZPr*{Y(2cbB>97U3}eHKpglEWfcHcBiS|#-1UZ_Q~XLJ2{^>0ugK6&`$@E^MjSYYBAWO@7eIQMpqEcY16fU*qT4A)c04c*jy?3tNxIihD-vp4b?PcMh(hS6a840HE3SL9VmRs9D%>0qxV?0?-C`QdYYrT&K)kf9*>DE>V1XXh5$U9lx#&4!fK5!J{=wAQB&2s6R#&A?QpO{k-&I>=|LnUIzz|Cu9+I*Pl#=COeC)BCPMzt){E9xjZGbT~M1+49U^$Q@=s=@B)|fQsJAW^pmpMO1ugQEvuh72cLUJ|B5!v-a%0*_p7t=C8BjHsn-4@wZoKFj~2C--kHlLXJy=z9-P(lk*#(4&i3KX+;e9YW(NywzE9(c;|Wsm178yq6FA>)K@=~#5(-9GvVf=KKqbx)K`&lmBrTUSfF}4l9)IfbxyDG7Wa^mG@#D;-}>Qr_&wizV`MrkZ(5?VKMVOp4H22=i!;EsJ0W^d1ohR6s{=z*TQXqUl`qp597NuI{FzqKgG`{#D`Ng27kc~h-Z452ZtQzLc!`1cLp`_q%IGkn98}kG74_9B6@~c@lL@Fl``0z-4eG0duP678R1%=keSIXu6Ln6oYT}%sEGC5B?f)EEjJl%FU^w@OaT>gNTKqae5U)ek-AgP<1DW2NSAT{hw~N)Q721^!Vq)KgZcIgewZ^67OtEMNR4;a&b^ICf=~Q5QMFs?(-F6~60q;lhTA$)C@_9(zVxk#kh4(|PyB`W@K=s+a@EbWd{(Axg#CB`Nt5=}T>73Xf-K$G*`}w~5g8E@k@>&z#lLjB(WfVV9FW)*3^V$cs~^nd=&n0GGNlZsz=>lk*_}Rt3i&I3E#J`)31Apdgi#Dw*R+E8r00)J#$I}-oMfejjrOQ4A2gY>^QatbxZM)cO@+@1nhgca$4gM>K5fACljQa?gORwPiW)kdcF>0Pcut}vo_x+wbGI6w{JL}RFKNuSJHLyelFNWSuV6p1FGL+b|doO8_7!TJ!x>){cvROZM;t*hv!NEXz5@q@TI9Q5_Q)gtDAH1dOc`+H;6JH$&bf6ov{~?XitLgbPdATqwYjFIRYNRT9NBeZiNKa|o*a5SO6xTn%4fC;cqQU_Vol4!jCNKg9N1)Ox2Fu_zM@Y|bxYq%gPW(;bo=z9F1j%3)Y?OubTB-g=4K;-{wV4kJa#$*3Wu+6j<81k!|w3U(hw$q>VuS$in`QRd4B4|cmfVkh2ECCkB|3zezLMflL=FlP8!SVqF&Y2-+n{u3ln17e(TGPpr4TH&k~r*f~(KTjZGB#wWxoG9b*GG?{NKp=ZO^t3Y7w9H&4lg>M7fP^}3@c8Ej8|{cIjibZSBel1e&BXEPOAkhSr!rt<2Valm1RPKG8y)f{xb>DlEW+{J-%I{~ep-e9?x(__VF9Z~u9FEVWxfY4y}|pW>J90?VS!>x-apAZsO$1I1SUA;j`d?u_>1R;GwSaoYwXAXt*fU$e`!Ka<*}TS%mgZ4=5IA}>fA`QArq3bB~ldLBB%URCkkoMHE8cz_zAg+uq_N%&|!{skgJR+Po8X{MX=XI0s_7VKIZH|{&0&6EsG$)`QhDn(Jja)=q0avd58(!wKuJsXVj?PAph*Q}T_~AnLJy4vDM$MbhE*iGgW{c>G#*#`o!*#B^@_#vCW)Gt0F~E6g$=X90VyTL|)pU(7@HOJqX(^%W9l8OXVL&YhWHviZ+U{~_d=bJQi@chKO(*>oq7-Kgu{RS52il4d|bkCeu#5#;CBs-B#oMZl8UdN;E=9zE9OW)w6+z{vJ1vv-T2?&>ysZ9>JfH3!7fEEuSl=5O^0p0za%K6&~(|9*h_O>}B~gIH4rrUF&3ntuc8IzKJe;wedYSbS{CB+=%y2y|=doXk+Jh19<<+s?s@p_H?-FsaH4E3Uy2H)xk3JE(Q!m_dNb5iu!~)cU-vaK2UvThAr@Osq<6C`1?Se({{Z?F7Rsg87uKr2n#ifGueXovsO%GrupSmn6*mm$ZQ@zAr()~&`5)2vx-dOIe4G8amQ?xJJMi*OPiP64b)vH2d1qGC`g9__s*s!o;bR-E-~|4Uu3{;>$WXYJn?DM6hz&QlJCW@v_&f*izklGVfk>QI~`I4tJH54qF?LKtA8zR=QClifz<}VXS>Ha|0P*NHzOLT1*q`7TkAB=6Zv-OeVIWA>Kv>_XvhC}lYve6cJbChI;=S99KWW~W_&!A&sH_^KmW$A|IYg=3<8^ONU5AAVDZejYLQgS@#|1^Qxz1Mpuy2ywLZgaoWHeEiP=}qgt-2fjZup+&MN92`%=R>7Ccz9c2DjJlkxG?{8{D5hMK6P8+$*QkB`p?R_gER&H(Rf(W)R9)Jy#_mj`wwXTsa2?ChQ^=ocE?d2fD<2MrGFEwL~tN4@mBE39+75vjYJyMK5pqh1=(^(nVo&w!40r5>Tncuu!Q^|5!|5(2`71gGfhU>sVNhsj6hR|K?{ectYMz(1Lo5s#6wkk^z-#I%j*;qb~Z8`FrR2pBW$`d&{w18TpPQiRm5We%4t$^NY@5)IZ;q=l%H-O9Lt{U`H+b_qcwpOZ2h&8)pCU3Iq29;_sj9^(wLk2MBTiTo3BBv!)J9dp`K%Oma(}OPb@2%_33Dm8~gehwlUYZ>nJbph^UaIL+8oYjY(Y((V$A5ObmZMothx;_CXTi&nFFWm*e2ml^uWw%46?_bN>gZbKOQhb|Wxvl#R0{9MZ~t2_^B_`hhVJK(zM;QMJfK@lK|cdj^FM5nD@Cp?P~_?&lnI$>OGHPCkQa-!_w;m;eCy^dTEocMosDNb`)LrfVOh$rIrzEat&C`<0)v~k((i+O@R*KCmmUG^?{mdshLH=jDq1`8GvS59&*zuBaIL%J*tsC;hlK>qzmwNqO_I>_WyPRNfy?(ux^(zE3mu%Td2^+BF|0m((a@*5{-LPEQvYTQKBS5&^Jn+OdYjpbOoJ&`YJy4Ch$2_5q0{rV)zhx$q+l5^hu7z6ygLka}mBbT?k5IylY0aE^^?`#B67acM<@MM8A6W;GA8RpAC{WJ7hb@AlmsbFtjE4}6^>a=AI%7PQc(zyCOp65Cfv=!DJy`Kiw+e0@h*dwRnRdOCUJJ(sw3O|?1Z>*Hg1T)bkVUaxf3w{v~Ryi!7fjplvpI0~X!NWsEO8e>X`AF!Anz^Wd9+W?E7;IrcTiWD@?;oQ6S#*J)vFHr}XCeg`27lz~C#%;dbmG;0_)TtGCzzssyZMgqh`4boP<u2;L|QzYpe{WcK{Lj`q11;dOQu{YolOd1H#|ct2F1j_mbm(6OU6Ao4kKs&0dncse+EoD7K%!28r!KKjGW4nQ;KAzQ{+Q}OC;qO4AR$>|QJ^j93(OLJQbvtK5gBMRfK60W>wMYfKmRiZm#dx22LDg5M@TEcQ>rfMe$#|au)s?=F-=)EoQI#}3MbuYRy#w*ebTC*YI%S(L-amKW^fv?ik87{;y@f~|5wj!Uc2{__g=JKFDL!}0T-pMLt{b4Z;V-5Owz`O^w9Ux{yWl9~B64zv}p1!hI#{P`%+I@%zdfYPHv1`|!uk9R!gidGu=z6<@x@Kbc)sZ;mYy(~wS2}*8*hi>rXhXytlx-CD;yz~nytXpIBUdq?&2`ZLxS+dvKLFP+NL2t0j^0F_RkfOm&6?k;)HjVG1l_oe!Fy3+8xSpDG^7sDk?NZlIAQY}FHtm^T2xcoBtJJOO3R%D@lsJdgPL|DL$%L~E2*i;>a2N%fi`=#k^(k!0*-vv7_Hmk6KS|7p>V;=PWQ1>H8->^YHUO%An8b1G&KW@VX&X`|r{5@(iIB54dK6g(Ruq(><+0@}Y6Vvnf$*VvD@?s9P{42ryS>@fIEFQfkxOK2U@$^-hZ2rDon*6>Es>TyF9Wft7^y8!JKdv&tw!?mk2anxY$3LB(IfDiLd|fHd2hna+Jl=x4EN-9N)oZbToa4hrZCevIY`AmJL9Ys*AL^XtAwOrVf8~69zZgQ7n$Og6U@2p#_mQRe{7`A*p2b;Xac=dP7r&@g;hUW&0XbQx+WyYMyx@(kc8$*p2=G{LvHs(G%x6h~#NzAonXqkN)c!jckyGbJndJBFnPIYd(<ll`Rf7yU6|@`mye7`d8p}sJg!R3-eUav8kDdD;MEh)vmfCFYK)|buzoyG>PaeNcc;(l!zgYxO;R9J3$f^G9CuPZfnc;33Ek5M_iE@*s#gM=I0#=R5E1tT7>*&?8vsiGgxY|6R~B>LgvXxYcG}LHvLMf4nfXL3v?sSdKtMLvKhXLd?MA&m}r!t)}@(JxzpoLh&)oHN#cLF+$0R`>XzdlpdnNfVYLr|NtD&dMI^qdFD&9*vIe#?uJ+)3N}ndHNj}E!2&*-cPPaN2J#$??q1KrQfX};6cj+Yrf0KjT~!U6dEz%ky%jf@Jr;k5?)KZtz<%bU#pMTU*wb<@=PELf|8Y$(^q4kmkLpF`$>9ipq}5qVaO-fy=(DZz<~+g;R0T-kyG#at_@j0<;Su!_!}%lqvftgYUreH+9Q*QD2288iP&Xk4uk%8s=;i@q0ybDUy_x$Kd4jO)t(r6fVvedrm&oIFsD4SW<(S<5s-gbKseWGhDNIlht5o!PhkUZflPrS`ELirZ>8P#|_GPZUz3g#2KO1(fp2@sYgxssSB}Ar!4I&LHzH@e9zve&MFM=yaIq<%lT@o-MW1R1PzSri1NjA*;J9tn%3wiq68MSu58SpP?!zodoIRCgMs!1=%@B2yX+eYuNxIS|KxIqBb|M_AyPu~ar%cnht2sp%4-*D?Ht_vsf2L^2&nGpIR)j~!abp_>jT3W$`uQ%$}k7S^(pz@kMELosL1*UYPu1NcE;CN^~i`!p#MHjB8H$MK@yz?L%e6CfwN?pW#%HD&1r)SG^fPYfstNV9w-`5pM7Zd7bz~%P}mu|G8e$X=NOm#CNV5XwphhTo>;axw!r`#mKH$6*zL>zSmcb@r2jMYW&#`(W@bQ(b@wPn8yJwGBf1aO=SaGsp7KZE<}(&u$ma{KJHhm$TK@iQscZ4W{;!|-Db(jn+<%D;D9prXN>zYo0CvOW&Nxb`EGItiE?8K0jXM#-q~pe>%h%bt$bOFey@p1GXYF&J-NP=ZA`0dozD*9^1DS_b=~)LbmK77(msTdu5O7)Q!y%VNOd4P?GN1-!&IG`FQKZULd%B=AZRwpS3spzS)ctu)wr-Q{y@05kHM+F68&6bow4OK_H*QfL(y(r9sGnf*2l*e`}#%a`7cO3!-kk6j~-cTpxwCV4F@>f_=JUY)TL5$yyT>UvVh9-P<)Ti4;6RuK8gYRiX@(Vxs*K47p>f~(Or)GUXy?3+W8=Vc)|DO+E4=c>cWI)86*F)@>E=YFS&m#=yENXhPP6&Ke{0Pm7OZnRJmS9`IaRkX^v3_*-{;s5h1#d|$8os*J~~#QJ*oIqi3eFg4c8RHetZoTmv6c`F+i*8v4uws>YOW}Orp!`LEqF_GqhdPT^b~g~*zT`JDk;^$9ano{Tg0bSO%$hjlvGFDKvjkXByz6BeJqS7V`zk+UfeQH|^IQJM$@NsWW-C3B4UeWj_n0;l$5Z=`h*S=@@4RhU^7weFpGxwlEN(pNIydB0-|Y0MjN8zk@3~qhJgG-V3XnWtVvmjvQwxQx%Ymm>lGb>8}IRR9?he!+L)Hz_8DHE#0*1mnS3pqDVxP!^v_f7Oe{X@NXlIj1;`wl}+)#ur8feqCEw)6sWs_t}cA_u7du6z+Ww_Zt0)>wbElgOz)Q+Zu|5^@=;{AFAKS&Nv28X;Q~ykY@-)73^L@aPyZNpCETVe>md6ErOdj8b5%1p0=HiuQC&;_yyZ#s9Q4DUae0nV8Y!Lxl%PhTqg|pxqmlWU7P1m&R3yB7d);Yw+TJD`{_@D`}c|wDvK{)eLN$bZSKbuQN-^~NTPZci4@V^qKDsih34zB-`L^qxP)OehW`id&sTfc9g{=*@OPA@stB^+c;uAI0IDy?>Ly&*sJdRyA28sspLzI_dB`~evnGaX5pet;&E>us>V&5iN=Ez%1nk|ZGlgY^cH`!6ivO?wf)?tlbIC&bHWx@cXw92h+llruC^C*(ugHS0SyLbF@Id>_ZaVH+_KF2d63Q(Cv+y~g{50Oba@sVtbd0(DkACKt7}&XxcKMU(|#f3RNc}nNhb76Z#eu|2JJ@01&Svyxp8in{-J%o-5EOnMu!E3(`Agcc>I3UHg@|D7Etr|MRn9yR2@WeZg+T745VB{JPjxG!8gbf42=cNBfkOtxWE0rUMnv;-Syehl}dF95Hq-zgZCZu`<8+8EX9(?ua#zg;}7|s+8AF52%Ls?)F1Ejzc`RcJ8?py6yLie1E)vS^XTyWl-}{>LCNEMpKqahn==FYj`^ld-HQCm%NMPZQwcB=>ijotF>g{FLp9`5%`-&e`Xd=J$RxB)jGvfjsPB&jzDUyS_<)dWqt{yE093VGt*Ln2PEI-dRxq}R#`oCEwBJbA`ZynlC!03|rd8>H(|5EiK&;KCjw*se25{Hpfbu4qwGGRjc1K<9g$VKPG*pw&Fw1_2(*aU_12!=ly5@CWD8~&8Z4@SrGc{K%LqS{9W#M4VdL60;prR#cIf@e4=$#1Wew)C`xxN&v>dotT&U}C&J1a^$&F(le&n-?SCrfhMdw{DWYs{f7l*>F1mS5Ii?#h}l$MX6&BcC*D;`B!oSwQteP`ioTdkSs3ZxajL22wt6=;iS*k@MA|@9eSu8s?~@xcxaav&Q1JQjt@Avy#nZ9>*O%KsT8?jVrxs>Vg|S`w6{o@g?h=fzlc*lf#CMlE%iZ8^{ulEAt3MDViV^Y*YKc!PY3UjE~h7j)>Dl-PRN2IsNo=0n{3p@)0b+^qR}4}eGIth{bTlk9nSxhAGv%B0aO_($AzdLsJI8KECNhFoYxoR>9-|!WN_zUB_{mXwpe;}GwLg{{_Ck@|^+7*E3r8okRPqfBh&_Zz}!HK2+ZB9%};nx*blG|3v$UY{|c^MeY+dW8Qks`Gh(l&Zx921(*;t-6~{V0@`P}%mcme6->}eocME43H?_qpC``~JjjCl#=pIezNjB4f0?x!8)y*;-%^gDzH<0mr))fd13%ww3-8cHeHC?o&OYH2ba0&NZm67v>waiMdwIcJ288vB&;B5f+^oD#4nY9P)X8-)d%;j+`us!UhUD%5LPgS*|#RI!ZJy}+)kTVaTpQT5S(S)e;Cf_u(`l)E2U6-^vGTOqDX!ypPrY9Bg3aKbe?>wM~K0~`jUb*jIc8(2YlhiJr+KBp!ihtM;%>fr$QuX(<_}*Rmlzi!{HXY1_ZQgBMl|0V>eyq5xRZE8yy94{YWRQDa(U!Y+kpYYDuTi=G1MNfQr(0-}>ye6$kw1@)3cSDCGLufgu6d2RjMK;`tc;R5LO#z_ey;9X)K`wAApJ~!U+K_k2Ln6NZab8Y`*I$zV8t!r=B?qVuND|jOn#BZ25Mcs$5a3L==_nk@RuBJo~CR%>MQkJRmt^&bcpPrg-_z?GrM?*kA3(a9YRQ9@8XHPVYl?PElv#Bn4#!v?1WsK*miu9ECIGxtof`qBacpU78)k^i5G~}2BIW%kpCLYLTCnn|Gjfm;t3uivI7~kq-~j*XAB3Aa29p+8Um7#&dgD-z%KL1gd}37Ae$S_bOZVOnbqEw{rHwKUH|n85wlZO*dFDJZ0;7x(@24`ls@#mdR|`BiZfTV2J$6?4-n3A31P-LAQjy5%QU=NAEf>(%@K^+UD6Kc>QaV!U2Jc=n&?5*Hlp%^-}-qUFRYi=rFn`+r`xixmeCo=2GWsl%sgi_`ydw3}dUF814WMuBHr99`7xlWUQ+1N8cqNsn?H$}WY)xXa|nE=7}tfP}oBk#SjRN*q4BEOM)&92{n&4~%5x_dS+>_2_gWRO1j;Vi0dD&z1|J!M(cS5$ol%Oz}JM(jSbr4)IXi*CSMM-FVH@9E9Gg!=01wJQZSk#umnem+jv4(Bnx-bW$VWEkL0Zd@h(aDDWMSoEio!+=+l+x4(f_5&CgdxNuB8u_jb9%9_*7_(XDd+vnd-g)^wd(_W|QMhwOe=ocE@~T#tHn4{M%tt{E0@^(Hc)HE`LG$QfJ*&kZC8+TLSu{kI0U(LO2VAJ_LSBjAzLjOkK0aDD9AJnh@1D+KUKiYw&#qJ5H;mEZmrXF}ZKyw@-1qJ13p|F9m8VFHyW`tl~~t21ZRL(ZzQpvUuKqe3hCuTDI_y=iU*3vO)b-}aoRUW%%8jwmaN4PL1;+av=pKJ7r#VyWQGbU5`^W?lJyT<<=2?ss6d(t+HrTxiO}^^WRu8Wh6-s-NfkAzbeaCGPE3UqHa?+>VJUQfRk8E2sEE^7pO&ZaXnw9Q{`cS9JQsr!wJv*5d}vPx$=k{WLl8J?c-1&etu&b6Vjx9U+c)m=gQ7EJ?p6*3o`%tU-h;}UAq0D%vD7tHpKLg8aVRQ!HYIyrpSwNz)wT4M&ljY=a=S|lP~_!pyKAPfARykzEgb|XC=@c^I~$REpp=G+M*_f0+di)=rm-4r_0-nEG^x%H4aipW0=8;UGSX96=dqAE?Fr+=&Q)>IEy7KFJ?nOm%i&mpCU+JOzftb!}@-sAIj#PTc088{Gm_}Ts84QRLDSwE|6%V@xVWYe8H^ODE8i0{{~Nqgx)Zfms<3L^ifCoxlx^55oG7U{L{`0?JDoGkpt0I=j2jC_RrRDF9Rj=Z(%S>)#GH}-Re3Fy9AX=7-~qp#GOSId*nbDxufunv!(kg5;!nf$&*Ng*IYqPaQMIoBfw)K-D|^V23(~ia$HCln!Yd3pHY`k#Al#KWh0WIz;)7&KKZ`r`o|<^t_D50BZrA$NSgujMqA>_05t1n>tmiFO*W+&P|tS{)tluc}CCRX(DKmLz58Cb2C4O8*sz=x8JqxTQtcT^OpKuxVPr@acYd#$`sG9Dnqn1}q-5!XhRD+BhjJN&m*@r-XB?T}hbaQjSM?n3UmqVLe~Lju|*%kr*Wcf2?`mEB>!BtS%9KLYznSoyC%#@dkv7VNokb6tXJ;V)x;v?66S?0{d|j<3*6C(ZgX7B!<^1-x^`;XHEmpo&V@UJpMEly7SIiy)i_=XEWhs*ijJ`LDW%HochYUEU;Q2=44rboQltLEoOtmuV=%T6Hs5tQU}g+=-m3-`=8@HA9GD?Cq0!8RG$HfFStHxEU4P+v5s7itV`EE?ZEk;|Ei|X)9(y!oY=*;s2?5(G$o$3BVZzx;F^HzLS;vb_}T&jI2qA>Uo=ryShH@NJfO#fFQ3;43EoA0)pAlK#jt=0-95D~vrqfhNjMcH{|(+Gm56n2JFO3%+>Wtrg_)i&Fh$_2_J%{JZmb`k>LPOg7#;OM~wsQ|se+;;im1IM$QH!7j@5xPg+Ut7hJ9B3QLevdFCa#1bDKH)&%gxy_3t1);=3jZz#7Xq?MxGJmX&*Ef;5jL&UqeTZ+(bRQ$$-=CL|&?8yJ@)?^^%Ra9M8&xQo%Ufso_Xt#gt)*=HN8c_8JPi{;e=hSmNwUY*W=XnPAsUxTC`!J3UMBD!Of~m;m<+{u_>|lW7V5fz97uxM*fTGPO1p=}kH^c@!L*DDMa=BS50rxgcee4;9e8se&yjLbnSev{4?63)PiI?);$wDlc(Qw$j?I(}@N&Q^b!GfvkkMb(dBd6*RO&n%}($8BZl_JP@M+#lODNBRkY-4ZY80wjb#qK}4=rlOmYj}jibFN3#x7}<<2deIoCXc`C(x{^-L!JTDI+^B;d?{0Nb`l=}?p0Dx-?2JcL->#kt%qQR959g|;IH)0~>eq3aSYz?e!Wgf0sP!u$Gs@=1O`U#=ze}CC&)UKdnGjWQ&FL!#^-sW2j!uCG4ccAOe%^Y;6ZcN)gPBrv$P@aOU)qE`x93E^Ml~Hyo_HL&_WgA(b|+AZRE4;ih9|?Om3XsiS5X#dPBWsOm2L;LMZAbDxPf56BbZ)9Te{)r~IKqU)ZpC#*>AfC3u~cQ8HptmofonB(E>-LcXf{$MexSG`M*0u;#MasDJiL9!Z+;j0QjJYr~^9A=gr|KNA%~hceq&MU#2_S9cn%SGhVcVBq6ATdNY}QY-JrPFg`gNI*x4!A#UAc0LA82dfFF3(+im;)`55H#;XPo(cU5YYg?@BR_rcOT*2REN(vOOAFL3J{69~n(mRhdd|kV36(tlqM~Ytea4x<*=FkEt%TR1;)0IUWsd#b>p$LPV7fRziP%enK<$>qRoOWH&bFoPcBF0zvAMR;d0SQ2kW3=i~gJ*xF)9mm#3%!(EBmZ|HxZ;)EJQ$@TZo$hrCu^j}f+*(HAxFkmewq}GP|A-eX2>9s>l5H7y5*>@)DD-ONVuaum(d+zq!wwJ}Yqgh2JgPS=lu3shO2>P!=H4D$|OQ6B&ODjT4dHgVOyL@$=$@OUPdSrX73F?H>1iPk@96EeydaH586YbLg;X#^v7(msbyzY%U;kC5z>giL-_cWZa&NJufzo~Q6#XpPyy*o1%K2OBFx!ygyBbJO3+HS+G+tug!<2Z*0J^xsw~oc{}9d@6I@Vo;ovblAI5IG@$D93C+iKjf&?<8=*n;{`D_^9YZ}p#qB6up~H}0qTIF@JUZ$~VtTsK|LSbCqJ3JXN8H*fL_l?=uh!Idv=3Du%K9j|U%0jAN@O8EKa<_0cirJ*!c^(%p1%QTpM4X&!?)gKLW_AwRLEDXh|fbfDtU@2^C@u4_}$as^Uf{cbmqJ&ksw>RnFkV{q$iTj%oF?V-mlF+T#1E~t#PEkQqwYD0YSqzOz|bn(E+uXMDV@1$uR!*`j$=*XNAyc6x#meJz8Y#$5G>iSDYzC!y@>(g{|Hh5?RU)65K`1V*w@(G_xgUn2?vqe1p+^-)j94fm(1FG&t$xY;X^(iZttfm9?y`}deKkb+7aIlXKc9es0A#$!BEn+}pQKj6qe6(lwX{#fOy9rPlHdB~1895an8AQIn&n|k@CF-I*!;gwg&m_Muf2U4}unyYO`(|ivaS#ihD#tC%{)5k(^ZJz|wZ3floTFHHJ(#CXa>Ow{;rE%`x|bt^JpL%=P;=F88mJwNu3g`VTs#CZ62?5vJB97*WBLAdqt$6wf6GAsm7`^s8d7PikD9Jb8!vc}b)~`=DA#cy#pcZ_L4KAz)|E4@ZzGl}PO%>}*SdsgkR^foUXkoWR{;zkLpdTAMr#t}p%OX{mAuk#{Im+5ocLDi6pB+1PDbV3wg8jzGOddbjhR030MXj9{PVgw&&Vw|6m47?d948Xu!pg4s|*d|D;%Z<4I^K$bf=9*0S&^IGIq-7@Z=ko#!e`^K!-DCUOo$Y~$66z@LBfGy8HPr6o&pPPHF@?!q7OgOQ^xza_FNACr6YQ21v39kngy&vx4Ij>xt_xij84U|QmPoMGxdEK6zH`__wC31J!$*v{%x%ux~3ttG1^(XD2BbR(@-O?gSz@OC9e=SVVf7SFMGBzTQ0C+r0i}4S+(f9U_z8EHWrJcyr|A6{Ryktc}@pTro6%L$qXh40%t;4>OHkMZ|j{Yl--!gS)HVt4nH)z^2TpvR{@&c?4=wta`>Uh4>DaX$;{z&K6GhZ%cmtK-1*WXhC!4abvf3-!~=>#}*Rv_p;}>Z|mHuXOXIXb^X_OHEx6=X0Hb8Is=7G_Y05eQO0cpC6-bJWr7CDK(!7?7?-A`^O9Nxt;O8e8>&;6--}wK;$R`sJLeD^*nW7o!i%cnNPl_%Bs?~J*Xe3xZHoY3D6a|An=H%9}|_I{&6vr8xP5Ogy(~PPu6btc@)6HTw_3*@3~tK=s=v)dSzOn)93Ne`jNBJg%s*rKI{Z;Pa#V%I3<*TmlxxG6bgP;q!A~`U`L-zweG<$3@w@(LNSAT~lOMGJ&dp!(WZ|p~9Y%zA}M||2_8`{doJ01RsttSlqnkJ3RH1g@lesS7m2{#NEMpx+b_z{U29n9!^yo_5Y|8Nu)uFCX$TJQfY-0A(~`LgCs*`jL4J{Nhngvbj~rH`5Z}vBAE)222&{-sYHp!-`?kW-`0MA|2$pK=W^|{&pLbG>wDk#y1#3)?P)!2Jr2}OzaFo95A(i+?t!i|4>(Z!h8bv}gM9JsL1y+bF3dW9HYzF<-wLKHC%H_68;utldE5-%Qhet0?tU_jW$Ke)S$3rr5eKOnQo(c77ymlr5pV^iJNMU4ndGWm105SYo^)5`jW0a4RLfE?mKbVpC~xcSGDCtm>R&*G=eZGJba``f8xyU~=qy0f_!B#(273I&vcHrvRR23rY{$A}7yVDvizm?>#EQ^Mlf>V@(T3v!N$q>G0AysAmprpHamLV?*b0i%I$veq_Mj_Z2a|wR^BDJCu==@0U&q2ewzfSFxw)s2iKw&c&VLLduq%(z6wj+m;_O>LKRKs&f{+oII7H(;`E%-&pWrW_s54jzL&E?1IMn_x?-KPT;g_%=Q+MH`J=;;|RLCFyJ$D5gu6Bkh`h_9uunmWFY4!>Fdy|y!!I|P;RZf@8+w~H!=7?Jam%?&aoqpLEAy+UugJW3u}UcNHOlEh9(;MBp}rRjR=JL3`Z4TGbmwcaM)>uH(K+SZ_M`7!?2%g@Any;jzi{<0W3IX?LA7r>02UrhYBqHdWsbp7rzUm=jkh+m9FebVNwea~+$3%)!VDcn|qpF7RXVlX?71?jH?k2;N})YU)fI`MiU8!TGik2|*mdHZQ=*Jl3!a&q4p78CO+ufGYBl)Cpz)mIW!_4zQ#X+g}Laj2tiWYv3J87%pO9DF9W!LTt@3DHjsTOyPu*?5Wi_#67Yi!5+x7#dq;4bPd+{^GBK3%-~W$6PWm1O$#EgDVVbNNWqwWeqc<<)!pkI;#^p5BR|nG^wml@?U$TBYeI@FvSF>+?bx`92c^;IVg!SziFY6UkvIt$RTfophf%@wBImax2Z2?5OJT3L3`2CW{G%FqmV11G2i}~JI-~Q*?$EFL8Y>3`%B9Nw>mnVjcKs#c7M6SDzo`jtI{XW_e3MIM9>alH3xC4=Hy%Pp+muII)B&)2GdPnKYO^z9xe#w`4A{bztu-%jpRhjaLlVHxO~AAtHQ)N*}DnTY_-|J>O-#f!3jb^Q4`&X52WKP=GMqmAo$gYQgsEnCb6lLcK*Z+4>|*miMq_pv-S@FuL&n`D68k@gzWmvBV>D#c-#?|dJ*Ty<&Sz>)MFE^QQ@AouHts{2VU2vcYLewT~-YSAm-M8xczSsDL5=V2zuJ$)OtsM`_q3%iNYL4g>zmCFv~d|%1~jp>X2UO9v7SL8a{&n1s*OjobNaryUYN?!B(PZHF;F(+9>M9%Cqk?B*?ctNrl#$y*Y8%eIyUWS?QR9L(3GFFFI*5N>~LaLjS!VoP6?KdocKfl;}yZWtqmk*X#J3hkz#%=AUEeSdv0{CI#+jxbK&)coAOEa?Vgs?4eb;V_6j9dAt`DPmDSm5(@xK!yO>Y1E1#d6QZ*&r`_;b`aElX<|CA@HE9iYqStlII-!+uLhoFc`|Jj$3R}Je1`Rx&aYJicVryfQ3wkfPm*dv7R7q80S^2Rum>ju|2N9|l5y_V{3Dk+@HnY)pyWGp!<6>YjsPy4EMISvdM+BU&gY)Y2lvL0gF-Rc$d%krR2*3dtzdiwF&u>x}`deUs*ujuFihsr2l8-Swe3wh;?CvBiH;ACX@sYXdLd?=fXf9;FL7s_Y7jbJVSAdaU=4+$&c+%s`B9cQM-QcQK)AEWDevmSj7jXM*8a}edP1$hYto#5I~oizei6f^0m?&OJxNi==OI6K_l|wjIsl1x0q0O*yZb^{m93xIrNgL!h$~=vyC=hK;E+Ghtd9Y7F5uOhbwE5my2mR3Ut`8eBAgq0g|X&$bA!|b~YG4_x?uPhWuIRwbUvW@xDI_eIm`K)Wb*a4xPv5f=#38=lRo6w`^a&zU4qK4_3VKs}#G0ysw--eDyXT7?vRKwUkoF{zNbJbcF!Sgfbf&Df@Bs8E3Qa9%jPEQ7g|Lr1*E8W*`3c^&u0i^b_{9wIN@$b+1RBF-z13M_Cg;cZ{+E$Ub1fd(HguuVavZkdP{QXesv~d#x_}EeBLrnn5Iwhxw3SABOay42G{iqKM#&aJ}qkLZK-@V_{gM5mQKd;-__vl;X(r<|Ms7%b^b-Ezunf&Xz$>Nd@!oYP+zHh8Sp(E&xL`Y)IZYOF>jK-rZ1d$BLAxoMX0Yvbc0$~sPbV>$e$qHTd1#ghJ9YaWAWj>Y<00-1nMh>#pAU?V*#Z6>{*z>L48Hzn9Z|KV?kwO=%i2W6d#7UO3G%0PENJ)+u5#&oa`rFMU2l)$A_258DJhH=O+&oIimHVKkHGK#@zoRwWf>%MA|U&os01i`NjlsMeBsO9$|i*9oDko4WUES=iOZtx8wi%Gu&0@|5tx?3H8i{=;y54=P3Q(=eHRppIP;s8q_$LzMCi2l<%>B>bCI$7?)!0RM$Is(|&a~4ttBzyb#;k3*!I{kmso~{`&hs&Dlif~l&#UKy9oQ~TO%7(8;F8vmcr_{qsT9?Uca=Ur3F(gV~vWZ&=f6TrVG`ya*R3gBt!)abx7l=?vZbJv|im{8LkrR_SL^^fbfh7A{XvtSG%fW#=A+_!t##{$w<$@m-c_3Cy-=}Bz(UTYmzGk|<$b&*B?UJmRZKPs-^Gjio=ZWgJ;d%b6sp@iWFdxdcfxk*q-e8Vc@_pPbZ=}tv%ompIT=Pw(k(YOVnRmjOY!yCjrI>vtN;$0(@eM#o}l>I6^@Z*$jIYFt{nyIn4F>O0vR1dEhhJ4BWv@zL4{w4cpyncc_#{1AO@sD{B`@MT;a3^y9pT@mU%$Sg?CsV>agXx39Y4v9DY>|I^*)__3Vw|G9Q~(F+qW!13NuoX>`|2LJ!UeKFwq7jqO)G5b(;&u{$jx(TeSW&dK>Bokjy+Hjy+LArl#RXCSWJAiuyt1N57o+pFffu#kZWj^>~a5AKDT=tX}sEb*7;s-AZ_m4`alynYOE;&UBkxGMAIhgr>lAj`KoL4}3J;<0BzW=qs*T@$;vc*A5!}x%?%J1up~hp4H4iPS%NajAe`Z8gv<8+(iFmvj6iJU61QmWPhDeJ2_DDX2-SH6#sUS-=HQ}FT?#o&o}WcAKLkFJnvb`xc8KPTjw4&svKp)t1;P+KBQCXtR|=|eAB`NofzfeO|y_&&4SzMn^JFqv6Lr#`CN2zdtoR~XIp`1%~k>3*_&IQv<&EV4h|8IX;iU)?{94oBPVSIXM_huBT5%UPipZ?x&@%f4H6&%{z$A^vaW&-(ke2;!-jro0IITK>udWbc-W4@NQ83(Z`OxV$G(eJqyIlFR=My(VJi0O1g%{b)bI_CHDENF`lb=i}M`8_cqpI@!XhLEivAMO2vaobV)%ku0yHcWqV?%1)-$VnahwvGdF7b;4Q`B3WrOJ?~`ddY>QiyhCXx?$YN|Mn5@@8@%KN2ScdxD8#u>ojhF4;=Gh#-Ct}n~hYsgWXUb_&!vf^@HN`>BZf9x?v|1mW)pNQb?(rQu6b4P_1G@Q0F{dWjl)Ry7a5j`%PJ}N2z*J{R+yt0H=A+>v~ww5!N_~HIbsDe){FiOlOPES!|*BvQAa1eLXvp10Dw4iJg=>H_^UDIv3*Rxld$lLEfy_^7)lGAM%sMn-4$3IFsk8UcBMM4%a!!T1^;FuPR+Nh3k0`Zn*Y@Z&B7izOGVY!bVvp98k2-b}2+&GJ4ISFF{Nw3@X~P;5u>zr|Z@2KbWF*l?Fyew0|_jMt2w5=frb1m)9JmlDH|qT7dJAYBag^)d19!+fmdtCCI7sFeDk`OeG7R^U#&K>fgLyNJ^MOxsX^s~A2xHKE5gIJVHxTcvTnOIl?#g$-9vegDeGFEOQ%X`@Zr(Y(#qTniXZ8;K_6CIF02a4U1qipuTP#!YFdy7x)D|8;t`bn%FF|uPGNbF%X|pZ6ko4huMJ-}e#nFIJKTm+7UAb!rNzaqKE#B!o_8uJCjCN|`%+5#N-evstmVhnl=Vj|lIahcvd5r994ve~2lNj!d`f9cg{cgKI57gfcC7MwD8OZY{3Q=?*eJ^?!VjXo=4j~LrFklO(tk`Zot`FQUkXH>%%Lb7T&2P-_q#wnNk2yf3#|397{s0yuvfDYt{k=B6B~^PJ^^fsL#5AduELh`aekSk^rSJTh<-r>I9N1S@GAfmYeZInqrfKO0@!Mp^!ouA(P@?~@$WQKj*V>}k)*7TMZ`_P#MlH|r*Fve|s-2I!jQ5>*udZYLKKJM!&yPHTP^z(qewa>Lf3F9_(c6z*pnc%#gm!+!*N5W7aF3nw`SDus&<=ySKs%kO6&;HJNVmh1yC4vmynAW=cPx0`28j{&FB+Dpf2^75Pc?CEj*B_^_eHIQ_OCuH)4hz34pNAb_j%k^PGvVEm=$m*yU_&xf+fo1*JiBLCC0@=)_`IviK9yT-nTd711h+2llwr!!^e#)Tn2`1q|GEg>87osJccc0w-jAO!259Jpot?Fmro{9TVn3wi{^xEFc#`wL0r1`ggG>x)84lpv?9#fIf4tb)FRJBK4HTV=oZD@2B~N3qDfToh(V?QR4eL*gP0-vljVy{JmlHC3&+oD7QmOnwd*H~Vck(uf8_4(PWeFgP4Y5CzG>Uq%hNsS@MDAIk8WMcI#sOpk>~CV2-WTH$fwjvrv8Hruvgrj5J5~T)8Kpl)(Xq}dQZ`=4bcYZgxq2`DW5oFv2if(H-#MP9!$3o(w5kflZ|Zc8&5uw9bbhv)GEC7|oW<`V6^QStNsR;XeaSxdCu>6feJ?q&C@aBsA(-7LzB;)z@E`vYCRBgwLkFX}EzGqOQ4h#0-aWX;ix{7`SIA#kgL;7UNw6c{Ux`!eFF)CWdcbPy9x>mc90+%`NSnL~>$uJjk0Sch6T964f5gv9ea6c{_ucLVj6#`Bsr659oE{?8?M!FKGo7(_4kv@RBcKBqlnXw~U|ob(+#P3VnQJ13Qkb1}a!yM1MJ$vy_$aM93_JcIg*tPe;b^6!=1`!w%9#XNqjmACpH@jM?X%^o*(GV;HY+B<^@eWiEM_z;iM|0pWE@9TwgEO2=HLOaL=x|LvqcS0&_kzXVGd)AJxOpfUX0Wz<&}bsr7AptGPfPS5!+r5_M^?s)z$j;PMW*%RZxJ$7)VDxt3!Q+$K+9-_V?`^Xj(`s#Q$T{nF-{w`3VyC;*-R|%WihaZ(v{L^Asbvw7v!R5?;M~^hrKMVUU4V0`I5X1AIaxfZsNg&fG`(!p$c!*1fg{tk7NtfSS7G#5T3_dOf$d>1*pu1rJfy#UC*3ak|5Wfq}Bw?p$`tf%*|vp?!CH$uoro72Hv&CF0p(N{0?{f_EdFd#Ze^F;0>)F-7C5kE&lvqiqsni>?p&{y2uQ;GQ?Yup2)Pn(giU>Vp9X5<0TeBVz$iuz}v^IOkZc`V554E|5MY(YKL%=lJp!_y5-yukkH%Df1k^39kjP(Vua^d{Wjwe)3Gq^|#0KLGFCz{iT{&|L$je;xU<17IfImtFLON=qp}u^4ma529WDL5iQ88=(jHkPh^AWy_t@>sLbk)zwFx_;4V}h)4QM2ukh}1nn_X~5ToOS+g(c$Tjd6^q1^;esw-eYMJ&$G5qv1Z&^qnIC;@m|RhZ|?W8NQC=~((hJRg2u815*FLVZ>EFll^?10511hnEjf^wsJ6i#*Z@U1)UFp-PM5b2VSbeP3-zHh8UGra8nzKDt0*&9YWve2(0(p>I9j59z1hb~q38Z7xn8c!`|!aqu@~0eMch`yAfS;sS<@(1QcM{pPMxhNw@38d~!^AM@b;vxoH|gUDZ4&Z~H|MgT-w8hCpdb<3HF(=3@;LRhtMZ?+Oew~+fsL5Ju-_VKfz=qs|WZ024DXhFMMaz1j$PQkO}@N8I9R_dN>f$_X-+A?8UQ_g?$ukXkg=Qr-ZXp;v6j%JRAe7w&IGCF5cW)k|jXo}4#U%bym-k7b1vpLYJvhLN9brgL?4FBzW{?k|G<4{LkS1vQJ?B&DOFQFSd?jpA_xIY-IF9c>-P})W})K}5!3C1s;(7<--lA4J^%wJP0;c47cI?%Hn%|{objyhF8YI=`YHh5=Cwr|;jIzdKmWlpg}4mci3&Fde+b(lTtDkaW-&V^=XvhS3msIP85crSDg+b1w-rsL9ZWiC1|GaEtf@}Tx+bvNTH_L|$qCQJ-{_|&8hWd(pZ+rcD@T5}Q>B|7dZS^ciM$SY5C~tqIZ}JiKm0jAnV>(_!=-uJ$duIj4lbpA_&Za@M(TeznV$9bx2gTd2Y&xXB-7@o=Dsr+OCA^CPfvYPHg@<4sXKenP_;qs*r27xM58Oo^we+l&N5OC|OrFY2O&!8`I&ecg%=(#d^w^WbXJ;b6dt<}pq?N?`YjSZYc?HIK`}W^vjWs;5{$W_7ZjW((@yB5q=?_Nwgtt-7JIol}tGBcKzy3jchEQMm$QLa8evt;pt#3KqqxhKZN@x<3yGn;3vxewv8OW~$j0+fOV!*v!*-lxMeb0ib4EaRE92od8YqVh#>ZQOjE4OMB-z`sq4YNsYJJ~*HGhUWDkaBf!;D=V*!yeQCr@kS_UnEh94pR;4aAExy%FQ@)e~N$e@q~n*SvF})bG73yDIlv2rE}+tM!Q?Pk&e3uMtfHyTNXqPGi(LWL@#P^K_`WWK~|i1Uc!K#i(Myi8Wt4JC!N>eT2||yebFC^FS@*kvj+4tljiA7lOWhdH8eybq?9DYSdpQ9Iu!>NrAF{6|y>d{OA1~U|!qnrcqAuy=U=f1jz8gZcF)L%f~Zm}-B{#gAFBlsG&phGcc<1;^7_>PWTTXBi<;&FV~=eAjC%|qmtQiIC8lLGjx_?3}P>C5wd?AHoY*?cJ9DLL)CQr5q}pG@4y(Qq1w`et}%{rh|S>!Un_hF%PZwwb1IRx;+1qnn4+HfHf5EuaXbx@_6u(wOUC;l>v3-+(jm-Peqk1+Uj46sE6@HG13uLsNjVyayq5`D+B0)Nf3EMtbIN!>TkPjYs2AjdtWY!M9i^Y3(yqAp@C!`nNShXbgnI>XD<+}8@>+tsgSfzOdY4B9__PC5-{#L7i4lEV85spReIy+VhTN3Kp$zKERM*KEH{d|#gO_j8o`u5&j>EqgU32cq1G5uydTm_lQQdPXjsQv3SDK88{^^+j4y%9RNp>JA24n&SOrZ``(a#$mR|&*zgg>MOFJbrY8hlY%nC>hB}}TIqAcA)XHjH>;bYf>2*+YFL;>w+i6YN45QZlTlywzbMf&9Zdt#zRhgZ36mD4dUK}HA&2+YJzE2Hf@!1)KY`HI3X-0yju~SelyLui*|&AsqQ1$o<56D)NEL0p?Vk&Kf7UAei1^1-UkjT~F!@mCQsm+L9rYFIZ@X$h01fBfOKx5i`tSQDN)#4oz086*|Bn8db1?7Q?SCjacZ4SL*)F!hyieB8+%aGPSr^|Mgn8e%JXSsTRyL4zzW(PhZYsf_kM#THf*@w)k|XCaZk(lMI>|mvV9o1r{yG`;)dyk9vy0?;fvfG2x2B=KBKv{W>+qoM=q|-)>#&|`!sGgT_umu0Z-43Smqi#)^1m6zLeLx0(jU2o>w)BYLThCfv|IFB?B9ZUncPQt-${c)wM`z?w@^osb-X9k7?3_M>Ws!rxv=PSky^_A>>7a4(fF1X9cKJa2;JV`&+%#%!5_sWJX_YUKE!k)if?KvA>fwCUB^XBVGu|i0=YTlt3g*@#;e5xrY3tmfo_Rgf}D7xN8r32M8@F@{*>b5|i`AI5vp-Ou%w2tC|NSuxP|T7FUC@g>J<(^MT0Ajc`=;pJrs$;y>SBxcI_JWe+SO56waCeHH*e1{!K$XAec?^iOGo#12H1?^0P(ude#1qs`FL!J`5hjx?3%6PGLgrOEz26T5di7S)t8CaC#Kb-*FF(~;m1OM@jT>TV{(*hld_<4{L7{{w@^osePIM#8pthgdOP@(;xF-4Zg}-iI`nML?Hd0b`Ef?s7`f!KXDuTf8iY>2;liTSO*!|@sF?em4&*xAg)hjtH}w`p1!se5Lrm^o1Jp|kvL^^)Hs!*c^-{k`3$z}7ihnf)uTQRftQOF~^}W=M)}zSVD{FuMA-*rEdlyprs2bb;Pi1}!`y1*+7AO1EBz5Awsy5-qP(=TJk3Zdg*(&bktkf)BiJ8=G17C0W22rZ=ei{{$YEs3n7!F}^Xzwc4{?|9X91fLwsfV(Gpo_yVa_qoG!W%=}@*`TyGd%8QvrkUlXomOmw!6)$XgnLbWSK4IKaroES(p;Kohv$L{V9V|uRc9xYTbT56e+eQJzs+Q>R`Bklx~gyrb}~+CgdQ$GGF7iheZ~|T==O}9FBTG~#A)Konv%#XQ_05~{$m1T&4-HtB3s02JdcK;0@hm@E7STuiuB(@6nv^=CE>(EoGj*dX)E|TP_OCyhQ1(@AdMjVc?qveG|Nl1{>(W&|n#?{~!-kKSRmB#)!Z=5)xfQJ8#Dn}3HTGpT$jS3d*CYf$_L*!R#5gbA`Z@2qy%4t5vl;zm$p18F86^D8gr^mn*J-Axufk+&<9(JBd17m--g}CUBKx*~&7ec&h0X^zDg7ly{cbmB!|7G)Q`waBeXT}6cP(C(3)_O^Jfp6oUNUxTySLqoDf0C-F-3hQ;{zM|ejbgFe~r3`JRjPf%mc_wGgy*{`iiXo_tg@>stp^xB`NDym6=ny=iw<`4-a^kin-V%9b(XMWf;&9~joSM0c#P=Oj^+RH(EAoJSPtJ<@GeJ~WYlV8L#G&$7;tw_it~-2tmLBqkSNAH;2zWsDd+eq3#}RB9b~r<=Uf|7yA?cSX=a!*f@_NNmnmWK1^;`eB6?t0Fq)WbeJW<}f?@n1CJ8TwMzxuyEq!5OjT%Qd|69TL6);!lZhu^AehQ#l?(t7h|itlKl)V_>C?Odp}Gsd`8-6smr_Wr8y5&>j2BS9%{>w*d>BtX$j=d2>jL$7$>zmWZp>8>{Zq%jXO8vw-YB-%MFg)4l4RvVI#4#HP&Oyg(DLGkxNW^I7?Hn6NLyU58HbH`q~MJ&p_FYfqdRMsjGBNCKPmzdGTNY>XTu;N0C!~*pO&{;cz#lE}itH`rN~XjMy)GO{6IMZtG>tmKE|rHUD_jW(VY?pS=7p0c1O`lGI8-{v!Ojl1DeC_0DF1|<6hm$k1{j2D3_nBe*HY>cJa?Y(lsjb};O6aSFw=Op|9>dR_vxn2hkzxW_PnR$Ob(E+t@G>@h_uuS2e39a3mEA!5agqzx7N$?iDeGEfUHS_@J{-MbusX#ZIa!Z#h$VpShqIEWagfsjk_sk1%>;vw{ZB8hK|L_j?Bj+93N#>IM<0zm)B{rpq3jk-hx`T8hCkd!J&<&{`Nw|ZIWS3nAXw9kd0(4zy3$W97f64&_a9JSaiVnOmyiGNyu);g|EFfll{ahk*r1^^k{+CZ`-2fR^DIgtxp1`MO!M;{sJpgalX12<%!g5RFG^`APyXXQS$4+nlK<;F!<~aX;_dUhQ?F-=_M^pjp}r#hNoW1Y0>QF=TH7Ve?>BTZrYC#TLHwY)ZNmf1;}O+`$CTz|!z20R0R9h*+uVk`k}YF%MRkTV7a=F-zd`euB7d8o^%&0^t-GRMdaz+uexGSqAnH}J?boU&T&QR1vtD~)oUJ<@e$8d@VKRMdUv3TRE@q*`jp9}TxJ`3CmK#awbA8d=((_U#oN~xJn8`#PHMBdp=}%V{oIWQE*+%h$Rk9s9kl{oJvMzok0`=9Ok3y%}Q?uda&Dd1^m#Cwz+svNCk<5jNy5aB9M#vXSJn>S|V*)wf)!|a&+&y%kcbN?jlG!m~8pvmsDrPv$4n_tE5%|4z9i&m)(WfY(eaUQc>ukBtI)QrzPdi^SL(qD!24-%TJH9mO?c|&Z-vMJ-Uff$B=aNQ{DUBvSoOMKs!f+2%@))b!#MOOnSOC~%$L}x5ni#jTUq48{p(9d027Z`8Uk(1-sGZ!AHm9<%yDB*Q%)~%>DBJ^`q?8dxGivO+G-1A)qTZHiG{fD@z6n%9^!uX7QP$tkle??bhQ~VGX&k1@>d|w~k)KU4Ab*;W(9oZHWItXTTMYJ>{U)~%0c><9~E3)QU9{fP*!x&T&pG`c^m(A9_^c6?Fw7%uUD8tQ6IARva`AS*unw{086j{lJ`ulsof7Hdl@6uGg|78ykDpee61}W=c9~`XBO2h>s-@hCyw$%KUA}67?CJl8L+`vWb1slF(NbW@9Rd)H9TzD;$TI0KgvTyian6hgf6UcfZi!;bq5)+aJLT}g?xEsDIMt<$o+K>FTJXo2ND0ZfYQYZiI)A?h)e4yzo)tHT<=q2mO7Ec`^q*m|M4W;Y@ekuJ$5Z>O_cSqpwmYm?E9Mo*ADh=E(=EfYiDoeM|CEUePDc=kgM7|T85uuga7j?mnbF5ew>Z|Y=5!;>1Sa}@yYyo{}babA6AZ^hfCxm?Uf22_SE3#ZWvmhynG}}^u9~!;NLsH_4Jr_m=0BC&fV%)Dd+55w2#^wcE=sPVcPksNG#0hjo1kt9khDB;^g0*FzFUVAkuyg2+oi|z!8k^2^0g}Deq-Cu{4Ezif>CAtmoDTq-}g@9gx(;1IxQ)E2B&uavRF8s20I_${~TM3oEV<()JM|cGrQCOGNrz~e5>P~rSr03ASJxcst&nx?X3H~Uvi*+tx7O&GwLg{?_}+lJa~~87UX{qIg##krzx^wAXuV>wHWo)>X)i|uN}FdXOXUS^9=IB&(@*uck)5udVE+>74mnj>>rxJ0`OSy!bAQ&@~Rbiu6+iXpx5Sgx6uXHsUjCG4~kF7f_IZ;N*NKD_xYo;rPs*Qq1xH&Z&M=XapLjrk*Q)p$O`YymK0n+A^SaiWaWU1Y1ox3Lex>IvkcxF-^qi|ep{V(en%Z8oY)cG{DTF@$-8Nih8K5XTNI_lC)X}_-PIbbqB-KIkm<7r-f^`Jvn9*ohyuwpq2drFLLFPrW`yx?2q56{UYhwM5IW%1fy`=DuSV7&fg5Q{_?Csq8-PJ@%0Xv(!!nuA6{9T^5VStshs&fOtARN^T$Os2egeLvf`!qWb5sTd0>FN=e%${mO%-({HXhP1y%LIb$1N`4Ai4y!#T=PQy5dtn3uJf8+vl-=g2Xl=A|&PblfFF5<&QxAeG;(~y&O?J@lVNFI}$=Qk0#y!2bep}`Ee-EWrow3AYQPR!rOT4h1&f~n`02O%fxO#{1WFb+B%YsewbG^|2sOcw;WG!h&h1Ce+|L;8sn{7o?LywLaG&C(j*4V~U^HJgeU)JC+Dx-`5Vq@1fY2FmGhh$f)lbpgXzEJ3F1?>%|D4eQjG78bBk$-nQk2_lN0r`h9%jD7sy`d|ktu#pKuU$2T?bWcE_`YlNRRVq@Kk_L3ckUn`9$$1;3i*w^?e8dexurrN`NJ(f}W=8Ww7%ur#%yejwIN_&u#eFD~{vEi7;W?%o4$gA82|Grwx1H*=&f8V7d-zrsH%74iR3Hi_|1=+~kPrcDMRT9FSg@qrxX~-)de&~6yAQN(z*RKv)iF)Znzyl}TUnuEAZG-H#pgLS=2f84OzzwZ}UN@(;85tf}HH*e0NX)&v#5pc{-o69<|Bp*BOgU*j07<@bezLKIs!tNy~yY7A_@Pl>JH~UF7y^(4nW~@A;)nwf%aG@#$G^ydvJSP4w%!!K&~1r+Ai)HiwR@Bk?<3E0vR}7h2OGYx{lK%CN;$9RNVj@Y%!OeOrCFM0$jNhea}tQ>Swbx<$_4rEVpHjPC4&F_0Np4)>Puc5EhOfHp;1}T=!>5_JA&C{^dJieSv=D^*2y<$$z7eeK`|)KMD_+`Y1>KTmYdbO{G}`Wnra=J{;cpCW%aaBJskRl*knufP8FiG<#W~)mG80(W?=9bb2=x+sc4|+QFAa2yOI8JQP#47*%sxP#H*{7Bij4V;dZzvPVN;1jVt$mFo;PkaaeLaSpKR0$nZ5v|C*E$8JTD{NKLxpxRP=%RiiAkKakKHPSUT9?OQSa4n1kyst!KPsL8*tR!&(DqKWd@hdnvkwp*`a^@qLvp-1~jW4fo?BC#l-aODFWRQ5DVkGwM}xA5DrFpOac7UAIP}uNQef*{7HdUpD_PxvYhMPo7U1?ZJb!U#@CdQT#6Aj%}BG7I(?uQeN(^h`tdMHiwVzWf6m3}Zuq%M{x23+nq|PkCwT+s98sTaEsD0Ad^Zyk9&^&>yHNa5KR&KL8At;YL;D8R!<7EiSJ>8Sehj#{*x&*87{zCGbfACqjU0IPIodBK4EY_w!Nz($CWO>hoh*$+{X?FUEb3vy)}~!QZ$(l1HcA<9S(3&B@sso|J`}#|mDqvqc>*}7c9OQ{Bwpvzo1NpA?h%U4x84atPJXWAfee^f?lq&(GV9-UmZgn<72A;s$2NQ4*%^quxbyyr=6D(~FBeR)Vj#b;GuUYH83tq-b!{3&(Osl(vR6e86wCMBp7s+t=~rX3iU|*zE$g)?{d6*)rdKvTV?zaFe}mBqDDpF@UV?mr+Mz%3u^Es)HnZfI7V4#%4FzYOiDiLxNnKkAW&P?}+l=f50^mhP};`z?jxk9K)2)vg&>?3zL81@&3L;@VY0H6|+!VPRJ1BhvAGOxHPGG`NUy=E59&+;BGR>Y1H{Umgczi{!*tx#X_a+xEXPiE=R~hw^=0fSZjwn7HIB&HyRs(r;xXpb*jsW7#1hmVu{;w~Vk#agbd#1{qz8CX*zVX4!s;Ze_-+MN4h*E!^wO%Ui%0QN=-ZrYx-b9zGu(*rT9#_OVvx-+&_I7Kf9Z20E_5(OAf@l>CF&6|1P<(u@$G6D5ZpmN8xBrD?mZEl+xQ3FF!SBfN{>-PCaMTQRZiVs5s?kK~JgMfeJQdeW`2Fmi{Mnn4$dBw(l3}BC>w3Wo?eg-%`vOc`%U>UOxVx=d~Z>oNjl*FNx4sn^sn2&Eq03Os+jDt;d7Jz@ACTbmT5(y+_7&6Z78#iWX%LDSjZgjjXp%5&}))k#6il{M>iLu3kf=f79=>(D{_UMN^Uk;AKe$9D2Qb&znNjOT;wiY-MH^e0y?dr|nwQS6fZ5g{^3!L;vs)H@qJ8QuX5+u8L6(^l!T>wlDe9ogHg|r>(}qCb3}D$-Z97@`{ic0h%w=@zkKlO3zWWr{q3@MiSJw9W0Igs>4OvDV{*~*JP#&qswjJ$irgrUb1-9y0EQgpe(_TA`l()uS)YuBV0OLd%hgNB2X{I~#l)t8zCE}WxM%&l&Rjx>z3a(%GY^OAfB%0WEtY6OnOn9z&PBx0vx2WvV7ht+G8-yg@d<`YVseJat&Rf4c2iE!N?_5WUQyrj+mMg5z<@9H5bw}>nzUwCug!E>#2j$ftNOw=bMtDXEDZJ1z5z5m8l4*A~(No~ouEFgR(=c$qORfg~UoUCF_A94P_d4D}Rxq%S{ckY$|k&k*iP3mW~pH!5X$^^pS{T->!e@4tg+2*Kh2)X)%E^rdhKQOhZ&e${uh<@?Aq&ln9bq7=ZjB?@dp_n@=yHFP~FPALj^`HSU?{1iZoXDH7s_2lAw$S$tNk;)??jk7(CXDCw#>cKiT@+~L`1tlk7Q|dSzgbrm`PuR6eS2MsIleS`GRT)OHCoR2vh{}fb@@chfN)SATSv;t7hT?Al`|7$3vTkBi9t^Mp6FdHuvxcnMNJ&)sI%-BcX3KF%(46QqwO)CzqfqHGHq4~)D*?a7r5_W+)0L?`dD7~`Ek_PIUelO`ZsB>yZHiw9g(Shin)_8_`=`ruihrG#5Aar7UJ@Vxj)H~NG7Qtq*lHEP#c%J-I2J#+H+4}kT9xXvL)Nk@q)|Lz3mq20FZp(Yw_&te!wy⋙fiF!!P!DsXFkDIwzc9w7JSh#*!J=;>ZsV;>F1BTQ@~rBd-zX1>K3BkM6c%m>Kyctw>3!7J56Z7H>WT(x`(8rifoimaTmai?Zq1VijZ%NQQnw-p9v#AM-_cd6qp)P}W+zxV;4VfMt5ig47})>Np%bNbxAGg(*>jCGg?HvZmt;F%S61<=}09#ZvhG-R~J?H|oI6mUj>9_ol&HEx{mRWz;Qq3>=wjH)esw%n7aeq`8V7%*b|Y0}6O{$glWhi`-Ul+;l9B3XW%Qk42qA-geetbT@l{WYxOyAzvhEZsS|4GTCW5)NK9mR4yBNfE2?{=@}F9EyqJcN|CRb@o0TdKoJn@n?VigrMV)Z>sQYx0ZFG3ThBV=s#^|(A71`{_1>g>CDX#xY_U{2$7k=LBjq3WYZ70(&pZp#)3R^vNkX2f`Eie|Ed_W3XDsm~`HmJ1>FQ?Fs6hB1d+?&3DczR8P9PuB6K(D`E&`Q1tLHP$AoqE6_fTk8G2|~XH;_7x`ii~%8T&O+0%y9{X^re7=`qW1C7Z+2;o{H9FD0Zn)w00%s#gA4|E*t7Nb><}G^OAAQDElOo&v4qqgaG@mv3&&TjWIFd$cPPc4~}^=!_vx9SHN=J;{Oy?!k%vapXA?0JhI21FvFme;f6xXA$yKZG&m+gG!+Lq(sHDLHt}||Dd0n0V8oaGw3Vv_~t{8+OPh}0>ZamISF}DymOdcCtGj)5qP^}F6x$u_ce@%?EM1a-~99hDc`sG-t--L8mGU{y_VEJsQE%~MF1T}L)6wt&Olu>_0a9f)?Nn3@3epvry}O`NN!*OD`g-|MglqO8_#|7jm2Pa)8W+v9^~uU{|Fzjt-Rkp1(N(%9lg9y9Wh7;o!(Ea3oiUG9@V4c$3DTGz$^%mgb+a{#-m0%d~fly_e%;37B;__7x<48zP08bsBm07^j>8R>KvkfxSfH6!+Wd2^r3t$VEh#iM$3f^u*BS0AN-jo3}bQ_nm@8K=gaHZ^ZNKFN#wiEGPzQ_g%rXL->7yI*X477nQ(?RJu@OGse>nU$-=_-IWGDGa{#+_TZeI^ohS7FNLz;LG!gu=X6N*PR6gYM%nA{+oi%$+$_{HcHU3^9xA1B=1u(Ai2Tmyt)~Rodh(RQrIvG_P#5ukD2iDpSOB~Ne-@^_K|XS=&;N5Z`+9ZmJ@lDIPR!*h-(Ccv>xRA&Bl1Z}dD+XeY#QJvR4_y5Dls}ble4dqb@w#TbU!tZzkqTF&Ti@v|Kpj#kb$Om!QzpkhJY@uRPRh!fA$v&*I0W4t|Imp1tjfX6e73$4dQQ8tij?nD;**_zVMYVTnLC#}W{~1k7ByRn*zcV!{stGS$a9(Xzqe|SWT+VIMjCkDFT(F%FZgx7-q#Y)zNYQfWQaV3Tgs+pMH-xtABa4C0Ck9G&STrL(M;GneC9`$2XbMH%MRrV6d1apuiO)W{DPR2)_wN#tu20#6ctO#4|=^=#bjTv{kzB9@)@K$uEop7eu);qyOPX@1*AFJN9NQizJJBuFO1B*y_VF^81#GQd^MLMV80Hhsu-xFh&iVjoyD+dA2UCI#N&Ddj+(OfM+c5arN1G~k-X{so+@-Y4UF>iXpJ<=Kb{s@{n=PD3s%kkVjjJvO&uQ63+t=aoVsp3-MX~iplhjEWAyU1)nlnwJ?|T|ZyHXnWHlU8$H#6AhpiLHd#F;r;FDB*P7*F<`IYWU`p%q+-)}*;GgX5LUo>O6+u0Z$FSmf;G<%lW!@0aL%;=PT0b+y52r(rrcDDubNd4~M@>668EeoP?zn6E!Y?yg$E@AQcULocgkf=e+TMbsg!O(=%Z^~%fNkn)TNcmDFVOelecj@HwQY)JV>mm^yD64E(y2_HT{9aUB~n7$@6i{sZ(x&rly=Y~>+4NMAr+qy|hiCpRf-N4WkX|A8B?4Dem|LT#NCXtUliRcYXWPu)Ydd{g1E6=`Enc!{t0H7QaV6!P4DtKFxshFUo9kyOH>@W<6h`H{$FAJ55G6KCtIxZ10043WRv_ke#(P8vM_)AC+?#{YCk564$i&OQsiXcjN;4aaztGkatCE13dGopGV7T>bwYZ=m$7Q0Na8KAf9HS$!IHQHy=sENL$qbiQg?!6%1&P&vHJbC3>oYb&qH{6Vg-BB)$t$OIx^r~Vmr6fuu>jxUQdPo&5=@E?z+_0Q(gE(Wt|KD)RtsH66@`MjH{1%Ptc&s!#qj!GsdG1ZSLOv><=A?zI-QBJibcoY54P#OmKc&^8J$ne(upzY3*s{EC`WE+iiaYb(Ek`L(^WzVi=flZ~6K6`2Afn>*Q8%D*+dxAus@S<8$-UwA#>AXnC$u-qMfyWN6+E;S)8PaCXchbf+V7!hiYOCJIC|V(sVtK>b6^D;=(-Ld@IRC+EwMuhFQK+|K^{S^ef>x&jS35$74?F97wf6-yMFkQeB;*)6@w-v9RRi||#%&n5c18s4!$)c8)5dNFeCA^kuBpJKT2bJ2{PouoM1h2NVF9V~&aQ;wPoz9OGI+L5|@Q!142u5*$l#iMQ}WiA``&V+fF(hok=MLzXc%<~57A)Bz=^G~kC5kY)DYgXxBz;Tf1ef|Ao;JVWz0z-<|ugHzjRLyKewn%>MwPQ1tVwW=ILJ|=`Kb2vnRreVUEQ1>$P8ze^*GK|M6rA5WbZy2T@-U``d3aso*rPRU^_H<3i$8+T(RjnGoG$_*8^6C#X|8mC?F@!twJtxe1Ra`~X)MP~llaLj%789`AU%&*8GdZzD^cws3%$bKvioea)4^!Aym>bq$WFx!JP%P1mu^@BkAAB7dYni8@ad7h_nXpS{C+y$vHPg6UT%mx@qASl5WW;)KS{o(${Io4&J-|6ec$0AgSw?JgEaz8RIm+<@*mbk?lEi8@B#MvOVQsU{>6mUCwMLX&O|F6i0413kGwUC-}ALL6Wr|L+f)=#M`@{Ar8b^pas2Hm+{grz!K7TYlMABWXZN08+ebuhoqqxC?Si%vgCF0=8~Vtf#5jFir@(^io2g<_G#}@6Tg>5WbkNFvo%xC6OYd~S{m5_~1Kgh9TVJvq`S`TXuHx5)@Yj2(ihnPDpB;r0%ap2$pzf<)?viAZpZsg#Q0t0fnD(E|`2h{kkGkn-vy`Ufyq*a;kO!QF~X$6H$uUo_d_G@u(RTBC+-0@Fba^YPOsIULkBuSc2bWYGYe^+HO5dGPTb)@=ybMMXXVpE}HU6Hgqsh-M`{USU+BMT_}mg^Q{cN%yljIeUlk%x-3J+Ef(2TYf>3<(7zPrk(G-7L$5td1LBq{fj4pWhtrxPb+Oi+68P^~HKH!oSXwrMMy>1RODhK)eH6AM-Y)OUQ->-k|{IiG;xx*o@3;nHB$YFNxROCV4UDIdieS`+|O!dXdOG))wP1e5|eROD;`?k+?Cvth&6aJd(nJ_cdG}kJDcj{0e@rq{SV-?KDz1YfSNP9-*_`>a1z~hPcNy5SZ;;~$6$WsT$%&zs)Au{aXHy0!1k0w)1RaBV}Xa3^zcPBhQ=RfxKE>HB>lM{@`7i-RL92Y3&_<~B4`VGV9{9Vby1qqhi#qc1VPdfJ!o}c|Q*zEAUm{Zqx{v7gQtu@oT^VruLb-UGY2F7``j@`76;mQJyW21L(i;(*Ma+V!v+E0OmZR+>8lIp40f3`{VHY%*n3NL=L8u=UlIUdifX+Xp^O(c-lJbU-h`~e+^ex2@l7>^>}n;*HEU@8`W^!g{tKc4ZqY1wl@7N_pZ48miG#<+qAK@W{|S7eC}H81Wf4s%bFGZML+b2I`z0k7sYm+05Sm%0~V^VTXL;oYV@J(Eog9HlIX(Y)$0->5o(picLAA>4m&1I!9BLt*??EjBFNnK~DIAP8QH%NZvC{$PoFN-q`~S-!kC6*b{N7WvHY0i=%ffep?7pq)aOyO?0!Z`w`0F#bv31^WE}!1%OUVB^%$x6OMgzr*ca?-rAs1r#Z#9Uf12InK<_=Ok%JFhp34;M?`MDK^3rO`*4C!sEX@wj=#*}BMm%e6j*Uz;pf;9IwDe(Z*SMA|fW9E1jgMCgvB&y)?4(tt9RAxHF9MgN4&yRYh#!gbVq%jNTmme1k-h}*6!prpupDFNZu}Fu61@Z>(M|TxhBbm%WJstAo9xUpXTG@KJS2^a^`Fn6#t7DgyZ)`(Z;si@~yHOQTLa>MO#>KKpYDoE%CTbBjRz)2EVDt!keM#C(`1op?N}vhSkpYzip((6~mzkh>n?F8+Fg3fx;i_VSVHowmH5=*@qX2Za8$md5k*D(otE7pKGE8{JjPvru389Xi#*ufu@b3j&7sljh@SiL_Ho6$?RWe`2rBRn%8!Hh4e%_KpRAG9UOo;U?ARyNQP$RW0Vc59>&McK(Mpd2K(Q!in?m(IokLWk!89`J_&(jbOa!vFxO9VrMp_RnHBUt3w`M{&SI-6%}T&Hw-;bkrV#p9rbxoy+(9R_b*a?)UuRPzEyO{nlAe=VMg)`mA_h4X~y8x6$Cy)ez7`9$=k4y<8RMHn)Aq9dZ{9KW)bvFZ2Z&Kg}g@gShMKXV&Kfh^+bL3;OHVEXa=j7!e=hOunP=Ofl@rYCh)p7CArscJHa6b0Mwe_SqfWZm#)~L$Sq4=SDrt>IrBCfv1jsfqiMQ_gBggQ!_d-$1kUIa78Wxy@8w@lqWsq}6!Yijwkx8w@|@zpKduTZ4;7tXRl}cr$#X+0S=_T*~aMD&*T%tk_#`!+_b|Taw~mA#agVf3Rv#At?Wq`s4B)Ij8=UeZ8+mG7@i-@`KCw`?{pF-&Y5BMCWZH)#nrQQ~b43pmyF(KN&aFA)|NMKfpT~5WcE^$|LcEFWdV`f#6n6HcW1sA%^~Ci+xh_O6_$wfq0;8GxHa6=DTV_l4jPFsBpv_2aoROE1&BH_jpvkq{By-lllwxM@af3%;oYSC;Od~9K7syh=m^-84mmE(g`?&*z0dz{Ofs3N%N5_IvkVSs31Gj)is$9`P>KzCy@tvV8-4sTpmH4<0Y-Q=GP25$JZ-`6gRV6e@y;}7y}BNkDdP-h1^8ww8Xh7CWLNCFlaMFeHFg%ByT8##i=LEU4X|Eep2Tb7Q?-0*Ecs`p^mla6Y_XJl?qzporU89xGtwVi)5c$oCS@_-M=1_{6ddgE@=B=L;;WJ-1)hykQBg8nc0AQC>;_01jRU+R-TbBz^n`h6d`m$)mi4tw-2@w=wI^Dn0pz{F)(Dola_fUS9yIbfIW9RZ={vWphVs91|oRUay@&%7=D-q~2Ym!UAq>ohV6vykbs`8OdQ`~xEwf49K=ApO|q^IQ_y@Js#*_u3)M-)&+Uo_Xe%11dip{7QZx|2+EoQ1Gi<5V?D|bygsrNB)eOpvnAv*r-)yeum`F;Gr?bh?OpY1L|&eM7o_=&_nOBbYb_T3Men5T1Fxn6W|Bnx~q3%2Hv@^=~YZVd!D<#74|uSk&m((4YWG&bhK&gI^c--3{@;tfc6AdwH}bv8KM-i@D2)Sa|%Er8#9ty0vEq8{^fJ)D%H!i0}8sl6dLP>=BsjS30&7s3ypi8|lqsJjG%8(Y^MDgrL$$Jd-A(MO`vcBG+peiBe#h9z%lL;d5mimRoYl?IXF&+1xEASc!lo@ZI`AZuri4Jm)OgvUxyz&ropD%lM`QBRg@3k&t%h|KY?^n-R`pTgIf`a4JiaL=K>qn0{6RP&ioT#)#-Q}Y$vPhes1@l*{q_=hyf4(|f}EI77gv=9aSZFJYb#0h=egO2#wI!N)w4i@kdK89DPI?awBn<>JhIA?R=PXrT*4j(p({Z(dL^`UIp+cB%D{?lvGbOW?o`;oC%yh+63fIWzsF(vMk`4sp`e-L*6^LYPut@2*LuF>^Zpsb(iQZt=6c%MA*IetfFB%>K47&k%8LFX~3DYL8@1e6A!VX)n;*gnNFG^pA1#na^EV4lW%<|f&6Z6+S=bqZ!8*SDhC$8=_@na>OUbr_wv58vkw#coz4cloIu`wFYLVPdKUahm_4L98$Z`PE$7OOk|Ow1NjFMZio7c7U`4rB5(xAt#SD_-JXiLq=Q7`>0pWw2=z#pNps^COFAE;aHC9gPA}4&7txn{Ct)juVs+FWU(M^wp%f97;?_|2{18$OURi>qjxm7-=Uoz=&=Kt{?&Rh(hQ1Qz!pn26CdFK<{-D@JkK++0EX^|Bo+?%qx?2OoxSvf`_kkASdem)-25icdA?L^?S%~mKAB;iq8RJUwAJadDSCjvuCsOfavQQIEmcmk8sEVhkWRq6B%K>1^M*6WCc6+^EFnA-#Ietf4oQM>zl@dN8Oq5swUbs>;>wj#D}#X;>20dSZ)7Z=8YQRfivS)P@7K+L7FD@DF)cvhy>fqWny<5_p)^D+yAa?Tb&jPt$PZ8FFSpNH*MOwQb4p%&CjM1AC+zl9)_VAv2(@?|CTrPrwwBt2c9@j$z%@rT@3oMU<&mQG2i#Z<~;B?wPuN2C33a)#lOxS%ID;*!jF@D>HU+xh&dNP%h?NNFBhV|BIX=?P-g<`P@SR1b-d433JWhJw-!RJj@!_>J;(=ZJTLX>7eR&Ts4FIcv_{OfYyIED<8`3Bb3R;N^WfGoQvc&=%Pf(4(*jUyoqlfkg4ADWSXNrTfXS)HE^$Uq%#)U-6+)mo)$Hp8-nYHJZ}_SNi$E}FQsGlL^6=-Xk&@bp&@-;w6`gqgA5V6<{km-+6@E+eb6Xws`^O329Dm0wxS{ma%~Tcn3hvU^PA@1BwEpMsSqtzyE+W})-mS}pZ>6##8o#k0(513)yx;_lQ}5Bxg?fze`ET;4L$B|}pc`R<|M)3?$1Bfm8Q^Z-WZixk<6WD4rn-2inJ^g?FraOTdBY2rWpsPoSP;}UJee5dOlnT4bMO+R%!SggEiaP#Xkp;V-_47JiMLzGyO1G1F6qr{vEi>JQoT#4|70(5W+98?L6g+?EFZ(w>o-`0&Dv~o&P3i~i84a|)N{93;6Txa_Qryh&Oz!2g4DjbGbxyvIx{KIvt4S6@WPZ5z{-YT068JmBTY8lRIx&@}jAo&}BKkfuS`*;Ro~Ot9gD|coKltOSRe1`>N6|(RdEAC!DWBF%PTzqVDLxi|r1@?KJ(;41C2fg7^v9KU)X^&t+Oe}Am#G6RI{eAG^NA^#?qFq*cReZ5hFM(@s}zS_%vA@#FZK+K?_E|}}rhwZ=+TR9i<1_F5p#Ke$ab!Z+@pO*^PC`2ImW+9%F87M)GEZdBk!V~2^%}f#hsi9@290-WnV%L_Z~(BvaeTT!I9#&{m37Qe*Rj@p9?)zIgj*BkpEd!7qHEj1_O_uuGJ&)%k$FQe2eJN;WVT-U`O)L->+?xoymYXXAghgcn0~B!kmJVU4@Vs>$AHh9=V8`QpuVc7RUD{>;`iA*=2KMUME2BXkb|UI@CYux4+rkWwEdKO|!TDBGQ~e8rMkpi%dwKKgY}JBkGpZ?1f7_lmbNm?hOWVj%|o&F5I0^Kho`vIx0YCYU;#A8dSVDxo}JaIZ?NuT}X!&%)h7JaN~IjJNO#rB{Lw>d~5OTR-6l|=c($!tzQVX0aA?3#mIS$Gp)j}vtZa);GWrK)M2_sZHT73971(T$oQWn?i`b+zV&rYX812|9ZS%^HN$!e9ZYZfGW#RtWH!F7DEH`js2P73Vv@UYleiM*Q6u57VhE;zMFHk|h*`8-6>#65y(;I!(4P48NaN7cD(E4X-#4gpR5&nkK_Pde0k%x8u>1DadI94(?zFICZvf_wQ3;c|I(*)!4{?RujsTEuA<5dQSz-|;@rbNwlj=a~cp?@svIlJazfU*EF#X%HH!av@L?xf%7hX2QKJcvEq7{c}?O?t`}GJb%#~=xmgK{Q3~E%Lt#x!i^*ElQJ30y#PV9x!8@*-5=pAFO3F=7u@lec)Wr#r;#!_HEZIUi||Tu_eQApOw+`G@}E-_Ijx9DliUBwq->@*IuV9(1^}X%p)Psqgar61DNe3JhRxGiIhPLw?yw#+O>oggKV3KaBG6zEx}(y5S|v-X|WETTM|%zJnp<(RlS5-1+o6UHORjKTi0EZa<$2ALcB1T=wYPKki&-D5-6b1xtHB>(0@|;~hV2{@GMV0foso_Kw{?|2SJ_*yXC`!mYkrdwzwW?s~`dLaxe#2AYDEwj;i%uc)=G&$+&IkZ4_2e(-GIKTgyWeA~_dN}`$K#8uQ+L1Ke%2fCQBX@I72r37`3`RF3ga%~n2Zs#fJet>$Wc;MKz9rOe^_2c;wzWW#lJFtA;rj6|PIPo4;-;I2aHjm}|ubH5MA2bsjh*B@bJS7I{B(-SF$VndmDiG+i8^Y7f&Z&z^VsW=;J9f$3wg1ZwwCm97N?Id*^-n`lt}Fpjg5!K9Sus%@9dBXd!J~ma98*M@`%k{ef!z#R!UQJ$ez787dzn7_mKg68f_i*-i6w=Cp(M|6OufAAI~B011f1svbVK8hLEfOygUYnehC*O497v$g96}SHeCD+)4c1XVieYh&gk+UKRWK9+&ub%`OskRLu)%LkSxi+z{SwV6~nF}epevXX>$XC*e29{aVplw#rG1+Z+K!Luo4-2U8(`ncS!gX5x%vyvjY9KSW!tH|^87gX)EpuyQg%#GW0P+ui=A63nY`vz*o-~R2Vfc9Ls=i$F_eJ6C@W#wE5-PL$!2?e=co#2{ea~k;HV(cy1g52s`$(=BLIxIT@V=f95;BL>=|n;QESX+jGIVZROFk9>`~${M4pkMuW*qpDNFDAt(BQeU#{sB=X%@JQD9Gab3}G3xLQwVmox)l?M`abt$k}p~GdXt#kLMV(l8RxwUdFQh|D?BL)&?<32?4;n?f873l_DzlI6fo_bV@@wV^N-7y>B?$;&*bFeHU{JI8>NFfzDH1CSNgVxf3KkKGF!0VDBl$O{yv_&FeIH62h;9TTD_SDNgZ;fH#VTY8u@&!Z&Zg4#5|~n7J>ixYZblsOJ*^kGsVk}Lh|F(ia}ue!}zY7*r1D{*uh;pG}KFF8Re$ARDR3*T06lD=w?8J_hekIC_qX=*}!HKTCy>)AhrFxj3Vxh@9v55@7(BCWAFu>B!Z+_oP%QMY$scQRZ~)~}L$hk3^P>*_OP+B1N%+Sxp)9XT<7B3Ow6R=4jwH#EWX5WX0Do>GB$KJo71?ri?T>tCQKa*g2)0U5$_>jkbF&|!;kO4&9y4etEu44U7ZJxyxFsSNz6-Cll+s@=V^Hfp6LFLv5Wm!B=V?h6$uX1et?3y*%;e~u&z`l2q?CU-GQcbR)6}k0?!rSib_p^tj44;t>>L{*^>nEFTF`$^So{a;e$#JmkhwnjqB~qUt;d?xh1Qvg`4{&#(KH0Uu@wHY=25`;imrTn>em(A<8P@^|ETH)5-tk2)R@}G7rGg3vjdsbh+>pP|O|9*bp@ICq==fU|?BmxSz1yHhfmP$Z?H9CQnLVcy4Z!|_76<5XfY?+S7vPkQBDJZ%1xrMy5B*K7Bq8)UR+roivhw9RJ)k(<8nnhG(^gdIiC9=&X%{NptZXGc?aQb1Rr`~EwUA1Te2uWUvW72bL(KU}pJdGP+>fldh;od5X1XNS=Lc#n?3HqXg!_IgD46kVuCeMRKyT_y`4M0}l(dnD>5|8bKP@gOF6E{^QpN1C^Iug>w|%$7pf_$2zL0BN2hqp`(m>Q@4MYB$!GBl)FUThtCU52U~fOA{f12;}eVtkqe+G9fc2{bt1u+(3aA=d4Pskr!-&cI7=NlZPg2CZrgIhVI_?1ZtZ>J>t_Y8{~lD4A0>O6lXT6P5;p7zG=y55WTIVZt4U}k#(6#m+G{Bt152ZPU>hvvWpZ5h8W^VcAswZV_ij#&r`cJVprljcHhxIXiZkX9mSP<&fw4dFU2bK&9AD_>IKy60MzJGYQ)?P`j>?vMp`WeJJRq2S#+@40j!>f^ALxh9`^oltAOJR{mUFV5r5ydo(aU<>Fw`H^=U@O__zBNLWKBFv3MWS+->vWtJ#rB@V3xdwe~scrLDyU4$o(#!veQ`e}AMP-`CJ6Q2rnb=17)@*OPoiiMk5z89A_GW`|L8a34wI`6DFcy51o0kDncGrq_xMEz3cpk-r*>Ik>IW;yG<5%}2E=)7bsqpi7*w+*W#;-nKSlm+t|@glrCVpq?S-p6}{lLfLHFfPh!1XQuLs&A+aQgT*u6FS%ZVx`^=2IGL6NoOQ_<`RiQ6!M(B>K+NZy@FE?bx%u9s``J*xHfY^S75rRltCV;jeJaFWbP@XNfbpyA9<{dPp?N^~=4Q3y_qktl>dS#k`4GOf{MI+Q*9!%-3xNG+Q=PE}>#vA9o&z@-K+N;8B*6XCV|YW>{nwGc>FS@**;-S>EN~>)>b}6PF=6^?LH$L#E%*B+VGM5KU1z*>uOV>VtEmaA41NX`JqqgN*-8UymY{{7x}i+n_|AlkjY_$H0|>dnEMjoWRn!j&z)%4MpkPs+}fsHjaP!l&xzCLiyi&LQUHhE}8lkr(RnMecZR)syx4*|5}g(N!%c*q4~J%e)kS|-~V(AIcRo^k^D-Ce`=lx2nRe4~2a#0}(xk61+ZRd_d0J$tP#)`7=eo^8k6kOYS$8B*2rtlrmF99hy(p41qWA(k?MRj?M0+tCc(J_$8Kz`M;&#!Y-mo_!3>zE=r14SN2+_L)gRn6kPV8dnlcYnkP~qymOB*)e_VxEsFwtfTJ(5b&ja@3m+P`bef2%)w$Z(ke6aW{c~y7-b%Vd{c(m?)nnd66gkwW;TpCNPk8_s|1mvudQ!6zQp*_E!@)J>YRTvuTtR+S7M+}b*d5y(?d7Bwh{WJ2)j@n2=6^<7MM&n)g$6fiqHA{9W&GfKZUk-r&71z#0;ZE*+W4uW^SoUF@(`OWgt+LNfGCZ1MWN|fir;nZcX_|ozIi^U&Ri*+mjR!~rtyfN~Ot*qu(&ls>|(;3sbqqKX*OxUNr3&Is(wb;VLQ>V#|K^pX;kw^o;J2FfCJ%_ZPR4T7S5s3HJrCK}+coHk}Ns`zAj}y!%HMgHxyd>?HD{Yn#^xG&14B-wzLaf8+f*c;vKa$eSb(Smykvi!{IQugujQETp1LAqpP0|+aBh5)1Rr&mWDvy(o_+5qfhw$OKT9gkL9tCsvN+9>J9id)zZ|-k8yc=J_rAPpPBN6_Iz_ES?7kMBZvDMPl81vViK7H#74=y!QDbpA?dx!^_2PPE!mi#k`TPuMDjktfprM|b_0xUqE-*R1#1MjY<_Gd0%nLQV3b%Kf1gbA4#g}Re1Cs_5q4UNUv+k#Oe(#w-nwA8o1Ciez6~W_)c+(fpY!Ef{G5bA&yid5pNcVFNoNW*Ouv7_kRL;!GSt&AkK*SNPS)@6G3s*@=EzF1B7j{}&yD&}_p!<^cy^;>u)i0!7Mp0k+)@U6%D8~Sz?(fJYj4uu59(2-X@0%RH`+E;gqb}-v5ubkLMl9$&^yo>Tlk#+PYjj#pC&EwlBSp`xk#9LT-r=d44%>!aRv$7#-tz2Wx1nP;nDecQJLQS|vr@mG_s1OIuO=T0Fnocx;j!<#~0V}D>`OvGwhSVeRs?oS#jhm>>7pc{z`}EVK2L4YH%H2OZl8MT+DvH-+1nCJdFIIrE~XjB`Og8oj*x^e8rnQsSgh20qjarvAu@6%c%PN3RBa3Ao>M2E=Df$yM9D?oDNrpy(I7Cp^i%4HtqP6eZ9n7qlWFsO|rraE`>5-tGC29r{Acrhyf3OqRuO&9Bb>;_?Vdrk^cf#*UKA%eV_e36KK+a%5^bpBkov15~{gDj@cjn0tOi=#u{5+YDCvB*p)%GkZBLF$!N4@@h9(XRL%&QhgKBjeRbD2#(+}eEX=CcCSU5mxl?zpqB_qc|lK;JIB{|^+5Gg8eN;8(HxiY-ZB<)zk2o;=TlP_ZI!gL34A-pC0|0OKl}C#8{8KkUtQ;ATn+utt?d*X<+CJDwE0u(Bu<)PjE2xWB=5?eX*WH%uc6+-O%;+fRyX=|#P++#W>*^`5Z@=WgTu)Cif;b1NYatWWCnd?n32)ax7nzViTEUtOLRyd)p*r=jlXPlqpb*r(}xc&8Hb8K=2tjTkWCz`Z~Iq5piq*!rhlsZiF93HRQ&-x0J$?om*#!dRXN{z^srUQeMONGLb?IyjgL3b}`U0s=_B=$H8WzI--zJ?^45L2Kfm$$^vhf4npOXozh1}H`P$Rv@qIy5_w5T-?94(j-d``wexgYP3{M90!mA8_BsK;?>L46ha`*C5LdOFBlR2e;FiQG0lEqk;%3zQ#U>vtmge6s&6{4?3VW1=qo3aL(>n0GbtoeI{P*B={_=Iog5mI&DYI1d^p_PpQn0Pjy*(re+ruK5tS^lq@h66Az0e|kF|CWH50)jx~(hse_mi8J7FqakZY52?@My7=8nO(wkT-qCy15;?zw@SX*%SZK4|FEife^^cp>6vd8jP6V#z=F;-M)Bm{TZ!fJ@Mj8dNFXy|6q*xWQYMl=SeqwXTY@Vcd0@Sq}O$zvI|N1Y$G&fRIjfFC!K=an2M>7O;!De8-82*3HfT7Xo?e#}K_*7e5;K*T427rD%NTLX!dRG7YQmhLW&oY1wDD_P*@Sa(s^9eMDOuRxPf4ul0=l3P1Kific#Za=pz7cR?v78oJ*56TIhiRe_J!4m7buVccfmxS}=5?z||!KgOgh>PUYWyM~26;%she2M9akS(aAitOK>)UaoO`R7+(&pkwb=Zl#5Z_{Ybyo1|Ls6zyLlbrX*CV;-$?VxkK$VcDi3hebr1;6I~Ma3k&MC6<91!lplPKTHIq`E1>f2@@+2WA~hGZ`T1v10*SWZ$x{_kHh{*=I=cD6xk9QajeuAglM;QmsSC`z!9wf8CM~5=Ul*@H0sDSMr`=KQ|V@o0P)JLnMFE=*v*4eSiUD(RYpY)?RBD!t`@<54};`uAmIQ>Kk)wqrm^EoQ2vY?^-$V|_}m}g89b(C18ngcZLn92vD$kP^m*z&&!a_yad$;IH+ke0?%Tc3v!CzZS%EW>YfwkMH(S$d!`>GYbE{t;MQ%J+cRj?40ap|D^OlJt_qyT#ViVt0=rC$qxx^ONFT#KClXoIGUB6PmBGm;c)8D!WcBa808RL&JF!~1#9G6V8MbK%Z6n~bxhKEW2*T_d8~XwV%|%VU{|_fynhzF+*4eBin{@}Yv{Gv;6v8k!_p0Cy>NMK-tazO6f#^do_-LvG%*ySjsvhuutHyCZT_0>_ViiqtpfY_a6gdHxg_GWdKUJsNcaF&F;W(+pVlUFfpmchmy~f)z_d^0VP(&y5==O_9eexO3z6-5en1GmFsizFANE{XeR{J1*z<`(KHM2Bk9EB7_D>l8$JX5?Sp;8A)4d@4ffDSBr|0l_Clul_F6z?L^Tq``)kn{rhxYKmWWRp6|=`x?bnL@9R9TbDi@%7JAeo=yLD)9l?RP-GJzgum#K*=xD!*MXh4pgOAM5SVK6lRh{^a{!2JdIgbvHjo`)IAKJhE%<1sM5#CP|N^XS?Fqq)(hj0)$iuuH)Z)2EQkS(DKJL_|OwlwDqU!EKca`5Or7!Wxt9Ud`CVe<@4TDB#~){)KXEuKIC1Oudb2M6{mrl$pP>3<9I()U!(fd$sriOib*tSJ{?{Hiw+s9D2%F#T@Oe=R+{_pE`HS(ZS6l4Yk4~4d^d$MGFkVFT%lN_-_g|e|TgWW#&++dY{ZlHdKg(Mse6BP^Bs?j}hWS%-C9bbU-t{c6t~rgf5O`brzh>qj?~+}q!Rt9jg@f#Csumo=^#q2uqz4N#Sn>S0ZMYudyd*tZ1eZU#Uzw0Ye)V;)xl>R`32ajkUcUDi#;=Gz)|D?yL892--R3gJuLxZLw!dZI0fLkMGRSj^uW5=p+c5cDVyUUdeH_1){rVxxEvb-nCuXm6A>u^84SUIK$TJbYuxSeMJ>A+*LrV%+bpem-N%>dCA*y+uRIoIkv|>9>suNV-%)W?&0ga0oX1tupuj-^^RKnjCL0q?7P{(=1Cl;&iDi16H|7|~B#~UEOa-UM$&hx4iPTF4JxH*9Mbxl#es(;M$lv?%p?^DRH!WRAJFl}Pm*DQBS^i$+NVsha=7spdT>}bseOlK*5!g4RTv$Dc_<^ijFFyE{uyoEJkox8v+7o(Que%hCso$4bL?bTq>&nDq=I85>bdzgt8{#WRdh{LaW8n9^n|A7s$fKP9{wOSxPi5&uEq;hRO7`ka&Sw5>R@|US2k~PsQyZ@47C@f!X(NRp%wvCWeQKrtO0mAPzS{=?HE>%neb|&_D6lk!PiFEyweIq&nhfs`+~FOqIdfxb+;_YKWUJvEb@Zhy$XnddE@p*B9G4A2$!Ag2fj*1*4znuLGF}wlAsKV09uaARq~G_mItMBi{=k@TG>&7DePyPQKAqexImN;LEs^e+};eWlJR#uC7y>h_4lK~g`y=O1D6cN)Y|^PEgbdP*l4MdMeG<*@3(3k^v5T2pR?e?kkPG2}O!VmT1iUAv4o_p%Gp`G*Y#fF!CEdnBbnS6|t$FAq}nC)x{9N`a1c*BFZ@}-0!-TS3L^gU}P-29#pwP2#=3*3>x-h42o+#dP4XmO+T4G9rwI0?--g}`viMrx2Z3e`6XqIdtJeD){-A^QzwIsAxM>jyM>7nQ>9fY{wvJ<&ddUi_=dGU)E0m+dC$ffQuhZt+%*1koU!j~y3}&EgwWmwckQB*VfsK?jc16SKJEk(KXW&dY?B9qmuo`XL{yNeX(ZqL{~uH$F&0-lgmIQy}>y1uApRtS_kGePYnn=jEy1G`N;$=$bBwx(&blXWkWQFhEQzJ*WN*@~&awsDiM@BFI#YJn31B{Ac?}I6MEs61dl#qSn=iJcmfXzb0P_MNV(6p$mCVZ%~`Skqcp9kfT|A@yaxsZdqa6QEWR;Cv%X;3`+XhXLYu4leL=PjZhn5fTInv1;4FxhWq(yb!+U9PdCD4$gNf}}dvCXQA}fE=unXt;CogaO=|(!dkq8U26vXjT+5Gw2b#vi`Pk2HE6S-g43OCCee^&A^0EB}Z9kOjiy*Zr#VvCc>E7@_^^sUX=6Pz(fwNQB5Z9^JEv0TO1w!{!QG=vE|F|~Ls4xU7^H+0o1M(RnKbcP`k#+74sl|Nt@9sPIW~8PAUtC@J@zaRgN+`b_Qp|;?mzH?uANU{MuPM3kgOS;C3RwMdHfeCg@wc23MFpAf+jYO2TOkc`LdQ~jEd%yRyyiODhIqNUNDqU#uW|SNUOvo+>pY$)+Ob2p1Qe7qKE5|4-9K8Sp5D8;6gqo(>{JpFzwIx+#W5`uChC?ic(n-m)j{=J|2%*Wu2M6WO!)v#)o%WECiI;B(Vkr{w?P{hIUsEYnXp#C+d>t&>qEIG)gv(^6r;r3bqVj>zJ8HtNK;iF-w$DW15rdmfJ8Vq7S`dT9ylyMMdQ=?Chj5_tyiRZGFzu$lA8XT*hv{ur0`hQt2cnFAW;=*KGqPNhgbO@h|Jdw1vDL4Uo}v!dQ5HUo+#u5p}IMV#nIY5qPJOsb#1iykkkN?S^#R*>WUWWl}rywlrB=RC3cDoYO_97ta@J{}~&t>2K&IwtG5=fXAzC$eqaewB)Y-CF*T$J^xbRp%@31o_S^K6WUjsfYo16H_i*R;qiUcNR3jBD2?A32Zy>*;5c!SAV=;1y#YYWkZti?jNT73IOR=i;$n%n|40JSTKHj{@d*N*P_Z@V;-)$sF%tD)aZ-s$kHqhIU?fIn!Cyh5^r84)b(3p*?N*OqW%^E`o~|9QVygeId6g27TMZ^!IWK%4{wRNcXe9csjPJmBRWeh^gzmoGWwcv%4u?zkmm;uIPDqYhkN8`g$MU*sO5nN|O?K0Dv>WqrdYR1cbAGtSmj+UNkLa&dRg(mpQ(dkuGDQC1vf|7TIg%Y?bSZlbJ#OG`4)GQlSN?HASoJf6|-d^=jtZhpHg{2Sl?kga_BJP#NG%{h&tL1)FGvrrECe5uE!g8UEu^Wy!qkT?l=ML3H7XrbLL`nMUIad}Zy(yr=*xHl1hs#Jh>J3TH)Ai{vP|cHjs0;0LEt_Xd?;ZpE54|e$5k$PJ-`{*c^Y4UCrjiZXhqxDit5O1|WV!EZ*W>p}Fg(Na0n;DtzqyJbz7FvR`gU*VMFAi$x_0JOjQuQ5#4XP)iv{s{Q6WozAn&rBH+_1pTq-Q|dHg)_q4O+Wb$7j_nn@Pu?bXN*ly;xRMPE!CiHzpKo^Z{^+!vT9|IxnF;9~#x8B)7gZEqGYih0||9Mb*J^o)49juKDs((#~%;Nj?9VEjR7QsiGlt=r7k?E~7nnibHQr%tf1R%gI$UfxcNbv1%SFC^^NRJw@L}4?wRjowpLZP2Zqr{pS$%=)+mT1rZuryxCo~d{Z&hDv>4+G@LZ$%wC&5PfdHCllIvcn|rn!}-;Reh<>L^WYM@-?f**$ggx0`+69L6kr~+yM)#vzuM;^o2jsh20e||tNT|Wzxw#4P5b0^IvBYGZuoTtarWn$QL_9+K-9}dY9haKNOQE_tXK>w+bd{o^@xjoO^AE0;R$@I{ohyYKpt|{Am8@*JXG_(VxEwBP8NklBtrO8@552XT-IRlip7HVWeS(vrjm6Q=*OpU_Ag@sH?`=%$#vFc|R%>)*XUCQ$^Q7v3}EoDet2J%282TQRKO)gUdqA920AxAMb={6M?5a4#hQ{glCH7jCItF|cvj&pMeFQk+UY?0MA76zI+EQ&d`majM7l4dse*S#aNUcTMg#*)XJX*BYvsZT>xg@ZKcuiG*W9=q;OqOv!!Oct-zNI9#ahGz(f3BFfmEk9efql&ZyLz%`WaG8(gEmMT6~p*FB|qr>b;?ELENO`R_(HseCU{QTi=m{{OXzf(WP6PDIl!2tJjE>H$~`)QG;kK-LnJdGkK6hC7X?1en)sMv~^L#D-Gc~JEY-z&5;|BDj>7PS!&b*#Wr-U$6;dyZt_jff;5>IjWUdGAm5TaUK|ro-70$Es6q=m&{=Px`7HR{w(1G_>2T*C}EPZ3=+USLSR+yG1Swm)$Esh2dAGN&yQI*Y6tmFkVH2k~aS9*3M`*g+28uOO`WvW_sIrO&{7V{d$6H_?{xzHlY{Va|FMiM4#6`mc^_-Yc{0#YEk&(wMN0QEM0enY~&A7d?LG30#hJF;zW;PF7k)CMbTRF3p3#ohnfBDe6$atza)Dg7X*9tUgnT=nTT_cvgUtwKhsFkYvoPZo^DNrQ|E53v?JxKr+D)pb^1VqJvVLUO)DXObm`#1i<%6ewO5atM5BF_xJAd4oQfc?_p52sceIbVTE|ko6UD%r9=P6yq+8p}6R><-G6}lJA59z!MSex-RI;B<1B)T#vpX#tHN*VEauw;c`_j#5t58^8O3L#m?!_Xc>2U0%fAW?Vv`=k_bJOFa4Cr6C^0B@E;!0INudfO&f-@_Q#_l_c_967pY|j>h{**h&8O6VAF{V0=X$rJ3-q`S9{2_#?{2?%?e`0`Yvp2NRfQMuhM*}$`K-o|4_n3r|AQ{Yp|%X}DIVQ=8@5A(7J-M6BP6lnAx?s6~=nZ+s2DxV!xXsrJ1GXBV0rd>DbT8A;;XB$mRB?5Vi>xcCc5)1}-nb~A?k@BG4wRnZ!8a)95V*(aAFOe@D4(MOo_ACUt^Fkd5P4KylvVxY|M-t$(`xW7yy%?wB-V(M}J1PxUh$xLH*5P`j+31g#n`J}&el2fq8(dGS*rf}HBJ;uM_q%^<#c(~ZKdF6un@)jvt&~IJUC5(|dv|9h54oUuSFt}3c@&ZNve%Cegx=e|1;}%5O}3;cQW>!6`*04sC-NL3&u?B=jB~+SQ@nJE_J2yAYU3{D1KGq&IVWWm)_bvh#PRwdCv0oIq{&gs{h66P5*zt=6aqqkPH_O&|XR8t7{e@;LeS?|jh^{7fNngZ$G_n?dEoH!$=MQ#jmLcx1VRO0H-VumCdu*EM_gieF-NU&;pk|xE=!W&^-=FaZ8hhQ32O_R;#}NIv`h%d6@Pla}cQ>LWG8=hU_Z_(2!(BfRB9-O-7xIKT-CNsn~l)(>|%(}B=AHseK}z7d4NaN*l@-l5RuFOan>pLUsdVW4@sdrn06!N($7A6g2GmJjvq>QJi>&*YAuhAn2Qt3wd}F@^@424&rTeXmiUgtjqatN$xX;TQ^_^V3C>eFbM+~JjtguCm#s+kfax`Zm#3JY@6qU1`&Xp80F8|8ejYTqdy1X+B&k0U(Qk6aO*&kXn5tOCgSh>4R2F+D1J;jfD#yDZ?^=J+(&e{CFk~&3EX*S5X=~Z|{@!~!76@I^PE!0~qmotBQECb>>7>Z{LG*(}-_J5N=J_bfF7nPFjKdIl8cI&N@aDiC$`fHd{~4FknT&$gxUN-z6f?*;79jR<_2JatoBt;-_!>Rcn1thBMw>r$c|C9Sqr@J!9v}fVrQy1Vp_@I}q^>|3N0NctJnoPwKN{`{}*0=b3!io>`{f(1&*T)9?3b&Rz;U7R*1oous$Wx^&O0op-2UE16%bEP;4Zn7_L8JUUFZq|C9hMEekW`ah%?AnktC)T$EgL+FO@URngN+_Q5SLWm2TqXt!oxr39;sk6SN|GU5I*VM99JNF19?cGV4=FJG6i(^m7YHR4|xdVj0Vqvdkf#6S3&vZBwAjni47hROKyq>s@`TPe{R>hPPr#Q&Cn7vn;rt1yck4=&LxAWjt~ZHzg@WL#6vKG%;M=%KLLTqwN)yZt+FDW}<^8Yib)+~F>psRK3kGu3fAwuf{-bRlvMeAq4|1}zvzNZc^_ZGdgRcuyK-_I(uhcf=8*j%YJ2dH3c-8E=muC+0imzLjk3X2E!HDxlVdWacmw1Odg-bAC?$yvmHxDA;kR%#C{<4RxS7x00R{z8MHJ{Fv44udiV)0v!BZ#N?3=0$s#6j@(WVz^Moab8RCY^H!Q^8h!NtNah;#%1{skyRQP_}U@NpUykL8Tlt8+~J&2L|Ut6)YQ4XXl^edf?)(`4sRPbgQFn!FZ1K^YbP0g&zhY&g=1Ifm5|D{4|XHq>%iSR0=jBq;kvsWLzNUiSuy3|sj8j|tbAKN#ECkb5uq%YJZGPOSOf9>i%u&aw#tLZ)03RO`iQ>}9N!ViMSnHTlt~Lu2iWpLacAdSK1p59eKt)KY9(lPPRLM_&`m+wkT0AU~E{vP7ZO?eVfaFDlFZR6WrNq5OR9Ig(Vmx*Wx2e)@*z~gsMvl8?N&Y*-{S5?ftR)evd*@M-(1B|+5dwI*&!;e$G(v2I;(`NA2I#zJQqDWdko^M9o{=L4ly9fG1FzH?D3^!Aao#NN&S&c=JkHB+n&Md(--fAb~6r9W$ZYf!|IR8QHXXU{7Bb|0+=}%#ee(*+ULpqYzMI`6c{r|c|Q)Me$5IZ5e+gl$dLJIAXSOH;s~GUjjuLz*!qP1ORGF7K6ZQ6$zfLptSU27a=d|da|}@7Y}O6~{&l*|XALl(L)3HrD~^YksSWSq_9NdYnu@>p*DMuc4k<*i+auo~`ecknX9A&b_spHtUvKz(%nK%;BAMc+x7470xY&LQzKUnSzpqg|^&}ok^qUVBi~diSbz8+Oo~?I$^TpRmaC)QgVDL8NT}mtJG@_X2+sZXbFS*swK8<$A`(N~BLC>l3rhV#YpXH&uxhh=q;2BTnREI9w=Qf{`_0Eby7~}uOn6O9toG|{Luvd=?8=0<g+i2G^*$aW1fStarl;(p6(J{3;2-q}c{B0ssD)$JE|js~v#PSd6!rzCoybFMh(_^2XF>Ii_|ng}FkU47fqK^M|@$%fR`wUhe7QYU}M`#~{6HmE=<&yQX1OZh0{UWdr`5|Ipjs`g_1g@m$QNB7oALs&(t0pf710NA6)M%%1z%xd}&hs8}Vui_#bq6_RAjgv@_Wp*F4-#gU^3@j%t2K{Pxa06wOpR+!q$rU3nJk=7>D5unwADI^|s~MeB^1AcuUprgV{jK{TnRv8uO9rXA*_ph37-X>5063R}h~NkXg!}P648yPe2y(x5e8nI0fWruq(p6ZY&V-_gk)Us|L}5IInk|Li~Q|$uBA;3=pUd+xgW3aYFBJV1qksmukg+#5D^he6H5fm9Ka?$G24ZHKd$5@Ea5>nbh}#0kCTTVK-PtGT?;)fKeac?_kK4C7+5A@t4iowl!#UlH{%TZ;36xZv|oM_j4>io&G=3hXm?l8PYpe<5_0L*;3#`%``yQva8{h|+52`&I{gR3(oi?~-}YwQ*Mw0}houn&N$kIFaYirgRp5{C##-S`_0C|8$FYJ{XRGjrYVjjuzm4{_gBNnr=xF+zec|D^U{hsfw=X-;wF?P=b1_n~MH!DlJb)eL5TLoa6E-t1-?)=nYkV&u5+Ai>{-c%?fMYR>CEH5xQ)Zj5py^?&(M690)2MF&FPLY@>id%yH|id88C7z1fH*hqQ>L0>n!^mYfpwa-Os?mjG?eXi2Zp=jIEXjrJRCe=)V)Nd|-beqzhWU#S3-|>&s-{k(U`Ku0CXF$<0ff~2Z=m$T_<-Puto&z4EUiGJp5hwCyb!`fODx}5v_BzH1LoRF!j_RcVp*OF!9_<++X3<75rNPdG3djB`v?o!|keyBkvH9N*Tq5zY{ug?J<;>sjvwXP%!(Oyod7RF6lU+nDQ)tM%iWs`dzc%Iod)6qHXQK}hYR4@xAo;#h%=90^At+xkU3Z5S-^c#KW@I?8V{NKGb`>zijV#4pl$!SHxd+&8Sal?jr{8EH+?x}$t0k@C~V5KC&jg#2Yh@S(^!4yzow#nMt8n(TX`}ID0dezcpA|@+nK~pOCk^S9c_n=Cy`$r3%ka7$EOhfb?r_YQ9^u4=J}ex+o-UmK6XmT2koQ8d(drVG7ZwAzA2qf!e%(x@6Hvg;d>(^ux`8gr$Ga@#E&J5Ita*Bs0)JntpWrRVcure=q~R(<8W87+h+D`{#sYc+ewNcAOkm~V6mH}R?fz<)=M6GoFY`dsyqUy9R^$gqj~2nYU6BoTJCSctog^CWiiSZ}iM#f3KV0XbS7kRWcO?K(5Ah(!*cJlLphKw3T1y<2nzAPMMccvS4qT;gIeblD@&W$il*B%yaJUv@nh~S2l&k*B#`*yA5c5}q%OY8zF3qR-sX=>eQPrg0jnk#Bj;G~>^*7$FXJ9U(wk{l1q1R^dDOL09!KZpaLbKzJ-eD$q$xE{HUZ}y*mRmfx=jh(;O;(AUPMcwEvro!FuZ6TjUF%IMJX-?U{iq7ieY5xxKIJ%qA6Xv;3-q0gsDFykA=(B4rdlHLaP)hpIdo5CZnX~GhsVnCoTPHQvt_q*q6D4=^=iMksJahP)TM*9wO5BW>Ql1Ro-}i(}7~%Zl(sO;T(ldZ&6`s~6g!5k)UnbJHJ{O2SnPpG#zKrNM=c`r-$CRpmF7ZPCV_};ZU1v`P&t$DbSqm@@v(h88>EUM@7|!{(MkN{X6M}Wp72BD-u`O>xp9AAXU4NzxL+y(oC$n+%vm@fY-6MJ`6=zxc(oMq{cQPvN|900R66)ihB*@w#KkAUX%a=v`mce!}$wds450BEps_5qDxK%jM63zH?J1ukIV5!QJ3o?i+**-M4bS;4C{wszzm*G4cJXW%6%%#HX&gbHv7a;Bzuta*8xj%bPtW`eokCcZWvgCvBM>;e;HLvX%MclY|ZB&_H5ws@k>wDOTIFSdo{)G>SP`i0(ljyHI7qjga$c_XtAF1kgl5X|~n)FcBR1&0?lowyPOVZEeU4GQ~c{=bMkKbXFh4^uoZ{ar#a$wBxZ=L=z!5cyCWvk@oim+pOI0Jn>PR`V&uMfyyq%TM@&>b|(|FG@>h*F)%6EB=lG;{RKcbj#PL8SS?6NCw^(9&NXEh##w8@`zhH1L%idZr|67{w|3B``hQIa=_tJ<;bHj#Hs7wn~5>sx6bQ$;~{zEvEi$2+F!km_N`cU^rVxWrdT6((<`2ev$-d&f%%2O32^^viP3-)Zu%K%2>&Lxr`ktd`@h9ACsB?ne4T6U+BlqbJuQAz5y69phHb9(o4lAif~2M^$3zV8C7XjmCT(vz3J&6{CHgI9@*lNX7R`bxh_C`-+ugCaGgaRI6Rj_6O!Rm%W-{TshW%n`TVFsME@9SYxQ7p2y(K^`^q$9T1aVmydHG8JyDM;@ias~-1~$tN%P{>-n`LcHaR^{9|~Cd~DhG100+yB&NmwzFtyE-+k6`z90-7iZUHuP7{F#S_LDXgAkG;ZGFbQs9%d+(Z$n?_vEW?Vwa+8eH%kbbFSCcGE4tS28D#4yT9)KjMggR=>UaDV+gCUef$>w9mg)i)Fw*7Uo*4JSevMfA@g>n#6fvzgP-f3;5NxOd@0!SDtq=?}_Dq{gH#WM9ktu{T-Wq4s>^!%q-Qwd$ip-^R?+B|J5~I7eRg^ukf?b?*;`9R$hD3^b+~Wa)sBj+nMJe&eeP>YXi~mZxJq2)M38YmxVKzgy&%V#DdGsl>G_=3g^Tm-#dVQf5dRJ#3|-EWM*ZV5nC+!eWHGB@NfjHf2+xC9bdmDk+`(AJ`sq1VxsS2W^r{l#zv`AX;9+xV9nuDTtCmWN{Z}_EC|o+fA(TE@|L)%p-IC_c~H=~u03H8*MHDl;r0b-3UnTSJzvESd6bB->sIL-RG7;omOW#bw?p)?1qnJBbW)rWwj)nyHLK2x+s^>sy~#Xtk0MW4ZNI4T-_asC%X7ml@i_8?AbW?0evQFE=z@Q&NSd8rG&J&fA2k+&7Hv8vL%KKYb(-ViT9^VvUX0*ev~$JXV?h?{GgQH-8W43|=_I|QfCC&eM}E>ljY<6aa*(&o?2z5*wYUgu*{_Z6cS3%$)-CF~&)_-MeY(9ie(n*Hc_x3Aqd-^kJKMlzTxX_)@kH2?WH1hHX;l`+c$cP%b*=uhbP#>nI@M{7JnCX*F;|jO4qRBFyVX4c*HgcI0ngC#0+wExWn$j!_+8G+b)G(=u=JTfdLb`j)nAy<;L@QD%U^3E|6#ftSVf@&mrU%YJ)aQ2RK97=>qZ9X8{f=Y6@Yw3J-%k2guWN>{S~tOvjXiv2nr($lT#LN&()q#RqMx5KnRRNy`=dxIRJ;DwmPUJK2h3CP=k2`kk2&K)=BX{f79))(^|KP+uNBPlQyjRL~aWdpRr~GCgMwN?9ZRB4+c0;|ZytG{4KWHvoB*r{@Fv+<%#{>%^;jy$OgDeN-*k@<4;PV)tk=;`Mz_59-qkVMKH!!Z-=%C;C$8Sx~`0wRne55aL@u2=eDMdG);C7v1IE5H~v6***G+4$fy}erec}_@SXo;OXyfApVgzZa4*b4w1jLIVTjJIo$8LTZ8`EVa39W3q0e2+iZ;&#~s9Vv@BZh9ZhA$6TaQRc^+Prv`@XB34+mDkJ%YGemorv{xEWZxEB%%#qoFl2rG-OE`&#W_jlG?;P_>xE;{j2R5)?_iqKyL#Qzj&`>*wE{VeHmNEGbI`vN_gor&VXXSxE$oQv3x>%zOvMAyH}c;I`u8`IiAu)JcDcBjI9_A_{^2kE8n7hwm#gS`FIx{zBV6p&LG*D&__FdH~}i^P0a5c3Y~o};YTh(D!9K893Oa(dID|7MVt<(X2K??4~4d;<7UTS4fAW?IVTqileyxhj-ekX;!(RJ3*hk&!=}&P=*K;!K9_~}QQ)-GqusY{k#F?8IjtYS&9;}fbjGDqUf&)KcaoB2&VriYBld8^|6i1xv2az3L4Jo#+S8WJnh6A*O-6Lli=&YQ>igaaQzCVX12jg(&5L+&n1Q1kS~4fJ$F5AbvE1%ei*N8fIOtw`Wjc<*F0d|^OO3s5IW`zB?=hDx3`6n?z3EOwp(V_Gk>SbL(caCaQ#9H{Imm?(}90-Rm8r2T>qX^^Ndq>Ggy75&MrlNYU1OuV%VaHRR!?8J=T$7lcndVCpC$}e_&$Rveg2Eq&(OOBLyYvOa_?AQKD_rNPTkOJ{dUt+#9Z~bi4EO46d_-O~3ovvv6=xI3Bl(q$_T=E5f`tBN0S%_wyv{;&X|6J_qkKu(1*@P5**Cs<%L@%IZlL?5%NA==US_Ns)HBvGr~qtQydg@EIf3Nd>2{r^--(rC&nQQT*ewQhmckDiHc)dZhfQr9+J)=G=5(-c_Cw?E;pQD5RdL6~oWM)|`eB$aqwk8GfD|dg?zf(v7qThQ-BgVnrpQ)Hk3eJECDbAIDUgP+_sL?~JXLDHj56#1fzwz8WtT3+tMs|A_Ea^o&HgZagl1Tv@-{0=~j}T8Et-KulhYEy_rdbu@#QmN7W;)!K>nf8;M_iuqhw)0^1ynMZ^Hyv}KThbnuJsHC3E>&9}1^EthdThxDNa*-7R(UtQICdlTX>8uoKcd@F7d?5UTZ#X`8&Etg+?wV1cS<8d#*#R71lJ>%&p@s@X|IF=jh!cIL)xOYR{m0duJ4yX(2wjf209O!Lo$Ge*DDo>YxcxOyCh5>9^|3&hL7a+sXV@3H)X`-4)-T7emyY;<{dLmeQOSd=y`G2@`HT7W*}y2aGCHY)IFU}WMm8S?Y+dZLcoDB!{P4huB^3B{>F)a5kCCUzZFnGmhIxKddMY)~I}-5~KMkZR&eMR%>-W|o@w&ePm%6qkfc25gQtKJan<`pgImW#_6*%oqPnl8hzN|}C@rK<@2ISX{AKFghA)_AxZ@jya1F94LHqt^QLtf|vcyqy%$tgMy!O=n$|NZ2^-l==fbpmcl{;0g^rk`GC${glBDj8{E;Xw!3rx2r+rE;+^>T>h&d4_-88Mh^;N+{PuKaaSiN1#Ul0SiYeR<0Rj`!aChjs8CJK{rmJV`gc~|(pMS~`blqZ;QERFdbzvIRnwX;qlf%tk=vV@2Lb7<^U5X5u-27{T3fFkI7=C<+xKh?_tqeW-f1k@5+AL1gDfFLaK*=G>>zC&c4_Izrw`#LDh`Tn=5BY}cBi5nEZzu60=AZAuRF>Y6egdg49#1#_{yrL5y6ettY(sqY0vj6(0R|{OZ#nEc7x_bukDD>uCs!cqMQ&}y=YBhVG@5@n1ZtH_H%I+M`y5`UJ)T|_2gLoqLq5(Q>Qv#hmp2tAHoQr^DT}-%T=ufB_vuWq$&F7>NH~Jp(EI#Cv(p!R?q=x&qa8h4aZOLWC6QHg#kuL}GgI3)=b{q4)Rt<+1XcXqdwVjRjHMKaN==;g;L;iZ^X=4+6^Gq{0c6^Rw$Yb=J3N-KS`fG?c9U;DUbqctZIfGv8zoiD>@V8H+g0_oVIPnsj(8ADq^lh`840fyW$K*-)hT)%AWL;_}p+vI%1Oz~QChv(*lt8(#fwLRgvtmv^jM`coCh4=hM6lVP574Ezth+QWso`>pPCcN%FB{P@U|_AY!cRwKh@r-6B#6>6A4ewDMUzJKqBAh;LzZPJvK-%jW_1@p&%g7KpMyu;`vA%Ux_~Vu%yEMkg=lfi%akq0@Vk9@oB-xzUdbVQ2Y2F8T9_M6w&uZo9SnXet)s?7!OH)UQw{OD+e4rFT7uT8~r$;n|JC!0kl|O&ENb4{WvTB-%R;$|1U=#@-jUm*=!pP=<4tm+k?PP1UYNuc2CBcZ1P(Ug`t$A@%u|^k53UuHm!`(i{@T~9J5wi8V71;U?>;u{htf21w1-+G(qLG~~kSyw`^(^U%Mm#)b4NjTQi3vE6hjFRq7!P1&PvIThXrxZX>y=DDbh|7rW#$+ByAZ+t{Mj$xuA*6_(nJai^n$`*--2ri0z`F^9gZ$d`=%?0LrhCL1!vybZ3oA`c;Swl%Nh!_5w5GX;LyEH1e5_qNtl3j98J$AzAPc<3D!Z;vH3_@N}ZkZTV5efJ;J_1dTDAiL(H9oJ#R8UK94uVgZSxEGCJApVUJ{`ga+H>@+@z9UnF>r~dTidiV)fNE0VP>5k0>Z&AU<*3<;p1Y91(AGcIA!b$baGtK5-ZcQ(#hC%i^C8;zZxiuO(Cvylv0tcpq{9?T?~9bJ9Vl^X0>=Imi>TyZtN|Y-7NK?@LW@Z$O-=E0EQ71ERm;EjwHf5vQG8&OArlDqJSIfyBprU&|y-#dz~V$#ddZ4CL0m1e}ZPCNy|yy}*}qJ1H;dB#%P^lV=MmCpkK*Aa49>-)nm9325;dtzACoC8eOiwp#EHC8p&2Ta&RNp7x*75O89=hJO5%7vooJPBMtAmo`1QhdA>%aJ}JeIxO9{Ja4)M=OOaaIbUQ0f5g`EOLaJ&PxMB~Imdj6T6CB0nTNR6{P7WcBMSTs4SsKZ2JynA{A<$JsGue{*?vp|@iXn#{%KP*AoLWY=OeCgV(LPWtusj8Q2Dq)q+)hGRE7G#FMEO@=!bF6Eqlbb+`MA+P9_FUjeZE+6N|WK^OG|}A<3Zn=XCAsRKzo?sJT`b(m{HD?Id3i=Fgwk{}!_SGm|0F$6+kERpB-F-@q{&+Ws}ECDX^qtKw4}L`oU8&8%0ZHX{_(LX)(raB3xCYD!rI~HpcC^mPr7d|s)2)z)Xgg+WHow4i57=w-=`4(b)3+AA4khJ5sS+=0o&?NQs%>gV9>UzN6<(*Mfpx7uFFP-;pY>iBvfx+1i8_yE$U`1ewXeE|<^f?p?!U-GK0e)N5;2zoZ??{OeJsWGU(EKqtddQICl;RKwS2fv)_LY14Z=t2;;&pnJbXvC&PH_xYzrIfq--VW{H%O;Xpcz|NGD$%i>yX`)K62zdQK=TCJ5~=lKm|c?@ma?vGhaggK+(Vp$(6uvr|C5&m>+n3*$Mge58pCAlmM}^F|)R>(zMm%7Xv?{aI4~5y{1AwD9HvIIL?f#H)wvi5N^!WfP!+`_0VXyu*l>-s`v98bbr-&pz@tslWUU(JbMV=XA(@ALS?7jrhxKt@p2|7!bBr!{Pl-KP(b}e5z3K~8&CtoGqi?QDGc@jMIx>cC71^H5)N9vNW6X_5s^0L*Nhc=6|>{gQvFI%Vf4%Hz}z^e=Lf#_TNZ4df=LZ@PP0tIMXWj$3bxXyERN&F9({K|z%u%r~x@Bi7{bk^LB4%OYOgzu5^SRCH5XNpo75ERgNd+8m-iSOI@Mo$fAoGM{_;s&fQJwr%5Hs+jgd#55WBY`oNB;;w(w-@btWV|>SpE#m2d{GON4(;uE+J9bF4Af_Xq(Zeyo**^M6^RCYKQr2ff!0%Oz;wJn@;Q1?MhF1=ca_9`Y9A_xvLx6LvE<0v~x&{DjyKt8yW)N$OIyJL2<$(|0bgE(Bux%%LOxdPE>CbvG5-ZjDPh-$g!i&Ph@}sFntd-)i&9IuQTXxI?RViVj5FeT3BaWO^_2lWjQhpRUUpoS*f3{1gN$nF|P&LLL(B&%Qc>BNispIX?!MA#Y*5=b;ohKh|M9$b@2*=IDh2FyLjEf8dY!$xxxEZPOGW${tppL;lbbsCWB{BMlV#eqD+c2VHi)&3_efJmFt!Y)=AfUA~pGk&ehXt*^|NcnaD2#q+va7-$uRX!)yU%qj`zPPy=8lAI_zhDA-sDK|M%?d$5mIdfw^r3n_s|rRJ4OSe{1GLKv|)x|4AIbzB>Qwdld?-U@mj5B#s|lacz||g$mkhqz~4&quu%o-kVqq&>$vZc)TP4aYA?I)UhPc^0R#~BZd5G((j4e$Feja?$ajukYBkMR4M3pWx>sBGD>3iD-km|ymq%y*vGybosbB~5HjpKM&r{N&9jyj`a6)If_gQOpo+HEXJ9VI3jXku(ZiL@>=W?kk!qZ=v}tJ-BsYD;XZEi0Fbh8iRlxs-k1-97#0-|zXJXP$Xy&ij0x+xG`|QqIL2tDWZ|-oBO?r>V~6qqOZS%r1udc{F&qh~$z6L8T~xBc5<xQSx0yVSaG<6Z3M+1JyO3}Spaw$0GZKofa@94_=yWMD`D`8~D#A_7~umUVK7)zfGwo`sw+o1z@hX(QMN%Is}{T7Kh8)kMVeJg~SQ;1InD`?<_7BuazJg)6@HF7KZrACh@)3yl8%J^ZnsYaMx1`dR@@4yhW7CCFW!Z>;J~G{lg)vv_IlUhL1<;tMW5l@gda?;5wU3-w>4%RNt6$slxvySAZPK4hfL6;oEM9Kf!cX&^?ONlYN$<(9)J!<<4<%iE#y-)`U2oB`Gc3UA&X#(t8yPO8f%|IGvJQ@f`|@<4(+2c~zb8ea_H`j2YHOj)Y@8Ln3`E(EgGau?^eWqxqwL%_+rbXzUS=XNxHdvZOUn9qjNCzI#1B%l4{J>EaPCEy<;DJr^yeqZWeFGt#>aCKF9O|KDh&Qzf0h_#g*8gw!#pjM}Y+{X;|E(Z&@4(FsK)Q!V8J(R6ugNin{?bbSM|BWz4Bx0U`wz2aSwtcAou_2mTzPb>O&U)G&7>DhU_azg?dGP#>R{jbl@*y$2CM*msgLv&HS*?IPW8JZ1i;kTL(ixUtA2^CSdAx!nC?P8bQ;(iJKiG$iHEMha~%C-UD}`Y%i%a><|~RW@)El-VccAn2H&^%u$UUib-umb(_a1AP&Z|^=zbRZ$-G>RD~6)({UJtu}4t%@D@#OU`WCf<$fq~KnqZ<3?7P8Bp^+q#`EgEI;Ty(2=k`&P@}DU4g?@M@Rg-AE4VK7p2O*2g1Ycu{d9U9H~7N6|_@o7LISXFK>E!wC5*t?gRksxJ#*q+!;L*#W4xIMK>yw--Too|m>08@Y?z&z5_X!mZrE=J9;=bE4v1v^|7y+h7?>o{RoOUd{)DNHLfPKVBtDME~SrjuC^H4}RKb;kq#h{e$9^3Sh`!kzG>EaaYvI`bn1xPK;X)y_dZ%Kc$;aG)HerQz+>(0GJ-*Yl0JQDb<|s>1C+j4dmKDJ$F!O_tVLJ~61&8cgN`No&HaNcr{TXb(%W*Q|`}#N4KVF1>@>;o`z8FGI1vuKYBbVCp=d_+JBIbizq?-L%$dk)vb_a_`r7$$|m>J}Z{%f1|R`e_(#wnwDs%!oD+~ST~&grvf!`<{s02BaeZe(d=WpiIN3KX>N0AV{>0)VQpo2baH8Kb7^C9E^csn0RRvHI0*m%00000xB&nF00000oyg~33;+Pe@ynLIH)mdPMoN;%%q$rpE2p~@>2jBhWbaM(-g|F<9q04$;``d~)%ST?O3I2$%hLjlfu>M2maI&K@`Is*nw(HL7^;dV8WNGZig+R#`}-F~YLl_lpRA75$5J~ZD=#-3%+3r4n}h#Zdf;EbQ>EcnxHWEr+v0Y(J??-z;&j{zcg9_CSKJME$31XQ+za={eQ;mg5BJ9d@IX8W55`0AP&^C=@o+o>kHn+!Xgmgoa0brAWAQi~#^dn>JP}XAS$Hze#yNNj&c#!49-fBt@pN2(XW*H*5YNK1@fhcpKi1Yw-?ThvT>&@5Bk5#0_{CZp6Fs9=sRt!%cWUZpH`jL3{`w#z*i`d<-AQC-6yp3ZKSj@L7BgpT`&QMSKZg##e9)zKXBm>-Yw~iErWC_zu2{@8SFS0e*-d;m7z1eu|&r=lBJFiC^K@_zixG-{JT81OA9V;m`OB{))fh@AwD)iGSfgP)h>@6aWAK2mk;8ApkvIdTT`h004vl000&M6aa5xb7gXNVRUJ4ZgXF7Z)t9HE^csn0RRvHga7~l00000MF0Q*00000o9q|r8xYCJP{vTLo|0OeT%>NLpl%atsIH@+o|a!!Qk0k%pI?-c3KDlq%qdON3KX>N0AV{>0)VQpo2baH8Kb7^C9E^csn0RRvHga7~l00000MF0Q*00000o9q|r8xYCJP{vTLo|0OeT%>NLpl%atsIH@+o|a!!Qk0k%pI?-c3KDlq%qdONLpl%atXs)iKpq`drR8o|f7oT60k_wV=OUx-w1&SAEBo?Fs`5Kx!3bhK904^T}1_oCk_5DO=WpZ=)`A5Xs0;#!#)El3JWxq;934Zj))EuA`uymS0p-l$aNvUzCyx5_e0?DNY577iT0EqyqUGhB^vHnmP)#3Sw?r0FVFx0000009610000000GsR=>KhQr$WX>mt)7xvoLr=CrJ!z;W}&X5pq`drR8o|f7oT60k_r-cOUx-w1&SAEBo?Fs`5Hz#nmP)#3KRe?k5HGk2+qL$zxFq3<{CTN0{~D<0|XQR000O8001EXf-U&dLjV8(fdBvi9{>~pWN%+@aCB*HX?kT}X>N3KX>N0AV{>0)Z*pZWZg6=401yCy000000000(000000001+>=)`A5Xs0;#!#)El3JWxq;934UXx^~uA`uymS0p-l$aNvUzCyx5_e0?DNY577iT0EqyqUGnmP)#3KRh@MgUMt0|XQR000O8001EXf-U&dLjV8(fdBviCIA!wWN%+@aCB*HX?kT}X>N3KX>N0AV{>0*X>)XMa&&2LZgVbfaCrd$5CDMy00000002V(00000005ip7wQ`j$;eQ~P_3SlTAW;@Zl$1JlVqr_qoAIaUsO_*m=~X4l#&V(cT3DEP6dh=XCxM+0{I%6ItsN46ag+q08mQ<1QY-O00;m803iT^E%?(z0001i0000Q02BaZZ(nb4bZKpAdSzc_cyw}UZgXj4b1rUhc>w?r0D%Ai0000007C!(000000GsR=>KhQr$WX>mt)7xvoLr=CrJ!DuWT>vApq`drR8o|f7oT60k_r-cOUx-w1&SAEBo?Fs`5Kx!3bhIp0WL-WP)h>@6aWAK2mk;8Apn9c_|roG004mi000&M6aZvzUvF@9X>DnGWnX4;VQpn|E^csn0RRvHfdBvi00000LjV8(00000o9q|r8xYCJP{vTLo|0OeT%>NLpk9+?sIH@+o|a!!Qk0k%pI?-c3KDlq%qdO*}(?b9N0D%Ai03HAo0Az1pZ*X*JZE1RCUt?ixZ(?d?V{~74VRCRTZg6=401yCy000000000(000000001+>=)`A5Xs0;#!#)El3JWxq;934UXx^~uA`uymS0p-l$aNvUzCyx5_e0?DNY577iT0EqyqUGnmP)#3KRh@MgUMt0|XQR000O8001EX3|xSDO8@`>hyVZp9sm>oV_|G*Vsc@0X>V>{Z(?d?V{~70aA9L00000005ip7wQ`j$;eQ~P_3SlTAW;@Zl$1ZlV+i=qoAIaUsO_*m=~X4l#&V(cT3DEP6dh=XCxM+0{I%6ItsN46alX01E&_cZrf}R08mQ<1QY-O00;m803iT^E%?(z0001i0000U02BaZZ(m_>aBO*BZ*_ERX=QR>a%E~|V{~b6ZZ2+cc>w?r0D%Ai0000007C!(000000GsR=>KhQr$WX>mt)7xvoLr=CrJ!DuWT>vApq`drR8o|f7oT60k_r-cOUx-w1&SAEBo?Fs`5Kx!3bhIp0WL-WP)h>@6aWAK2mk;8ApkLPR`*5#004*p0015U6aa5xb7gXNWn^D)X?SI9Uv+L{WpZ?3X>N3RE^csn0RRvHhyVZp00000MgRZ+00000o9q|r8xYCJP{vTLo|0OeT%>NLpl*|9p{}E#o|a!!Qk0k%pI?-c3KDlq%qdOV>WZg6=401yCy000000000(000000001+>=)`A5Xs0;#!#)El3JWxq;934UXx^~uA`uymS0p-l$aNvUzCyx5_e0?DNY577iT0EqyqUGnmP)#3KRh@MgUMt0|XQR000O8001EX6dnJhLjV8(fdBvi3jh=Vc4cy6Z*yfXZg6=401yCy000000000(000000001+>=)`A5Xs0;#!#)El3JWxq;934UXx^~uA`uymS0p-l$aNvUzCyx5_e0?DNY577iT0EqyqUGnmP)#3KRh@1^`e?0Rj{Q6aWAK2mk;8AprP8D`%|$007_s000gE0000000000004ji00000X>N3KX>N0AV{P0000000000004ji?EnA(Wq5RQX>N0AV{>0}bYEt2Z*6jAW-e}Uc~DCM0u%!j000080000X09Nz%JHR0T0AM2k022TJ00000000000Du900RRAIa$#*{b6;|FUvzJBWo9mJaCuNm0Rj{Q6aWAK2mk;8ApkvIdTT`h004vl000UA0000000000004jigChU{aBpdDbaO6laCuNm0Rj{Q6aWAK2mk;8Aprd-3vzW(1OPzL1^^ZS0000000000004ji1S9|eZ(?(0a&}>KX>V?GUt(`za%3)UaCuNm0Rj{Q6aWAK2mk;8ApmjbxhJ>*001}%001oj0000000000004ji!E^)wX>Md`V`Xz+W^!R|WnW`qZE0?Fa%paJX=8I=V_|J&cyw}UZgXj4b1rUhc~DCM0u%!j000080000X06kuMYefJ60E7Sl02TlM00000000000DuA5b_4)#VsmA3c42gBZ*Fs6aBpdDbS`dic~DCM0u%!j000080000X06kuMYefJ60E7Sl04)Fj00000000000Du8ycLV@wZe(d=WpiI}Z)t9HUt?iyX>N3KX>N0AV{>0)VQpo2baH8Kb7^C9E^csnP)h*<6ay3h000O8001EXR9KkdW&i*H!~g&Q4FCWD0000000000fB^}31ORMhZgXvKWMynFZg6=}O928D0~7!N00;m803iSflZ&BF0001p0000F00000000000001h0j_ui0BLPuXJvA8X?kUIE^csnP)h*<6ay3h000O8001EXqC%trRR910kN^Mx5&!@I0000000000fB`*u1OQ`UY;R&}Wn*+-cVTjHE^csnP)h*<6ay3h000O8001EXf-U&dLjV8(fdBvi9{>OV0000000000fC1Kd1OQ}jUvF@9X>DnGWnXD-baH8Kb7^C9Ut@1_WiD=Tc~DCM0u%!j000080000X0D>*}(?b9N0D%Ai044wc00000000000Du8%dISJuZ(nb4bZKpAdSzc}Zgg^KZgXj4b6;d>b98TVbZKvHb1rUhc~DCM0u%!j000080000X0D>*}(?b9N0D%Ai02%-Q00000000000Du7ndjtSvZ(nb4bZKpAdSzc_cyw}UZgXj4b1rUhc~DCM0u%!j000080000X0D>*}(?b9N0D%Ai02TlM00000000000Du9MdjtSvZ(nb4bZKpAdSzc`a$#*{b1rUhc~DCM0u%!j000080000X0D>*}(?b9N0D%Ai03HAU00000000000Du7>d;|bwZ(nb4bZKpAdSzc@VQg<=YGq?|Uw2`0a4v3ec~DCM0u%!j000080000X01RA!c}oBQ0Ehqp03HAU00000000000Du9qd;|bvVQgt)a$$67Z*E_2Vrpe$bYF9DVPk1-XD)7Vc~DCM0u%!j000080000X0D>*}(?b9N0D%Ai03HAU00000000000Du8aeFOkxZ(m_>aBO*BZ*_ERX=QR>a%E~|V{~b6ZZ2+cc~DCM0u%!j000080000X05Ne^_eKB!0Ehqp03HAU00000000000DuADeFOk+VsmA3c4cH=aA|mDY+rS5V`Xx5VQFr3c`j~nc~DCM0u%!j000080000X0D>*}(?b9N0D%Ai02=@R00000000000Du8@egptyZ(m_>aBO*Ba%E?AY+-U~dSP^FZ*DGbaCuNm0Rj{Q6aWAK2mk;8ApjH||D;0z004mi000XB0000000000004ji27d$qc4cy6Z*yfXZg6=}O9ci10000L02Khy1pokse*^#k00', } mrcal-2.4.1/doc/data/figueroa-overpass-looking-S/opencv8-1.cameramodel000066400000000000000000013311251456301662300255220ustar00rootroot00000000000000# generated on 2020-11-14 21:49:59 with /home/dima/jpl/deltapose-lite/calibrate-extrinsics --skip-outlier-rejection --correspondences /proc/self/fd/15 --regularization t --seedrt01 0 0 0 2.1335999999999999 0 0 --cam0pose identity --observed-pixel-uncertainty 1 data/board/opencv8.cameramodel data/board/opencv8.cameramodel # # # Npoints_all Npoints_ranged Noutliers rms_err rms_err_reprojectiononly expected_err_yaw__rad range_uncertainty_1000m rms_err_optimization_range rms_err_range # # 81 0 0 0.5864956382518457 0.5972518353763385 0.0006951826725578303 325.84567147387764 - - # # ## WARNING: the range uncertainty of target at 1000m is 325.8. This is almost certainly too high. This solve is not reliable { 'lensmodel': 'LENSMODEL_OPENCV8', # intrinsics are fx,fy,cx,cy,distortion0,distortion1,.... 'intrinsics': [ 2073.872915, 2077.452267, 3004.686823, 1997.377253, 0.4791613797, 0.0266824914, 4.398264387e-05, -1.180073913e-05, 8.959722542e-05, 0.7666912469, 0.09633561231, 0.001407513313,], 'valid_intrinsics_region': [ [ 622, 0 ], [ 0, 634 ], [ 0, 2747 ], [ 207, 2958 ], [ 207, 3804 ], [ 415, 3804 ], [ 622, 4015 ], [ 830, 3804 ], [ 1037, 4015 ], [ 1244, 3804 ], [ 1452, 3804 ], [ 1659, 4015 ], [ 1867, 3804 ], [ 2696, 3804 ], [ 2904, 4015 ], [ 3111, 3804 ], [ 4563, 3804 ], [ 4771, 4015 ], [ 5185, 4015 ], [ 5185, 3804 ], [ 5600, 3381 ], [ 5808, 3592 ], [ 5808, 2536 ], [ 6015, 2324 ], [ 6015, 2113 ], [ 5808, 1902 ], [ 6015, 1691 ], [ 5808, 1479 ], [ 5808, 423 ], [ 5600, 211 ], [ 5600, 0 ], [ 5393, 211 ], [ 5185, 0 ], [ 2282, 0 ], [ 2074, 211 ], [ 1867, 211 ], [ 1659, 0 ], [ 1244, 0 ], [ 1244, 211 ], [ 1037, 423 ], [ 622, 423 ], [ 415, 211 ], [ 622, 0 ], ], # extrinsics are rt_fromref 'extrinsics': [ -0.003280535911, -0.02376844776, 0.01836950824, -2.133344352, -0.02335054537, -0.0003698665433,], 'imagersize': [ 6016, 4016,], 'icam_intrinsics': 0, # The optimization inputs contain all the data used to compute this model. # This contains ALL the observations for ALL the cameras in the solve. The uses of # this are to be able to compute projection uncertainties, to visualize the # calibration-time geometry and to re-run the original optimization for # diagnostics. This is a big chunk of data that isn't useful for humans to # interpret, so it's stored in binary, compressed, and encoded to ascii in # base-85. Modifying the intrinsics of the model invalidates the optimization # inputs: the optimum implied by the inputs would no longer match the stored # parameters. Modifying the extrinsics is OK, however: if we move the camera # elsewhere, the original solve can still be used to represent the camera-relative # projection uncertainties 'optimization_inputs': b'P)h>@6aWAK2mk;8AprP8D`%|$007_s000gE6aZ;%baH8Kb7^C9E^csn0RRvH-~a#s00000tpET300000o9q|r8xYCJP{vTLo|0OeT%>NLpl*|9p{}E#o|a!!Qk0k%pI?-c3KDlq%qdO?A9+gBDe+f?p7lRw-Z08mQ<1QY-O00;m803iTcY7!NLpl*|9p{}E#o|a!!Qk0k%pI?-c3KDlq%qdOp^Rf@bEoTGT=UxF+OvFo|Ap`Cx7T@`$9bIbc%J9;gk89DUf*~XhbxEI0V``~OQ!>>Vh4`fs2q?HJ79Cy$;HXs(d@31mG%GGwap!ztyk>McINl2SN@U;Do13*j!4Ofd5ir&AMdfw)zfEWyTDvaBFH9o8sz4F)Oj)+;JvxmxG-m-UV!=bybW&a?h%1IXMF(?OR0qDPO?i*&HF$qX{&q4Bu>GD^`p7`CVZ5!7R0eP9-wn(a7G6$uBdoXWG+eydedzb%dHorPJWqoRkUs5FHKtSR34%`oT-(Tuj?j8f*~To#0qA1D>6Qg4=f%V?w`WFBdNzkYJR3;2Z^wiKzzOYX_l{R(@xIp9&8PYp)N_&p>gLhNi}aN{sjzIiBp!fJ@V#8v4QsnB!wgN~#)!t@1y+L%tEgX}s2Qt;Q_Wg#3D%5=X#;!h8BQHnsxKq}bPenw9uUv-^Cg<`5Kqnc7`VZ-oCIoe>LOnt@H$|FriHlaV7qZ6MmX6=dZ|$-c~DEK0h%3P?k6gzJv#p44A3^3mBt^3XJR-nnRG`?wQJcelUM|3Qbi>#19Fk{uROql*_S+?JS0DlXQe>0XIg>vWMSPjKIaPuRC?3HH2kzJoV&)ark<1H##``IJV{abVXtTh472c1{=r#A{qVIqAr-&`n{eb3xBH3SN}y2DyxU6^_>My;%?3^%aM`CMv9(0nc7%f&sTpl3&4av3E;+Lsf>+4sH!d2+AQZ@XsHr>(ZtGM_->myvs`XmxP1;AzzM&n>{o@560wPlg-sB7P5Shz0M}3%mqvDmHFyOW4>vff{RCjDIYafz!~Nh>rzyI5_B5COe;oT5{`-|8dSo&I_6Eq9kkK^XrB^+?UzNS7kC&Uet*BuHk;GPB($b+1+Zj9q~A5`SeG3J)$U6q?&TN4lcY^(VcQdBH~?C6|XdwvI=BQW4R`to7jw#d@eB=>BJSn~k1}ZC8|Z$avta&6>SmDbRD^S$L7ncSyW-FaMEg5o%nCIcXJK57d-L`56{$lzLa9v(Kmr1s^}uts5tUVfeTinUn+W%@Mp|?L~OmfBh%V*Y)7&oc;UON_^+<@|RtzX;?FM%5v%|8ICOzPUET~*q%LluD}&>-*sSIZ?tDJCvlVSV@#qa7Bf|HMObeD_EhusDahysiMj>bK9Ud)>u>aMJ{-f(`+zTT!Xrk2l%oq4q2xwTrseE7%tpL@_KL^)KMlaA)V)dI5*ydoByvTMGqHJJe&I!tMyS#&i_~Wl;gb1CB71i+p54x4=I+q|4~nD}g$&u4b3t{yd7vE~-&`JiySg4M8A2t7YGn9e>R@~IMG2;>S-AbkZUmi^&ALWLZ2bPFsQ+I?2kMI?*}rVBhFr5*{XQ)!q!qnti{4d&6{=DdyrzwiMk_wN-++x(snub7csj8rRk0>duL^dF*XtO{(7>zi$EBqsB-wcC>b%~AOI>I&_d!Waqa2)CMA+H=bQr#+^WHbD7;QyIKL@*!z#&uc#k<@wEX$>Dj&<)wGM~EcQL8f8HmYR%pFSOuu919L%7wUwcE{f}i40Yn%E}!j$8h|}77w?@ZZw-c7qdqH4;)kq{=4xh9qbnEk1~@pu}F8Lc<&uD)W&N`@tcm~hL|_no4I?C8OxozHKh*bO!dNfN9X{KLH_EkVTfCNO?Zxwfp^y5`~BGwykzKkC+<)W4xc*mAm%m^ik(D)+O{*GW>?)LH6|9yY`F53K9itofa`UF$S`gq+#7u;(1V4RK)})-;tAVYNIvUIrL4pcmy`>%&+J8$sx?Q4(t40OF}dCC1{3a|?;6=W%z$mf3Fo1L085cFGfuZjFq5F6_}7|+)fo+EPu%Oln5$vSL-#vi@Fne*b9xJ~pKB1Y%q8z`k>&3&aH{Si+(gVt>&LR;}OyDX#E<3%Z8}7a#2WL2D13T@@WVlE?&2m&fNdH?UxhRdkNjeG-Vf&a&>MG+_Djz}zJw3&#@N-`)&i!OrdsQGp-r;B;4H-@a9SaEFnaKsF?R+{k6C$+${fC0hRXQ926?-rjOFSY(0s+IIml1|3jo+X7O8128{QH^i~I0nQN?449nDFr#FM&Pu3h-$q}9rUhVcu6(+Jg`?X_PDD8G)e*SPT@Hl@u@VcP`P9EMax6ynIvs)r)M@Qf|QMi}3*jjLjYg}bJl3{SQ6!0LY0_|%k62yy0U(h{G5>B3K;GSBKE>v8jkI3fwGO^nXQAL>PR$<@VA$~_Rx8SmxH(FK(e`8yh60zL~bcoKUXp|wZyb@eP6Hk{K9{IP-qfe(B*K0d0C)*J?;cqVZN9`{?yFTM%lr@`##KsvPX0)Ppu_ofM;QIk)DkjF37NxZ4=+K={N!-Zn8k}GA!~YNC}@_OD(6CKMII8bp`te#84Y?1A31a3e5anSQBXhJwa|FM?>K`2jSq%rq^Kyp_2Y0?atrS3WvUS8R`The?^d4q4g9b32*t~N5Z(6Ao-cM94fWOvYL+!&;J@!=1vUdIq2mR=2;>!AAgJNaT@0kw0{6+(KG^!-Kf(1GQ|Lq(3ohPH$M+Lj2OOjrsQ%Jj+N+<8q*1{`M-G<)pXA1|Ggtb+BI~`dc;h5C3{>)T`Z17D>9xoDBpsDhM>qp`C}>}%$)~x$9JKCxnCsj1f|+gB*PgTq%u7?BRa$Jp7Sq5DSPUz{W(dRVOAH%ms}$$`KyQXPm1T~1rfV!;gW`|umQBWMu)U%Q7s6F)EBok}kw;@Az1!k~sZi;PbLc1K+J+6Yt6x&G$s_Ck&P!WYNnJ`_1P{fobOWv*+H!m+Um>zQ@0?@`H^quy-zAgvJudrkOu$@apz4!PeGk}Tw!qR&|EZ9yj&FxaqMf-W&Z>r9T5u|+Il=uAW-2=%`Rs?1@*CNas-+(+HGR^?r;qHqhwemZC9r%`~}^h;|cACpjpIr`$}L?d+Tzk2U?k_8O5T&`MRC-z?KW={NR!MQu7p#oajcv`G*jq5rR#>`*08xkeJvkYSJ*OfigBtl?ad(K3oo~v6Zb*sxoO5X%6|Js{=IAT6VTvNR5K7zzs@;j8b!P~;#XZz?jM4zyuV$o1wspfpy{wFVYgg{FE-4dxwKnW9RV-$V!~@+or~d&z0n=sO{%S_n!|)bS^_xQ7Abd&ogZlMKoJ-ev$PH~sY&Uw`{xb`lJ}rcZaS`x)lSNy>lUnd?`DD1+p#uZd8*7X&%p=eCoqJCyRX}2_7lHkYiH%kwo7v?nc$f(_CpA*RHfn4n>4iI&9S4Zg}(DxXe$Pf{gQD~EZIFRzZ0#L?=WijF;Mwq<|?(SIv{JzefaN2D`vV)3vCye$Fl#FKTatA!k|}y3)0+OXt$%v^NcDT|4P=^^Jvt9`h_2T7X(_c_w*D0-5GOuN=9afXh2!Jb5zm21yzZu0{5OfsEtZEu=IJ2Qk~dhna%Ya(EWHX8Ct={BxD;XG4)`gs%hT78i6S*cTCZFtkTpaQ?K!-nr&FA%JGm%GN}B9j_k@VsEO|fme(!+JMwaO{H74GO4~Q|W7{`ZHMb5iFTH$ouDO-y)A`kZ*Ywd{naiyt+Y2+I~F>QfhFj%sfhUP{F=u~n{HTpCc8o%7tkq6@5CWF1E|X}CfB^mVPyezfoj=#o?KhH<{@iq0j@xH&;=dwX>~+Q~I_*igCvq>@=P(NsJ~ZjDkn)`yc)@)AEYy5UO|XXR15cu+Zb!+C&JkJCQKd7|^X!1wJ`;A>wB7VY3k+wqKrMxlGG=0m!nTa&JMb|D+CzdGZ7!@2KV0X?)wlloYlaMS0)A)eJlWYs0!*=g2+qbJn9hvjua{8>Tw@0r!m+@nzt;77okrk&G!LOWrBc6g5qwHgOBwPPwoNm#4(R3cug1L|%;(WoI6`W~Df;4vlRtNqse!6r;dpLxFF>)JoK_R)|&=hmu~Jvk$2$JY-0{lV`zR?~r7`mMr7R|oYIK7(gL+#4e$Fc7UQ^!0`K|k-zfIvybom^6Xu5AFC3Cmcu4^AXvb`1tq*xZX4X~yg09qH#Z3AiW7@=~L8GTaoIJ`iX&1|QVy3IdfE@%6&zt9yOxa9LmUirhF2h2Ke?PK+a`>7YUyipg!4I$l9W?gcY#1v&w51qd^_gUdi_Jn4~B?l36ccJT3?pGLmcGuqG3Fi`y5*}wb_BuqPL?eEu2K;ML!7xd~1s4LyO!!LdaPIYyt{d+r!#{>5te!apU2jta$SVq<3Q~DNaItLL;CXUOeiPXUK1`efN9|mFb-K>^+fiZO1wl;I9n2GItcCu#th~K_`Zg6@|#KA5#1;(X%kg;5QC^E1I^Op&%pzWWO7eJ*u(?#(13Lg{+GzDw*f>>U~RPU2&pskwp$-K@6OOK&nJH@-v^Vr+-;m_*z+pCh+Tvq&mz>Foy+mPkII!x;)9?$L-=`W;W3!5?d~C3j)BbUA9@s{c4ToEnbZAt=#qI#rt`mbS{EW)ab4-iA>NTIKEmK8-kRpF`Wzb73gz8x5^}S1PUu#eW`j3^gWp`CQ-WxAwT$>Xxhb~ZoA7Nd(|*xRaoWSZEC=2F-CNh^a$*bE@#E>qv3M9WaxCoB9OKoEVA5I36XDq2&u^oLwkB^%`poK&i>l+?XJ@>xYAELefUX5##NU+yh$td5;Cqdd~bv-<+W~>MZ>UgXXM_Mm3Rc5C!1_n>N#6*lpSYKi+=rm+T_N0_^@n#LR_K^cJDd6(b;1N4i#GLsN(BF_30h+-^B)jF-PhvaIC->tN)gaug=4B7hPSh6`m3_9WHSlAA}6g;Ji|i9yH!xEueq{gc>s*Ihvi6{=3z~Xe&NfP(;!pz_xmZhulvNUSg9A>OV25th+EP5!u#uFdIwP@IwM?5bO6S0UpFv%5stpb28Xk#laLpkf4DHH7lh>}N}gQmfxG_iO@(WRv4GdS+198Zguc8uu|_!wgTFN&btkalRO+UU37>o64VB-vP`edeX4EfaD378fS3T!5u0e3iF*(YADjmfZ=!j`at#5QfwHt1y0GFDzh^k#lvw2w_0u-gt>;{rJ|N^_$ou-pZxeJ4Ex=>*}1(R(i}yvs6C*=x`x>SQ_(RDo~wO3%^ZMKfmAHi*3ngbG_t~rn+9LZ_Q6r58<%p9HNne<)uX8?V^~~%cBdQvNnOmyHmWT_>>zQo$GIdN^+JcVSg7z2GAI<{V);2UQBLvR-cW0V2+JIq^5npIig)();1IY)+Vb3+k?41tH$epaPH6eZ$Oml9(`_}OlW`ZTOUao0{s=yjO1)W-S-cS3rU1}T*Iud*NG@5aX@bJg6uvuvGJwIq76$i~TYhT{Tr9(rpxcMEgTAa3)wK#lX9E1}~Jlt3GuD_FCN{_`XP{w1^4BBFWd#>QM%g-kG>rjwy?Olh8VqHo5{Kp}mlPS_yM8ikF{>$6Ca~Ag86}o(I#ov>+t#-|8GQ`c@7z({#hdNu!H=e2)hw0gGl@dE>$P-2yT-`APNnUTWQ&W5^&E{y|qJ$FE0PdI+#E#K=p-47QZq@TngKYZ7<^MqPlDQ+h2Z&r+;;AWRQU1f^>V9Gh~wN&>GMa|oBuC5t4aXUU;(E{L{;S{t#99HEg=*4?f=a^g#D^DpozJ-8@y$2Om{L%CCvN!4Y0hmlUNQh)h1$5x64+iXti852b7I`hyc}X-g`el$O6mtnLNbgwtg_g*P#~;aX&}Y$tdmn!CK?af4IOOsoC{tmrl$=Z{+xsd#^mliR0`1%qECwOOK;z^%H=)b)HDSQzM;M9JKP(|djyi`f$pCtrL`Eu&(kg#0cM0~TyMpcU|)@f?mlxk=_E(?L_4Ywt_eW3)cDFUK>Uh+?ptN*$)6XJ+nZeU}~}IqpsFH;M)wRg<;dR!wl+!i_9b7>G`j^}}Q@680>QRZiqJq3ysng+)RaWH7sR6D^Y9>%+bFCs*e4Q>$LIkmiK6A%crYG#P*N%)ZwcZbIVw=l6&IbUXW-S7v3jgcH_lhEL)}x`YYaZp7A26V7-nnc(D-SYrhJ;nj2&kO~zk10O#j&^Q_8-n=(+dT^5Z~n&p_UTj%R6g5B>I9$HLin;)T-uY1olH&SSZy8AVS!Ua&N#;&$KEet~@r(6@#tuYb1!2*K&D?+5yDkDrW0q)|Gq+5Gj8nG79y>WVH>eW^HL-K=zXctw}Ruk!AhsRWg>mz$1U8^ZJhmbd>K%*9i$70xC0GjIc+;sx&zD&`7$3xBy<4hOV6c@v_lU}#P1H*)PLI{wp@MRAM3srtI!T6rXM$;qMari?`fCdHZ_JqnE`^v<(v`hCB$4U6g=WvWRl7Q1yO?`@0j;WbD5^i?b8H(G?9QGfk#m^1Cs5$lU?BkqX9h1?myjVbpxBc7v=-0C6H?^0M{r4RA=pEQ3TZckblllY?EF>xH94~m4~i{FADtwFbL7b2iV8+m!?Mt3%OTXe>3SvUbtBN}6|P(K+OU%A=)`A5Xs0;#!#)El3JWxq;934ZWC&#uA`uymS0p-l$aNvUzCyx5_e0?DNY577iT0EqyqUGnmP)#3KRh@1|R?cP)h>@6aWAK2mk;8Aprd-3vzW(1OPzL1^^ZS6aa5xb7gXNVRUJ4ZgXE^Z((v|E^csn0RRvHK+pyN00000bx;HV00000l%07zRp0mjladBf3KbG%s$@ut%Bob9v8YHQq(mZ0NRkqTkYtW1^3K=!kfB$GGt&lk@^Z)rXKX+Jne-G=VAuI**CwVXmp2HdvA&j2;kLj#RX+z0E&5*eOz8u>IX8xEO@9lR9mFEn|qvFS#>MhMDjt*xN1yoXg4?hOmt&f^JEIh`2X=0Q9RF$f9PL){6s4SBpF=>G9dw6K20I*;J^pz`*XQvddTT(TWN5xtKe6f!&xq;U)W)Nav>e=IOs%X=m-o9e%W0-I{uYi@nL#MNW=xwNu+G8Mx2T`^fwgj~o%EoR{q0^U46@U#35@}Y~@21XJH2&akKJV{5cx8|D42O}ChNzM26et|rwX5W($DLT9t`Y5(cGMLN7KDWx=n8Sd<`RNOCp8v<2bX{AQ{VgZ2?}?3GxpTi>=JIb+ciUHcvS7w-%X)u$DEBx=-Z(ltH?u*hQ%h9TF^tO#)77k|t)+m}=^fLqgkR-y-{QOLmWWZopw6)H_h;l;!ACq9GYF`pcQ0OUh{t)EXOK@zCLq1BPkihgq+idQQKK;PSteH;GxJbch&VaU+U)joU7*r$WCB1(|R>#QKET!$@v?UV(`PpEe6x(ya7WD@JqUh0IGHe+y%SxBO~@iWxCn9-y$&I(!=iEN@GvofpF6@HMQkNtdQVr_N)=C9cS8!@o*ym`Q-Ed)S-RUysJZqij(}Huf$J7}MsazUT4a^pMj8Z`=AZttJete>{5GHZK1u__kflDBqSv{6`OPf+_<``!9$V_{*tdEEndZQ+uJvLzYo)h0wK1N);k`do}z;lH*(4L=3TTrQfiEPRJSdiaa4c+zT4#qw?~nGf8(D%FPwlb@vci@<*4&?>V4zeN;I%32)%l|6m?!Idwk>J2O7-yr5Uw!B$mrPzJR`SIvw6By?DcRi{o;M&96trFEe1DjL)t+8VOvUIInGke-IODHqh_K?@i+J?Hj4y-LWh<9QehW@g;@JSLg*7Z8D|+L(eHL#uW8zW6;mOC-3K;Ki<>_La3*H`l{k}zo~G??$>4SPUM%5cuwo{BVd;2kD2Y=*v|!{%?0wpGI`3zlZxa=yLd98+d8!%M&-TjWK~Ec~V0w4`gE`r#KVq!||5+yj@_QedOTI__f0vB^O!`59?w_hOV=dJGv-*3E(?uGLU7a~Cts@w;7?1wq7v=GOCIrk|;-z!!BI>UiPYj$_L4djRC&A`PsQ(`2=A6xYXt1cyLF-{X^7}b^BjGs-kh>&R($azL(v0h42X19RWKuruj9faGmlg4?EZ`&Wb6@4V1^yWr?>Dn^n;HdL-uqm-rj7a?ymG!7Hc+7B$D6IqyHWo&;{(43d)D9^JAVo4OSi~Uemu6_0P`V^7Jc}9LK)qUj8nN*QNGLyYfmsI`lp4xRJ3Q+qE;|j*tIWI-Co#D^mBwc2#zq(ds6j_tIL8pbMpUxcu-1L-p*6JUH~wH=z3^`iBc+E-h7g6sUe66>yt!P|cHf^w1#(;>2k7BEumABTT@!)rFBxMrkeKeeF18STnvJ9D?peR-;ILmHF@x^Ljb9t2toc-i33}~mHSm2ZC`cyIOF!wl%QeOT!J2@Y0TO5s6^f>$%|JaEHLx1x?c}<&Fdi+Ihe1>EC=gzMb=&$^Gb;<7_E_cit@|WwR!hEgcYAO22O|KL`^^PE5uGoC{__zyP?yTm0(?gF2QeK|cuet)cy!_)F0r@t?|I_3|9F#b!n&obUy=-%C%3cByAQ)x>F>yY2uAI1MVmjGppv@RiO^dZChbY>?ZksBG*ez9Ff2lW>RfR=$`CRw|2<QT6S?q<_#{N^!!Csy(0yFX&s?cr`>Bdda|7cUi?!(FX%*_-^-lND3jw=P|~5ATXRuos8_b%-IsKjzEC4X*&Fkt&H~A0GieN18j$e(m=fj@B}?PYVRR;(UAk<;ELF@GFQe0s)t0ePI_xo&w2?sX_9AsOMC1Q@p(~74FIGzwvlI`VIbrm3jFK2`E}(o@FVHI%nywP4P)0^HIgAi?78|r+<^O$!c{Py!B7NynYMj@#w5Tv!Qw#^xIzf^g09e&u};;mU@E@17YpS&$pufC#!}A%8oFgN3zV+C>He(tq^RDG+_e2uVH#31M^);k#_hheHJX4(y}vPB#p~2Cl)5_22tSqX}e>4`ceP3s^f!S^r@h`cR%fMCF)lb%#~ayMg04{?LYl*b?GZ^{z?cVAbYEx+JZ6EfAhnxX+z>PNF2>6P1=R}mwX#P_l!=1JMoq~U%H|GT1lCkDK>PtU}lhX#2oeSzdF&%s{V!!Q4Hd4%ol9eY$XBxNx=-LoA;tCXg2zd4Ama@cms0&csFlO)&cYzq}}kS^`k)HMX%iqZtRIe$I26{egfv+U;|H?nM2161rjg571y%~5%f5@SLz(c!_lZVk)w7=i9Yz>79OZI-ZeESl8#gx3FYX^=KV0Vn&-yax==k2G91C4xLo(D3E}cr739xm8o1Rj`EytdXOkK<@Y2bcMq*W&w`Ro}xDxWCQ!TDl`uj?b^g{i&u$>g}yG7x(A^DpFEYp9-~YnZUz@^Rc{`~Q4PlP)|>(0t^_f(xGr*Yne(xV&3eUCOzG{qOgwSmzPG@OydgAquF)n!AdhLtnAfHzjvR=`$aB^`Q0o6ePsVBQbhTb|@7#sHlsM~lk~k$-LNu&$S5fluL_Tjbcxu;arwaddpZN;_r45)L=bR9<7#U%}p^N)B9ty+!n5TLDL+N}L=xDi?WGQ2QA+iQCj~KB*w7Peti}ZivaFg!*T=zAt@f1jrp?&(%gnGWp4tolnpu+t-aQO5|)bq{bLaLP-0apjpPR*7|zqI*^+l(}X%N2W-haE=$L%irA}@up79BgW*=7bW|o7w4%Gkngv2nb0KEdEMy#6I~_&q0ysK%76ajO}gX1c3zomK!f^&r%Z$uQD@Vzo6WpF8vN07d|I{{b!zsk-FlirhZch>&4HPi*Hj-W%&rSyK$K;{Q?Fs6D6=c7*BlfudOU(-M=Bgj^&7WvVVw2o?DI?TOw=f-meUKgi(d?~To4A}Kf*<)66-=MW?#ZW2+z$fNP-hW8zo3FA74m|*qb6NKeprq6`<^TTvhEQX+j;b>w^5eej3wv4IUD!--usU?=}KqrmOi?G1{)4CtUtS<{;(N|F1IsjkWo-9zD*bPH>`ZgH?WNkzAC$;?1wx_217Fn-h7FfapDbTPoX-%RYH5=rc}$@l2aRRwlMbZ;e%o#wYNu|;RY!?&;%{Vlb3H>*67B8yF#Ou3ColilW0_1elA@2~bo9JrVJUG)!fz0f;;9`M(V@Hgl@39|Lux|6TbXkRd!%m}U>Vi-Lf*wg5?r28;Ftc*WiF7R*Z0`J0zSJAniF%*qitA3H!{FVp@AG=Fj%2;JLh$4e9nR+M3_D@+pRa4u6_mZQdg>e|M7>#_{NYX@mxs3=7+Srb9GASzHTmZ7)N^Jye(`pR7LC8R#*Op%gw@G{PjslDGG(2j8WVYwNOrXZIsY}?U0!SDh;@<;3I%R!$??kDcG8y%voU^g(u4jQG9THq9V{G9;5yN3ivh`0b<$rwBc9%SjCGi?N$G1^moi|vi@?2G3&Od_Uw6;5;{GNke5Z5;+C_zNx$pa#Q!7GQ;Pb5g{?_ft`RR2J-6rLOW}k4c-XY{i_bzGun@9nDHAq`mhQ8ue)Fe#{Un(qqIP@luw*9mh5@V7+QUZ*d34|FLbl&u_s5p==>zht=p?M%(^;Z@tcf0`1a(++5_nYWv*F#@Mid{FhA*xL)RCKGwLPiUKTS>+s;K=qvhE#QTP*WInofUtK>R`BSIPrh9t{I9IrGU;Gc`t|#q%0y_!taCW*mV>SAX`x>INB5u&2vGG!+ooza9f_e-nGKIT87am2yM=#!Todc)aO~J^F!$2MKpKo@If5*wRh=9B^H1+0v>tcV4rBayY5)KwbiuPn#9Bv2~mR$3L%Cy2?|>*z@4w>pSnMkTm!+>X<==0Yvc4T{ZOfSyFK~pn2M6~oT_9#c4lamY*zDhB`dH#6n`OBCGW8HW2XH8*(r(L>u-Zsn^tDVl4)lX%CJfE}k%VlX?{$pnQMXEF#`fMuWc<<&06!dkX^fnWrhyGP!Q42Eym(Pn=By2L@PDdzVRby}?;B{mFz}na&s`;^ZsMuiO!|9WneP0Fy9o=RSu%zOLjX*K-7j)aNjbwWbg0>M#8&Ie6q!JB>VFD&eo29B(Aom?E^|d3%t4N{rD_+M@KWCo&MTQPyzlXM5S3vz+vI;J@y`e+OwWNH5-^eQk*HFZ-F~FkGX{k>ew(G`^EuWJQG2w*l2+OMn+ogYOmUfID3kqFyT*KyLURFFb=c$+_6@)K~?7iWNI;Yw4%eKrSK;cOA)5qVC(?;ZGMV}(zW$x!M0$!+}e|qTRzg+|*UU~eZcn<0el}$gs^8^iK&5l?GKS6Hp-YoWpj}Enax>hX@LH#1M;wM6Bbm+F)yfM=W^>fzwrkgRKEK~g|gQsqDZ*gx?g)kF#BxL(KoWOSNBq!pc^-OpjZr-RAkA8!FX_s%uK`QL_xf6ShNB>SvL3$pPXOMoFKFi%j0)1LIJfd{=(_z|-N6`@~ScjRoZ^-dVY5&q6cf>AnxpBO}R)sArXf`olbM@y1E*ID_V?{cZ4QpgJTmP;{-&K1hHIc}pOzii#u^aPyw@r7n{Us_`-50;Ii=zeuj_IiiZ)`^Y)*K@9daphc?(}F*x$A^HuqA0r#$^@^Yz%KZG7!P#E9PYWas0`K6#nu#RXdSCkMbCHC-d)&!I1R}M9@EQ>Wq`?so?m6Hk3PzbrqILsr{j21o%}Sq^dR||0ueY{g=!~jI%HHzb-}oz9+XCkjZvnauWyl)TOkuTQCLjM!CIm&XY4Fj5=KM`4X7voJ=&$i7w&VHBd&bOZ7*Mu(tZ84W(?7LR71Lw-&D>txReI^5cQE#=iaGzp7s1WwTQ16nEKBlXLie=ws*~QK&sp@Ke({kzEYOzQ;cFj(K57zqBUh8xm-Vdd$Z9`aFLUeP@2P%{3M*$kRQ%wGe&ggytAOkkGhsX^jmz`fn1Ao4P6Q{2szwtWQ$@Mc0W_{n^W-f(3BzWP)r74MYNUOHd(|Lh>X1?Fj;!_N8kQ1T$-atP9w>>-L+?ZfXC7OgIG4H=mkcc`+-p_)h;Wj;hd9(fSxm)iavw<)d@7*PW^Klp7hsz>qROsGVy8UAhp7(NnIa^eZ0GlACvX~Qi-sp%=Q+)~vX!ZGMc#+44c}-D6Ddy{ipfvqT>vzhTv*MR8`pAXL-SK@&wFLnx;blh53&=}XwtbVYAYiuePx<5)I9VOdKG00ywQiJ?-Y%2$DSv=`@uO2m50djfy3-rSY!%e$CXzRQt2qrGedilcr6bP>POX{KOao_Q8;7Xvs584}@7}CHGS4dBRCDb`?j$eq`qOF#lstZOZy)iWelj1W|F%E=n*mE%rs@lVQ9oz>qU$XaCX*8+rPG+N6DSG~4&7(LhZFl2W}d@*&Drn!XgUG>XJt(e9Yvj-{C<-hhl8J16%BtvE|^0Ly7-;|`Os?*!fa7zSyqzWCGz?PdP(Z~4IuZEAN|%*M+327jmOHd*#FwP&)pkb=cL0^MY52zC1y|@MOm3$}Z$xh4$VA*^rVSlFsGl8(2wFabrZq~XOb4VY3)Tg)ClYBNa;d1}fl`h+{UC-BjZzujT!ETqIAKfyW%Oje$mHCHKz&E|v)riUCH*P*yKCqVxQJr_LPg{xghYgB~TW8A>aLxIB&;3aB6>=$i*RRYaz_Ys2eSS0g2Rn5ORcWLD&3_jm?_kyM%Om|&$wmGpO4{fj3g_yF#C6cYesjgLA#bebxbq#kuHManpuu_T^bBx+PWk({uau=&Fv3`@l-3%;<(z$B#@=kG>3~`dTUYh!KOa@ij^%`Z&A4XV0OC^9WE4Wo}S`_>rHCYHf^7&#sGVUT#Zu`_H%*OrAaHanXvkCJU`P2`8lzjkzFn<$g$2G(|L$~Z_3(&D?Mdw2-;bixK{yr<=$(D9Z0`1dSl&zlIfWD>x`7BOGuw=bAXj=OxuCSH0TrVO|RkESEKDS_F48k9puE+x^9KvO>zh{rR4^l0buQrlxGB82XJJ-9*UcRvP#T6}wv+qtBUs%)U!MgAS|I`5s@2#CZEncBamO44{bYv0u=E@#$H~70UyeP$c`{Nu4rJ&~0JX#75$(D@blg%55&ylrR@=4aFAV92u`C-t(`eiHdSGQ+b^RiF>Kc}MWX!UuF{Nv3prt73iWv&WEqa0CPF*4C*;hhTnRYdmAXnQX7enCVfMevIe%w(1xbq%DiMYs52u7i^ik-MN$vTLZHW+l-;Vx@`DcnnYiih61+dBW%UB7)qzI01?-YQQTBv`R)hgaZvcRA#xj)~CWQ>@0vf)M0CJB?3&ctW3eu7`Nmzc{~d3S+<;?}IVRx%2TR-Ep-%qegcogemQ7widvAk$G~flBPQg78XTjLm@Uw9OYBPh6q^qZK`9R+6&b&YxEOLm7+!BxcP5|?-s{|c5>*~z8sPkJ>+*`k5ItVpBd9W@Hb!zQm>zAElfOv9jXod#rrOF?Ex16Iny<XXb&Iyev2SaftC=lnS@mJYhoBi+YSQ2+P!%75OdGT`ZhzHZyYs9(r*p|jq525|O$4CtbMANQ|0?qN*0c4>E;@pAN0sjCXcH<_@2Q)kjp$l>w>&O!dtuPG3w{PbSu2>OHe`iJR%@}uTIBVhNd+zeZF^bfXEe;v2CrNNdmlWZwhp7)Px%7Plj=&;O9YOoXLW&k*N>uR-+#aIq>mg!9F%b3FNb;9>)FEg!FKpjV2Y+4qUwM7K{0P)Ak&zZaxAetdbJ@^pSJwP@-oDaLs+Tezb>YooG~Yu@XNG_d7K+`bL>{EWGQ#$VhNx6R&@3DUvEV=)#OA5=d@!Z?mKvCg|(3wd)!!n1%@Hhl4!M=9m*t9h$idVX*Dfi@~QmTr^TSd6~q;xcJd_5lJ;>N}^JHy~G^tSnhmN5J!w>;PMyeX#2i!Y6HWpuvFD*s~=v=tE>P7Zw-`(BWiiKh@C)`8$)f51*6yC{0Oc{6rA)XUj^HUdJ(jd3xJ^%@XuQF7$01{Gyq#(0N|e3JLTr@!ej#&QZzxxp63Nw>SEnv+D;xRd$o}{fZ4sb9<4;hQ0p%L!6xNe44r=O$PnL;A876C4mH_eBbH=@+n#Kbaph*C*J!wErtHa?s8(`4hjR#PgQjUXUzLQlGm@uOk{$RoXVtvrx;&nSXked&4Nb)XFD>K)41_5b`3&z>ez6hVe8F9x6-)r8khbiExZ!9Dy;*qHY9A6!fFLDj}&I(3U=mHwlEcM><;4M!*#CVIjW-1L7LYB3LOW}E)Z);0k*P+8Ge=A#vXZ^zW!xt)zoad_f=^5J9AwMqK9b?8|z`A!qKeY7Ghp46oKAjfBgqeCKWw|dgZw3YUO=m^2;OcoV$xy(1V23Q&mT)=+aHkQu)fP_rmfs&KdKu*fGqH%q4#-^aGf{sZ&NIq7O;i${x@>#)8zNAu(TeV!m5LE85F+A^p|E%2IQoyWIHY#}d9ybtb_1j&Bk(2K7iBWR@npAwXX|VNW)X&b2GOD@VzB&=+RYRyQlu!}>I(v7Mav{hq75w&6AMbq@R;ZR9*x=S64nEHlj4logeh0%YD)$eUdnT;6WXBvq2`+epC2apj`Zf~bcv&FcJoBN{kdce3&4c`xtXd>6UzB{bNvC2aFTKI~`ny&KCr$@adKS`)b-8oBOs_og{5bf7Fh92Bd8`p+FTOKAvUfTw?G^Q1Q9gKCRKigcN9+97w%;%w9((rsCHmGqOVS8O|=aTa|@tAB8sXCn(9v;9X(?a+s;aO$}ldX<31kMld6Vo|?|=Yd}}7iy_*)p|*rcpfbmp-vSKlf8Ql=x}Xbq}_Nva`7GVca3Z5aO}`|YOg)&UoPsOwcDKmhed7ol`Ka6)aggVA{R0t@t5=VtS;o{*?RTjRZMsr;G^OE65G|P_i#q)4Hhid^u5)}M1NI%s8>~U9~I8u44QfL9r_B1X|dt=g@}pyUH)#K_h{bur&stBaQ|84w0=7JieL%qnN5>vFmtJ*|5ZNp6(h{hKhNSwztR6{jlyd54~LRtn7ek;VPbt_2l|Jz){B&_7BL`NtEfVpXCKb;V6l2*A?C#XhpImGV@>+EinW)K^P`*kN5z8Bk9Eka3063;q08)^^u?F|t(U#ko#tKjq_va^@5JhUjoI?}3Ym%@Hw*|!TE1g?pD^-0bB?Q9JtiPjDr}1o75xC`J-A2PXmCJGG$BHd=Y67_vci)sH0XLV`*qz*+=pzh@My~71p2?<*I*rq+0w_%C9f}M-@bbo)?qrO>#a99GvP)4X`vnE*q?pXazeX8Sipbg)bATVus`?lU%#~ZEgJ&e;x~Tm#{O*7D*X9gi~#e@<0>kh=pVeKvX#8f5s)u*Tjt0six4w3U;&ifI^E+F5O@*=uLmJXcvGV?5u+Xv{0N`4~ezw6k^l~P!T;kxL}9|?xSJ|^aaiYxKP!D(Ydp{@_-j<0U4^Z4SS;-HUv|zS6#Cb2_lJem!Zh$2v^@y%ML*!VEYqqO<#&7shkmYrE3S0Mc&GEDy%`u|>?i)OsdV2)fPQm4NY~do4c}^|C-T$x$qo!1$kUH|~*Hkq=K?UB66!fn0RE^yNWUV&Z*R=5h2731Klezr815gZ)8zRs?d+KCZG|G;s8Ac6z}??i%s=1pg-*WCYn-)O_Zt+a!c^wE5EE?ZNgrw}sNUJSHJCBSVb=T}LFpQ@5mX_1I+uhC1^xVN>s~pJD+RU()zPBQ!GoE35{P&k*!y_!1>gw^!MFjKa&ofv1m&)fuY2TI%_e1DgydqpE+ED~F7Mn=kOv2-T-?T}omh_D?3XhH?Rv~{P5vh2@iw5~N?=I{T#^ZhhS+Jn6A_K6K2=F{O~r`f%5p1J`u?{Jc94mmEp^lUeuhxzVT^Urb(3kJL@w;R3~gnBOh_2ge7$^`aDmDO%Mc|0)daP6OOOyJC`Mz5d`*{S=bORRpA)>t=&tcEh-53`}$}5P$lY&%?&-VU4sT;TgFx9@zgg|+*{83-J!uUewe>F6uE@l+>7c8bcpNSIX*bVQ#Z59-(b1vt-fJ^T+McwJ0n65>*7fuwmv;+@)0oAa*jJEr5p{CD6BJv`gnKVG9C$8|`MNE7{?iPC17X9j)q!D)^Jx&FDR-fPXTQ+*Z$?`WYtUi)`ubOca@fzqEq1As3rN3lv0cPF2f1hb)DQ0D^=&;gD|Zx7f8_QPa%cWB;K!l(jy=uDg;RIDD!I=DqYvhvZpWbh2Oo#3{4TLTdsBj>ygB-fEm4*Q-|X2F>k-Y1(Qo|S|1wHYS@M-$bgNxb7&A+_q4cDfF&C1h<19ea*=RFDv*r@`8pnpig-I&6qe@%b1u~x`v_eI_Km&xTB2;0q-7qyYXS&=B|wHA~Q)gXv#mc_Sl5Ji~qpr;-SpJw=M|F?I$S>W?z?(Fw~eoQle^S-1gHcb6^Sz(bh`ms%V&L2|w$@!7>-N+kBSSNXRj6r)q&J%UDRy%(4<9W}w=Si*Ymw)@pBFvEgZBJOez?lZquMP<{$RNM}{fEreod4YeS`%P!t2Mn7T~;WQN?mL{;HLFcS=)TwG88fqsm0UGi_SCdR#kr;(TL)C%EiWJ9A#SZw!qd@ozjQ{J^!lK^dcf4S*&^a;QIx<6T;LV)lbt-C(6dG^6BJa%r2I1N-zK3MTu3^~2-p{{Hy4OS@5Dw`#Re8%JIHzq)bB|2{Q_HsP$JDco1J!O~{BW69dy$*XYZp}_=LPa#HcOvBjeHrgZrbfPG*AdO(f-1-el%xSK10Wq4(kH^8;6ULC(bt$9hYGMr!H97{U2}Aec2wcw5x{!ocEZ|O7X1AbZak4`@n=*-f?yhccE{2J?1Rj)WU)r2L%vYP(Hl1D}1E?7~^k^Op9E7g@9}ImV?sv7=LZ3`n%H*IbS$*u0AXpc|f(iaiA*=sJ_eR=J3>!_E)y8{WwH}V_OrN(|P>KrM*$>MX%9;tvd6E%MSEQ+xExk(RCT%*W>m!{5r-jx?n80avFKxiVZKG{te^9_saNOYA5Hvcisp~Y~soLGu{iAw6Z|p;-)zNRP-&Y#4f$a8fSw#`Jh<~qCZ(AvV>AZA%IhlAM)q%Mf=MgW=YT{#={>x{>^pIS&CIS4T`9dOZUyd^IlG^dHF?@4!dSNC@{3f^YVAy-aU{-hs(o~`+nwQyfJB%wRbb1?$i33EJ@TeczlJT1L?1R%)b8dGe7!}>IAa^7U{2McfbB1brJJpcEXj%OB&b^&pzjvA&hzO^si%dJeHU5weUefdbZl8`i6?>YGINOl(`r|uW=oe5YXCFl>=_f5lJ=e<%qF>r{=%KH}Cnl&WXNg{pMg6}rAKRRH#G0s|zgElQ#&g!+O{r|~O%3=liD$j+Zr9+2*X;y&Jb!Lx$5Wpfb6ci!*q8sZLY9q`9b<2ix4YsH=>B!zCuH{VNym#Brhkj$}c5VK>2`oqnFP&wbhg@pUz1IDHZ16B!DJy#jeMotV+f1=Zw2AjR`}|R-@;Zf|lJ>NT@7hIuLq5gg_FkR0G>CiWsAjew^^bpae7wVe4xD`u!aViBjb)c-HoT_88}%!udIwQ|qS&MM6gvhyeN-BkJcQiBiB)uop9za^je1fmRfY)mcViTF!^(*n*!{C@#vzrUpKnn&6GWn?X`cXa#dYWkDU#bi#w>OJODk$vl!f@AcFdMw{+tYhR#S~)!IWcfi_}EGZ8RnSBd+@7LuZ}Y24%Fjaa+>ppxx6Bjrxa$N0a3PXmtX(%{#a>gE8ReVA{8O^&|$6GP}p7h1eK7Bf9g>152Hje#fb}at%i`fj2q3et0^Yk+(K5~Eo^rW7<0xL0|Gw+@;%$(pQ33wlJzRz`L5gYzgdw1Mv!~Su)@8Y?qlL|?RsrOFu%*VA)nTFi9CSd;L`_C$Q>g|sQe}0==MNF*YEd7OfDrojHtA27mrSP#xO0k*eJ!{T&>81Va|L2%bM^9E>Q%a@7mFI3VZu8XnIqy&DA7g+Qd0}dgV!U0tI4j4D2~oNd-p6^q%g0&1kKW4yvYTc1Kf`{OvU1Q_OpaG4$p>eQXB~>OzVMFplO5ZiDkUi6I4o(c-PS<*Nr7R0X;4Q#a*(q1Ht8qVubRK;!W!hxk36F#ZqZ;C=fTs)e9GBZ9jZg0`0ighPyB_Vvef6~Jcx6BLRB!n?oz1xp?n4$deml-$Fo1yG%WUbR3Z~L%&5CfjAMSUIJo3waS985`W{O1d4<=7Z2m{fA~taPFO#Q!VzIjRPq#Y((kA7znOZmw&$%1zQv8X4rz;m5+&4kqa?#UUk-Uza&j9Z}g52gp;b4Cg4TM}Lt&!l_Z>*punCs_9hq0`_s<0T$zb5o^q`YHai54qA^)N`c+4$}oCoPNJ&4!FJOV-YJf4Wr;K}eGfls!`ReKwJJ+IM#d_30qg(AOseC~yS1$5w?UyhCWbS&FC^B0p2#Ho4Tym|J|aQeUg5CeYgZqC>*h(2K*OT#cpfeDed5}sD8Fi**S{O$jJG7HGZz17qd<2m!Ugkcs)>Y6V!JB;xhee|8N^0e|P(?gj$%#H;hI)iC~k=yNx*9W-cPHF!Ca=Qy12qn42K**0P{JSzqHz8BUDtPSaqnK=@pQiq%~&Q!LL^CQCJh}qn1?s+%Fog4fS!GO(i+oC&7Fwc_d=De3N6FB4UwksGPqA2e+OO6GFg}>IzBOo7nkDkCsY{x#?#Mm{&e7N8gSk-DA+8rl-<^yJV#1u~EkcUj$oG|8I5u4riV9uUGCwU1*vm@~SUOu4-xK!QXwCgTTMV&gP&adcdV1_AP0VhblSi5psnaDIOCG`4f@1&uhTNE1(V*1ok_&$Ye$*^3Mn9nByK|kmOdeD)$CqEYhFs;fk{$r<@U3YbNrZAH~Daob}8$A8uz@{A8D7uO#<9fEDo#h!hTaC6Nsh-ZQ{9zsKkCVY!9zNKN{j;4aptwOG4+fTGE?m}xd3@+_wO`HCJa{V~Y!dhk`RtjjJ0S@aD9lJ)^*I%Jc3+i|>e{*AZe=m$K+elq`-(%^YcuIoq!_S?kxpF@Y2rwUU(Xkt9)zMV&BOx!0G-2JXi6ZiS626EnUvD55V7xvrV=*PY$y~m9<5OP#InzIv0W%EmdR>si_-&-oHebY?$k!1({*B`!w{2rhjN3u_$a@oAjImJqS3{{&2tLQsjO!J4+ZdXfW-as^4lJ&S}rV`!qO58nbtc(GM_YB=9{6qyy)>J3nS)d?xu=C>>?|%TvAR$2fn!CCBqS`MTl-#sAmuc}KJU^_wTgCyqeBd@g0;y@qFV(GScGc9F3-ONE)r+5Q%wt(%(<2zSZeSJv4h6i)RVtD)sXM9;sK93y#v-cGG5Y9e?xl_n_-=VoGl3^H6UM7=QWpvUJ~E;B_|lArD+qu`96e#1|ElVUxm;K;Q05s$M86V!H1Ir*3qCKM_SeGHpWlv7pWxYO=RL|_=xfRr*9dX`I6($#uxN`5}2g(roFrMQ-mHF84jvO}LKSR!!W?Nz|K!D^@z281xc>EP-K1Du{oc6tx!T8p*lCL5=2nbuc>7EBqU1(ywI8KAeAAY)CcQO9-g(G=}SY$I8{;|m_vvgp#K*M(wg1&CiZGt@UG($wSg^t0?cMMw#!t+LXR?8e?yFKjzcF!Nt@}5An%+a56Z7|U;$L0mFLKWJ^XnGUAbst2sn(r%{F5Jcdpt>|0q1)FZ{v`2^1YDSKmR=EJL;?p9@^&kjt))9-%O%6pkLz5V|6YuV8WkXL!FiqvUhuSGU0Y^qv7?>7{7<}0Fl0$v+p;U9C!bV=j=ziD$Jg^?tG5OeZ_+M1>!P+^Bt^Mp7$b;*@=CyTbTt%_Fa9jEstk^X77>aUUELb_bFC`pQk<_R_&`ioRSUN(Q7OY&On|MtugOlNDjR3FB|&IQ?J;g|J&eIQZDq}%M?2*gM9uM`P=brdGK!MRmUgi(N|2|2gj)s`Sji+^c9@%<0~W+z*(;_x`}>_(|(0q8dS=XH}+PngH3$@Qzr|iO5D&b<*A9PS;$u#z4xE&k^|0$m+!B4Lmu(@#NuM7T)4Yz&$g4xkUu+65V}4x4@Ne>IP<0y`)A^L=%q}|YhLU|U%~l~Yq&lE2VAU_Rup0XaOTUB8)*~%O=(IRH=c7pw^`9A@|~yz`i+tJR(e)L7PQ*f?#YzH{B=4>=y%=aY)Bt@y((J>dD~0PsdJ5UU?W9n{=;7EpR9WRJVGrOhG~I~DsOqdS2Jtj$S`@oj-Ec-HkN{%GtR`E{&$}hIq>+37t!g>->4Jc_Y0Tc+3!KllM^b)c`NwF4#toxa&1+IwuN+8WI70sf7T<5Y9t*P8MA9yR2X?>~zSo|Fr6zjw&QC?l_!HbuL+muzpFmf<656rfz`|Yj$b*F9fbAa>R1vy>JbOP+g!J%J;)z{!Fks0JUIH)?q~py-yk3VTAL^2{dp?X;+P}PcWeg6tM>{1`_BLUgXjl@?%4e*Dj}d~y+c{4CB}2=)#u3h(S$z*jCY$O(YYm!4wiSzhPy;C{-|5;#ZScypd{?F*}}8laiMVVXK+>y9M7mb{Bb?z-;0U|-yU+!g|cFo$qxIFuVkK#&oIoJ_?~vMCvx|QjM+kl6ezw{leZ@VIj8>c$b-o*H{N~vczv~nT+`GTiz9w>brNA4x1~MS)AnAZ^L=cWt|ukb(RG?YpuDl0Q0$tHX6@v=igvNvTE4I?U2l%hmMN(v1t`n}Gp&$sKmfB*Ep^|(FX=UnI6d7bC|c|ET|T|S&=N@@GYkZK=0on{uWtQ+vi|ABx<;`r0M+Uw>7aPj`{m*@E2zJRgKRc*n^&T4>%D!==h`AjRW#peV26A~@F+#51cjd1F>(gBE?s8y4-I2qnHP)?}!vVUV`hC&I_65@Rxbu)czsW<^`_fA!e=R?GgDv#q+CIuA;7-sO-pVPyozyQA*Y(sO#*Ha&$gc2z4t8Rphx)zv^PD`pT{dnl|dUTHnBVBmVShEvD^{z9}FlC{=eRtTil!n1%yg!g)A9RIKQjO8>hL{q`9-N@7#&Nd3)nxVSlo#dsdiVPCCVF#bN62brsOGdZonb)5Enr|x5Eey}B^_=*|f4LS!3fZ_G`-=E&${1E4ui?sJ#kf&|emndc)&`Lo2l8x+&db5%8Q{P6mQRSL}|aF{FNpx*+{58;n0mMNp{munM{uZa3kcej_r()_+x`&n^3ZU3WLLGw?Jox*wh{;|(*$Uh$f{Ek;G+lK2h5qE34vjE0~JC1!L#ea4+)ZW=jR|rIZIqx;76Lo(CMhk&HrnhMw$uC6v{mvHsJrDYc^OmTz^nBv35?X!E@#i?t#OJoJw3PN9Zq3H=ooY6GpG(T%bZ>qwr{#Zn%)Frd@3|Nojwk#o)(>K1~Y#Nm>zyz0H2=IU0+Fx|NKsW|43+AA!r}Eezi;ubwy5w*{bX!*e=-bu;KvfK4PW%Z|jTUrUu{g#)BmP53%1_@<0CxiI;|w?(xhhl>w0-GqV%NKbg{cZ_Zu*_uNDP$IB?zAD>)V0Zj1v`L_2s&%{3WrdTBqT&6-gFB|h24SRK~0K)VbBzSJHv&@6-p-3G7fN%6N|LQ7aQR~NyutHu5fs;J+5Iac}XR}pw~TvceZK;7)oq|i$QV1*%q;f}HVv%gq(26W@gp@v^`EIgFOUX!Fq{j^j9<=6`M|r^V0rFG6lPvy453t)v2u9u3p^N{{^D;qCuxaZM$yKhDS`UgueO@BFjALLk0>A%9TUeKBvkG`9$LSB~~?-GSF3>ht%96+`5ukbSaeNcwNi2bAyJ>RZw^B&yZg{>e~16veO5Opg3nVwBZWcQ@^lL*}JS5sGs?hI(RKi9bmn*ZdG0rC~`IpR{O1mbt!7>46rI94tk*jxo`nwXs9^Kty@yYaqy1KAMqDpq?PDSon5MJj~d^g1n`e^eQD%eclZ^)uJOjSBF`ejz8sTeiKwm!AWCqG{QS(osKnxx4eGOD>#}7fN^9MLI{jKAu52p9j+sdo0cBvi|9J%YM%Y#^i&i%QlVM8&J=;^2>7=qpl-blx3^Vk@CK~^)I}PE`sCK4G|})&K}W6^SjUA^)90m&&v|aGgF&`u7f>S_}ePdIgX8!+$LtO95|`F@AJ>|sOvE?x$D*D0FghjTn=@geV?AWxaLBcti;AUbEG~3)X(#2>b`x;ZTej0a@2`FFVjZ(5ci?BVLvIaM|7O)&DPWccvazHaN#|2!rp_GZv3mL@7cq*^_4m}Z)**Eb_i3soal?)aV_iLcv_s#U@7gKQRqI-&(%lW8^^_RAZM>jY3FfL>rwxd(k5GYtNleOsm^i%4-jHo|a#fUs+Lw#{~QTc|+OJR=5sFyM?RGTa>06+eC@jfqH_xm4mT+x;-r1ejcHO2A7I+PYu1m+R!mATS5KKulaUZ-#gJUSrkxpWHWP2#hz`Z)zcgS;W8l7~&GKR0;A5I&v<#Ch-RBh(8w2@EB_$cN;<`q%7Fkbj7H<9%-m;GoFJuUS$)4pG;5bY&5U8rwv$wc>c9KFdq{VsP9by4C(Bj;EbBu$R)#TffBN_)7Q5GH@z`nAa(ejc0It82|bU2LsDt-l9Faloj>Cq*=E@Dxd8Le&fP=135%AVi2B)}$cmhte5i3@o88@ydi6f~_pLDnpw7c6`sq9B#GiSYf7iLZMaUK7cM`sczbpcxzNQ`ruKS7cx1P8umVn83JDX%)98c`OMEXjB=u_do9LE#=8`NKw!LA)gJeq$XUuC8%FP<7K2cpl$i#uq~kGX~R#=1Oc(-!q|C&k+k^^RIx^C5P`oKxx^>bFvJ<)x1l0MWu^P#kBfYs>-MnackSBsn45XeI`SP#7pYa{d0T&*9XuXuRnKEC#6-a9JJ3r9!=K6@%k-?*-mY*0FxiDcgw2ac>Z=u!qwyXa5KQ8)7lfqYfrTfzvC)^-XT4q;XKs$ZCoa{YJ$3dXIaX_MdFj0SFKK!BZY8BSk-&oB3!Q<8eUva|3lrsJB%N?yOk7&6VG`{T)qT|?|s|})QLPJlgp*>;82#~#Y@N`2ZH$ZSdz-Xcui0=T@1+&!@i!k#i<;|ZDuQ(QgM7^4c{IXn+iCdJhe-MH2%qqNR;VNJ}8+z3?4s1ii?g?xW1v7`naons~y0>~ky9*G}kx=WyW(T_Rh!^j)zIcm8qyk(FvlXk255{@V0q;=nx{q-Xy{h!{c^1Jzb+xDt*xLKFRFYuga`|udZ=#pWVdkU%z_MSORC5~_OKil(Dz7TZ01B`1lP;XbP%^Be@qWzBE2jF$A&x$cT<|>B4rS%IDcX0f+zTn$zVkNZtY|p1qPv6waTw_!U>iGd%JS35Si1QvTlmET9rvImRs<`fNvD(604sFE;s`p0Yc-p>qq#THTdXlBcSC54g^-3O9(9XHKZsB-4ojr#g-#S8imuTlg6|Uo(wfhd2O*(^X@~?I!bJQJfCCz0YbAu_mH%Zp4s3$pylx$t<0ZQLm{1)eD{nNuE-2@~=z2WWk?oDc>{z2{0cdCSKe4(t=DZji1c_6}H;{kt~KWH(zDKT$Goj9+0zcUC{D92mYdXe($w?>Es7=}Xman-$CZg@Vp`>CSOb;(Guw|-_LQj2+lMBl3}*-J1~smLxfit9D4A7O|G#JzjJ>R};?mqw+Z#cuG1S04I&i%E6=h&XMJ6~1sS?)r!F|=Sa^ug}V0P6;5~721CW|LcyB%I6u-o=duGwLP2kt`rMR0>e0DFOkb5FVb#|Jx5~Su`1y0IEqkuTz*i-G`;DZ$xnY--$FASJA+Vi}J76`g%dBwCQAEub`gX1>o*6;TNlf~!DOl}C>&t9bMap~HG_vD_VF0XJ5qELIjTA3LH11Ukf}{By=9;poe{8IzuXPN86AL$P_kPCtdC|1^%*5hwAnM=zjzztjMY;VPLlk(VtJpM&lIqw<9kO}#I0mGr=b9Bs?ebrasz8fuG`4^1cPApQ&b!Fb|0XNud=ZC)`ml=WILqEI9$FpS>R@DyWwgNsDY^Oa>`Fv)BWqf0tKP$C;Z38FR{?bHvOB26xVI%MAsB)7Y}kvukVmPjQZo<3b}2PiC`By9KCce>O`HZdFfb}Ns((r2Q;2jAB9?b4`+|53==y(1Q^W_$}pN#~D_sTWK6UE*MyrLKwRA=GaK*B>4D7!OQi&mZ`c_|U6WucRb65vGP7JCEt3PQ=BjS^h6i+WhSld@3tv$Z&!`u2?HEY_&0Vor~Qp1(#G*@Yi75!I$s5%k6)t#jwk9gIb~C5dD#J^e6-R}s;c>SVu6A4^C$o1$V)8;O_BX!T1i3MH=|@wzX&mM3**K-uZ-d_NDMe#^KoOL2c3RCgvY>y!LxM7+WZ>ic&4aoMqw7pRBqe>X(*^H?ggR^*Xg$=K{=08@r@ZR#`?LnOSYj-oUiyg|1WNPCy4{8``9-rfBiB%syLpAudepV`0Kw?#_?nO!&=9CGC};x3mZ!b9KVGsj3wHDR@?yFI`^!9diYyTovkw$p)WhDTv-Hl?K{tA#GM_$;oR^03LUtP)BbbR8A_8^_BU9P)_vb0X5K4qkU7<|g69`<5pk~3?B)q7YmQu=b3|RseWlF&NF6OvdzVWuyAtwfgttqwqM4XM9F60gibX=m8bu&Q#oD~TH;OgFlZx%~B13xIAu;cX>E(O<&CW+Ju6knst}Pv300#u@L@R6BPzBts6IR2jaYCJ=xD&UKvHpH#|$~<3{A~AWG1p+PynOI1DsRr0p{s{2+Q}&Va6H}JZe}5DXwr77_6Cvd-X3VRvlv^DQ0&>rIjqZ^02b=lnBQH^ab7Ym9{5jO=!hg>`eGms$nP&F7OHemxWQ`0C@`EbDhC{bWbpkn7F6@n29{?g$;-FiPI+5RceJl_{Ze8NCV?$kH!)+zY@4-OSWA-EQ4ACc1P&EuT-2G%g-%IkdF}|?le;)y--`@R@Q%kBF8B0GHHWm#H67+OEv8c1B7)&MBQQ(4vimaIl>i1e7rL?xjf#KPg!r`R+M@a_jv@1IkK}f8FXE`bFz#-73HY7I?Mlv*ZiK-%p=s&1=xBD#hJ77E=QbRfq)o8Ql2-6D%qJL(KH0qt6a+UKj;XuU8J8wf>wWq;Ha8(rWr3&QlTZ?+zDVqgN#~85KbIz7|CF->E^;NO7a~b}5^iO6j-}aj0R~($<|LkH%I`<^%J@KwjgfN}242JhmUl$jV#*m*3R#vZcOXEm+>(Lhi0=q-NSyOOztTJ+4#)&yc{)RBvljFf0M&icT-+!N5@+Ja^K3!t!s0*zUY2U0EP0JVls)71DXUkKsf5kxj{o4>vqNi5eN5RA1VHA^jJ;0-2dwA$l>^PP6~5j4#|+#c%xTu8;-w9FZ1yzYbuynI@vE@iTV=iM&jwx2#_pbeJ?|*kF8(gbzYJu3g$i+K>IG#B_B%dnA#Bod)ab~Gxnj*v8sFgup{&5kNxJ$dD6Km5eM+($p4<}9CBb&@{g(YddWb#sApRJuoBl!h6_{nSNWYte#^Q8tbSCUB;uJHJdqoT`f`q)X<*2yH2%s9$5*QTZgh6N3ehrAr@EX`|Mus7z>Ew9_&pypy?%eOZ0Z!|j&d^@ran=>F^O>VxkmzymCjERP2f~bpKHg&VOk_h}urC*+xL7h!oBB9}QGVErY{PK&KJo`&V%_y~gB8pA);j~!7pqBncC6pN@v?Y5{4ir{GU^J)JwM6@1i(YtzSqp3Q71S&AR`2_e`ojR9>IPzR@QsOqx2)e+LO|G^DgRvRV^7())c7Y@ckUEj&-y?yR+TPOo#`GZ+1CuBdAZ9J~rS}OonKw!!N&H!+KoFjb9ZQ?^{EuO6U`VpE&;H`lItpuG)h}%*vyxqQNs*WEuOC-3#QY6DTc(b--GryXvF-{a`kko%u%%sSn+(o0ddy5FE0}_rHA%>qz|O7ZO`877p7_a}DmB!@5{RKX|TvF(5OdVY{Oq>u8yJB-cN-h=Y1tk1^gPnL;`NDo?zJo3A#80&<7ra;2fD%y``7&Rfx|z|7RuxBz6EA2Xn6{s4e)%HXKZ5k8t+hAeey0q4vZUgRaWbX0yQn?*-rwd;XO>5!ydhBqyuNN|2Q$p;Xx%C(?*A=`yPqRD{JQ=%FCr)Jj8!zCHUe5l70s~i%Z;G8kJ*58V-5}QlIL5(o&Yu(yNxUcK>&}4gR@?n+Z=jvp+fOX)d}j$xkCsoA^5K1Xl-K9%DYFBu&#`uUNOeb>HcU)b)w;mD;S-W{%d-BBXZK*$NsIAd^iZvfSQ%H!L7={mj8rfOeXPXTPyLXa~RF*ITud>T@zbdfCaA;PUre(hBV)`k(b=c)_bL>OVJeqMc{AUvxWf?hkr~wf*~=@SNKGxEkL8a|kVd_?923zW2b_qBnYxko9#*OqM#H|Gx3qP-js^f&A?Q=0`{zMY}G40_5sBhvfF6PK%>`Z$PUPqVw;4=u}yA&FRFAAxqHOT~?q|hx1Qc?>OvfeMu@$<@_5@@V3cWS7^zlOAnee+`8zwxOTOCR&4_`qBV^TJ1Aw6kO9G0emC$Bqn+C-u#oZsSd1R}+>3^zQH%F1dW!b*)huz6Z;gdggWij~;?Pe;Ig0bV)EJ=nj-%=L?fgt7yC$!-v3TaMh-%J{5#xWN^|`}2KL5279;_Nd2v#tX8lWT$siP}kRG3sqqBhozxakyl@%K0Tkx&9pWcTqi%3E2$!P3Hfwy?&uDOB3|APC8elOukm}oJ2M7|I+|=U$X!vN9oJen#{uEyT-t@YW8&!m6Z0e}bb4nW5s4fXG%O!k_1YZv|9NzSXCBAD&tXi_JZcM%0?vGXa1zHKTji-7_Qw(G{A`*W8c_crc2eaRi#vR=k>WbO1G%g3f}d^OoDaxNg4w-F)UAJ5`5gZl0O>dSwsY=9?&4I|W7;1R3TKRTgiXGo-tg;jEZyfQuw)1-5-dd?o6o$wg()hQ_CA>UBNr`tcRE*64lqudjn?`NEN;etG$?_lSvYiUh+<_Cz~zLBrQ%X-1nttj84Z#{wx5Ch#T$MRW))fzMqQ6+VRtEWM;}u^@kE9>Op000fu0VTeb!F>=KwErk{w;ar9Mg%^`wxGGL++B(nvqYDa}+|E|14&rKzi~|6Jdv}f8$w;k93TO!~^y7%*jLQdtzm?rq6ojINX_Bt8_&b@5>_G-SyzH2{8UjR+q~~J8yRc{jL$c&^`ZvD&OljFbx-Z;*GV%2Dzjy%ZzTQySD0O2Hd9!~{#1l){))2k2tUPsE$)h}L^5*{RNi@?fA!?YRWe%YXCjxM2afs(6FXAfc%rWNZ*E5*`f2oNlKS~BKOh#r)E(kt)cab8&`zSxYN@j?tnKQR77Rx_5A+;r;GGSGm2#d+CzX*~I;$BpxDJNH&$_)v`ajVALZ-)R!+9~Fzj$0T|0b@dhA)~HzvYStB9HB>2dBT4zcT!oCr9k+aeDJe=W`Y76&k-NyhNjnINdv~sjT!wZMJnxhq4nhGw9-)tsTiExX{1o*#2AsKtMLH8m`3^e{cG_->hwx)Py^lzBAPK*~wVGqJIQjH{e%($Lu}bDsvdF$x|kG04Bz**+Q)kQz>xlR?ZxXS$ug0XGv&*p9*H*U!~qxVNH0_yG#l^-GXg~?gkrzyip0U^%#ET#RpzMsn-wvRg-4>1SJuN`B<^qXUJZP=ZVqGTk1^SqvJ*RL-FW^j_Zu$;9T^~{6qf_Zx`!tW2l5Pu5oKTi}yyX_3FPke{+=+Vx}4PMQ<3|jC_*~Dw`05zNxk97ohZklhr2f%g6(?@f`@nf!5&DNbIRAH^M)7%x2S7=ex`qv@9{Wez-Rn#SLV(!M*{9%ht!pdlzsC^;FKjpG%o(EnM8ChT&lLC;JylS@7S9Kr^Kv$(awR}<<5O+i(f#(gGvs1yBDij6MN`cTs_t|5en4hU>TS<|M?E~mWRkHu7D6l?nHG`!W3M(9R5Kn(gmj}nP8U*1eFNWapZhs&49_cWG)%w1>-aaatUoSB-5+TUxjSoOeXz$OizM1!*h2y9`wK?T@cM7Mo(qKEbA{!7tIdN&8hkEG*C`y$}}^tsn+-;s-CoCLYpw^C^F{0kAtKhfOJ1_!g^;dd^d@Cd1IZ;~Pv1V8Bj5#P5<4DWlbEIf-T*9<<#y*BRpf_^!okB=mSEf9SXCynsFL_BD_gA)*q53Y5goz&&=>m^AKAnG3V9z%O%S93D%UE~Mz0hM|z{m5eiBbhhHJc59T+r9RW564xGUM$Z#TNnSpl0jC~HHoaPp_tmPh-%%E53dg@|Px{89ovmX@nmTaF=mU$oKEa1I_Z<4f}^;po@EVhbgHaoP}sghq8P;ylY)TVe`QCl=j}5>(KhB)~&$#ROGt&9v#rp9wYAOW7C_6pWkSE4gLo>PnxP#~x7`=oui*UK{$hGK*5U$_%l2p%>_+bL-Vw;uKH~*9IqEbPlen>^?_gRBpc|NeYvvZaj{5O!hu&&%`_Q;6_CD%Ip8b{>EB1$HZ#4!N4WWKdt2IIXaWFixa1%VVitIQitjw_7(*7iu`fsd_sQ_EUez5!}dcOC=X?y{#1nDs2KXz9FcyU!Ghyk`oOq2BE;khWzG4*JLpNF&2VaR;el$px&ksEE(^d2tF@tG=>N!@>M(xS0C;FvkPTGOWP_k$T5BlY(pGOg=ZWpMR;oJ7K2Jf3BRP%6Egcp1=RbC4=$ZvBo)%tHX`NJo#BdUgyr1M!K5%5YdWOWT~UTuPs3?Qhh%1yzC5xw%<=?LjKubsQc_`M?4(-#&<>`1$Cl-LvNry5OLXOMe)A;t~Xv^wzB}icS1M2pCLDvGEjFIUoL`Pa-g$U7;&9=z|1KXQ*F|l+x1!Uzsp3Use`Zs=(`9k)2`*=`O{>AnBMG)kEzW&k#j-Njg$6K2248LWXT%FFMokV`YC1X!m*U`8%?IYUhBGK;nB*72%*zoOZvqyVQAOETx%p43+ZSNMOmLcc7^uCfRvpE8e9jPi@TZEiL)H8ifM**c|PNAuj$PX$5zKc$rjE6^=dv88kN;?0FS)*&5eg*kUYm4L8F_%{OD=aY9=?6#{1E*Mb<^d3Q96=mV0i6_}*9up{U4S2i}ZGxM6Z*g17q2w&)Y>`tny^OjGIu1wS$JWQGCWE4n##j(xPj8xwEL;2JxLh8TcomF8x#uEZ#&w?6tLy^a5^ROcl>@R*wHdRJ$Ni-0z(Q&1~b7g_(%%8{!_k_F_Qj6ljWs2_2lVaq7WmkG$Zu)5qrK)ExX<7WYKJ%dwYar^;I*;LV=-yd=Qon#Crif0oCU(*toXi-u@0mow|x|M#$Y0vyeG`azP!V~U5*-WGdk17!~b9}00r|I>+j_icR+K-ao-)i6Km)@g_L-?epvKMa0!yxUM$pA#|~Yw`v+Mz;Alb<{&FmP-2h_yd78;`XTjNwR*Ll^P5@RWUx4Jk&q=M&J8IgP-8tIOiSZ&1HcF&uTz;UZ19>q#K+fIUHGj>Ly8XZIHjQNK&sZ$>s$B6qR9TcXfVdl5!|_nB+ok6MlrZGJma@U(DBCStUJz&p~Gf!OhV&B7ks^il#mwo^43xaXHUZ=b1NKzm~n$%vu-h<;kla42Skqm=#y!lfbcOs9i-Nzg)6BG?MBD&p|^nMBag*;^ymje794LPr-}Q*ccRpH_a4`q-WW>KiN11CjTzRtmX`=66bSfHl_M7LOuOXME1M<=tgBu)6;%&UgZKjgO6$O%gs(!?bQ~v^nw^f90108GHdyuvK~m%SY6wcXb7fT@HaAA?k-8T|ypfTyFa8%#%nU{0*x~Jf^6rXfgMhLW?)p`w{i_Q_@%7P~YdCS25m7B>R>w^moCInXahNpY5FKX(q;7Q7_FL-0DU5A2yv8n6Sw^W}Y0tau%R?4zr_I$VH9_ez=_$sg!1vHqBFh!>P=(lwt_LLSQ+ecvUY>wj;xEd|_jw2fRXR%1RwMKnB{8>_@y)6@YtmIpx>h4~BxT@>vbb}Nxx6EHMGN-@-w$sZA8$ZGOa{KYek2BiA3MV0-s!Mp^Ae}81c@xgy^5ViRaVfknN55bIU8W~IyKl~w_y=`jpI%tt2MYGtQg;WC$Mh-_l5TSb!&T+Q-qY5|Iqb`SZDy39@+9^9Z8(XXLyOm9puo{JR-7gQ$T<({XW0Br;~|w_`O{;etbaP~e7Z#sI@a7SJ*a{A<>Qz-HLGF)ZM*hWOfAOyrsc|iIQ!!we9KS!^_bM};GuMiegu^#iM-1_FK~R1rCg`~6;J40voeC^2=dI%nqslvIetL=`-DA1J8dV%)BUMDN%XZ~H_rMup2%l=P30>s*Um3t(`Y}<-}om6@|v6?q*9R|#Cx(BULK5x^NclXE7eH-1c`$hO9P0X69}^>`Rl@4df&d#tQal>}V&`M&q{~ncmR8v;0YKeV1^v8>+(P(oBX@*CwR^2*x;5IFA2gr7ODYO7Y<7+Y@FKUY@0b6hGeQB4;we6^Hsltf-eTn91aLkYItnhxT`LP!?u!SUg#};xK4(eftIa3Nr`ydh0?`+Dk`!O}o11yD8J{yP--_=b+CRqDAkG`;0mCJmKIjdS`aX!WHRksEf@JB2<-Fb`Ki>UU#m%n*;f#L4vlkoD&WuQX*=Ef!NObo-Ezyq8#lxcZ;m3h!kT2t3H|mb|Q@7_@gXXcYdOGYv0*SklxxySvtr9@$&1kk)C+b?UPP^pYY+&r*BXv*V$bUNFm%Lu%0KW?#cxniuF0yva`>viFxG}jtTg-zx(ND$srZ>d8y2H`{ss#5&UaBOu$gYzQfF5-Orypjj-(iPOK+=}{~>&UIS4Bx-;mc}Gb6N|~%l@SP|Ys8qsu9Ey|nYW|;mBL`N^Z`-c3DoT#?LQtH6%EmmaJ%6I@)&Db^bxV1Sh$?l%e(p^^4sOwyF-J9iI5~`uzHCha#}LCk&u9qDV!K`-)Az0`h%YI)3Gh*VY$Wgw=>-Ru-YY0rh1|6@YDwv8DSz0meJ(t;3Uy*Xo|qF1qTMOOV>ZZR8Vp?8LiZwI7}#&j%Oe*(uL?hxs6~M>H=xJ^OiLnq(0iB?i|TIo^VSoY*E%TwCC85yAO;S{lIyU>7(g2w5K7H3Yy!3f$-B?g(3$!OjIk~Q;YzI?~x-VyODF&zrEhQlZgU%yuZKeeuSJew2yLQGxa?t`ZIhpB<0Uudno>ON}pCgUzXG#{A>L37v2voz$>>cLY5Bi>v%bZ-gcuMcx=s8VyH(R>kFGVcUj{C)aCX_?>@ZmZG#<$pT6~kqdf8FHrAk>>?Rh=1e*PT$>4sbtQ6XlRAR(O5etUY2gc$%YLRn@IELdg5kSod~VivL_yP92aK!(iIV1q5%nGrEz?7YJtj$BT)&Hl%S11dU`<+n1DgF)tGyF+&b+PNlsK;%PO1Q7L5ZA6d<85E9Tgc>agF4AP8FeqxeC8w;|D5xNy`m;BpDsl^#q>tQ=|B3z5@nSL9+JQ7QfoZB@97ZQ_u;-GatjrQEfr2ig2o3wsk{NSKS4b!$&SibnL)P3^CW*4(cfxwW;{%2%->$O6S;-p=Ea<5K!jU~oJTvk{lIkL|MQ-uimFx(_K54)b?W8YFRHz)e1oR&xgs=R-=lWvF|M}#Y58SZctveTtc1rKp@v7|)fZ1_T)qNY#PVG$JQ_h;9wEm&(EyykI2RlLy)T3a{8`Uq5ZID}(((XF0q3(a#y$`<#;U@Ko@EX`EG#3v&8d~(@cTulY-OO9tZ2>imHxG`NV|<-T)Nt#;&liD+n|>#acD@d9H}5ZW2EJ}DYukF9|E2vg`xusZ!r4?z>{B;uT7SNMTO?8n*uVSFwkpP_;&2*d-@rc{D({%Lsxc40uok-3xdh`a7=Ob{`S2Gz3`PaB_-@{7l(e|@!x1&&{18++Z5yXMOJ^L|qI`)4)@-AX0Z0Ve9ozLvA0`3IcD!tvkTvhDr3JO{Y`YkhAAGwRp$*W9^y*bTP+(KVbI3j3#@J|7phuhtt@ANqYv`XTDO#A}abd-(%hghgj(CF&fn)nA$91w)oWV7y8>>co5rA8=bw&7{Yk^*+WMQ(K-6QHCh?vRb-}zo8VkIFbEowck;l$&etTZaJ`ra3zs>$si~5R7GKI-PI`wcGA9>O{RVefI=d{5?kG?G@xPqP~O2abpmqzSwg@s5|q-Ef^+S!J$Fb%5ZnoOHw|DC`Q_Y*Msqw-`=7Awq`hpDWO3evbN?E`Pt{)O|$7^8F`InSHqw0A)Fx-3J7w&*ubi$$b-ceQ~pnP9Y@lwU>>|?AAFEc*}gumg-9XxOK*jsI=HDm`MQ$m6dJ|F_HXT8~p6Vw^6|T=R{}HBIF06PR@DHc&L~#3Lgtaov6?3!e#_SpTiC<LqKckkwT(c0{t&GrM*dFmCD~ADjW_^BOY(6CdA~Gc6^1@Ij{9uPRQQ&vy7wL-eW9j_`(5f&2!oc9Q=v(~EocRey-|Y->?Cob~Ve*1|WqpVEf_u`jvs674*m(*FJ^9rb;t?n}%`oIv!CE7YbyL}r@hM@HlUqJQ)6z<8)~NMX>;A@xru_*~x67Zw3HNZe@|XYbd)-KiyK7Q8|LI{olx}n@5wbuYP!E}85c57uJLk}uoZimIqM^8h6eaw{M3fi8ADtb4`zx{|Lpx4b2CpQCg&W&iW5(?h7Y?o6vp-{hz2$sNYr;Ft!3A^Ckv$QMA*7g}FFb)gG*ZP8@qpdLL*7?WSE|Wz^|k-NI;R%sHDidTL%!a-e$CrAm^&i~76zn&StT_)-Oys-c}LqnjRmzY+viJF>=nNOfkY`0rftI}FPEED}UqNp(~t)*l;r8x6kY0D;9|L@DHhe@(G=;pN@$MaKD#F!A=Xgt1sx-ire{CAnm(;^~Ac+e|noe$HA*+_Hg3F{J|}sLjLJ{djf@CuXKfV!?6X2^H9GhxJraAzzc}JSb`3ymwmKOWclbv+sCCUqAvHP!IXzP7!0R$HZlsK&R^l{_;fIw<`;d;j(Y5R$)fvZF<|qMtG{^->eOwli|VU52wqsaUFHPpy-v1!?>i>JqZhO5jayMCzDLf{=3ujM#_2-<`n7!No1@E5*utR;oTpi$P~YB~IJ9k}6YzhFir~sXeS%%@lC+*Xq()n-G2B8u_jJaaK`CDlczBen>pkjA(A+k^{P{i9OWn6|tddEDdnX-7e~KcH$)1S#E<0!pY2wDxg}?rfy9QLWMsBxkKWq&LelhRtT8G@F>1Z(R`^O%%s2iWH$52mE$+?lw^uz?$6G@{un~wp57MkEvPRx8+m!}nI-I*J9Y1g3+g9^hxsTuc0l;;es!Ww>}#0PT;NsQ-C=!Fd>Ut^A?v2IULbZRY4A=C>h`>{JIh%8!TpzhPS6(QuBRLJJrQ#ch7WZjLpN$rcQj!iTapk#tJ@rN26;>@dHUKZ1q!HhH5WeSMP4G#{nw<%gZ=e%hKVuMKXoTOnOtT7+lM^L_aDORFx+)zjO@37;F-zAhwkDzDXY_|!PT4WU@K+Mj%zA-og(d9o3lAxKt{(T-TV>qSoJgON{MDqTK#Y-OXRU_^)h^qYW=|L_w~I3Jb3;{)B&643x+&8o+kq@kjGXqrn`UJ6anxmej95M^3QRz;>@aFG4OCe*exNER5#-$OZ(5g@$hc#x`)*X$Ul!(JgBP)H-PRsHmj?;c;8o>xgvK;SVHBqY);24McE!w-b6SRh&a4pIHr5|CuZb8VxPv=>j%-t(%nQ}qdg{v&5xZ@42EZUciT1_BhN%j*AyR?jez(!k4H-1qArni!p7xC3=~fX-Tz36`wBktOPVAog)1&)X!5t3=6xAXnu7CExfP&nyh8swdZK{h`!PxUzKiH{)$e;9xSS~4>+3Oebs-5?bKIrrNy6Qw&D1MuJqXN%e+C6y1*$ZkoZuFyC%)ZA8PG?bqrLXziat+0SCj|!SMZ0!G^c8S^viOMk)_qyBPr|RaqU28?*k6pH0e^Y~D(tofk8oL>}NwV6$FxGM<)?+5Zi7QNl4?YXV#kd{5q5MXD=uV@})0;XIV?$(Y^mhIX!$&5d1D<^bhVfgPqpIR3>#$FGqlH(>1;_*Q)y?VO`O8WC~I2QuEQYd-n{?G&_~)a#ZA0H={3w@3BRp1W0fnv=01ke4@`;5CArqxRv)&)fcypr_i!!AI(Q!rgUfsxFuUY`ZktmaQhmt3RCE^*JLRI>Y+{~D2S!;uKG7|~4D=$L8$~k)G*Jx)R&qrIoNGF(`NLs!37~1*n;~l2byY3LU^xEmAPe}Qsr5~+d==#F3S7kX?CrJHSE?NEDxhIfz{wp_toKr;^&EdQj3U`&BTxE1ZJFhw4SymPp1>XH9vU^E=yIKyjNtgbiz|qF)vgHNHEyQ~l;XW#W+P;FpYvP}f-yr0u?%`e#xyhB|_Z&%{{7uRcQ-}4Hh)lr$-gLW>74_dQ#APnduFYj^c!{?IGb88c-j)ra0D<0)Iq5W!WxOT~f#KLsm9m8Yn$X81k4_sw*O#mW%fiDmBkzVdj7A7nB5j5Az#u4;Sm;ac%D{7rR(CW>!1^&}5&bY-0_PfASr$Hu*OQ;JtIqJ6?dV$={^mS?SsNb)bwEa2Y2d|i$M(Y*={^{&gK$%?~3`E`WlaEoS)Lrr1`#Bu+b&REaN>N`Kvm?{~Rt#8EC-lNi)bASn8a4bB2X#TbYn}|FK05r));%H##Qj=ay5%KmFK2W*zN>3lPuYr=4Jrx>IZWMYZRSaM({ao8pGL-6G5Q?JL}YI5(&dLY>8wMfC!gFYKA|TV0Wj`XWu;n)4e2;at)DmEum+XWc~PuEMyCqj^{^?3gX>UL{4vhYk8(c;`zIv{t2th|3M(#GoladqbLP_A#lkCKRxB^6PYQp!@YC08mD*;1m#ntk8*ecxxszNZM;N+{Y%k&;wINfH%Nv{JnD%z1yVdEfKLIiK_WJfG*jj4|_l?)zGRY4$+Dfh^<`zoj@Mv)o~&zY7~fEAj>38k6jEzVP^=un*Tyb~0;0phOX&U*up)5fh(J$s?LEAPc~e_H+-IFEm22*8+UtapTE`z9&N9R{(gb({FL~oFNpU4p`7SrJ<@>(Bs;=^q1ddgH4eFZt4W}}N(@A0H-w1sppS9CZ0n0Vnh1O0*N4h_oTMD@%Rb()CDg)75%B(NM|RvxlL!I>(+uy!y~v4tFE5*LI5kpGT^)j+7WY*uysa%7Vz>TXyF-y~|Lscl{^_R)KzyHgGou$#ANvl-KTHLp9;k_~KQPgk@-S~2Sc>aQDSSaMvbn}kC^TyVrMa!bMWg6}3Y=u7&K_$RUFPH->q%F~+O5p%TJH+^HWOM6oVYHNy^L>PmN#wgSkO&em$q+tItaqslQuc{;JzGjn-rgL;H`SSl1&qROx)1b*Ssg1_W7_+5`8S5Vf7KSjs)6Vu=`x-IRS+gYIQeLq2bkuIQaZfUVG_A$%R!iG%}PTVQ+awJtlJu5RMtrXzoY+`#a`){;zh^szb8CfNy3AJAPP=*hr>el@k{Ti$lLV3^Em+Lqvh@su${T#))2PU|o9>xOwY)tlwwgSR)wHh(bA&sKDrKg>NyM9+=(%Kf#(n^*o&zWS_7IXA{*esoNqG!hCPnlHQ~GLXlaUXD&^iG*vT$@4ZFG0tEGjac%UIM8~?tYTS*ady38R7?1tMC&`ZTMNC#uqw*f@gLDDK7Vf(2PaOM)KUbbiCrggH8{DmG_S@t}HxG{eV&{~)`p+ha?wnM_wo{Z?XLpzA~OC$Cv>O$u1sT^wa>!1(|0EO~!@Cz;l7^PE0<7jaG1z)*y1~ZdA(8LgkrVU&YD0bC7T24)Y6j#+rl)z!Rt3ZF!M8>E*%6DJd3-@&l=__eAwYc-&sOANq7wrw^U?6zd8V!XS@fHcZ}}NRm&PD}P@s}o9&80sSy~l*T6k_4GTW6?XzdJU6uHj~+mOqtsUCH?M=G*O%HaEH)qmyBdM(4$16u6*?x^#vlm>4FsU{Bzgdv%ddKWkZ|2_7B1ieyy>{_A7H4$Yn8dd%VS|CY#GSkT}#Yecfkj^zpwFc9ir>!MioN=uVC6-%O#5FT`N-0SzZ*5fXz{UDf{z~lgDQF3S`8W{lY(25FmRTlIsEu-2b-@`ue^s6;{a4>SePB?pmB^Y?y_`ty?@D;H_tJ!6BCT%#c@lYEvB-68>ig_Na7^)?o9IP_Oy_P)nWw?(-z{BTMd&}odE62qQ+Q|QV$o-aes$}2vC812EocwDd~@mr-hY>*`sqs#+~Ca5ah;emc<$-7T>Z?;t3I^6IKjWTF5#D&-ocPvxIX7uDf(E~c26;jRS_`uZds{^8G24Cm)^UFt})MBqAZ$IYPJYZ(fIMAMK%~Pc5}>oUUG#NNjrM4yWb1xHQu-p5@dJ#OTMqaIrctW3xWSvtnfRp)>g*usvXP-!gVww}Hd&kyk|oJhD$9B}ZPU41dGx&uO1;FPTXMbLt0BhZ}mr3L=5;FbQ%Oj08!4kQ0wP%ARR(?&nG6xY*)Fo*^t!bZ@s67|%Xs;$4mRpROZ~i!(Yy-r)VYbB@SskAKNYb@YS)Ek)CjF62aC@m)#&uujiKJzoLWwU)X3=UROzod0a36jDKVPTG)SXBp~LGX~>`tEOEaVx$zPSwzmDrmA;EU!0TeQ!R~GvczrS@+aE(8Sm$(X^{XYeK-AM5r<<#5rp$ktn+S%k8!%MF^|9U*%wNFCDj~B!8os1Of+xW6#|`X>(2(UV4R;0gqKIJjer%k4{H|UG0weDS=q9GN5h6e53}~w7>|FMQ;Y4<1X`V@bs>7=+|myXRjX2gYB}9G(sX%f)c4s$0~wN5GOIPUAeT=JA2KgWhYvlLC!>#{Uopg!#Ad9lftbfqu8RJ1GVPTxw~;G+I~Z_7`d0WNU;F60)`6|wK(xU%lSM8;S=SHEfglt$uCGuUhVP%j%DX4|!r?G6K#L#wXGg`s3t6Fye6A{gOZmYBD0F)VWunNpR^1lU^GXF`zK2*w2>!mPK18}gfp!0E6-s20%WfPcAGXPaYbKj_95O_nurpe5ABP3}v2|;EdL7S0fB%`fJO0rDR!+Hd75XB7|DOBG&QuRbniTe4z8`r_5W~&dH-6wQ>vpMV1@hR!g$)8Rp>W;l?fKw-x^v9O59-Z}B0=vjzsH(u$cJ{!c|AB82Na_*e!Yvx>y}SlB0oun^EJYcf7c)<^5$pa$sj!W`IzW?v|oG=cjn|h?U+M$Q>2D_)q{nYPYXxdP0*ec(TL{8i*mkF?uZjMVlL~Uy7_Wa=}k*i8qFQfMZIrHc<`vhsKXqp9X{BW_;qR-^R$#9-ne;wv7PZhZB-Ye#rUHXindlkAdB(J9e|v_4g>bCHaNtP!edbRVe!K4!ORrP*@1{`AB9$T3m1^`dHY+kI5S8bVzz0ur;#)xtDwNa59{Pz<}N&T_f}^qCPr+(}uPWFc68HXd8Lsg)5{ut###VLatP;?p@O74MM;9D}8?mZ&ZdSu4dUZU%-+f?we$#rK8Y@e`;xlOlk_Tb0VthR9?bdyfa*PZ?U_Q%9Xkf(Fyh1?|a855Q_2b0r)@%!BT%~bR;O&*h%|Gt~RNWY%UjtJyFQF~9c^;!eVMJB0uy1pDCk>+=vU3LYg`zbOuboB+YWEHifOWrUp=p5snN#|+DB6HcSgJAx^*%nqd^ezz_bKSY5aIiZ4TK#-7@+uz2>lc1RLzwuz=**4iT|~dL9ZM6T)35E8)dS?5%q;pkpHhLUr8@<~(2I!t#$4*_>rQOs8leBs`m}SO2JR3ZueMCOI?x+#2K>ux;lA=6%5rwR4>8AUo2DDAidL%BOF$nh2-aI;x6cO>9LMIa^V7}Gvd&#knG1r1)@5>%_2^@I^OJ(do`(Zb5536@eUF#%daI0l3qty7^*F13#Xn9SxzKx0-IF^FVQ#6%%0*@Z73xp#L{=;yin3AO?s$%`&?BQ0J0fYs=0=2(i;IWE(;5q{MiQMUDgoU7`LbEzuLUn=v*Pn5NM_XPQ3K)eAhxA?=&7gw*hhsh4bU-7gwH@=aTuX!|PrS@8ZnB_Wy>I-Zcha{GDAS>$*8+=jO~`$N&L=UaBQ(|K3i$KKuNLZPp>>3QrfT(_!pJWeMl625&uZ2a;f^8Fu7A89?K`ef07);iJRMQ*I4_Gx8v5?K5aY{@M_PCP&67LlN8?tz-96nes^05Ed2hrb~OyLw80Y18pVF_K4T1b?0yU}G80Ym?5_9pE2q0aTEvx21zasjuRI$YXqh-+2<_wJUh~~?8A5SGf49`;0a6$B|Uq&f&%lT5Fy*6HcQ#r;zasH^${0%aY#0MEx(e;0O;^xf#)b6VBzuwkN@Rz1u72q>&T#>Q`CGwEaDnQ^;fccPBn8PX}UucltJRo9u&I8q|(K&$*r%9YH)doIS`go3Pgk&X#COlx;%JT*o3^Dc}Mt%{uO!+m3v0kGkJzwHLg1RAN+6N4}h^+|H;X5H=+CZ8oz-enhJ>u}wD|EWb*BSzmzM()7x=(9vj+Zr;qXavZsWeblG*)bFE(jsJei8DZWU(PzJm>Kj3)qZhtUAXjxw-&}h!4I&R7%zJVgeXN|1>;8ze0T6Q%LUeGyYnxm^QF^=u?e&rML;l11d0@Jb6I?&WxiqN^`IjG)De@#wAo}PR(e=^woO(yLvqMS0cK1!TLITKvUD-Z)y1pC@-)(2fsqpuKnx{e&a-!etpE(LGKdr?Gz3aJVLsMRlJ`nS_FND+85#;?$6F6!CuT=a_lr7c~45^y0i%wZF=m^CAO@lak7x8a6=}G(lr!mOm;0H(Xx&XNJ6eKVGL~ebf>U)lL7?5k08H9VFj}de3TRNlQYy411?h^E_N`}MxtNP+Wr=HLHTM_c+Y2yML{Zyd7UDTf(M_=M#c{`VIfdV_rb}QT!L0_WPYb-Scg9FjW*z*2&pCQ$7Wxb0x+%4g5Ifv*18{Q{8Rnm-c!3hqv+0WF()761){-tdA(-W3cMeRN(-d{7^l_{+%0EqW*X({?xw^6Ef<)tuqp1-+3gsv`tm{&2(8V!w`H5}!aqW|oaV;QVnngHkehYpN%A@`-;=q2?z$BcnnL$RSJ69OcGfA-yHHwXEqoPXU>c1)6KVv(N!Xu9gP6V8;=e;ieWt7cf9UPUWx(vR^P`*^O1M(X*P4kCBmI2M{=*z^$#i6YLf|HMgn5~Ug^c+#rt1fTD?u2FAbWcpCwrAL?0mhqprph3IhEdAEncsBNL6!ZaYC$bgPOrT|bjE-=2%G8+*diE4|I~Comq%XK%I6`TB$P5y`KD_mRJ3;PiQMITRS2`J_g7W1OmtA;15`M}qYB&y>G480VmgcnfJD7Kr`nd0C9}NMEq*XjKvrb%gm%$gS;H-{?*tL5Teg&z0(Q-t|vixgaKucCJV2K~C&TbC7I-$B*o}eE{?2I@QPirs=uC^*ECphkY35Tlrf*wdcHn@NV-ejB~7YL;s;2K|sv0e?m9ULiC{32_~*^@KU`f%$$QhwtSmTz4v4ktnmK3CUza&yjQ1%j?aqmw0Y%*hP6!`fBLkdtoW^UZ2%kOd@TzH@;LWb-2|Gw5}K%TU3bEM9SbQrm5f0k7Z{i=Sawo~~zGa$}Se7Mk;-nSYlv$8q>+h|Ry-<_aEUe5jWzzGKrSS532=Cf_!Vmu=K$>q(g{xJ5iLu%<4^cmuP`0ZgR^j}JexfSHM$PYg?{djpp6bMX;G+OieE^^}Uft5QRVw@6W*WdGA>Mkfs$3mm{n~aZtasP14$yvMeWJMz=OsKhl-pmiW$?ZwG+SOiQjvo^!qNEFj!Vw)^!mULgGA(Q(wl92{Jh}EO=qsGaO9@BN$Gt7fgrzRJ!e=X@_$^>3|gw;AiHeIgIk%%pD}3m`SeG_9p;+TP0h%=c$8|oB@>}JMDoC)1-f{+yKBCPlfX#DYy;U2^UzqQ>qw7k(qKO8WvR?6I^X-T-J^-g0Q?RAzTKCN`&xZ3MkFqISioWNi{3x$ky{WA?AAB|an8K?74m-N^Hm)bPgtleIkcayF9$KlLeDV(hHjp3J3yCjrrh#8L#Z$ftoyc%|8he9%)n2%SRfiM3@;@2H6j;i%qpDIOn{(M>$h5Sp?6VV&a5?sslarbU1l-}`T1r4qLNppfgg$Gcl~not~Z|*KLz<10QJwFMdUGEURiqgLz@x{XyUzR|C$}WE3ETLv5&M9l!V7uaGXG{&N935CfO4-*5n@lT#4N5(YD_81_7YEfzMu$75ysyL~E^OXc(BhASaXQ>II0t?UoZ!Ai?zJ3?p5iw6#frXWah9L;3A9=I27t$5!lJzRlS>l~yN}DvaLMnNb<9*GvJTKisK)<@K`1Q%RbIEV?F_|ZCBg2&wAeHmO%Gt~4MZ}y?9zcgUJMyL58zikG8*P$tT_2k-4O&@2V75W_!+8Zr_sa|6usrf*OXFAcF^XHFmCLVa&?xEaK5+xRE8?%?NYm#8*y~kkaG0(hp<&ziyZ3IT!rg`ASG3g7A1=pro=P2~z=`$;lWKR66JDkF-3%lx`pjQ9;ks=OXI{K&v4>pJzR7z=xGvEj^5uPZxPScV)vJuSu9erNG10fa!1b?xmZcH-Owz{!ujUXiT#{&WZ7+ID`7cAAxta(_mlzdRpqq0VC_Xo4#}o^@Ua9IjtVM6xca4#i_d_DAD)ij6HVt{2-mKbh84@Th6_Gm1Q@qIecHSHC*q=tL+x?r3eC5-IoF5)%VelA77Ki-*TOaz-$OT4E3cch`!8nQjDkt`M!CHl)l9?}f{m37-vR_64;8k@~*UJFCMeUSgz~)V1@YO+-#s3b*Nt}c1oQs5C4@WB$cVavb#s6@r9*%<(dwyu_tU>O6d%wQfx@3^LvsX!u?mU#}E2Mdw1j(o5Oa5L(9^$b1@Fwc>;X8|i?DKT<0`?4?mw%mV51E3)LZki|PmzApcPV3c@H}IgX*+;?SKo8Lv_I7E*-r608g%`K{XDK657-q9rV}@R$J510)Rj1;h12>}-=LenAaaYlF4!>|JR;df81gaB*+fS3)(`5KPzx<2XX7sBoMbcZS?;dz$r`!Ij5_!Vk*^RsXPr-VN8>27G{TJi8%dq|Q-8;5G{W^-a8$ti+aoi9SrsEEYkqvoTmOhKub98@PHN34w7fzcJr)MbLBBOXgizTNw#eI#2XYrMWM1V!!fmO&rkvzJ=WI=RLmJ=Am~AT$VfO*IwkZ$Q{^}Hj1)Qpq)|N)uGdAkuyJ?n(OV&fUkTSdV#Z!i`+xQ{+v~%A?&?!-G0L(^pj41nKa5#D^Pa+{U*%-`P+BiwtdYm&>`D;S!X1CkrRC|c4&EnkftVwh!b*`RlW8psX<_S`uvAGbGRSaQ6`(H{5>2dDd(4TCnApvV%#F$76Xdi)oPz*k)P{h&1uj}qUDEgn8y7>VovDK0TSH2v_V>T0J(+CXA_6GbePcbDY&+PJbR1UXYVFm;K(oVIdA*F{4VNqYv*aLhh^pYH|jA9+IoVor{EDstlU!R6EuIQVU=!}t~SF}sDOl`lHXz~D>IH{S{5`*JSZHd#8rHL~D(uI=b!ra7DLe5&@K^{>wM#&geiD=FpSj{b1SWUI>>I)5Yj0-3K4gR=Eoz7|NMkEO*#nNUKaVAEQ6N2em>KP4VmT_(lA35Yp(%$s98BnAz7sZ=(+&o}@UqgLoDk%WEPsl|Ji=hr>oBEs4)ifv9rd#)2vRYv+j9whjJ0@j>C>)wAnKV6PSMqSnvy#rAr%aFSC)4QqyMnSk20JJp@3bPzJ|dcx_v4K_L85`Mvz?;?LwlPcaXulwPIfLEG+C3-M`~7dY$9s#}LKku5i<-RL!v)*BvURl<+O}2E%nSbu|{~W1Dp*eQetUp&&!(n#nTsu7>Zn6&Lq}12?1n`(eM{54!w+8%wd#SDSpHiF@L0N@9f{X8;ud=KDkW8B3+H@DMk2tq#+o}7ZFtdd3PZeGM|Kt@@pV@-Q|K>Pkp^p*idp)0HAujWx#~aS##p@?x`pg)vCP9&$>bz_+^04K(O1I({5kiQbYeQFXf{G7Z+xC=Gv1r^{E*UX{N=%?`vqGZpTh!8mI&OILhtbOXgN5{hf|FwT!s-(yKeK5*oR)x2UI#>vEYCoL={i1t1?Er{`K6x?vnm-@aX=A=Dctf!#9&+kQFT*FI!&fV?i9;KN%1F>Caidh9IYX&#g%TqOZ@BCFob@pS<4BC_x6|90sD0AKzM5c6env+(;KwnpuHFMOxJs-v(mbA@*hbZe~4?#p_M4K3FNC?FZTpJ$-}u=ta5mI;=hZp|JPM*WQtFm&NN}Jdv*dFdPYKTJP7K$wU7sTX%Eaoo{h4DilO1CEG1tUlh~7yYqGmr015ET<^7Byk0?vb*5l91(+@V_=(}{mlP4`i%TSjnZ_Z71Xx9@*FWj&e6EPWfP|>EKUD5#r+z+g?OFSBE4Zg|4aA!)5sqNUGlPc8w3`IMY|K)a6iyOil_F?#t7KVvuQ~06`r56evjMJ{yPRa+Y4SGKinwhes`ZX96l|ZOj<$L|G#m9Go;WAh{kXS=;jWz#k_jdVCq22W9iUGPV|H0z3TxvWfDy%Wyq5Lokh`C1jN07&RRRnVUi-#1&uD+N|7bd3exNglN(czKV@YzRw<4Lk#pO}EI81+8n@K#Yfwt1mwAIk`R|;at{>VXNwv$o8x6pR<7trJYrH=FyY$tj5DVZdos#3(Mc0?()%Y7BAtzY3yJPlE8v0nT?t<~oSWj9X>0n0mvCI$SvVr>pKqSay8X_VDF&d1!X>vkHAtaJ6$2&q}&;PkDm|4ga2aAo^-_XrUJg3T=PVNA;^mtMkwD(aj4mc-HciHJAcbF;d)2?~yAJjgX6sfH?mz9>DvnWiWAvn4E*>c02IzGozt263WpRZst0b0}y})&8^UWE(Vc$2)PWH3tW3;?ps$ZQro|9(4fL_i1M`)s2y<3iL4|KWu$`G&nxFyVKkeeN4(pLGp-40@Pk=KYCml_nibuQwAmxskFIHmjuysgjTICK2=76mF%ro{?O(B6MZ$Kq)j1_S1zlx0oN54^LCn2vV+nCt8Z#+;JV-PwhLcnbcbj2%qIrkqK|FjXUkAdvUz=&9()B|l8bqVuIR<#TUNMqCqK_Td_@kNbmw{UF_|aP^@^?CWpT~kph}M#5y8dJ4!zsndxk=zyA9M4>%Hl4{Ef=e}?kdRIL46!$E}hO-qx@%A1fF*T;#^dUZk|GzcMMO9nh!|dAdi^KW1JWFb?>?390UmlYPG|K80Q_+&Wy_K;UI9p;ozlJ#f#Sy{ns-8MZr6@4R=c-Fix5A`+ClM;~~Fq{~Z4Ua{Dzs+D1Q;!T4T3|2SQL+Uxh4Pl@u9;ecbUE8|l1tBB}%mNPSHkRUIc!WM(PtNC(K?NTeSJEo;{_%!-YovNPmK$|nr`W75Q{~`K?UGVY(>g~y+ThM>rEFqk7z@4OhE!||5?Gxc#*S>t+Up+oeGH>JSHz24HvoUyNQ>@8`40}Mg6hSHT^{{e09Su$={h^IA4FmeHC&pLB>Oj>ZYLOey3V|5c9s~d)Rq?PuanGuEdB(-!Sj%)-QQmmuv2{y2X#b@!T`?VDLY^{eE!4RfV;8DRL3};x1;RP_PN=kXb8;=b`aFp_`L3BVqZkr5pOR{DUBMBXnvo)vQp7;*L>ulSe+li^TdrR2Un5$T*3Qa_#5f#$Z7L5g?-?nvhJRX`N*}YdK{+~48^P=(LS+wPHO*VdA*Qa1ZZ;Xzf>1S*MB2V`*p{M82Fja{3(utT;UuiL(GvRIHNgzDx?j$%At|w@2w;t=2Td1!}woxM4E0jrhdPEm>MKKMgEB6)CU%i<3Rp+mgi9(?rUv%Sw5}u+6r`Q7nCyZAt(A3bX{}-+Vl4ma$+7NY1|90JvNMG-i+s!M1IugzCbv1!mu^Y6M0OlO2#d-aNxUWva;tn^7iAIN7W{xAt#&qk3ODnK72CJm$)erp0u!NGygzd#b3QDl&dYY737uWlB~_@E^yMXec?hNa_cv$e8cCxpso1R#4ftN9Ey!BzdD=)L5=zJJ()G=Y0hhM#tr$xftW)TN0-lLp*ZvOU`z3qB{K)c-=Rlk$wWb=yQ$H30KY25OVWgxRyBHXB&~gwZj%z;;tsS6wvV!8~-?KH{j5?ck9hYyuW6|K);%)4`fBZ6LGIYp1D-zx%awYP}?VA(tZ@zO%eFSrrjG3?-PFdnlqvAoh`jOpCKLt*=cA_)^@)S+sX*1M0KPc%BH}px_eTmq|H6`hSoEKNjw4MHGv+{iJu5QOt=l$mSSsBCh;A^0!9HT+bslK#?wuaCk0^`Y$JE>Qf9`e1nqeN}sx#$Ae)7rcIDv|$+!#zWMR?hg$B)+4L6;$I>U;NI^(Ef@yBOFz}sRbZTQ4ZYz7A0lbrYkddNb5dh&HP?&AK{8X+KKAJY1;ov-Gkg;(3UgBnptIfrq^yc4lt{pABo1GF!&nPZ&G81psPvj+p^gJ_y}2i@zu-|a!JO*o8twQjWBgYk$TR~HeIi-sRXMLc44$V06;g|0bJ{YtWaFhmC93~q0WIKrI*&)kb*`skWU1EINOzY5@0gEvnv^0`l{4!1OufvBIjt&4s|VGxcn+3HTm8mw?wlz1rGgn`Z|?#odCfo6w`2byNE$C)|L@-?X+sU*dHyDLB~d16$v*+zh^ezGPx?cGt9eFgSkdHstt>=cmN}jQZfV8wFxOUwd%L&T8}@or7BwkIW~~o=?M%ASbKx`|jvUg;Fa;mXaOF8T9TaJ)(Z^5PjSHqmh?p@;~~1D--67j^`M9;JQQ~*WW_cKz$qa>90d?IrI<;-psjx(q5B1w-w0C1m|-c$zEXWG;f;z2hT~XHMI3wo(8~lt)9c|4Dtn6g$A%gZ4{jZ=10#+gR}<;GHh(b%2#-*xKpuQ-hhf1a8Th35qHR^sqoiNTOS6PzKzhL^F>7AB{Qm_bLB)AX(2ua=pU=Sa#7korez6xi!Rpy;f59%~Ek)YrHFtSJSmxT@hq=+OZa&BsuhjB~)qK2eO4i7Aue|uclNSmB(XO5DUC4=gQrG0j|K^qGpkLV^nMt1EiKF!obe%+gJa}!QzE(0kRuK(MxlY&LOxNq7pePw$i9BbMxQ>2BX!2G{IuPZNMt{(+h&m22O-mqU6-5{N)9sJdzWbDZ!x5hFahjwwBY&8wclTVS2lz<+YL{U`kLp$#UsqM`2M5_p&H0V#d`#&Q({A}tcq@DH(X;Ew_3mj8yj>j$XAYm1o!o{VMVveM2gJgj?W(RXDv?jT5t{lDodiwIPof>w(XU=SzW-Ldf<&ADewVIJvs$v-xNR;C_HI;mse6dNG;;Qc9M>8%GiSQ(j&p2hpbe#-K};51&q%zeP^WYp6RI3KxY{*K69KU%?v)YvhOo!?xR93d`u~G$k7}#jIlC`kE|Wr8?w99oKz>Bv>~8b*9D}{fBixw~ar51Un6;$|dRM0;t!=Zc(pEgQCI2oZEDLVu^FO=Rs%TANQ%s*kru_#X8De{b^@l`TK4xgahx-k`S-(=B_8yOoZP(NatPp#bPNowf@i?nz{C+BCfl2#^X#5pb^7mu^ma569GwJY>L^g24rfa?xd&A9aL@&@AZNu(0_oBGJWr=o%Ic!ModsU^l^RDa=oo_!eTUbg4-mZXd4*Rkt*5>YU-)W}bE1zjJE=%b^{&&I(mZJv!Eejrb9n-@=$NQQ{`3e)l*bmyUDlP!N*Nbvf_rH4h!@Oz*A?Y*YEt!bb(xk;OguJ73~y99^7wGOoNxDtMhXJt@r;*rbl@LA+*j8r@F>k3=t^?7`Os4M+S=cVRvbvA`lePbfpDd7rTep+3ZW!eLaaENefrF@Y?Zz(Ch{8L^e8mvS(YfjSj!5}vk>M!+8BqLX2+39qfF$I3)eZSSc4*i7xO4Ex7VKVd;wvJ_#BbR)^bVHjt9hwiCRUX<~yvXgNJ_WG%yU_am+R)W;oK-03TJpm4zy5xf7-zPI-R>@Ze^~3rV0(2f#*>qAV(sJYp|IMu796f<)R9jHhO$s={0K7|^jAWmFADZt?TV7enU+*we3IA;*Yu5_x!8%Tj^U=f_sr6yyWW;V$tMGIa0Dbp0xX9##FkPT0^a9j3d76Wi(PF5ihh7NVT;fypzI6iZ{*MIQFZ@^S3_KoGj!_(_+=d66fNKJ2J*41?NXLkDwBhea-AWh~wOHWDtkWPSH>w_W5!UPR4A!(RRf%i`Nr*uc;=|&$T`owNzi-ENsy{oTmLT>tH%M+4r0=T7=aJ-2?Pcu3tkp4(G6?*kwEbEp+zUmb;ef&v=nr`=^LmbH89Ly>{rI-OkJ}ot`+r#tO)dg$ZtK@GQXj>GzT5e{^Z~b#>I7=;jfYRw-0SmTow$wDJ~6)?Z~H9|1`^Q4Tmm=iPbM2AfKIPoOpjP3J&(S6|Q)M{EC*Li_>r%ZEnc%G31v_KLzsVCWDZq<$fb!^d+u~6vvX~WXS1GiRPy3TTATAHAm=qFNi#)sDTl^l#*=fLfTz3qV@uz!iG_Fd#EjZf2Ky~AKe`G|EO4|-7#4}(t4bR@j#UU07pK<>0&eIMs|EQpbUQt!_q7n0`4CI=@$RK1M%a6WpJ1+R`*nj9vCPW1($6Yf*U)tf7+PhTM9geEiR?Oc)&RSR%vHzbptjze#n7jnN=*EhpX$iW4kSLjL8Fv^tG2f77TNtDkY>N3v*YCn{Me-vB3ianrn>JBgKyD*ptW)e23weL}@+)1?qwXpt3ssC!pX+5ShriIBOGftYa8jVgLHr%xqU--p{Jp76P~iF{BT^Wk=e%Og$@qOB6Nvq@3U2hA$JGJbRwuYaDSJ!_=>gv7$`0rAVc-MlO;!RTTk$?uwrv;rksJsqE>r84Wg%Btspe;@8V0OI{KoF9@%~;Lco&TFsoofI>$^8yAG3*{#%IM{V!`ReQR5ML^c<$0rDk8+6QNAek7PH7To<^_j}E6o*}Ib`I#cUABAp+xkV^yaQ_Zqpf1B4ct$E(X2g3da@6zSAB+%#)w0#rxCFb=LR-XWGEeBeHmZ=Yd~k3zk9f?&{D%jyuSSb77u}Fz~GBozpsn>uRh&R4K*~1xHVQ7Up2Zb$Qpto}GCV3o27>;pB(NcYk1=y26tLydIpMR(a?%M4#E@KdJDpC+|jCB>GJFlC?^sHz+XY6Eu1w8a+Xba#Wepp8@wuET3@aqbHQ#-Np9yyeBL<_WIfjKU`O?i|dcGvmf*`^zzp6;JOpB`*(9T2SakFNXXDl{P3xM;!dHt=Me29^*M%{v-H&Z4w;c#vN?Tiat;tMQ+#JLxRlViYumU=mU`C*KW578c2Vru|oOHQhWcOq}?3gOs$AQTSfzJDE^h;g2(c*fVeF9Mizx~@Mmp_@Nco*PC&Nu=2^xk%*PO&vl5{ODPm1W@0sRn<$^|6gw?KhPvL1&IDVCzoKH{l?#QyjGLJ`dogGV-j-hvZ1fVh1BPQ684xcbbdwjOKNq<1mb%>tRDH>wNA$jcte4ijl9<>6!WG;sDIE~9)&|HpAB1`FnX7z<(WeQucP3&gi6mNOUx(V>M@hF;zS%QT_JS%s-68Jr@qa9&1xmV#bvFcuY+wC`45eVft>MFNaJmJ!Ehb-yGEMRns{O6W0MTDl*vf2?Kj2&W$+~?>y%eRY~JztUv7YrtB1tgGwfFAD;MMacX6|g<&Xm*Sylg4>LK(NvyWWoV;+V=N`-iA4&Aw1#4gM3wCo6w(h01$HJR`rYEeZCN=_GaV=99*q|K_k1U@7I`06jALy*39=(s`W>K)$38B-+czi;-Ya~yf0ajf4j8cYqDpNhMAy`K*=&-grSRaw0#FvOEG_ePZ?^eL-GjuX#vOI2vjh0~`I6(3f^78QbTV#{p5-c!aL*(rTm9vL~05;8+n~#33H^s93wVuT!>>;A?S>a8)((yu__7Tly$)c~*o?#1s9hHLcN{Q1T^2UME4`0k%Vk0Q<;UwH+<#DM03YmbrN^w_eWS11(xYVSKQu%Z|3vm%La=n98?u9BNF`pCCf24>~=MFDeTeU#C8U;anOHt$(SMr?jhVaDwZ0-xI#eDh?@fXC6<4O##i18f?Yt#5?~(zX&vYI~?Lq$`>L`0(Wy9!RMb;uN^qh{EBKz-m1K{8duldt-`C#wgkS@=vhC;Z}qkK(qypMH+wyf;uaB#mD+5I<_uFwC@H{;93qhPG;{Cj^EyuV`I>2ofIaUlDsVA=6hOjyq-qR+X}t60+L|Q8^7UCwHQx%KlK6rQz~fiNrzpEqU#?!E9#SFMgfz<8I)RQ^qI!Gnmv7z8Nhn`dDnnDdcyKs#V6k$%Z669D!W^Bo>0AYuKMAFAoz1uTK(!NT$h#)tR6<2Gj8#NuHKXS0n|AY0a>w)Ph9db9t|CF=O16A;SfWy*-Jx=hj_o~=)?n2huyOQbcI|Np=-?P9tZEN;!=;w+6OEbX-w?!}>>f2vZussT#7CH|1Oe6mjWke3_h=swWo~A!->0Zz2PnX%n5}|!5>0rkY^6Kq-q+SfB(B`Hsm|~p7dAh_>GA(~E_akyXyJ10TgETNVG}yew8{>Bzzql|llmXvcR=nd{i5^AldsNnB!`{d332En%vu@)xG#rWq)2?30UO&uZZ;`y}F`F9$pFfFwjalxo$V;>q$UJrN@QNwI!8sOv%%1n(xmR+@;BffLD&{5VW6xj4ngt4wfHuGSAD%z@zk3q(&5izhCa51V`crQP&T|dNy;iR$9=F|!(A_LozH{%GF^9O4fHhg!S~wA21W28uW$ccAo7sA&VAn0zsFw;8cr4`F)y8wYq(=ADH@!Azwy-S!@TsWU+cg4#>Bx9DVYqr-{@n$jaLp_98QEYy;6Nggpm_-U|Ub80x?!d`WSi|Eq{?h2H6MG)w6}@X~cZH&JF4Cej&L`j~n^hf8Wl0;K+i@&Nq~0d(hubyDksu^2`O!6N*x`1sNO#yx3Nm*Epj4nfkT(-OMiy~w+5r1xK*1+Tfc~cpQdA_Urr*oB9rQ#R>wlqoe!6-)sP2?im6CWCP4fi&8BE6x;aWuobIU>;H}Xucg%kXiX|Sh|;m2|_0%ji@C%QS6DgPuhif6*X+#oQJF%A8Pa{u3<<@Qma^l|m7{JY2pbWVz>Nyh@wU(@Li@{ZSmBI}MPKo09Sjlg~AMK)|6;SJ--P`5ek@%239w0-|b5>#-AP6_a!FP)J(!u52R0vi8*usT#AC+e%4^D|(l{jI~nj&%7{iRydbwq!%hJ)3cmLtk=JVeLI{p8wxm&OYRiKV8Y{dm9c!osGFVdJ&P=+Nu==#GJRBaOB5gUbFpL8VfA*jpR3N$af}*uMt_70Q^1?wkmXaRzy9;>D**cKbd|Y!vi_7PgP9Q8fcDGD*#@qdNyIv2SMCaX1^MQhrs4Rigi#JAZ7u-~BxBkj`BaLD$#I?cwrgAJ`&5PtITNDP8^J8QbcfEnZPzPYkw5M1DhM1;bkLSg1I7Kql@7@{{|^Z+?_X09WSEX)#WC|F7K4Pj$~HLp8^EQvVEcqCe`q1_^dEeruXfM9*PaGreLmh5|(24l`x+83m$o+S&}*FrQQTjsd;JDz$mV3~M&*@SdyO^d32pekg2_2eki=pg$1(+ManvfN-9!;L1O^ZnUxOSlR&9htsbmyZL1PKi8AvV}Y2Pw2Kk%Z`@kj!cR`1?c2=fBEKcI;~2|qGOSRXT9{F%t55Xji@f4Q0_w7tb}d71QDNs7-F}V&X>li+WL_bU65F6BE|LLv_67VncMm;b{Jx$}>ueS*+h}}e8QnRTk{G{_>qsg}ZQ={k!^(CvOO*kTH{dlEHFdm(&mr|#_qk+g{-M$CcwVo9lc9MvLrk_mTE$He3h(6e@I}(AIM--8R@hI)f6*!Zc0)|9mFDr~EYmJ%E=_@3tttyuc1U?47c)qDW??#IeH-M`|%*7#RSeHO-POC+rPO$4Iv?@4Qn^ZkRYX73%T@b>(?|NVm)=jq>f|9s~m!@oZbX7AR~oxAN-9#Yzs21I`awF2ZOoE>wvnHf-hR#sqY3wnrO<=VBP`?7)PKX>3J^4PHIAh%t4;7|Pltc;5B^;f;`R&*nZR_A3#SJ!EOyPjK2Di*|DLbGdhFwV<&?`igbj0f`N{=f1Z7!NULbk~<8aG*Zuh6E$eyd;!+p(qs=m`_~t{)wDXtJ-2;6dAbUtBMr8G0vGi*ObR|(}0*eTKVxjP!tmue|Hl((U)7`X*_Ijj)`V^jvm#0Wm0H7Hwn^8Ud|<1V*iA#%KwUPS)>B{C0`MbSLjhh|GNt^WZ2Bz$ZFAy=ZSrs0-0fIX(0Tf_AR9b&l4k@rR>zkgT9F~4h+sqYYT9QFMfe6gL)5`F3ZgUwbPyhSkM=2VsyjpvMee%77n7b^zucg$lwJMj8!&F3p`jmCk*MDfS4H|SAUjelJC&q##m6aToP8IcqH>vD=xKq`L2?-OF^QRg?l*H?-s0df9juZ|wI;!)pI!DtHY+^skSJ*O^vzd`QfbfC={c!It}%rmT0(s+ji9~oS^||Jn&{wl2hO4>2Qkr0Ip1Tp9V?OOqtqD;NI@H=gT;9vghNGfPx%27`B&mNE7{v*bl$O@PDW}^RSw}_WvVFNhvBNiI65Cl%noT6(tl!DM>|9p+Q0#P-)aWp1FA*iISu=kVa{cNQyEPrI6p*=efS0d;k7t63W894c2gQ&x=gY+X~R5-={;&pqGyQbwrxSaa@LCO56mC+ckM~PVlUX-)G149nc4JoAlK}5a-WqSymc`+UN-VF6G?(6ufAB2JB)n+NdRMZCtmo*zi-sR*iJm*2a%HLXZAhsY9o|)xb*Y`#J!jO{Go7FL(GG&`!wifw{KfLwTrC)KdF;0Hzktx)P^_OiLNkIJnt=y!(MeAg{{(4eji>&gdm1U^wI?LE7RQhwChgHLY)-n|w%%AUy@i=Gt%j)$8~70#pX!Tti6kzp|E^LR^Y1?mz3FXwYx-32$bvVF2EkfS0exGk4DN5Y~PsUhv8ya<)e$@2@EqCr5ZAc-Q19JS9&`R47wI0#-hy3nx{b)t?rAUhEz!_6Yrdm#T1`#XIrsZf_OUzOJqIY-=O=MePxb8;qSpW<~iE;3cV8QcNM*q(KC(s{;Emf#6z{*eE1ASqX${qg9lvET16*7Y}Y`SJR<#U%`xrgwpRedrdM7}W1ntq)8#i-aLxn{&^$Am_~PjZs;a84aRaVsFhJLEV3G>;VnKI4C~9be?uO@(+x<1s@>gzJ3dE%`i{C0}fw}j_A(A>l1Zot4#mLhgTv<`;wNc-q;s~!C3wSsN0D5J?gum)RWE4M1Qu>e$<;NTQgeO-)}wZ`+|QY&LR4j734-k>HMIde|?c>9%mh7K46ct%Qe!fSsutUSBZlta*1H`Z~MYCLC6WhmCxT5J5fOTTji{Rd!)RDb2;&~1p%<&`m$4hWbwY5k!R}Ov;S_19Fm4A)NeZ!-|p=Wf%2zMJP({hKXV86r!D#!2D<%MmPoBbKdaauyipGO_dGLNpgf7XBO5>@Xp!*gqrskxF7$bzt)=HvOEkm=278=%g+32a1_YKFvB%jjmm?m1Ku%C0Hh@Ezx;fZ&?IFp44P^NecQQ+HyU6$>t?{decV}^ke_{PQ{#nP*@!gLZ8La56_7G*nnO*=lTDZ)Gwg;-|UY1SrH&b1X#47Poj->#&9I`^Q~*!^&EMoI)A<6Vv!hl^6FLD>GSB*s8Rdncds~3u2<^}>W9}YuvFfZ2t>)%XWjBS$To@3Pi_J+IK1^)APv7I`VG^NSRuQ^0F;;wDwOQ~14)oRRb?q5-jg^{4{t=Qq=fRM)jLICY-I|M2y(jM}dTYeV5|b)#mJCi2qQ>f!i+@h~`_tt=dGhrD!td*`WA-@D+cVqd`*jNI}r%Rhdpek43UM!DGd06FKkhfz46X*BFV{(a$|DN@d=(b3i|g|YDGeYrjBIO=1gCw#9vCctQXScmB^-0z#cAz6EIbTVu#Y_eWL(gRjs5kD_UgJ-+<6?*vNb#5~NSxil|czjiZB>QLdTab>yq_65S57xk6wodthSCM!tG0B$9Dwe;5q0PFW{!M7`+arY&b5hr?94fmg`|)IUk*@)$WpaQeg6KS6!r8Wc-ZUM+qL_gf4FM}cRai8+7v#6hXB-^2<5C-}we0y)Ep$%|i-UI;AI_l_qt5qh%iYzN5`i8)cvQ_Axkzwb!o?%G6i&XJg$nY|%6Wz>YjbH3THVk(tc08+=q=;Dwj&tUof3Ldp^4XdxkmEJXSpzVpi5IUr;&0b&h{643JZrje{CjRgz)aQ$yA+4v4zi0a9OY=a|1`45>t@x|M1&ZHt`KQPau$Xd4CWPL(ZcutlCZBKB=lf&~o*w_98KkaFfvu)+NIq7e9U;Z`3=O!gchkdeArD+#*L>H`BLt2MZE5C-MnA;)^PlcvoOQh4o6*m|Rc9K1bcRENt$^Nn(z@ShsTQ(^HvS5=)LQh!O|j+&+OL*b5i|7f!y>2o_gf54|Q3=SGKbV$^o&JPTiZPIt)yY9p7%Sk!0sv)L#`Z6QHbzZl>jxG9RWba$`+a?N1y=++GN73gx`DGnNM`JkigbcmVbT1X0AJPwH@|B}J@S#K&WX}w=(>AEXsavoiTR3-Wj1f9K=db^A?4ezAN+XB_I@bn)V4p8JiTK4Uj#JD&EEKW9ChM(wWuTtlyCRCU-dwrwnBl~vyx-}$HQEt{Xx-3a@#B7V7^q}8`l_8er$(P=D+2M;Poh0=`1OKRZ%EyX5+(TkobK!n5PqU_Oz}*^f?vy>*}gSe2}k*mpNqJg$Iekiz4Wl3wqdQsr#;#k+88@dR~(}?i+f?`YqU2AI0hWusIodY_jq0toEE3h>M@=^lSm{8#*N}84T`;15SU=1(*wZ{Io{jij#?uBXHxM!Y14|tlh5~uu_)-pIxLs%a!4|MdF-Y`9T_|uH!QwavCG6PhW8d1El4HV~^d%{lo!frBB`VEU+$=X?K5zuYaAZ(K`%x;Z99g-~BY)AKc_>;?|!U0ai6jvhvkXKX+Vi?oNn;CEPX=!9lpL^=0@|NV{+hWOP(1ZZ1YnGgZ?Yw^N9N#Az4{8AMJyu3I^@DkcGnT%GgWbx{xb|JX2$9QR|+97Wu-md+_RYu{$?1tLUvMP$&tKpU;yRWcq?B2b`QU*H2eLwa}BPPA@v(_c)(ksXA=oA*+2J;rK0Y+BuA&8I~tDPC}|H`hu05mG=EF)kKyExr9DKQ=)c%CJ0A3u?I$zskY|Y8fetn|p7`6jI+v7dI!pDAShp4h<{uN)9}z@O2zoTiJFP|o8AbVbKSYrSpj>>5DmMcRpMT(v&_*8cdnlz}-xv;}EWeXcr2dk$8>1(8FN%Q5m@413^YOmF8;?<1u0%q83r=T-iP=rg_hwaE-01uQClTAe5H!1pni98-Q85Oph8zakG1d7jIw=peyxHU7C3$5UdSIrJ|adah5M-XcQkQz^Zx)&e3R-s7Ud>=II+aVGP2b6O-E;2W0`vqL{-&4X&Sn$hs|!rOKq1@t4Q?L`ygjfLTpe<=)Z^z(Ve?oGyv;yHaGg@2Ly3ib8YzcWt+qTXj@4*E2^%6FsrM>71XSu`tA4##(bJKuh#!qL4ll%~x%zBgXw(fS@t2LjKvNOeIqe|lc}?Ys+4_owrRebML7iH~$|-w4RyTUb4|o%FdeZ#I+-M}kX&b8aFxslJ{4XSjpS*~*TL*^&dOdkIrC4r#{1n8#BiOHytF(XSy}Js$Q@LO1#Jq5nUj`nRvUCIXSC{>lq|@@oX?8U9S>!G;H)tZ0#NN%3pOZACoSU!vo5@9VN?AnH@97}%#~p`*hB!)Gzz!k$pf5=9>C=lN)qS`-JPa@%CL-oSlE%M&7LH-{4->f{BrOCOQD1h2oFCE=b7M4eQGGp>&j`#OL`e_C1aQ4-aOQaTR~sB7Ondd4f9QaR$-6&uB@5)t);P$7qqaK{}}3SkKe{GtBZ$<*Ml{Yrl^Z`1iMelCxM{shNOv$sB>A^cItkiaPmfS3sL{Q+P!lij0QuGdyg%XLtaWWs+*;DmH|Xxrh8+k-~O9ys^i1r^rx7;0`nFUH!lnnWske*5102ZIfMMOSt);$yj&ElYx$e#6NCD#ZQ2PVInls87haUmiu%VtOKNH7V!@$g?5-ARUyrCy3U-KxnT`XIyTec?&ikA#O9Y}0;)gi$65VR!r$8GD+)#L(-`s+_UzskgX9o>jBYj^-S|dl<`dgpaK9|AS-?5*IoU=mV*ZHCOEKZ%6K?mwJ)r0S^R7JqU6Uqh`{81lKejwW<90lL}`P!36byoYiZ^(ZMjRyJJ(-$aLc)fkdIdvC>_gT)RfNJn)@rFLsiCoc^zf>UJ_tgmGoS4C*^B=J13);4J%?^&pGo~7Wmy9V)5a<@Q;l6}ip;4`Mj<-GnTF+eEn4*iAT>?yTqeIkX|Cw_nbw#0JQdygcep6n?YqbL~<{z6rZ>`i#zywC$D#B~#4bhn=FKp*O-%`aRSs7VGlf3MDWDabRbH3u#qdP#*p1M8rTbWYHMe#N2EnGW5(TrN$~$O+alX>V4s=L-Z^?5RdhxSJDq)o3^ZikS?_o^N>Hl^LpTP)`Cr30BLF1Ajua*}2;q)^~O$J%RV+QW)kq36Pye$bSq(c7YZwz}4QXRV<<>)q`gKB{GN!K$to=&%PQx^YbK)z9ygmD3mr)e|Vs~0be1SM|4*6XD6gFECRBmz&e-*4{@u#-SP%Kb0R6q}-9nS9OE=LXdGel@PV<`4@usVmxC!%6uJ><_MZM?CaBSyQ|4Jo+rO;Qz4NFcJ2=y18P6R5yNgeA!xiW-@2rMAi{~^6xnHLy|#-?1RkTucL9?cMPoEW3ZeKHitU*%qH!xX|BHdweJxF4j%fcFptD1Ra>~+jW>noE8Nwjz2d3i$kBgBt+B#_+vnr@lkZz8h!emQaHoMjD@|Qc0{#mqt9W*!ucYO@zC>t`q4A03h2CSDZlG@6m|EClC0n?e0uzlm_r;FC0Pa?nL^4BO(>3eLr{Tu2;-tk|P7>K{jbNTQK^snn^P}Vyf3k%f&rN5>1FI|b{kDG8iGE;@=!xL4C*gggBl=8V|JJ6YIT^G|6fIY9qtDQkE1Oa&R3O%0MN?7V{P38s7JFQF`mu4vtb@o=$-BfeTI?Ad&fGJD`s>1vo3_l2fdePivzMjfJ`}M{Q|1#3oWA#Sk-Lh;Q&$FVjpyW##hD;?RW|T1TceN&M_jURpTlKXx8rZ{rN3f62f4WZCzWj)FvA{X6JQwxcPg$a-O>yvdNv*e-FLGDf2cDd&!UUMxAhgMu3w6I6S9#m}lYskluDe$Na?ZOPi#-!6R7jQ?J5eu<`fz-mDpw{Ap4`7Be!K{I>DzBr;zqwzPJc|Zd{WMQc$0#ZcQlL~x+k?q1Nr2b!@6P<_Po`o-eHX~sXn~@#Ory5K5?+jTJ~Y}0P>HM?GJ{KX#%A8>{e2$MV&bBZRVB)<_)LS-c+DY)P;t9q`<~?t!E0VQ2*H(J-gO|2JRc5yBPjN-OuLS&|WSE7zd53dRw5M^BG^lS%XZ_7oA*jOalAqRH$@iJmgCSDG5=AqZabjQnUFNsi&iXsGHXOh`i*fXI)fL6$8BQwkJw2L@vtFD_v7?C=MoCy*eIhqW)dpA)!hl0f@E$2Ypd*mf71>E}O*pT}kz!PV`%)+@x^o*4|nmM-^!>m#VFz!Mmf{{6+JSqn7#I?~N#>L(!aFM|DW+RO~-HiFAJ^7}w1@$Pz^^VoyUBTg0Zo!GO<8Uk#A*+Y1M4oh+hZ_svg(!lb$>n;^kLo{|{2ckH2Q+9c}4`l;P^_V0PZ^=;yI$cFS?;F5U!UH*<#xzXK6ga6toupjoDXfAK>eC#y}yDd9pN5L+m&bv_!1Tsl`5ypEjosMohgF>vShq@;f-l)ID9AMnitcI=c2xU@HrV{gagE$O+Rg=lx6yi-vUN{Tfe&@cPMXRo+DRvH$&ycd>0a>O`OAuw!wc8szg!(Grp!%EZL-cy|Gkb~5e(u|Gu;0x5{gWQl^Ec+oyirK_Umtl2`m7NB@n-(~Bq;8Q;}vyBpZ>PV=7p;$;K~Mu<0KBeJ;S@cqlyY&UUZ$;xr9Cy-aOmRCqW0HKTc~L;&I#;&-FO+D2@Tdxd#D99N&rKPJ_ULmFjatf=GNt)YVz=#K0GinIhU(^l7lTgra{a7Jl?*D_XJ8=Ys{2OO`%~10p};k^}m5bJ}yN>Qn-()NrzXzZZR8?2%ipxH$<-inhH7Rz;uf4PQ4000j&l?S7cO0)0l=j;k%Hp@NCUm{xio>T#u?)T;&Pkkauxcs+@))`ST^IB`+V`vhn5DRe>6p+-GfBK>UIf|GE75|_@mNWYg@)xdCoo*O&eQZF7jocj8C>0O)0Ka`FXlV;vWfA9O061@7K==PWph`-TsAE6z@rqyn)&xg`Vl0f{{AqjNJL@2Ml@$SA(Pc}2X(#aZ#-e9hF!B^SAfc)lFJo&W=#S8g3#jrzT8rR}*YNnmj^lCn7lx#huH=9UyW3VfHFRTIHSTEDv8O{*)Rg4C3+x9k$+qHSyd8kt9j=aJRD!$EZi715u~5{W{*)TJCOcTXP(zUsaV6@(jTtH})ie;y&KT`y^4{{$`+5_iG{$^GKObxPM2SM^J1}2IBj1u15X$iOzT;e`IUa9xL}e)c2e=efpq|25(#%1oHDyf0DF7W^^Y5Ud9!rOAMgyE|jwF(F7B+dlod>A4ESN)k=9OpHhIb>bCzfG32gG)>o?Hm#4$ddAG#|4kC92C4Cc?ycY+)QwpaAzT$qLoQ2JKE|~=QIP0-wIUjPDHxKusoXSL)Bgijpz6Et6Cs!^Z8Mdl_Ozpf#%3D~U=5)b=3X5d?bTk@JC+300aWp8rdg2yE2f2$lmu1b(fTFM)&1-(5e(QMaLxl_`TxCxShCU#V4Yx%#O$VlM`c~|WM(!eVN-w3QLBsglFZ|BPOI$D4osch#0~elrm8WW`2i7e+StFVNKL4^$r#hid)Xn>5BtrDAJLgpMQJ4RB+~Sx=GN}4@1lp2v7}$?r*IRq2z{sC)x3xn3(ktPy05=*)7Y9Uicc3nQZgj>BVR@7Ej*uhmI*3i88SKA`EB?XA{om*#6zcr`CS6eL&Mi*9W2;fJaA@=VdSH{8T_q4AeA4z?Dj6NQ+l1cz`<2(MVcH?!C_WP~c@BB$67jp5nqM0tRG5(Sz#~Iu3GxgZCyXx)vBw?tyA2c>IMkI5?|jgno#;qz<=a_$|ZFRicc3PE@;}da;EH@H>3frXkdcbx{dp8YFY`-_0o_Y_FGsR*7`|)Y)Ifk6z`g|Z^o^vX+U5&aLq>JNecA#^FHh(-Ew%*zJVFLY}-S%?V=*a{yy>#Q`Oav+4-gDt&?fyil|HE*illE1KKG6`C44rKr#v^mlk7e5z6YcF(;Cry{%F8~~jgPke%sNPedPmzIGVSOyZOe0w5Pv%K7VP?CO*-coW!1BA&PN6(53Owpj{8ejZtpTZ&w}Nv`a;@$o4n((C<%7W?tc7?l#4}-mzHc!eWFtxc`uDr*Yrv;CRmTn{{?$mDw6PXCb)5s_6AvT>9qmzkh!`*aL&#D|MMK{NPwx=&s=2=kk;Q${-tp3Pl92cCvvT%eOTw=*m1?-WFYRpa3T6!dORtS*PIGJj3jwF!cZr2dm`BLdLqB%Jt@D7$j4E*MhC#^w%FBs2wn`mK?oK0%$}=_Tyr_dWY`w29_Hg+v3LS(D1R?!;GC&YbN}gH_d0g_9x3OO{a!qWUW6kUM{-RQMt0FbJKmZ7W~P1i|luX46}+Zc2Hn`6ZKD7QCXx-_6>F=l%$8e!)tGe;+qkT4_AiZdpM=X~L7mIckB7lnC$GjlfpweK&g+hK=585Ro0bkR;Kpfnm$ERdOV@Pw`O9;K{e6ku+a5hdT0dkQjlF%Hq;-KPwpe)H4dyISjXFr6cppP7W$xwu4{&+T3&JhGx|2RfjiSi__IlgpA|@2(ogl4PtKub+Ni?MG!lfAp>$>#{_hIRCYCJr#&NlH;$pkFFrq!>69mR}o2LfNZ(b)${LAUr?OlA*jNFM2A?~1yU}S^JVSb@lz=v5+WT{6^42MU;Fc?|I#2WQ$sZ20x4fYZ9H>oXC`E{jd;7YAdi{5j~joSlLXxRU1xvYgmvjpgUuShUQ33e?Sfwp=%Jphb>7%gl*-AwyKx?MqVGVp01eV#b7h}QMSYNa*Kz?xI(U4z(tYkP>Yl#J`fps>^YppPv+J)Q*M0gt6>l@f1Z!eqvk`gBW~NzHC_M!lPn{ayxBfE|i$@wPumx$XmcElCfU5V$;e*Ju!OSNMV#Zv`z=;M$Ac9G?BiMbBT*-LI&pfnh!KR*f3+&-=~0MfUE`fQbcePejd-a~Q71Tf*7j@9*tj>NJX=`F`y^qW*hF{(*(_sPL?4YjAcQDet|+%O>h86;|e5JfpoA?;AFC18z^VzxNF#iy}KwUzH|NzH>bTeCmQ%-MNK+^p+g&xEag@ZW{>$MF~Ax?)w+{q`aw{ck8xEB!R%A1jm3lysz!#fYpWT$)KpKBHAm4_g(!Z|A+T{Hb2;vM&D0Gy(Q(7RR0JSf+pWjWbQ{lwSrN5ncrxzC+Ys})x78@&bI8;wxtYk3;2{RM9z`e_gw0w9TV(sEGUTTCiTT!g%4h1?z#2&IS-nx=(xlFeuHBig`ZTTf62?mJ;!D#qM7&QF7%OSbLK+K!*|xm|K()yK#xa9K{R50y7&9K{TLcVyx(9nM?{$k(q$j;eorZcY#|p*4obx=csQh>s}hR*L*(TyIGqaN9ZOwyKEWK(O*^atybh+rabf{&5$1>z^(|G`G9h=Z;W2}MnA1+w9r6!l|L=U0C32V8w@pu8%%MVwUG&@`1>~sflF!3;G*f|SOV~7xd~!XVqFP=~1K-9b38XjE_P+l3tgGhhArM2@4*d}Fk2bVVj)YMPi`Fu?0CUv46!a3h;jf9~plK38q_308Pb0pj?LU?y_T?q6csPl~Ca_~4}T`Ln2JKWRQ9pGX5mId{sgO{iyBN3~=!=^*yCcGR5AJu|Lk7Z-(ic)L0PER&*!eH|ly5^S6w%=QY;yfBlRAuQRwhvf>vj4H|p`wDz^2p6IlD(!4AKY9^nu_O&8+MV7M?wfM4u|HJMF^%lri#5~ZcoWjZZ=heV{!>l{qXQ*^4Oy>La4IV)KG}rK{-#+Z|)ZQnp+ZA=Ap@%iLY)&qJ+nOj@gu0x0Xw~^F2K;+|XE8+x`N~hOo;90`1uX-o_=8A&58J-SdY1*Iz#8|?-Gir)yH@M6I(ZMJLF0TUL7%J0U1!(>bNs;!kbmcLci}ALs}~{0eXsqqK;QWj7q1_3(f+!N!hG!Kc=`dJ0;wW=z4vgDV?zuT*dIsk4ncf9`|)!`;UW!AJsdoeeF$}fiKf>1?0Kf`xgpzsG}1n%&0pKYfefghI`wtUeB>ylyxQHuZA=Iah_oHQje37VO4G!F6yW3~$Rl5+d|#03GLs55PJ9Zi2~s`$4LL5I!E}(B+9w_L1Nmp6k=ZBRSy`~_shZb&MdS*#eHKaY^C@sSkuEcQ6R*=SvC@f`J#HOO+}QZ~9qJ}KPD<@NOM?>Ovi((tc>R<0m9tNn(Ls2LR!vV6>O_vlC1(csQ~pU^J%fBj)NdJOGeJH4WXAAv^g}#1mW!ppi}xF1DU+xZeMyw_Q(@xNI@z*GQXZ+sleU^`>Ch!16cizgoIvz*?|07xqVDg4KdJ8BezEMUM-=#|s=xWyQoMe{gHN-~*x&B~+1H;A$D>Z{OI6s?INX)Ap48`>zk%}T5FN@oiw>{rM7`JZ-hlrJ2FUp7EOSpp?h08sOD&qsjqm0OrSo1#pXYd|sA7XG&iRFIZ&J?Zt#qYw`&9VwO;5Ik)TbuAk}fowgX1Z&&Zs_~0W$R1hlg(9c)Gv7_oHqn1t#kb-MB~E_gs_D>@lEHK~4Bf-dR$wIy1-)^t(fB!cHh+LVbkLZ)g$y}2|h0E<+gUxjGX?$3gT6c*CjU(erSr^eK=iD{>`<-XF(nR7o`W)$c^V0cnQ|dH7D?=WH_1eq-24CJ?#5CRfov(T_4Gh6NH+58vsPp?`vl7JN^Enb?k$sX)@Y(B2)p-#es1ht$N*`#Q)cl6;ixJ99IDsK?Y3QJ=`v1arE$^HTgR`HQGl2dHPWpX_2`p;&{xXvPkVvJwq8=;=frmM{8_<8?5#J476)E7iH}68!d(`zNFY!%Fr*Zmx@ssuqdp|QPt|q3#pLd6&+|D9jg|}xX`})#gmH)W&97$ZiI#fZusc%7tm)~p`CY$4aA7xfxc$6sv7C$H{?GDEMzMj(KvH~7VAaXb&Z(zNX$cL6+qtz^MCmIX!B6meC%E}PioeEc+_-9xC!hD9!H%cM!ZyIE}zPtF4j_X&H`m=`3KQiF;YOQxBH;~6PGUBB_$!9~}Op{fGI=-H$FDi}Ch2GZo<#%k5>n>4mcXim%;NQx>6RvAO@Y;AUy+;#*HLvS)_HUrHz(WO<53e_~qz_KX`owL+O#MExDlVuWR7xkN$6Oowe+j0S)#Q8`kb3^`rTmX76JvMThDIs}8q*A#qOh(Op&i3{L*A*<;j86n;FGkYWPCgHxpbfbWfF1yPQ(V3%p|8vR^SALp0Rm%cwuf#KrUrgB}Vi@y1=%F#Xz9=b#1AaV86{tqBuOP)3ew&)+wk|1gJ>gE8+1?i)UcYYq+BLF1f*Hq1aS8q)7FzBZrDhpqaPT`y42YI^jMXDT(-T}4!AK%5IdxCmb#bEK0$jXjT3+qhbm%K-HiuWkj(bZ$Cl#)r$-R$bi(98Q*l)pr3`aj`YMdwr=&MEXcQCG+45YbS`iAl8D+ZG|2P_c^2~s{Y;z?`Xly*1~n>YhCe2=?d`GFRl28^Sz6=JdIf0hJmKSe164EAZ4TJqyKK7F4i_j@1{R<5iU^XoyKs7DP28c3W!BCIEZeu%nE$`2aMyDhfcg_PsUQ{303&3?aJYvzek^YL?DM%~=Dfx-Z>#K(Q14D^4crsDMe1SV9x`TJd}5dEj6+c;zwvp9LM;r-}e=);2J&TNii3}y~ki=j`sqO9LB25G<_`d6{zIVo>yMEQYJT{@hfP5YS_fgEzA=ibw-lbPTvc5U8S8~T5GSFq+_!~q%1Ubq^!eD(0dtN}~QAJ6T{I8B{=SpA!Z}sPC)&tZz|9PGAzkgr)KmRYa4lh^}@nAt3+z(2S*svP?(_8%Gg3qTzLOnfi{1fUe&pwJ6e$0U3*zq8P2gp|i`j2+=kJ4d>&6X3P8h9S?XOd;)vlk4A2<9;xxrXangTv;Bre89l^ZKS5oibe45^*{$)&GkHoW5;eurB>s{!f0IK`JcC_qVzoiS_54I@^vka1c7AZ*dRnqoTF?MB8FBK+wyeV;u{*h{&NBj>&@d7aNM#G$4Nj67(1J!hwb8`g2Le&{R9wbDUEe0f;)QrsUT>IT&F7(nDlmajnWlHO^)%`=M$;-QCmn?#XY>{*MR8N6Ttk;i7e9QO@>e>_|1FPREvg;6nAjgZIYANOAQJ1Gqej~TpL+<;s}^nZF|k^#H=3tczdLw(1q$^JzLvVh*CBc6X4uftjQ@y>xK30p2x`tZIhbS|Bqa>)Z?9w~AJ-`A*MWVd4l9hlBL_$EnxXD+_^S34EOfKSIgDf^sJFR+$bWEaGQ(&#$pp8cp3_4Y?oS+FSQ#?B-S)Q|O54wQ_fK=X^UqPlvh7uQf1*ITCnk#9857xir=$t&B0GGP8Z)|s3CP-jGWdVBoN1X;UvUt(KvAMn`O!+h_gayWV5TUQ}R)%_dz+NGWczSGg$%DIu3hdb&wenmAeZ=o*Zu#h!#j0pyIvc3^*s3%gxP2RaXlPEU32u?tB0Gj!P4^cVa5{Vgy7aiN2HB&VRajS`W#nM-YK)ReWL$Ul@1dQ@cQeik=Ch*I;TuM78qYVFtYI^a@29Q@xzWO5D>jRIfaxv$~D3;`u8vuh&-Xsov2UF`%!g5H61MX?B)583Xb2a~xEU*&WBPgkb<36!I^Pw;YqP&!HgGlEG-yeLmKqZk5XWuPLMpb3{&?fXbbW=mj@p~F5mi>%he;9p6r28Dw^UeTkqG3!Tj{C&#@0nT_1c_{kbrZsIbLAWX+C||Um@Zr)cPbahO?SbU*M^hnpmNBsZFB^E_LL>0@|iPW^y|6MnOG9PGK*lnL{X*iRhP!g0LyoYd`fw`^GOg=f322y#f8aX`UsCLLaXk)k$`&S^?o9TJi~!GKzMmR-g?QvbxRfV*MxOd#@N>jzLTa+%k?PKX7|O+&&~_Mra|>8Mj*g;U^I_mWVJG4#I%43wU1N`<827~7p4iF8}Lqt!{bNBwjDtK1Hw8|)b|aMOS%_Q7HQJnl%eWCJ{Y8Yt0->sK{PvMz8h$ODN@QmngQQGaw&^<1G&KJ3`d(D1)VS|7W=luPCt1Cl?5C9EW!@4NNSg^Sh9gzC|kd7U-LS3F-J=}H?5E?+<7bNw>%74g3?lLF8uswkp?oWl}MewkpL2JbXBe!eM*TqITX>#ScNoAXVEd_QO+M~OcEck~K96V7OUbQG({b*c=3`{JUEY+z=(xG$fDufM>4ppL%Dh0gfwhXX6{`kOQxExyR+18a$kr=BzVO!s{#r9aGmF70d3O?wA@Tr!KLe3OR>sbv&e3v%tEgZ~x=#r2fm*9%|x4DKOBpw#UH$^_nN10@bQ%K-BfI&E)e@Lt|xH)s^wjfRn=4;WHT~&s}^8=`;lImgeM;upb3*7&fP&Sx^(tWmBJ$?5bv)!0d=A-`AjJb>>s*BTz-K1s(w$eJFO{Dt8+(X?G);x3W6>BCDK4WyPG<31o?`{ZLTj$o=BtAv%avHDEOJAN1Yq-6m7?a3dYaKRd8*jaiUu?vzkhhMcpGJrPQ+&w*AYjcTU`dZ0^jbgs@Bh_e@<^VvCBL|Ib4XC>mY8^~|l)>pwt(}WLU0xVoIPH=JM7|CmX&vU8w8zJjM{!y;Zuu!}9T&YYoih)0Q9z$s#u6Jpdu2eF!I(@4sZULia@YH75?RofCXzyN$8o>Jrt+9XPd3PhaOI|u#(ll<+M??fxt#oYe+L{ljhcK8ewk#zRObmQQ<9W#Kguh-xSR<^?t9ISRH8mB|JLVy=rdr%S8-WJD*Sud7}21PKGP?LFSor2sLS+<1rKFzH|Nij+EbJT|DI_63c@8o)-J1v(e`sySP1PZl{32kAvNAq?|FQ@)RC}yQyGj=@Dk}2mNt?owz^!}hCWluZp6qrWJ333+9Qjvs1xUW)4yhc`l>$Gk3!^=_kZvG?Fz~P$!}9ujW_B4>B^~dtAhmC^Y<2q!pEfgtNmPB8B@=gkYjbLhC#}4CGrh|V_2Y(@})k+96#q@;$i}k*HVDKcKT|Y6{)YHj+DRo)l_iy^r=n(^m(v))vctcG?>~rm}5gaS7^()biJTH9SY62s(-zM{)zgTOz}+M_I3DjW-t2h{qjLG-zN)xdJiNOlIq)uIys|RIZz+qCPIIM`o^ypQl_+6@M&k(jDIVxU&WqJ&DK^-0bWPux#lcfzuHvy?AS^5RLJ_9G#c)L>sQ3So7;snP)>7-GqS+Cte0ck@7?K02cmDP-~_Hy9a8?a+0Ho=i2d{OZse$~<^#z!yR%`x^cuJGw@&@1Q!eU@mLAE4%U3;LQO{sqmfyXL6VosApvW|EKw$~$M80jdPyw(W#Z+-A;&uGX4^~=ev%rjp$8-E7^40lc73&k^Q$V7BRC~S=^3`4$iizabRLDKi<=okg9L2rZYstK`X;6M=@_orU!wq3>ioH2QeZ9fEduY`k)=}co0bQoN*}I%ry_Svx8?8CZqJ7Tzv7J@fa_XI3(DGCby+YRXL0JBEppNB%9X||6;dFp_F87K4eCMmLWfQ(rUE}v=;)66TZZ-x(u)S@7%qL_?|;@>Tq*%HgCJIUraxXP27|^3`to%L2#Cc_3hSear0`T-RcTgk-u>@`1=-|FVe0Ia5}Cm4+-BShBpX_zd!r%;Z5u<=Ip=NLuA@#*JY({jD-$&D-jzD~4|V;gH4k58WWk1gFD=icAYc7Bcl26{PY#4++s(gy1v!U3?dUPtlLtc&%#KyvM9yK^3KrFv=X2(FJdMZ|1Ae>=nh6Um`9JK=MA9oye1V+{GM|~`vvO6dhb*9GzjPYwdJrr-gm2J#NWkk=^)1&P*gsEI~4qnqvhqFemp?{X4Poi(&7QYPmOP~9$(NO4g=x=4%oC=%1*cmNLzN^`;pM{P~bii21NlS|pAb3NpQ$;}U+C)mj6que@l&9NN#_Aili%9cuJr$OqOIEzUp5cBuj4BUMxPX^?oIc0rGW9AQ^GGS(P!QEF`icORG^P2eHbB~GYwx?l-0_e2Jg&FRlktduQvG9=(q5vgWAN%{XeAK(QCOY)%Gf7K&EzV_qkTum(a&VUg_;erH@rys?R(*-b$J#Lb)EOOq5s_~hB?FXIS?w=(tl_+a@0-kQ?DB{bHRH^FV3X}b!%P+>&@(W>*O}g<2`)1ex;@E`r&h7D%5X|H`nh*zH)qg_(W$z8k8jumF2}DU%9l}CPpvFfMu_vqQmbZUtQjrt5tU;6HZYbEGtE^{))(t+q)tg>VK=nGZx|cQmCWfo~M6vVC%=XaRQmcj{1}PsW5W8^W@4~$XCSQ(Y+UGK;%Mkk?OLD^W)za{BQkDEfIO<-Uk`Ejh8dwaotwuT7BfJN4jSkw8gVIbu6p&kc;kVIF$B|<-qin3fuc7$WdBZs`gR7c|i09diw(Pf5Y5-J?Z&Se=bb#RzF^c=*#};V*&Ix*9c{Y5h1x7|B)zR|xZ`_u0fg^XW^_{ikFVZp`6W*N>wlF3`{#)q`A6FCJC{4JytFD6zL;e%Rwd~~|M+tD_uCQduEU*#dgRUA+|gMXVDjRP`1xn3S8MN#RJF*2(?kG^G;);B$2U({BUvElwpk!56Llhwa&vADRKg-@hBxw6Z@i1yj8PsC^$z}J$XEC8Y}iw5mk-J}d7evcME=!KgLKl(-=@HcnO)NhJ@NG!x;OLNYf{1H-BIntbkyHuJ^p>XF%6E0NceC0K;o`l%Wm}kOy``NIJ6mgDXd$W;-{Ml#uwg;j>n_!Wte63vo;GR{vTCm9!^#J^>HDkGNj3zC=n_YQnE5e8dQb`M3fSlA}Ujp6q(7Cc{PPw)Zn}O}W&klKXLliTj>X}UyCdpMn05@#J+A!6Go897N|hPeTUg-89T0v_IDSf>KI%5Ku`d^he)%@CxDL@L!KEe-re{TK+n*x!jo&A;>C&V8$vO^d59*@vx^Hto7Jy5m{+hzW$WaXz<+pNGC}0=wb2Ne%d8Yh``nGwgMNn@&zW(!l)V~>?y6vpR;i#jjWl!^wXHuQ5mZ>azO(%*97`IusaIt%YxvTc8aW^Eocaph#ltKxk-e;&7Ozn2f5)z#+f9+LW6{5|2eqPYMBw;9|qBKfb*neKm-FG!iJTbTjKEqv+b<;5;VuuJ#&iiVYFXUF3W->-h9PWB5e(L+0rMKAuAoJ^nWi{%-D`~JDtyrOQ!jLH56LxZ@Vo)q}ipr6kKA`eUQ0`8k~Lys5pj^)CD(c+;cOVOS?v-h#5*X2QnB<+7mGuIVs9JKz2CJ+n}&2;B9rH20I{{Sk8yd2*;A=_kW_d=>Zo>fOKi?bPYu>$GSNZ4m8`*x19<%Hb%h_+I5KlK*Fe`aO4lb0%~SJ(%eyK#HTy+C2W2D-Z6AMk(y}CDjjp@yIoKmIt1{cN}S4OX@S0SNP&9D357&JT+Iji!`pjN=3Ei7u;yF9dW*6o<>LeKMHmU58d!87`3WyQXkQJtw!BK2FzSvT{xH2U$k=NgFrRTxrRPlS8FlJf0c8WJF#4$0GuSsc-H14UlI8_-NuFB7}uaa;e>oe^b?kkqJZu2g6wP7$XA2Q51wZ5QzvK1=tCR*|+FnAJRv=#y{qHVrV}R?UMw{2mFy8lERp!(iTjpe*A$>2_13uAgYj?iP0_zi&vyTO#ephbA?!0GgxLBR^ZihPwZPj80694cHWP&pxNhkP}1Mr(6R2@NW5bB*VFBNr_k4RaGSW5C;EUI%{(piY0LD)V*^6Ku>)XEyCYov70;2w}l|I;-?Z=D+njC+9`-++)L5m3^PLNFWCi^CZ^k=L6@sYxw3Ha?A5=e8#WW6#y|uT0Q}FQ8|(Gxw{KtO!@iQWKtY(QGol#4{;PA`s0cVqkcZ2v+>4sD%3^A*%^%@N10u5`jwMMo1CxhMdGof>8(<-z<|VzZw9MfQGeOGru3~b6Hcc#Cgdm~N3BsdvXMK&0(*&XjyGKX#Rofe6Q&(jbWLMJ%A)0!Nm>{mTzf;$db(LYv>Ur^_4h_DYF_h2%SM;;{#no+C3+h5<#W62vUe52-=!OUGm}X9T2<@sdPPt`%HuI#^h;76yTVK7!XHIYp7r;Gwl;E9(D2qIpDQ%zj@h=XAPS<7&8=@J{`;u5LGS&M$rS?U^%KK(x!b!1s?II&~|4Z;N5duwg`RTAS)&Y>a!E=0Ng~%@f%9wV(68+T1Cmd;JsYV?Xqd-Q}DM+)oc&Tjqs)^=;_w*%_R3E0GucQVeW_3ZeY*Nr;S$NnkjeVaFZ)vv-=$TNeV@2-n^&VWD;D65e2#)-b$PaZMh>ir)I`?n$wc)I3`>esPg<@ze!_Njd4PF)Xc@lg-Ee0ZDn$NvKeUmt^&GlqK({cIS@lM<~iQnh6gZUt%|47hOhGb6^vz1q;0Av(pA80=&)m?IlK7YKb5V!?1Ob0Haoy2t_K!Nh%RVGdjXy*ZGwGU_Aia?%oP*Jr(JI9<>8$GR{0#&v5T%BMfC|<367E`4Vm3p?q+ZdA@QLDK4C0mR0jXs{nR*Uff!&g?6&$hBgl@DTIKB=Xo|QKs*03a*WwaDbWA+$F;LUXs66+h5BE5Mew9!=d&B~_&L|SJ2EzQh6)jneHBj}K>N8v_G-4amLZ5449TXM^Z}~?LWK9EO+N826(?%CV77V_0C&$67R~GApbY!&b+$JDSc;fjOz~Pd~j(JdwY>o??BYib#V6I`&*6Tf`ie1y;DEFfk+`7%{`S`@_YzdG<2^>-b=FI)?xf%vGoz~^GLpNKoQH`BrKL&7};f3!d2=R;x0WI&Td$^CvaQXhsG4U1C;m~evEo&9x1_LP1)<;eY!q5|-0-Q_8$i+n}BvyAHty$}u%3C2>$S26*APW3iZK;0d-SPf#HRc>lh?Rka&{KJ3FVf~V|@7bsnKAk7o}y7lF}RSdY&vOLJ)3C0JBe7iOBOz_;rQ+Ie4^3|F6kN1Mtv7qsl)MeKU%@}Naa9j5e!qO5Y2qGA|i+4*WO#r1{x(oW5|T>#$#jdwdQLB4vIlUyZJSvc8Gcy|}_$-@cbT%~sukk6gX^bbP58mbBFYEY%ZJ+Cia4Qr9Fu9$w}Ju=%;Axh`c1m^I6M{^SlS=6ulc&Kz&4E|JC~%EJzn$^=4`5KfP0z$P*H^XaCoCLjClVE*#r7vMIe7M!PSMXnjHZ2|juGr~r=n3cZ+MAkWBE2E>Z)He0t=3WXc;J#U9?t}W$o4+rdd~tnn#j$H=IIy|!zt5emjpf`=TtwAURT;&03R<`ETUVHc*#HCwe4vkoY&)(%)E*^5qI|Qrhs^;llt;zQa-%J@I@a*Gu%eRuS43Slh4cOqINsE`m6YFpk2_KAD<1u0LqeoFLVj%qJ}KZ1tA&*JdD?cbwf`yUj7yTa+xl`?o=t9{Hn#~xDPa6|5=l@Cz=U45)Zq^}5~9D)qkLC9Ce9ueBnDm2KcxVNas4(*JW&q+TUM~C=YqmO1zXlMLW=I!T^4AA@BRl7R|d4Q;=o94`fbvO8bYJVm5mE!7bIkk-iM}NGs2tJMbrtamO%^kXINc^ewayMyiOT6zZo5KQkKi6Z3%@fHRuA7B8{Z>;_u+E4gt&nPhAwr&Td)E4az@iK~)pI}0wn8uUtU{Zh1+Czc^Z7j$*I(#($5UKxpeC(}@Ed@a2@olpw&2yah!hnmj|2`0UmS?MscINMreiM{JnVchBAxz@Hr3bw0vx*>CE|^bAgp`NB_VnzSYAQt2d3WlqA?3OGt-tTbLx)qG7nUb!uAkQVxLN)yIsCBLUew(K?I-$Kw0~qw_NAw3q5V$b{-GL0Oqg+iM^_|Al^$9we)jyp{0>(?eoyr02_!Rd$2%i17c1)hHzSD;x8{A1~d)lKmFyiN5Ricgn-?!@7`tGAJ_{tU3}@{}n+%w_F4iGHd}0j?7UYm2~&81$uxe6npB51eOYyeJ;ZeUi{6DYk#0@FrCHtI^u-qZ$B!@o}#OsS0c~Yf(Y|!koz2;kudii;p!A!Mc2=Q#IoN*rcidUzxbeU%fToyNbu=*@M*LyX$qwd-iAmaJvqqg>Ol^UHOeClIOBh;Hs~+vj}@NZp5MoWWize7J{s>!#2r2kvp`nN^VpfI=)bC_4GdfmEe5Mtkr0d7m}k|WU8!8ZwFK1GU+yT7!}`IsGiLVm>QN^1G~RckPUJ;AF(?87@n6feexokTPH;7Lrh+&TNK!|R3N`Nj;K!zc#V`KDi%5C$^6x}z+~zZ&aZW*|=py8(?`J#;x_cPV64D{@?gQ$CKe4Tz3FDDB_Up{TIN%)ZCEjL@EGYI|wR(0M`mcyS@b;hC(3Q0Q*YW26U*Fd#QUaS^^}ceKC)MkDHP+V~Q^2EFMOu0#ULV@3ab>4|5%_y_Q{K3szH53`H1`22SeiZ`jxI;tM^bk;E1d=_G|jij$sk9)%y>C8$jbnm4oO-`7V6G3_FIiUV}R`Lg4c3pXb-Uu7SoxNdBwArAkUPWZ4HsjVZoJj)tFut|tu)=F7T$CTVMNZ^={0SEp9MiAX+HQ(GK-5i39AtxjZ7PIDL-7{;OWFvLkc`iSad+wgTz-uzmKS^6+yt2n=U5Y`1xo?SYOuErox^bqOpCX{Hv`;oq2lgX+Xqj?L5)Wr2gx9%tAVhe09ovybtXZbnctA?J{Sdtq}`TI!5Z>{%MK$wVh0$``_JAoR2(UD{|P-c?ApRN+_oc&&Pf9fc2l#Y#}zh96fI(QjGiN=o{}^x4&!%UGZCNFc|m86;efiy>uy)b-`Odp`FJA9vDc-6+!r*j8ASVY2Hxy(oI@2RFJz95K5k(ILUMCXi!Zla-C(3b}FopXnKE~4k6WDPjwHI{6c1T3{o5zFd(SNrdi{Q8Bs%?_<&`w?HUxP;6oO6BG^tne!eNcN&PR|USLxXWXdChWuwDYG7?|V5_I@I%qS)W^rd_tr>tkq&b<&L{P2QHxfp)CixL^Mw?gaoX3qYba;Z=6sSke6MBZWWZwiEpsQAqx2ekjH_&f(w0R|BH!hZA7{(&EZSDUE}=y+5wX-=B&9Qf;bl7uxAY@4dMeJS`{ZI_+bN6%(~#iFljpCd?lR^Ry&ovK-oKCyZ3k|5+Od9J^)4xD}GN9DJY!}-WjMBmS|yQ%;Ee*|*W-e%`@tHWq8ofynEh#VDTG1qNxA057MZQol~gB&%jgPVWw76Srb>-e>dBS(F>mhhmE^L<@?m=TarfxHyYf2VOC=X|GFEBvVZE%p($^B?z8EM|jhvGzLs&DclO>)f38Z$1=5E`QthhkbTaI+2&)pj-+EV%C1jsQKpy>(ssQxbJg~brIC~DxTnfLYh0nj#WM1se`=%$T>tE#Sbqk==&B-Kws4OJ_G16zgUg4@%le=jyG*cV?yM;uw4UtQIBV6Jlq(=0#k)EOR~BD@l~fTQ8%uc$%dPS{kK9EqW`L?&}N>`qhgT%qwwh%3*&=2rA~L56D5$dQtVNF|D`FN$mf{jQ3P;t?0e=S%6Wtqh3X~ez2~L0YqQhR!`)v@{#Gof)Pw`TzcwU>rUjWBtFBTbEjBviD`D{TsZo#_HMr0n;FOkNmj78xhC>eLpURUcVaQfK6J7DP=fv|{lC16gzlEWEN9tc)(c5>c^(nk-@S`KP$ctoMl!BbKU0I|>q7;iOyrIra@51s%bjOmqk&+CY27n>)cXdtC8FQbC;JsJNqybF$G-A5$zwo6*l~p`R>)T?dDkf{@Mc10vF4~6KPk^@hBbxHiUspO?;iWphdR;E|HL*n`24jF9ppxy;k+hwM68Noe7|e8^giS(UYWs93*1U3^Sj(eFh2Oq-1yOXuOcYAda-g#Ags}@KMC2_dIty8dZj5M#1i1VFPV8PqB=@qTb$TMq>>^iY{E*n_FQryc){;TxM7p}PQ7ek4-$j_6Ee>~8s>o6LcC_bkI`a8m^8hw(d^zsbF^(C%Flk+8`N&Q8M`Se@tsL;D=IP@D8^{!KaXDyG>Cg)d9w?TV~*FAIHnMj8dUf*tPU4h&}%;m}TWPta;>|Q5we!I^W&&U-_Ao4N>){^=jNSt}9$vF>B_T@W6;ug+aDOEHMb-z4;EUJk;<8w@^W8(09^)-kXx^$wU$zzP+|KJEeZh8}?YNBfJl4kog9vw_Idv`fbQohMPv{p9LmAmUxCNqwRU_1!M0TNZ)L(%Ff3zoPv~u_10&YpDO#H9REsmvHokZUq|5m%nnTx(w~VXORY*HRv$hIap*v>fcV}Nf)hTKvarZd+T4c|K-ZuYo^Z`P#3u(?BZUue_uSkmT{VM{`F3%x<{IysPC0(v~ev9I)!xq3K*jOL_dMSpDd7WPc4Zd=1=}lC+1u5-sA8yG1pO%#34z2wsuBEz6QZ8c_kyonJz{J?bwVJe2YkZJc=HQxN*}UbhxeAUIzK?CT+BBPAbijZHU3R?TVm=t}Bj)gJ2&7NWH{Ym$@xBa^X4RvdzteoNorWIr=r2+V4W_-?zyv>=I|npLebgzs_gCLt!h&*@sM*gh?w`_gR)6t$xP%QA8WKvXN3ExH*<1sWJvzle^#3zlXEmi)?cZ4v?ok4xi#8pUci%guGbbFcc$Jre#r=8y69ND3+o_wHzEyCsF%{Hzeks^LioB$J_{$af{j|w>3YX~UFCy~2y<_PxM_22*zZ-JSy}y<$-O~&>rlYTwYlB=Q9~N1zW5|Tv-b)j7!+odp$v)Ve_b~DIsx6DU$PtM^2YEK!rr9ytj8R{*f7*GzjU0}88r$^N9M@-m{ZTULS^{#n8q`EiA=kNZ{*Y`LrNGQF-gV{+a^r?ycC_hMRABz>z8s&9Ty*V+gTixX8dxP(Hm|lvo#>~>lg9aeKmTDys-aHAr;Y?L;CE-IL&(3p7~+gOsMN)C7!&EIuXZo7GX{HjWMK<`jJZQ?w00ePsZPAW5`|KoHAz`&Mbz#WkvUmD*pMkI(3QpXF{?ipf8i4_5A|!m1A$qrfSntIK=svJBIn~*`hM_DF>-={N?ot=Q{L{wcOI}cz1*bhu-Ke)&oa!-IVFT_NtP*-s`cn6~Z9&I;7C3;8n}+E|lyD+lwDbBKOtHI3}aKK$Bs|2U^pcb6WcaA!yH)RqRyLJhkbNppF)O)XVyXoIvymAGur%R=sDP=ENdjO+WH5GyG}^_=~UJ?C*kn)%7yvc8fI?&gL$&EWL^LIDVq_@7zj*kivS(y`5-}9p_+r-Ifk{Pkvr0=0kgA9L}DXGiJc#e_K%}`adgvVSv4d){s&I+PO1T(9t!Y2^&;&-G7kg03IbAPM$2N{eD8sjnoHK{J2sD_ZIeK-`d^vxbHtJeEv#XwHVTOY+rnjlpjuTi!ZSp4fCE`GO7G*Z*F7BntQUX%D`CtSu~tnwl!=(Wrm>c&F}1iFzFuZ7L9b7uF`Coohrg=Jt!zfDwL@<>HBU^8WccWFn`*TMa!-xqIDWL%qa%g`t_q9~NVJ4)AM#uD7qy5A@`%gtIXwGuiFXYxN?d@OMLxY~0wbMnK(0(GH=fE%efB(PmpZza%*A`D}X*t9Bo%4_Ts41iU9BeLqFpmk`0pUwu_nB+T#^HE;E@H01At5#_Kb!Sl=Mp|wZ)M8s6%W}^>y+iCaT)n)jpGJW*JvvEip>2}ZH;|61umO6cT;FE&~V|wPJQg#IdI5G_g5eNzkF{q%#R}KZ%Yaoph*lQ7(~Al5kJuNVZxyNXl|bn@>09d$pi2AvnK1v#`1Pf>83Vn5vjIpFjQP(ZSiH>lx}ITb-2R67^YV(-T&Br`~UP#-9CBMnLFqu&}C@1DamyA)b*=}q<-)JSqhdaeF`)DZKtj$`sc36p#l$|$@PU@$Sq~Es+-|H_uy{LWsMv?P^}6E6e}2+Iy*=o;kQT-tPbXF!dz8-rQwNiq$#m40UzcucILd@Y*SQaDa6%qiWOA#XtUeZ1ijCUlrBS-CZ(S&oXNs@>P|-sP6PrrLa;b>62J0^3})utasccRCpDy{rK`$Tt_WhN3V|ad*b6#>iL1T$AwGB|w}9&}2Jaiv{U|Y+N`p?}!p4+(QXdI}Ez-VE>2Oi~PSOKgwC98E0m~~F7{GKjKlF|t`6}wBT7IS$6XKL^*S=~+{i9p+mgWg2SiJT%e9?rQGu!|8oD;8DK-6P7%s_5Q*zKx$vyu(YeBXlWJdg+OGJcPRl@x=&#o-bzN#rYvPXGBorJVPe;(JpnH}VzX$N!X01YXyrNv-X!kg=6vuPt_(tPT@hvtS|dd}fY-{Ct?EsuHE_`@?quLnv&4h{amuD=CftYVBJRkSRts$D(7WyS{GVr#Q%_7|250+_jeUG5R{bSs7YJ<>D;@qKsiUw;cSFJn&XlH)@uQ*x|9f!`u`myx$sdd1EXoKmV_`<~PoJY_`oMFr0_>2fy$i{j``3M4zYV2k2KJ>H!qLv!V05wYuysQlBV;pG6Y2#n3J&aG8HU?&HG~jVIUnQGxz>QU6F6+F!Nz^emZuG%(9MArX5A?eEV~e@0S(f;B5(L37@GvT|9sm;z%wBJTE=k|s9ED$}ls`9ZA+J9d6L9*0S7MO1}Y4Z3+s=w2ww!OH*hMp*0QH5T7u1oqFk(RrP|C^ieJri~L9aXaSRN#H&)SfLv;;R$y-q>r>Ac^%-XvHGrs~K`5{0g#kAmUDYR*>@E_dUz$6z06I{;*C(+oAm-RX#tRlNs%EJMeW$Ju+}f1?e0B!JUfMUExftsT8Pn!=ueg^Dm)~rpn28;ky8dgM@H=WrJ~)YWTPKk6+ll$~Hxr9M@HLcM|HU{X(O>Sc5Cb*|%jiFB{u~%Ay{NUdaK3(N~K5%G{eaSUsO8=0mFUI1bLg0eVTLVgX{bRYZs85y**nGG5`vnQ~=j>CsmXg`dgbU%U0CfiXbK(?EZE;%22CkmH#X-k#f7gh*HruQ=5;VLvADw#={R5R3I?K#v#KCcaV{zbw@8=(7$4gcoPl5Vs5_o@9?@BawR$^Ne%>L6*~*Sf)PEKmS5_w|p63F3Z7l=-V$aL#LNxmV35s1x%^7hPif=l>bTbtIHjpO*@<;H+y^jLl2D@3%%dft~uC-}%E;x9{J^{km#~&+p}bBPZ*rPxj#7?;cUvJUjI`AUH+En=}{I-uZ-HbP|kqmTXBL#`o0;A2luU!gMI9dg5H=gZk;OtvS@PY;dt(*y<;MI^mD{rdR;G__z0-Z@~AV@C<%)+6gLD`~2jRYC_#@P0$UkLO}qWRg+{W^M2~*wi$KCWBTHdk#wLQH8H+qiTcLR;wo2rv*B=gvx(sz)T`q94TaE=XU{CfXU#{u6&IbjUe{P%!zvkp?o@&MS9^ogwq`-!k&Yr5zn4~;go@j>dk7zIq-Wc^#Rj5C@C3i4&J{1x?D_hq8L3>7BSVpc!42Ya3eH+8)otZE

      y&OmWvojL!kh9WzRb;P4!;5VvKhpE_g`#NwP&_}`98?7xloy~}@ornfy4Ce%dbxV6yE)yZ5B2E$lD^i!u%@VSWmz4x;5P<`TxQkqD?luiq5K3r*$1XS0sN3L0@S5`LVGUO9D_zcK!t-Y3gt$c16=n@zGGpgJu+7%A6|Ja`wWZ03@fQGhN=LOs7wVguD}$cxC<5w{4v(V+s5>*~*XUZ)!O8NA`)r+mdZ(^VLuYB>G$wepoO#qsM>}h8TQrMt&LdyLIs;uu&-EzeetP?}1d!eNa^=G5lqr2OelU>yU%!GR%GCOUCFwt(S*AmJsNtL;xgz}B^7f?L@MeLlHg{P@1nSYgf=6^>5eR(oYWOPtIE@YeJpq-#-8QfA@oI)Qt>Nwslw1AWG?nverh_m*=Fn-O6OZ(9>G`=2Eni;LmLpObB>jaQ6KIe6HL63&bYeu7UaR-ABDSxDMAk`}-{}sj&It#nmJ0s8jme6LE!s6ImcOZ9#3ENaS0t&dCSvSGu9^Eivz_e09TRJtzW(^iS%-RJ?w!mWZ?UWjYM<)$g4vjq67ZoYqxUXTl3Z{fF;nW8M@ocP7AzHQCRc|M|ZAqF?fSz&vfN(%Wmo5z1tXnTYn&5ovBS(`T2V?c)jjTc|L}GMdVewsb_%5uWSBNf~0fwLXp*`L)oAaXK1f!hy26$nsqvLG#_picQMY9{22RA+O8PvDuQn*Dl)NJs4Mz+9<)|r01-dQEJZzIi`KAUIuqt|4q&E-@V>x)UWP-J62+n0lrOcw^q}UXNGA0cT;BPz~xYf?;~4Lf4FGi+tGyuV7OB2>=#nsMgD5b7b#p+7~OgDh2%`sTZEYRo~>uVn&Iv4o0cL+5%ZN-QJB!bT7F`y73y*vu;_ou0%G3Ov`Esq)%9)GpItGq@NR4{dlqsF5s!R!B>{%-sc96G=5Y+3jCs4WIt5f>x=s#Cq5do{!a_SD19&5N#plbQ{&g+yBNeS2u;v`Nu8N_azVPhDBg+b);P57ei+rdzo{l^1{k;gHdAnv=Px;|Hb=^2-Zd}0tnOTR-#_pqjSLgY4kys`y_%rADLsGtqr9#8R-J2{}z_TSi+>})#X?1as{HNbo+Y>n?$27LWkSht|T1qMmU!%TJuP!o)_d3YU`|47xg`A^wjIYeuH51e#qWUw=q2BZ9k$eU{2RMH=YGyRlzqqeovqrK2daS&HxbjhduzA%{`iY{+Il_7#sH-g&?j1fy2Zr~?4NCJ+C(bVq7czl3-|tF8J4>4u@h{O}fgknUpsXzFM8BQ<9SK16rxc|jza=r9wQD)&B8HW7Gn*?S3EdWe{~?hUGx?ryS7G{nOAbjlA^!!rQIK1q@Fw>|1`zIW3O8OabjDYyt%C_0wjR3u${U}H@L%<{Cc;eL!vlZf@xH_yl$_oaSfIhPUsx2mWk@pWi|K>($vLXCt{}H;Q2ku}*eYwX?)ybI>T|f2E?O?m1)~1URRnqF6H|q!=TAO7%#G9AF&A}S>-Wu?jTAVd<>VI8f$Qjf@);>PLj%#0af`gTRyp)ULTayow)1sYSAr?I_J-*QrqK7*GA8g=WpDN3V0Ul4b37r21qc)O~Cp@IQumGEKWEbXs^S4ADQtQ38Ueu0OP@ZQH!^47hf98MW*UX)az!Vf}1A&Ux?h?_XVJnAcPjy)J&nnS9vizvflUGmLW)b1m~eP=KnoYww-wnD0c)#lAh04tpLL4)z^Hj^a13On?2J0q;j@m(SjS{T6C(&bO)-Vu5arl*YH{kSRNfIp!0^F;L~}&_wx-e3j#r-Enp}0j_o$J&7mHgJYk0yiagZDiC=M%SVt~DEoAlOT}}(_vK~Q%rfLI?i+(WHJs<&B6nzH-F%E62^lOrVoJ$}y+k654f5F6_ETkZHWb0F8?vgK@=%X6dfG4NPluVkl__JjxXwHyHtUis6Evo)t*`Y%KO5KI*cHKMEFk8t1e4|nud4cVm2ou&Hh1~Yr;+N3B=x!6_g5!?BCBb~(He{+T)FAOZ}KGt)_&14T;7e`(&b<%z!#nYo31~OnJ<7mHoR?mJI?~n`FEazLzgr1&-9%R&4aJcrKGC5eD~*_Ek%vPRy4nS4;(oAHw0%6y&QWi{QQI3Nv8$yPV`$QvVsD!Dp=kYjVJ0^EP?gSI9YVuFSK8!;=b)FOA)=qAuh2affYY(PUrWVN$=KXqzKq^`Gf*SYhzwE)Uez#||a0+Vfw2X+aq38<%~o8a&Mc9zUNkODZXEBw%|HPe?3;rp20^Sb>~#;&GjO3@Z_S2?lhFu0oxN>&4Zk!tFh0e=Z=+i?8S|Fz)`60TvhA=iE?4ojCu@cgz8M@e5ZI#Zf2v@Aq@|BO-p)P3k8jl2dVyo?Zm29jlGa$x7m#Kvr#AV@V{(k!sBc5#|~e_b$qrqf*RRv}unLcZx7kN_T={?;;_*KCadi1Ln9PHgK>i`-GRWOYgBp)K@5C*rH!3-aecF);t&0_Il(?eKd0j-=r{zHFN7W~CeyFE(RFCfwD*&q5XikI^>U-y|t@jNmf+DWBt{2oub=h$OF5hG5FzT_!_(I=5J3Dnt*2;=Lmu5nh?yO}d2ISgufQUaF--r76hnNK}oaZItU%$*y53@MCdb?2(j2-6tCN`g>_e@ikRi{Jo#t(`8WoYL|%bAqEZU%50C1~cEqE7U)IxxdIw{zn+|50Npw>;>Ve&e~GHI_&mJ`2IKrFmM2k9*1Gw&zM2N1=|_j3h@vk3d%~eKl>x;bReOJ@k^F%I*_SWTnQ$<`&H0Ha>I(>mMd>xzA@+CUXBXs<$^0!=Dn!s4-mL8)`NudfAaRKdxSGG?&4x|LIm>L+$1WsifqYRoQ|=Opf0T}{)-lP2x$Dm8_!gl~^yR6WT>v*lc|JeRLj91)kC5gn3W(g(D(iPeJ&QTw+hjol2K_{Vsxaz?X-jRETQY!{zrh`cb_Vk$YhUG@BUmflvc~xFxdsF(SHG4?p6qM=lovVV_Wmm0?(sCp^Je@>@J0Py_UbPM*%?r`%L%gtMWpoug9CNbLT-}selJ8w?bhQ@0`8WenX32EuQFMm+?NJL-oB{}}6SoH0PczSfBbKE?ucMKFhS}G^~QfV;x_qQ4SY0=N_KGx*?o}=`u>Mjl8ea#P@HTzS+guK{h)6E}|50x%1d>!Ev2Z_#+Avf3>lm{h`6-&OjwU1LV3d@0=q>>lyI%$Tr(^*YLizuh(YsextO;g{Ivd^alkdmde*M5wiUT6eADuCEB(^oR_Tp>dSU4AI)2X3PU_V>6H+UJu-@jTJ6t4A6TfAkqDKdl*6@u+fV}ka(#K<)Mi@}!nep8&A9bSs+XVS8f|B-@KIH7bDLIbou4$p}Ve#5`Ix`LK`nTU`Z9tB)Y?N{I5`?zH~;F48pwV9x+QFC>aAGwH_$L9Ms2VSvCDh~*uUa^*8@qJ;zB>z;5ll)E*T8>%ki=bvncaPa~)NchU8(fv4gWZg0Vg*siS45rs%vTJUZ?h<%b2DD=uxdV|u8;X&Uh72Wl>V1@krFX?`O;@ms}wHe6XN_^vN;7JVpXEuOi*8b^oW~IKswxiv*(sn80tiOu+Iuv5Ee5oRZij`F0GON43S(&91{%KS&Mq=NNma$4qu78-Tip{HtGVGPAN+X7XfX>IPL2t)N2Z7YT7r@Ka^dDxBufP&gZ}oJ)y&9LW5T0muMg4D}9|ayp{gffbcVwOOX6L7semI@lFNBeM<*c`l7ydb&3mcWk9B3>5$Vy)Ng9uvHumC1;jqNmkaqP=`_1e#~>HP^REONi=*CRaA@Uf&i6~~3kia#Z=pGS8*ih)rNKST3hlT)UzyCl4j&q5&(z*~{?b3aQU{dDotnt0l!rg-ToxETTcVFh#fA7j?q#sjS3+jdeAbugpQdBK%Zyl$k*EmsN|v=Xzl*=8-Wc1tvyLbedft`QL7Tyes?kI!t7@=8gBG&Yd(<_FUUZgFq-so*@^VDB9`o6O#|;pT=!kt4z|DSOz+#Q-Jf@Fw)f_^#gC%ktOU$gJ)~($1lA@UHfC6){0=pWM9gzU&vPmfG4%E3twx&Z_J{%V4uv#z!^`WTP;nlAwK-ATlj-&sI=u@%f1`YJB!%0pPbXQdpGJt|F?i26u9hGk(;1~`hI%fCXZJ%*u*&q87rbbW-7C61)Tv;2WuYaX`x=GyGVdp#e^thcR9lysP8*HD`-h#0z5oA^j9PkIi!6==hOCU$v_;BbxHZ0?aH>w$K=z&Bt!W$H3D^FPS{vWCJ=r4mj$A}X1?$3O$|Ad=N*%ysHeO8xZM1b4{f6ByWZ?TeMMnF&Z*xN_#RJLJg$Zu^}YD_UBeeN_;91wkvSjr4=)ey3&~?Z<)tO-_`hI2suZsjRlJ-DVxGrzvPgNVMBf{gLy6#&Tl{AuX@33OX%~0AI*{C%7IC8NP~+#w%dX}nGoiFRMa0@2b;=7+zIEstTnRoQ`N$4Ags20_vq*({Iiu%JiKw3)pC+{7b2<=xeRQ9o?icM{C+V35w_bTQ%>In}%k$O~{Ht;&>#3_oP+u=5xor9L0tk5L@;s#n^^cVI2aTUoV9VZb0u4LAK!w|B3T`r*icH~m7f>Wa8d!{yeA4p$~{uu_V*0Xa6!@XPKO=aax^k%HojqsSpyayNhH*`>jZ&wnM;ZlK;IDU;}8n*rbBz;we1>K{%S$(lXN0-_#z%TnZ=XucaIulDBx+fS0ORulCspF6W2^A!Nm|58{9^^AKAm&;>_=D?zmkX$Nkfp)Ngv+DyH!!cv$-KqzhdKiYjw>Pg1N$@16pgNB!t`GTX|cn|pAYZl9E@NjLup9vvQjPNkjXq$kLy6pCwv=@@yG0Hu?O?(Ga&fWVgvCeyq@Uy`N&P+?hLQq7HYl7BDKA;|kT9V$gOU#ieWJ0)khSnn7UrVB*cB$%TUlDHu}+BQ@ViUi-wZ0NFX>@^f_K{TKxVS@1GbL>aMa{-?C>)C;a{*-SJ>petlPDGu9glP)^FlY`+Gpj@4OqEOeOC?L`^yXW1sh&kcdC`46yTt0MlrGDgOo}2FA$*Joy{_@lm~1|@zyo!{|JBiu2*O0;$la*Bq{)5PX-|SPJTVf6?x?>!lyYHaN(yl3_K-|I>co83C(@kvI(Y9pwJzFKTA+H?envCvs34u7*7SaHub?gtnz<|z@~pllQgy=JYu&(t8VX1nXmYW9qQydKZ9OKj0kNPLexO7Wn%vvjkzEpl)7{s(ggPA7uliYqEhGeYopqS!maI+X+xDl_~ai=j^RhZkRy0z}?%TN(0puj&)^KvpWam>91sb48tJ-!kiV0k6q8&R`32mznz~9)8CV5UU;D;u!QVzpGPsKylsjg&V@)sp0A6xkVT+9_|q3-f<-oINM>z=}Y*zNiE^=GdddsJjK*QZ)}l!h`h6R2FE_@x@Y2Mihw9!Z!;M!(>VJ;oxkh78mbBXbR0!s+zUond{$#5c#Z_Ul{_uV@qhXX(hh9;1X?jQ9IhY@#c~?@N)c5jMgIYt~WiTy^G!EiHekSq`m8V5Pq$xA&n+bBS+FoOecNH-Z{;KD%Q!k!Ji2Se$*?3@f8Na|n8C+MuWJ`qm7R9WxHM$RwT?s-vaF6ViB1sxu(!t)5x|4@mV49DUQc$AU)-gmA#w53Tj75L6?x+dR&e%*LK3Qhlh5Uj2LnDz7*))RdkFZd?ndvS8^r_~zd>wEuDk_p9LziuR%msFoGN*Bx>0)_yt*xOZAreTqSDME{?uhuJ_bc&QkA1G%+lPsj~EjsO+c;75j<)PMHudq#8pI%9zQ^a82Xynl%}!#^Y3dh5KUw{1)Sf&)1vW?Zr*>>cKPd^Ybgk%5g^^1;RV7kz9ra|iOGzfDgXd2lQjt9J@lG;#*}6Ov?EEi?RxGGv$DO@hzohNIkbkOT4F>RDn6_!kKN<|{`I_uD`9o!OZNSs%yE!@1B;L@yo`zWq2Ih+|CC3+N|*Ezf;bRnG+R{==$Vn~+b$@)dh@FJwV}ObAJm7y0BlOkTQCk`4PM0{8xyMm~Gxd-#F}W7%_s^ukeBU$oUqOzeth*E9ESK@R$?jf-_w%J5P!%#45Bj<|uz7Dtzsu*8QfUe}R1BUw8hic^5!K1oAlYuy&@8QAwV+%sU)tc|7fy;{B8^RCaeKXyu4IYXsGuiXg4OgH&V@xtXYIQbyp7ObcXis#J&fM=+V3Xu-3Ijp>C(xKFsewzW#2p`Irn`)WZ*wpQFAa&X2w)ra^Y?$pdP4QD0eXtAC#NIsi0`&*9s`%_V0v1E(T^V}@(fA`>sK``p87uyZ`-t5eQr;URmU(-=vJvr&WY5(&si@ul1?K`c>08;6M3!!K)E`?{6Ap)YfEs3H*la6AMjHU!DB)$aT3&98{ib4}2wu`byn?rouF8P#_kAlRKA^q|wiA>85tap4BzSIBS|U#e56Q-|=3)Dt59_gw$%}VL2j{Zy2g;A5e}1g>3G)aH1D@Mz;qkl}C(k+j8jlr>hU-JT?|C@-18}{zDqj>G4_B3zymlPNxJT5@ju<4t*Q>is4s-v<=e@QrJ@24LMG9DJHIEB8q5m8bNXYEyP6O`)->5UZm>*X~)cy5q$$;X{N5-c8$S3AbsLIZeEZ|K%wP?#%)KOA$Lk>4)_tvR`Ne=g7;gry%liad$=sjZ@yU|S^b%!<31M{3*G>c>5d1^p-7tINxfgY&f;GpC~yV6U9N%JeSG7a~p8vzJdMf%WIicvV%*3x>JFf0Q?*0?`-thZpi8=9xZINQarV&nQV>Fh4$Y_MRyl&j1T1w@o(%`EVaP@@g_V3v^ZEHw;`vKE!!P{V&$%c$lmC@-q5Wqtsg01jvQp!KKn}w>bKkbr!cj42p)L6=64TZ=(LQuYK!mA*U7(Cs~f0*p3{Y=GQh=MkT_VpZRw$D`P&buPXJdxtZM>Bz_@45w{pA?;FHn`W41wkUq#RU|QPnN_dEwjZr>^_{+GZ<$EB=>1uSILDdrOV%6n?yduyLkkxSlbkGxbRjl{pq$`$T=r-??@l|iRbH>X9B&xutp^`cG&1Y-SS>Lf^mNJ3(Jd8eIu6VTmRvIf1j9p_iOC`#zzMBQKy|wshB#K1ipr>Peeug?CQ+z((hBjb5Hy$&sq3$esb+Pu2Y@?J^Cym+K&24UuwQ$vrsk!OUEzS_5t-(+?KT$T9)R*?R%kr&I_Wxa@b_4{QEHp+GQg4Xy~B6x~X!u$C5#2zqkEkiTcV*aM`ffTYs>(D|~9z5cvnmek_N%??x`_JfM#`bA9JeGO=E$wG#JU#ICq$$m72;{?*T#5JU+s2F+@I){!9Fio#L+MG^*$fdx7As2|KRN?liyf(V*ha?2VA!1K88NDo6TxyT;o9kYt6%}d^qY<{`V!t;(f^QN?>K0w>bWM*Be}gLF~>QEWQcLk3)1vPyG*x-Z||D(aI}l3qWe3>F{1xf{?$l0xaZ`-{bY{0!*>jy9VW+vqiMU0K{MvHHM6$<;QyKg@m+I`j@F_c5L&!0Ye`Eg1bnQvwTa}Yw;1_*B!HZ|98~n3|JeI+d1A=w<%Pp0R%4n9%p5pYu>(DMXH37}=Bqb`N$hJSmPmrTDp1SJvjj(i_`5);~p_#GIk}#bo$9-5ULjWBy}V#E&xSo=ZT?E!3*Td_lKV9BOR444!p+51R2}JnSUb!xlv`zR4D*FN>x0tmlEB0(WWz0v_p{EnJlTHrDbPBn{^r0m<^{2voO~Ckn(kTJp7R_8)=Y=C$IM}OM)H-DbsWBtD2&GH^r9COC~)%N(EK9$IxODmv>`l|k!f{Tr9GHi8UA>1{A-@9AF=QDTLr$TvP#2ZR8a^O!1QH<+N1N(NJ*)n&K!@DNt!|-z%U~@MkT`LVac$c);&Yj5w;{BghA4ebl)iwS%9kU@JtA}T$J^IONmf$mI=~3>_i{yTAA)k@WuECj4S@Ei~?Pq!O|2r?>)dv!|W|mI%T|+)DQ%4*%{sh6R7kzS9G93Te7wqi&?zb-zi1*?lTG$ueb*xqO;mHK3l^A*^FJtx3e#<3dQjN9VW)l~5*Q4F1D|zhGlXUPdFtW8v!~UYf%$cGgQWj|UDOzjmVZE#D@2|=ee{#T!c;F1E$7;E`dB6T9!SR@!Z;3wmIf*_Y>t2#!qm-;r6$#G`nX|tH2DQlvD=r8!=8@_++mpSVGE;Rw}bS17V4MrXHO3rGb3Hd-pIs9mWEc<<1JD{<)Y@8FG<0-<%Wqx!4)|bUp2JVV^5Dq&PV&%xZlGK1!N%3G3Kr2=yy7J+(Xov0__U9fl}sZZz@^s*t;ea>c{t%c{l%8A9$~w^zhjjcV#r#>&%U?{)2rUi2b$*Pa@>bzcCn~g8BW}5yiPu=_x?;#V^@_=Yy$9X1~W6>9FkZ>YU6QsH2E?K5rolmWUK)EyxS~XHU81yi$m@PKkG>>2Hw#DffDZA!ib>!jr<70owhU+x9%aNQR_-sbsBAeD9EwbJk2&lLBU9FNV&Aqn-Un_C@$xF#2?N+JAAZR@ng;%=v$A|VU*nIS8@vTzQDEh>AUo@Aftxs$ejk%QIo$9q-nV1fbZBEp;C9$QT+=J>{8YwfdkPP&KfxvZ9iW+ew56fALM)rbyUitj+rOo6d?BB7PZLV!SeRs;kU*Ch)&lWGUfY(s8DKj&jda$v2<15rmB>L@Q)`v5ap5?p*zW5@ZdL(%*#ipSBd(qs%;De89H6xz>je<`!3(b$)gD%S)6^l*B~v&%!=_9sL$H6Y&ZjmIf_fJVtyq0K3(o%?F(4{Lv0K4A^J#PByGnm%?Sq!oNXE)@%q>zoG4Ip%Au`lwlXq`ef%cC6g*4Bm`{&op2}YGBMG?Pu0Nz=jvO?uz9By_VC`pF`y|jqeYM#mc_PRw9m0z|CyF*<-aKuevS6-jCd4|Jwu^GieI`k+EcZ~(2IJ;kx2v9@pCpV=Yp-f&@$C!a>-9oD$*zYMT`?fRsKA3g7dZS!ppAKXw=wJU#kjV|E2F*|PdZAv^MMTO1pK2IJCPglzCQX#BFxhppJnx$`p-Tc^zF5tL<+!BA=$4S^9udVB8N|JNP~=LE*r}nkOMJCeuG#Bgc#47?kqwM^+t0=Ec-Iq{l+JrB8S)0DJcV&vVmEACbf!Vo;We5LytEXoUIS&%irSgle`LdJ63#FJhYzwi4XE2;%uuW8Di5smt2tjk58@kD+6Zn$a^w0>YU^qF+o1WJmx>f$#Ajl*hpd*>d7Un1^JNWXPOxy-}|$WL%IE_TfTfOeYjgch2oDKeDb?5YTnO)pT6_Q%8zq!VC9cc$1EV~0SeQ|VXkOxa?gis2oW_-*lv#N#dOD6)q5&CC$UDHcjl!gzc1CZWi|LhW#-`yNEPlE(kpdn;)za#(uup09@x4#Z?WTgw-Y;4PH5~otL+iFw?YIES8(2G~N1^}h>kMC-!f39w_qCoKJREeEpXz$XoUNeiI%I-U{=q~Cjx6|c3kKH1HXP3%(Djnk(D-G%x_Qk_}EiU15GmiZ-L$TN)BN?tdxxy877W3V`J2|>iFVbMO61~2DE$RfLOzpfE)J%BYZ@XHwAN2r3h%fK=;vCqJu%PX*6!Oe_x@YSGmaecnHEuC@8}-%9wV<)|ATsPZ_-nlq2{{w~Z>2|pd+)wkF;()3?01?WRT$rbw}0;v4@_at*$F2jpIx52Z*{q)!y2!fzehhIABn?PUpM^CgjMxU+QyeqC;T?(rVnZ5fc#Wgd5{Z-zM|TeEZ<53qTjaD2y(l#$C4r!Kn7Fif!S3Y{X?qwem+Xppuo3ftNvsx!TOc{aQ@NEJ_;BLAL!`%jXaOA62n}hc$n68sei43anfO_-r{VQZX|uY_05T+KUl|!gdlm3R2X}9L(R(+^8)3E?Ka6p88964HF|+7@`+mQ^o5vDv!_YDOqOH*VC2TlMId#$Bou*n8%Tj(<9Gv#Imi`L>e+#Qm3?N2sr!FACW`Fgua0Lu5GSsd)tS2P(8C!_^2Sp_Crv@cSIN&UQ%yB2Ki$V7?&w>&?HH0rB76MRs38Ke-$y>T1`U1y}z()Vbb@`eFW?JrCABVST?$O=;_W$mh0|&Z*^*B)B%g-;=+HLqGJ-ePw-#%$~pY_dAFF41TmRK#c-?$DBsOW~1G^*fKT`dN7I1P0OMBf`2BAb6W>|FhyNK+-J@|k_`o6vfnjA&`+-0Oxz5V&jl+(=hb1u|M|&#Z4xSay8Kdc}P=^~%*%}XfmPbhHO;aH`Q75bGd)!ueSAO#dQGbUbkQ~%j7C|3o!tEPbf?@5{CDab)}_UNr*tqhb75R6{t-?%&zT3gkq<-y2dbiDgQT6-3>CUAU;uQA$+#RhruP}OxUEjO5bPzpuqw%%~>Z|QW(%ZTIWI^=34N^EO6GV|KyF?+-#0z9m)Mtz73)#KmKba%j`qv(=ePfvqQarYG7S;S(B9!$-M&&b3X+BQ&q~VY$ag>0+`K9iAaUNB=;SQSU+c5!zntn*p!>w?n<8nL_X%BHqn*L-OW$mZ`CT&kr+3)4Y&d4%efdBI@+9h?mJf2_{Nu%I!-7Kp*+=Mi)&~cY!P>U$E`L1gCAnhxKhy3Ma1^XxM0-k4qTGI(6bNT$@aU?O~(Oc;zsjJ2#K{Wsp)~pY11!yGEGr&X;`bFn*c=dn87Ln;EDFZZzd@%1+6Ko#IwE`mIo3MILm^9``US|U(xH1AMd$HhSHUi+?@+iU)jwRKfZsI0z{w4i`}TBqTdyq+qa4J{qkfp!iJD@kg>YG#d|6g#g++8i=+MT@^?i$ZpK6C)g|kvm*9Fo(5clIYncp2e07ELXEDA#{v~(0H$4q11^4(1IUt{}F_rQKL771GRpO%~pOfiIN~QC1*!T8Fx1vr+)#URyw1WgSNqgdg1&~|HnUM`!GyWHsK5RjMYpmqo+Ur9B_sd0pujQhSYUK)5*VssfqjbjDk6p-fplFY}RwosbFP4-{$e@3ou6UafnUDxp{MPeoe_+1I*l_=oc2x?zyJ97?l4CBOSz)lom&|lH_tLd3iW}oz)`7~7G?gsSJ*JoCv<&$Kh2Hm1yO_g1Z@L(aeBurD+d`8`Ak(|7scjAFgoAW5(I3~y?0aGdrjZX(Z&f`<0ipAsR$K6(J^jt?x7u5%5O*cvVADqA_W2d>{oxlZ4nIJ_><4l)o-1PMWtI#Q&-La@OJE+UYi!Qs6-Wc(oUn{zuHT&>Es18N3|JF+NPh=M-!?9jwv|jzd1js`>74X;Oh(=EQJY2Kv?Wv&Uq8I;bF(En0KB9{Idg7`IaVoC3dtX9gxhIrNoZ(cW8@=|IdmzoLX3Ch0P?VueeGi`pH~Y!W$SR!)B2W3A;Gni4gtPRr4rNk}mje`ZMxb&)QHP*+qrsj^Aq>-Xb63zQj$IKNl|)={+-yd}6a!xOqCIK||j{<+WF-|Lpq<$ka!n89>Yj({M%(ri(}?_g>6`jK#bswKR|edtc|A1JZ3#`H>ttlh32AjwV5Zjj2Ov`C+(T3U7Ev3)+!^m|xWT9yt*Avcg3uQ1re^a=;z^#88*rzN=S-lGR6wpoKm?af%NIp1r=qIits=j2?2um+&X;!+N7)3r#RgdK_T>syCoLzwW%3tJRj_8yEE3licE~nTg=ywe_!Xi)%8(h3ZymMAL!*r-Q}<)wKUI&`oH;xb@<-!@^%56Inp#B&WC@$!8+LPTZ#!+-qXN(joB2ptK&brsyNr%^(;McRMhPhuQ=*~Fc*)HqDKE~EY-`c#PTp}>mGk%3$11dN~&P!f+6z%iFavWX6XrQmX!nAWE+D{2=+voO-1~Xc{_jas7d$qh-wB)B)aHyL)_wW+N?edJBd!t!#kjNYNj$!^XF5Q~ll$-{umcCdMYJ>VJMA&a&6@M1=y$TGE7sUMDzauc}%$!_cxo30nVdVKfd|AmaJu>*_=pQ(`GW4JQL+gqfZCeTuePS%up}x{8IsK{AkP5`y2J&&#QDX~Aq`a5X;Dclg>A_w6UOp9%gf4$X1HtC`|n7@T~3D~|{7w@+G_1{H>-gHyWD^_y!k-x2c-_mpKpm3-s~Z4c_Jr}gch`cC8mQ7>=dxX1ohiBz=CjSQ>rmKUuP4IB5oMXKevWr5=^N)Nn544rqe|?>xOZZt)3+%i1M;JVABAq@=s(u*E?UVo8`eatjC%TF9weSC?fRMvCQ~&9`SUOjeoDJkrJu;s$t}EIUvFT&<^8$T;>k-CSo!IcgTf=^rXJ*az3VU)T;=bt9p&gx^5<0WfQL8@x^|41aJ@jDgx^x?X)t!EViQ*h@>CDjv>%U8h6lA8mmk++oIF_}^5Wfo_qynecv$|KI<*(|(^KL0xRJBGnN2%(+?{Kevty%_iipW1UXn7vx6FFHvKCzdRk@e+5Etof-`O6=s^JLe!jnt>0&39{KjmA*^?<0GW$KO$S2efzuxlwkd>jZ=L9wGMLts3`|ZX?D3GzsUA5#ht|Map$T||0UB_5diF~4xkBkG*KuoDiiid`L)R>7}ZtXNU`1kl8i8ACvoFk0bXMmLcW5vEG>OVWtZ_wj>7WgGCo0F@{F*jia>j#JBK(O|fLxJMR!BND^xy^|LVBT5!Kn8UMaZj}KG8rCE1aJLlg6rjLLH3W6HWWDEl6UEV`e*5&4*oP=Z(9ptA45t{y-?k)6yNO4>tXzu%!=xbxaP+g6ndcB?zY`Z?-&#Jhm#CsZJva@uiz2sxN6YklN-m*{DS6m1iIqZ@#EUyl^GX|_%VJSn?iWM_hTeDRZyi$aM$=fnYn4C*f89>sDVGJKJBI+H#d>spPFd+>-g1^zUDY1)~Kb*+1Mc~|uMQQ7lMjXBN%pKL#;r+<_N_H7>4>sFwh=X}b}=52JCC!-csbQ^UValdYo_4|e?kj)lH{C{<=$^=>vRFKo-9JHVLFhmGwgM&N&4D!bJFK&s9Q=RmNZqYVhm*3eLZ-4&cU6c5x6J!ahg%}|j<&2q`@C36A?$a8#)KDg}slDvNnhCuED53+*nUvgd}sIfFcjIfB&7G&s9FM$k|lbytn{yDI~G=)l7N<(V>aW|$mxtDmGp_07pQ(-x?^FhIAHpa-US@{c(`BN(NZRAc7%tUU4t{bJZ^3M6w2kl2uUlH?wZy%&X{e>ehb7GL^(Yok6V>5IxpHRqIY>Padw;M?pd8L8mJn0q{Rm`U;0!4*t(U~Cl*GpO<7W0LUPO{R+gE{Q;*@yZV4|}(id|Ej~f=K==r+3uNy_j3mvi~O){Ir=8Bn6K7m@ZUahdVSFt`DRQC?GfTzIc-5aXMuG70nqjLvDOti*p-B3+-p=mpqPRz6j9vylY}ZhJJ&;QI@XgC&YX;+F=U&{eA!w^TL-_uk?5mD*N62Mk(a8QP5z<(PAQd2Pps1)Vf-JYVuL{5tZH<6YHl8bXKO>9x;BIr=bsxFX(Aw}b)AM?YhpzePSX%@uBC_cNiU*uFFeV$`pgZ~Ggn)!tk_PtqU6ZDg+1+9K#p;RF9+i)32owLY%F_%6KPPB?o*&8DtV(!n9?=)B^``U8XV&s$X;%e^N1Uf{7H{?hE;;0YL^oIQsXTb2byX$(m(H?ed7iImXZ1@-25?*wl2lR`zm_?crg2+jX9%Q+hTgy^TOEIzk;+D}IvC-~n=A$JHS!MBLX*Enbf6WjyYVp>HA$suijapG!v$`kANaxhc@$$^Jjvj%lKwq_#!4CREbl)cQ)pxpR=uik{Cq^0zRcspM(L3`iEGh#zULMC4)8NI0ulJD_Q>`J+g_r{5Ps@ey0fvC?3m0`V0Pfl|G+{a`%ZSdgexSiua`K#PTM`#Mtv1L*ZslXZU!_A^uBI4M}0-iKaQ7Y?f3O=s@ze=JVo@qgym`AA;ovkvJLY)!C|d!7Cf(N8QSz7^%Z@2bRPFqE-bBjGV4$->MK8%KrH2@u-|=DxS+n;aHVv4x)qguuW!j9>Z^u*aVi2nG$8JG%Y8x}rMW;SfayesYvZb_K|9bcRbjSCZZiYo`o>l-d4W2rZhH9b+W`i&1p5d}B%poflXv%uKS^+9kpA0Z8zc`XysmkOdf>@{Cjcc_h;zJS38=4@zMM39aFGgA)mpwklsNjn%2`tRlW0KPU*M7m#qZHj&*^v|9TvYxb`Ca1{%01at+dx+z}&kFH%>E9M}3X^S(x&b0bfq7oBv%B?IZ3Hck>2Pz#!hJtd|${Rn67!uSeczz{9X~V|gaV`6rSmq$G~y05NCA=??N)c0K-FohEDDs!Hh8_@Yj*OXT*ynn(en|CZ8x)CqgnS6z>~Nrmsr`ZHdNp&p28ERAAT(I9ijnZpmGk*CIvtd;MQ=&)RULC^tR)K_Wh2SuCrGGKY^nL~o=$hjo2cKi2V3?QESrdXrjM$ko#!k?u=mO?J;yttXS1JgsS?*J_2e}b?Z~HqMoV#(w+MJHuC^Sn&hhjQBid}Q;^H1dFzRxeN$e96yUOJK=;?NI?|HjYBgI#s|8n+xko*fOxRpJXX;ErHdxu*oi$zgHN2-Vtb2q;t5T@;G((0PuB)-;%os)?c#h2d#=YCYmWPANqIXW<*1-q@~KGlCi3aqeKwj$mIh;Kq7zN~Q9pc}TKGD8E*)$al(!$^xJP8y&ljfohz_Gi7QP!)L~g{qk6-=_Am$ZcHb-vVW|JPRi}T>2Ji|3}9qKFR1etebhq9p1c~<@sS&n;0D~`C028>I(+i1~uJv@dx+VGbpJ&Kt(?GHG-+nqg&m0g>l_8^J%_Sk{?SR%;W5pm``Qzg)`^1Qa~e_BL6@Lbw$!lQ+Gu*6;{=*xqDd;{Um2YbYul9E{O{BxX2fypAh%VcU!P@MddBLLF{ze&lmp)ynZfHUo%ugiVti^DG(%MIvPLAZE$;rSm!TRjJJevE9bG5dP?HY6!=@qdAGCUNfxUQ_pzSo@$Od-mP0sWhrVDxWPqQod?Ll`EhP@jWiXA_un`DkOSk$;_DhSR9N&wCj2{@<6KPY@x0Jx$4*#~20iIiiW8&12&x-nNvUCXpi20L60?3EF*?r$!l{_HkyglPVK4lwA*1o$)g88{R#U3dfeXbmq>Qz;d+4J1*I3ow1=UL{yBnlL`FMVdhaX$Eg=gir4r>L+yY~h}V2FPJ(aqD(LZ5puOVcbFvaZ8`}^i0s;nR^$Hv=FYB69+f0Rmr8phxmo`Hwn02%o^L?oK|H3?~t6&ehuW4A64+Zx{d*E^X#lWxH$Oi68d^WI}eCHd_F_SVe0520sg{75K;`-{y72bSGQ;4gk*lD0nx|()Jp8ndGfHjj{l`>;QAdrb3_<*&goQ%wYxU4boJl7(!Kt8Z|X&BLwER73K0FIOU&`SZ@tq_wJXXj-ME;w@%Og8Z>;!LBI3&cYn?`=YLq#kx*ZpbcE<<358rYL}?;dE;yvSP%(%S?E8zalD{eWIi2Wlek7OH|i+XuX%n|90PXc?PNx5K>h*TEoZ!}@*v#CZSXojo(~e&1si5FVPS)~*Vr_^_ax?!DJZ3b*|KDJXO8^9?(50!GsKQxYrH?POD%Xd!q7G**|0$o{G$8I#Zd67-#QsX&kPh7{!T#T#aJ&;F8gt7sAo-U;w^SbL1ft*a#ZL^#m~dQY%|vd8*7GMkOU(mfenNc;atkwln9bb4gtnE52QDo`T}rfH)+Xlw(HEhm0`Ke2I+?CiqDThn@V&+FR$;#Qu5vj3FH1)e`#+}+%nLKxrs-~pR2aH>vG{oh`iWIdLcsQP8oQsi#|n<~Q>~Lbq|eiV=u5ge2l;$-vozK*V}K-tU+&_V*O2BbSNwZk9uWOtRx6{vavs{bbo-S&Xv|F5ad|UxBi?xmZD&H-?5ER%*2pc)DOIy+EeSwG&695v$NZ*01Jm-2WN0jJt}5o}YsBZ>KQc8)f$LkH(uER{!=sq06fKti7d}~|kxG03MX+t{0NClBf!+}}s|bMz5yvGrSM$Yl4W5xjtWY(#owoV3W0p|`HmXdm^Teb~nc`u0*_$5~aM3XZwzOJ6yynakRz6X$E!CXmC+@F?$GJsPaP8PzcJ895NTZI2`!ys`=eR*T_!@sR2E=pCd(@sjn6Tm#Whi1(7IEPcqhFcETSF7hGHeMDILLD!tT$KodX$!p79zlPdby3sk#tUdwxkUbuWY_Md)@%&|jUJ=NLUvhBjaR(X9-;T<3bIgbO_5D@q&|?a4kI?o-h#?21zwgiNy+sAHy@$D+=OBj@DY63oEIq6|YG9r=2lW;4K1A;z9Zr5Taoekg`s$s=jDMLZ1H#6%E{De>2e+a5m7{kUFnj&ju*#h&Q;2`s$g%55L+UX%rQUImT1+{gS*#3`XeB=){i!vXb`O71PC;T4cH>h6yzBC;+9&WOXF~oRId|!K0v*DqexaH>|%xixA<=d5Zl7TdrQd5$Mdf=s-dVB8#1&BGNit{n=f9}|{yv>~kX?`>N8zoR*324eC{bta?tRdERqyTl)*?QdzVb>Y(sq~)WOf+()kP2QZX6M1e_log{_o0poun}5d=gb7bm@%Oo+*v-|$PCIj(K^n^U-!JH%K{jFW85I8IP@9T}I6G;65C#>(#fX1Czy5|~lBm8yY038mI)Q5$xVV$btgw4g2J_Z!(cG^A?K%QswRUG|m^I-JW**ecV$dmnUF@y=Xr=_$`aon>qdb%ZPsdPS+q;A`Mz8X2Jd2ZBRx+WX8vjSqt0IqkXJ%dp`S4l7xR&HBuhH+2KO>1xiEB`t-t!&;Vi+p~)$(1PUphEMDxZSgDk&?zO92fGz*hZO+15q(r%vEq_&>S?%n3H8;r_34wg=}aK*_uUaeo;S^Yy);tG2b=ENz9X-YXWG8mjvuCS;M3!?^sTuVCoi6sI#d})h6Ej($;`hP50@AGvH|JNFHv^fozmzd(?0F)WpP`>@JTzWtRZIsNjpp^C9Q6l1$IumD(iz}%Lu1zLD31FxLjh`9?s@Eaph{}UhuHr-mt=yAIv>Mc5cLC*CiXTk|Ce6`klVGeij4zS`5-UWVKJ})xfKgoIjN_UVbhgUH?FF2%q1@wnDvXbPk+>~Y=6}Uh=;8T~aXYi83SW_^ZJMkMA#%gwfA*N&3Ku7BSvuBS-YcT6$WhBt|T%ng6oBtYoI#KfX6OJm$Z0t_=(lisH*Zj@OwlPGoL^XA>DTa`1UhFwXD`UjE;Wdaw55A$uJXMluIOA`y(G>E{Ka)K0MbY#ZldnkHp#Op#85X;CIq4HikoAwRtKgjlQ4)ao_DXhrVK|5GCUV8W8hy9&zZanwC;?87dug@BN%M<=16?`bk&OqnR8!@Z(^dKMCvr(D*3|%;{JZiagO`0c5(MA0`lR0!MtQC4izP#hYkRx)KF5Fd;rOhcwkRs}-9GAaPXX&ouYEHzrBvyVt?Zzp5QO^Yfyh#W7g-FDx{+{AZx`Nse;une@T`%w4zhwFo)P)G3(eG}Mlpa44O*@&8i;pZXh`NoaukT{%|tacCc*PV-gy^0+6}0MWNfoTVF8{UbkJorn27|HA{t=?N`ni9!yoHcMBOSZf({)6GnNnev3^w;YHqmuH3Oa@qD(c@~ip0&;nSc_Sf@w6MiqPpTs?_TUmO8wc$O)F&}4Updr%Qiwrj(xL&j8sLxy#edT1NNdGj=`?ytLY*)nud5|;@&*CtZm-;Z3os{W|LOylg*j%`-@d-BL($Up?(R^d&PX%!_8xO*97ZVw&KCMj$)2F19yPGgC7Gn26g&JZN@yfzd0vkYg8Wm8b4llZ4~_~K;qgi?m#A#JkFjl{D9m%T81xeGs*|=#DO?IIXoX!QHtp5p2;WL{QP`Vj{55PLgCZQ+yc1vJn-(QFYeUIb6kqc_e$c!K}rnsIdNlP`&=*7(_m@MM}>4{%ohnyxD3rk=`b^>Z2wLX{Uke|akF)b0WFUg?ru7cd10mO#Q^3=9`Fu)9L*Z!sL#kpj$Ei^La|`oR^AlkbLQ+a$*{nDu<*TEC*jF)|LXI?JMUK)fIdqY=y;%C5p#vw$_k)w{fPU#NaS|Idf+OxmI4+QQ$|c{%%`0ryC(YQ&|t>T^R?76gQVL_SdiTfACM_l}5n9X6pfh}7fX<_yR|&Fp=SMFJgQ>B8kCDdb@K^zX*jXa*P%gK;_ffEoL7DXl$`2RBZ(1n~IadYQQSI;vlb3H{I8lv7$c>YRt>FQ)!tg5B(IdpfPqPwtoqOESp$Af~YK@d_T~L-bMX-BJL=+)I;Aj&tO+{C6K}3gGJNEs|4@kWZTG%2cf(DyYSNu9$R0ebrcXYGL6w8k})?SD3^x7m4f7$LE$G>F{X9gg`LI{q|%=$Dd%99)9+{lgnTOa`01^mQbbS0WohjA_h6cSM%UFFz@N_M)vJD3)pka-KtSvZMn|%sxiJ0zVI^VDv9Cw;|;s1SATb10b;-InT_uam#{YWzxA?V?`Vj@_i5AvE)6IA8gG%oR(r~IVF>2;=Pnz|B3b*R{;cDk{Bl?)*(x~oddX`#l<>L7at&hrs_c?O#734spV0kTG<+NDSH!!ciu+6;n+BY8GDm&Y+S1Zu(wh&p0p1^mT~S}X*=#(UzoP(Nb?lj0-iA8L)#Xn-lU@khg)*f&ywNVOU;TQ!)fG72cT0}39qm&>c17!ya^bkf>>HgsF`loN|8R2t2?`|ayx$r*A9cbx#S**0KpL!Faxqop73u-v9)ZkueDFPNF2_A~qJMYa=K{FTXTnVJME>vM_2+K5UI>{W7`;Cc>sp5>i&KBuUjbtN&({RhUC|F-ch~WfVQjwcp2BjBZ{*r-zqYTT!qMI1mp9vR^uNkWzi{FY4fsFV4)pnOyz{b~wStktfO#3teMLQ}6PyoZJ-9rMM3Wx?2c>;Mcu0MZBRnBv3f|i{2TYD&u|fZOG^NiZ{m`l$p?^UKWvh2=kzuf0r#EOD{>t^ysWoL~f=1DZ^Ja3*fMp&BpDvs1s&81#|ydTnNPbhUTlNuMF4AovM0J2$oUeu}(V3GhEW=x6zR+K-?dkzks7Z8(*z<$}I}J&i~^r#>v)ZhoAipG+1-RR`aC|#zW${@x@*`%r{~BMRUwI*%c9?tjfx>K}%j`a~mR`@RAb0CKo0oSqgfNl^~zG2NPeZ9xUBESl6X)j`@-3KX_#?D=s;X@$8pDZvJA=&-Sh;gtXYUU%#Y~o6qmSJN}Ofq4&P^w)wj_`ZJsxjuK>jzu~Jk2DUB2b=u^&?-9+L3XMEZ8wNPu4~B9dxTP~f1CPYjqkp1MR}k$1w;M2^F7D_nZ41m7TW?4Iv^|>#jAJt0{D;v`q+z$>zGNmS{9XR;OcCaV+dW!7y;1o{(dI%}RQ+|?m-`%bzv!R6xreX7tf@O8n>pqJyi!5x;xx^ZHol`|FSHtM#1c-m~9lpS9k5?X}NmBT)+3%-2J3J?=8VGuHmI=ka+f|`Hy2bPcpwtj`by{16yCM4(AE69~o+s!Os6@nUeG?UK~womZHENnZv11HzGc~70Zq~)l;DMqB`aMGUOF8v5x1zp3H>J-`h@~CFMo;ZdS6kk4}Qt<*&w~NqxO<9Z`05Xi8@5y38ik9o=l~q8A>N>+vUa@oF^-a(lRq|W`Ndf*KKN4oF~=SL=ARsqyTfF5Qo%x#D~xcqOjiI^i{g5Lkfsb!I0Dj1)WStj10`OlO^f@>s#(DT9yneh=rap@~gxq^;NSsr-1H@%I05ch(qnhg^Cf|QX#7Mtz^|clD_DazH889U)Gj_{>})zJxRjG5Mqy?CrMR>PLXZ?$(zJ`g)PW8b@U&fldm6m}mU&um@9*(6H;a9Ac-C=dFI=3@V7YH9HX<11P4=JbxHMLfv62)z4lI?Tx&M&@0zrtY&yA6hxokahL7|2MJB*tx~%AkD*Caas(`t=HA(Egz07I!=M$fTmhok!K$yRPOFM}tbf)#n_G+bp&)xj!XU@p4=u=JSXbhHLx|6J(xfS`qnQeXnH@Y)mVy~Jr_gUmu4mPV7NcT{Hk$$iBU?1X1=u1B<&4iy;rrxw%jv$|IJr@{8amKmHmq;p<&Qm+L%)8TDL#cvaB#Es)z+6mLq4Cp_tb0}RJaU=BpBEL~!`C9>}?u$6zjtXT4TRq8yGw;3ba5W&mTHUU{+=DfrnIn$*mn;!aqAoUR85J%G8S^jFkTQk+7n&LaDVnCpdrGoUMh?b@^$gjR=sc!gIo5ZebGJ1{sK?|LXXU*14fhRYZCeqdzFT!^)%61m9p6?Zt+k>P&jO&e>Rm3LKVBhsEdg3M+7k)VorkAhEfWWWKUyDd}HK`Fl><=xYK%em9QZF?U|IFkRdH0I~kNtLC5a&StP*i@@>v3)-TbCg83*tlQhe#P`fkJwfeFN!S>J8SyV|XMBZ2FGdEnJTFgIbTm`Sn@z*61{4j|#@q{U37d{R>i{w&VR915*AgN^JF069+z?AjQ!3?f3LDYDkNx(+Uf2`9GZXln`kJo_@VN=Sl!)-Lt+0OeeuKTa8M)JauX?UL+JU;QOyAMd0diyduLVszjg@u`dfcy-Gg0*dsm?5ib=EH)g@Kv*6ZrE5wI0Xtiq1juc=l+rByCDDo?Q*|WbZ3{zpZ8dH4?5Qi_?t6$bzrGeABdb^j(h=aj--Yc!F^^V;kILx6((%sErEY>@g0o~{6J;Of{2SS%Ai^YfUX=puKc^2OnmYelX?4y85%!c=RgNOssUQIVJ6C}Q?t-X_k^Mue_r*6uE8|^zz#o8f0(ic8kek;g=@iM<@cO%4SN5oLROG`Y=AsT|5#5@(TU-PXc33Q8xWe%nxZ*j49Z2zH`%C5%@4b)8GDJlRlw{MtaC6V|sY3IF}^j+p>EjQxiX8oAHd1I4ywMcOBWzgOv_Wi}YEw1=-+`waQjmw3%xRfi~G_IW#B?k>z<9g3n{=ZegP>u(%7B99>Nsy%q_T_!yX5*E((I$Dpsi`b`8i=+Y}mmYW*?O#$%&i^o?K{ACm(dsJN+5H|^VW#rO;(CvPif_z{ei*T)@++;f?0{=5f15n9d(Q46#QEdF7dx($W`U)C8mIG1+^QRnnSFFStIo{ti`1YhxtMdoqPt-G=TbB%l&-L$xog}TNF1G8MiKRlELiv>DAM|gHHHR8Nf!LMFx7HA7?N3Jw0fdAPJC0`Vktmg?ToK%;tEXpsf-uFsQ8Yi*t;17&^v9-n>aC$BA#+s+@53S0_Pd@XH(N3?fH*%Sw+QihN4M1JdrE;9KB}!nW{8j0NK@-rT_$9G5E~sP&7Ulx>fI)3S#UXiJo*`_zur>CpR$GKRN(Fq(tS(XH?(~>U7N9l2KUaNdD|C_^D6M^Qags7WyKR4H7L0`2mO81B;->3|kkdL;I5Je2KEjW@VoHE+pf$>R?&Hyq&iq4stbb$+r`@N4^rj&<4qmhqyrgGGDim3ZNFnww67-T$hG8bao#Y?xkdcr7urSzzUKsmYs>fbIU9sc*KTGoF}R3dWx%rsIb}bqWihCh)+l6L$7zmRCd36E*ZopHtfFdL3J8*obYyTUybcqHTBm#4Q*H#{e&3m%I?i*fINK$*wSDIpe$TM%+J(k%sj#Hbey8>UiMgBRlll~UP~Y@CNQWrlrNJDFFb~rr);a!8n*t{*Rexl3Vca*ZRTHVH$%KBDtSOCM824|V(Ta`ymj(3(VR{v$eb_c>iHJY5Xzcprd;Dk*C^-Euy^{viC+lVz>A26>D-y+yNQGoWvw-;B&n3vaimE5yzFtL#%M-^9B302|68N!*J3kq2GEEALN#}Y_4Ih~^Ih+d01!3E3RM5}2-ix^D(31`uX4S}jvA}qjB|n{g|1JfHz8p@ZIvKY?`Kxz(GQoiLKn3HFClI=kvAk3`y=!6MoGRo4FOC&I>YGi29Yg#-B>;Js!oT<}Pup1h;mJ**T^xw>&!bDfRNl)5`4hVi=1d^(I=`;(0dvxR;)PFP<@8ypKwhP^WLJ=?o-)N#q*)Xp%`&%)$}n9{Fx0edVJ1VjgsHOoHtlIlse2-$_Q#!K{f+8~ektTf84JwKWSay#GO`|$|zd114I`MZ@0F1v1jm9Ry8EY7|>xgeMZ4YxF&C~D)p+U0d6@3TTSyiV>VbV`4QrL6>-~R2xeUasbCg(Lbq{(q~9LW8rxx<4$Ggc&q{tp(y^ECskh3@0GGO8f!RSAPbDjdZtUx$K=HWRHGvdTy?4W0E|ZZ=&~}hZnkMBdq7%i7-u7hyk!K1e^(EAi8QcDf6;F9SE>rz84jGwo^r^+#wxd`|uDm8o8p4bFyN^PKY#AKgM>553H6NVZm-cl;6JL!1kEtD5#-{(Ld=jciHnlaC|PA$@03-^4$}Vfg)>S5qw+U~>5H^@uUV!7poaTlgRa2z`#tb4hxea}LdG`;iG-jw{K(IfnCu7-$AS?Wymf05;QWI8DtlnXH-3+7SdfwEl=2qwsS;hS;l*0d5`C^KCULxSlWD8X>eGQcUZ?oLNaBp$;8jB8p@9sxpS(ATIK=*39IY};fyPvEx86l)&pfl_MaQR12$~&#UyrnZDz?hj!k)G6qeVZKd-{&lM@fCw&el6r@XdRY^VkaKNr&JfpMh;Ou>3b1=OK*v%(1i`Thl^=Kl}yzIlmzebLW)=tv#E~*1b$`#d$*L;im>CLE*+;{u!aJMy3I1^+(G#l=9M!rPoa(^hxg0%uS9XHmYov-loxWY0TTVGf5G1jF!^mYY!Z^{P#Cs9^!ZeZQiqMd1he|YI||Jl&Is(R#C#6IPcD|DDL$-nTDq|=_|qqcA0F&$WL)%wH;@+*NtTDXmOGVFWyyW8qC?z0ej=%U(bpm?hzokr?&N1Q|c6qx~pen00AtfO9aa$9Y&OD0_3q8DVm8TGHsoQ2;m;GhDbPtbV@_Y;Gr&d$qbtR15tMzwi@l{H~hQXYD0%XU(s1kFOf$jtzD3Ip_~rU7Mza8q`rjOPm?``EmI(f@?BDc)KB)(%g>i52GSrW{Pm5!A4vU56eVuR%%MPcf^>6QGsblAgm+-!Ln|m2`N-7rb;A%^iO?_;ub6TRM9_IP;*rQLrR?&l5TvC==EHdIz7E(3)>rAGfo3)PnaFdlsO7({!-ls<2Lnqg7&_UB&3n^B>Lq(s+Ub5eM7&Tstt{5xOe_zcZmkVVi-%Da4J??cvp=0#QfyPaE@EB_d)wK3%4Po%v)1pE2V3Wbl27^qK7c`bE|wznW^+^4J%|sn-x;+u3re1;-jH&|I4GIs;5mMr3MpDI6)WZ;Zb4V`i$q!DrEHq_$m}KJ7Uv&Ruu3l*h`RojO^BOaXQ}$`1$1`Z)Wr|TuL%FpVnT<4b4$6dlIptc63=+lWzk`Fn&Z&EwaB|7+;=oiv3R5Mc}bn=1oV@c`;HqHZO?#(5`$~@$e=&G#D8$}{CWxqS2Zr}=SF-2znCuVmCk}>xvjq{BoUv8Mel@jPf|h3d@4NE8}T`|ZI(W-5ehL(mQpF?-a&O1>anK2R$nIA2~DrHj$(|TE=}qM2iOPJ$keDij(kB3wmH9nGLN=LY?AUNP6Z=^5d5FX0y**C8i@j#CgU|2k7j56BCl2dHJ*f^NtT4?A(m~j*#BRB!zo1Eeh$7x4l3meplj*oj4cvlbHcxYjVE5S&H%0Lu&Z%5+0UcS~y3pW)7(z-;Dxi&D~kh*~NM7i4du84!87zJasC3d1QDp&=}_l@$Y%^G}x`e{cCSC&J*F)x1D@>vLVoZSFzv~#7ApL~v=k90>>KhjQO{Wx=14)qJ+fh{M5>y)h4VQQ7a&7LwlPizHuJrZw3@Iukv~M3Yvql^UU2J|18W3`uqFVUARQy%)GOwY5?t%%$MQ;!XVxQ~BwQTtAx~x0u4$hN6M#tn%77qzqJ>TB!FzG#dukAZ}gbo}Vy_TQc@;`jKl_bu_Hky7&hRb8i+ZUu_{z^)dI$HTF4Gy(DeOz`3d5&?=j{f!b6sR*g)h5-UkJo#Cyx{JV1?Tyc`48>IeZy-e0^d2;(BStMwG;ZEu+FOJgJWxoRW{^i@72&gf%}7}WISz8snFqP`IRtv3V#2a?>SGm=h4}E`+E&B4<^FYSdzAk0qahzX`EEU{)Y2|m!1f}#DL2yS`UwkU>;19+iipVuM{{see(DDMHu(bz3V+Z@i-lVy*y5}#$f)cHF00P7GEYj7%xg#Pr>|E!MBCe{$H~oPBARQn~pqcorC4ot5!5PMhI~fBQM%+u4lg@D;o~wejLiRLjL0;)6u)?BpuS6YuE1y!hJ*HoVjET9f*48t+UZSRG7Yekr)H21-IA=B;h{bu-u>GW7Z5XJadG%&KT`Po-OB7Dp)1WF7Y7c6P}Iw9I!Ue0B)JT^L~-?1J_i(#OJtY!sWyFiay$7+?Rj)_xYN=RJc87tEn3w#`m-5!_xWFXzkS{$ghY#nBFh4VQN#T*zOkOQ6YRGx4KN}u&HqE&v??lp{`WCw?rcy2%b3q4e}+upzZ}!Ne1{m)oR-NG&jojJel~ed%025z2YK49S7{v>FH-lXeWubW;4^llA@T(JLn04wQ=JuOtLp#JNPWbrjDmIurc>d^I^UK^lK=l)_f&@S6%E*ZoV*YpyO(>_lRL73t@8r42Zb>bgW=5#*vWx!WyHW6d-iPS`sl{MEQnTm6I~FHP&st)0r6{waJQqh|l6BZ9m6l8L%|4q5sTp#3w3a;Y0m_447-oDYn!Cc?CtogK<+m6Pn@^ZmAqY9EkdaQI9O(JGUb={4nCcTCU1OrBY$9F4GuDK$4UrFni!lz4kuB@YgX@$(6)w;;9e2UxOJu%G$qQBOz!-#{_CFvhue6v8e{i@`Vqlkm)sS;QV>*{%-X^Y8vP@C^xtK#q)!g@4BYaS}D-~?Sgf%1=eM$&)WH*)|3i?j{K(SpYZ&kV3+c@HoI(CJ4$W$o`dt_DEFMR`q_tS{X>}kII^S6xF5eT~{s~KlQGQ4$B@sxI7eze8Bi=*=!p-28e6+otWZ8oLda{mh2y7u=S`p%8=h0bNNQ>HDH1Wi=Z|YBOi;O>{3XjGNHA!=t<;9d@h9U;`uQq~Z{pxz8oFCuo+ATVdP5ZOhdXi5bpnuDmd+PS=4>WckjdB-K-xJ9rKazkB!YPYmtx3F#ZlAFz^cxEYw*yO7T9I_i0}jY2TxS5mUp7T!9)>t)e*G5%Sj$J(k|&6#a@);WKUm}C`ly*ci&Q6HCK0lJDw7F>er-V);=D^MPH1?T38B|-pA>zBd~8KqL4&z;CR@jH?l8s+|JOf+&6KI|%eh)l#t8kP&zrzw3H;e$OjG3pQe1G=ai0=CL`JE2Kl{_CrV=+GNp5K>!!jS>q;foL6RYKf0i`}n3Kfr(uyQN0Dm*RZeS>2mhti=RfftD{vmLZ;Y9eTDM2~3#io9h3t3-LU6FS=Bvp9vgq2D;Y%L_8PS9ekM|k_m)A9<@jR8Nd9Fm-lrlo3}(%JU*%K%-tK*+DA(k0QD_EE~W51T8bd;7r1&0bv>yA#ufsx9TzPm9S`uy8eR=FVWTE_{?YL)3w;-qBNM5>23P0gL^Z)ZJU&xtzUXi}d(WvRQmCs^yaJ;zGZNP1#oJHDH^)-phZcfvvU9^ymj+fb#LK-<)EGL_WFutD{Pl<;*X5c7zSq=ON7dTRfRN+u9GNtUE@cFP~@&3?Zw3+8mk>E1kxaW-Ro!?4#Ya}uyi)CmSN^Mq)7c!4wzq+mZt;JC&XX!fB1AOEu^`rEUTuo^+pak;XIktX^WUpX23+l$vAh?zAEutbg~%`ZszY^pn>=lSzK#;&(8!6YjM-4ABc}@jRz;=921(O?(454^`}doOzs$$d@KoM_vPCokPo;S5_HI1KyTtpCO0MdBrjJfc>KGrwDV!DhNEnhsl70dk2isV{a*!0E(AEIz+hy5Lh0zAtJ0!f%G18L;4Ld-vmSh{MyQ)#oDG8L;>6P;1@o*qQHt?%=WS^m-=yyzO2BFdVt#@xlkHc#ClLq9e~*`{y~qG|y@s9T%=IJZ9_u_C$pU>r*&J;@++X{vQs*plJsZZ#$J-dZ$a5S8nr{j{ro;OTx9hPrsL!zO`P$Yk-VDfnR#%Z41-aH7{@k1X=8a*ptATW4po^H-JkFz#!g)Oz)-lL`vnJkvdc?lX4c{Nue75WcmBW}P%~1F99oNZLOA}$+Z?uD)^H;7D{IMAzVd-gs8X`{Ii>jTpy2-)Z@XpW_4s8=Z(X3SY=OrER%qIV2iJj6GM^#!P*Zki~f=Hh`j!&Rlj0@-!*Qvv%ipE5qeFIW=tUJ?o*E;&W7UdHrKkDFd{WnWXFg3uJw#7*R>DiKvMtlJ-7ZMzuNY2vK%6EV1mQt1HT~J=M_IrcK(n9x+bqi^3US)in?Yfb}1wa+NrTYrKEka*L-s<-hZZntFMIey;k(+ZX4e)R$0*5{$XAX#=GgS-1BzrV!%sosl>Pyh})!9vFY`01~esWz3eJL+*qss%{^C`kYzW&u5<(PRc-sa=UZ9hT`pJAc}E5FGwn66d6SfLfH=P%nvVR6*e^*9&Vhn;w&mkTFyEEaZ`Mf^u#0;A$*|7TMSLiE2{;+32&u^6z9hxq_{CtR{KfJ1@OXLS@yo8=jYYfIgqV77ZgTd~D;5UUlL3sIPtu$5~dG^Y5OeO|#WB=XCil?jvL*`Y)ZN7rf!Gi5MaQfMWUBc$buX?_QFpqk%?8h5;-g_aQgKPO(v>J1u|J3!kes{!^$V+P&Qi1#NPEY?d^po71ita0_vHWo5&qYI|bJ_h|+ZV~R#`{Z|HDW)E3$=^eYr?lMK**2w;xVaTp}DOrx64xo{7m+EHt!kYbKIHZoaPZGoLniECP3m3M4z^?QYH}nv9n2iq6s||(X~1My}lsBPtv({=8*A&F1>6Z>Q%d!V;p(0TdCTEweD8QHOO@)>3i4LoqSy>#DJ69)Y1;pI{i1zr7S&%0k19#T>r2J@ge$yJ8owJAxr(>I^sjD=a(ciA>jKBr5!w&uZY&GpLLik2eb)dPdbOV;!Wdd&hZ=|-j8iQp)=R--mp_=ZF~-R*6Wv>d64=?d!M%6$Kp}MeqdoJ##2eFWmP{7vVl&Go04-z95UVszK*;=2jV`8Zfmya#Q*T=R`OY5^xfKn33K_R%>7!BUse8*KCS(U36T-3Kem{!&-lz2B$xtmh{O4Bcf+`j(?PC#)4D6shyx-2_~REHIDh#YBhIy-@d>Ep;H$W-fJVTxM=a^qEr1b=dH|vaI3|4AQpMW+Bp9h0h1hdo#eD7Nx$^y(fbz%sIbmyzhH_F@~d5%^|pbU+0dxVjLr>496rpSa{Z)1hwuFBxy=#~hZ`ym?@ZpZ{Fq0;S&0I~foqLQNd7qn^z_fV*ZLZ9_`#a4``$2scy0nSdEjoPp?S7mmA6%BwKC{++Y<;TLnC~L$I-dSv!q6hwb=#iedqn7q+CvUZwK;uF4Z?ia;iHuWPVJeX$6CnGR>FRQgzod5KQvfvQqp&<9rH{6qm+>E`E+*uq@Ww_>(SIdxCGM~?E1Y|Bz=aw_Z{9Y4onbykeU;85bb9D_78lPvG@|jSYOu!_YJ{3UFURI4%CSk1~6^$``tEJz1_l*3;ywAvV9e}Z>X)5{@}1-?tlN*M*c?B?}?@5!h`Nx8{a%Zo|d>F^@Tbo6&`Lcq<+`M`0hI0SIzq>8-DFiS+t}d_n{Il<@ERRF+d>P>+rZD>H~}h$?kLe$p9JRz~?&LH~ckU@NZKZ6OMT^3-o7U-8-QtHKdRO4MXz|Jaj}JNBY5^xZu_m#yy<C$XVkW!4p<58fcb`)C?S@a7FqKzgdy}O1e!_Oyg8|JPu(8{)s_Y-)thaXyo`M)h#1wuwmkIbo15-D+ONj|-d%S$?4Xm*mEX;+kzT_Dv*0cN9?T`_B6hl`=$11fy;qjgl!AO9;c!wt^Vp1fjBR|uMGWL!(6UCgT#2fbA8|YlKP018H#u;VZuB!F$;}MU*S^Ot|9_w0)58f4Frk%~i6Q#bCve^y#c|9V+6czAxJ;H6w?eN8)uw+^+ndrd;RAg+dX-&}m1UhrbQZc)d883r${^cz*>Vp4B$pFMHy0K|A!+;HxmiQ@`d(lk_kRdaV{x|74>-{NkDVt~uViWWbTKaUrrBH-n`A;w+N_n+44gl%vmaakzLEn87i=$oRziMtG5MXI5Nkcl5r2QR*C6sMAub`R%39WQbiO9OrixV0_Luk4vrDd)*&v)OrFCkn<>VLeAvFB3XcUZ5E7C7mzhbotP@ZY={gOUkd^=}GF-XD)XnshR;q9Ypti+^8>l;eT~(}kY9C4zTJ3!eKs)uiqGF)hP=X(rn=^RNGZ)Dx>t>F^H0n8L{w4^d%kLa~#k7tMjajs+`izl107HI$a5C`!Nzl=&c6NrAi#!GRY5cO1@!a4ud;m7@No-`|o{Ts1gc`FAt^GQze>_k8F;ID+^;kF#;yxhL(>JQ{sD;tbNudtqbaPk#N?MFC&&b(Vg^VpOPYl()nDafxTD>fcntVw70F_+0f9GX@4*IXK+v+GZ^s}To|Ep?%f?=gVT$>{Au9AsGwvZ#ej$YyBj8*!lhr|0$!*7sTKh0xR06~*5FR6Vp<|^XQ+8Ou2)gT8>X_S2tyMg?wbB8E(cUBHqJGNUzN#J`#)Vmvwfo>8aK)_#P2_#j`CCj>(3&x*NLA*cW6vi3ha>L(m7OeVo%CGj{ezZYU(gv~Fq^#`w$rum}gwpzXIdJx4#uu78^!2}EDqIlIuGsD&q<-rybuHIr|fm!3qw9eLX4_Kucl5XluT-9*wWyOnyjVAt$ecww+EV8LgcpPvf8T;N?82Q+@S!i{I~IV!&B&X1iP57!e1Dzek@xwFFVx2>W9;3G@-tJJwOV~2Ye>O`*xK}Moe$T3%pYd1q~eDkA)z|;4SlWJ!4YPywfHfh{#r-i|7rO8PtIUJYGtbe64w<91RJl=C{432B%%{k_M!cov#(z{fv7{|4ZGh|3RFdB$FqMr}?t0Y?9sQH^1nEU-@EvE#oo04tP-@lv{2P}6xe#RG{qcvzApT!#QJP)2-7fNyd6Z?xHC;UJ}>hQ|VH*jC+LZ~8d^mG6mwmJ63apK|3_ej6^7yTU;r)%)XIxDLIw_2=71!{IRSaelRs3C1J0^G&f6HIXnC^S$M|Df%DjUlL#UoQ{UuaOp*jDEccx-)cog4Dess@W3P%{oCM&z+V3GSn$`bYkc+z=W~>Q`^pP*<00mDKv>>5&i}f+1e54*-taMQRh9Yz9G6w9%HE1|{;;T$|NJ&%9GB_+-8_FSgMg@m=8C~_5qcSAYeRuJPqya>`bk0-&)+^Ao@T_H+w%bDRYj7oxPwz9yAHYh3gUk(@!MvPUD5EZJbA2e6z^Yp-mrH=ZVb5I?=8DS>f2lX&uwlW>-pN)KG|QMkN%Lzx3(^fhv0IZUoP9wKM?y|DhoW|?IZ4+UrR~*o6oD?8=Un8LU;3@5AuO+&tkboGy`Gff#g)hWYT%VjD!V0FNMHGO#@X85z_j-(`=T~oN(wmwQxM!@tnSvvx!t!led*m>p&d4Zf&nu(#-WHmoaT!NA<<#NYGj;YTv4W@lG@NaZ1VIXmEQOApX)H?Zn^B{INjjXDGL#z0*@?VaeS%Ao7$Jyckboje_HMn#6-ZF2{b_4z&MOyVg`3UY!R=W3V&gQ$)9uV;;)Zc4%%8Z@R`I6!DhZ_eDdp883o%lOmHyCc5=b4rN8^53E!|^yb45~SdS}bK#@psSN{i$Id30=*>G2Dh|f4rJ+UTb(XG_*-L@j0QL9{8{;#UvKIWWNqt`k;NU*EW6CcX7b^)uh!V3hh<%3Rr=JHQpQZ4Y*R#ZW1@^et_X6AnGYhYtv`$pPe6kdKVH^^MC*Q@jrXB(nnLRO~xDj+2@$X`tkZ$lb0f=6N16wxxrbnmh_qLH}Acd_gXLlo0UmAQ<5<>g1yu5;LoCQ=y$7{)_P-pIc6_McF=LwFbae`O>X3dOO_P`M%nQ#7}{^e5tKb@?Z>j$YChZmj+0YYBrb3x|J_fKSP)0_7^9E3!|lVrA|y?;bnfE_|2~1Gk=pZ>~2*`}aGW_~gywK+?8+Rl_p0r!^+^s9VOvdZmn!`sR!oyWPgSFP*p(KteM8Lu&}yiE^pV#{tlH;@z<(m;dEky4m_vyg!22=RNITBM)JJjD^6*(wBQ=TX7xD{%8vWqR+h5MqF<;UB0a-84v+&s`E@4-*Mea@Me*zoPN>e8#3QaEq#baEt@jn=p1XQB^Pk_)E7&>@mb~{rbw-Z1*A(+$k-Y3Ff4AZi&9d;giu&d;9n^Em`D^e>YyB9cIN}Lf`4bBaH7|p>=cS_QryezMw4UGK}x@igcUY$Kqg#@rkK5>KI=H$4h!LZu!8Ip}b2DA8?=U!pW^eQmO&KTT`CWyAsDWRJ7#Vd){DRdWg);+l1pfs`sq@vI~oEgv|YV@-2?5)co%^dPX?Z{u%r`DNgF|CfWV!L_j3WyM4Ono*>4-MCLiI>OIl0m4Ay+YbC~a;=KG|dJKFrmYf!JyeAADsM{r(c=Z$7`u=xFMsgdSbQXf_J$JS`L$oi8Sj`zQFWk21P#W#jtH<_6C;{Bi4voRxJ2ni+o^O<>AVIEq9fTD>tYj0ZPeuq=hy}_j|!4MZ{XCfts_p`?3ftOcP7;N3R^sDeF+6g_?JdH?Dyzta3Jpk_~@YyYmt0$sCdH%KU8|Np^*#D~X{(U463lF9h5_@dX-f>(wdDMf&H#nN5Usj>LVf}2`-Ny0Ie^%H^*;No9@2UC4}&Xm=0pd>m*i33rcC_Ze#U0bBd^0CR5B$#lf(mwd`+f9Bt$yfYB~F%{ndT>+M=jv;F&$X*tP@hcalE739xX?H_3embtl8T*VE1)YL;L$QO0)mNcu3Z{9b{^S_9g3|_sObQ!}t^N4Ie)v5A@{n*&^`U1AO`Bs%%TZ>xp$WpACy|q&D%dT#o!oW0lS9!pFg|JGagu^$hZ>CyzqbZ4e8G<~*7B>HBCGSua+3xjho3%IK338EE&GdK6JUHwL~+&&^r&m{c!hJ{7+FMJ(*+TBD-%4DE_ikFQ3v_{L{T3kQofv|H9wcrMk(vvu>rJJC+)9Lm48grZs752g7aUt)jk_XOhn!4)s$SK-^$2I^k1p6_+{s(cf?{*z1R;XleDAU^i~(9|~MGaRp$$^FU+2i*-Hc)K{zzW=z`(SH_EpfhG6^zCIDj_Z%9`SGY2IM_M1#FvV8LT_c{TpZl&Kauj*8|~ZO3ZTLw9u8hudqMOv+Wi{G*T?cEK(x<>N|7UI4|&uy)N;xWh(5-_$BlT<+OEip>_rW3NwDHhnNdUNra5RQ_OpK+j|HO7n0*}bB9FPxX_-9n?ETP54YU(={M$?8f#?hRd=}cnC$*>ek0pSJ^3eIo^8b&QI{C5l)sB9+52eCbw!JGk0EqQ5M;r2xm1htB+SC;Ul7t{m2JQzDyMoq(A#D9#?k>!05xUhGRbg<_9X_EWy8$V2)X4{zNx83-9ALLYKdeP+JLJJ(k!;BW{C-ZPa;8^Uop!<*noCSh>xK&j?>`JkEW=kFaA_S+Q!zBlV@a<(IHT>WRE?~l$%=nHlW-~JWH6A~~xHkhff4N>eW{h=oF7j{(__$XlNFOo{8oc|q=;-TQUCFb_%WI~2?L!E!ITCz0+rF8{G*S9UE51RlR|zafd*!|m>2d{_5B#8|@OnF~I?`D94a6}hrV=P<1>1_-_L2c$k1E9TRR_V>raeC}6oMa41S@@d_4(EFr2pnTi$R|XBoMI9dsGq8C85z;FC`RzEaqmwJ`UP%Xl3DIDv26^Monj=o;8-jr+SgXi=H_oe29{uT~m7%b2Zm2kyGTuMcdrs+#k#P9@e#^w4QM~^ZkptU%-bccd_7pXzi^v-#?KTa%xJQH7)H%(EQOH}07iKEG_!a|=>Ej#f6Oj*Ca2JYPkz&PVVa>IdJ&l7e&@IKX6{a6si|;wzm+v4U7dgfGD%-Jqu`%=7v1+B-ltaa<^aReXc+w1dVb@6%*%1rn!XL*9?RxeXGl7MzXO7Y;bt88Y~144LF((8utir|Gu{EJ3_ri;55xPPIxo6MVz(y{dS;DxkzXCP`z4lh<{@~T&bVaLi1TERVbE;>)+oj6#+uCY>pR@?q`;Py59lyD7bjgEt10l?L-}B)8ZI-w}$poxEbwZH4A5L3Wx>b(_&5HjGYsf?R>}LA^#Q+wI4i%c0#AS!uTo-)_xBgOhbM}}4?t(z%nbFXG#EqCA9eI90=&hpv+65@)_g$@a>N1x=yAa=Tj#==i(U*7mdX-6B9+tm4T+4&+hCT`c8Ca-zVdW~aFQ`ypIa-?iEJ8QMR9#&S9c-!g$nsPCgVtF0#01$oZuF4TyIfILs#N>Q|5>wkKwXiY4WO&ec;c1N=lK7uShN%X_n(2e=GEl(}{ht|cz$#=&DUKgON`zB=V(Wo;EwfS#kDF=k)MIkTb9!sRh!57V|w}?Fyk%!zVdzzs7E)496gTZQnGvDu(y!?=ZV+33amyz-3MSfKp$GQ;~Zy@Rf9V0Q%V54u9D8DHherjhd&LimzOHvBBM+{W}4@1i+8H_)$p?99MuG|?%5q+d<^DGp(u7szSAaaDp@E+yu9;yS6j5h6F!w(Eb-i42Z5Q$o)2cb~LmT{Iyfap05lLUV-huT5#sYzO@1Of1Z_ElfV?KU41VjV!hjudlzkFkG7<3nnS{L2K`zLgMtXbm~O!v8Ev>5N7s1N+JFbYzmszm6QN%_WzsH+EVMuTZ@`SL4%7&k|Qqn9X@#lZDLjoy#%Vcci0f8<<&JzoZJTsJhv-mN|9#jc|}*@ojH>N%C8{eT!>WIFOIJzniEbFK%n>uMS}@&4K8d$)xE@iSLPk++}G&Febg9R_`hjoU?|5Pu@?O}!rhtX0SDWq*;k9RG61)M7ttym{spN}|ZGh`hvjMf88?#D$PwHGKQMGG$&Y>>8`MaA*Yi%#sUS`c4ZRAa7NgXt69w*X#GcHm91qu-0Qhr|=~5tK(<9F5j2%1zppXj&`JcFI%`rED(sY)}~3s-!4Y&)G475&~sL(Se1@Av)`k{Fkt(MIe4ET>N_h`DkDHj>rP^ZIPw-khhl9=6uXb4G)ez(bwXT*`l=Xc8ei|HVDbOuyUb!?#jCNyYNY);qF!3BzyesaMf$BUt}lA}^tZ+Pxq~saV~1=r&J(tuS?TlN^ZJDRirC+c91nmD^A)Xc-S9rmRD!BF{wf9*n+E3=n!bE8gPu1fM_H6AOpFtLA=RmN;`g@mfeX8-w##N!febknj11SuMV^^)~!hFN5E+-{)1y(lF>{J5KS>S48{ReXGY81!IBe%X;n%+AlaCSB$rcgT2eFn;tl#-Hr%I*~j7P;yY!B?2#`C-`n)!)p$=RTX(&23cqJ*ZvBU#1rcz!&~{{G0_`T9i46`0QE*E;OK%Q|r;WHK2^Gl4z?~h9slNx&emP}f-Hz&57`80ewfutiBE3B)jCkY0l|x$1-~-y(eoFrw5cSLY!vBl=-AWonf%TL-46|Ni^GxJXv(19H2;K05v~>n*59Be9%e^yjd7cx*-cR>xHrm<#-Nc4{jzFgl`4!twHG2Xv?k#@EuZZ`z`lCPmOsmn{>5BQQOy=PIclxxn^wmB+84Es|$2v?*(Eh8naOdak@c=q+=p(#num9NA$n!iNmhvc6tCS+1bpz$euLZn-&9e;tr<>HR^zpTer}YCLFdTSrH{bRDadqbLRK43DR~gczq9|o3B^pE`N>&QdfJh>lN`{iDD3Y0wnSt=^C!H=nDCYI5a6)I^7a`bU-4VKd8Q;81=p0?eBG}hhm1~MyLn1~9JE$9_aE@X^XjczE8v-!2wHk4dTTZ#UmZO2K&9e+G7#%y%Z?*ou@BeJxjC8&=4EdeD_A05U6S>Pds~+Vo^GOpyC-5C-2Gz55W_J8t_0=H?r_KWE;&>7ivJTjES{_U5iV2m54$G684+cGW7wjXtOn$kbBPmpL>vgjd)RX;Jg=^Dd%f==5#&1Bxe3T2#QODol~@SB?Dlm<2cDPA^mC0brzb-2giw*vPtY}w+@r8xgva{VVOwxz)%ah(UQc{u)|4!<(h_zY-I+&ydOIF7$4KCmThS|$+r*H!Z{ZvOlcGqu!;0YqO@+nJabQmMPYH_hG`o_{)XOz~emd6%|eX3l|m??d4Zr_^^D#SgP%`Db&j#25%ado7?k4*5!zDyJ}VD-pzJtT?r|Xl9_t;`lnFq-N|R{#5*_3Yb?YNkyienG+5B2+8_OdYjye=BF80U!is)BzMkN|d>s^;*Q}~MTk$z*601v;OT6ew^`ARFOz%<4^8J6d^8ht;G<0SU^iiy&IXdh^O3&%lfx@9!C3Z+KS&io@6c_vEHRl@y`qm^jDB(!f<8PCf9I^Um~$#dHnl+QiYw}KdBD-MnE^z9LeYz;FP-4xay^F$jR7zFp1wqV@2$R;BsT3db$V0*^_T3Datz`6Wd^zej`cfC#0}H}Exz@)hd9W=%t5c;eYyqFq6rro_$VIgwE00$Mo`%7~`t27c;W}X2k2lL?c=4ttK6AVOG}Ke3@$LSoo(P6|5AHk_M17r8{>H&4DR8qxUcZjQOF>CTx?*pn!B6-2nY-ViPV}Q`pF@Yx&len)JVRao3Vm0=LO|UpE+&dM4@~uP-eu<~?tZJ}+5DuSPD4Wc`ua@SXt)ncF+21fx#)*q3{38Hjp>t>=)h2;Y`-d($B4ytsdT2Xd5RUeywJK{_x8S|m%

      1oQJ4BTjFjAQCq4zTKl0)&>>9wDj5Lqq)yEIWJd}S9ZvteD89rpxfo^#6sX`33^aG*Yd?HP%>M8O+H^QutjV;(y@*YH2yl*0TlY-ycN|5n0|b;_)UK{v`A@pSg&96>-L9Kc%fSIEU_%%-|<-HPgrSf@&x&0udzgO-witS_U$w27sohA^lOpe=W%KI@``v3jPF@jM}5>7L2&qZ_V@#D^jk>&u`o&}C=%#0{Tm?@&&!b5sBl)ayU%i+uI;?nImJ&Q!QF$M}3L;P}Zu&41&ZZ5{GSWadrgr_&km>PY9hF?r;x=hvOr{QgCUI@#B~U-n>puYBcH`_hO3yT_Ob68n%(oZs%ZO+D@pOY**lFQW8o*8bhf4NwUO*$G(r!5{M%Aqpyj)m4xP0v3&zgjI7xr1bULj2d`TnzF!Ibf0j2T&jSNuwR%gN%Ms6YY{a)bl#sjyNNo_k(e?Dv@6Dei~Z@zr>UpX1aN!Ywp`vroy{a5|(A~>ELmkMF#)hO8T^2BQcHs;wjaCMGVpG|-*ot|GeKf&>MPZ=q^Dv$ykvAm8)cE~e!hh^^%zofy`v|D)&w{SeO+l2Ps+mHbhD>61{O+}uOfbYh^YcgSiXxXu66cu?)CSwcpO}1?oTfvejBfGJ&<*(eU#})T6um`65%8&=Nnq?9@2wks+bW^2b;ZyLVKM%}?Pgw{XcJ0*+GUui-G%g>2HcKk1AieR5o_QFjrQ|F)bj3ARU%%jvJi^|;=vjt6FPQ-Sxo*yJOC`rVHQU(`jVlN`IX6Zz+XI@j-bFCC8Tc^^_-fjZ4%-q{t884w?-kWj=x-Dk&ESN|g{&|n<6^dkiIdiM>ibbB@g{F*8GJrILLQA6jUzxls&OV?g|P2EqtXT4lWi69|&%JS_3aCzE}_EN38JjqPkaIbk3bK3fXETzdn#kqA$sAJc%Sqa0q1@m=d_%rupY8PFl(Yg=#M>Hle1@+SiZQ{My*@F8Cj{n?qcOfb@F?GpTrJm7Wxw(*`H40tEL90LD@n?XUy7*~VKIAK+4{`oD9R{Yp58HMPImfBs!so473^*>4^n0T|at`5_D><752NuuFkFLRd*HF$7d#~^TD8DHpBpi!;mAd$VjFDCl+*A2Adx8d~@AIeb#H^FikXAjoJ~tT0GtGNo>hmuNAVMT=g7JHA^iTNg?v?^XS)8LB@>RQ3Ww)DQ8mtb@{8s9Pd{r!Ys*!dn1CHEtjx4{5dZBz!lW(t!E{WBpr?sn8-itlCWqA^4EAttP}3@llwggWVm^@jxs@&?bmMNk(npBzcC7^f>fe#;35<$(F$dXcII=yr$bKc$y9BYn%OVCZj&3>hZ%#vK%lz;=X921?q>JX`LID1AzCq%Kzw$eC0iOyz9e2#^H;=k*-Ih`t{*MlY37FctHS07&P!!!aHh4hOVk+oYWt7g-|f3I;P9qTXPq69qlkXW=DnG)nfLg-oQv}&CRb9SKgNXZKTRIbqOA9YS#3-l-^~V^=gsHzFr2pxop)b(AazQK&=IU#gNaky6YN*Cih>G#!}&l~22!_4Ftqc3~#yvRRqW61iP`FWVXI+f6z>fo6``i&bM#W+sZNiR$Wvz{FK7C^p=6L0Nq;c*_Zo>JNN-+8&ffV98-jj2+_KXyCwRVjCTunSDUsEUJW&3;XxG+S2BdAD6Qg+!x#d{X8+u-w2kE;TDT3qQ_ui1-B|8{iYYC->_~QH%+cLBkM}rG7AwiVH56#abNaHO8lN_so-l*v2s-8^?L#?a3D__-L@qepdB^r#Mbx-^b9FbU4lX0#OPFN2iK=j2uP07y~PUGF-;m)Mb;XDhRXS*{($!8sdfKj=o-G$;q?mBc+QT%b#-~O=U|IL9t2NHm|eYfsFZm~9gr4mt+O#1Y;AHeaDbuXbbAm&3)ANfk|>1)&G_H;16ZagMF5qajtSb)ohb~+IAT}jC!<=imWiHKl;efi8wMil=C_x+jQ%g33p2RO`tIMfM0Ll<9rvM!~s6#3I4Z~J$FzCidjdaNsE27Yhe3-+j=ax|hxC9xGag?BdA=yoMlKq5oZcz4HVqy{tUB)#fck2ODNo<0^WOW+q9ZRBpib=noRX0Vk(?)WoHo=qxNMJ9Fkr&hS>LPwjH50P89Z-NDGT0iHeRbDj(kPzS65nSN8Ue465N018)I-O_7dYjHZce*Nkg>cqYy;V?Q#ssD6yq3FrR<2vh3GoWsr-nCN7=ltBIee~iI7DS&vvr(I}k5b?3z*~7;HoRYTrqGkZZ)E+Xy3^l&J)8a$r~dklGoFONp5~&vvs*A;llTAU|9^ftAz#S_)XZPin*_!aRx>Av;PJGClSTp_G`RPzCTI3-b?I`{!Yr`_=eW`2qrw-zB+TW1nM!*Zd{~`u*o?4{u6T4<=qua_m#6DXk&tWOB3p3ee*|exH#Op<8=)374ev5bw&KGi}pgkBJPKLlLW}TD^s8ngzJOy&rdV9C8faZu+(FFu2a_gcn=_l(KJX4JH9ho40Yb?X@tNPI$SIjEZKDyd4TY<>we7usj-lthy|$M6q8b|xXJ>dl(JZjDxA-p_H#YLX>2I8=7xmx9HwTq=@)@X1s3N4|QlU_O0fHVveBFVuI8kgtgR+rv8h?@j7^c+o*v$`*^L-r;d-?`7{q~&scf3}yUmo5JFGRDo_qFY|-Cu9QQ-|&@#JeE95Jn-HMUzjsL^5AEo;D5&x&)L?=p|GKSoqgU@%wMUl(6esfJ)dcpqudJ@AvX?lwrq2|6%YK01xF9{VO~xkD^b%VA_+{CAG`{khupZ(i+NRgJOw`Va6bJ$i{npBlnT#XmF6`X+?pM&b2`2hdBP(T>nkWyW^p6sq*CQfa4_kE$*M03`F0v?h`o92FDo&O$|JL?z#D7JP5}_yDxBPrc^rg7f!nJ!U6MgM4WP-PlxFqm!thCeeteFbA^}>Ghub$5J#?&(g)4gZ>G*xCTu)*d6(gCD{#U94fyiUY?a@y3Haf)prn$;aLLMXg!XEhl|Lyo6y;*zGVkOs!f-LyqbEP#BuFbo*=REw707Tl|^%3e5c@O5Bt|@T4TVU3h2IkE|%eQj;ccy`1$}+#HvB+al0ynvmMZEcn7hT%%5OvMo4Gu;nnIM}KlewE8If{sbmmHZ;628k%Sd!vDANsU9;u#Aj4jEn8rG)ymkp|moT?e6T?+uId6uxqE+ivtcG8k5@D3dM_;Ql*);7dsPWbLzLKZyE4%*0zQQsrrqU>wS2Ev!FJrH%``%Xo>!@(Gl!efVuQzIy9Bh_}2RLGOZh05hYaLR&yLk9$GQf_NR&+;-FNB-HjIuX0_!-SsPMUx^(U;MsAOjw#+Wpv@Pw^{b*tz(9=lvd^aRr=QP?uR&I2iEM|Y}P`_?eD3Pc~jDMH9sL4Hi_JXPLxycs%WQ04N!phnBTklEd#!MuiPQcMqbKZE68YWXF;?6Jdc(UoS&$-speS~Y}j&sS7E6=>X(XY)&}s-i`bVo)<^N#pnDB{`Nn~6;mY6qp{Nsn$i7}aWFOBZL&#SS!mbXD!XepFOi;ud?iu1ggVR37b-6Y|I>}$7Mi!&S&v2POubeG?W3iXIDl`YVyIR5WFTFL4rK%UJN-T_4bol(TK!7jx+pI9?MoRI(NMYE|v>nG6#eK<6d%rN@x3x(-N|tn<^qy;Q^u#ip!ECASQckeZ>m&O||V^|NVkjAnBKK+!*s$J8d=dUc^Siuz~#Sn4id3$9rBTv@qg8{$=X@lq8)0wdunp+^$3z>XM%^G=%d{_~E2Srof$BUY~-baGcxEcMWkL(!fOY)W-THl>Vo)e(QEMrjx#QcP1mZtS!r1xgwZO`kBi=Ku&m}78BehzyP8yZ0B)GzV3pd)jq?6&`_1S=XVC)KfjAi7&8`}2I6^niQ+FhP}c3U=2#?LTrs6WqL0Fd>TAYZrp1E_KVL0#4UTh?P?7i79Z6(f;=&FbC(#E&Nh}r276|P>wGqcd(;^2d5xkB_G;9W2#RE42?T7Zx$VB|B%t{1NINiM?^oN;aSXVvSpcaefROieg=k2Y~HyBdMjvIG!ntXU}VTBjJPjLjxmw{N95#?#BYd<3TK$n{r7X`6^L*czG}Hx)Np9@{^FSw)OL?PI#CK#J;Y_TuQ$!bG^k%8tHIxL~HS;rN~z&YfR(#b?IRL+2crBD(b}kF^35ZSh)WD-D9JuJ2lGne?7${{h6)wk(a*j;zg3_`^bKd8{8@Dk^w(+!qQJe=(ANvoPJXJzx2B2jV_1+ts!L#jx%yp!;`ojBSs0p9NaLxuNrlQV|D9}KTQUQX_tE=EDy3=zvt;m3!uciEKchsM}f5I2GCKKMQPOGv{L!GD>THDWn=VtS>=*);#lJH5(SN_H6hXNvQ|hwN>TPw-$St7yE9_%zx{5UE1A)mtUG^1%a&BLF2XZ+<(VgEwNZIV_OW_M^$(fxrM0Hu=Y!Yvx?Parj7sYUp*+83W<9wtD7i&Rotztd^h%|0pWM@Cld8rS`S&H+vrf5#*&=kj{4&j&4bOl3?Tb)S)v~IYej0}AQLp3CJrn$K)txTKoyp=VNk#^Y_n!Svzj+_4P4;n(zsEck@%}qWBoVfY+kcI?i=1#`QRHXi*{Sf}@ihDLQ{;ggdqcj3ZBK`cEtOqXVyF)XUQ>|oqr;tX?FfzI$OA+l5S^(^Xd9GbhkV9)YpA?+Ik1TZVpf|T8AhT`^mP*8vdQ~@*-F&QLpLAQ01l`we-Uw`3+F9n)K_+4N*E{uSNQTDth4eR4(M<*jtAkpAI1k3VE&5TWv^@9kPK%BirM+m$XC5G@152jN`om`d)qoUW1fn48yK85p~KJf;lIo&b?I#NIT!c}7~uKS*x8?wkIFsebvlg20{ifLqHUKcKC$iV>{n*8;m}BvTD~~y0yS~Uuk<*e*z@Yp-3*+!X_i}WSv=){b6to|_qUEymn3V}||C;Soo?#Ja_Or8Lr?;oB)(r@JAuXsxwC1~_}%TP?HzIcJT;;@P@PIy5MSC{Ikrb;)g3`+5q;9f07G0!qIX@^d@={`x9xMs6h6J->zl(I2}tC*t4t5P7!rwkYuaU=|NqFllb4i9dd_D6XSEBEw?YrEj^DVsJ1y{CbmMx_odrkYr#{+3#%vW=NqR)T(KlCdoO9`-wch)_0wBR_S55N1NppZiLANPvIaRv|#m)JB2vRQ1fdINGMxjuL&{qOugLVnBaqUYMM=R`ox`(4abV#3JOe7Qa`{~UQ18n6!g!EWyf?O-;`ep***4QJ%E=($_Oj`b2kOP{d&3qkqrv^j=iTMbp}zIEZCBlebWmAmxIeE0^&`9=kVg}pTnDkAiR-G*)`U9fu^BLN2FK8PJ#rxF!=l0>*O$!>;qg)N<&0l99LatkbFz@fw$J@0Jp-3X9^`t;qg3P~!mnq0c_>JR$rZkSjrlI3{_;|5ECe+;G@Uo2tUu1#UDZlYg3fgcjaK!@Z$y8`3{e^ozKmNWQ77^RTRx{lo3_y;!35;b>oq?+U{5AYUpvL1SB9eRdKheM@z+oF8YSPj?Ok=@U4Ay4R<^np6@Yq6-m@>OE7@@5O}WAoN?#|B4Xg=k9sPi4NA`RwWgT$yS)JK-XJD?xweo}A7_W)`dSOWkq@P37KhEjWzRdUP$P7jbEQ(>>TcX7McRc&Z+7H_Y)8LD$ZM=6fa^0JqeYQK!(_!hluR#YSQ0ISJa?0of1DXU@#l57|*Li0Mw4Z8Z{p~+!gSwDB*JcgxIMtC8HD2>k|D@jTk!8&R*OiSr+wR~zlYS#-LrGtPD<_eo$mgwN9O-{`uoF4+S?<-!RE=cPCv!nG&X4u)&Euy=X{2w%q!Y+F#6Hki0Xoc^^kH3WCe9n-3+j1>0do@U=A3?y^CPfh+vT4O7BsZ2&kCdTW1?S}8RvhQ4gB}U1)sj42tZd`XG*b4}>J>*W3m=LB!cPUx;d&pr{0&KD|GuS{FdyZ$n$B0PLxWxE_A}ZAk(b^ccx`TyoB>4MMd}LjPg&wZ$=f>^pgUBRf`0xyerVcoT`-0PyYy?HJkO)l-Gy2Fx?04B1N>&|S}E(f`aUz)fAHhLC4td2i(ROTe!iTYvxo~3RZCq%n{a;a+gLufDd2)-K$qfaYt(P;HB4Q6I|U|+Oq0pX#C0NKU%bGCG`Qn@J9=>Bzw2=LBr@PnL$OnLBgP9|#h8^}re}h}wWr1>t?;?(SSe92+`#~%&)Z@SzArCZF&r2i!h*SDUpF_hDg9sOMdwcPXTw}4pRLMH_`74@&V7(1&w&-XBPnc3pOO76jStIja)9s^>sp2PGvTkg+kgwzr3G%6>rnT9QXi^)DGAC~w?>~_gXfiEuirDIlS=M$H#>p(u9y3M9x=L-M%J4tAEfwD9e1+G{FDJtw60y({D$Xc*Dco+H=YTt5_wteYjFKyYt^ZRWxVIA_^g^YrxbDgMncz^chuSN!CU5oLOZ1&Ymf67XMhcPJ0BQtx%fZ6K=B+HTa~j)*%a^F$$YU|lNNJfc24DOY0CcYU7vT4wD8{3c|UtAo27VORR?-*hg&BD@3zZb9gKMx5xtM11Sy-F?vYWP!vvy_R_Q6M6ZQ%I^(?)U1()QmiP%&2Rc(1GBvVt$hQ8u9i&6d$PgFc0%z1}{cT~q{|Vop#mCN)c`Dahyk5U%O0HdhMQuxkBX?Vl$x4-->0ARH`^O!}*2i{ki~pZOTlv6luOQaf#16}kV8*Zs^lS6DLx6wjX@FP=v6_ug@!*ZyiINC+R%(5LhTD_ZA}R{fX>p$@59*DZ0JzYoNSWSO#I{A1vUlTT3}&@EaRy^sSNZdSTFY2ovb*f%HI$h+=VO`1O_b+dLJ>ppKg6%4oDkMx$+;(gWGdp1eOBnH~{t$lb^2gh%c{X?VpR3eBKER3-@ihkgExgXBBY4U#W9_PFREimul_2qjd!!aF*^(*5U_`PngvVNbO$NOEcO*(pyfqFrGSUt;*38iKC4$Y?QpNbDY7r$7M4YBb-8$?}Dzix6MZ|pZ4Xf=0xtqM^W(;8ClD&~Nh=gyBoL#Q)9ox8WK?j+eaB){iB<8RiU+aco1PK<=ZmJ0mAi!h&~$OC0Jxdb?3VY*jrI>u$vXHP2y?2g1Ro|mD%R!7_P;ng%4c&ailKn>TMx;|G=?oOq{ZN57Z^-1`?|LwACQOqPJ5P96DHq?oF?hYX~biQ45^TiB|gOVa8&v*B-;nln&yGPVf=h948h~#iU%Ivk~Tnp3*-?sr@Pax`#Z2sjLc;|cjkGUr;3=W-UcQAF4Loy>o(`L+$hqx}i`tWv2znH-d!SQ0sFV5f-`Y2d`I_{5~(Dl4fKPv=s85s?4BT!fBxV~EDb}Wntrj0GVgE~E7(_k=PG8~Ze3r&20dV%>s2D^y{0}cXJ$7+yg8e4k4nSafI!4J1IJ{O=~wm5U{f$8gw0^tidQ1zen!Dj8^!+A<7?ZGg8jVhC`9@h;CAA=<;Vj-^D_V<*mEBL+Ehb{LuB$503diUe;MBmBki!^xc^JrzyEIj_#x31##FEgNadcebw<|Z$Ao_N7(Zf#63+XlOsZ&3Z4ma}a!}`x+{=v|HkY6%^4&R!7J#jdI@tSzP*atDl=aTOLzAw9+Nok4HV?lOo>?K)cYj2Fwto?E*=;y|D7K){?ZEGWRhww|Vd5TMP>orr~*s)6J&@DP}-ni-z_wihrp#--R9ic9}3@ZD_3%jOS&zsg$Pb$OPS)@4CgR@VufL_jP5=VMF1d^wdp-$c_11*yFTrHo0%q;1G_#IrFQ+Q5pvbU;n$5zLWcB{XDu-oeOP?oYjNpQu>+Bx#QAtj|;c<+uh!ggYUVfTIr|7+7f}__ufj(w-D<|%U-8|P-$`4yIIH~E-wX(<1VGa(cvLxHKqP}q4dfJPHX7!-uafym>;dXC#tsP%Z;uDn9nS-TcOy5lYj(-myhwuUzeeh&9EqH>1(_hY<3KGyxRLqk&PjAYY~!xiMi`(dFfL63DvBy+g>2U$@=0dgq@4O%sAOxQ%#UC5W6_2ZU-z3vvv-ji$S1J4SiRafPUYxCWDQAK|a!cR=P4E7xY&dFoA}>@7$7v+c@p=0Y8?47xJY18A`qkWP%Rch1_fFwR1E+D+^`;!`cD3We#B!xW=BCIq&s0CHTT&VZ*>|4nETeGy+SA)z3-`ytxX%3(`d@MUxqght^214B;T33mQwqnK91&(InnnYnfAtF?HgtTLXF^=cZvO(XZG!_)?{d!&JF6s=$S8G~tu_5}Llyjsk@>1+u>#x2E9M~_~I-h<7bwLA`dBPShc<_KvjIvHagrl>Jz`uRyqL8l`qsf_tiP7*us%>A>JskhKc8}_~$VBj~Sfb&36}c<6Dc0;^Y%2K7p7ndc2KlO~NuBHWIUU@7NPRujjk=N5;@}B&nc!=aGSzw$a+I^XmDSeeELgm)*FrD~^*q<21*>Un$dF4-UVI1jiC-NbcX)7M)m#6o-v%hhcT8=3y@CryAJopDor!$)Xovkwi#lH*^4Z`2ab~mj>^T?d4Ze{;>?09tLk>Kf*7k0ea{`z%;kmLW^3}ax`nf&jDR4>9&P}}y^+g_WInrk7zl#iGkV}o3?t*MV2>O}s0Xb%U-yqXW{WPWBI7l^(nmHwzRTg;cV40yu$<~2qok+?qi?GoRsJfmu^mYT(RcCyySiL9(h9ajtX|hG0QLH`S@##$(5cw4m8`Oz^+y0^h4-FgZgSz#Dg*~aF0mh@r2)d*yCh)^=o)P;|;De3i2-G<*YPl@jkBN#6m6#vfja*-AD&H+MoEPd+>PuSZ~3lE=&+hneN&@3y&x2YtwhIA$;A_nt_MNOT@YzTZ02p?+#BGOGKThqun-v3w)9@W%aC3-@fMMhwR}rD0bDctoFn@9HrYAL{v5CVA?02X}uZOYwl0&8*<;v0AfE}H)TKm`imJd^UYWw{X(T{doadpvOjbz8!9hs4U@fr@tX7x-^U^QvN;wZhuBFDAJCWJLaW;EEn$>?bAek#m(}0qf|*CpTv1B?YWK^6{=956O_z*Z@v0`hsj;c%hfbIx;{}b6B<5u4cL%_taYC5W}go-4e76sCRSxlElFCDmwlmtalOPuYdbYTyG%@Z6NXTxmG>U_;lFV(xCy;xq9v!&%p(P2vn@s;?b{%{&tS5G_pY#z?@?^fQ81i_ZGh@gER;OgAy*PldaShewJWk+1g2UcMKcoeq*jBF_N%WapzpLep+!!nXIT&b;`E^SNPBS|iQu5*C!h0-uXUg|FD(q-{}*GAgsqeGdff7866v_>-vqGM)k9e;s3vCe)$JdE^vf7XWgxfSn$o$)3P7OfqypFbTrYW(C)$9cKQaEH5SXVvh3_dDj}qygbebd!!8b=}SI#Mz&8IJqvUZ^b<17MJmlfmZjKP&zs0Yw#!4H$4}_k%pS>iNa6Gyz?4Nf(ihH3)_!0q^J46Lb#shqK03)zs6Vxg_J5+ceByUEY(>;<1-b=HGU2L(VCvoBwra2NUGBj0HP-qfXT8$T_eB@l_-x91E=%{PxUDNmFy$6PdRGw+cM%}Jw+~@6-EFkJHBG02v{^|6C`^{HF%JY%0=G>bbydg6Rb_MJjpsOH99n(H1W0ao=5qGsxrMyrdv<|tcsz?Lr;EOF4XOMFoPTrYq)0qLpevYG&s1yCRUVLJ}(MPObGAAj%o$rnu-oKFzck?Z(k5Ky2e6N0Z+Q*1@eb3Z~uQfz{L|##Hh8h=muepyWtwx>j5#BMzg+qQ{!hg&`{mBOXH|rnzlKrfYsURc)U+aH4!#_*6@*BhsPgWu(++~ekxSkId|=ug!;ID@~lJg88FOpV*@2mm7Qz7-Qg+&ieK`-^7lu+Ivv3U`6X;v)$r`#I(0n$M#>V+&zc;NI3?gbV-$Hw{ZGE;YdJ1#Y}{XRsvPytp3hHx`oIOE4^?6?>csw5p_}QXKfl;ntg9jVO8=RX35kNG#b57ZT}s2u+VZWdn9!yZA2Jewd{sHY@uq_)o9qWV;TLj<&8ZDvQpVY!CwM*Db~VOp!vD0pi326qm9>UtFfQzAkS;Q+$s(ycfYb+TT7q%aI!|j46)2Kb!%-#%0yYw&8j0yAp7C*XvBkE!7s+nveA%^oi+=-3wVj?ng|*^RgOjoN@3!2)^U9Xs1!f-(Sfy+koj~zj>{{I-)1=D<9!{-f$>I2Ce10o1`8yY`P45UAc}eLn)@!CBk(vcxYC5Ao1z~(7`VZR4X9MpsOuO>0&urJ<^&?sekUjwmvCdqX0EBaCK)xRvA%|QH$oVXLf=>2_O_WCNCHBo~PGADb#j(g&Nv7+oZ}521>~5c&RW4o^a(}T5hpgY*U5fMnWq!q$BY!w>GrX&;!|#9cSNFJJ)mPkBu$cQ#57@oR?6_MN6nJmku)G9yr&Rv)Z9>^FBO)j0A*Jq=?6aeg^tTT1DxMcHZr7WsfBR#;L%t&W!HlH?=^v1be8q7-lM>XC3BeX>UPC8w{-5~vExl^PBI_dFdLm!-Ic$^(yw8R=l`aQ^|E*6AY11U99W$=rz?N4p>)R=HuteSX%~&p^FanH)!f^b{g4cSjTcX3vk46EVIMbv_T@W|2NEEfjyk05#8-TTzy#ZkdzBAs<2WZCG`(`mlMRK7pZKT^qh4a5>kxK=178(YG`CXy6=OOS1y((yHcyZ@FtIPgiE9&9yjn}F!@c7C!FKpHf@aT4i}(D(6weO-3oI0+x^S-jsnIsTQ%QDk3|_;ixf_B=tII4tc=CTt-<&KP;-ib8ywK>>^OlM$fy`CX@XO^BZZ+Fno3ZJ=<}2X)a$FZsAIcUyx0LV4sRudfbCAD?kyhmvyYJY&>-KOVaJF)oYrWvz6l_&V|)FD9MA#_^DKkF~L+U%~5b$Wg@kCU_zm^|aDHidr{b5_0!e#C~*Cl+^FZ&8k4G-kN<1qUuN8?_A|Qu^8X=`Hdv=fXZM`AY3)l;dRVJcLMfy$z#E|{M+#Qjli06DaE$MGPUN-8FjI-iZMbhA|@b+`lE0Jf2bqb4HbeR3J@QT3=)T3lI(%&~RVZLd>J(J6*o1V<2HD6|v{kttwQC}t1=~Zxp12ubRt#zjOB$&Rxac`8vd;bj(FS%)ldIP(?OYUG6Ty}5JpRbR)G11s5+W)UVg9UOC`M#_c{r5VaK>e!e<@s;Kl7Qi~M|R->@X)fmK;N~`hLD@e|HoUR?p?3}!iKZis5$Z5-?PUL$p@t)h43N39P_9I8N6~0rMvpWk;e~X>Jz7TbCU4MBd>3eg30QrjO+qCZ_lk6wRKY$#_?T++YMi{fiNlCkHQ<1a33+3{s;s|s?+=)T;gCdFCM(4Omi_#fYigrrH1jH>;re_FHgEZL%#YF+2XZrXF6nDb<&LfgXcATKz+@45byrqnCvuGg4gBTq`gK1<}A>c{yc#bNU2k;9iZj+vH$L0_Qvu5$oG1bI?jPl-HAOLb#a_TzC!#x7a|VJSQibW-gIof^KelXlohz$unMQ_YPo0DuqM7%CeQ#n86j?PK`0j=}xelS3^tWG|JaR9=NeyN+GC$lqANeXaU#n2{M+N|gxv}3G$4~Z=UCxA5-ec>~A@0B9Z5MTFihHxkeM1u|eM}Y~jLuGBbAa%9Y8^tI@S#rUJ#Xvh8dTH;<2b`6uM3@hDhon~oO*02e08I-z+~zAY$$6oi#$!?tA}Em`6pgwga3>b`thZx|FwaNCwZxJ5#IlVe@^h86w;qmlkRES8GFon+UM6FeDsIh-FCSOFy}JT=>1vd^ioSjpko%;=Q78K3Mu}v@o3FOJ#F|kbA2d&GuE++Wzv$33zK=TD|5cR*%d2y)=!crLWN1&c4_Lh??zG{rvDWqtkql*FV!|!i4)n7GrFjKBgI#oeE%5;CEphwTt>bkxtSdg#OtDy8gdlrKiHK5EsI`^ZKU+$JM!xb>&eCp(*L$L9eIZQ{dX{6kcV+h79Q``VIL6g#)iulKXaca-6OyR4Br{k9NET~rS`h03P>WS9Q^Mb6h$=}7ajg;}MazAl+EErZL9?z=cM_#)4Mf8DNP8^J;2=#4JL7jY_E2jYIr??C`iuA9@ODFdkM2yp#6ytaQ%#Ne9XCn{;o3zh`x&tb1)8`JUVTHgiS6?SMU1#VFNygw_ULxuCUGosfgP@=Zqp>y`5IGkj2LW#h8`+3X}1?i2TpAGB)gc!@P2(4$q6|^K!VE13`jx%}?twUN6!}FUx7*Lgk-0QN8`hA;l`)v<%++sbuARwzn3JfA84A)s9EAfpsbG`KKc|ew)FhteKKIK=d0oS&DIxTQWTh3Ui?Bn7UEZJv^_W?68I?&0NsFf6Z297Z>L4|WxOskWj5FDx8Xv*-}2d)WGMaP*grg_%(CG4oo()|6LFjobKJ(xD`dmM_|Q{cck#TACFtzE^(Gs(nj9K*cERxr$$k$o0r%2;LjyjH$=p$%*DI3mv=_)wap-wa3{915t4m`borKm_3Ib_UGX36NM9I#25nnEi;{ZguT@*1}k2!cbc_iB)@h;^5fA?e^1tfq1J5c1XasG6fLG7KorJyARB0;Nt#@rcJUSvJYrNAtP=^fK9duDK^TP_)Q}YeV5cy~1m!;#pjnWp;KyLyfZkJ?w$&hKwv2GblFFzlZu#6Q%DfJhDNd=<*K{ZR8W;eP%!*2Nc);V(Vq0en95oD($))aCQqTu>6iXJ(kaHXKzA%lgIDS)|f{Xhz>F})c+{N!7kgwimKHvO9f(0{J-itKqaGXZ2QF-+F20HjgE`T-fHTlb_E=@wIj|2zeX{qQ5~0rSIEEmyu*^ZVt5VpL$YcC+aWe9#nI(j|XFQ_ow3L&pOID{h7uFAExgE!3fleK4?=1dGE^-jW%{YsNboYJiljJ7I;4}^7yDg+0V7#_W!v0^0=Dz?|mg9B!mW~iBc3rrf5ZlG*KyO(43T^QX(=%B{XOr&*_YvMukj`MAD=vB1IxoRFYDDd!PHeckR#jpWEv`uVbHQowLtg&-?ve>sh-z$FqPVGoGx!7jfPP#;--S3=ntxs^T7j`1ysYW_8Dye7$s*I`{4S@~`cOB7yv#MK7Yha@`}GdVM4osz-zuYaBowwd199a8p+zESh2sl9NzJZ9e=kC3rLyxU?DNC-*1F`})|CABaEEpS3gpVHSUGvY{Z>7d=Y66JL_X0Ids*d6m-<7kJ~-QEtJ6?Gtsgqh}+2>HCnJl4v+wYFd}A@CxrG7|;w3_z8E+S+f_mg2UAPf((r>D=fXHhXE7fD3Q*;!O08@9;U}V|`XZ?D_cl>Vce;Y}M44Fgrg_QlS>k>M~?_#qc`o<4sO%CE@eM2tsyY9S~RoxwpxRj68>{;qeX#d42b2yIp^!NIAL|V^-`jMzsHF?xgT9J43?q7?Bl-#@B7pxG!)_O-*Rwx0kcN{F{?L<7y1%}r7rN9r-?~J+XsJryF%<{q)WI$3|u-%+d)J5d{#gW-Gcy-fOIiMWz&DkmrGP~$78aw=|<{aYPFW&FbaLt0-!|mx|+Yu*uF4)R|MpZ3lojBqUvCgk`DibO-eh$ogi~35^f78cCiOhfMQnq3}(!qi1ZEJODAd?S+#X4AzMAmZ{n9{-Jo9!lt@2EpW_gQw{H^>6AKJJD+=Cv`p(3q7X1N=8z1b9VYzIGU#%h3D6fY9qJ0-XIQ^UJK-O$w5kV1L2O$X6Bf-Hy`C(4{L`u*%?6^BrrrVw=_zaKUv6Wr&~+On%KE;mcbYMEjhxW@ho)4hOkHH1bx2-VQxh*jo1tznFd^tF^F)-U|O(x^i|@VZ@;iS=61iAQ_VfB)}3kDLvYfByKO9^>Nsz7fyyLhWkP&NG@S+`en!@6^5(DCcL6yT&pWqn`rFHfb8d$OZ{swuIpoJYOkjf&lv^pqY;-;hn%T4rVr`SVQHJ8&aDBA%P;f7OHo2cNv_Fc`cd|IXzp9*F4AW}efWmr4^H^`E2))Dcb~%q&DwOKlazBnJ89MGibqT!&q=KRnM>?6`Gm!}~A4byW?^9pH@E<8PkrG}sXq4_+tkbM^5X%3=(}P0I75pFCm#v3yjGrS!F#+(~p#K9K(6{9Z<{6r%dU;Oa4^zXF!kzI&IE3`vg#jkaow9(^zo2_^-hEU5G!kJFr~o<5m7V^q-A*UvWzZF76CZ0@|-?vE`Kg%+)L1*bT91pyQsYS#O5=zVxZ$k~I4lXI+!5C8M;frq%MihlVH#~3)XYwx2?caZ<)cj0oE6B9sbT4MR@kEpLs)>NNeHaC?&zp3>h>Z_3L6UM{aGJud#^TNFG`YKPyQl(DP!2Iv-0hbSmSE)zH4nLuTwttbX`DWBVKW8dPo_U`IE_zPpd0~jht`jh^Y+^wF=L>C~rHH>!KIQx;kqJkv11h$DM4a^V)zc^L=UJmddqq&UsOO%)KSLo3)P{Y+ntD)Q{joaLcm72j+_jNVm|27RirnwBxseQc$sfXmoKasDM}KDdSEhpkOMmtlrC+a;rqWm@N`rZj_&ErHAUQMv_@iP3!ZR@70mAv8x>gHoJ@#_iP}16IpSpfoVN@e7FTPI8BtzO&WCCv)(d1k-Ozl*cb5wtSY$=~uG2(aLnk60ce3)u7@?zf4PJ1U{fat@To-VN`_g_SfpMl4asTUcN4GDEfE^WGlbl>oFMTO>Il90i79N)iEVD{Sz4X|!f^#l85gfKGxE7R&uP4vl948R#g&E<;|AgS{4}{wt+GtMvu759Ex7!R~Px=WM5YG$A+^p;u^APuuHq`5!nFSjX#TT}|LcR1ruE6({6a(^`d^2?!h?Bmc#iI;3BA}u5>Hy+zUO%3_><;lel-)t|+JJa;a=?mEF&Z=vhgzS}M}6gBWUpzcMF$P~*Tn1%sIP9Eoi$pllLgbsh4C=v>&iLD#*&sXAZl>m+&VAxQ9L|htTaRTpL2~V$&@*3ryNRZA2MOh;JleLFJitc&LaXMo-;l@Q7xPFQHPun?Ca)DW`l9K(y=5r%!3M2uk~Cnvw@uR>@*AW;4bI%xEw(a^i7O<*+Q99Pjh>%E2@?W8{yacCv4PLANR-Cn)=aTYq)*;dWyc%+je@A1f33+QY(t`BT$Es^&)lo#Jcs}{swOW)FDS~y5gL_CgK?>B^$uK}nh7U#24BCf#JJQVtan@dqybah|M*&pzS<}7a#y=j7OYvJq&zT;aqV50cH3w<13of-UDCLKas8%maA=btbX4Fnc@1ymPxc$!=^}9dFPY91Uz$P9i1*`BEdE?wzgEP3w0Ak1E@6Y`y7)R|XzQ28Rx2f=b^z&wxqDGqbBsDzcx@lbiBdV#SbWOr6z$|GF#?vp0Ve^9k{{);V3iI~d?L-n3ehGT)Y1u4RsHWI|%)S@#SLtC1>K&Pb1b=t%kPQLue!;C%{G@7*@>Y(k$uy#>Zl1DLVJ(Tpm`u}+ke#dz@2#h+};bfQD2esCT1I_K=_ou3I$5IPc^x*ZXvM)lqiv=!E-)!%dK>Z`vm{go}FB&QiORmnnjrxkTU-ouN;D7ILD0S?7{l6p?W<}&?1{tBg>O8keD0NmQkh*EY4ZQvv3BgnCH)-H<{dY**U&NpO^d@yN2q$;8U~Q_et%Ksu#o!In$YFsdGT5|#L2mp^}|f4uS^e^;E#A=xwZd#4h!l#`{s`ZBmVX0w=1h7t^ntNDLKTSTU$?xDWLOxDa#fjPTnWMUBr4hCN?~4E=6CN<(8^;GT_t45-F}Q;$xm`+#GH)VXAk1#k)aDz1BOHaK8@=%xcya&U}YBSx0f69tqE{nDkGRK%K)s#|pU$)tyc+%Un<|k#jvoZY4pYc}17KAHIG`!`%h*W~akF$yJWm9r5+td9xnawPeC*;kJ_t*5d11R7WO0J#sGyi>hEqiq7LDoZ|!6Pxxd1o>?fRjJ7FYOkp(JS1nA}zKc&*lP@$HWEC|ZCO;VXc>FcKpjh#5ohUcqnMN`WV&xrAJ-ZF&)os?3LA=u><)Z`@2xt&W#Ckvr{h4mq(t;b8d=M>af6J`=iMZ8W7+8ro8*c5OM#L{nO6KpPWB(Ac4*I-CF#X;uGc8zE4Y$17sc9epAZ+kN&+*t?pzX_hrQ&;Qe-L+BLV|ZRtSv(cb!k`s(Z5OLd~kG&pAEaov-m&u{Oa`nxTQ4sEIxZ&fxT&*9hpwFd}YksSAR^St@Uhn!PB_YVWa8}-}PJVrbvXU9x|9wt0CpKH-;hdfFB*_F$JX${*S#8Y$&IbU+bhRyfQuHA_Ggwz}IU)gZ9$vUe3D&j+nq-P52B*MT3#aZjRQD2e$%!kWT`F+hhDE*j4eG#1@R+;cN`e;zU59$-LKlk1r8oY~iGTlq@TZk$v=IAs6CPm!K;5BX<&y!~B~n+*D+HWkVPsIQzg#0xG7Wq^jJK-u_9)K_G_^R=Xbnax{)BViO>_w;<#%NKN591(SUk_hS_>)_2@E;0-_eAx29I!b*Mx&E=D$2c~#2p?6zSi;X&^zGyst!V_Hhe(S}Ke9%dY&II}p$RwX%JntBC(JpX;uPZV_y|J;if2c&<=a#z$#q%T%XeKH8s?q2zP0$)%1i#aVM^dzB|-yKF=$STWvB9Yh5|Mj0ZX$M~C`2M}TC(U#y>1{Z9e=)wE@4GRR0XJIDbnG8SU1YaLEavAtCPWz(X4O2R=q0X8+?k)ufBdpi5I0yNZ*!#RpLJ90Axht()X;I?w{!?Qop)l^3)ENp9;_B0`kMvh?{9W1>X1)UI^CBDGT})|)%B4W)FJyz9&MQMnF*t|2~zUYFt2T1&)!{rhsEy~OV!1Ey+(ZFo&@jh18u6YK8MTP|{suaeJ83j}~>R$$(h5kn?d~m17>%_?_`5bP*RcFGqi&9mG6nDV-X2IgShUJGMLwrJRFI`u*Zj9r0Y*-lA%nb2W*#N3=~5#No^;4|f4(!*7~>-SB)hI>!3u|g>;tl>Lj;}JHYZ*(z?bb`a3BW1mlL(A>hE4KK{#{A?Z{S)>)CNt_M{RPJZ9N-$x!qm>CaXi$OevO_%+816#j+ou3@qq=$bx$a@$JeA8y~?J|mw4-@d5Lbbf?*>8#g94$HXw_4u=`nBPfVMUT&bFAZH~{vyg$KjnXSqX4uqaqAHMYz;u^ndcEE%*m=Y5x8h0P>H^-DqappdmU?rY^?Igvgi;Q=QEFG5Z6})+#(&xDJq=ijyR2C@R`g1|Z5_yK4b1J9TGQjTA7o#~^$nzEp+{yi&-XF(Pv_B*M;X!!5`)w8&Ez+U=I)gl=4wQdrCDsc+Jl}=6QFIIGr|?0Z1FcNMkA2>V@7i+Nzo&o$tCH;^1s)+D_H3aOM=u%DoxHZEwW7Xae|T+U&Pj(K6DAlX3VL-I&uD&)&d|%QZFK`bN-brQDjOQY5;h;w2?O;LZ;_yXvi%_?W_Kbg8qQHg&=A*eAD0NK-Rd+gFZDvEx0$bPiR>Vs?#(rETzV}$p{9s!t)F+ERP0HvANC48;b`Bl+*QN_;2Odi0pF4-YNB$P|^N%~)Wd1V;;RWg|>9eL&nDTTWWWn_L(fGbr>Xzd&=~>Wy{*B4O1^B*hou}eAwlknSFlF_w^N5rFr8nL&`93OlTMEbGepJF?i-~hjvEkC9oJ%xg#A8>NKiQ(dfzcjceD54byQdH*uH%q4JIF-v$>z5uU1W8I4gEy7I?=-RC}qT&Z#uNFxSwU0h+yi%uLF;-mP)_j9y{<~wB#rpvVnFFx;K?61QD3=x>dac{o(Odxw^Y>}L>;x@W@1K)Wg6JX9oyN{iMX_(-uI6;Gx_zIALLQbO!_0WZRdVMPp<9z>$eHc`<$-D1>5i*(;w2Y01F$nfvJ=v}Cb0=TnAmWXG9Xm``!y~z%ID{%;p=;Eh2|;6F@f~Wig=HD$yuHIQq-RXyDMKxw3i~zpAWZ!4Oa8NYhFx7eDcw!m0!PQ!40q0b5|{~-aEG1Q^rS_35VA@oIYxab?$Pz_SrwQU+An&p-#C>E8(be>$kfApNA{^MC-f58KCy5LK3D%XK8f8Unhi8h+49O;me`UaZy^4<^uV-x{7q$GGNcRkr(ivcT!$>y3BhFkkzcoPM%+8ykA3N8Sy#KpoPXCQ=eOg9DzrJM~Rz7#F$Du_@vFQ_mcP{A*2Gp1PWHq3TDl@KSB$zcgj760?B|Ztp7QjlM!WlPz%8cyl&nx#XG{n`=`-d{sZ(l6kMUEjXMx&_!dab^xe`%fOQMY#Y>2PF;88OXd1|eG6BgjefxO$I&sv@!z9y5YCMLiIaz1U_F^aw_G%i~j$%WjPtK{p%Fpry-Sog#UXT$0a8OhPBh{qW|`BK%E301ewOB#)1T*DV%#Eb>g`TYe~H{kttROHr9jlL}4w!g6MIg4=}O5V8Md<7Fizs0PvxJEg57F~AjrvVH0-_n{RUWoi{mm2glHQA6$YjH5Xfc#0_uQ$eqD;EAr4LZnksBz;i;BjD4&+csl6hHIjXR3`iZQ_EK<|BJ!Thu2(N)G9l?{oQmAF_3bllzJr#WSE`h1~Jia(KTn(Up0@B}f$5G_J?CJgWQ70H6(k5!S^b+!)6sdl2ynqSrXN@%BTjDoe>ld4&sUaDKQ$Zm0NGEaqMr(6Us2W=rM`V|bUbu>Cg@}c{2ULY^gFzGBENeH9ZvLqZFtQ@{xY_%>lc=00pCyhD(aIr7tWsBJDXTPwkRE)V}X2#$9qMJI_n?bzfXuC>2-|pm1V<5VKvhk9>|mQ>$m*GhG|=(jGSr_U-30%v^}1~pNG{Yi~5AY><{o)<3dL7qH0Z7#QFVwZvX6?mzSWv;``}rPKUv(~unpP%=p-9FT%+!^*&;six`fVxH5|B_S=J~WgZRMvNp04IK8xJPI&MYrKPTs-uvqc@epnGM>MPP#<@9*UKmAiTQC~^uxh!65kO`-peh(a>=rr>D+DMHK&Ef*4>_3P{RYX`!BEI*Le!(wy_Mpxo=jjN~VDitEf+_n>g&mx^rHU-D>}vSFxB>BZ+EV3;qQrfEK3rI`AMrr(51j3Ujw0)_0;b`)*oxwHYk4O)kVvmvQTsz=dKjfYju6T&Ni5hoJ<5|Fj(EUI(Vx=ZY;aCfebXF@c(pdyvv?r~R&HCmq=9mMa=))kDF%q>=IxF|eMPoWPMev?&+i#?Q0L5d(|*K|OoQfquZ7(xb?*<|w`7-bGa>l-D%%4-h?71$cfINV^c(KO>#Y5DRaEp{7T-@&hN9CZNyO`hEMUSPftk}K)+0{N5o=Lk!Sak8i5_Xhqh{Z^u|l|H`wvA&DbpR_l@fXX*#u@UrH<=W%A4f^O$@M3un^RYM}0-s`IPrEf$YzonSlC=^x3cLX7T;;EO(>6%6#+d;K_$<{#G-yH#zX^wYJQ?opI-&IU)j?58Yk%om^PIKMZ&$OdN*ku;Bwlyfw}y*lsoc+eWQcflZKpM2d^a11YZdf|?`zAIV|DCqj!W-iv?RgrB`^tEAxLzj%eI19j?(Ux0$pQb#gThc?>U~4ZA6(vbnNh3-ZL5->{lq>_0dEAJ(KhLjr}=%zuaBw$p6r{eAz3iT#(OQ@o~X##3dT11)4tMf)4ZSPhAf3C;JPSX4w#z^mL?Fk1|(_;Bl<_pXX5~#jlb)|6X{H2JSD%Nl~}Uf{eAFEo6gHU){6xezLiS0lcG%1C5ma)6<(aoJb||R#5G;D{ieASD%HI=dd^%PW1=&eQZPiJy%a9cK>0+USSt~k!#4G?CX}Q;y}ap2i4yDkmqEl1HWE+6MCs>!S0$#s6zsOs%p;u%Y_BUE?(F|nJ@N8_~`@Dli5&gwaxX-IO0M!-L0+rGvU2q^!4XE@pq)pVA(5eqr<&Frm;?&k-y}JgPY`gv-tBy&mIb1z*F>_L3~>B7<=^=$Ah+q~nb0qOz1Khj7Vkm+aFtbh4;>XP-xCl=D+M(79T(<_vH&I~DyG(uO9zel+$)F;Br-8#$9GT`(5_eXOn{#v}L^l!CIOdx$Y5{@DtpNWB)mwQ=IEL&>qDvo?yHm@F4d&Y*dbJ?~RV-T;d6kB^Kl>>I`cg*hpjrjAo786_zxghx6jC;lmb&LC}7I10f!rxwDk(>m?`99{8Q~3T@1`qzXzP+P418S@VmjqGf&*ofg_xw0S1BTC^@OAU?eJ6i?_V8>$7OdWRW2@9_#NQ`WNNiikgxQ`2+;_hCzHM7)pF3;Lf{LC6I_>WfC(lE*%-L{0Pd{@Vpl;d6*|D`!nF9hB%$XfwhQ!7Oq76uVORp_|EcnzlmH&OPN$o+&oUKS{LA3bJI@x4?#@XA@6(39zlwL0cyAbxX^Z$+;b3rt$)*f&t-yu5bY@NGbq4Nb9{+(r_j0y^L2>lUf}5%!72)FLK~23&*Oktt-Gi|0mUb({+ETz?%02PLVQqP@%`CWCIM;Bu|)`V5#P6PWjfz)WRex)FLOrhF0G`2hhtFG$w1UU3rXXaK{}B0PFI}3*WaA_>#+{;{N0eIW;Ba(p19(haFZsD32v*kMw;vp=f2JtT*_v_oXx(PlKO~`PZJV&dyWm9u01xtlo9`Syv6b0CJsCkR;FuAN4zP(__e_p6Ntx$DK`i8mAs5>r8)5&Deigb_&68!)mfUTn$9c^?0On;@Z%xWAuq0~-Q^MM&|=%YS9<$VhfKZD@pi{eE=&_StNB$6^R(6^HdJ|h?(EdYyl^ikeA320*|2(T@YA&+nD6F|?3HW};qjmUDHPxGbA#e*TLyS=JHsL>V~mmqkL+};-kk&W)kaU+)9C-bldYHlS-WrZ^z2VGdd2Hi??KZX2!YYhQw&K!NlS$bizp>!mhgTSvcK~B#7blzFr`&uK*W&ukal=-~-H`ywNG5P+^y;?qfUH};+eOLyqeAB1BXsB!xUJE;oicZcoWm5yfGd}I(aYi}`ii*Uw2AxQa#!=u1;rSbSxjEi(v@s@;`B?#?*qmaUu*c`j}8ZVTc4XPr1S}vxtS(BljTCC*#c0mrs%`9Q<)lXxUkbrA}}QcdAi0#7kQo~baH)}eW?uQ_uF^s&s&P|AmfVWTW2QX^%gR|qZfJbS5IlPur%gV&bXdZZ8i=36YlTsa>x6P^f~`vibEeLzMa@WpRa0iK1+H;TT}nL8)IN=Rx#q^FVAjBfNo9k6oQ*S!uC86Lz3@(i2lYvAdDOE@+p~ex`+55j-`V2Fqjt*#>`00r`-1YzOKX@bKlE7p0#NXWeMgyS$PGa;ldS_npP}CF@)EIj}*~c8k@-5yZ=jIc6i)9I)SEH0822#ovIb*0y*F7f$5ea6U+DC{<>%c#n+&IJpBDVUKz&tGd-C<}k_`CvHNLx(Qh#-Dd-s|Bgw8%p2&2cB@cOe3XlCF4m<0{XuQSyb;`NVv{d~6JAQKE19TB95A^!fvg1V$@EYSAb>J{FC`0Vn!x7W+r;LxhkHa4B&bH01|59=%r-@m$B8*!t_pa1@G=7Rg|pJ)E=qUf$6-EyhP+3+`iov;2u#B=-u(`M8r0I>`XDZ7CBYL(My&9HSEjNee+x{~70Q03fm-E=AqdX-aOR}LYbxYF=*lwcN=U7xdPH|1Qf$OfxzOKRxGc7gvOl)^)fQ9FI3WGc9#Z_K$o}@F%Tr*9yp5Ia57b@x!SNr0W@Z98zdhOr_0qt?rw4y2(7~_0bjw$N#BW)NO}zdp3&{0u@fpO4+e$>qlnKAf6jjBKBTm+Ji=QF#{^0WBb(DRuy}ntGo)S8WtZNFkp`1VJpSL3YN2;rii?#s8M?(ETR)sXNK8m04$4>=ug@_vIL|ZmouN=Jh{0r)cW*gnn8Is87>w_MD34ZoLMb}7%{&oA>kiur=?Z@eNG$aTQuCG`J3H~ycfTu?K;KJR%0{lC|fb3`OBut2`PYU+Y*7+0RkA|b6ZHbiYRtba<;jfoxOb~?{Euw`TZQB@<1YnIQ$mb!;rc>ZU2d+l?Ki(c~1#4sfri1c&v{50e*C*p4Wn^?DaY@PeSVlwh4eTFZ5;eqe#tNl{lh)b7DJTm)84sa$&G#q6k|NSST8#_Mb@aM|i+JSjQlx9>XyfYVSZ-*@Hru5ODtymRU9LWUh#^U>*6fv$2!Ko3ei9C|At7)N#3&yosE@6%BVh$XBnDU2Zh&qJj?BXzUB^UN2?~%`;^lzU0!!&p=oegIzGmQr*e(YqQuMMG>6tr#D?DIzc9{T$ZatNKU!(`j@uJx3C9s}j=J~BBly(d5F$2Y`hNM6|)o{|IVa>cTykrdx@&PwNwDY@`w-qL5Q=3;)lCc4FX2eD3BH@V^5P&CH%`F&t=DxsrR-n(z3{TkyEoS}W>q&*w95g$atON>kVy+~hw1c&cqrY?s3$+_N7!ntr+w(MrpT;xeUXRZ?Kg%1)@_b&G%?tAg~t*O#H=t^`mdz^>-N&la*TRgD-qH*U9rCwdTo~6jq%YlYv{);|Q>cE{2{POjn`h38#-@p}>Yr4w?D&{6JZy6omq&Sz6(xTQrkY^Xmpaidu;@~;-pIV{{m=qTwM%T!yC|FWybrte$0@T~5^8&*8>w0iT~AUr)A;_V*1oxGOfw>f&bOL7|z7#B^{R#i~=Pc@lc+s=cN@AZyFti-(k^wEd8t;G81cc^vDp9I7cd`sJob7^qC#Ms!i193&F0$aEIumMxl)F&(czDeR1-iw7H$LIzC)xrnd(^s!`i7zea_Z|I9EQu^%P*L4X7abYoQTA}7S#I0=&KmFXC4N+q6rwKkq+)29FMzVX3$ZL9*B`o+I`eRY>FbN@*zin#b=9g7#E&tTZVqnYz~lMFQAa5{>Z-}D$~y&I{+x~=SHug&YphlGXT!Sqz-N0X^Jtj#!l4Wi9^9)uGwPH@@i8FJv&@tE^HW;RpuXbI^{&i-YiWIK;eDv1$p5ciPXA}#gdqAeoQ!x^zF(FBMMWRe`rS~^upAXSUfyKF$ceu__Dsa@UrX8?F^vr?nuqd(DY}UCp&KHe|2k*SkMI6K*^hF+o9imh1rsB^n;}0De|GJ9=@ddY&kt#zV>gEQ-flOO?(l3F3zc2rI{|gnYvJo}KHW`#6}qce%B(`1zpv$<2BclA;5*b;q|a)(G&B3*_3`P+wWy`(rB2<3f;~<;Ac!s6$Rq78VnwWy6{1gjE7Ln6JCylp0KectFm5TD1!Enx6XM?&y^{uwAgFW#WJG6(Y=|Ie#j$a(bflxr~N3-Y;UO?>Vx0|%B)(4_zOd0NEFUtUDdgP4MY%KIqiIAlGWE|Evby1$r}7}qX$qtAik9N6?t!T9uEjEk&eSwO6>M8m|a$8|BTgRZi_=Zt1U&0)5`TocAc_H(U&z~j#atEA|wA6xJ0_ypuYhmEl=H0_1Pc=C(?byNTvvy%zgPq@ULS48pu*?3!hz{zINpDu3sP-hj_k+nBT_`^J&!vpMzTd(F*NMH(Jj(aN$!-M8$vI%Usdw6vgUJ8KX_>#doE(_-CVY1v#Si@EG1FrnTDd^ZLz_XV13xC6BGbgnh3~^dd0dLmQmBZihUc6-2)-dIx>24oucWR!AK-M{lE3pcioM}SLWu7GoXL!i=e7}D5I-Cw)HTA6NYe`Rj*%>bbp;14A>65BT>WfA7hPL%pV4=w6;!7E_2kH^#)s_84V@#=gksD|R8DO@Z4|tz>y%d@w{k`4y$UUG`_IUn37lpT8uEZ+Q-)!a)%B$ms+e>xOUw~%w*&5vh8me5#eJmoxY%%kp#$42707dCJxxef7UN_+jA-tj>8^^}XM(x_W*EPL!-a5x7HPsFSb-bwM>yrCNYq$mT57S9`2NI-qHQ2Z)A)S3>YkI}QcsIR=#S4(IfV!$qgk{TOIeb-yxyMocnSaA5`GFe$l9ecmN*oWR!HY~bYDt3&9IL$;fV`UwOKPR_q2=Q05Z*|^(%mo2W|1XDDqb?%r*&;Kt`RmpgPsGV{pJ59g+|6?=7`TG?K6a09>^B}XZjn5ED-ZFBjVksdd8zQ$X8z3@N7PpZmyTZBEJy=C;)nK*GViZzNw-n%<}AKXQCBbG720oWE-Nv?y?x()AJH&}}dFJB~7Z{e6bJqQ$^c!~n-23TvHf(Tlyw)U$dWr1Yndr>p`x+%oMZDQaK5Fzw5;%Jv@jW>aasGK|NCv;I>~+b%c%$xccHGnuSvvHK=$i>r`u^mI2br2Q1BQxhA|jnpM}3a$yVzXC1p7ZeX5T5g$bNkDNG{obVtM%8`7p%KvKH-HY{G#Lkt$zLoJZVlH@(QtkPF*F3qw1D5hs1M1f;TIL9mmi)j`DlzhusSSf34kFD-oY91$mdq&ZwJzb;N98ugWpw2QKMRW|fLHE}M8M;(%7b6{WHT^^AAQe27-A^VK_<8t7PWrWOzuXsL4&S#?U%!P}U>Jc5QP=}B{ax#Ot{JGVSH(_2NeU>H8_!F19N8dkiz)asLUp?DY)7>JU4Mjl45xYSKj$1vosfqL{bELEGgg1o}#$2`dsLBZZ>+c2zjp1oAIV{S01d0J6T!rno?J0Ff-V{HV?G^u%*RLQ2NxegD!v6$Oq$h^BuaTVtx#}XI`%TgT>dq6O1vgqk8&Y>q0o-`dPA4J{jXuE`7N}r)`W5mg_mjQtbAhaXnUjkAFDugq$+0U(F~>@cPLCw(Ybcu>$0uAoF%%z^ZH@QF@U;SX+K-}>7-6(f~JRtp11k_OvoSoB@KPey&TywPlDqlr>!j9^*mnolgQT`pCzBu}^mCmK->B6V6mp>e%gssz-$XUFYkdZqa%x*f=FD7f$X1lK}GkWpyJmo@V{}Y(TH-68ND|W^hFfz4i2J-Zalm*c>Xvj}AIrdqTyR>c)~>q+aUVaIW2%d3{C>KMSkzZ_ymh=8#P_=Mnb3}q>!`1u?htjaDrCY#Ri;NjrS8iJj4SWCv*E__X9qKEx&x`bPuIc^!yWap`zego0)s}b;S}S{~2zMbqNm5|0ur&+(`W5C3Z$teZ^v+@26ClW`RIfZOR;3)GbeaGcSD7XM%XllTUMPQD24Jt31Pd&*J-;6b0bxiwoE?!g?Ioc`MxZ@hQaf14HgQx^O}6=|M*`iXJ2V#UgF8`EwYZDc5;qa6L>ynTR*=r>cS%WxmhtE!r9{c#s#;>hWz4;`~0!B{}f>e5FVG9rS0I6{SJ5-I@y{&4d6eMI92oY4`B8O?ePI?jWLZ0rRy#%pN)+l@Iro)3$cbMIG|=;>$6wmVBrmx$1Jw8T$wMf7TShY(M+40A?NbQ{~>lJaX*vqrk2?h0xxie0p(%^uwiLSa>s@LqZ@Y>068a6;Q(b`On&T0Ol$#+9{qSHb~XJ!{8Ph8#-Hi}IKF(z#&}Bo&-VPf>XQQnuz%)p+VTj@FBX%sV#xJHzJr0`7Ez3AT~PGYt@CoAa7Di20TYai^wD3XJRPjcIk4rsspZafQ_Uag6Km<#p?-@8$E?%ln3~uFP9OYkv8X0vM29ER|Y^{1+XQe9+@r07DJUr)t8HzqVa>x?x5Egf5abuU5zWBEP#_XlH!^h%O(Hu`I=PJzIA)+UpS)hMKr)4Hq!3-**CAz?cVPLq|GwnlY|yXVo#G*c>=er7}g-2KkfsM=B#1J}=bQET;IolK+(>)<0xle|-k>|GMmbFxN02L_8I|ZO&1Ax(J08(3203&9YC7P<$jNSYLB_qg?>{9lk${ejr{NF28oxp#uJVNwHAMzKSDggwYDXjT6BY7oyY!xgOz_F*%S`clbao4}V8j#uN5)cV~m^(JvlT2QaRTcUcc=?(;xOvRj>;XZ0`MQ`cqd^CJiHm2ayX`y&7I(GD%9pNMr(z>YyVH{`j$xy?bXBoB@*Ub*eda?1JO%ePVo-SR=oOz3bxJK|zR2|hE2^1v)h4@+WnG$l3x(^m1Qj-%IhE8aS9R=|BOLDL?1#v_d`bl4Cmgu{j%LCEpy@Vc#zboM~G`5b&N|<%mWow>E}zeP|w)5damU(c}KV|&pQ`daBF3FaUX{MYr%G|GaeVY%A(Y2F)Q0lKFURXYbP-mykR^12$KGx?${awu*aO>hym`=*dt20maxU4=9I<>}$oj53JE~&4rY8S0X-qL_Ef!_<&5_P_Ta531+R-@-ISobmU)ZK`=be}3*WKg8LE_vQ^I&>`!HnFU;TkJu64u0Q_ODJ{hwYS8r$0YOMhN$S!Wy(I7TXnn9{A)zMNOZq_vl($Qp+}9}nKX#<6g048AWrs+KE9Rp&s=Y7)K~8lmwsy)V#1u@=0UytsM97E=ekd7VFUMG*bNKH9K*vp83H~ITnKo*CwiDt2W7Kn+khD>8#YIO`|xDV|DFR1mGI!?B_%!cjfj)$$we7C;B#c{qOBVcf0c3ZypmHce3|`h&%0HKzcIU%@NNA6^Hcj5Z`AeFQ|Wuxodfr$bTuue%*T1x@#p+$u{^kSN%(sJWj@aLi`%V|=jKD-CHV?we)D}cW3A?_zkny=p9_O+&|v^38&&w;_LuB(z|=-+OnKRmxCJ{MvS-nezT1>>5pvZSEAfLK?$*ro_`Fs`RQ;dX5q`S3-{-S7Yjgq(`5Ti8~%^JYAygrmA&hiDsy8`E$lk{8zW%sjGT84u9XKr+-G#Grs&4_z-JR3wDQ6E_kfSyX8c~JDeoH}o>Ty&Kk-G%{tr2ywa>BOpMJ(d)K{B=7H(0?DF9*jPz3`@U#I$-vt@6-6oBH{R|ZEZ`7v_2!L3BaLNNB>o-L-FTUlLrHT|MRA&~RHMJ7ym#^&YIdEu-l~>PEyx++ETS&|W5Py<*TM7B^`Rb%GJueS(8FSx=QT#=x?4Dk<8j51F!X2YgB@!!Pn#XE3jn;z!P(z_Ez?Nke4`@-9qJ>`g#{pT4)Tu{$8(BBb=`fA5=7m;xykC4w9u?CEbSf(`YB-W*GI;X{MqxjFy+cD?Fd67IgbZy3~COyiWLHqrEqZ0{zxMKG!>*dI^D6uX0+|zt;S=6(;X&CXf&mZ^{=oaw%F(v58b9gLezFJrTw1`;^Z`Z`UAEdKPH}ydQtZKez>P+#Kx@_w-a$uwYEC``6MCpUG2wGq1*HKQhh7?}ePhs_v4_-yiN=OgUd>3x4bR&4cQ(Ev$jv$g}HP&TCV{Td}57mcxttQqH+fF5W-KXpy)}9G3>(7U~w%?u%QsxGhH!2#kw-kWc)pPoqRfyNBOW1u5FMx8TxFxJbs1w3|8s-XB6#(grOb;>vwLvSGYw^}eT+eZo(VJ%R%E=74p5hvX!R4z%;X)?yTy3uN0Kn=+SKP{lAl^$hXcTWoSRCKGWJU3o*8}c0sq|a0Il~hMgMHR80dLXna_>K}@M~5LH_rs0{M+B3nxZFnks)vIpkCg*{ZstBJOHsFYZ`i!%8|laNzON(t45hxkE%mHNd>*JysMacffVkC*Km&7&eCX)86gx7CxbBr5=~IdOLHk2z(i&ydISZ1uj4#+wz&~eMOF8covsqib^?eq94)q3k)K|w_Gc~RsV!?8wMn}0}ynf4Md(;(vkxwVp)1L2h=%aADT~XE*uCgkeU-h=__nd)tZr<2b(7x`tl+U@vxA#r`xv?>q?`h#}6p=T}4V@^1dS|uCclWK=ubYTEC&cTnzXhR>gNT2ybs_F+*^q;=yLo(kiYnsoe3-2Vh;?PLkfgu~RlJTs<%QXoT5@4k&||NcixBUzEuL^GHV-UiUr(u}_%_@~yJ5I=O+JwOd9%e3*I2G5Ztqn9kKf$Osy-C?A1+eX($Fx!5CRSwI6IF={fA2%SACz6TL`W6NuJZvP@nJuOJtrey9P_X&_Di|iFv$6;7+n#$~BN{5{i&8!*e(C_dI#{+CM%vcK_zVPF+U>!^xIgia?`+JF|El=J&$o`lfyti~jllFPIY28(-$U$O?W6cS_{>k~zhgJlSg?yK{Qfnm&w+yg#HbU*q@NzEDm1@Adm~J^ehtTm#bA++{iPC+C`XtSjQzE8hKsdhB%Y)VX3Oi=gfMppm3W=Koy(_{}09FE1*Dx+V1K{7tqWih!(x`+rnjd0dTM*A}Ieic(S$rO4c%QCcF=K%)kvB8m(t(nzT^Yo3SGJfbtCBorztDw>f7g%S-^LcVh!@6$Tp`^WSCp7pz*)4s2J@3pSI_gdGoEo3^!qtmB?WyRp5s-L@<1$na6b{b1rM=@MnZXGm#9-eEBl=ZqC_auXdW~n9r1LR$V49{0K3ZrkkmrU~9-zDzNW3Esb_cARlYF9V;G8B`#20e9PF%so%kvn0Qw{?mtHK|M*Ty8b!-ygN`?zgVQ?DZbYe&kt?U*~OruUhUZP0(sYVYV3S}Lo$5oESk~1ir=NnDIqbdmkjeyeCjah!g)pL$GIG$z+11MCpI&k3l-IR7G{@H;KXIY2WQ%t^y=4T9NWr4h22UgJC7&h_^}^rqfU{Fd>fg7qwCLgss>Ji4|Va%TyZq4R9cbdKcAEhm5A*KPPHeA3QiC$5)u9amG{TNXpG{20#?c^vK%8ydPB;(6wZhPbjy26>4IKrv0bCJVK9C_+6zeiot`Xbew~UhZFUN(X90SX#?AqJ6<@Rql(!TU14N6rB(3FK?whDC`U~d%RCB_gF}x%hX9J`{(F=)6}zVZjk|{GI!nRz-hr7K2Xxz6Ymz(cb*oRdJ^jnMi9kuHBEki_kX?NhdS<4K)3M&VEZprj^r^AOs(wbh|7v#0O7>!?sZ;Q#Q!#|?vf*e3T3>08&iMhbnO?bMic4lMeXQ2dpER;R~gIw9VbKc$IK9LL_3dPV_V5i3W%y33qL=BcEk87B{^#{5P1j2?tyc5dH%&8%LOUWsJktBcsgv(?sKy$h?hcvYn$&JdA|ztwQ6Ml@cmSvfcRLH$r_tcx04GF4`!ScxEN5TEN}?lYl!_)#JM606uc5_U(XdY_xmzO16t3^Qz5CI+y8VJ#&P$w0*zDIRAAq|^3bPN?8CU(;@aJxY&00)ve?(uhv#^1D;=L%9HK!=dRf2T{gk=qZ=IouIwa6QcD4HhE?XS`h20_T;mtH4`bRx>#Q384_m0Y;1tqX1;_ld^l^7ohUE_zF$k4#4S^nr2zLy%$^`FDv$w1#G8o1rY_iB~w7ivzX0Fl4^>KuNTz2GMiK=+3cyPv-JJcN9Bm$%EfcOn(8>b2!*NgzKl8_*bd^z(mwSQvG{i2TX>`)II`$L{lt1CGD$!j80e!8DM2H=OlVhN<7;645w;Cp2iR5WSq+kM>H9!MY_AG}yoKVfvM88FTjPRb911v&BF@<9`2AD9$&cj}rSUG9-PPFsO+`-Z;V|z3|9Y3K0DscOS%g_5N}BSRXeP&X0|zPEe6IcCiY@{<=m5jhIBWCR^l<#QsORmkRW7&GPyHjh-Az?ucU36!hewlG40x)4lv!5N=s~+SCvnL3nd4RD4b@>Ghb`vEYL|`FBYR2Q%v;>YBt~Bs@yLIB3~nRJ(GTjFu#pI-9Id*6R&_ZIQ~0i9pmfz6mZ#}EFf)x_&e|NtS{=N`~QWS6UENRZ+*EB-f1zT^E#it+V~SV&R;_Xz*bI$@UExN|H$Hai1USooHUR!B~SnOz?26lS9L*Lj|TD;=GV2nm~=k-gM!ca(HQ5(%B;u-hP{Rk21Nx`!|i);{64Erzp>ILgAmv54E^$bwK(ah{(A^5AI@W~vEtR5FcJ%ycvB&_ZYt!h9237fz0{zxg$jgj%Il|0d33(t{zwYbfY80;+J!tJN$jdUn+c84XHcsM?Wb(Ymo)m*fY2d6xCr?}$`9$<@8mo1sPuE=<^4F$uurL%LOY9r|LU?!HJ5OlguVwYn+y+f*xA@l;&}9zOGl4sQ6Rw2;&sb9{JZrXO)s|8Qy6v7$E(p!)I|!={rTkZ0hcXWIG$#+U#fS)sG$4w@W)0f+8en2Rq{Hhkndn-^qB|w454$nemMF$Z+Y0T{VdsnL%Mn>CDY-ZANCHhZ?uO&nMCJnN!5dMyG)9$miEp$I`vhL3?+5iSkTYVf(N6S(^HHSlkJLO_{d3SBrkZ_SGl2fxH!R=q=slC(mz2;;g9a+JFMIYyo+;l<>{McL{z4iM_b{4@Xzw!re!%l>5p?fpU2`fIf9KoHse)?RJ8=5obLBBTCO#%owm>tm7*4<0#yP)|>HO{Mr>oWb$)Mi<*qgKj`OLDB4Otw6WSIWz_}GK#+-$E@Pdmp+`hNfW(&=Dlv>UBi6&Tk|3u@$FKN$Rr=WNeEw7je=x%02TIUsLgdArH-EuA;^QaF>UtdK7e{)OL+4EKyw%pNiIUrsB$)zLUW2D{??iEyUAfw|PEs{M!Q`(?g+Jr3v5K56~HfclWasOK`WLwjTsSN#xpzBd{zwgUa?mMAMgHeZ@-THhO$A35a~R({Y)Tu2v*Y`TsF8Nsp;MbxO_}yn1Q}Y&i7oo=$Ygz(TqH11SZ{hg+K0aa>ODKWZ&v5~#vT*zX-`})*H_tB4RxLu@hzHKqF4;CAtfSQkpbiEpW7ebHDEP?v(e1H|t8z&Q2En6Z*=Q&mvGpAktzkcj!91R#cc4^2PAMK4??eT*KL|&VI6^_3nNhs1uqXcr{#>59A(x>ZZ(`SkFnzp50+xv*=cVaTcyu=Ft!>$$*G-?}9@aJyv*qmJ^}Qse_{3Lkq~qe@^`i|4!{cH_{y_8<*bz|zlQ!$uMV6tRz|BvD48~6PsyJG4{OzZC-CLJZAb**v@Od^I&)WxY*DYwFKttSet5d(wUa*Pte#==Zu-#a`NAw9(-y+#n*{?oR8GWe|nEGf_xZiq@AD}VrM=0OWUKe;-Krn;Ohm~Vps+n}jMv{IN9{)&#kxg#7;!O9UQwi%Z|hP3J*eJ0-Z<=2JqvMa?fbumqJy9EB-%Li8p&Ull7$PfL-jlbXYHQZ*I5e2%Hq#ODlqy5%FeEg`_cDIIPKOwd@cGoE3{~!B#^&N%9g2*p@Z1CO%x6E^n4VZne@Ic_QF1m*ECT5Rd;)F;tupvi}=_@D0j3*=Xo#mHNDt$)k=JS9W8j;O2ERjsh2D7PcAeLi+{k6*B8L3L~%P!G5$e^ooyB!8>Mmu){v&X**8q2Hbi;g<(bh*PAu*`5dcIY6&;p?{SV($?9k)^iq8cY5(pq74dhHB6fWhr&&Y8s{=0v-X8nU{%FX;Jxx388Z_}r_-d&c&Hav}=#`SUqCvnhFHFt-gYKNY{CY=1Uu!tHe1CK#I8_I~JHO{ni?>nWyNOF`HuAunec}GJL)QAS5V-DsLNmo+&QA2tdSn<6`h-x4v+s3f8A2(mce{IfAiK;O`&#kh=3xBt){)XX3X@bM~7GVP?NJ#Q@RwCOOP`&My2UnG`A$2ht7h$)97L=ImO97O&F#YnkN@M1J?aDFVz2IaTxIkn&sM~HVN=)n*17j?0HHJCWE(K|d|*7^{^%oNuzXW1+wXY4x#zhZi-Ln^A{h4|$=-;kMY2qT>%nMnz2*DWaMFA3c{zvZANBiU8GU0j9$cHVpBayCW&Ih);Lol}SLf_bx`If;&8yiCt}(kY_xx0JGQX;F99Z|yxOl!nJl%5QgxquDfsZI0%krJGFICv_fYP4;#6963()BsJ^Xrqz{$4I%qPOJIqb0}>n<-z#3Qzk$SHGY0bUpIqCAS35zH|(L>w@%8Jvs#PL@9^Um`3?t^A_uTRQ-8;=F$bV#MZQXiv?s-Bl&Y3p`ro_9#^1Van?D+yY->NfX!83a4@_BKHTZn&%)@QbO`f6=fEt$dd^P4O3Ld13?fX;23v80%QIlIBq+$e`#o?x(bTE6r(?mJcw=eM@2_(E`S=EZ)0#9>cH6NSer5Y8+ay!@@2N&n4EUuc;?7%Yh;r~h)pd;g%~-p>M(5it6=&7mY5_Z?RAOTV_UM#1HCT_L-_6V5M&v6N9lFren^>h5mN=Z=Uq1H*Q*_zu;3OJZXtl$-9sH6bFv5dZEkFK-42@0^%b|GZnkp6$8uS4-7AyLVVbsu03)^I1XCwS}*(X2Jw+kNm=Z*BObmhrZ17{M|?sP??fJae;u;)1s^_S>OWp&G~k}oaRZ3@C*@4!{|{E_25r3^47~|WYa{#-2mAhjk}{o}puMQ7pg;`w-9+Cq2l_lN`CVyZ$;s63EMs@izWzvv(7GU@Ik*4nQP0c0S*flc&FHr)oQ?j3aQ}5FF`%;W#GTSTxQ;4JZ|Ryf#KM#I_HtGp#E1CjweC1Lt8mCB^$+3`o_?JD(t3Y5@=2R@oGEX1)A8MkhrKjHzYY46X#SB6%fe#e{@v2U8bXNA+aIr%?TU_r+xtr;4JQzXGp)B51GBuXySIn<^d*%cMe1zGKoOTD)Uw)q#a!44tdP#}S8Z{F?i?9l~M4@oXL_BMwUK+jeJGMlkAb9GLP|4#s?2;kq~qJobvqk9!~v!Gff-B|D;F;H#5IRx{#2)N7wGj{&XKmhFEH@jPK5W%r7q(3bRrV&mnbk&BUErT-YU)p!*OG&bM11*ef;*@o~^*)K%GhjQtG?I)05DO*3blhTiY36pX1{S%kx?0lIY1E`nEl&rJZi$8WAL5l7xd`m=AT{lO%do?SR1;ElZNu1}6+Y-ut>=Wuu_+KDF~NS`nN>twDZ8oMW;mTmkvksGnM1$ghf(l7E(%`hlW;PfGF##yf)k~4kq>lTFcY2*rLRYo1roe5i0AIXI#ObLES$Jh`0)gv&)oA;3S#Y(^f;H;aOLpx&&aR14M&&xoJoX~4e#Y%%^<%z8sdFvM@teA^?74{$ggrnj+rYjP63G<0ZB%OJm>6@!#UB*zx?A{m0UQ_3ElX^hy3B)(Nnv-mm|NrYsbLA?_a5%4Dz~X^LN)Gzan&r<;A_B)cxMU1F?8-8&~~w@Ob47=;>Vbz`zOpz~cw9=UdA|A!Wiyw00Qp@gux`smyba0F%>`pwo^1U%@{EQ4VJMscsjsSL)MF60m!Y2*1v@3eBhQser{)LE+2eHuLO8RM;E`7Vw_qX8!+|l{@1B>}A++(t-%b0_e-gUJE*Ap9+fD9tstEF{?M)spkNSmy`d_sxq0Y#!E*i#9T}hz7@6@xw(}42?o+NF5Ru~1@+rBwYp1`<3r^#WVWba-G9@<$lJh(0D9?G0yIBaL!+3^!aAQL8GK9kmLGINDh89^4SY<;MIVK@-HJG@^*rUoE-A2tM&$I^0%Xa&~MIE#d$KDGSYm;CI$$7ozr2+uZX&)vY}XL(DYb$auwq9X=bOWv35LAkGYf|??HSjEv>7L`X@kmh12@o^@z{wX+P7)S&5MO$@``wQywhQH_Gr%09=U+p1#eL4?x@(TrUfOLdlf_`>YX%vtr}1zxIcNelLe%rwHO8m}|i$u{;t=zYgXGKm4b&4-6YSdmv)hf+VsKa7PVmsS>hzJl}QtLrSSnLQp3Hr^*+6KB#<9NRlMCYu0`tJiV`{J?!muGw~uIbw6WNPLHzVIxOB{Nhe1^`Kt~8rAEk+!y1Ck%U{1ye3QG#1^Sdmvux=qy{Hj9Du_Oz!iO2{jSKH?HNu|V_{Kbej=5bY?%JL4GjTwMw{Pd=QIXb&BahveRc9;uVaGbdE_PJa2G0GUPab-#4tJn2X^=et%K0^&mKaoyF(CpA;<-C!-h2}LVbe8{my95gsnHMSgzfLJ#Et3{HCgK~+S?&fEaV8I>ep1c6(18eA0G$qT3M%-g4jFX-ToLd0qPVfhfd*v41RygJ+UqJ65m3c~TYp(8stc9zJAP?Ah}Qad6Rn7qjwi0(}0eA|jrR`!z4I9UAyr+-*6KN)~JizJ7;ua&b~3o)SSyI9V&OKTpCcp@pJbrP)$AM$H;SF@5Z>6W^z({jk7AaAOj82n$=jTKKkPbZUvoS8fe~jiOzyq4?T-oav6l{}pX3Ho;O9PVH#1e2IXh8Lop?D740OBaP1qt&^PtntcPB`&b-RXo)N|x%?-d_TwoH;>was-ueq*!~dE;^iZv5+~xeL!9D7=(S9Y1fviG>^b-v^*SC;E{;$&7;20ULgszek=>)&J)HWpXTdQ>0Cm)*(+=oxqclx+{U9r;#9ncoO;l8po3u{dAiBkq?ZdG#|2+O#zkFi+)Y+N1PXu49a~Uqym3x({Q5!o_BrhJMT{6Ai?ti^(=KipvOMHhL|-?7>L?JdJiOZa9Qyxy-(y4V{;`n3UAZvpDDsEmu>KoC{qZpQY8lJd6g>A^KF)E@cZlvkKP9L2okpIJ`|+Kbeoiu6xUy@{P%83-yc!+FMe9--bv=L9-k2K?!HeWBrorXDixoa!5YMX6=*_a)B=C#j+%VLGyo)4cF1t=A1m1220Gl|-yg=fz$;Zhi+`<8F1Ftz6Vy)GW)U4&k=C>sfcfB&&LM8SC&bo1b|mrY^Nc-mV{>InMJ;NLTAF7rmhHBGNSqXrmHpT@4ztM-ZpqW)v{G4iYBq_f*~iesVH_H7F(8RtnS^`q>iZ2G=W=r)hlONCGTy1s9G&9T)Q9uxqQPcy;g~c=|5o`uh+EzO`)%2{a4^&y+hCN&)F0FJS+x3_NVr>`%y(foQ@`?Edro&vMZ>1H3lXZf5r@?+nw%zdUKAx-T&R2*Ru-2S;M!2&)w&IFXxDw%d093NI@J#@$oY;qNGuhu@_!x=vh)pP@;qEGr)R!gbB9C_Oz+^V)4_SNt*hT}Sxgd;{e$01)Zsi?5GA4+`#c$5Dk$chaz%U&N^Fi<*Ovli7VEaS=p#NveNb3WDx0^xiL6La_EbAoSf4TXyr7-SzBMM%kY!}Lb2pPduyx)O&fFg{An@FDz9SRA%KMPqA$K(nI956@id%~~5IXoXWAQ-vKch{^DXS?86x7T{GjwR(4j>MCZyr&6&c!n7XRnJQ4#d7lxG|1#?ya{FanKr!P>&Z$0KSSfp))HGhb8mJCFKt#f(FO4xF$2qm)O_CtFC?}37!t!+*b6INw;(Cm7dLwWQMN(GE+RivNgIr`jV)F5?Qh)j1T7tL!aS9Dx+RcVia*8^aOhK0vY$7`@bN+BEmA2z8=;LtZRK}j{M|Rtp|`|V;T3kqB+QmR@CmB+{cp$3p9p%>(^M#*E5dKHrMWL1w8ESh)=1dQ*#)}?#J`@;_{Yb_(f(|GW5p5wATV7kl~+}Y@r$_cOrpPUiMX*zE-W&JC%7WoxX-^+10mC^UA%LRE9C9T>pdN~P}m+fdKQSOXb=w?JU>R!7@#GII0}ay9(JGcJuIOfVHF2#F-svXYh%_kbn7O!pN_vG$SYb#7Kx}igo%dgZ!#@?F+Hv^7Q?S+luOOUyN&l_I)cW>HD(1$95$eRAHW8{C0BX^1DgUkZ9J!bqnKue#OdO-67@5ayP}|0hmMF7`nT^23aWgkVu9$>^<4q|Jkbx%Su6oo?9lz?{{!P)O6z?0kaPb#Pg{>XA>@tSyl?g?kaG3@m(mHu?evdUlXTHEhQ9PZapYHwJ|A?xw5Ir?T||ce+<3&U3*^oWlc4%i$VQ&iI6wUdRYE;n)1j%kAhyK{aelqD^2PXQI9MBfH1G~b|IpJF7F^^2>`re@NsXs6CB^cWW1V$E?KtCU4@=DSw#+I7n$7h+c*9k*M!pN#`pS&QU_XS8@InowvI9L^1_lvFz_K6-RzW=-6mi(&srL;Kh#Tenj2Vwq+#HSuJ^avjpPyYr(+X%@h)>`pf1+3PfIN-%H_KKws}`ZM4_QY(zY->dc!BREPv3kBN&5{bwWJ3D%ZZ(J*dVB5S~b@w9WztaYJc9OGQ#jXU~7-7~K{W{)L6!)V&MVpE(aW4wpm_Gl*oueXGETM))aqTfvUpX7gi+c|Ll3~2ohYQ35YY7-YbQkeK>xKD04S6dq6+%hr)@v);^O}*?*g3gi$?_`;HyX7@c=Na~N(AE$?D{&v!0>p=?kKSSz1H?90EG7f(rIbB!f^neW^8JyAGUCACF_d^9&PBG)L!LP=udgOlDG{#!+<4-^OT>Z5Pmaq>`p2)j5QiV>Ttn^?$&9|+(qia0s_N1;?@Fh_B|0H&i$WX{o7R$9Aq|QO;@&H7$9Y18m!>r&m^SLq7Wv6^es%NV{^M~Z*lO@#drv>&P$(5pF19O{alb5Ji~K720Hu|!A`apr+z#q7=>|U}`LS-=kO2F2^`AT%#_!J2uscW8KM@H1S`jMdVV*nN>uTPV1k;Lkcg{UU92h)_H3f)$Z6MP*-d@+ifq83ELDXtcHQ*BBU`2f3^=Yt={-15(Mt(JqzL9g}AwhQpx$DR?#DUN&dF(}k`5o6dWHNA`OpdG-PYwJ;)$m=f4^ZYn`@Ft|(Ke~0K4&&Dina|%OgQKCc!DZB_9pgTcZyf3y4@AH8qh=V#m#4-B=~X6y@x=pQ(u>^Y?8N>n?071ys0+N@x)RT+=-Zt(zI`OvGgWlPSqFKP(}S});#fzuBve{_Tc;bzb32JbXLfWciK_@p&$`c!w6)WQ*7TKYgUm!wJ)6e!*x9OBkG^m)A^F^#nY#*%;G%kv8(0IU7i8n3zJk1(h$!E4|a9Oj11VsbIQwvDgWyA_7{J2tXDOfMbMCl9NRxgu^v-{Q`X=?wk4^bW+$f6c|2y0aPJ&lWevjP3*eBQ;Yi=yKg`UCH45Qj(KCqMFiNr1tZy4!xMAiqka<(Io~CWC!g(Qg}m+;0-|aQtHmK(=-?_il^}XU~_eT^E%G?$fdcS@#ehH-r1fR{D`ZwoYy<`x%@+SH7GgJ8Vpcb3$xY5_-t5YTHxI%O9r0$wyzEb8q9k(kxFif?XMmzIam$5I4~w7wdXi`u=@a@{Qv<7+-carYUrtjE5PUZ`I3l5eJL$D;B9viSRDb`LOtMjHlm>OzbKRlVMYt*y!qhroJ0pc?Z@lOa4n&{H`|*fR>8_E|ogx`fd@F4>DhKi54qfMSWltPbh?O3@djWaHY|`>|v-CKtE_@&%m;-SbX|3ITY$_4HJu^G|G8l1KS$}`XIx`tw+g+5YIfOWvO5A_-YE$aJzB$K{U-c%c&YY+7!-7^*Q@`7|UWj(+LT5-o>>Co9{K?`=X1!s5NHCjfmOIpi^Mq9M;HMgW|7$w@bl_7l;*+nJ{FeP!I_&NbTzw!P@p1MPTw9Y#rfu`aN+Jf89k=FM4LzJ+N4QoFv0rxfXs8m;r4ykg8Gvrm~;&p$Mw>qPTWWKjFMof(6ETmJH&zL2NrNH9Xi^}TkJBJ>emjqYd`Es2cpljOyK{|Lz^d+069rdS8tokH)~S2r8^`U-$Zch4rP=4jPFaV!^z<$tykD}O|3BTcTA(CL&&`|i+&E9&)J(_+6!Jw$^dcYgff$6w8w?>y6rrg2}%zq8zK$xcf=|#+yDBT2}eS|XxFbrK1Sp*`UYizR_G#`I9}vqn>EM+Pi-RMh{%STpX-n(5a&gMo8urSdF$jVexEtJr1_1^!evRY?Mh>l<70zLAk%wfl)BYth#uk$3dr2cAVQ0|;?nF$*TYQU<(ZVKiA5fj!!z!7Wq%g%Xvf>%A99?t^X~n^UtCR(zrTNl)Jvd$BR+RXe;lNV?d7<$4E;H~JO6H3vm{18N+AV|ckDE0w)?87@Z)&Y?*MJY?LhptL^UH4tWG|-@(e%n0sgVJpT~^TK_bm`N9!TPb9d1!htrk}5K!t|`0^+6sEV~OgO+^EfTylX-u6{^-xtnz|1Ph8CS2p9*ed@(9>vLZNfXPK7&%S!;xkV;tP~GelymX$^W{b*2bUsW3IBn!tkvrO_3@S2UH_Mxp5<#)oGC}J$;=p;&uu=R)GGqy@ZuS*ts^_gx8uNRX3QoL>-Vgu5efQO6mj@e(dEA$@p1g%{mf=vI^5pWY<@Bs@p)=B%jx|t9bV1ro^P*>_(bsVT4#A>0H2_Mu^PX;GHId!~C*VjZ5dCo%4YUv%Pnc~!`wJxqUJq20>Osd5-M3EgkkSLv{4c}wZ?o_=kl=NWz8E-(4j%2d}t%vX21Uy7~Y`!U%aaZn-OnB4U$4g5yd9rw^h9A=Y!ez(x$Z!h~tBbOt1u6tSGLz=l_Iv5-j^ZrXh9Cp?PaBX{>?*Ba>z2SfFvoLnlmsQRy>T;}G43}}&3}C6%YeL_m0}O=@P2UVJW=;U^mW9jUn#@$t4%G5g91ib@KvHzDy16Fug)K*N|==4P0^{j8)j-^g-lZGwaICcFp9#Db1EWX(Z%bS1dOu#BwCUQNxmVS*y^$^-Qt`>hY!momQS)A&YU4*jId_k$}jXXg-7Sj?lsJ63T#UWre0=(TJPz%8POh>Y1QebKpw;N#p}WnT+T5ED%czPl=--o@GwfSvUXFIWoiZE6>=ERoqnicb6`nSF;m&*A{2V`JVf8fY>(}GTj3b`do>1IiQ`Wo^weSdDku7>FjR1BzQRs_x^~WAJAANclKsiDir-m8HvzAzenUTZl~{4I6HXuR`4M{ajJ4vSET9l`FX$nPZGvKzi)rIWtB6b($%rAupW6r+o3O8hu365f8N_YBmRgRQBQGdAd8X5VwQ>gDz*8LWM^nLNc>2xd%g_uTrsbp?6X)7xcgsd7_UV9U+DnnM5;WKkB>le&6Z$`K#WwUTPAWb9fdYO>Q?sDqZ2;$I7y>tN%WoU$4kVe7gVEE|O?TgXfXTu{U=x<#k&wi3sW?LAGqQsP9wc6-1tVU2QrLW$TlsOy@Qu8?svH`*fmyF;52LsZNB4q>_0iG?eZvs@27KO4LaOvt=>r$c)pmj*=dZ#fC{)@H>Qy{h}oL6CywP*2ZiQ)oc?UYR7Y6n~Fh`vw7K|7~<38&2)YhDK1-7E|dd}4{qqp=0?svZ<1-cV9!AkEIhs^1J-BEJ+IpTt50@gI*90)iTvuu@1B^DkYGNY&gd_&*bZ^1EiVgID9d2zD2`|&4)o9TPV7`BoK=qND>#KbQ#6tCx{*B#ELzsx%cLLf@|8vP?VG}R-CPn7>Czj%;`{Q(-_T8PNQcwuCoYbcFzLW>>kAu7WdLz~%Mpt>sLpb+vb1I}>U6Y35r?gE4$-ZbG8y-Vs_KYCFSot19ak0{RD0E<5P~?A^oeltMrAS1bNtwFy&QIvZYUxF_BAfi?P7;vPl%b2hwNtk@H!hU@5Q@ss!+O6frCgCD)abE-+o2rcwkCI~O*@jY=5`AMep=VLZi*>E~Arumr^*7p_0EPB+iKNpC;BFhR;&w(XN!BOLC9@NO$eM&RJ`oZMPu&_dxd`4dqpKWL_eccvNrcnUC8@9WXiqXDDzWjRe=K`3ztaGu_3xA(-?{uofgA!nKzri6asO+5_28vA9u(eN?O;L4(>n3n%duBoEj_36YS;Bf{L9^ZR|Q2-*3v7-O8r(oEvY_tz~MEN4Z`KV;R%V1;+<)>1j~1R&-3xQ99(Y;^{JSs8I_4lxzC^aq9zB@>^kvp~k01Tm@eO}`MXa-c=yN!J5#t@9x0w2e&VTatl8=ls=?T=Y+c>D33!0l>+#21_l(%;H%j7+)JXkz`RX^XyK!Ct=q|VU!ES{(f9M=Id@QX1cq%NuhTK9PW#<-1-n6a|Di5#TB{PBNRPz_tr>#pW1V$ZIAbyvN{(WJ*6B%&G+hXxod5jC)w>C9@F35tqY9TYN0QCPRGBI9;qB)FvwDdEG&({XlC&~wNq2=4-wl7RPL5w)a*3V<~aZ9hqd?9(;TrpPZeCV3z09j0V?77cFN~^o`p;B_*U*jg^QG!)}56yQg0EMXYca`;-?x}BV^Q!w>!02NbzXMi?CCr-b1oB-4sm+#IDvk0TGT8o{%aNxeJ~a!qCZsJ-sEvxDF*_&6heG-(eDxG9^r<$P#m$AW8HDYr|a*$Gm;v4pffPSQQC<3ysXh~;OEVUn>lW>V!x3mFm%Bl=0keuCbX%EJ9L|&BBEb&1?RoG;CgPRDJB*LS{`&P~9>ggh6{IrZ!^QQLeQ{bo)cBv9G+o1VewBDxCPk(IK21i}|WJ#LNbV((eR(WMr#VexVLe1Z!qFU)CWq-XTkde;*SpoU>tGUY;i62ST+#(jQK5ygP)bjgCl3?`>!?glmwkIUJ!MN{ARfjHu$XWsul7pvixXf#`-))pI_%_oF_!ugGo;wjK5G&RA51T*j?4)eSPvFll70EWjYgopcd!8;3(s2d(6``Bs|1^uCH+%jS@(Q9K(8ZE$@ZcJ*kw`!s77Bss}%bF)-;NRtM84c~A^KkOEJvB`C!p~K2$ogjGz^T+DM*2q)hnB>_l{c(%;hk%rGFK&&PK)H_vj@5Ipi4!mqkar=VDul#$@{0TWq>&744QQh$mKJ1(bvC39Ef?ll#&mjap(9JTta^3S0Z!SMzR2=drEZPsGvU~@*aN%7XXn?!Ll0p)nQ39QQ3RNU?x0mAn+02m*{8xalDu@AB2u&%ssC=yYA|Q3>l0=CKQ!x5r_GE;}i=okr{Om{VV@J{}ikw1F?=}%@H5^tW+;qLV?lT8Xd(M)Lrinu|80Ik^*GC4Z^>cApa!tENRsg#{Fz-ANq|8F9Tkk+dzeJsYja29dW&|e$dH#8bO6Zw#oQuDz1yheZG4aHx$G9Q^#CM19(2E_2GWBFee!Z{qNJK&`#vXPwJ6@=u?;1h4|e1Eh|J#Aj8?eb=sLqXeatK{TU(yhw`_-udgBwoo@aY)@xFL@?&wY{vD>i9{LV!v}xeuJ2|y!_OE^+$92vL5x)*yk5W{!}>D*uKfMA90wc(hzr(g$BN9O4n{LM;w;LaGyEwt{8%DbE&T%N4=4IXWwVmh>;=4Sv_~!8||O;G&iiZC&NZN3meIKXqUFMJ?m6X2FCn4i}(=r5mn15kaa`;JIgdr2p!l@6o@~^cYU4^>V#ihwwklRh6MQR2;x~WRn+)w|^?${vqMi60vz=tdK5@rA#9{5d-#5PRpum82dYil$+KGJb=t2r3@AUjR?AK#F--eHGJr#WS`HRXW;XEN|NGg@e&})64jySOS7oFR#M}v*&_t&m+MH~X*2k+n{jd6ceErHert=t=mu+$QzEGk6(N$+B#A~$m~NccEj`0R^z`xW_9`|i?l$YiN_a0ul>A_a(k#is3uTkVp0qAu&GaADWoO^RM<_hIqn4XmfaTl#i0aWUH8oFCcK8AO8*KdcN-xFT-Eau2gBVZ`64a>On2)|T94ySs4mZ3`@5>Q8;D%@A%cBEy-*Dr@A&Q72QGzVT{1N``UHJqIs-Ks(E1bNN6GJ<(pWXa`25iAk5*|H9Jo6MY2RGg>0rLPJ@1&h*Cuo@Z^SeOIcjX)Z;YQ~zx>G7@^zTdPWH_s%-sY}TuX2Rx@0;lMPP}P9+P9IGf7O3PhDCqH?XnEfPV~jm+D3utnkDlZ%$fQxx6O!?X%rx2R>lsaeIi_1?CSw4a3wn|h%-gIf8C?lCu}q@8@yE>yBF=l^8)VAyrcV{H(41gB+*XvW2SVM{L`KOi2ZlyG%cNtr}Up6@IpJWzet`(hJ69!Y$-QUpHs7A^gE|18GPHG#Qmh8UE=;LSs!}bQC%S_$=ikY)w^qXQa97TBkh7Y8w>XPBl-bdpug|r`Xe_rq_NMSi|=cnLIWzJ4|tg&K2P+e^H@y#_wTOwJfSPTd6@Pu?!=&7O4Kd*K7E}Mbp%^7@OKElYPhWwQorTaaNV4lo&H86%E%I%SsJ{O5H>n`+EiM=#g8b@_j$uMUQ8DCri?x;=M?Y_!?GtovxEN-&a&~Y1j5tt-oJz>s$RNfq{X)<(WA68f_x$Kd1|8MyarI9Shjk|(2vM5o^FQn9?NDB{lND+Xe4)<=qeTZlRqsW7ER&~C4@XeokKXz{7s?QajWUheZ7ftUOm$Um$U+>5{sQx^P@(>WQtJ6#h(pDlI==(cRM>5Fd1fpKdG#QrSy_wDpNT$hKhL2*C-Rav{w@YWZ`f--+6}JT3oXjYh*aw+(!ij%giy<@48NSc)@Fw-aJK^^dztjDjU*vOhrucY=OI^v-f&zZ7H|1=ZbjyD~-nd`3o&rR^xkee&efp))*kAjoP@{i<_KQiE+im%`+Rd-15V7&craTek+qZIt123PV!4|c|p}>=fgXLDer7cg28GX%+1JQ4*&%ZhyNaxQQm%D2wH=w;^=?w=C3o@v++_g4-gg6ko`2iF%taDIbQK*6Tne`G|-U?74dWJ%y7Blfo{|gN@{uFreY_*FcJK7I&taN^`fC>h0{0*L|X3W_?OsBs(Lg)Ws6fe2`ddRQh<@XL7Z=pe?^NSA~nd+nn9M`<1ftdfHb#YZp_hQ2b``qh`!D4c4@zP?9?`3Q{m#PKGV7FuG)1@cSPVBGp>HK+ceq3!G7uxx~hs5-skzv2T=wX*k#3wsbw82Y`0z@3PkVd=Zn>U-!-lBl>x8BGzafpxPr>)=Rm8jrZpS(q95P3pPZ^IqFHY!v^m!DY7$JFO#`27!oKpKqM^#`ov#rY%gQ+suaK?yu#S4*mXjW`@=Rinf-7K3~SO>uQU#_>k)0gkgP$?z!YT<6k4w2$iAMVis~ebE&vwPkip{q?xteYrvB&kgG~`l|{v@qteA(gqz0oZ?JrpJwWRx7usg{YxVS4!frn6zpT_`)q6!nSPQAZo=F4b(JALIUCM8E)t+I{5c2ve|Gx*=$paS7xXx_t;O0;m8tKc)Cy%Tt|uix$ZLr%Mcl5XIrdsL6*KZrKn&wGk&l(Ln#{=C`9H3{Je;ccd%GxQNJu47QX*wYgETIosFWf}MM-I(LZ*~ZC`BTrSu+*R9?p?6BpMVYNg~mN3`vn8^zP^Qe690){h`Z!J?*p4+RuL0z2+y~$aAIySlg}KPr>WG-Uji-h${^ibB_N?!E!CrhaDpGVq#`ZzFM+@hEOrVA&bo-eCej|dYSJuRL-;>m#l#JtYy>9&5kqR)TWwqJ_+S^RyViqiv?}i}0K?5ieJB_FzbUtZ~R%#LdIP^p|kw@aOSPOZG2C{MxuLD{p?MpioL??G}-FG;Uv3*o<+ZVRieo^p&F#pP{K|Ky}a%wv!*`)q--qp6%vF-C%&k)k886*N9ShP_%~y`PsD!%Xj||=Xj%!?3NZsKHQ?U8l?J(@GhmA-5!1d@Eg0>bAl7{D`KzCe9Qy>^7WA`lCaPDxRgOLSCuG`HkMuD`vCFXIx(N@d?{g_lxrU1V|vcr{Z>uEhx_Mm)xAYLXyLpAKe_LlKWM;g=_FL?!P}h-dG$PxT66;rgt_s&8K*ZvUWhVM;I`B!+YklevXF%KyE0Sx=GxE{ngA-(iRAUF&cC+s5f5H9^ZZu@2;E4lX7=@()(^LL40Rmk(G1>1@Wsio=f;4PWn&TI@0j9bYG}kBI0vYpY028r@?aR-Q(5eh>wHN$cQ8cNZ74#2=XX$Ki@)GD2q&dpgae0!4$_ctw;G#d+qqWBkK_-bD*lS1P~ClCHt-m;!_*X|9w-*gKx6upWTf?JxJ=o-i)STi1oTUD-oVR=Fa?E$LZM}OI2I;;kj3)QZqB{8YS$9w*Cg@n_XEtt3|4r64r?io{Ic|%#mkIY0z_9BCQA<$@zZ8*?`()`SpK0l0_703d_%_(&W=z{IDW8AH2;t@R3<3Wa5!+kWa9#nIWm_rHYqE6RGT)a?g!o(3cQrJA1y&SoO-VoQ#^_VIi78!av1t`{WG_wwewgY_B6i)<*=$Kr%<9l1wVXaD(wZRzwA_vibBjOVSfO#wTK7I^r%pZqkz;I*f*jauCHp?X3p)~>eIF+QtpU1T(e$dznX?OSLf%2h|D{_S@JhR>In@oCn^RS%={l-wSc7Ao0>7uKeIgjy&KA>O?-?}!W#y}&J7+d2*NsR($_o2gN1Qx>ek8?;XYX;Gv~OUIv<8aMz0xZi1o!JALg_K1uNrMeEt3b^?T)!A8W_1q~N%@qWzC3#OXgi0?!*11beA0$TvcKY+&(3j{!79PZ+#rPZ7#zbyiVF`fgg-@7K)^{ZVm$3c63$(U9je$*bcj%4f!eA5^Xv1Fjo(9PUv{rhklgiSQ+PcTeqsAvDxKo!F69hw=%SF=()aBm<=1{~I6V1IaSChtTm1D8?8*bZ$Vok$%?UD_D4Uy9Iv+bQr`*0HCv5O5KRZ|qK{=0YXuKpr(VI1pMolvHM#J9J-Lb;LtmJQJ~ENO0*Ogo8qm{N-0<1w7QA7eeo(-d*S`=35!z^}fmeE27nTSDaOCDRVF!24{o^Xw+X``y0hK6C>g-en9w`uzdQGuqd0wuyrPNS=|{XOvIXFS}{7{V4FSP}k3lM1Hbn5Paz7_H)}_ucw_N{<;~)#Ru3F3hI3Gq0t-hwray=hey*;4MX{>oe}rFr>eXoj)oem(A%XV^PQ6~WK3J6&DpI%V|LU}6q)bbl@RLpmJ#+n+wu$LnQi?n_V#5KevJ=!Tyz`x((8e(I+YQ87-ieMXxBnq-@ViCo53vsj9ohRer?LFzV-K_7Vp{I$^&aPhDj(vzUMQ1RX`nQ=aT30`WxbEn}68L-lAahp=)PijsQLq6j_;_xqtQ#7#8mu=4&g81~-`)0Y57^od_Ut#-j#3?1Oq)%lG^xGXYpj!n0<pam^cAj^7MbJx-fMToD@Hhn>xD7Swdu~Pd)9h`vvX4htor4J_@sq(-m`D=VNRmnQt@ku$2@)WYjmjqNT2)n8Hkg4u`f8i6XvS6;j5X5---A$Lpl3>>fpNsTlW+uW~YT3unMhRi#07Eb=JQ2W@f}12^Li#aq8X9!389RZkY!XWp4(^)T-LTD`oZX9Wese;Kk6&vOzN-WW~6H8tP;n_r+D0z4GeZkAK9?fLQr8%5^Hy4Czmbe}>4kyF-cluxSm(FSYod|r9^tL*45yKaTE#74;iLFoM_pT#!;Xx~ZJKXcNK)h&4UKZp8}-!u(P|0^Z+&ZdwGWqd37B!`JO$P@E1Tba6^Uckc`T8uC@+WhgN<#=om;QyUd{OddmoO!l#tSQFF)jwC;&~x}uv+Lc`nA<3aSo5oAyzD5juo!9*BNFEg;VCcGx=IQ2E&B~YT+3wjGWQlrIOkFA2FhoRri)hfN*bQuT>nW`4{=hblzoo|jeNFy^c9p3+5aIrOz(X5Zj{6EYaYY4aQ0yNqu;Bt=ZW+Ke6rLq(TwfQix6OZyew&p!Jc{+c5}pd-$mRfB;VuOHGXfuyK!iDygfPoBDIDR_Osd&f%=`jt)aU1It5m%uLRYaB2MBQ`#UK(qTMyB=O@Zxkb{no?RpxLOOC#1jzpaF5!(8K2GT}n*J$KRH*}Jl%`6zmUVRD7qftJjueZ~CMyTIq8&N(kT0eYi_Or0h`lQsfiHMW;r*h_h@r9WvH}dxaNkQ-56Hz|jUPtgQtfGYT?1D2KLaQw=6<2Nf4#Y~3G-gI3WR;bPC4Sa#Ls=c&Dny29UsnD*0v*WIq2fw;&6@<*4b?-7x7Ojt@lj%LqX%ADbn7lh=*)YoVRTw4P;*NqGO2L+2np-Rz|}mO7A_`AYPxd@0x)NXV+_A?`jz;!k4%okYOR;|HAfjBL2FuIxm&B=Cg3CZp?ev#fXm@U@M!H#P5x>@KJ8Uear}i^V;sV;=cN5bN$f-&hAr_em#yi8~MqOP@9!D5fs?;JMO}pj<|-{+XZU%6l_0Uvhwj{#4R7DoK#ywL#f$o@uo3|PmFjyTfLYDE7d!v7Ky|+moR=R+FKdOnAQAtW;621kuu3?YZO@6vtjD^>CX`-^V#b^uy8!cOJ#91;v^qvay}m{N>gL30CAH4v!Plb%>R+h$2cjO3#_X}LG0Gwvs40+*O9p}yY^AA=XCTp=V-)7EbCesUrIqw+O}s8MdnS5kJsDjVMaqlBR@VR4eKkr&YVijsaP@{MRub5&syu$G&S23-j$SOwDaXoV2sMSIV8k+ng8n+;{NLAnVcfH$5pfb1{?RTFp7W<)BCdYaVNrw}1zUDy$`?FAet6DzkZQ}^ByYR2&`zc7X>Uek64fPee;!ldB%dSucP`?yzaRLrS)PV)74=<_`;bS)TSr|UvV{gi*L9~XR-=5xPlYO9iCy^SFB`@+%U5njTES%)5zGo|jzh!{=`EuJA9Qz$EW$@x(yHM|8BB>>Wo7=L?9dBK~2KxUcv@8g}11@!|6=ln+PS#U|I$kSf{seEI~$Ke)u6-LZ)QGB-Fm40(bPw{TZ217mL0nvc1H?-$7vxE{y?$rI1{fjo29_8Aj)X!Bvm@a`+$n~-M?{;IIppq39B6N+Zap2B{2B#-(N_x`Rc^xu5sFY584Rep0MxaVt68gdE{CwWfK)w%ana!0$j2>+Zr?A!!m_c;wao8~KpxbY#&i^JMzxM;5bcFM)8eV_Yh{$v6)pIvHM(5)Gk^K-f`>Y!ugnfx}asQA!zz-$@5Xj2@k+>q#*C>DDLn}{8SjQ(b8TEL7%fmxbawxc5{nc!%$XsJns~P*YjG^I3{En8oY!UyG^eM%B&JI%LK3Mr6;z^IT2G;+jK{iwWY_tyIhZN_AJUqmJNpdlxpO1XNa(lOqr5X$F{kk(RTcg}a{}4US-np>r{Ww7u%I8Mu>sd;i{rlcnBiVBh;>1r^8Y_UVUH7+Wsw2OeeyIJS_7)0G8}qYAZAP9WEs$UFL_mSj>*R%>Mf`79-~8V7Y#7IfZ{02|oFp=r`LUAS=l~ktxqj1V6GMD&K=_w??Hu1Qw5m!fLcbiD-{2L>Kvc!RCE>9s=MC-I9dVOc2!68cs<%1fnqezu$2PEFym{ivrmrIM{KFf0u7EF`$FY19@~b}wWq-df7C`ja=E=+Nq1?#4HaU(zlX(jLuZqlTzCOHiE@v-HIQw=Edl_-Uvz5hYaL8=kq;VecvN0K-)OXQvW!spC_eJvSw(1PLE?-Z>9FC~}3`IP4XK5-znkz3vUJFKgX7zw!gEQhMXy^=Q(Y}b7VIcO?yLw%ni!V_l7zH}azL(3NsizOdkxl(FK*QN&xzT<;Ek&j*uFj8|1O;>7>l)g=JZKe*x;;s*a}&ljsu!ntoVw2((BXFq8*bfZAGfBUWJYY;EV6?43pN5R@*();=0h>x>9czDuu8pynhFS&@f&+LAGo<{?jU)MAMc~qC%im3R74BQ$Yc;0du;*E0ucxRg!pgtxH-*pc0?j5pnrX;^EY^15;4-vm#rk?IVmJf>tP1v;C6nPh$_bEoVOaN0QO5D@WA;0>yaQ57}pD9Sbs3j>m26<84f}H`rlW1V1CEo3yg6I6FGo5~ie7NrwY4oa81Njp99hgT0DFb>|h5aIg|4d<^=vZ0zeF5@>N&BicM@2IbdeWgdc_!+|-S5Zs6bxWtxW|o48ZlURK>7kHa{4IW$>}$hg!L(sZboNrOYq^$rv(*((a58oF)vcb#PLBcrGDfTm*ai-l$LCRF%=YC8#G^Hjsoiaog9%j)1+Z#={CF!cIH_7a$hy>{=+h?sziA8+O`uRQ@m;T5`OHO(^-^H;Q7bLbV_Jg?Pi$Wb{q8_(XR%^3~XChF#F3H!dUGxPJ)$zdxS^^S@&^Rx~0{Xbz+&y(nhE#-@9TrYXwj`%k$iFZ}r+t9QiQ(jMzFqV2WL)=m?EN5!dM$|7^n%G`6BK0cv@eHvG2iR2A__aE|YI1T1*pT92ufO07C`8jOpZW_4bUw2{%;$6A@TSjuvH&T7)kZ)?pm&Q)nY|>=Hz}Z$Ot&wX`ZZ#t{YMgiCNatJ%AIet^^6M@_zU_85ckZ170_gdnI%Cl@%riW-<8tI*mIB%G5nE)JTOW1z(DPTb!)>#^#1ekPjz#jaB>)8kQXIDxh<#`7hAiLg~??qHIXwBKU(y$>X;lKPMaKatr4mJavqp9gkQ#oIe(uY`uYIhyUZo?z3VdtLO*J18_MU3zSbMxOB6V0&#cbai+b5_kZ;k5W(tNsYnXC%1>)x6&v;vx(?I5^w~iO#lT+&-|GdXNcegJq);FPi2G5t6oNT}V>BCpWL%e-Yp8MD=P9GU&ZPMO~_*MSZf~lKWc=qO(xQis>ZeB(j=Bj)k{~kGm^4v1|o_O;gK0KefXV7O!#MKi+qCYhYAl6wma{gM}Z(FZieAC6*3#k{Dx|`iX-ZGUtV3OWa@O6jt8iP2*|GZ9|{9+mn#|#Zl+zml|=AHR#PF$v;U~fu{he#gga+$om!qE)OAF%pblNIuxL;9)yMt2$5vE0G=_GDZiHPuHa#D=r$yY=3!>O!6=_B(3QoKbwBORRRdq@$d-pBPzW^p6jwtE4p^Y{m7-_hsM84M~NDj&tAYI#6zFS0rW5bfRF>^^yE_mB`;n-xeuupT8(AERd~5e5#C{M;d4Urkd)``rU-M@p+Z`AqQx9lQkhWs10$k3m+e!>7-%(v+?(gdJtdpW8hYc!*)oe0-0YlyHF(GtZZcAzd0OFJ~&M3`zYjTzOUCr*&gSf@1GZ%CbLEAEDV=TH?5`Mv!`ZhmILCgvZ*F|t7s56%|0$K!W#>y^gEXdXyD9N`ZSIB1ZTBZ5)O>8zpjEv9^)X#xMfENv#|By+9fxYkk^qs>e?a}mcMZsw09Na7d|vu^~>c0nR{Ovfq2;Cgq{4)0ywgH!-wjph%-#>#Yb|z&oRIT@k^U_EOmFFV9S^65$BI1-hSM4n^h_&hoKUe9^{MU4fc-@U%=T-wr3|L{ZmAKc(f_^ZdNS!e2x5FE^HOaS5zG5HC~;2e{F8){K!Fk!ka5^9G`JKq*iX0n4U=8M9#08oCsDpFPMKzgumU6l}z>H3+tDk>mlzVzad5dWWK@dCzyw(aD7$7gifmW?`6mbNdEm*Q@VF9p)=}1ZFki#_hV>?&#hU`b3#4X@6Pze$qh6JE{#+9vH*DkvoEatu_XiQUB}`-wWGf!tkN=dJ*R(v4zJj^Ar$o^p=SaeRyhA?XEoNbk~y^%$*i!CpOHwPqM%rlV={C3z4JaKa2^Nor#*SYhk0Z`!X~WyCUrmtzbGJe19KN6AJ8#g1O@YHAoCjscq1PeE|!-2HkyW;MJr~l3rG2o@ac>ux_9165XxuU%g$4OZ5ikYSrh$Xm56-E&kF`p&rDx*>>u(;BPqFoE*30ErN^u|u@~h-^0+>fupq3@5MZB~`|rnU9rWPCz9*T^F=;3V@-@3v1j2abf<}~sd-A5xt<@B8=D2o(E$aQ{X4=OsXV5_Otw}uU{VzAp=c+}}K!)Kr$!zbSsJU1FD@eAvj_6MuGaJY=O_`{5*!Ji34#={7g`z4hHiBJ+s3uQ_~+07xC)m}J~1L{E$?p}>$coVEh$_oqW+7d1?zf#l^?*Q0(PG3@+_(Lpp!4@`xHCWw>wj7V#;wj>%Yg2fkDhWDMfy6%O2_JbU|_0Q+Vtcz$iuyCr5jG}W}&cABjU9a%8kUQHAeD<^(HU6aR0Pa9(p&Tm=8tY3O?$g|OF)dyY>p7M;w+{dPll)YJG$eBs|!BKwUz*XVXW2;)c#aldhIv&rO7g5Ldq3ip+BOxF>^TNJbod%0`%(W`yeaXD+IHIqBXLdRZM(Ygh3arNBT#db7&d~v{|WiH}Gj(>A#VLkp&>8pL$H_a_bd^n#0g@*;7V_&1(9&_8THlGpNkLJgbXYM@bbK%Jz7GA3jT;V8dR+df$t$TJWH`|HyjeJ#lM(GFz8Usf>Oix4J(z;A<>aQ}+uJ0@ym~>Yp-d&RTYm*TTP7kB+@Gc;3AzS)3;RX#4oEG_>KY}=k&*gJ^hy3+$H}aoO*?`Yc3~Cy1i;C0W@UH96kBLh%klsgw4c3NH1RFszg4?(yIuHj?6%|g{X3C&rR+alV-z5Oho^$XpNr(J$?B?lJ{d%V%a*@UhJfce>Hk1+e3<0doU=!Jndnoc>vS*wS%c?1?@pezK@Vpa7i#`eoQFJtoR1!xnBMoR9eKj8M;Qh_uNWu}*s1ya1p1?hed}V*_U1LUp&#aLzP;480&brVGG1Koh<#(o{dGFgc~PVaBJtb;yXl|WIUaIp@aOfPkS~!uH?eIDN{88SgM1K}8-$^QUbVIob^RG1cz5Q_HQEo{&uUB_g^M(0ll?PBhWPfWv6abl%<|Wc^hn$Zq9#OES_RyBORw8pwpO3K6NHv>L|pW6ES8H;iw?TK!P3*fGbz4L=@xZg-V!}MPQAp1pDWM7fK);2dN`1SIN4BrR&%;mfuztim$I9%Pgv(N_dSh>5mU)gf!(m1=-2Xzo9c3HzC8iaOI5Aw#jmRr-Oa{Q|2V&m)0Pf>2S@(AVY_#BVx(`43DV4rTMw5k+&9huiSGl>H4Q9W-Cd_nv+UtiixiiX37wH%K$A%2H9sw&uvdw&gV9#7~JxsEUI@yq7kctnLH^0deQR9EU8Vqm;(zX$~-#J|ZrRvoI#0_nG>r-3;6KK2QLAx4C=PPN|}2_i0G4oopT>K-|#n$#!201`b{I>lgDAaiSNCn;9VI`Xd93V-k5$X)GKJHQc!;KqMY*Qf026z=z1YT?T`T5${~I_mxww020P*-y=O0c@c?!4ejB<<=Xo{e;ecav2wM`f-NYxaKqUsd%p+|^!W2~eLN+c556=D@lB&f-%lDqgO6TYp1cfRU)8&Es)`>Cr)#n+&TdAWDY~wxCdNQrEG=^-PlTs6nz1_983^*fw4h)C@-Fhb)|rLp*G6wz`y6qf4?iDhEak(y8;fd(?nK^2;-PyT1Tf|8!1NE}k#~`N+&QCZVSm(wc8o)jIWLu4X}G+uc8QHV@&Pg@@^>2Do3AK`=lry8g=UB046N{aRuK3L`I23YQq&MX&JMDdZIR=lzol%Co$}r94E)g;J#^v{k@;Lp4UcATVtdcM$q{|mZ%}x7BcJA9=#?RROC){8*UbA3t0PP(H%`ZbSJ0$>BubdYDQ(t5bZK(a@G_Z-;$B$@l-TMIf{*&nSlVttWGpuJ%xHHh9L%KTW9LNnOu0&fZb5j6d>NWKIN;+n5Bpx4vL6>NWDaRGK@7KdHABN21)kqTU@E<72^!W{bN1wTJ)Gg?)%1-+zeWTd~)z?`?q4_Y4|c~ddsU)M_nB)?1RcaL%ESYFpZmg{TuzpAYb}z6ZT=_4+f-V)>iCWhw@xFzVx0$1PdQ7sZlzfC{NP2ZlD<-2+z`RLb;LWmp)R^+sAJl?l;2McMnbl;>S96S!6z7+|t{b6a}jeW;`ldjC^LHy4#mm+X=LOX_yni+Bn!E9^>gWRPqiDb#z?m0Mje~=W|DDF~Yp%o0E~}kp5iCX$dho;#TjSvLmxn@?z>&Twg5ZoSt(ObYSfJp&a<-Pr;4710hRh?Blo!)|i+#Xc*mxok&t_d_;ah_*2B5yeq{0IZ)+zYAB%|?w2mFXz>^!=ZWbba|1{LQjvc?jfcS>LVov`=`UD<-BNxl@tE2m}Z=DQBKDORV_4apjKIk6|$^WKI22V7v;-&yUrkw>Is;-PHZ9z_vJ?nUnw#_cjwPc?SD5}$kG1z?7|`R!~ESlcdPkyJ{;Bf_QP}Xkv=@*(|iyALO%4jdK~d!$KgKQ_pNyK5Pty-vuH7RZis!thfJG(No58NKUX9w%s7eX_L})Gey1Oz;gZz78ozwx1EF6!WEv{C_qXQLfQc>t-<(QdV55Dp=BPH551IFBl)}K2(nWJe)gVuJSH4yInKlbQqz>@bC!s&8^V~POn_(e!{{)Q!3zW}DbE~c?%lR)-wzY^tE^rda)h6gMRSi2(0K_2~?Z@)u{$wod{9A3mTzJ>dT=wFpl0w8g!v(o>QPvHWulMB~2R11K_VdNb!zixx8{iK9}w9wyjg!;evZ-HxRVZY@rv2%UbscbKs_C`R%-tkkkgCkJyztNN5{aB3=&b`(6h)JFZOM!G{2AyTrm;v{OhPNtQvce*=PWUs>&5R8X#%3d2aFjY`}Wx!N{ZEf`->Z}N(VXLxnXQ{LPVPrNPV9u>vmD=O4PG%`LZl8QR4L`C1S71+WI~WHsUMr(91z6u$&1Ygn(I-X_LIw0eh*=Re*5iIzd4BeXWufCOksiKISRIm%-wK%TKsK0A5xn&wdd>;;h%4#Bk2VKh#KJ{H0cvvhhYY~TGeL~;ner}=TgGp^=PaQ)6+p9(ePKU-`@J;@l^yU)A7BF`at8^e5P=s4VvZg~lDGS6k+^7Q{e(VR{%$J6LxQpM>$tC3_Z1bVJalKj{Q}VfqXvHR@0^B90l?@vYQP=`o-CdzHp?okpic8f4s#-`W1V5J#~s%MnjY5ezyG@;@-LAMyqjlF^P}87MU|b<}YlT$(`F!zGI?DUB>Z{aUPvd87LTkP=DiITz_YwIA!j^!XCf7qnaHM*VCV@=x4--L4{3!Ym7zKZx~i2#o4)XelOk*9gElRoM?F{dS)tY>b{)g`WgA{)4+yS12+m5jQWxzBU0C_e1^<;;)+6A=F#HRO8bNd|H@FF5Aa*Qc&(!79ho-nw&Ga9#f|+0Yu-56N~P)g;abxffey{dVK}l$cIhrkS%N&UcN_5b6JO$=Ku{PcjuQ$wWqOM(WMgf^yRV2a#&m??QF1Dw&H2N*-tm`)v}~)e8E+6TSDN#w|5=Vt<|YNtS}Edx`(b-J&V~i=&mQUfY7p<=dElQi$3uA0Cn`cj;+Rs3)RDyb0{DDK^>Laj@+;CO^Mx!8ttAg_kB$|YcMntPS(7yE%KmVvTjOFyK_YA)!RyYSFeQ%7?*OdR_M}N`pwEKc$^|uv#xbfjYpuxV-bm^x5(f*Q*~~xP>KD$PA$Dk6S+AYAcWpr5`UA-Vr!#pJ7~K6FG1nCN9(=rG>!C)&uA}SsNMsledD9X)Y>9au<+#IA?mvPZNbWMhPA3qhYo0~old0qRBfRF8eDDaLrEpAzeyk*b2b-s`6XegaL<=)Wsh?{@fr?~40E$l1)T*QtL&M7frU`15vj~@$Bp2UCHRmk-A1G$WHbCmgJI@*(kaX#`lmA;|eg!yAr{;TsHg?_oQEv~kSJ$zw3%M(}JZzL|b`iB5WI?~1cC^zyu(1QZvXDSfM%Od`ZOzyc0=hF9}y>R5>q`kMbY4D0p(tUat@v`bCEeUbl{?`x(4J(oOHMb4djbMa+RK5rg+>|@N|KOVpaP%kdus6zCcs?v;g>lT*4&={d&f;S!esBK`SClg+=Hy$|d?4=Hh+>p8dEPHR3xxY>(ImvZZx;GlETo_`$a9hNX5?wzD|&uxI8DJ0gD-BY=OgYCZ6f6!Y>J;v^qs$OB5)-)U9^;$#~?)}SG1p#GLUClM!cwCC|OSlP_Hn|B)VxAh}}bo3c8@X;B!`x@fJ&n)+j0qcdl+qxokzHQIbSKm3u0_m$dqzG}+x7{<4FYIek*n_;WH6-eH(QyHEXCC}b&q1C^;)@}#c@V-riQjx5d1=mtc*~Np6qK!PSw8R!;wSl`t5W?a(97I*!er=*oT&y#=eKC@vN^7A$^X5og#EXXQc-G4G4aZ=y-RhtiI6)aj7?neGk-rJ0s0-=33cZ^6MlKhDeA4cce|sN%^p{M;LP>HUY_s7KRTSn+*hw~HC_y=^f$nr}6^^E{#Ir?QCuO-k3c_-+pca`R7ZOYA|t|I~#(sIZy_mpAecbxz~_uNyljRwl4Ctbr?+dSsC=eb*YqtRBmNvDw>{=?=)3e)kW085qle?VDE9H6g)$>jzQOLdr(5z@MJFFwPJCOUw4uiNC+YLhZ*KjWA!FH@9m?e8;Jkd~ki4J#Eu1pFUhSv20h#p#S>h_hZ#|>caJ8X~g6&3yCOXkL=Svu;FrZ=9{Uts=Ht092dlhhfdJGMx+^S?xb)vt>z%%GY*gqObJ;$>HD7Wh8@nvd$43PXp*LTR5-b!v$mlNak&Z&@;6mjGOI_v6>%{tFQ@Lp=WnIz8dv$b#@JJ_5LUURp`7nKI~U7z&#e#r5S(azB)nSMCen9M!BUL^n>pRK`H>U{dvliz_9CCrOnw;26Dwu{DJzAQxp=~pLafq7is-N6;Ut~89_a_suW3799ZdV5md=`tFg!KDoWA5m`prP2fS*D!GTmQfPSW-PUj3Q{+F&*1RYDDV(0Q-*}>98uBFr_d9AgA23kI?mASai#*ea*>L5BBMVQI?4G)RK%N=A``r8(Wj@elU0LDI$d@V__if+zlMid#JMB|niSW#WL247e2w;kHvW(O?tk)p@x?9&!uxr$w(;gyqlrGLu58{$2NKwBg9{djZjFDqQMlokkHRwIi{1=M&{Fv_F+YZnmv$mqnNFQ+$=X=cAeTGK+i_X44p0jY`D5Iyx7|6~YYi79>xpJKpo7ETzwDjnpD_`vD%GmjMV!KCM`@rQPl^Mt~U*1KN`Ao<`smod8$Cvlg+@f2*94UUwUhWzB8Z;Jg{9}3)Uc3mAY1aZ4P3#u&NQ4kR*wOH*N^2SwhZL@xx(2y6kxjyj$;2oixiRZ)RIoUmb-ylxPTg(y!py*XS#)Cl~J45nglvq6vB22n`_x}*8NmCtcwQ@+yPf4!uRfHT%WpXH3hzs%MbA0AWr57U*&k_FiydE3_<>O)S_A#pFLf&vsy7^N^8gYm|`JEq8DhyRFJX|0}IOy>1|G{OjeFQ~y|yNtxj1V2eC0Z*Of&yQBbqNvBM(n2kKDI_bV_w;K;U!YrLfB;a+7HpdMMOy$9fR}ZLo5x?lupQW#oIlfKe%+7Xr{rcQ*z6V?>ApJ5|KNaay&HV&^qI&aqr~L183m4q7n=$yA&6&~MfGpXod}o*6vdq#W@*k`EWSkECFoL)u4Okvb-io{5UH11UHW{%_8?D~R7)Fmgy@Ck2mO#bkDl!26Mm*!ZP0oQCKP+eb|jxz9_|<1_4LFtA$T{h+lguJ+*>k8}LD{$t>lcW7dPNMF0)F9y3xey|W>x@|y=NS+?aYx0q&V2#7C1xDM0`|wr2SN}@dNkQ}P%0nYJpr7Q#?TJTDzog)3M;6X+tN1TZDa)&Gy>XgbrRPx=e#G6M{2&YG9g}=?6OM7{|M*pNz=l9l79ukeV@CkDe=PAFdDR#!7EkT3bo)mdOiG0@VXHU7sElpD#1barBUBcS*=yCED41?p8bAjkuO{;?X1=CCEFfaSm7Bb&{`4ND3gYhOP({D0O@KEU*@e{!gAy)X}%)5}|3YquVJ7~Hr1#T7Hbn|^#CdAJH$=+Er`x3*ZLmJc&k`+sOCziJZgG1BW|2~#L{7UHVO~w-_xW!v#9I^-fw6~tO9bX^K=_&uk5l8cp=aBKr0Yhn!T6W9p{CLDkI;-bJTG&6(!V~#VW|pzPBrx!Eny$*T9F((~slnIvoL+WnU91#39Pu~XDtdR0V`4fNQ(v04^B=uit*Gx6}a@1Le2OkGiPS;Tv$@ABqmEID>gOYwXu7uVjf7Y3>aj*O*9+3aHF$!^#w-#!87U{pvre6A<6@MDgwk->-+xihNmHZ;pQt@rFSWi_UOU-!xG5r+Nj`4^?5wF@JV9-t`6jHR@N^{bkFi&o#O-Tpl$3vDr8TPgyILd9l-zaQ)$%xk0kq?tTR4*SS1L0XEzj1x@@+oSW~`gC;lZh^vHr%Hi2MAu32Wf=;OsoxGn;qe{Y)^wQ98+u0{K1F{d$A8*HFt1!_bJ`(rNLK`*Ac$kkjwG0JP!rs#mI}~V8<}S<4IsJaOZ`_HoPCj^>-7DB$HvAz0(#&k-W`$%@=fP&m=?G?oAc5#PEJxCsw+8&P@T*PhB9=w>dl2aKG2mA1`&TI8!S5a`@UHNKwJo-sCsy-dM=^h20lOn~N68-z|IiI73#A(qWT_`x$x()UIxrwd|-ruCb`Sd(VR|E7rk@!U*J+^t>eioXSMAz(d-QBmog;Ud#^ZCL&$%zp=`qqA6$Uo=G=lV?_!H0%Ww_^rw-hH^x|JKR}lAmRLesACPvH@6z%#=OJt!ui!S<_i_e9`zekALO6Yf8=8pKhw41Q-G6fQg97?Y1Ax`wJ?GzeF|B{nGk(UzweC#C+L=3kI(4Sem{h`{*qYNmMjggA$ZMBNJRW`CP^i5{k<(G&XN&AZ0m0xu|EaArDYEFIf#7nRl16|=TIIrRE%wU?2GvN0Z%%eIKI7R9hEi36YzXug8fLG9Z9{G$&Y7pwczp&&yS$N)FGt+X&U&rsAQp!0f75by3i2_IHcU+V$JrNUJ+T8t@((56eRyqHp9~7zgPtwoCoD@Y93&l*0t3Vck5vvp+*8LsaECGvZ0|pKIq?GGY8u{dl>s~;ef?Xr5hroq)?d8deb_EipId#~?~e}!7Mt0~PDA8%q`ys(!hdy_Co%qeuBl2>J&%U*S9EF~Nh0qed717P8F=im^iKaI#PvA?;>al$$h@q>A;_aRGrwc9O){(;k(qhZ7T4FfE9D!0O9oS=1rhZTh?D+ucfvV-HCC>6?rX%qUTNB;F@Xo%Yp1hR9j{NnKUufpBoC_R8%YINic5Is3Y@yV;>NUu5oW-tN~2IG(vaIl%Rorbz$H!Bt!HygB_IxNllnIr5p9-Ga20%1JQnY}&)si$wgHU#g0XVw2#2nqQ6DBgFkbq}r#BONPB~wq7_b;^$O}J)bZzCmBfo6#p;cw;#~bHxH!1RPKP@mW%gE>cgK*=7E*l9`!mt@-fn%cF7&?{A@^%a4W<6S6D9X&}G~^->_!^@~-20WnbR@rl84s^)~20-sRoXNQXV9f%FfE9fJJIBlL4*4tL%Lh-ob<2|-?DxMxtE{%{JCjtuj7Azw=HG@Ep>lLn^2Vx#9bOFYMnkvT9@B`kF4qr|t(h`=wyc^4EOS%S~$DH)p-)!AG9k%87H47lqClxkz~d1>rB6r3NHmyfR){ui`L|>g9pb=wC{n@_OwLJsR5X^s7u-jq)Ts&?1ZOtrt6w@w-X2f1;Hg8BkA9&M0d{c?x-^0xRsVVrGwgsa41GerY)it|pIXWqn3J9?{p!AMk;UsaJaB-nahD6TNhW1w7~oedJO<68&$AwZr_L#PJ{}Ep*hmgTa0HqiYf41>HQDCzG^1vKINI(WXb+X6~Y3OoH{8i$;hGC)B@}D%76j0jVJ6~o)Dax7T+31X6gms#7moQIk-}JXJ798K0H+lPGpMA*Zh538e*xvqE=a83{&paMn9L|Tb0ZON{6!5tioxQgjI#Xcd*DaR$UdU(uo%~+Nx8cG4jzxQ4NgBKb(Ml3JtdYy(mQ_J+>I4c7hR8r$EpI?c1zlfq6$BJqAYVNYpv;*Z&9R^c_A7&}eU#FRlxX0gbF&p-zfI@kN`1E$#xi3g#GpprXybe>4oWb&W;=PZ~m97!HBv_m2B&~9uRjLy*dTFxfeN>u9hvndv53bT4o|cS;q;4B+KtxBh@U$!=2}%34@y4OYIi?G{QlC-WbCnI)-IC_);AB1x-`MH&!Tynesd5)35mkF^9kbS^^a63=DAC;H%cnQI+3v_!5>Nl!?wnQQ^)~DVCd5DkxL4wrVNqvm3UoRu))(y*Jj`{6}G0sqpcKQX=hXsBIq`znJ=soG(1yvcq2K_^JsahJS)2KQ-Rhk?qNGM6J;PJB+p5j+DrPCm?XW8-i3wRyceH*7ZeL9q{*gazU3i+qBup>6jbVyH7=$Jeium4r`oxbZW29(9bISD!=mw7iY*<>{VRKMtl#mKpJ10NFH`Szs|p3ll8bgp>2kqNBu0OqxJywAo7%Rl)JG2yXpQJ5zOby|;>K+&nEERZ!?+Y_9Nx`;^YPqoWn!;F)C`sETl{-{^}$DT;iK>6qoZ{jFkpQzdOB>EbejL@3Gx@6zb94QVSwZV`qkcTct2;hOwo%qCif$nf9}5)M?E${XRzyG1p#Z#x<2H8M^5<}b9|Y=P(DPL6y(ueU8ndQ$@R`-#@?U^7t}Lvb*g_PNU*`{g8%g%In*sHOqVPi^2!9N&-VNScs~Z)P6@KwGU1wOwU~Z8a-Us(DOdey;IMqyZAUQPkBIf1_rWSTlAg*YWgOE2>#uZBD?B_N@0hzw!R%$RFJFGr{dsknhNo2eiy>qt!(wY|D37)||!@cNePOb9)C1)R#Tg@0iIG|8`bx-n;zz6M5{u8D<*1ylN2KCQ=GuGrEnM_zs1@tHF9Uo6Ux1r0%>K;t_i28^1=$*e`-dI1ru-B-6sQ6}?o$Rsr*l+gZ_+07TT>QI|10MS~s82p=GR~qpYRgIR9GZyyN>y0_sP$PT&3obt5&8nO`RNH4Z<+hWDah$l$Mgnal_Qw<>K^V(L&ga_ee(Gsn)|tp1CiCv~92Uuip1XPzxNt+nkM+LPKJd4>E>XSU!uX6)qwb!7!M%+d|q9GUMqKAwu(S0MEUSC7^28y{a}R?7aJ$bsptYsxwMQD+*4?rqHq%i`8|dQpJ>I-ei22ON4B+&I`#d(@5PjkCO7S`pB@a6)0fGU^#|{`j41Nxj`$>vH~gBl;(sUmb9(UdV*5O-cQ;ucM!hTaPrAITjDU3iAt2ZTL`FyNU&EGov3nN}~Ub(n*>Ptg$@wZal}_c6TZLZX6p<9a|k~!lN^_6=@otE*$vPl(q5t3gqRUw%-yrWkIvRy{g}R_`A$oF7sgLeg+I^Yp?D*b9|iBkI($pC_zAGbl;_t>B#52T-EW-hXAYVIuGaGMctUXZQ#uJPvrjhYVyv6Wys5ARZqQi9P6KJ^aA~Cmsf;tx^^>s)7%J+VNOAHHQ$!VTn6#1Fd=ZPX4*$_-FxCJ!SpG^;kd<^GspzzPfit4M#znm{sauUyi^w24)5LJy-t@riDy{QAvJ1RNplkFu>gtXD;j(0aGJj1wr)IfDi7ZxodLha*6iWLATJ8HeQl~wfK6V^A>|v$eYd?2nx0KSL)AO^C^qt#aJ}3K@V|4?R^&d1Wq$lop>#>S2uXj!(jqrVpYb+-=RdFJ|n2E+BY6k>Lwt~1ZQ>egXJ2k+d9ok9^j=cgK_A}l@zOtRWj8~6hG-oug1%Own`&M9s8lSUnw!Fj3WXh(pWP4%wX$B3O@0J?Toe)RsDbyBZyq{mJBbNt@A+v@%XrRhB{m%pXELGbxTk&o1)h8j(FN5Rhgfh6>K58uMqRYZ(Ae*;GaINnyAhvI|HKBST=Wgggm0Q!BKjxr`cJA{3UdW%utP}bh<_b&>YS9BNCPTNa+Mx_t|I@Tz(eGFLHUawv5{~1c*87vCIk3-EYteday899)H~%i~15f|o-caMPb|y3kN1gq)6!nbMESugvMdbWH+imZ;kEmz#rY^H&G-ZI)0nPMtJb5uxzOmbm%(3^Y6M6UKg@VGQ?n*woR?MEK{&u)hxZsg9G}!&@ZNFe4t7krn5a4{{iAY=(-v5dZ>B^(jdB+#c1KSs)?)vJ|Y%^&S6BbOq{i&@A{a}=TVB1U;Ic=Jw85tK)U?VSr#`QtXA7%d^~r*v5C#i!`h`~JU*Vv(;J+}foh|Jy3r5UkB{Ga-ccfYFAbd5`|LEjgn5NjzLJdgccew;|3RI}tt0e`F{TrCpk6Y_D7~!fLe5t!XLb-JsF$dCsyn^JSbm=^o?~ttl|nmHem1EMEa)h4KXl93ZJd_{?`VG}%7%K29ZGyEsG|z4l$}Jru|c8Y8fPIta_`6YgdA$f{X((9@`#)0Pn*}M`|tZ{8kChM2YJM!{;8{dRQ;5EPrKgxUz>du^=C+CQ%>Y!2E5G3^g4SC^(Pf~BrQz?@OFNWJ~0t7$ETZu=a{>iDTiD)rkLd&CtU$v^y{#5-O{Q)LCQLRbST#cN{FY2JPeLdN0YoAXy8uU=B|eM%Y)Jl=12YB_@XGvm!W8-e3=SRS?6)9?lAPkEaMUuAj_1F8cpNd$;+(-Y>s+XutEd*+DCPq?W8`T`r~BGL0&ubSwUmpSicYcgUEln8(67ZvB8#I{%dqEelAPmW4Pb#3{an}Cf~mq{aVJYF$Tr!Gl9xW9+gGj*|f`>^@n^OGVI;uI*yNXqIJTvP31KB3??&to*-ZD^{*s7k3QCiC>gn`rhoYUG6s-81N%!H@`f^N`O_x|_$zgK;>LT(O;Y$&f2<_+r@LYGi#FudH}Z-JLGn3|mv4Tu5AQSl>PfLzeJrT@D7t&PG3vAthJO|PZ#rDmQaW+81a;T3Z^wU^U(Eo~{yFZCULdFZUzH}Au=JYqA={V8_kDHT)jEa7?cZni4ta~(^J!j#G??IP%V_?|lV=erV6F0x)OCMrEVioSxiB@K*v%wh*ThY;X7c0#<*~#BGhPwge23rac)py{VXMoIXM#;1Gq*_wby`)j{;T&V$nV?OB-ZbZdQ5NGblDNxbhw-b__@b@ecFGSWx{p8Q$g(udCrS(hHMtnp@FIKs;lO=k*^q3k!>@lLsD(x3!#;$$8=eJuZhbHxbs(%5d4MwLfM6_GNeBF8Fr|6#Q^G}b8fC9(OyiLK1)7&D^Fd!l24CQY$l~afbx}pn|ttcsdMF?&@?DG;a2Olo+ob5e)?y+csk^NR5gBf2l+v&!4y56TX#ZbCVpi9d3rrKhBdcQ&*>w9u!3C`8_5Uh03UNwv&S1zKH>^);KhL_CY;E`9VAj2}tgIE?GVeb<4u8-=3!(_nj&$&h~)@>Jaxx4QZ?NQu>*=;e*~>DZrM{`O=#$cc%b=v%&l?+`uf0HS9l{0X75YOyXnGnj+xQ%RVJPe58!xn8z1Vf=l9A}K1dQE-CHxflBe#?iHK^Be;o~;75@BjxZY!&*Qt5ww8YZk!a-kIi2z*pxqVYy7-Rmc8UL;OO$K#FdhZpL2w2G6e`Ix%^Z0m5FU2Gi-28EKtKH+{XI>h0)Kq7}fhbK`m*bA(&bbwxNFJb`>p7AT0VO?FZmfAZY)pcto(xdid*0E9)sKOzPb+e)h*Rq?4->Em}OZOeQEU?A5WbVWHl1p{s_<4dXA6(c51au>`^A%a>)PrxgYJ%t#_=(8mj|rjCzdvxAFiB7+FJUi#Fi+-YJEa?r+%KeqNehsFRy_7KqE=$%KBIWT!+9>L{h;t9c8zk?&FdR1?$hsH3>`!DrLQ&RZ4m95W^ENch7cI+W(x>AjLjIwXQZPr*{Y(2cbB>97U3}eHKpglEWfcHcBiS|#-1UZ_Q~XLJ2{^>0ugK6&`$@E^MjSYYBAWO@7eIQMpqEcY16fU*qT4A)c04c*jy?3tNxIihD-vp4b?PcMh(hS6a840HE3SL9VmRs9D%>0qxV?0?-C`QdYYrT&K)kf9*>DE>V1XXh5$U9lx#&4!fK5!J{=wAQB&2s6R#&A?QpO{k-&I>=|LnUIzz|Cu9+I*Pl#=COeC)BCPMzt){E9xjZGbT~M1+49U^$Q@=s=@B)|fQsJAW^pmpMO1ugQEvuh72cLUJ|B5!v-a%0*_p7t=C8BjHsn-4@wZoKFj~2C--kHlLXJy=z9-P(lk*#(4&i3KX+;e9YW(NywzE9(c;|Wsm178yq6FA>)K@=~#5(-9GvVf=KKqbx)K`&lmBrTUSfF}4l9)IfbxyDG7Wa^mG@#D;-}>Qr_&wizV`MrkZ(5?VKMVOp4H22=i!;EsJ0W^d1ohR6s{=z*TQXqUl`qp597NuI{FzqKgG`{#D`Ng27kc~h-Z452ZtQzLc!`1cLp`_q%IGkn98}kG74_9B6@~c@lL@Fl``0z-4eG0duP678R1%=keSIXu6Ln6oYT}%sEGC5B?f)EEjJl%FU^w@OaT>gNTKqae5U)ek-AgP<1DW2NSAT{hw~N)Q721^!Vq)KgZcIgewZ^67OtEMNR4;a&b^ICf=~Q5QMFs?(-F6~60q;lhTA$)C@_9(zVxk#kh4(|PyB`W@K=s+a@EbWd{(Axg#CB`Nt5=}T>73Xf-K$G*`}w~5g8E@k@>&z#lLjB(WfVV9FW)*3^V$cs~^nd=&n0GGNlZsz=>lk*_}Rt3i&I3E#J`)31Apdgi#Dw*R+E8r00)J#$I}-oMfejjrOQ4A2gY>^QatbxZM)cO@+@1nhgca$4gM>K5fACljQa?gORwPiW)kdcF>0Pcut}vo_x+wbGI6w{JL}RFKNuSJHLyelFNWSuV6p1FGL+b|doO8_7!TJ!x>){cvROZM;t*hv!NEXz5@q@TI9Q5_Q)gtDAH1dOc`+H;6JH$&bf6ov{~?XitLgbPdATqwYjFIRYNRT9NBeZiNKa|o*a5SO6xTn%4fC;cqQU_Vol4!jCNKg9N1)Ox2Fu_zM@Y|bxYq%gPW(;bo=z9F1j%3)Y?OubTB-g=4K;-{wV4kJa#$*3Wu+6j<81k!|w3U(hw$q>VuS$in`QRd4B4|cmfVkh2ECCkB|3zezLMflL=FlP8!SVqF&Y2-+n{u3ln17e(TGPpr4TH&k~r*f~(KTjZGB#wWxoG9b*GG?{NKp=ZO^t3Y7w9H&4lg>M7fP^}3@c8Ej8|{cIjibZSBel1e&BXEPOAkhSr!rt<2Valm1RPKG8y)f{xb>DlEW+{J-%I{~ep-e9?x(__VF9Z~u9FEVWxfY4y}|pW>J90?VS!>x-apAZsO$1I1SUA;j`d?u_>1R;GwSaoYwXAXt*fU$e`!Ka<*}TS%mgZ4=5IA}>fA`QArq3bB~ldLBB%URCkkoMHE8cz_zAg+uq_N%&|!{skgJR+Po8X{MX=XI0s_7VKIZH|{&0&6EsG$)`QhDn(Jja)=q0avd58(!wKuJsXVj?PAph*Q}T_~AnLJy4vDM$MbhE*iGgW{c>G#*#`o!*#B^@_#vCW)Gt0F~E6g$=X90VyTL|)pU(7@HOJqX(^%W9l8OXVL&YhWHviZ+U{~_d=bJQi@chKO(*>oq7-Kgu{RS52il4d|bkCeu#5#;CBs-B#oMZl8UdN;E=9zE9OW)w6+z{vJ1vv-T2?&>ysZ9>JfH3!7fEEuSl=5O^0p0za%K6&~(|9*h_O>}B~gIH4rrUF&3ntuc8IzKJe;wedYSbS{CB+=%y2y|=doXk+Jh19<<+s?s@p_H?-FsaH4E3Uy2H)xk3JE(Q!m_dNb5iu!~)cU-vaK2UvThAr@Osq<6C`1?Se({{Z?F7Rsg87uKr2n#ifGueXovsO%GrupSmn6*mm$ZQ@zAr()~&`5)2vx-dOIe4G8amQ?xJJMi*OPiP64b)vH2d1qGC`g9__s*s!o;bR-E-~|4Uu3{;>$WXYJn?DM6hz&QlJCW@v_&f*izklGVfk>QI~`I4tJH54qF?LKtA8zR=QClifz<}VXS>Ha|0P*NHzOLT1*q`7TkAB=6Zv-OeVIWA>Kv>_XvhC}lYve6cJbChI;=S99KWW~W_&!A&sH_^KmW$A|IYg=3<8^ONU5AAVDZejYLQgS@#|1^Qxz1Mpuy2ywLZgaoWHeEiP=}qgt-2fjZup+&MN92`%=R>7Ccz9c2DjJlkxG?{8{D5hMK6P8+$*QkB`p?R_gER&H(Rf(W)R9)Jy#_mj`wwXTsa2?ChQ^=ocE?d2fD<2MrGFEwL~tN4@mBE39+75vjYJyMK5pqh1=(^(nVo&w!40r5>Tncuu!Q^|5!|5(2`71gGfhU>sVNhsj6hR|K?{ectYMz(1Lo5s#6wkk^z-#I%j*;qb~Z8`FrR2pBW$`d&{w18TpPQiRm5We%4t$^NY@5)IZ;q=l%H-O9Lt{U`H+b_qcwpOZ2h&8)pCU3Iq29;_sj9^(wLk2MBTiTo3BBv!)J9dp`K%Oma(}OPb@2%_33Dm8~gehwlUYZ>nJbph^UaIL+8oYjY(Y((V$A5ObmZMothx;_CXTi&nFFWm*e2ml^uWw%46?_bN>gZbKOQhb|Wxvl#R0{9MZ~t2_^B_`hhVJK(zM;QMJfK@lK|cdj^FM5nD@Cp?P~_?&lnI$>OGHPCkQa-!_w;m;eCy^dTEocMosDNb`)LrfVOh$rIrzEat&C`<0)v~k((i+O@R*KCmmUG^?{mdshLH=jDq1`8GvS59&*zuBaIL%J*tsC;hlK>qzmwNqO_I>_WyPRNfy?(ux^(zE3mu%Td2^+BF|0m((a@*5{-LPEQvYTQKBS5&^Jn+OdYjpbOoJ&`YJy4Ch$2_5q0{rV)zhx$q+l5^hu7z6ygLka}mBbT?k5IylY0aE^^?`#B67acM<@MM8A6W;GA8RpAC{WJ7hb@AlmsbFtjE4}6^>a=AI%7PQc(zyCOp65Cfv=!DJy`Kiw+e0@h*dwRnRdOCUJJ(sw3O|?1Z>*Hg1T)bkVUaxf3w{v~Ryi!7fjplvpI0~X!NWsEO8e>X`AF!Anz^Wd9+W?E7;IrcTiWD@?;oQ6S#*J)vFHr}XCeg`27lz~C#%;dbmG;0_)TtGCzzssyZMgqh`4boP<u2;L|QzYpe{WcK{Lj`q11;dOQu{YolOd1H#|ct2F1j_mbm(6OU6Ao4kKs&0dncse+EoD7K%!28r!KKjGW4nQ;KAzQ{+Q}OC;qO4AR$>|QJ^j93(OLJQbvtK5gBMRfK60W>wMYfKmRiZm#dx22LDg5M@TEcQ>rfMe$#|au)s?=F-=)EoQI#}3MbuYRy#w*ebTC*YI%S(L-amKW^fv?ik87{;y@f~|5wj!Uc2{__g=JKFDL!}0T-pMLt{b4Z;V-5Owz`O^w9Ux{yWl9~B64zv}p1!hI#{P`%+I@%zdfYPHv1`|!uk9R!gidGu=z6<@x@Kbc)sZ;mYy(~wS2}*8*hi>rXhXytlx-CD;yz~nytXpIBUdq?&2`ZLxS+dvKLFP+NL2t0j^0F_RkfOm&6?k;)HjVG1l_oe!Fy3+8xSpDG^7sDk?NZlIAQY}FHtm^T2xcoBtJJOO3R%D@lsJdgPL|DL$%L~E2*i;>a2N%fi`=#k^(k!0*-vv7_Hmk6KS|7p>V;=PWQ1>H8->^YHUO%An8b1G&KW@VX&X`|r{5@(iIB54dK6g(Ruq(><+0@}Y6Vvnf$*VvD@?s9P{42ryS>@fIEFQfkxOK2U@$^-hZ2rDon*6>Es>TyF9Wft7^y8!JKdv&tw!?mk2anxY$3LB(IfDiLd|fHd2hna+Jl=x4EN-9N)oZbToa4hrZCevIY`AmJL9Ys*AL^XtAwOrVf8~69zZgQ7n$Og6U@2p#_mQRe{7`A*p2b;Xac=dP7r&@g;hUW&0XbQx+WyYMyx@(kc8$*p2=G{LvHs(G%x6h~#NzAonXqkN)c!jckyGbJndJBFnPIYd(<ll`Rf7yU6|@`mye7`d8p}sJg!R3-eUav8kDdD;MEh)vmfCFYK)|buzoyG>PaeNcc;(l!zgYxO;R9J3$f^G9CuPZfnc;33Ek5M_iE@*s#gM=I0#=R5E1tT7>*&?8vsiGgxY|6R~B>LgvXxYcG}LHvLMf4nfXL3v?sSdKtMLvKhXLd?MA&m}r!t)}@(JxzpoLh&)oHN#cLF+$0R`>XzdlpdnNfVYLr|NtD&dMI^qdFD&9*vIe#?uJ+)3N}ndHNj}E!2&*-cPPaN2J#$??q1KrQfX};6cj+Yrf0KjT~!U6dEz%ky%jf@Jr;k5?)KZtz<%bU#pMTU*wb<@=PELf|8Y$(^q4kmkLpF`$>9ipq}5qVaO-fy=(DZz<~+g;R0T-kyG#at_@j0<;Su!_!}%lqvftgYUreH+9Q*QD2288iP&Xk4uk%8s=;i@q0ybDUy_x$Kd4jO)t(r6fVvedrm&oIFsD4SW<(S<5s-gbKseWGhDNIlht5o!PhkUZflPrS`ELirZ>8P#|_GPZUz3g#2KO1(fp2@sYgxssSB}Ar!4I&LHzH@e9zve&MFM=yaIq<%lT@o-MW1R1PzSri1NjA*;J9tn%3wiq68MSu58SpP?!zodoIRCgMs!1=%@B2yX+eYuNxIS|KxIqBb|M_AyPu~ar%cnht2sp%4-*D?Ht_vsf2L^2&nGpIR)j~!abp_>jT3W$`uQ%$}k7S^(pz@kMELosL1*UYPu1NcE;CN^~i`!p#MHjB8H$MK@yz?L%e6CfwN?pW#%HD&1r)SG^fPYfstNV9w-`5pM7Zd7bz~%P}mu|G8e$X=NOm#CNV5XwphhTo>;axw!r`#mKH$6*zL>zSmcb@r2jMYW&#`(W@bQ(b@wPn8yJwGBf1aO=SaGsp7KZE<}(&u$ma{KJHhm$TK@iQscZ4W{;!|-Db(jn+<%D;D9prXN>zYo0CvOW&Nxb`EGItiE?8K0jXM#-q~pe>%h%bt$bOFey@p1GXYF&J-NP=ZA`0dozD*9^1DS_b=~)LbmK77(msTdu5O7)Q!y%VNOd4P?GN1-!&IG`FQKZULd%B=AZRwpS3spzS)ctu)wr-Q{y@05kHM+F68&6bow4OK_H*QfL(y(r9sGnf*2l*e`}#%a`7cO3!-kk6j~-cTpxwCV4F@>f_=JUY)TL5$yyT>UvVh9-P<)Ti4;6RuK8gYRiX@(Vxs*K47p>f~(Or)GUXy?3+W8=Vc)|DO+E4=c>cWI)86*F)@>E=YFS&m#=yENXhPP6&Ke{0Pm7OZnRJmS9`IaRkX^v3_*-{;s5h1#d|$8os*J~~#QJ*oIqi3eFg4c8RHetZoTmv6c`F+i*8v4uws>YOW}Orp!`LEqF_GqhdPT^b~g~*zT`JDk;^$9ano{Tg0bSO%$hjlvGFDKvjkXByz6BeJqS7V`zk+UfeQH|^IQJM$@NsWW-C3B4UeWj_n0;l$5Z=`h*S=@@4RhU^7weFpGxwlEN(pNIydB0-|Y0MjN8zk@3~qhJgG-V3XnWtVvmjvQwxQx%Ymm>lGb>8}IRR9?he!+L)Hz_8DHE#0*1mnS3pqDVxP!^v_f7Oe{X@NXlIj1;`wl}+)#ur8feqCEw)6sWs_t}cA_u7du6z+Ww_Zt0)>wbElgOz)Q+Zu|5^@=;{AFAKS&Nv28X;Q~ykY@-)73^L@aPyZNpCETVe>md6ErOdj8b5%1p0=HiuQC&;_yyZ#s9Q4DUae0nV8Y!Lxl%PhTqg|pxqmlWU7P1m&R3yB7d);Yw+TJD`{_@D`}c|wDvK{)eLN$bZSKbuQN-^~NTPZci4@V^qKDsih34zB-`L^qxP)OehW`id&sTfc9g{=*@OPA@stB^+c;uAI0IDy?>Ly&*sJdRyA28sspLzI_dB`~evnGaX5pet;&E>us>V&5iN=Ez%1nk|ZGlgY^cH`!6ivO?wf)?tlbIC&bHWx@cXw92h+llruC^C*(ugHS0SyLbF@Id>_ZaVH+_KF2d63Q(Cv+y~g{50Oba@sVtbd0(DkACKt7}&XxcKMU(|#f3RNc}nNhb76Z#eu|2JJ@01&Svyxp8in{-J%o-5EOnMu!E3(`Agcc>I3UHg@|D7Etr|MRn9yR2@WeZg+T745VB{JPjxG!8gbf42=cNBfkOtxWE0rUMnv;-Syehl}dF95Hq-zgZCZu`<8+8EX9(?ua#zg;}7|s+8AF52%Ls?)F1Ejzc`RcJ8?py6yLie1E)vS^XTyWl-}{>LCNEMpKqahn==FYj`^ld-HQCm%NMPZQwcB=>ijotF>g{FLp9`5%`-&e`Xd=J$RxB)jGvfjsPB&jzDUyS_<)dWqt{yE093VGt*Ln2PEI-dRxq}R#`oCEwBJbA`ZynlC!03|rd8>H(|5EiK&;KCjw*se25{Hpfbu4qwGGRjc1K<9g$VKPG*pw&Fw1_2(*aU_12!=ly5@CWD8~&8Z4@SrGc{K%LqS{9W#M4VdL60;prR#cIf@e4=$#1Wew)C`xxN&v>dotT&U}C&J1a^$&F(le&n-?SCrfhMdw{DWYs{f7l*>F1mS5Ii?#h}l$MX6&BcC*D;`B!oSwQteP`ioTdkSs3ZxajL22wt6=;iS*k@MA|@9eSu8s?~@xcxaav&Q1JQjt@Avy#nZ9>*O%KsT8?jVrxs>Vg|S`w6{o@g?h=fzlc*lf#CMlE%iZ8^{ulEAt3MDViV^Y*YKc!PY3UjE~h7j)>Dl-PRN2IsNo=0n{3p@)0b+^qR}4}eGIth{bTlk9nSxhAGv%B0aO_($AzdLsJI8KECNhFoYxoR>9-|!WN_zUB_{mXwpe;}GwLg{{_Ck@|^+7*E3r8okRPqfBh&_Zz}!HK2+ZB9%};nx*blG|3v$UY{|c^MeY+dW8Qks`Gh(l&Zx921(*;t-6~{V0@`P}%mcme6->}eocME43H?_qpC``~JjjCl#=pIezNjB4f0?x!8)y*;-%^gDzH<0mr))fd13%ww3-8cHeHC?o&OYH2ba0&NZm67v>waiMdwIcJ288vB&;B5f+^oD#4nY9P)X8-)d%;j+`us!UhUD%5LPgS*|#RI!ZJy}+)kTVaTpQT5S(S)e;Cf_u(`l)E2U6-^vGTOqDX!ypPrY9Bg3aKbe?>wM~K0~`jUb*jIc8(2YlhiJr+KBp!ihtM;%>fr$QuX(<_}*Rmlzi!{HXY1_ZQgBMl|0V>eyq5xRZE8yy94{YWRQDa(U!Y+kpYYDuTi=G1MNfQr(0-}>ye6$kw1@)3cSDCGLufgu6d2RjMK;`tc;R5LO#z_ey;9X)K`wAApJ~!U+K_k2Ln6NZab8Y`*I$zV8t!r=B?qVuND|jOn#BZ25Mcs$5a3L==_nk@RuBJo~CR%>MQkJRmt^&bcpPrg-_z?GrM?*kA3(a9YRQ9@8XHPVYl?PElv#Bn4#!v?1WsK*miu9ECIGxtof`qBacpU78)k^i5G~}2BIW%kpCLYLTCnn|Gjfm;t3uivI7~kq-~j*XAB3Aa29p+8Um7#&dgD-z%KL1gd}37Ae$S_bOZVOnbqEw{rHwKUH|n85wlZO*dFDJZ0;7x(@24`ls@#mdR|`BiZfTV2J$6?4-n3A31P-LAQjy5%QU=NAEf>(%@K^+UD6Kc>QaV!U2Jc=n&?5*Hlp%^-}-qUFRYi=rFn`+r`xixmeCo=2GWsl%sgi_`ydw3}dUF814WMuBHr99`7xlWUQ+1N8cqNsn?H$}WY)xXa|nE=7}tfP}oBk#SjRN*q4BEOM)&92{n&4~%5x_dS+>_2_gWRO1j;Vi0dD&z1|J!M(cS5$ol%Oz}JM(jSbr4)IXi*CSMM-FVH@9E9Gg!=01wJQZSk#umnem+jv4(Bnx-bW$VWEkL0Zd@h(aDDWMSoEio!+=+l+x4(f_5&CgdxNuB8u_jb9%9_*7_(XDd+vnd-g)^wd(_W|QMhwOe=ocE@~T#tHn4{M%tt{E0@^(Hc)HE`LG$QfJ*&kZC8+TLSu{kI0U(LO2VAJ_LSBjAzLjOkK0aDD9AJnh@1D+KUKiYw&#qJ5H;mEZmrXF}ZKyw@-1qJ13p|F9m8VFHyW`tl~~t21ZRL(ZzQpvUuKqe3hCuTDI_y=iU*3vO)b-}aoRUW%%8jwmaN4PL1;+av=pKJ7r#VyWQGbU5`^W?lJyT<<=2?ss6d(t+HrTxiO}^^WRu8Wh6-s-NfkAzbeaCGPE3UqHa?+>VJUQfRk8E2sEE^7pO&ZaXnw9Q{`cS9JQsr!wJv*5d}vPx$=k{WLl8J?c-1&etu&b6Vjx9U+c)m=gQ7EJ?p6*3o`%tU-h;}UAq0D%vD7tHpKLg8aVRQ!HYIyrpSwNz)wT4M&ljY=a=S|lP~_!pyKAPfARykzEgb|XC=@c^I~$REpp=G+M*_f0+di)=rm-4r_0-nEG^x%H4aipW0=8;UGSX96=dqAE?Fr+=&Q)>IEy7KFJ?nOm%i&mpCU+JOzftb!}@-sAIj#PTc088{Gm_}Ts84QRLDSwE|6%V@xVWYe8H^ODE8i0{{~Nqgx)Zfms<3L^ifCoxlx^55oG7U{L{`0?JDoGkpt0I=j2jC_RrRDF9Rj=Z(%S>)#GH}-Re3Fy9AX=7-~qp#GOSId*nbDxufunv!(kg5;!nf$&*Ng*IYqPaQMIoBfw)K-D|^V23(~ia$HCln!Yd3pHY`k#Al#KWh0WIz;)7&KKZ`r`o|<^t_D50BZrA$NSgujMqA>_05t1n>tmiFO*W+&P|tS{)tluc}CCRX(DKmLz58Cb2C4O8*sz=x8JqxTQtcT^OpKuxVPr@acYd#$`sG9Dnqn1}q-5!XhRD+BhjJN&m*@r-XB?T}hbaQjSM?n3UmqVLe~Lju|*%kr*Wcf2?`mEB>!BtS%9KLYznSoyC%#@dkv7VNokb6tXJ;V)x;v?66S?0{d|j<3*6C(ZgX7B!<^1-x^`;XHEmpo&V@UJpMEly7SIiy)i_=XEWhs*ijJ`LDW%HochYUEU;Q2=44rboQltLEoOtmuV=%T6Hs5tQU}g+=-m3-`=8@HA9GD?Cq0!8RG$HfFStHxEU4P+v5s7itV`EE?ZEk;|Ei|X)9(y!oY=*;s2?5(G$o$3BVZzx;F^HzLS;vb_}T&jI2qA>Uo=ryShH@NJfO#fFQ3;43EoA0)pAlK#jt=0-95D~vrqfhNjMcH{|(+Gm56n2JFO3%+>Wtrg_)i&Fh$_2_J%{JZmb`k>LPOg7#;OM~wsQ|se+;;im1IM$QH!7j@5xPg+Ut7hJ9B3QLevdFCa#1bDKH)&%gxy_3t1);=3jZz#7Xq?MxGJmX&*Ef;5jL&UqeTZ+(bRQ$$-=CL|&?8yJ@)?^^%Ra9M8&xQo%Ufso_Xt#gt)*=HN8c_8JPi{;e=hSmNwUY*W=XnPAsUxTC`!J3UMBD!Of~m;m<+{u_>|lW7V5fz97uxM*fTGPO1p=}kH^c@!L*DDMa=BS50rxgcee4;9e8se&yjLbnSev{4?63)PiI?);$wDlc(Qw$j?I(}@N&Q^b!GfvkkMb(dBd6*RO&n%}($8BZl_JP@M+#lODNBRkY-4ZY80wjb#qK}4=rlOmYj}jibFN3#x7}<<2deIoCXc`C(x{^-L!JTDI+^B;d?{0Nb`l=}?p0Dx-?2JcL->#kt%qQR959g|;IH)0~>eq3aSYz?e!Wgf0sP!u$Gs@=1O`U#=ze}CC&)UKdnGjWQ&FL!#^-sW2j!uCG4ccAOe%^Y;6ZcN)gPBrv$P@aOU)qE`x93E^Ml~Hyo_HL&_WgA(b|+AZRE4;ih9|?Om3XsiS5X#dPBWsOm2L;LMZAbDxPf56BbZ)9Te{)r~IKqU)ZpC#*>AfC3u~cQ8HptmofonB(E>-LcXf{$MexSG`M*0u;#MasDJiL9!Z+;j0QjJYr~^9A=gr|KNA%~hceq&MU#2_S9cn%SGhVcVBq6ATdNY}QY-JrPFg`gNI*x4!A#UAc0LA82dfFF3(+im;)`55H#;XPo(cU5YYg?@BR_rcOT*2REN(vOOAFL3J{69~n(mRhdd|kV36(tlqM~Ytea4x<*=FkEt%TR1;)0IUWsd#b>p$LPV7fRziP%enK<$>qRoOWH&bFoPcBF0zvAMR;d0SQ2kW3=i~gJ*xF)9mm#3%!(EBmZ|HxZ;)EJQ$@TZo$hrCu^j}f+*(HAxFkmewq}GP|A-eX2>9s>l5H7y5*>@)DD-ONVuaum(d+zq!wwJ}Yqgh2JgPS=lu3shO2>P!=H4D$|OQ6B&ODjT4dHgVOyL@$=$@OUPdSrX73F?H>1iPk@96EeydaH586YbLg;X#^v7(msbyzY%U;kC5z>giL-_cWZa&NJufzo~Q6#XpPyy*o1%K2OBFx!ygyBbJO3+HS+G+tug!<2Z*0J^xsw~oc{}9d@6I@Vo;ovblAI5IG@$D93C+iKjf&?<8=*n;{`D_^9YZ}p#qB6up~H}0qTIF@JUZ$~VtTsK|LSbCqJ3JXN8H*fL_l?=uh!Idv=3Du%K9j|U%0jAN@O8EKa<_0cirJ*!c^(%p1%QTpM4X&!?)gKLW_AwRLEDXh|fbfDtU@2^C@u4_}$as^Uf{cbmqJ&ksw>RnFkV{q$iTj%oF?V-mlF+T#1E~t#PEkQqwYD0YSqzOz|bn(E+uXMDV@1$uR!*`j$=*XNAyc6x#meJz8Y#$5G>iSDYzC!y@>(g{|Hh5?RU)65K`1V*w@(G_xgUn2?vqe1p+^-)j94fm(1FG&t$xY;X^(iZttfm9?y`}deKkb+7aIlXKc9es0A#$!BEn+}pQKj6qe6(lwX{#fOy9rPlHdB~1895an8AQIn&n|k@CF-I*!;gwg&m_Muf2U4}unyYO`(|ivaS#ihD#tC%{)5k(^ZJz|wZ3floTFHHJ(#CXa>Ow{;rE%`x|bt^JpL%=P;=F88mJwNu3g`VTs#CZ62?5vJB97*WBLAdqt$6wf6GAsm7`^s8d7PikD9Jb8!vc}b)~`=DA#cy#pcZ_L4KAz)|E4@ZzGl}PO%>}*SdsgkR^foUXkoWR{;zkLpdTAMr#t}p%OX{mAuk#{Im+5ocLDi6pB+1PDbV3wg8jzGOddbjhR030MXj9{PVgw&&Vw|6m47?d948Xu!pg4s|*d|D;%Z<4I^K$bf=9*0S&^IGIq-7@Z=ko#!e`^K!-DCUOo$Y~$66z@LBfGy8HPr6o&pPPHF@?!q7OgOQ^xza_FNACr6YQ21v39kngy&vx4Ij>xt_xij84U|QmPoMGxdEK6zH`__wC31J!$*v{%x%ux~3ttG1^(XD2BbR(@-O?gSz@OC9e=SVVf7SFMGBzTQ0C+r0i}4S+(f9U_z8EHWrJcyr|A6{Ryktc}@pTro6%L$qXh40%t;4>OHkMZ|j{Yl--!gS)HVt4nH)z^2TpvR{@&c?4=wta`>Uh4>DaX$;{z&K6GhZ%cmtK-1*WXhC!4abvf3-!~=>#}*Rv_p;}>Z|mHuXOXIXb^X_OHEx6=X0Hb8Is=7G_Y05eQO0cpC6-bJWr7CDK(!7?7?-A`^O9Nxt;O8e8>&;6--}wK;$R`sJLeD^*nW7o!i%cnNPl_%Bs?~J*Xe3xZHoY3D6a|An=H%9}|_I{&6vr8xP5Ogy(~PPu6btc@)6HTw_3*@3~tK=s=v)dSzOn)93Ne`jNBJg%s*rKI{Z;Pa#V%I3<*TmlxxG6bgP;q!A~`U`L-zweG<$3@w@(LNSAT~lOMGJ&dp!(WZ|p~9Y%zA}M||2_8`{doJ01RsttSlqnkJ3RH1g@lesS7m2{#NEMpx+b_z{U29n9!^yo_5Y|8Nu)uFCX$TJQfY-0A(~`LgCs*`jL4J{Nhngvbj~rH`5Z}vBAE)222&{-sYHp!-`?kW-`0MA|2$pK=W^|{&pLbG>wDk#y1#3)?P)!2Jr2}OzaFo95A(i+?t!i|4>(Z!h8bv}gM9JsL1y+bF3dW9HYzF<-wLKHC%H_68;utldE5-%Qhet0?tU_jW$Ke)S$3rr5eKOnQo(c77ymlr5pV^iJNMU4ndGWm105SYo^)5`jW0a4RLfE?mKbVpC~xcSGDCtm>R&*G=eZGJba``f8xyU~=qy0f_!B#(273I&vcHrvRR23rY{$A}7yVDvizm?>#EQ^Mlf>V@(T3v!N$q>G0AysAmprpHamLV?*b0i%I$veq_Mj_Z2a|wR^BDJCu==@0U&q2ewzfSFxw)s2iKw&c&VLLduq%(z6wj+m;_O>LKRKs&f{+oII7H(;`E%-&pWrW_s54jzL&E?1IMn_x?-KPT;g_%=Q+MH`J=;;|RLCFyJ$D5gu6Bkh`h_9uunmWFY4!>Fdy|y!!I|P;RZf@8+w~H!=7?Jam%?&aoqpLEAy+UugJW3u}UcNHOlEh9(;MBp}rRjR=JL3`Z4TGbmwcaM)>uH(K+SZ_M`7!?2%g@Any;jzi{<0W3IX?LA7r>02UrhYBqHdWsbp7rzUm=jkh+m9FebVNwea~+$3%)!VDcn|qpF7RXVlX?71?jH?k2;N})YU)fI`MiU8!TGik2|*mdHZQ=*Jl3!a&q4p78CO+ufGYBl)Cpz)mIW!_4zQ#X+g}Laj2tiWYv3J87%pO9DF9W!LTt@3DHjsTOyPu*?5Wi_#67Yi!5+x7#dq;4bPd+{^GBK3%-~W$6PWm1O$#EgDVVbNNWqwWeqc<<)!pkI;#^p5BR|nG^wml@?U$TBYeI@FvSF>+?bx`92c^;IVg!SziFY6UkvIt$RTfophf%@wBImax2Z2?5OJT3L3`2CW{G%FqmV11G2i}~JI-~Q*?$EFL8Y>3`%B9Nw>mnVjcKs#c7M6SDzo`jtI{XW_e3MIM9>alH3xC4=Hy%Pp+muII)B&)2GdPnKYO^z9xe#w`4A{bztu-%jpRhjaLlVHxO~AAtHQ)N*}DnTY_-|J>O-#f!3jb^Q4`&X52WKP=GMqmAo$gYQgsEnCb6lLcK*Z+4>|*miMq_pv-S@FuL&n`D68k@gzWmvBV>D#c-#?|dJ*Ty<&Sz>)MFE^QQ@AouHts{2VU2vcYLewT~-YSAm-M8xczSsDL5=V2zuJ$)OtsM`_q3%iNYL4g>zmCFv~d|%1~jp>X2UO9v7SL8a{&n1s*OjobNaryUYN?!B(PZHF;F(+9>M9%Cqk?B*?ctNrl#$y*Y8%eIyUWS?QR9L(3GFFFI*5N>~LaLjS!VoP6?KdocKfl;}yZWtqmk*X#J3hkz#%=AUEeSdv0{CI#+jxbK&)coAOEa?Vgs?4eb;V_6j9dAt`DPmDSm5(@xK!yO>Y1E1#d6QZ*&r`_;b`aElX<|CA@HE9iYqStlII-!+uLhoFc`|Jj$3R}Je1`Rx&aYJicVryfQ3wkfPm*dv7R7q80S^2Rum>ju|2N9|l5y_V{3Dk+@HnY)pyWGp!<6>YjsPy4EMISvdM+BU&gY)Y2lvL0gF-Rc$d%krR2*3dtzdiwF&u>x}`deUs*ujuFihsr2l8-Swe3wh;?CvBiH;ACX@sYXdLd?=fXf9;FL7s_Y7jbJVSAdaU=4+$&c+%s`B9cQM-QcQK)AEWDevmSj7jXM*8a}edP1$hYto#5I~oizei6f^0m?&OJxNi==OI6K_l|wjIsl1x0q0O*yZb^{m93xIrNgL!h$~=vyC=hK;E+Ghtd9Y7F5uOhbwE5my2mR3Ut`8eBAgq0g|X&$bA!|b~YG4_x?uPhWuIRwbUvW@xDI_eIm`K)Wb*a4xPv5f=#38=lRo6w`^a&zU4qK4_3VKs}#G0ysw--eDyXT7?vRKwUkoF{zNbJbcF!Sgfbf&Df@Bs8E3Qa9%jPEQ7g|Lr1*E8W*`3c^&u0i^b_{9wIN@$b+1RBF-z13M_Cg;cZ{+E$Ub1fd(HguuVavZkdP{QXesv~d#x_}EeBLrnn5Iwhxw3SABOay42G{iqKM#&aJ}qkLZK-@V_{gM5mQKd;-__vl;X(r<|Ms7%b^b-Ezunf&Xz$>Nd@!oYP+zHh8Sp(E&xL`Y)IZYOF>jK-rZ1d$BLAxoMX0Yvbc0$~sPbV>$e$qHTd1#ghJ9YaWAWj>Y<00-1nMh>#pAU?V*#Z6>{*z>L48Hzn9Z|KV?kwO=%i2W6d#7UO3G%0PENJ)+u5#&oa`rFMU2l)$A_258DJhH=O+&oIimHVKkHGK#@zoRwWf>%MA|U&os01i`NjlsMeBsO9$|i*9oDko4WUES=iOZtx8wi%Gu&0@|5tx?3H8i{=;y54=P3Q(=eHRppIP;s8q_$LzMCi2l<%>B>bCI$7?)!0RM$Is(|&a~4ttBzyb#;k3*!I{kmso~{`&hs&Dlif~l&#UKy9oQ~TO%7(8;F8vmcr_{qsT9?Uca=Ur3F(gV~vWZ&=f6TrVG`ya*R3gBt!)abx7l=?vZbJv|im{8LkrR_SL^^fbfh7A{XvtSG%fW#=A+_!t##{$w<$@m-c_3Cy-=}Bz(UTYmzGk|<$b&*B?UJmRZKPs-^Gjio=ZWgJ;d%b6sp@iWFdxdcfxk*q-e8Vc@_pPbZ=}tv%ompIT=Pw(k(YOVnRmjOY!yCjrI>vtN;$0(@eM#o}l>I6^@Z*$jIYFt{nyIn4F>O0vR1dEhhJ4BWv@zL4{w4cpyncc_#{1AO@sD{B`@MT;a3^y9pT@mU%$Sg?CsV>agXx39Y4v9DY>|I^*)__3Vw|G9Q~(F+qW!13NuoX>`|2LJ!UeKFwq7jqO)G5b(;&u{$jx(TeSW&dK>Bokjy+Hjy+LArl#RXCSWJAiuyt1N57o+pFffu#kZWj^>~a5AKDT=tX}sEb*7;s-AZ_m4`alynYOE;&UBkxGMAIhgr>lAj`KoL4}3J;<0BzW=qs*T@$;vc*A5!}x%?%J1up~hp4H4iPS%NajAe`Z8gv<8+(iFmvj6iJU61QmWPhDeJ2_DDX2-SH6#sUS-=HQ}FT?#o&o}WcAKLkFJnvb`xc8KPTjw4&svKp)t1;P+KBQCXtR|=|eAB`NofzfeO|y_&&4SzMn^JFqv6Lr#`CN2zdtoR~XIp`1%~k>3*_&IQv<&EV4h|8IX;iU)?{94oBPVSIXM_huBT5%UPipZ?x&@%f4H6&%{z$A^vaW&-(ke2;!-jro0IITK>udWbc-W4@NQ83(Z`OxV$G(eJqyIlFR=My(VJi0O1g%{b)bI_CHDENF`lb=i}M`8_cqpI@!XhLEivAMO2vaobV)%ku0yHcWqV?%1)-$VnahwvGdF7b;4Q`B3WrOJ?~`ddY>QiyhCXx?$YN|Mn5@@8@%KN2ScdxD8#u>ojhF4;=Gh#-Ct}n~hYsgWXUb_&!vf^@HN`>BZf9x?v|1mW)pNQb?(rQu6b4P_1G@Q0F{dWjl)Ry7a5j`%PJ}N2z*J{R+yt0H=A+>v~ww5!N_~HIbsDe){FiOlOPES!|*BvQAa1eLXvp10Dw4iJg=>H_^UDIv3*Rxld$lLEfy_^7)lGAM%sMn-4$3IFsk8UcBMM4%a!!T1^;FuPR+Nh3k0`Zn*Y@Z&B7izOGVY!bVvp98k2-b}2+&GJ4ISFF{Nw3@X~P;5u>zr|Z@2KbWF*l?Fyew0|_jMt2w5=frb1m)9JmlDH|qT7dJAYBag^)d19!+fmdtCCI7sFeDk`OeG7R^U#&K>fgLyNJ^MOxsX^s~A2xHKE5gIJVHxTcvTnOIl?#g$-9vegDeGFEOQ%X`@Zr(Y(#qTniXZ8;K_6CIF02a4U1qipuTP#!YFdy7x)D|8;t`bn%FF|uPGNbF%X|pZ6ko4huMJ-}e#nFIJKTm+7UAb!rNzaqKE#B!o_8uJCjCN|`%+5#N-evstmVhnl=Vj|lIahcvd5r994ve~2lNj!d`f9cg{cgKI57gfcC7MwD8OZY{3Q=?*eJ^?!VjXo=4j~LrFklO(tk`Zot`FQUkXH>%%Lb7T&2P-_q#wnNk2yf3#|397{s0yuvfDYt{k=B6B~^PJ^^fsL#5AduELh`aekSk^rSJTh<-r>I9N1S@GAfmYeZInqrfKO0@!Mp^!ouA(P@?~@$WQKj*V>}k)*7TMZ`_P#MlH|r*Fve|s-2I!jQ5>*udZYLKKJM!&yPHTP^z(qewa>Lf3F9_(c6z*pnc%#gm!+!*N5W7aF3nw`SDus&<=ySKs%kO6&;HJNVmh1yC4vmynAW=cPx0`28j{&FB+Dpf2^75Pc?CEj*B_^_eHIQ_OCuH)4hz34pNAb_j%k^PGvVEm=$m*yU_&xf+fo1*JiBLCC0@=)_`IviK9yT-nTd711h+2llwr!!^e#)Tn2`1q|GEg>87osJccc0w-jAO!259Jpot?Fmro{9TVn3wi{^xEFc#`wL0r1`ggG>x)84lpv?9#fIf4tb)FRJBK4HTV=oZD@2B~N3qDfToh(V?QR4eL*gP0-vljVy{JmlHC3&+oD7QmOnwd*H~Vck(uf8_4(PWeFgP4Y5CzG>Uq%hNsS@MDAIk8WMcI#sOpk>~CV2-WTH$fwjvrv8Hruvgrj5J5~T)8Kpl)(Xq}dQZ`=4bcYZgxq2`DW5oFv2if(H-#MP9!$3o(w5kflZ|Zc8&5uw9bbhv)GEC7|oW<`V6^QStNsR;XeaSxdCu>6feJ?q&C@aBsA(-7LzB;)z@E`vYCRBgwLkFX}EzGqOQ4h#0-aWX;ix{7`SIA#kgL;7UNw6c{Ux`!eFF)CWdcbPy9x>mc90+%`NSnL~>$uJjk0Sch6T964f5gv9ea6c{_ucLVj6#`Bsr659oE{?8?M!FKGo7(_4kv@RBcKBqlnXw~U|ob(+#P3VnQJ13Qkb1}a!yM1MJ$vy_$aM93_JcIg*tPe;b^6!=1`!w%9#XNqjmACpH@jM?X%^o*(GV;HY+B<^@eWiEM_z;iM|0pWE@9TwgEO2=HLOaL=x|LvqcS0&_kzXVGd)AJxOpfUX0Wz<&}bsr7AptGPfPS5!+r5_M^?s)z$j;PMW*%RZxJ$7)VDxt3!Q+$K+9-_V?`^Xj(`s#Q$T{nF-{w`3VyC;*-R|%WihaZ(v{L^Asbvw7v!R5?;M~^hrKMVUU4V0`I5X1AIaxfZsNg&fG`(!p$c!*1fg{tk7NtfSS7G#5T3_dOf$d>1*pu1rJfy#UC*3ak|5Wfq}Bw?p$`tf%*|vp?!CH$uoro72Hv&CF0p(N{0?{f_EdFd#Ze^F;0>)F-7C5kE&lvqiqsni>?p&{y2uQ;GQ?Yup2)Pn(giU>Vp9X5<0TeBVz$iuz}v^IOkZc`V554E|5MY(YKL%=lJp!_y5-yukkH%Df1k^39kjP(Vua^d{Wjwe)3Gq^|#0KLGFCz{iT{&|L$je;xU<17IfImtFLON=qp}u^4ma529WDL5iQ88=(jHkPh^AWy_t@>sLbk)zwFx_;4V}h)4QM2ukh}1nn_X~5ToOS+g(c$Tjd6^q1^;esw-eYMJ&$G5qv1Z&^qnIC;@m|RhZ|?W8NQC=~((hJRg2u815*FLVZ>EFll^?10511hnEjf^wsJ6i#*Z@U1)UFp-PM5b2VSbeP3-zHh8UGra8nzKDt0*&9YWve2(0(p>I9j59z1hb~q38Z7xn8c!`|!aqu@~0eMch`yAfS;sS<@(1QcM{pPMxhNw@38d~!^AM@b;vxoH|gUDZ4&Z~H|MgT-w8hCpdb<3HF(=3@;LRhtMZ?+Oew~+fsL5Ju-_VKfz=qs|WZ024DXhFMMaz1j$PQkO}@N8I9R_dN>f$_X-+A?8UQ_g?$ukXkg=Qr-ZXp;v6j%JRAe7w&IGCF5cW)k|jXo}4#U%bym-k7b1vpLYJvhLN9brgL?4FBzW{?k|G<4{LkS1vQJ?B&DOFQFSd?jpA_xIY-IF9c>-P})W})K}5!3C1s;(7<--lA4J^%wJP0;c47cI?%Hn%|{objyhF8YI=`YHh5=Cwr|;jIzdKmWlpg}4mci3&Fde+b(lTtDkaW-&V^=XvhS3msIP85crSDg+b1w-rsL9ZWiC1|GaEtf@}Tx+bvNTH_L|$qCQJ-{_|&8hWd(pZ+rcD@T5}Q>B|7dZS^ciM$SY5C~tqIZ}JiKm0jAnV>(_!=-uJ$duIj4lbpA_&Za@M(TeznV$9bx2gTd2Y&xXB-7@o=Dsr+OCA^CPfvYPHg@<4sXKenP_;qs*r27xM58Oo^we+l&N5OC|OrFY2O&!8`I&ecg%=(#d^w^WbXJ;b6dt<}pq?N?`YjSZYc?HIK`}W^vjWs;5{$W_7ZjW((@yB5q=?_Nwgtt-7JIol}tGBcKzy3jchEQMm$QLa8evt;pt#3KqqxhKZN@x<3yGn;3vxewv8OW~$j0+fOV!*v!*-lxMeb0ib4EaRE92od8YqVh#>ZQOjE4OMB-z`sq4YNsYJJ~*HGhUWDkaBf!;D=V*!yeQCr@kS_UnEh94pR;4aAExy%FQ@)e~N$e@q~n*SvF})bG73yDIlv2rE}+tM!Q?Pk&e3uMtfHyTNXqPGi(LWL@#P^K_`WWK~|i1Uc!K#i(Myi8Wt4JC!N>eT2||yebFC^FS@*kvj+4tljiA7lOWhdH8eybq?9DYSdpQ9Iu!>NrAF{6|y>d{OA1~U|!qnrcqAuy=U=f1jz8gZcF)L%f~Zm}-B{#gAFBlsG&phGcc<1;^7_>PWTTXBi<;&FV~=eAjC%|qmtQiIC8lLGjx_?3}P>C5wd?AHoY*?cJ9DLL)CQr5q}pG@4y(Qq1w`et}%{rh|S>!Un_hF%PZwwb1IRx;+1qnn4+HfHf5EuaXbx@_6u(wOUC;l>v3-+(jm-Peqk1+Uj46sE6@HG13uLsNjVyayq5`D+B0)Nf3EMtbIN!>TkPjYs2AjdtWY!M9i^Y3(yqAp@C!`nNShXbgnI>XD<+}8@>+tsgSfzOdY4B9__PC5-{#L7i4lEV85spReIy+VhTN3Kp$zKERM*KEH{d|#gO_j8o`u5&j>EqgU32cq1G5uydTm_lQQdPXjsQv3SDK88{^^+j4y%9RNp>JA24n&SOrZ``(a#$mR|&*zgg>MOFJbrY8hlY%nC>hB}}TIqAcA)XHjH>;bYf>2*+YFL;>w+i6YN45QZlTlywzbMf&9Zdt#zRhgZ36mD4dUK}HA&2+YJzE2Hf@!1)KY`HI3X-0yju~SelyLui*|&AsqQ1$o<56D)NEL0p?Vk&Kf7UAei1^1-UkjT~F!@mCQsm+L9rYFIZ@X$h01fBfOKx5i`tSQDN)#4oz086*|Bn8db1?7Q?SCjacZ4SL*)F!hyieB8+%aGPSr^|Mgn8e%JXSsTRyL4zzW(PhZYsf_kM#THf*@w)k|XCaZk(lMI>|mvV9o1r{yG`;)dyk9vy0?;fvfG2x2B=KBKv{W>+qoM=q|-)>#&|`!sGgT_umu0Z-43Smqi#)^1m6zLeLx0(jU2o>w)BYLThCfv|IFB?B9ZUncPQt-${c)wM`z?w@^osb-X9k7?3_M>Ws!rxv=PSky^_A>>7a4(fF1X9cKJa2;JV`&+%#%!5_sWJX_YUKE!k)if?KvA>fwCUB^XBVGu|i0=YTlt3g*@#;e5xrY3tmfo_Rgf}D7xN8r32M8@F@{*>b5|i`AI5vp-Ou%w2tC|NSuxP|T7FUC@g>J<(^MT0Ajc`=;pJrs$;y>SBxcI_JWe+SO56waCeHH*e1{!K$XAec?^iOGo#12H1?^0P(ude#1qs`FL!J`5hjx?3%6PGLgrOEz26T5di7S)t8CaC#Kb-*FF(~;m1OM@jT>TV{(*hld_<4{L7{{w@^osePIM#8pthgdOP@(;xF-4Zg}-iI`nML?Hd0b`Ef?s7`f!KXDuTf8iY>2;liTSO*!|@sF?em4&*xAg)hjtH}w`p1!se5Lrm^o1Jp|kvL^^)Hs!*c^-{k`3$z}7ihnf)uTQRftQOF~^}W=M)}zSVD{FuMA-*rEdlyprs2bb;Pi1}!`y1*+7AO1EBz5Awsy5-qP(=TJk3Zdg*(&bktkf)BiJ8=G17C0W22rZ=ei{{$YEs3n7!F}^Xzwc4{?|9X91fLwsfV(Gpo_yVa_qoG!W%=}@*`TyGd%8QvrkUlXomOmw!6)$XgnLbWSK4IKaroES(p;Kohv$L{V9V|uRc9xYTbT56e+eQJzs+Q>R`Bklx~gyrb}~+CgdQ$GGF7iheZ~|T==O}9FBTG~#A)Konv%#XQ_05~{$m1T&4-HtB3s02JdcK;0@hm@E7STuiuB(@6nv^=CE>(EoGj*dX)E|TP_OCyhQ1(@AdMjVc?qveG|Nl1{>(W&|n#?{~!-kKSRmB#)!Z=5)xfQJ8#Dn}3HTGpT$jS3d*CYf$_L*!R#5gbA`Z@2qy%4t5vl;zm$p18F86^D8gr^mn*J-Axufk+&<9(JBd17m--g}CUBKx*~&7ec&h0X^zDg7ly{cbmB!|7G)Q`waBeXT}6cP(C(3)_O^Jfp6oUNUxTySLqoDf0C-F-3hQ;{zM|ejbgFe~r3`JRjPf%mc_wGgy*{`iiXo_tg@>stp^xB`NDym6=ny=iw<`4-a^kin-V%9b(XMWf;&9~joSM0c#P=Oj^+RH(EAoJSPtJ<@GeJ~WYlV8L#G&$7;tw_it~-2tmLBqkSNAH;2zWsDd+eq3#}RB9b~r<=Uf|7yA?cSX=a!*f@_NNmnmWK1^;`eB6?t0Fq)WbeJW<}f?@n1CJ8TwMzxuyEq!5OjT%Qd|69TL6);!lZhu^AehQ#l?(t7h|itlKl)V_>C?Odp}Gsd`8-6smr_Wr8y5&>j2BS9%{>w*d>BtX$j=d2>jL$7$>zmWZp>8>{Zq%jXO8vw-YB-%MFg)4l4RvVI#4#HP&Oyg(DLGkxNW^I7?Hn6NLyU58HbH`q~MJ&p_FYfqdRMsjGBNCKPmzdGTNY>XTu;N0C!~*pO&{;cz#lE}itH`rN~XjMy)GO{6IMZtG>tmKE|rHUD_jW(VY?pS=7p0c1O`lGI8-{v!Ojl1DeC_0DF1|<6hm$k1{j2D3_nBe*HY>cJa?Y(lsjb};O6aSFw=Op|9>dR_vxn2hkzxW_PnR$Ob(E+t@G>@h_uuS2e39a3mEA!5agqzx7N$?iDeGEfUHS_@J{-MbusX#ZIa!Z#h$VpShqIEWagfsjk_sk1%>;vw{ZB8hK|L_j?Bj+93N#>IM<0zm)B{rpq3jk-hx`T8hCkd!J&<&{`Nw|ZIWS3nAXw9kd0(4zy3$W97f64&_a9JSaiVnOmyiGNyu);g|EFfll{ahk*r1^^k{+CZ`-2fR^DIgtxp1`MO!M;{sJpgalX12<%!g5RFG^`APyXXQS$4+nlK<;F!<~aX;_dUhQ?F-=_M^pjp}r#hNoW1Y0>QF=TH7Ve?>BTZrYC#TLHwY)ZNmf1;}O+`$CTz|!z20R0R9h*+uVk`k}YF%MRkTV7a=F-zd`euB7d8o^%&0^t-GRMdaz+uexGSqAnH}J?boU&T&QR1vtD~)oUJ<@e$8d@VKRMdUv3TRE@q*`jp9}TxJ`3CmK#awbA8d=((_U#oN~xJn8`#PHMBdp=}%V{oIWQE*+%h$Rk9s9kl{oJvMzok0`=9Ok3y%}Q?uda&Dd1^m#Cwz+svNCk<5jNy5aB9M#vXSJn>S|V*)wf)!|a&+&y%kcbN?jlG!m~8pvmsDrPv$4n_tE5%|4z9i&m)(WfY(eaUQc>ukBtI)QrzPdi^SL(qD!24-%TJH9mO?c|&Z-vMJ-Uff$B=aNQ{DUBvSoOMKs!f+2%@))b!#MOOnSOC~%$L}x5ni#jTUq48{p(9d027Z`8Uk(1-sGZ!AHm9<%yDB*Q%)~%>DBJ^`q?8dxGivO+G-1A)qTZHiG{fD@z6n%9^!uX7QP$tkle??bhQ~VGX&k1@>d|w~k)KU4Ab*;W(9oZHWItXTTMYJ>{U)~%0c><9~E3)QU9{fP*!x&T&pG`c^m(A9_^c6?Fw7%uUD8tQ6IARva`AS*unw{086j{lJ`ulsof7Hdl@6uGg|78ykDpee61}W=c9~`XBO2h>s-@hCyw$%KUA}67?CJl8L+`vWb1slF(NbW@9Rd)H9TzD;$TI0KgvTyian6hgf6UcfZi!;bq5)+aJLT}g?xEsDIMt<$o+K>FTJXo2ND0ZfYQYZiI)A?h)e4yzo)tHT<=q2mO7Ec`^q*m|M4W;Y@ekuJ$5Z>O_cSqpwmYm?E9Mo*ADh=E(=EfYiDoeM|CEUePDc=kgM7|T85uuga7j?mnbF5ew>Z|Y=5!;>1Sa}@yYyo{}babA6AZ^hfCxm?Uf22_SE3#ZWvmhynG}}^u9~!;NLsH_4Jr_m=0BC&fV%)Dd+55w2#^wcE=sPVcPksNG#0hjo1kt9khDB;^g0*FzFUVAkuyg2+oi|z!8k^2^0g}Deq-Cu{4Ezif>CAtmoDTq-}g@9gx(;1IxQ)E2B&uavRF8s20I_${~TM3oEV<()JM|cGrQCOGNrz~e5>P~rSr03ASJxcst&nx?X3H~Uvi*+tx7O&GwLg{?_}+lJa~~87UX{qIg##krzx^wAXuV>wHWo)>X)i|uN}FdXOXUS^9=IB&(@*uck)5udVE+>74mnj>>rxJ0`OSy!bAQ&@~Rbiu6+iXpx5Sgx6uXHsUjCG4~kF7f_IZ;N*NKD_xYo;rPs*Qq1xH&Z&M=XapLjrk*Q)p$O`YymK0n+A^SaiWaWU1Y1ox3Lex>IvkcxF-^qi|ep{V(en%Z8oY)cG{DTF@$-8Nih8K5XTNI_lC)X}_-PIbbqB-KIkm<7r-f^`Jvn9*ohyuwpq2drFLLFPrW`yx?2q56{UYhwM5IW%1fy`=DuSV7&fg5Q{_?Csq8-PJ@%0Xv(!!nuA6{9T^5VStshs&fOtARN^T$Os2egeLvf`!qWb5sTd0>FN=e%${mO%-({HXhP1y%LIb$1N`4Ai4y!#T=PQy5dtn3uJf8+vl-=g2Xl=A|&PblfFF5<&QxAeG;(~y&O?J@lVNFI}$=Qk0#y!2bep}`Ee-EWrow3AYQPR!rOT4h1&f~n`02O%fxO#{1WFb+B%YsewbG^|2sOcw;WG!h&h1Ce+|L;8sn{7o?LywLaG&C(j*4V~U^HJgeU)JC+Dx-`5Vq@1fY2FmGhh$f)lbpgXzEJ3F1?>%|D4eQjG78bBk$-nQk2_lN0r`h9%jD7sy`d|ktu#pKuU$2T?bWcE_`YlNRRVq@Kk_L3ckUn`9$$1;3i*w^?e8dexurrN`NJ(f}W=8Ww7%ur#%yejwIN_&u#eFD~{vEi7;W?%o4$gA82|Grwx1H*=&f8V7d-zrsH%74iR3Hi_|1=+~kPrcDMRT9FSg@qrxX~-)de&~6yAQN(z*RKv)iF)Znzyl}TUnuEAZG-H#pgLS=2f84OzzwZ}UN@(;85tf}HH*e0NX)&v#5pc{-o69<|Bp*BOgU*j07<@bezLKIs!tNy~yY7A_@Pl>JH~UF7y^(4nW~@A;)nwf%aG@#$G^ydvJSP4w%!!K&~1r+Ai)HiwR@Bk?<3E0vR}7h2OGYx{lK%CN;$9RNVj@Y%!OeOrCFM0$jNhea}tQ>Swbx<$_4rEVpHjPC4&F_0Np4)>Puc5EhOfHp;1}T=!>5_JA&C{^dJieSv=D^*2y<$$z7eeK`|)KMD_+`Y1>KTmYdbO{G}`Wnra=J{;cpCW%aaBJskRl*knufP8FiG<#W~)mG80(W?=9bb2=x+sc4|+QFAa2yOI8JQP#47*%sxP#H*{7Bij4V;dZzvPVN;1jVt$mFo;PkaaeLaSpKR0$nZ5v|C*E$8JTD{NKLxpxRP=%RiiAkKakKHPSUT9?OQSa4n1kyst!KPsL8*tR!&(DqKWd@hdnvkwp*`a^@qLvp-1~jW4fo?BC#l-aODFWRQ5DVkGwM}xA5DrFpOac7UAIP}uNQef*{7HdUpD_PxvYhMPo7U1?ZJb!U#@CdQT#6Aj%}BG7I(?uQeN(^h`tdMHiwVzWf6m3}Zuq%M{x23+nq|PkCwT+s98sTaEsD0Ad^Zyk9&^&>yHNa5KR&KL8At;YL;D8R!<7EiSJ>8Sehj#{*x&*87{zCGbfACqjU0IPIodBK4EY_w!Nz($CWO>hoh*$+{X?FUEb3vy)}~!QZ$(l1HcA<9S(3&B@sso|J`}#|mDqvqc>*}7c9OQ{Bwpvzo1NpA?h%U4x84atPJXWAfee^f?lq&(GV9-UmZgn<72A;s$2NQ4*%^quxbyyr=6D(~FBeR)Vj#b;GuUYH83tq-b!{3&(Osl(vR6e86wCMBp7s+t=~rX3iU|*zE$g)?{d6*)rdKvTV?zaFe}mBqDDpF@UV?mr+Mz%3u^Es)HnZfI7V4#%4FzYOiDiLxNnKkAW&P?}+l=f50^mhP};`z?jxk9K)2)vg&>?3zL81@&3L;@VY0H6|+!VPRJ1BhvAGOxHPGG`NUy=E59&+;BGR>Y1H{Umgczi{!*tx#X_a+xEXPiE=R~hw^=0fSZjwn7HIB&HyRs(r;xXpb*jsW7#1hmVu{;w~Vk#agbd#1{qz8CX*zVX4!s;Ze_-+MN4h*E!^wO%Ui%0QN=-ZrYx-b9zGu(*rT9#_OVvx-+&_I7Kf9Z20E_5(OAf@l>CF&6|1P<(u@$G6D5ZpmN8xBrD?mZEl+xQ3FF!SBfN{>-PCaMTQRZiVs5s?kK~JgMfeJQdeW`2Fmi{Mnn4$dBw(l3}BC>w3Wo?eg-%`vOc`%U>UOxVx=d~Z>oNjl*FNx4sn^sn2&Eq03Os+jDt;d7Jz@ACTbmT5(y+_7&6Z78#iWX%LDSjZgjjXp%5&}))k#6il{M>iLu3kf=f79=>(D{_UMN^Uk;AKe$9D2Qb&znNjOT;wiY-MH^e0y?dr|nwQS6fZ5g{^3!L;vs)H@qJ8QuX5+u8L6(^l!T>wlDe9ogHg|r>(}qCb3}D$-Z97@`{ic0h%w=@zkKlO3zWWr{q3@MiSJw9W0Igs>4OvDV{*~*JP#&qswjJ$irgrUb1-9y0EQgpe(_TA`l()uS)YuBV0OLd%hgNB2X{I~#l)t8zCE}WxM%&l&Rjx>z3a(%GY^OAfB%0WEtY6OnOn9z&PBx0vx2WvV7ht+G8-yg@d<`YVseJat&Rf4c2iE!N?_5WUQyrj+mMg5z<@9H5bw}>nzUwCug!E>#2j$ftNOw=bMtDXEDZJ1z5z5m8l4*A~(No~ouEFgR(=c$qORfg~UoUCF_A94P_d4D}Rxq%S{ckY$|k&k*iP3mW~pH!5X$^^pS{T->!e@4tg+2*Kh2)X)%E^rdhKQOhZ&e${uh<@?Aq&ln9bq7=ZjB?@dp_n@=yHFP~FPALj^`HSU?{1iZoXDH7s_2lAw$S$tNk;)??jk7(CXDCw#>cKiT@+~L`1tlk7Q|dSzgbrm`PuR6eS2MsIleS`GRT)OHCoR2vh{}fb@@chfN)SATSv;t7hT?Al`|7$3vTkBi9t^Mp6FdHuvxcnMNJ&)sI%-BcX3KF%(46QqwO)CzqfqHGHq4~)D*?a7r5_W+)0L?`dD7~`Ek_PIUelO`ZsB>yZHiw9g(Shin)_8_`=`ruihrG#5Aar7UJ@Vxj)H~NG7Qtq*lHEP#c%J-I2J#+H+4}kT9xXvL)Nk@q)|Lz3mq20FZp(Yw_&te!wy⋙fiF!!P!DsXFkDIwzc9w7JSh#*!J=;>ZsV;>F1BTQ@~rBd-zX1>K3BkM6c%m>Kyctw>3!7J56Z7H>WT(x`(8rifoimaTmai?Zq1VijZ%NQQnw-p9v#AM-_cd6qp)P}W+zxV;4VfMt5ig47})>Np%bNbxAGg(*>jCGg?HvZmt;F%S61<=}09#ZvhG-R~J?H|oI6mUj>9_ol&HEx{mRWz;Qq3>=wjH)esw%n7aeq`8V7%*b|Y0}6O{$glWhi`-Ul+;l9B3XW%Qk42qA-geetbT@l{WYxOyAzvhEZsS|4GTCW5)NK9mR4yBNfE2?{=@}F9EyqJcN|CRb@o0TdKoJn@n?VigrMV)Z>sQYx0ZFG3ThBV=s#^|(A71`{_1>g>CDX#xY_U{2$7k=LBjq3WYZ70(&pZp#)3R^vNkX2f`Eie|Ed_W3XDsm~`HmJ1>FQ?Fs6hB1d+?&3DczR8P9PuB6K(D`E&`Q1tLHP$AoqE6_fTk8G2|~XH;_7x`ii~%8T&O+0%y9{X^re7=`qW1C7Z+2;o{H9FD0Zn)w00%s#gA4|E*t7Nb><}G^OAAQDElOo&v4qqgaG@mv3&&TjWIFd$cPPc4~}^=!_vx9SHN=J;{Oy?!k%vapXA?0JhI21FvFme;f6xXA$yKZG&m+gG!+Lq(sHDLHt}||Dd0n0V8oaGw3Vv_~t{8+OPh}0>ZamISF}DymOdcCtGj)5qP^}F6x$u_ce@%?EM1a-~99hDc`sG-t--L8mGU{y_VEJsQE%~MF1T}L)6wt&Olu>_0a9f)?Nn3@3epvry}O`NN!*OD`g-|MglqO8_#|7jm2Pa)8W+v9^~uU{|Fzjt-Rkp1(N(%9lg9y9Wh7;o!(Ea3oiUG9@V4c$3DTGz$^%mgb+a{#-m0%d~fly_e%;37B;__7x<48zP08bsBm07^j>8R>KvkfxSfH6!+Wd2^r3t$VEh#iM$3f^u*BS0AN-jo3}bQ_nm@8K=gaHZ^ZNKFN#wiEGPzQ_g%rXL->7yI*X477nQ(?RJu@OGse>nU$-=_-IWGDGa{#+_TZeI^ohS7FNLz;LG!gu=X6N*PR6gYM%nA{+oi%$+$_{HcHU3^9xA1B=1u(Ai2Tmyt)~Rodh(RQrIvG_P#5ukD2iDpSOB~Ne-@^_K|XS=&;N5Z`+9ZmJ@lDIPR!*h-(Ccv>xRA&Bl1Z}dD+XeY#QJvR4_y5Dls}ble4dqb@w#TbU!tZzkqTF&Ti@v|Kpj#kb$Om!QzpkhJY@uRPRh!fA$v&*I0W4t|Imp1tjfX6e73$4dQQ8tij?nD;**_zVMYVTnLC#}W{~1k7ByRn*zcV!{stGS$a9(Xzqe|SWT+VIMjCkDFT(F%FZgx7-q#Y)zNYQfWQaV3Tgs+pMH-xtABa4C0Ck9G&STrL(M;GneC9`$2XbMH%MRrV6d1apuiO)W{DPR2)_wN#tu20#6ctO#4|=^=#bjTv{kzB9@)@K$uEop7eu);qyOPX@1*AFJN9NQizJJBuFO1B*y_VF^81#GQd^MLMV80Hhsu-xFh&iVjoyD+dA2UCI#N&Ddj+(OfM+c5arN1G~k-X{so+@-Y4UF>iXpJ<=Kb{s@{n=PD3s%kkVjjJvO&uQ63+t=aoVsp3-MX~iplhjEWAyU1)nlnwJ?|T|ZyHXnWHlU8$H#6AhpiLHd#F;r;FDB*P7*F<`IYWU`p%q+-)}*;GgX5LUo>O6+u0Z$FSmf;G<%lW!@0aL%;=PT0b+y52r(rrcDDubNd4~M@>668EeoP?zn6E!Y?yg$E@AQcULocgkf=e+TMbsg!O(=%Z^~%fNkn)TNcmDFVOelecj@HwQY)JV>mm^yD64E(y2_HT{9aUB~n7$@6i{sZ(x&rly=Y~>+4NMAr+qy|hiCpRf-N4WkX|A8B?4Dem|LT#NCXtUliRcYXWPu)Ydd{g1E6=`Enc!{t0H7QaV6!P4DtKFxshFUo9kyOH>@W<6h`H{$FAJ55G6KCtIxZ10043WRv_ke#(P8vM_)AC+?#{YCk564$i&OQsiXcjN;4aaztGkatCE13dGopGV7T>bwYZ=m$7Q0Na8KAf9HS$!IHQHy=sENL$qbiQg?!6%1&P&vHJbC3>oYb&qH{6Vg-BB)$t$OIx^r~Vmr6fuu>jxUQdPo&5=@E?z+_0Q(gE(Wt|KD)RtsH66@`MjH{1%Ptc&s!#qj!GsdG1ZSLOv><=A?zI-QBJibcoY54P#OmKc&^8J$ne(upzY3*s{EC`WE+iiaYb(Ek`L(^WzVi=flZ~6K6`2Afn>*Q8%D*+dxAus@S<8$-UwA#>AXnC$u-qMfyWN6+E;S)8PaCXchbf+V7!hiYOCJIC|V(sVtK>b6^D;=(-Ld@IRC+EwMuhFQK+|K^{S^ef>x&jS35$74?F97wf6-yMFkQeB;*)6@w-v9RRi||#%&n5c18s4!$)c8)5dNFeCA^kuBpJKT2bJ2{PouoM1h2NVF9V~&aQ;wPoz9OGI+L5|@Q!142u5*$l#iMQ}WiA``&V+fF(hok=MLzXc%<~57A)Bz=^G~kC5kY)DYgXxBz;Tf1ef|Ao;JVWz0z-<|ugHzjRLyKewn%>MwPQ1tVwW=ILJ|=`Kb2vnRreVUEQ1>$P8ze^*GK|M6rA5WbZy2T@-U``d3aso*rPRU^_H<3i$8+T(RjnGoG$_*8^6C#X|8mC?F@!twJtxe1Ra`~X)MP~llaLj%789`AU%&*8GdZzD^cws3%$bKvioea)4^!Aym>bq$WFx!JP%P1mu^@BkAAB7dYni8@ad7h_nXpS{C+y$vHPg6UT%mx@qASl5WW;)KS{o(${Io4&J-|6ec$0AgSw?JgEaz8RIm+<@*mbk?lEi8@B#MvOVQsU{>6mUCwMLX&O|F6i0413kGwUC-}ALL6Wr|L+f)=#M`@{Ar8b^pas2Hm+{grz!K7TYlMABWXZN08+ebuhoqqxC?Si%vgCF0=8~Vtf#5jFir@(^io2g<_G#}@6Tg>5WbkNFvo%xC6OYd~S{m5_~1Kgh9TVJvq`S`TXuHx5)@Yj2(ihnPDpB;r0%ap2$pzf<)?viAZpZsg#Q0t0fnD(E|`2h{kkGkn-vy`Ufyq*a;kO!QF~X$6H$uUo_d_G@u(RTBC+-0@Fba^YPOsIULkBuSc2bWYGYe^+HO5dGPTb)@=ybMMXXVpE}HU6Hgqsh-M`{USU+BMT_}mg^Q{cN%yljIeUlk%x-3J+Ef(2TYf>3<(7zPrk(G-7L$5td1LBq{fj4pWhtrxPb+Oi+68P^~HKH!oSXwrMMy>1RODhK)eH6AM-Y)OUQ->-k|{IiG;xx*o@3;nHB$YFNxROCV4UDIdieS`+|O!dXdOG))wP1e5|eROD;`?k+?Cvth&6aJd(nJ_cdG}kJDcj{0e@rq{SV-?KDz1YfSNP9-*_`>a1z~hPcNy5SZ;;~$6$WsT$%&zs)Au{aXHy0!1k0w)1RaBV}Xa3^zcPBhQ=RfxKE>HB>lM{@`7i-RL92Y3&_<~B4`VGV9{9Vby1qqhi#qc1VPdfJ!o}c|Q*zEAUm{Zqx{v7gQtu@oT^VruLb-UGY2F7``j@`76;mQJyW21L(i;(*Ma+V!v+E0OmZR+>8lIp40f3`{VHY%*n3NL=L8u=UlIUdifX+Xp^O(c-lJbU-h`~e+^ex2@l7>^>}n;*HEU@8`W^!g{tKc4ZqY1wl@7N_pZ48miG#<+qAK@W{|S7eC}H81Wf4s%bFGZML+b2I`z0k7sYm+05Sm%0~V^VTXL;oYV@J(Eog9HlIX(Y)$0->5o(picLAA>4m&1I!9BLt*??EjBFNnK~DIAP8QH%NZvC{$PoFN-q`~S-!kC6*b{N7WvHY0i=%ffep?7pq)aOyO?0!Z`w`0F#bv31^WE}!1%OUVB^%$x6OMgzr*ca?-rAs1r#Z#9Uf12InK<_=Ok%JFhp34;M?`MDK^3rO`*4C!sEX@wj=#*}BMm%e6j*Uz;pf;9IwDe(Z*SMA|fW9E1jgMCgvB&y)?4(tt9RAxHF9MgN4&yRYh#!gbVq%jNTmme1k-h}*6!prpupDFNZu}Fu61@Z>(M|TxhBbm%WJstAo9xUpXTG@KJS2^a^`Fn6#t7DgyZ)`(Z;si@~yHOQTLa>MO#>KKpYDoE%CTbBjRz)2EVDt!keM#C(`1op?N}vhSkpYzip((6~mzkh>n?F8+Fg3fx;i_VSVHowmH5=*@qX2Za8$md5k*D(otE7pKGE8{JjPvru389Xi#*ufu@b3j&7sljh@SiL_Ho6$?RWe`2rBRn%8!Hh4e%_KpRAG9UOo;U?ARyNQP$RW0Vc59>&McK(Mpd2K(Q!in?m(IokLWk!89`J_&(jbOa!vFxO9VrMp_RnHBUt3w`M{&SI-6%}T&Hw-;bkrV#p9rbxoy+(9R_b*a?)UuRPzEyO{nlAe=VMg)`mA_h4X~y8x6$Cy)ez7`9$=k4y<8RMHn)Aq9dZ{9KW)bvFZ2Z&Kg}g@gShMKXV&Kfh^+bL3;OHVEXa=j7!e=hOunP=Ofl@rYCh)p7CArscJHa6b0Mwe_SqfWZm#)~L$Sq4=SDrt>IrBCfv1jsfqiMQ_gBggQ!_d-$1kUIa78Wxy@8w@lqWsq}6!Yijwkx8w@|@zpKduTZ4;7tXRl}cr$#X+0S=_T*~aMD&*T%tk_#`!+_b|Taw~mA#agVf3Rv#At?Wq`s4B)Ij8=UeZ8+mG7@i-@`KCw`?{pF-&Y5BMCWZH)#nrQQ~b43pmyF(KN&aFA)|NMKfpT~5WcE^$|LcEFWdV`f#6n6HcW1sA%^~Ci+xh_O6_$wfq0;8GxHa6=DTV_l4jPFsBpv_2aoROE1&BH_jpvkq{By-lllwxM@af3%;oYSC;Od~9K7syh=m^-84mmE(g`?&*z0dz{Ofs3N%N5_IvkVSs31Gj)is$9`P>KzCy@tvV8-4sTpmH4<0Y-Q=GP25$JZ-`6gRV6e@y;}7y}BNkDdP-h1^8ww8Xh7CWLNCFlaMFeHFg%ByT8##i=LEU4X|Eep2Tb7Q?-0*Ecs`p^mla6Y_XJl?qzporU89xGtwVi)5c$oCS@_-M=1_{6ddgE@=B=L;;WJ-1)hykQBg8nc0AQC>;_01jRU+R-TbBz^n`h6d`m$)mi4tw-2@w=wI^Dn0pz{F)(Dola_fUS9yIbfIW9RZ={vWphVs91|oRUay@&%7=D-q~2Ym!UAq>ohV6vykbs`8OdQ`~xEwf49K=ApO|q^IQ_y@Js#*_u3)M-)&+Uo_Xe%11dip{7QZx|2+EoQ1Gi<5V?D|bygsrNB)eOpvnAv*r-)yeum`F;Gr?bh?OpY1L|&eM7o_=&_nOBbYb_T3Men5T1Fxn6W|Bnx~q3%2Hv@^=~YZVd!D<#74|uSk&m((4YWG&bhK&gI^c--3{@;tfc6AdwH}bv8KM-i@D2)Sa|%Er8#9ty0vEq8{^fJ)D%H!i0}8sl6dLP>=BsjS30&7s3ypi8|lqsJjG%8(Y^MDgrL$$Jd-A(MO`vcBG+peiBe#h9z%lL;d5mimRoYl?IXF&+1xEASc!lo@ZI`AZuri4Jm)OgvUxyz&ropD%lM`QBRg@3k&t%h|KY?^n-R`pTgIf`a4JiaL=K>qn0{6RP&ioT#)#-Q}Y$vPhes1@l*{q_=hyf4(|f}EI77gv=9aSZFJYb#0h=egO2#wI!N)w4i@kdK89DPI?awBn<>JhIA?R=PXrT*4j(p({Z(dL^`UIp+cB%D{?lvGbOW?o`;oC%yh+63fIWzsF(vMk`4sp`e-L*6^LYPut@2*LuF>^Zpsb(iQZt=6c%MA*IetfFB%>K47&k%8LFX~3DYL8@1e6A!VX)n;*gnNFG^pA1#na^EV4lW%<|f&6Z6+S=bqZ!8*SDhC$8=_@na>OUbr_wv58vkw#coz4cloIu`wFYLVPdKUahm_4L98$Z`PE$7OOk|Ow1NjFMZio7c7U`4rB5(xAt#SD_-JXiLq=Q7`>0pWw2=z#pNps^COFAE;aHC9gPA}4&7txn{Ct)juVs+FWU(M^wp%f97;?_|2{18$OURi>qjxm7-=Uoz=&=Kt{?&Rh(hQ1Qz!pn26CdFK<{-D@JkK++0EX^|Bo+?%qx?2OoxSvf`_kkASdem)-25icdA?L^?S%~mKAB;iq8RJUwAJadDSCjvuCsOfavQQIEmcmk8sEVhkWRq6B%K>1^M*6WCc6+^EFnA-#Ietf4oQM>zl@dN8Oq5swUbs>;>wj#D}#X;>20dSZ)7Z=8YQRfivS)P@7K+L7FD@DF)cvhy>fqWny<5_p)^D+yAa?Tb&jPt$PZ8FFSpNH*MOwQb4p%&CjM1AC+zl9)_VAv2(@?|CTrPrwwBt2c9@j$z%@rT@3oMU<&mQG2i#Z<~;B?wPuN2C33a)#lOxS%ID;*!jF@D>HU+xh&dNP%h?NNFBhV|BIX=?P-g<`P@SR1b-d433JWhJw-!RJj@!_>J;(=ZJTLX>7eR&Ts4FIcv_{OfYyIED<8`3Bb3R;N^WfGoQvc&=%Pf(4(*jUyoqlfkg4ADWSXNrTfXS)HE^$Uq%#)U-6+)mo)$Hp8-nYHJZ}_SNi$E}FQsGlL^6=-Xk&@bp&@-;w6`gqgA5V6<{km-+6@E+eb6Xws`^O329Dm0wxS{ma%~Tcn3hvU^PA@1BwEpMsSqtzyE+W})-mS}pZ>6##8o#k0(513)yx;_lQ}5Bxg?fze`ET;4L$B|}pc`R<|M)3?$1Bfm8Q^Z-WZixk<6WD4rn-2inJ^g?FraOTdBY2rWpsPoSP;}UJee5dOlnT4bMO+R%!SggEiaP#Xkp;V-_47JiMLzGyO1G1F6qr{vEi>JQoT#4|70(5W+98?L6g+?EFZ(w>o-`0&Dv~o&P3i~i84a|)N{93;6Txa_Qryh&Oz!2g4DjbGbxyvIx{KIvt4S6@WPZ5z{-YT068JmBTY8lRIx&@}jAo&}BKkfuS`*;Ro~Ot9gD|coKltOSRe1`>N6|(RdEAC!DWBF%PTzqVDLxi|r1@?KJ(;41C2fg7^v9KU)X^&t+Oe}Am#G6RI{eAG^NA^#?qFq*cReZ5hFM(@s}zS_%vA@#FZK+K?_E|}}rhwZ=+TR9i<1_F5p#Ke$ab!Z+@pO*^PC`2ImW+9%F87M)GEZdBk!V~2^%}f#hsi9@290-WnV%L_Z~(BvaeTT!I9#&{m37Qe*Rj@p9?)zIgj*BkpEd!7qHEj1_O_uuGJ&)%k$FQe2eJN;WVT-U`O)L->+?xoymYXXAghgcn0~B!kmJVU4@Vs>$AHh9=V8`QpuVc7RUD{>;`iA*=2KMUME2BXkb|UI@CYux4+rkWwEdKO|!TDBGQ~e8rMkpi%dwKKgY}JBkGpZ?1f7_lmbNm?hOWVj%|o&F5I0^Kho`vIx0YCYU;#A8dSVDxo}JaIZ?NuT}X!&%)h7JaN~IjJNO#rB{Lw>d~5OTR-6l|=c($!tzQVX0aA?3#mIS$Gp)j}vtZa);GWrK)M2_sZHT73971(T$oQWn?i`b+zV&rYX812|9ZS%^HN$!e9ZYZfGW#RtWH!F7DEH`js2P73Vv@UYleiM*Q6u57VhE;zMFHk|h*`8-6>#65y(;I!(4P48NaN7cD(E4X-#4gpR5&nkK_Pde0k%x8u>1DadI94(?zFICZvf_wQ3;c|I(*)!4{?RujsTEuA<5dQSz-|;@rbNwlj=a~cp?@svIlJazfU*EF#X%HH!av@L?xf%7hX2QKJcvEq7{c}?O?t`}GJb%#~=xmgK{Q3~E%Lt#x!i^*ElQJ30y#PV9x!8@*-5=pAFO3F=7u@lec)Wr#r;#!_HEZIUi||Tu_eQApOw+`G@}E-_Ijx9DliUBwq->@*IuV9(1^}X%p)Psqgar61DNe3JhRxGiIhPLw?yw#+O>oggKV3KaBG6zEx}(y5S|v-X|WETTM|%zJnp<(RlS5-1+o6UHORjKTi0EZa<$2ALcB1T=wYPKki&-D5-6b1xtHB>(0@|;~hV2{@GMV0foso_Kw{?|2SJ_*yXC`!mYkrdwzwW?s~`dLaxe#2AYDEwj;i%uc)=G&$+&IkZ4_2e(-GIKTgyWeA~_dN}`$K#8uQ+L1Ke%2fCQBX@I72r37`3`RF3ga%~n2Zs#fJet>$Wc;MKz9rOe^_2c;wzWW#lJFtA;rj6|PIPo4;-;I2aHjm}|ubH5MA2bsjh*B@bJS7I{B(-SF$VndmDiG+i8^Y7f&Z&z^VsW=;J9f$3wg1ZwwCm97N?Id*^-n`lt}Fpjg5!K9Sus%@9dBXd!J~ma98*M@`%k{ef!z#R!UQJ$ez787dzn7_mKg68f_i*-i6w=Cp(M|6OufAAI~B011f1svbVK8hLEfOygUYnehC*O497v$g96}SHeCD+)4c1XVieYh&gk+UKRWK9+&ub%`OskRLu)%LkSxi+z{SwV6~nF}epevXX>$XC*e29{aVplw#rG1+Z+K!Luo4-2U8(`ncS!gX5x%vyvjY9KSW!tH|^87gX)EpuyQg%#GW0P+ui=A63nY`vz*o-~R2Vfc9Ls=i$F_eJ6C@W#wE5-PL$!2?e=co#2{ea~k;HV(cy1g52s`$(=BLIxIT@V=f95;BL>=|n;QESX+jGIVZROFk9>`~${M4pkMuW*qpDNFDAt(BQeU#{sB=X%@JQD9Gab3}G3xLQwVmox)l?M`abt$k}p~GdXt#kLMV(l8RxwUdFQh|D?BL)&?<32?4;n?f873l_DzlI6fo_bV@@wV^N-7y>B?$;&*bFeHU{JI8>NFfzDH1CSNgVxf3KkKGF!0VDBl$O{yv_&FeIH62h;9TTD_SDNgZ;fH#VTY8u@&!Z&Zg4#5|~n7J>ixYZblsOJ*^kGsVk}Lh|F(ia}ue!}zY7*r1D{*uh;pG}KFF8Re$ARDR3*T06lD=w?8J_hekIC_qX=*}!HKTCy>)AhrFxj3Vxh@9v55@7(BCWAFu>B!Z+_oP%QMY$scQRZ~)~}L$hk3^P>*_OP+B1N%+Sxp)9XT<7B3Ow6R=4jwH#EWX5WX0Do>GB$KJo71?ri?T>tCQKa*g2)0U5$_>jkbF&|!;kO4&9y4etEu44U7ZJxyxFsSNz6-Cll+s@=V^Hfp6LFLv5Wm!B=V?h6$uX1et?3y*%;e~u&z`l2q?CU-GQcbR)6}k0?!rSib_p^tj44;t>>L{*^>nEFTF`$^So{a;e$#JmkhwnjqB~qUt;d?xh1Qvg`4{&#(KH0Uu@wHY=25`;imrTn>em(A<8P@^|ETH)5-tk2)R@}G7rGg3vjdsbh+>pP|O|9*bp@ICq==fU|?BmxSz1yHhfmP$Z?H9CQnLVcy4Z!|_76<5XfY?+S7vPkQBDJZ%1xrMy5B*K7Bq8)UR+roivhw9RJ)k(<8nnhG(^gdIiC9=&X%{NptZXGc?aQb1Rr`~EwUA1Te2uWUvW72bL(KU}pJdGP+>fldh;od5X1XNS=Lc#n?3HqXg!_IgD46kVuCeMRKyT_y`4M0}l(dnD>5|8bKP@gOF6E{^QpN1C^Iug>w|%$7pf_$2zL0BN2hqp`(m>Q@4MYB$!GBl)FUThtCU52U~fOA{f12;}eVtkqe+G9fc2{bt1u+(3aA=d4Pskr!-&cI7=NlZPg2CZrgIhVI_?1ZtZ>J>t_Y8{~lD4A0>O6lXT6P5;p7zG=y55WTIVZt4U}k#(6#m+G{Bt152ZPU>hvvWpZ5h8W^VcAswZV_ij#&r`cJVprljcHhxIXiZkX9mSP<&fw4dFU2bK&9AD_>IKy60MzJGYQ)?P`j>?vMp`WeJJRq2S#+@40j!>f^ALxh9`^oltAOJR{mUFV5r5ydo(aU<>Fw`H^=U@O__zBNLWKBFv3MWS+->vWtJ#rB@V3xdwe~scrLDyU4$o(#!veQ`e}AMP-`CJ6Q2rnb=17)@*OPoiiMk5z89A_GW`|L8a34wI`6DFcy51o0kDncGrq_xMEz3cpk-r*>Ik>IW;yG<5%}2E=)7bsqpi7*w+*W#;-nKSlm+t|@glrCVpq?S-p6}{lLfLHFfPh!1XQuLs&A+aQgT*u6FS%ZVx`^=2IGL6NoOQ_<`RiQ6!M(B>K+NZy@FE?bx%u9s``J*xHfY^S75rRltCV;jeJaFWbP@XNfbpyA9<{dPp?N^~=4Q3y_qktl>dS#k`4GOf{MI+Q*9!%-3xNG+Q=PE}>#vA9o&z@-K+N;8B*6XCV|YW>{nwGc>FS@**;-S>EN~>)>b}6PF=6^?LH$L#E%*B+VGM5KU1z*>uOV>VtEmaA41NX`JqqgN*-8UymY{{7x}i+n_|AlkjY_$H0|>dnEMjoWRn!j&z)%4MpkPs+}fsHjaP!l&xzCLiyi&LQUHhE}8lkr(RnMecZR)syx4*|5}g(N!%c*q4~J%e)kS|-~V(AIcRo^k^D-Ce`=lx2nRe4~2a#0}(xk61+ZRd_d0J$tP#)`7=eo^8k6kOYS$8B*2rtlrmF99hy(p41qWA(k?MRj?M0+tCc(J_$8Kz`M;&#!Y-mo_!3>zE=r14SN2+_L)gRn6kPV8dnlcYnkP~qymOB*)e_VxEsFwtfTJ(5b&ja@3m+P`bef2%)w$Z(ke6aW{c~y7-b%Vd{c(m?)nnd66gkwW;TpCNPk8_s|1mvudQ!6zQp*_E!@)J>YRTvuTtR+S7M+}b*d5y(?d7Bwh{WJ2)j@n2=6^<7MM&n)g$6fiqHA{9W&GfKZUk-r&71z#0;ZE*+W4uW^SoUF@(`OWgt+LNfGCZ1MWN|fir;nZcX_|ozIi^U&Ri*+mjR!~rtyfN~Ot*qu(&ls>|(;3sbqqKX*OxUNr3&Is(wb;VLQ>V#|K^pX;kw^o;J2FfCJ%_ZPR4T7S5s3HJrCK}+coHk}Ns`zAj}y!%HMgHxyd>?HD{Yn#^xG&14B-wzLaf8+f*c;vKa$eSb(Smykvi!{IQugujQETp1LAqpP0|+aBh5)1Rr&mWDvy(o_+5qfhw$OKT9gkL9tCsvN+9>J9id)zZ|-k8yc=J_rAPpPBN6_Iz_ES?7kMBZvDMPl81vViK7H#74=y!QDbpA?dx!^_2PPE!mi#k`TPuMDjktfprM|b_0xUqE-*R1#1MjY<_Gd0%nLQV3b%Kf1gbA4#g}Re1Cs_5q4UNUv+k#Oe(#w-nwA8o1Ciez6~W_)c+(fpY!Ef{G5bA&yid5pNcVFNoNW*Ouv7_kRL;!GSt&AkK*SNPS)@6G3s*@=EzF1B7j{}&yD&}_p!<^cy^;>u)i0!7Mp0k+)@U6%D8~Sz?(fJYj4uu59(2-X@0%RH`+E;gqb}-v5ubkLMl9$&^yo>Tlk#+PYjj#pC&EwlBSp`xk#9LT-r=d44%>!aRv$7#-tz2Wx1nP;nDecQJLQS|vr@mG_s1OIuO=T0Fnocx;j!<#~0V}D>`OvGwhSVeRs?oS#jhm>>7pc{z`}EVK2L4YH%H2OZl8MT+DvH-+1nCJdFIIrE~XjB`Og8oj*x^e8rnQsSgh20qjarvAu@6%c%PN3RBa3Ao>M2E=Df$yM9D?oDNrpy(I7Cp^i%4HtqP6eZ9n7qlWFsO|rraE`>5-tGC29r{Acrhyf3OqRuO&9Bb>;_?Vdrk^cf#*UKA%eV_e36KK+a%5^bpBkov15~{gDj@cjn0tOi=#u{5+YDCvB*p)%GkZBLF$!N4@@h9(XRL%&QhgKBjeRbD2#(+}eEX=CcCSU5mxl?zpqB_qc|lK;JIB{|^+5Gg8eN;8(HxiY-ZB<)zk2o;=TlP_ZI!gL34A-pC0|0OKl}C#8{8KkUtQ;ATn+utt?d*X<+CJDwE0u(Bu<)PjE2xWB=5?eX*WH%uc6+-O%;+fRyX=|#P++#W>*^`5Z@=WgTu)Cif;b1NYatWWCnd?n32)ax7nzViTEUtOLRyd)p*r=jlXPlqpb*r(}xc&8Hb8K=2tjTkWCz`Z~Iq5piq*!rhlsZiF93HRQ&-x0J$?om*#!dRXN{z^srUQeMONGLb?IyjgL3b}`U0s=_B=$H8WzI--zJ?^45L2Kfm$$^vhf4npOXozh1}H`P$Rv@qIy5_w5T-?94(j-d``wexgYP3{M90!mA8_BsK;?>L46ha`*C5LdOFBlR2e;FiQG0lEqk;%3zQ#U>vtmge6s&6{4?3VW1=qo3aL(>n0GbtoeI{P*B={_=Iog5mI&DYI1d^p_PpQn0Pjy*(re+ruK5tS^lq@h66Az0e|kF|CWH50)jx~(hse_mi8J7FqakZY52?@My7=8nO(wkT-qCy15;?zw@SX*%SZK4|FEife^^cp>6vd8jP6V#z=F;-M)Bm{TZ!fJ@Mj8dNFXy|6q*xWQYMl=SeqwXTY@Vcd0@Sq}O$zvI|N1Y$G&fRIjfFC!K=an2M>7O;!De8-82*3HfT7Xo?e#}K_*7e5;K*T427rD%NTLX!dRG7YQmhLW&oY1wDD_P*@Sa(s^9eMDOuRxPf4ul0=l3P1Kific#Za=pz7cR?v78oJ*56TIhiRe_J!4m7buVccfmxS}=5?z||!KgOgh>PUYWyM~26;%she2M9akS(aAitOK>)UaoO`R7+(&pkwb=Zl#5Z_{Ybyo1|Ls6zyLlbrX*CV;-$?VxkK$VcDi3hebr1;6I~Ma3k&MC6<91!lplPKTHIq`E1>f2@@+2WA~hGZ`T1v10*SWZ$x{_kHh{*=I=cD6xk9QajeuAglM;QmsSC`z!9wf8CM~5=Ul*@H0sDSMr`=KQ|V@o0P)JLnMFE=*v*4eSiUD(RYpY)?RBD!t`@<54};`uAmIQ>Kk)wqrm^EoQ2vY?^-$V|_}m}g89b(C18ngcZLn92vD$kP^m*z&&!a_yad$;IH+ke0?%Tc3v!CzZS%EW>YfwkMH(S$d!`>GYbE{t;MQ%J+cRj?40ap|D^OlJt_qyT#ViVt0=rC$qxx^ONFT#KClXoIGUB6PmBGm;c)8D!WcBa808RL&JF!~1#9G6V8MbK%Z6n~bxhKEW2*T_d8~XwV%|%VU{|_fynhzF+*4eBin{@}Yv{Gv;6v8k!_p0Cy>NMK-tazO6f#^do_-LvG%*ySjsvhuutHyCZT_0>_ViiqtpfY_a6gdHxg_GWdKUJsNcaF&F;W(+pVlUFfpmchmy~f)z_d^0VP(&y5==O_9eexO3z6-5en1GmFsizFANE{XeR{J1*z<`(KHM2Bk9EB7_D>l8$JX5?Sp;8A)4d@4ffDSBr|0l_Clul_F6z?L^Tq``)kn{rhxYKmWWRp6|=`x?bnL@9R9TbDi@%7JAeo=yLD)9l?RP-GJzgum#K*=xD!*MXh4pgOAM5SVK6lRh{^a{!2JdIgbvHjo`)IAKJhE%<1sM5#CP|N^XS?Fqq)(hj0)$iuuH)Z)2EQkS(DKJL_|OwlwDqU!EKca`5Or7!Wxt9Ud`CVe<@4TDB#~){)KXEuKIC1Oudb2M6{mrl$pP>3<9I()U!(fd$sriOib*tSJ{?{Hiw+s9D2%F#T@Oe=R+{_pE`HS(ZS6l4Yk4~4d^d$MGFkVFT%lN_-_g|e|TgWW#&++dY{ZlHdKg(Mse6BP^Bs?j}hWS%-C9bbU-t{c6t~rgf5O`brzh>qj?~+}q!Rt9jg@f#Csumo=^#q2uqz4N#Sn>S0ZMYudyd*tZ1eZU#Uzw0Ye)V;)xl>R`32ajkUcUDi#;=Gz)|D?yL892--R3gJuLxZLw!dZI0fLkMGRSj^uW5=p+c5cDVyUUdeH_1){rVxxEvb-nCuXm6A>u^84SUIK$TJbYuxSeMJ>A+*LrV%+bpem-N%>dCA*y+uRIoIkv|>9>suNV-%)W?&0ga0oX1tupuj-^^RKnjCL0q?7P{(=1Cl;&iDi16H|7|~B#~UEOa-UM$&hx4iPTF4JxH*9Mbxl#es(;M$lv?%p?^DRH!WRAJFl}Pm*DQBS^i$+NVsha=7spdT>}bseOlK*5!g4RTv$Dc_<^ijFFyE{uyoEJkox8v+7o(Que%hCso$4bL?bTq>&nDq=I85>bdzgt8{#WRdh{LaW8n9^n|A7s$fKP9{wOSxPi5&uEq;hRO7`ka&Sw5>R@|US2k~PsQyZ@47C@f!X(NRp%wvCWeQKrtO0mAPzS{=?HE>%neb|&_D6lk!PiFEyweIq&nhfs`+~FOqIdfxb+;_YKWUJvEb@Zhy$XnddE@p*B9G4A2$!Ag2fj*1*4znuLGF}wlAsKV09uaARq~G_mItMBi{=k@TG>&7DePyPQKAqexImN;LEs^e+};eWlJR#uC7y>h_4lK~g`y=O1D6cN)Y|^PEgbdP*l4MdMeG<*@3(3k^v5T2pR?e?kkPG2}O!VmT1iUAv4o_p%Gp`G*Y#fF!CEdnBbnS6|t$FAq}nC)x{9N`a1c*BFZ@}-0!-TS3L^gU}P-29#pwP2#=3*3>x-h42o+#dP4XmO+T4G9rwI0?--g}`viMrx2Z3e`6XqIdtJeD){-A^QzwIsAxM>jyM>7nQ>9fY{wvJ<&ddUi_=dGU)E0m+dC$ffQuhZt+%*1koU!j~y3}&EgwWmwckQB*VfsK?jc16SKJEk(KXW&dY?B9qmuo`XL{yNeX(ZqL{~uH$F&0-lgmIQy}>y1uApRtS_kGePYnn=jEy1G`N;$=$bBwx(&blXWkWQFhEQzJ*WN*@~&awsDiM@BFI#YJn31B{Ac?}I6MEs61dl#qSn=iJcmfXzb0P_MNV(6p$mCVZ%~`Skqcp9kfT|A@yaxsZdqa6QEWR;Cv%X;3`+XhXLYu4leL=PjZhn5fTInv1;4FxhWq(yb!+U9PdCD4$gNf}}dvCXQA}fE=unXt;CogaO=|(!dkq8U26vXjT+5Gw2b#vi`Pk2HE6S-g43OCCee^&A^0EB}Z9kOjiy*Zr#VvCc>E7@_^^sUX=6Pz(fwNQB5Z9^JEv0TO1w!{!QG=vE|F|~Ls4xU7^H+0o1M(RnKbcP`k#+74sl|Nt@9sPIW~8PAUtC@J@zaRgN+`b_Qp|;?mzH?uANU{MuPM3kgOS;C3RwMdHfeCg@wc23MFpAf+jYO2TOkc`LdQ~jEd%yRyyiODhIqNUNDqU#uW|SNUOvo+>pY$)+Ob2p1Qe7qKE5|4-9K8Sp5D8;6gqo(>{JpFzwIx+#W5`uChC?ic(n-m)j{=J|2%*Wu2M6WO!)v#)o%WECiI;B(Vkr{w?P{hIUsEYnXp#C+d>t&>qEIG)gv(^6r;r3bqVj>zJ8HtNK;iF-w$DW15rdmfJ8Vq7S`dT9ylyMMdQ=?Chj5_tyiRZGFzu$lA8XT*hv{ur0`hQt2cnFAW;=*KGqPNhgbO@h|Jdw1vDL4Uo}v!dQ5HUo+#u5p}IMV#nIY5qPJOsb#1iykkkN?S^#R*>WUWWl}rywlrB=RC3cDoYO_97ta@J{}~&t>2K&IwtG5=fXAzC$eqaewB)Y-CF*T$J^xbRp%@31o_S^K6WUjsfYo16H_i*R;qiUcNR3jBD2?A32Zy>*;5c!SAV=;1y#YYWkZti?jNT73IOR=i;$n%n|40JSTKHj{@d*N*P_Z@V;-)$sF%tD)aZ-s$kHqhIU?fIn!Cyh5^r84)b(3p*?N*OqW%^E`o~|9QVygeId6g27TMZ^!IWK%4{wRNcXe9csjPJmBRWeh^gzmoGWwcv%4u?zkmm;uIPDqYhkN8`g$MU*sO5nN|O?K0Dv>WqrdYR1cbAGtSmj+UNkLa&dRg(mpQ(dkuGDQC1vf|7TIg%Y?bSZlbJ#OG`4)GQlSN?HASoJf6|-d^=jtZhpHg{2Sl?kga_BJP#NG%{h&tL1)FGvrrECe5uE!g8UEu^Wy!qkT?l=ML3H7XrbLL`nMUIad}Zy(yr=*xHl1hs#Jh>J3TH)Ai{vP|cHjs0;0LEt_Xd?;ZpE54|e$5k$PJ-`{*c^Y4UCrjiZXhqxDit5O1|WV!EZ*W>p}Fg(Na0n;DtzqyJbz7FvR`gU*VMFAi$x_0JOjQuQ5#4XP)iv{s{Q6WozAn&rBH+_1pTq-Q|dHg)_q4O+Wb$7j_nn@Pu?bXN*ly;xRMPE!CiHzpKo^Z{^+!vT9|IxnF;9~#x8B)7gZEqGYih0||9Mb*J^o)49juKDs((#~%;Nj?9VEjR7QsiGlt=r7k?E~7nnibHQr%tf1R%gI$UfxcNbv1%SFC^^NRJw@L}4?wRjowpLZP2Zqr{pS$%=)+mT1rZuryxCo~d{Z&hDv>4+G@LZ$%wC&5PfdHCllIvcn|rn!}-;Reh<>L^WYM@-?f**$ggx0`+69L6kr~+yM)#vzuM;^o2jsh20e||tNT|Wzxw#4P5b0^IvBYGZuoTtarWn$QL_9+K-9}dY9haKNOQE_tXK>w+bd{o^@xjoO^AE0;R$@I{ohyYKpt|{Am8@*JXG_(VxEwBP8NklBtrO8@552XT-IRlip7HVWeS(vrjm6Q=*OpU_Ag@sH?`=%$#vFc|R%>)*XUCQ$^Q7v3}EoDet2J%282TQRKO)gUdqA920AxAMb={6M?5a4#hQ{glCH7jCItF|cvj&pMeFQk+UY?0MA76zI+EQ&d`majM7l4dse*S#aNUcTMg#*)XJX*BYvsZT>xg@ZKcuiG*W9=q;OqOv!!Oct-zNI9#ahGz(f3BFfmEk9efql&ZyLz%`WaG8(gEmMT6~p*FB|qr>b;?ELENO`R_(HseCU{QTi=m{{OXzf(WP6PDIl!2tJjE>H$~`)QG;kK-LnJdGkK6hC7X?1en)sMv~^L#D-Gc~JEY-z&5;|BDj>7PS!&b*#Wr-U$6;dyZt_jff;5>IjWUdGAm5TaUK|ro-70$Es6q=m&{=Px`7HR{w(1G_>2T*C}EPZ3=+USLSR+yG1Swm)$Esh2dAGN&yQI*Y6tmFkVH2k~aS9*3M`*g+28uOO`WvW_sIrO&{7V{d$6H_?{xzHlY{Va|FMiM4#6`mc^_-Yc{0#YEk&(wMN0QEM0enY~&A7d?LG30#hJF;zW;PF7k)CMbTRF3p3#ohnfBDe6$atza)Dg7X*9tUgnT=nTT_cvgUtwKhsFkYvoPZo^DNrQ|E53v?JxKr+D)pb^1VqJvVLUO)DXObm`#1i<%6ewO5atM5BF_xJAd4oQfc?_p52sceIbVTE|ko6UD%r9=P6yq+8p}6R><-G6}lJA59z!MSex-RI;B<1B)T#vpX#tHN*VEauw;c`_j#5t58^8O3L#m?!_Xc>2U0%fAW?Vv`=k_bJOFa4Cr6C^0B@E;!0INudfO&f-@_Q#_l_c_967pY|j>h{**h&8O6VAF{V0=X$rJ3-q`S9{2_#?{2?%?e`0`Yvp2NRfQMuhM*}$`K-o|4_n3r|AQ{Yp|%X}DIVQ=8@5A(7J-M6BP6lnAx?s6~=nZ+s2DxV!xXsrJ1GXBV0rd>DbT8A;;XB$mRB?5Vi>xcCc5)1}-nb~A?k@BG4wRnZ!8a)95V*(aAFOe@D4(MOo_ACUt^Fkd5P4KylvVxY|M-t$(`xW7yy%?wB-V(M}J1PxUh$xLH*5P`j+31g#n`J}&el2fq8(dGS*rf}HBJ;uM_q%^<#c(~ZKdF6un@)jvt&~IJUC5(|dv|9h54oUuSFt}3c@&ZNve%Cegx=e|1;}%5O}3;cQW>!6`*04sC-NL3&u?B=jB~+SQ@nJE_J2yAYU3{D1KGq&IVWWm)_bvh#PRwdCv0oIq{&gs{h66P5*zt=6aqqkPH_O&|XR8t7{e@;LeS?|jh^{7fNngZ$G_n?dEoH!$=MQ#jmLcx1VRO0H-VumCdu*EM_gieF-NU&;pk|xE=!W&^-=FaZ8hhQ32O_R;#}NIv`h%d6@Pla}cQ>LWG8=hU_Z_(2!(BfRB9-O-7xIKT-CNsn~l)(>|%(}B=AHseK}z7d4NaN*l@-l5RuFOan>pLUsdVW4@sdrn06!N($7A6g2GmJjvq>QJi>&*YAuhAn2Qt3wd}F@^@424&rTeXmiUgtjqatN$xX;TQ^_^V3C>eFbM+~JjtguCm#s+kfax`Zm#3JY@6qU1`&Xp80F8|8ejYTqdy1X+B&k0U(Qk6aO*&kXn5tOCgSh>4R2F+D1J;jfD#yDZ?^=J+(&e{CFk~&3EX*S5X=~Z|{@!~!76@I^PE!0~qmotBQECb>>7>Z{LG*(}-_J5N=J_bfF7nPFjKdIl8cI&N@aDiC$`fHd{~4FknT&$gxUN-z6f?*;79jR<_2JatoBt;-_!>Rcn1thBMw>r$c|C9Sqr@J!9v}fVrQy1Vp_@I}q^>|3N0NctJnoPwKN{`{}*0=b3!io>`{f(1&*T)9?3b&Rz;U7R*1oous$Wx^&O0op-2UE16%bEP;4Zn7_L8JUUFZq|C9hMEekW`ah%?AnktC)T$EgL+FO@URngN+_Q5SLWm2TqXt!oxr39;sk6SN|GU5I*VM99JNF19?cGV4=FJG6i(^m7YHR4|xdVj0Vqvdkf#6S3&vZBwAjni47hROKyq>s@`TPe{R>hPPr#Q&Cn7vn;rt1yck4=&LxAWjt~ZHzg@WL#6vKG%;M=%KLLTqwN)yZt+FDW}<^8Yib)+~F>psRK3kGu3fAwuf{-bRlvMeAq4|1}zvzNZc^_ZGdgRcuyK-_I(uhcf=8*j%YJ2dH3c-8E=muC+0imzLjk3X2E!HDxlVdWacmw1Odg-bAC?$yvmHxDA;kR%#C{<4RxS7x00R{z8MHJ{Fv44udiV)0v!BZ#N?3=0$s#6j@(WVz^Moab8RCY^H!Q^8h!NtNah;#%1{skyRQP_}U@NpUykL8Tlt8+~J&2L|Ut6)YQ4XXl^edf?)(`4sRPbgQFn!FZ1K^YbP0g&zhY&g=1Ifm5|D{4|XHq>%iSR0=jBq;kvsWLzNUiSuy3|sj8j|tbAKN#ECkb5uq%YJZGPOSOf9>i%u&aw#tLZ)03RO`iQ>}9N!ViMSnHTlt~Lu2iWpLacAdSK1p59eKt)KY9(lPPRLM_&`m+wkT0AU~E{vP7ZO?eVfaFDlFZR6WrNq5OR9Ig(Vmx*Wx2e)@*z~gsMvl8?N&Y*-{S5?ftR)evd*@M-(1B|+5dwI*&!;e$G(v2I;(`NA2I#zJQqDWdko^M9o{=L4ly9fG1FzH?D3^!Aao#NN&S&c=JkHB+n&Md(--fAb~6r9W$ZYf!|IR8QHXXU{7Bb|0+=}%#ee(*+ULpqYzMI`6c{r|c|Q)Me$5IZ5e+gl$dLJIAXSOH;s~GUjjuLz*!qP1ORGF7K6ZQ6$zfLptSU27a=d|da|}@7Y}O6~{&l*|XALl(L)3HrD~^YksSWSq_9NdYnu@>p*DMuc4k<*i+auo~`ecknX9A&b_spHtUvKz(%nK%;BAMc+x7470xY&LQzKUnSzpqg|^&}ok^qUVBi~diSbz8+Oo~?I$^TpRmaC)QgVDL8NT}mtJG@_X2+sZXbFS*swK8<$A`(N~BLC>l3rhV#YpXH&uxhh=q;2BTnREI9w=Qf{`_0Eby7~}uOn6O9toG|{Luvd=?8=0<g+i2G^*$aW1fStarl;(p6(J{3;2-q}c{B0ssD)$JE|js~v#PSd6!rzCoybFMh(_^2XF>Ii_|ng}FkU47fqK^M|@$%fR`wUhe7QYU}M`#~{6HmE=<&yQX1OZh0{UWdr`5|Ipjs`g_1g@m$QNB7oALs&(t0pf710NA6)M%%1z%xd}&hs8}Vui_#bq6_RAjgv@_Wp*F4-#gU^3@j%t2K{Pxa06wOpR+!q$rU3nJk=7>D5unwADI^|s~MeB^1AcuUprgV{jK{TnRv8uO9rXA*_ph37-X>5063R}h~NkXg!}P648yPe2y(x5e8nI0fWruq(p6ZY&V-_gk)Us|L}5IInk|Li~Q|$uBA;3=pUd+xgW3aYFBJV1qksmukg+#5D^he6H5fm9Ka?$G24ZHKd$5@Ea5>nbh}#0kCTTVK-PtGT?;)fKeac?_kK4C7+5A@t4iowl!#UlH{%TZ;36xZv|oM_j4>io&G=3hXm?l8PYpe<5_0L*;3#`%``yQva8{h|+52`&I{gR3(oi?~-}YwQ*Mw0}houn&N$kIFaYirgRp5{C##-S`_0C|8$FYJ{XRGjrYVjjuzm4{_gBNnr=xF+zec|D^U{hsfw=X-;wF?P=b1_n~MH!DlJb)eL5TLoa6E-t1-?)=nYkV&u5+Ai>{-c%?fMYR>CEH5xQ)Zj5py^?&(M690)2MF&FPLY@>id%yH|id88C7z1fH*hqQ>L0>n!^mYfpwa-Os?mjG?eXi2Zp=jIEXjrJRCe=)V)Nd|-beqzhWU#S3-|>&s-{k(U`Ku0CXF$<0ff~2Z=m$T_<-Puto&z4EUiGJp5hwCyb!`fODx}5v_BzH1LoRF!j_RcVp*OF!9_<++X3<75rNPdG3djB`v?o!|keyBkvH9N*Tq5zY{ug?J<;>sjvwXP%!(Oyod7RF6lU+nDQ)tM%iWs`dzc%Iod)6qHXQK}hYR4@xAo;#h%=90^At+xkU3Z5S-^c#KW@I?8V{NKGb`>zijV#4pl$!SHxd+&8Sal?jr{8EH+?x}$t0k@C~V5KC&jg#2Yh@S(^!4yzow#nMt8n(TX`}ID0dezcpA|@+nK~pOCk^S9c_n=Cy`$r3%ka7$EOhfb?r_YQ9^u4=J}ex+o-UmK6XmT2koQ8d(drVG7ZwAzA2qf!e%(x@6Hvg;d>(^ux`8gr$Ga@#E&J5Ita*Bs0)JntpWrRVcure=q~R(<8W87+h+D`{#sYc+ewNcAOkm~V6mH}R?fz<)=M6GoFY`dsyqUy9R^$gqj~2nYU6BoTJCSctog^CWiiSZ}iM#f3KV0XbS7kRWcO?K(5Ah(!*cJlLphKw3T1y<2nzAPMMccvS4qT;gIeblD@&W$il*B%yaJUv@nh~S2l&k*B#`*yA5c5}q%OY8zF3qR-sX=>eQPrg0jnk#Bj;G~>^*7$FXJ9U(wk{l1q1R^dDOL09!KZpaLbKzJ-eD$q$xE{HUZ}y*mRmfx=jh(;O;(AUPMcwEvro!FuZ6TjUF%IMJX-?U{iq7ieY5xxKIJ%qA6Xv;3-q0gsDFykA=(B4rdlHLaP)hpIdo5CZnX~GhsVnCoTPHQvt_q*q6D4=^=iMksJahP)TM*9wO5BW>Ql1Ro-}i(}7~%Zl(sO;T(ldZ&6`s~6g!5k)UnbJHJ{O2SnPpG#zKrNM=c`r-$CRpmF7ZPCV_};ZU1v`P&t$DbSqm@@v(h88>EUM@7|!{(MkN{X6M}Wp72BD-u`O>xp9AAXU4NzxL+y(oC$n+%vm@fY-6MJ`6=zxc(oMq{cQPvN|900R66)ihB*@w#KkAUX%a=v`mce!}$wds450BEps_5qDxK%jM63zH?J1ukIV5!QJ3o?i+**-M4bS;4C{wszzm*G4cJXW%6%%#HX&gbHv7a;Bzuta*8xj%bPtW`eokCcZWvgCvBM>;e;HLvX%MclY|ZB&_H5ws@k>wDOTIFSdo{)G>SP`i0(ljyHI7qjga$c_XtAF1kgl5X|~n)FcBR1&0?lowyPOVZEeU4GQ~c{=bMkKbXFh4^uoZ{ar#a$wBxZ=L=z!5cyCWvk@oim+pOI0Jn>PR`V&uMfyyq%TM@&>b|(|FG@>h*F)%6EB=lG;{RKcbj#PL8SS?6NCw^(9&NXEh##w8@`zhH1L%idZr|67{w|3B``hQIa=_tJ<;bHj#Hs7wn~5>sx6bQ$;~{zEvEi$2+F!km_N`cU^rVxWrdT6((<`2ev$-d&f%%2O32^^viP3-)Zu%K%2>&Lxr`ktd`@h9ACsB?ne4T6U+BlqbJuQAz5y69phHb9(o4lAif~2M^$3zV8C7XjmCT(vz3J&6{CHgI9@*lNX7R`bxh_C`-+ugCaGgaRI6Rj_6O!Rm%W-{TshW%n`TVFsME@9SYxQ7p2y(K^`^q$9T1aVmydHG8JyDM;@ias~-1~$tN%P{>-n`LcHaR^{9|~Cd~DhG100+yB&NmwzFtyE-+k6`z90-7iZUHuP7{F#S_LDXgAkG;ZGFbQs9%d+(Z$n?_vEW?Vwa+8eH%kbbFSCcGE4tS28D#4yT9)KjMggR=>UaDV+gCUef$>w9mg)i)Fw*7Uo*4JSevMfA@g>n#6fvzgP-f3;5NxOd@0!SDtq=?}_Dq{gH#WM9ktu{T-Wq4s>^!%q-Qwd$ip-^R?+B|J5~I7eRg^ukf?b?*;`9R$hD3^b+~Wa)sBj+nMJe&eeP>YXi~mZxJq2)M38YmxVKzgy&%V#DdGsl>G_=3g^Tm-#dVQf5dRJ#3|-EWM*ZV5nC+!eWHGB@NfjHf2+xC9bdmDk+`(AJ`sq1VxsS2W^r{l#zv`AX;9+xV9nuDTtCmWN{Z}_EC|o+fA(TE@|L)%p-IC_c~H=~u03H8*MHDl;r0b-3UnTSJzvESd6bB->sIL-RG7;omOW#bw?p)?1qnJBbW)rWwj)nyHLK2x+s^>sy~#Xtk0MW4ZNI4T-_asC%X7ml@i_8?AbW?0evQFE=z@Q&NSd8rG&J&fA2k+&7Hv8vL%KKYb(-ViT9^VvUX0*ev~$JXV?h?{GgQH-8W43|=_I|QfCC&eM}E>ljY<6aa*(&o?2z5*wYUgu*{_Z6cS3%$)-CF~&)_-MeY(9ie(n*Hc_x3Aqd-^kJKMlzTxX_)@kH2?WH1hHX;l`+c$cP%b*=uhbP#>nI@M{7JnCX*F;|jO4qRBFyVX4c*HgcI0ngC#0+wExWn$j!_+8G+b)G(=u=JTfdLb`j)nAy<;L@QD%U^3E|6#ftSVf@&mrU%YJ)aQ2RK97=>qZ9X8{f=Y6@Yw3J-%k2guWN>{S~tOvjXiv2nr($lT#LN&()q#RqMx5KnRRNy`=dxIRJ;DwmPUJK2h3CP=k2`kk2&K)=BX{f79))(^|KP+uNBPlQyjRL~aWdpRr~GCgMwN?9ZRB4+c0;|ZytG{4KWHvoB*r{@Fv+<%#{>%^;jy$OgDeN-*k@<4;PV)tk=;`Mz_59-qkVMKH!!Z-=%C;C$8Sx~`0wRne55aL@u2=eDMdG);C7v1IE5H~v6***G+4$fy}erec}_@SXo;OXyfApVgzZa4*b4w1jLIVTjJIo$8LTZ8`EVa39W3q0e2+iZ;&#~s9Vv@BZh9ZhA$6TaQRc^+Prv`@XB34+mDkJ%YGemorv{xEWZxEB%%#qoFl2rG-OE`&#W_jlG?;P_>xE;{j2R5)?_iqKyL#Qzj&`>*wE{VeHmNEGbI`vN_gor&VXXSxE$oQv3x>%zOvMAyH}c;I`u8`IiAu)JcDcBjI9_A_{^2kE8n7hwm#gS`FIx{zBV6p&LG*D&__FdH~}i^P0a5c3Y~o};YTh(D!9K893Oa(dID|7MVt<(X2K??4~4d;<7UTS4fAW?IVTqileyxhj-ekX;!(RJ3*hk&!=}&P=*K;!K9_~}QQ)-GqusY{k#F?8IjtYS&9;}fbjGDqUf&)KcaoB2&VriYBld8^|6i1xv2az3L4Jo#+S8WJnh6A*O-6Lli=&YQ>igaaQzCVX12jg(&5L+&n1Q1kS~4fJ$F5AbvE1%ei*N8fIOtw`Wjc<*F0d|^OO3s5IW`zB?=hDx3`6n?z3EOwp(V_Gk>SbL(caCaQ#9H{Imm?(}90-Rm8r2T>qX^^Ndq>Ggy75&MrlNYU1OuV%VaHRR!?8J=T$7lcndVCpC$}e_&$Rveg2Eq&(OOBLyYvOa_?AQKD_rNPTkOJ{dUt+#9Z~bi4EO46d_-O~3ovvv6=xI3Bl(q$_T=E5f`tBN0S%_wyv{;&X|6J_qkKu(1*@P5**Cs<%L@%IZlL?5%NA==US_Ns)HBvGr~qtQydg@EIf3Nd>2{r^--(rC&nQQT*ewQhmckDiHc)dZhfQr9+J)=G=5(-c_Cw?E;pQD5RdL6~oWM)|`eB$aqwk8GfD|dg?zf(v7qThQ-BgVnrpQ)Hk3eJECDbAIDUgP+_sL?~JXLDHj56#1fzwz8WtT3+tMs|A_Ea^o&HgZagl1Tv@-{0=~j}T8Et-KulhYEy_rdbu@#QmN7W;)!K>nf8;M_iuqhw)0^1ynMZ^Hyv}KThbnuJsHC3E>&9}1^EthdThxDNa*-7R(UtQICdlTX>8uoKcd@F7d?5UTZ#X`8&Etg+?wV1cS<8d#*#R71lJ>%&p@s@X|IF=jh!cIL)xOYR{m0duJ4yX(2wjf209O!Lo$Ge*DDo>YxcxOyCh5>9^|3&hL7a+sXV@3H)X`-4)-T7emyY;<{dLmeQOSd=y`G2@`HT7W*}y2aGCHY)IFU}WMm8S?Y+dZLcoDB!{P4huB^3B{>F)a5kCCUzZFnGmhIxKddMY)~I}-5~KMkZR&eMR%>-W|o@w&ePm%6qkfc25gQtKJan<`pgImW#_6*%oqPnl8hzN|}C@rK<@2ISX{AKFghA)_AxZ@jya1F94LHqt^QLtf|vcyqy%$tgMy!O=n$|NZ2^-l==fbpmcl{;0g^rk`GC${glBDj8{E;Xw!3rx2r+rE;+^>T>h&d4_-88Mh^;N+{PuKaaSiN1#Ul0SiYeR<0Rj`!aChjs8CJK{rmJV`gc~|(pMS~`blqZ;QERFdbzvIRnwX;qlf%tk=vV@2Lb7<^U5X5u-27{T3fFkI7=C<+xKh?_tqeW-f1k@5+AL1gDfFLaK*=G>>zC&c4_Izrw`#LDh`Tn=5BY}cBi5nEZzu60=AZAuRF>Y6egdg49#1#_{yrL5y6ettY(sqY0vj6(0R|{OZ#nEc7x_bukDD>uCs!cqMQ&}y=YBhVG@5@n1ZtH_H%I+M`y5`UJ)T|_2gLoqLq5(Q>Qv#hmp2tAHoQr^DT}-%T=ufB_vuWq$&F7>NH~Jp(EI#Cv(p!R?q=x&qa8h4aZOLWC6QHg#kuL}GgI3)=b{q4)Rt<+1XcXqdwVjRjHMKaN==;g;L;iZ^X=4+6^Gq{0c6^Rw$Yb=J3N-KS`fG?c9U;DUbqctZIfGv8zoiD>@V8H+g0_oVIPnsj(8ADq^lh`840fyW$K*-)hT)%AWL;_}p+vI%1Oz~QChv(*lt8(#fwLRgvtmv^jM`coCh4=hM6lVP574Ezth+QWso`>pPCcN%FB{P@U|_AY!cRwKh@r-6B#6>6A4ewDMUzJKqBAh;LzZPJvK-%jW_1@p&%g7KpMyu;`vA%Ux_~Vu%yEMkg=lfi%akq0@Vk9@oB-xzUdbVQ2Y2F8T9_M6w&uZo9SnXet)s?7!OH)UQw{OD+e4rFT7uT8~r$;n|JC!0kl|O&ENb4{WvTB-%R;$|1U=#@-jUm*=!pP=<4tm+k?PP1UYNuc2CBcZ1P(Ug`t$A@%u|^k53UuHm!`(i{@T~9J5wi8V71;U?>;u{htf21w1-+G(qLG~~kSyw`^(^U%Mm#)b4NjTQi3vE6hjFRq7!P1&PvIThXrxZX>y=DDbh|7rW#$+ByAZ+t{Mj$xuA*6_(nJai^n$`*--2ri0z`F^9gZ$d`=%?0LrhCL1!vybZ3oA`c;Swl%Nh!_5w5GX;LyEH1e5_qNtl3j98J$AzAPc<3D!Z;vH3_@N}ZkZTV5efJ;J_1dTDAiL(H9oJ#R8UK94uVgZSxEGCJApVUJ{`ga+H>@+@z9UnF>r~dTidiV)fNE0VP>5k0>Z&AU<*3<;p1Y91(AGcIA!b$baGtK5-ZcQ(#hC%i^C8;zZxiuO(Cvylv0tcpq{9?T?~9bJ9Vl^X0>=Imi>TyZtN|Y-7NK?@LW@Z$O-=E0EQ71ERm;EjwHf5vQG8&OArlDqJSIfyBprU&|y-#dz~V$#ddZ4CL0m1e}ZPCNy|yy}*}qJ1H;dB#%P^lV=MmCpkK*Aa49>-)nm9325;dtzACoC8eOiwp#EHC8p&2Ta&RNp7x*75O89=hJO5%7vooJPBMtAmo`1QhdA>%aJ}JeIxO9{Ja4)M=OOaaIbUQ0f5g`EOLaJ&PxMB~Imdj6T6CB0nTNR6{P7WcBMSTs4SsKZ2JynA{A<$JsGue{*?vp|@iXn#{%KP*AoLWY=OeCgV(LPWtusj8Q2Dq)q+)hGRE7G#FMEO@=!bF6Eqlbb+`MA+P9_FUjeZE+6N|WK^OG|}A<3Zn=XCAsRKzo?sJT`b(m{HD?Id3i=Fgwk{}!_SGm|0F$6+kERpB-F-@q{&+Ws}ECDX^qtKw4}L`oU8&8%0ZHX{_(LX)(raB3xCYD!rI~HpcC^mPr7d|s)2)z)Xgg+WHow4i57=w-=`4(b)3+AA4khJ5sS+=0o&?NQs%>gV9>UzN6<(*Mfpx7uFFP-;pY>iBvfx+1i8_yE$U`1ewXeE|<^f?p?!U-GK0e)N5;2zoZ??{OeJsWGU(EKqtddQICl;RKwS2fv)_LY14Z=t2;;&pnJbXvC&PH_xYzrIfq--VW{H%O;Xpcz|NGD$%i>yX`)K62zdQK=TCJ5~=lKm|c?@ma?vGhaggK+(Vp$(6uvr|C5&m>+n3*$Mge58pCAlmM}^F|)R>(zMm%7Xv?{aI4~5y{1AwD9HvIIL?f#H)wvi5N^!WfP!+`_0VXyu*l>-s`v98bbr-&pz@tslWUU(JbMV=XA(@ALS?7jrhxKt@p2|7!bBr!{Pl-KP(b}e5z3K~8&CtoGqi?QDGc@jMIx>cC71^H5)N9vNW6X_5s^0L*Nhc=6|>{gQvFI%Vf4%Hz}z^e=Lf#_TNZ4df=LZ@PP0tIMXWj$3bxXyERN&F9({K|z%u%r~x@Bi7{bk^LB4%OYOgzu5^SRCH5XNpo75ERgNd+8m-iSOI@Mo$fAoGM{_;s&fQJwr%5Hs+jgd#55WBY`oNB;;w(w-@btWV|>SpE#m2d{GON4(;uE+J9bF4Af_Xq(Zeyo**^M6^RCYKQr2ff!0%Oz;wJn@;Q1?MhF1=ca_9`Y9A_xvLx6LvE<0v~x&{DjyKt8yW)N$OIyJL2<$(|0bgE(Bux%%LOxdPE>CbvG5-ZjDPh-$g!i&Ph@}sFntd-)i&9IuQTXxI?RViVj5FeT3BaWO^_2lWjQhpRUUpoS*f3{1gN$nF|P&LLL(B&%Qc>BNispIX?!MA#Y*5=b;ohKh|M9$b@2*=IDh2FyLjEf8dY!$xxxEZPOGW${tppL;lbbsCWB{BMlV#eqD+c2VHi)&3_efJmFt!Y)=AfUA~pGk&ehXt*^|NcnaD2#q+va7-$uRX!)yU%qj`zPPy=8lAI_zhDA-sDK|M%?d$5mIdfw^r3n_s|rRJ4OSe{1GLKv|)x|4AIbzB>Qwdld?-U@mj5B#s|lacz||g$mkhqz~4&quu%o-kVqq&>$vZc)TP4aYA?I)UhPc^0R#~BZd5G((j4e$Feja?$ajukYBkMR4M3pWx>sBGD>3iD-km|ymq%y*vGybosbB~5HjpKM&r{N&9jyj`a6)If_gQOpo+HEXJ9VI3jXku(ZiL@>=W?kk!qZ=v}tJ-BsYD;XZEi0Fbh8iRlxs-k1-97#0-|zXJXP$Xy&ij0x+xG`|QqIL2tDWZ|-oBO?r>V~6qqOZS%r1udc{F&qh~$z6L8T~xBc5<xQSx0yVSaG<6Z3M+1JyO3}Spaw$0GZKofa@94_=yWMD`D`8~D#A_7~umUVK7)zfGwo`sw+o1z@hX(QMN%Is}{T7Kh8)kMVeJg~SQ;1InD`?<_7BuazJg)6@HF7KZrACh@)3yl8%J^ZnsYaMx1`dR@@4yhW7CCFW!Z>;J~G{lg)vv_IlUhL1<;tMW5l@gda?;5wU3-w>4%RNt6$slxvySAZPK4hfL6;oEM9Kf!cX&^?ONlYN$<(9)J!<<4<%iE#y-)`U2oB`Gc3UA&X#(t8yPO8f%|IGvJQ@f`|@<4(+2c~zb8ea_H`j2YHOj)Y@8Ln3`E(EgGau?^eWqxqwL%_+rbXzUS=XNxHdvZOUn9qjNCzI#1B%l4{J>EaPCEy<;DJr^yeqZWeFGt#>aCKF9O|KDh&Qzf0h_#g*8gw!#pjM}Y+{X;|E(Z&@4(FsK)Q!V8J(R6ugNin{?bbSM|BWz4Bx0U`wz2aSwtcAou_2mTzPb>O&U)G&7>DhU_azg?dGP#>R{jbl@*y$2CM*msgLv&HS*?IPW8JZ1i;kTL(ixUtA2^CSdAx!nC?P8bQ;(iJKiG$iHEMha~%C-UD}`Y%i%a><|~RW@)El-VccAn2H&^%u$UUib-umb(_a1AP&Z|^=zbRZ$-G>RD~6)({UJtu}4t%@D@#OU`WCf<$fq~KnqZ<3?7P8Bp^+q#`EgEI;Ty(2=k`&P@}DU4g?@M@Rg-AE4VK7p2O*2g1Ycu{d9U9H~7N6|_@o7LISXFK>E!wC5*t?gRksxJ#*q+!;L*#W4xIMK>yw--Too|m>08@Y?z&z5_X!mZrE=J9;=bE4v1v^|7y+h7?>o{RoOUd{)DNHLfPKVBtDME~SrjuC^H4}RKb;kq#h{e$9^3Sh`!kzG>EaaYvI`bn1xPK;X)y_dZ%Kc$;aG)HerQz+>(0GJ-*Yl0JQDb<|s>1C+j4dmKDJ$F!O_tVLJ~61&8cgN`No&HaNcr{TXb(%W*Q|`}#N4KVF1>@>;o`z8FGI1vuKYBbVCp=d_+JBIbizq?-L%$dk)vb_a_`r7$$|m>J}Z{%f1|R`e_(#wnwDs%!oD+~ST~&grvf!`<{s02BaeZe(d=WpiIN3KX>N0AV{>0)VQpo2baH8Kb7^C9E^csn0RRvHI0*m%00000xB&nF00000oyg~33;+Pe@ynLIH)mdPMoN;%%q$rpE2p~@>2jBhWbaM(-g|F<9q04$;``d~)%ST?O3I2$%hLjlfu>M2maI&K@`Is*nw(HL7^;dV8WNGZig+R#`}-F~YLl_lpRA75$5J~ZD=#-3%+3r4n}h#Zdf;EbQ>EcnxHWEr+v0Y(J??-z;&j{zcg9_CSKJME$31XQ+za={eQ;mg5BJ9d@IX8W55`0AP&^C=@o+o>kHn+!Xgmgoa0brAWAQi~#^dn>JP}XAS$Hze#yNNj&c#!49-fBt@pN2(XW*H*5YNK1@fhcpKi1Yw-?ThvT>&@5Bk5#0_{CZp6Fs9=sRt!%cWUZpH`jL3{`w#z*i`d<-AQC-6yp3ZKSj@L7BgpT`&QMSKZg##e9)zKXBm>-Yw~iErWC_zu2{@8SFS0e*-d;m7z1eu|&r=lBJFiC^K@_zixG-{JT81OA9V;m`OB{))fh@AwD)iGSfgP)h>@6aWAK2mk;8ApkvIdTT`h004vl000&M6aa5xb7gXNVRUJ4ZgXF7Z)t9HE^csn0RRvHga7~l00000MF0Q*00000o9q|r8xYCJP{vTLo|0OeT%>NLpl%atsIH@+o|a!!Qk0k%pI?-c3KDlq%qdON3KX>N0AV{>0)VQpo2baH8Kb7^C9E^csn0RRvHga7~l00000MF0Q*00000o9q|r8xYCJP{vTLo|0OeT%>NLpl%atsIH@+o|a!!Qk0k%pI?-c3KDlq%qdONLpl%atXs)iKpq`drR8o|f7oT60k_wV=OUx-w1&SAEBo?Fs`5Kx!3bhK904^T}1_oCk_5DO=WpZ=)`A5Xs0;#!#)El3JWxq;934Zj))EuA`uymS0p-l$aNvUzCyx5_e0?DNY577iT0EqyqUGhB^vHnmP)#3Sw?r0FVFx0000009610000000GsR=>KhQr$WX>mt)7xvoLr=CrJ!z;W}&X5pq`drR8o|f7oT60k_r-cOUx-w1&SAEBo?Fs`5Hz#nmP)#3KRe?k5HGk2+qL$zxFq3<{CTN0{~D<0|XQR000O8001EXf-U&dLjV8(fdBvi9{>~pWN%+@aCB*HX?kT}X>N3KX>N0AV{>0)Z*pZWZg6=401yCy000000000(000000001+>=)`A5Xs0;#!#)El3JWxq;934UXx^~uA`uymS0p-l$aNvUzCyx5_e0?DNY577iT0EqyqUGnmP)#3KRh@MgUMt0|XQR000O8001EXf-U&dLjV8(fdBviCIA!wWN%+@aCB*HX?kT}X>N3KX>N0AV{>0*X>)XMa&&2LZgVbfaCrd$5CDMy00000002V(00000005ip7wQ`j$;eQ~P_3SlTAW;@Zl$1JlVqr_qoAIaUsO_*m=~X4l#&V(cT3DEP6dh=XCxM+0{I%6ItsN46ag+q08mQ<1QY-O00;m803iT^E%?(z0001i0000Q02BaZZ(nb4bZKpAdSzc_cyw}UZgXj4b1rUhc>w?r0D%Ai0000007C!(000000GsR=>KhQr$WX>mt)7xvoLr=CrJ!DuWT>vApq`drR8o|f7oT60k_r-cOUx-w1&SAEBo?Fs`5Kx!3bhIp0WL-WP)h>@6aWAK2mk;8Apn9c_|roG004mi000&M6aZvzUvF@9X>DnGWnX4;VQpn|E^csn0RRvHfdBvi00000LjV8(00000o9q|r8xYCJP{vTLo|0OeT%>NLpk9+?sIH@+o|a!!Qk0k%pI?-c3KDlq%qdO*}(?b9N0D%Ai03HAo0Az1pZ*X*JZE1RCUt?ixZ(?d?V{~74VRCRTZg6=401yCy000000000(000000001+>=)`A5Xs0;#!#)El3JWxq;934UXx^~uA`uymS0p-l$aNvUzCyx5_e0?DNY577iT0EqyqUGnmP)#3KRh@MgUMt0|XQR000O8001EX3|xSDO8@`>hyVZp9sm>oV_|G*Vsc@0X>V>{Z(?d?V{~70aA9L00000005ip7wQ`j$;eQ~P_3SlTAW;@Zl$1ZlV+i=qoAIaUsO_*m=~X4l#&V(cT3DEP6dh=XCxM+0{I%6ItsN46alX01E&_cZrf}R08mQ<1QY-O00;m803iT^E%?(z0001i0000U02BaZZ(m_>aBO*BZ*_ERX=QR>a%E~|V{~b6ZZ2+cc>w?r0D%Ai0000007C!(000000GsR=>KhQr$WX>mt)7xvoLr=CrJ!DuWT>vApq`drR8o|f7oT60k_r-cOUx-w1&SAEBo?Fs`5Kx!3bhIp0WL-WP)h>@6aWAK2mk;8ApkLPR`*5#004*p0015U6aa5xb7gXNWn^D)X?SI9Uv+L{WpZ?3X>N3RE^csn0RRvHhyVZp00000MgRZ+00000o9q|r8xYCJP{vTLo|0OeT%>NLpl*|9p{}E#o|a!!Qk0k%pI?-c3KDlq%qdOV>WZg6=401yCy000000000(000000001+>=)`A5Xs0;#!#)El3JWxq;934UXx^~uA`uymS0p-l$aNvUzCyx5_e0?DNY577iT0EqyqUGnmP)#3KRh@MgUMt0|XQR000O8001EX6dnJhLjV8(fdBvi3jh=Vc4cy6Z*yfXZg6=401yCy000000000(000000001+>=)`A5Xs0;#!#)El3JWxq;934UXx^~uA`uymS0p-l$aNvUzCyx5_e0?DNY577iT0EqyqUGnmP)#3KRh@1^`e?0Rj{Q6aWAK2mk;8AprP8D`%|$007_s000gE0000000000004ji00000X>N3KX>N0AV{P0000000000004ji?EnA(Wq5RQX>N0AV{>0}bYEt2Z*6jAW-e}Uc~DCM0u%!j000080000X09Nz%JHR0T0AM2k022TJ00000000000Du900RRAIa$#*{b6;|FUvzJBWo9mJaCuNm0Rj{Q6aWAK2mk;8ApkvIdTT`h004vl000UA0000000000004jigChU{aBpdDbaO6laCuNm0Rj{Q6aWAK2mk;8Aprd-3vzW(1OPzL1^^ZS0000000000004ji1S9|eZ(?(0a&}>KX>V?GUt(`za%3)UaCuNm0Rj{Q6aWAK2mk;8ApmjbxhJ>*001}%001oj0000000000004ji!E^)wX>Md`V`Xz+W^!R|WnW`qZE0?Fa%paJX=8I=V_|J&cyw}UZgXj4b1rUhc~DCM0u%!j000080000X06kuMYefJ60E7Sl02TlM00000000000DuA5b_4)#VsmA3c42gBZ*Fs6aBpdDbS`dic~DCM0u%!j000080000X06kuMYefJ60E7Sl04)Fj00000000000Du8ycLV@wZe(d=WpiI}Z)t9HUt?iyX>N3KX>N0AV{>0)VQpo2baH8Kb7^C9E^csnP)h*<6ay3h000O8001EXR9KkdW&i*H!~g&Q4FCWD0000000000fB^}31ORMhZgXvKWMynFZg6=}O928D0~7!N00;m803iSflZ&BF0001p0000F00000000000001h0j_ui0BLPuXJvA8X?kUIE^csnP)h*<6ay3h000O8001EXqC%trRR910kN^Mx5&!@I0000000000fB`*u1OQ`UY;R&}Wn*+-cVTjHE^csnP)h*<6ay3h000O8001EXf-U&dLjV8(fdBvi9{>OV0000000000fC1Kd1OQ}jUvF@9X>DnGWnXD-baH8Kb7^C9Ut@1_WiD=Tc~DCM0u%!j000080000X0D>*}(?b9N0D%Ai044wc00000000000Du8%dISJuZ(nb4bZKpAdSzc}Zgg^KZgXj4b6;d>b98TVbZKvHb1rUhc~DCM0u%!j000080000X0D>*}(?b9N0D%Ai02%-Q00000000000Du7ndjtSvZ(nb4bZKpAdSzc_cyw}UZgXj4b1rUhc~DCM0u%!j000080000X0D>*}(?b9N0D%Ai02TlM00000000000Du9MdjtSvZ(nb4bZKpAdSzc`a$#*{b1rUhc~DCM0u%!j000080000X0D>*}(?b9N0D%Ai03HAU00000000000Du7>d;|bwZ(nb4bZKpAdSzc@VQg<=YGq?|Uw2`0a4v3ec~DCM0u%!j000080000X01RA!c}oBQ0Ehqp03HAU00000000000Du9qd;|bvVQgt)a$$67Z*E_2Vrpe$bYF9DVPk1-XD)7Vc~DCM0u%!j000080000X0D>*}(?b9N0D%Ai03HAU00000000000Du8aeFOkxZ(m_>aBO*BZ*_ERX=QR>a%E~|V{~b6ZZ2+cc~DCM0u%!j000080000X05Ne^_eKB!0Ehqp03HAU00000000000DuADeFOk+VsmA3c4cH=aA|mDY+rS5V`Xx5VQFr3c`j~nc~DCM0u%!j000080000X0D>*}(?b9N0D%Ai02=@R00000000000Du8@egptyZ(m_>aBO*Ba%E?AY+-U~dSP^FZ*DGbaCuNm0Rj{Q6aWAK2mk;8ApjH||D;0z004mi000XB0000000000004ji27d$qc4cy6Z*yfXZg6=}O9ci10000L02Khy1pokse*^#k00', } mrcal-2.4.1/doc/data/figueroa-overpass-looking-S/pinhole-narrow-yawed-left.cameramodel000066400000000000000000000004611456301662300310000ustar00rootroot00000000000000{ 'lensmodel': 'LENSMODEL_PINHOLE', # intrinsics are fx,fy,cx,cy,distortion0,distortion1,.... 'intrinsics': [ 2405.678127, 2453.362582, 1508.569804, 978.395964,], # extrinsics are rt_fromref 'extrinsics': [ -0, 0.7853981634, -0, -0, -0, -0,], 'imagersize': [ 3008, 2008,], } mrcal-2.4.1/doc/data/figueroa-overpass-looking-S/pinhole-narrow-yawed-right.cameramodel000066400000000000000000000005451456301662300311660ustar00rootroot00000000000000{ 'lensmodel': 'LENSMODEL_PINHOLE', # intrinsics are fx,fy,cx,cy,distortion0,distortion1,.... 'intrinsics': [ 2405.678127, 2453.362582, 1508.569804, 978.395964,], # extrinsics are rt_fromref 'extrinsics': [ 0.00462998711, 0.7619323943, 0.01943962341, -1.560523279, -0.1269510497, 1.441376183,], 'imagersize': [ 3008, 2008,], } mrcal-2.4.1/doc/data/figueroa-overpass-looking-S/splined-0.cameramodel000066400000000000000000014112321456301662300255730ustar00rootroot00000000000000# generated on 2020-11-14 21:49:57 with /home/dima/jpl/deltapose-lite/calibrate-extrinsics --skip-outlier-rejection --correspondences /proc/self/fd/15 --regularization t --seedrt01 0 0 0 2.1335999999999999 0 0 --cam0pose identity --observed-pixel-uncertainty 1 data/board/splined.cameramodel data/board/splined.cameramodel # # # Npoints_all Npoints_ranged Noutliers rms_err rms_err_reprojectiononly expected_err_yaw__rad range_uncertainty_1000m rms_err_optimization_range rms_err_range # # 81 0 0 0.6134012329940268 0.6244081560660618 0.0006823949868365514 320.65554441161197 - - # # ## WARNING: the range uncertainty of target at 1000m is 320.7. This is almost certainly too high. This solve is not reliable { 'lensmodel': 'LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=30_Ny=20_fov_x_deg=170', # intrinsics are fx,fy,cx,cy,distortion0,distortion1,.... 'intrinsics': [ 2018.95821, 2058.977247, 3017.639608, 1957.291928, 0, 0, 0, 0, 0.09635712204, 0.09404657554, 0.9993324525, 0.1688631115, -1.963361845, -1.066081999, 1.784866335, 2.100520933, -4.549558728, -4.092381993, 2.990260121, 1.938631768, 0.1447273961, 0.005455009208, -0.0007978624287, -0.002625856292, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.07723829595, 0.4587187292, 0.09307439919, 0.2087216263, 0.0154881859, 0.1478380322, 0.03075235416, 0.151714017, 0.009480677967, 0.1351917582, 0.00496267885, 0.1220434297, -0.008887385655, 0.1024226858, -0.001797970523, 0.09394620416, -0.006597483547, 0.08531003869, -0.04241255281, 0.118083759, -0.1176137079, 0.1078155468, -0.0180819227, 0.01439416381, -0.1477293971, 0.0339973354, -0.09735680289, -0.09143395577, 0.03251740719, 0.1769533334, -0.1697681405, -0.2235771083, -0.7566250127, -0.7780820157, -1.163561119, 1.985702533, 0.5740964308, 0.7102922499, -4.080781858, 0.7043775289, 0.3326100905, -0.3531402915, -1.125717216, 0.171029503, -2.496750201, 1.408250358, 3.105442379, -0.8080020431, 0.8603659039, -0.6047581604, 0.04889229266, -0.03452608696, 0, 0, 0, 0, 0, 0, 0, 0, 0.106593189, 0.1903878446, 0.07263001549, 0.1748426878, 0.05928309832, 0.1619530564, 0.03463152943, 0.139738303, 0.01916137052, 0.1211786499, 0.004683647399, 0.1039241118, -0.005558456744, 0.08778651161, -0.014553423, 0.07217904772, -0.01917654001, 0.05777051572, -0.02211753539, 0.04368435374, -0.02435235608, 0.03215140756, -0.02719262059, 0.02108783229, -0.02535368344, 0.01164959443, -0.02653544432, 0.003357642448, -0.02577260251, -0.005230223969, -0.02551334949, -0.008855714774, -0.0243616719, -0.01522561806, -0.02620799436, -0.01949767245, -0.02968823581, -0.01983689428, -0.0325320036, -0.01964896884, -0.04070553867, -0.01736705832, -0.05612424757, -0.01346427185, -0.0506212512, -0.01356880388, -0.07966185716, -0.03507321498, 0.04643416257, -0.08758243721, -2.100671273, 1.851595772, 0, 0, 0, 0, 0, 0, 0, 0, 0.09827416703, 0.1773525688, 0.07957781201, 0.1597715965, 0.05532496377, 0.1400412196, 0.03850040001, 0.1240284792, 0.02182844105, 0.107118291, 0.009687563553, 0.09076553411, -0.0003010313564, 0.07573083952, -0.007757921785, 0.06080888471, -0.01334597214, 0.04688629048, -0.01706628109, 0.03382090614, -0.01853185534, 0.02150966469, -0.01834242355, 0.01083091725, -0.01805147958, 0.001095512199, -0.01637589968, -0.006925901978, -0.01507621959, -0.01338518392, -0.01421108924, -0.01914560431, -0.014159713, -0.02256569629, -0.01559807699, -0.02481221384, -0.01821663737, -0.02676862396, -0.02298393245, -0.027084363, -0.02982696901, -0.02691692839, -0.03765443655, -0.02545254502, -0.04948579404, -0.02343948422, -0.06718716787, -0.01321733397, -0.09513894061, -0.00342374663, 0.09387289911, -0.3198367686, 0, 0, 0, 0, 0, 0, 0, 0, 0.1132572837, 0.1701937131, 0.08094499012, 0.1415663358, 0.06097210158, 0.1269068421, 0.04175911472, 0.110134056, 0.02663357797, 0.09457872459, 0.01417381178, 0.07965904596, 0.004194565642, 0.06465693851, -0.003140550503, 0.05082771968, -0.008133466028, 0.0374583639, -0.01077704414, 0.02482337778, -0.01189002328, 0.01350274965, -0.01149660227, 0.002895900193, -0.009724580792, -0.006167833175, -0.007752157128, -0.01404249264, -0.005467243246, -0.02074738914, -0.003859635652, -0.02585906383, -0.003036398428, -0.02979426898, -0.003738739727, -0.03269356745, -0.006319119467, -0.03404477647, -0.01049467585, -0.03451846534, -0.01670391117, -0.03484241742, -0.02661008585, -0.03254870516, -0.03584725172, -0.03234924212, -0.05140963261, -0.02912230792, -0.05784922481, -0.03107184578, 0.2644884108, -0.2091787285, 0, 0, 0, 0, 0, 0, 0, 0, 0.1105296827, 0.1417490727, 0.08570172594, 0.1288273687, 0.0647431508, 0.1127681705, 0.04599275932, 0.0980788072, 0.03118897802, 0.08354628364, 0.01910071761, 0.06965198446, 0.009465356827, 0.056075619, 0.002273127795, 0.04278518502, -0.002405203258, 0.0299993863, -0.004836185975, 0.0183457877, -0.00516430417, 0.007252685572, -0.003923633304, -0.002378393649, -0.001750099328, -0.01145296694, 0.0009802747206, -0.01865353304, 0.003903770067, -0.02536468569, 0.006128240639, -0.03042893342, 0.007166165129, -0.03438120349, 0.006870648246, -0.03736100301, 0.005134589989, -0.0393370068, 0.0003288587426, -0.04014524447, -0.00571262535, -0.04037164433, -0.01445008419, -0.03964290917, -0.02528956168, -0.03856936806, -0.03955851775, -0.03453276268, -0.05691583543, -0.03570582529, -0.212541744, 0.1013578834, 0, 0, 0, 0, 0, 0, 0, 0, 0.1164652846, 0.1320387297, 0.09122237299, 0.114655301, 0.06968748331, 0.1009247711, 0.05155281291, 0.08734352803, 0.0365215952, 0.07411704656, 0.02432238385, 0.06110126119, 0.01480676724, 0.04839022236, 0.007838108273, 0.03625820171, 0.003393853204, 0.02461644359, 0.001414761411, 0.01349448824, 0.0016270763, 0.003359195883, 0.003019620652, -0.006185620272, 0.005992668022, -0.0144179108, 0.00912279472, -0.02186300102, 0.01273030054, -0.02799984866, 0.01508844997, -0.03306641021, 0.01697186547, -0.0374062945, 0.01693833186, -0.04014181724, 0.01460058362, -0.04250522035, 0.01103474137, -0.04381690829, 0.003884235165, -0.04406628024, -0.004094080685, -0.04522547713, -0.01536424256, -0.04339119372, -0.02794036694, -0.04503614188, -0.04558254593, -0.03676298184, 1.539656475, -1.509084379, 0, 0, 0, 0, 0, 0, 0, 0, 0.1247157359, 0.1152430677, 0.09636120605, 0.102441971, 0.07570863658, 0.08953293763, 0.05740940168, 0.07743338994, 0.04238288641, 0.06544587188, 0.03037175965, 0.05378818894, 0.02083727099, 0.0423744212, 0.01380635848, 0.03105911011, 0.009615608243, 0.02043141044, 0.008027550717, 0.01060824776, 0.008167499016, 0.0007973446349, 0.01032635044, -0.00775989646, 0.01358299839, -0.01560284089, 0.01707279874, -0.02232471351, 0.02087908869, -0.02880856698, 0.02381612568, -0.03385261981, 0.02559686664, -0.0381843708, 0.02561724979, -0.04168166637, 0.02390020741, -0.04442552365, 0.0194223361, -0.04606394895, 0.01321207923, -0.04801276714, 0.0039097553, -0.04761373519, -0.006090641665, -0.04964001714, -0.02257809945, -0.045461033, -0.02416566986, -0.0614656529, -1.652782383, 1.622163435, 0, 0, 0, 0, 0, 0, -0.04176399001, -0.05595229424, 0.1297166391, 0.103095833, 0.1034664328, 0.0900097314, 0.08269306707, 0.07918724385, 0.06393344167, 0.06819097361, 0.0493067202, 0.05767939762, 0.03670966603, 0.04723907924, 0.02737744285, 0.03705617179, 0.02032296548, 0.02717578004, 0.01603270797, 0.01741271408, 0.01457799982, 0.008556913647, 0.01505174702, -5.452027213e-05, 0.01734310434, -0.008037579638, 0.02054035906, -0.01545773383, 0.02468779882, -0.0223178977, 0.02830628269, -0.02811714312, 0.03164142551, -0.03356087393, 0.03344256916, -0.03806697897, 0.03350017607, -0.04186707738, 0.03131120354, -0.04499317465, 0.0273319347, -0.04805056419, 0.02031076149, -0.04904189132, 0.01169646835, -0.05194236588, 8.563795727e-05, -0.05159258701, -0.01269033796, -0.05455194061, -0.02774582105, -0.04984835749, -0.03989658725, -0.4577700447, 0, 0, 0, 0, 0, 0, -4.041555366, 0.2089655323, 0.139790502, 0.08614597936, 0.1109481138, 0.07889523535, 0.09021593164, 0.06862139671, 0.07180126534, 0.05938315843, 0.05663537317, 0.05012427534, 0.04421377032, 0.04113223483, 0.03441570572, 0.0321885796, 0.02764984797, 0.02380324687, 0.02318141513, 0.01524342647, 0.0215031292, 0.007286966337, 0.02208882264, -0.0003253186382, 0.02403642202, -0.007722187619, 0.02761188427, -0.01474216203, 0.03143625855, -0.02074483069, 0.0352901756, -0.02707251429, 0.0383406546, -0.03205638419, 0.04027975895, -0.03732216533, 0.03989637503, -0.04125023651, 0.03793534151, -0.0453285531, 0.03331952794, -0.04823068246, 0.02650354318, -0.05151137411, 0.01725144836, -0.05358358004, 0.006372523857, -0.05576537491, -0.007438691174, -0.05659888786, -0.02666086875, -0.05925160112, 0.05265710692, -0.04506823323, 0, 0, 0, 0, 0, 0, 1.094257702, -0.08826978383, 0.1331776124, 0.0779771202, 0.1217843347, 0.06649939911, 0.09829627751, 0.05858120901, 0.08003562922, 0.05055822526, 0.06460014405, 0.04279127656, 0.05207013248, 0.03501053272, 0.04239662023, 0.02768530638, 0.03501936873, 0.02020217957, 0.03061755638, 0.01321800481, 0.02872727617, 0.006254551862, 0.02905709645, -0.0006240418048, 0.03070783056, -0.007073018871, 0.03401157222, -0.01340271146, 0.03795746166, -0.01961458009, 0.04135593782, -0.02504503816, 0.04413886202, -0.0308378852, 0.04593373633, -0.03560923925, 0.0451638797, -0.04056033608, 0.04283417719, -0.04502902195, 0.03816890152, -0.04912836393, 0.03076435309, -0.0526395351, 0.02165786089, -0.05600439163, 0.009168217285, -0.05886471568, -0.003948484817, -0.06082386259, -0.02113208612, -0.06436793999, -0.1079787793, 0.4093102867, 0, 0, 0, 0, 0, 0, -0.3703176641, 0.1586074174, 0.1638659289, 0.05884524289, 0.1286303381, 0.05488772167, 0.1081564315, 0.04756687464, 0.08928640494, 0.04137650319, 0.07359868226, 0.03487260044, 0.06077678301, 0.02881987638, 0.05081690433, 0.02230002318, 0.04347417823, 0.01658599988, 0.03858947035, 0.01068381329, 0.03611722237, 0.004928732149, 0.03622523798, -0.001042091003, 0.03751957518, -0.006674106487, 0.04040408138, -0.01274002686, 0.04362552329, -0.01824836763, 0.04675854008, -0.02405915171, 0.04898631808, -0.02954036089, 0.05006153404, -0.03497091054, 0.04942055066, -0.04035362206, 0.04654034119, -0.04516019089, 0.04114120242, -0.04994123513, 0.03380244281, -0.05450063305, 0.02405020308, -0.05846558114, 0.01218393616, -0.06226221899, -0.001327810737, -0.06511681708, -0.0217587447, -0.06829481944, 0.5724201295, -0.7898476633, 0, 0, 0, 0, 0, 0, 0.05393333212, 0.1347798816, 0.155571798, 0.04895714235, 0.1409148516, 0.04185377852, 0.1179928015, 0.03645467331, 0.09866198363, 0.03164061198, 0.08328675609, 0.0263762775, 0.07016186045, 0.02142621108, 0.06005286451, 0.01659088684, 0.05194946562, 0.01192623276, 0.047042161, 0.007236507451, 0.04391585171, 0.002496664376, 0.04330544781, -0.002429866421, 0.04420011446, -0.007786536242, 0.04626325661, -0.01292878065, 0.0488575551, -0.01847768014, 0.05114126873, -0.0238069102, 0.05300460266, -0.02935658634, 0.05337547081, -0.03507907953, 0.05217184107, -0.04051013781, 0.04853226119, -0.04617643724, 0.04311091914, -0.05176840283, 0.03485289066, -0.05679029539, 0.02548022659, -0.06152761747, 0.01237756674, -0.0659787964, -0.00176037595, -0.0704146149, -0.01794948774, -0.07199698728, -0.7231995936, -0.5471051509, 0, 0, 0, 0, 0, 0, 0.9835229985, -0.2883370524, 0.1845343154, 0.03258271018, 0.1497463991, 0.02762858231, 0.1287970526, 0.02450706502, 0.1099534957, 0.02031308325, 0.09309481756, 0.01711571714, 0.08012349807, 0.01309109466, 0.0692040494, 0.00942366062, 0.06123839248, 0.005942740323, 0.05543303959, 0.00231639371, 0.05193221474, -0.001355387215, 0.05030759829, -0.00550089812, 0.05048200764, -0.009773523475, 0.05183424448, -0.01501939236, 0.05336504472, -0.01962225007, 0.05507225517, -0.02496794799, 0.05588151203, -0.03065696973, 0.05538221882, -0.03675715686, 0.05356398903, -0.04238645716, 0.04955630041, -0.04860268069, 0.04313218856, -0.05455162281, 0.03514290816, -0.06046165391, 0.02427088789, -0.06582678766, 0.01186981146, -0.07129430164, -0.00255848772, -0.0760949994, -0.02121650241, -0.07777880419, -0.09286296169, -0.5047771216, 0, 0, 0, 0, 0, 0, -0.2895879657, -0.04155432655, 0.1630786491, 0.02425667487, 0.165816294, 0.01230749664, 0.1401451585, 0.0104860352, 0.1207596027, 0.008282723379, 0.104565003, 0.005575895091, 0.09040442793, 0.003219816942, 0.07925214253, 0.000761653618, 0.07027124317, -0.001858808035, 0.06411061168, -0.004586671982, 0.05968831608, -0.007428635128, 0.05736995892, -0.01077583517, 0.05667967723, -0.014834825, 0.05681532988, -0.01869153717, 0.05742542189, -0.02380660716, 0.05807747988, -0.02874613225, 0.05789123837, -0.03427920561, 0.05671803738, -0.04030290256, 0.05366960261, -0.04617026504, 0.0492700324, -0.05256055269, 0.04218829224, -0.05911931312, 0.03337218582, -0.06539162161, 0.02321303526, -0.07115942102, 0.008424071587, -0.07758569428, -0.001042735336, -0.08034334445, -0.04650619228, -0.1011959189, -0.6533085765, -0.4534200701, 0, 0, 0, 0, 0, 0, 1.015581028, 0.5963993192, 0.2179286789, -0.007147345449, 0.1714407747, -0.00216547566, 0.1515193288, -0.003840335482, 0.1325437832, -0.006049669303, 0.1152979029, -0.006578448087, 0.1008805788, -0.008678514236, 0.08926792682, -0.0105246236, 0.08010672948, -0.01164608859, 0.07279585359, -0.01354178178, 0.06751685342, -0.01520046945, 0.06417025009, -0.01816628376, 0.06233602388, -0.02110883617, 0.06126543439, -0.02504178724, 0.0609725437, -0.02931545183, 0.06026395762, -0.03422195275, 0.05937655826, -0.03987272985, 0.05664568331, -0.04588675767, 0.05326608732, -0.05196763947, 0.04752199379, -0.05889017316, 0.04031891551, -0.06557295336, 0.03071674604, -0.07224841007, 0.01788847431, -0.07938106926, 0.006499789995, -0.08519995448, -0.01400775887, -0.09304281732, -0.0166711407, -0.09117684746, -7.484022921, -3.550389987, 0, 0, 0, 0, 0, 0, -8.843765872, 5.110548726, 0.278930404, -0.07119881069, 0.1751380606, -0.01172864124, 0.1691557237, -0.02481669518, 0.1460413727, -0.02166590648, 0.1273182723, -0.02336960853, 0.1127784768, -0.0218546998, 0.09934493716, -0.02265670327, 0.08879651644, -0.02242884298, 0.08110841279, -0.02462318631, 0.07534178037, -0.02641392389, 0.07062476711, -0.02795267476, 0.06793038093, -0.03098653122, 0.06572764462, -0.03402873429, 0.06374426041, -0.03804590365, 0.06214877666, -0.0427306082, 0.05897708398, -0.04815287957, 0.05667585052, -0.05384964734, 0.05116881826, -0.06043054304, 0.04519913627, -0.06718197033, 0.03669632579, -0.07414775932, 0.02716635728, -0.08083366947, 0.01566406042, -0.08759963632, -0.0008795191043, -0.09581608729, -0.01357702772, -0.1004239753, -0.0199494411, -0.1054453066, -4.396176392, -1.614527433, 0, 0, 0, 0, 0, 0, -1.339168334, 1.681459361, 0.09189498919, 0.06795067211, 0.2076090049, -0.05267875536, 0.1636307711, -0.02811851623, 0.1539159328, -0.04060859516, 0.1322212428, -0.03086413121, 0.1217569478, -0.03994607641, 0.1090713428, -0.03721418756, 0.09936029685, -0.04071430764, 0.09137270205, -0.03868925185, 0.08322093749, -0.03940230845, 0.07817038905, -0.04135410766, 0.07305088459, -0.04289820628, 0.06856097427, -0.04569961066, 0.06643813619, -0.04929738404, 0.06261795988, -0.05340363653, 0.06072796984, -0.05974493017, 0.05317946756, -0.06507894152, 0.0497203459, -0.07181334054, 0.0412292748, -0.0780710943, 0.03306471027, -0.08493315045, 0.02022729566, -0.0933410947, 0.006003119189, -0.1007565762, -0.002253881741, -0.1057750289, -0.0389249297, -0.1230398762, 0.007810154328, -0.08876671615, -5.877077423, -4.718382118, 0, 0, 0, 0, 0, 0, 0.2255763283, -0.04592560109, 1.865619955, -1.322007172, 0.09135394107, 0.07351293836, 0.2969998089, -0.1577147299, 0.151884313, -0.03075073955, 0.2050022496, -0.124382265, 0.1238422425, -0.03492443832, 0.1348652704, -0.07183956498, 0.0881407338, -0.02511851946, 0.08485749938, -0.05471932051, 0.07473529438, -0.0476523671, 0.07631740821, -0.05108694733, 0.07737988982, -0.05750576856, 0.08226959459, -0.0604626097, 0.06568113136, -0.06578445548, 0.06910464046, -0.06949748036, 0.04534324753, -0.0669851157, 0.06409184906, -0.07843071212, 0.04095703505, -0.08280518579, 0.03739912613, -0.09135442899, 0.02258708894, -0.1026198969, 0.0231945809, -0.09942749479, 0.00519668435, -0.114831579, -0.02155458705, -0.1203485509, -0.01550444873, -0.1335065117, -0.07000316347, -0.1165860665, 1.088586321, 0.3936259735, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.0004364328199, 0.005438202047, 0.4443877762, 1.387962343, -0.5581952769, -0.05789343172, 1.052411399, 0.6532268064, -0.989443637, -0.9260812409, 0.3777867216, 0.2422021111, 0.7174813992, 0.1808502179, -1.292215705, -0.4620976877, 6.878633109, 4.200690837, 0.1713457284, 0.1008723368, 0, 0, 0, 0,], 'valid_intrinsics_region': [ [ 207, 211 ], [ 207, 3381 ], [ 415, 3381 ], [ 622, 3592 ], [ 622, 3804 ], [ 5393, 3804 ], [ 5600, 3592 ], [ 5808, 3592 ], [ 5808, 211 ], [ 207, 211 ], ], # extrinsics are rt_fromref 'extrinsics': [ 0, 0, 0, 0, 0, 0,], 'imagersize': [ 6016, 4016,], 'icam_intrinsics': 0, # The optimization inputs contain all the data used to compute this model. # This contains ALL the observations for ALL the cameras in the solve. The uses of # this are to be able to compute projection uncertainties, to visualize the # calibration-time geometry and to re-run the original optimization for # diagnostics. This is a big chunk of data that isn't useful for humans to # interpret, so it's stored in binary, compressed, and encoded to ascii in # base-85. Modifying the intrinsics of the model invalidates the optimization # inputs: the optimum implied by the inputs would no longer match the stored # parameters. Modifying the extrinsics is OK, however: if we move the camera # elsewhere, the original solve can still be used to represent the camera-relative # projection uncertainties 'optimization_inputs': b'P)h>@6aWAK2mk;8Apq(J8FQH)001B+000gE6aZ;%baH8Kb7^C9E^csn0RRvHASM6+00000nH~TD00000?V0yK)?fVp6%|n;87(T5QbJUcCmKc?Br}_gh^&n4L}p~~i;IiPyzKq7D=K?uBqNelh)N&dzu(dN93iJq0w=JimSTrOPyciPD?zI?9RKT%SUw@UrTz9h->HhE4muSk+{*{A1Eh9^i;{VxiAI1V4lrLfW^UTnFy6b9a$*yX!E4-$VWt#8FQLcW{q!8y~v$mE#zH*@zQ8q5=^+Jb(AsH)7@q4!jhCe7cxQHZ%lI5bH=T6<5;TzRtFuGt-uHy<`uC)50ev&_+k7SHP-T|#f{kE%V4_K!UK!7Yz3&K7)Z_cX%)?fd?}{+qVRalHE6SO6q`>i4OdLvZv(yh2%L2`DydPZ^Xn!$6!J=e5#c5UtEt(44J@PdRPw|K`y&v&Ah;YmzTV9vlfp0dAnSF*A{l?TKy82KrmbwDGCtwM5n<*Z=DO}VA}JCN8C;elPQ*UgAApx9)7}OWt%fnt)E^R?I{A@vrdOON>XtqT&ki{tQwlVUx&>dsK!gDd`sR%SHR$9A9I0>J@h{Y+b^-vrKk3#v386`pzk}HR_u8^wd6rzANB{wc@pd;&Hw)FOVZF{T_8MrMcY8|-nKpnLVSV=?SHO3@bh5Qr@MA2{B1+Fa-EU>kMHE7XiI>SYhh2HWGYS?j40c-KfdyG1Jvo+lQ5@0gFmwM*;gdF_*+yXM)bUSBM(79Mn9hzf^GbKT>2R-#dzfy7=t=mV#dMV=qvkHzLCftOD`9)eUWVee7H7#zvb50W#tL)G1dlc%_1Q1@ZM%;Hf`q`M`@b#*BUM|aW=#hwX9=jO`tt35I3XwH=;wE7BNB;8*}K1e|EZn72UoiOarXPcr;Pr_misrA9bVR#{;OiZ(vh!a#hgEHTQpv#tIP^`?t=2OD!$6xv5gP|tn9bYprl;hrxmAC$Q-$g>8)UXggUP<|IXqkY5hg80wZz4hYJ)!&B%^KY&v${^v7)@hf5CYVp%#Vx8+2-4Xz@kga`sVtBR|Sm`=<-7QW5sp%~d$~6cH)H$C7H6oyBvA=M?c?Eo6Wp8Be^@0mKlYW|rm%y#0w5})R!gwQ=p2TiY0I$iZ*BYDL(BP0%gzC{;0E>m)NALL~zmZ#?)0T8l;tHzla1255{@5F9cLhvz{iNW}%e~W}wGSE3a^@KN76drY{NIES{!8=c6UgR9oa0B?u|bseXCW2qKr%!&^%Wf!X@FTi@Y25N+}ouRNa%%`8`HoF!`D*B^Ra8@*Imn@#Gg7OaH74#s@l*J6Rmb35g>Xesb?s1t9!L4-WG2kUVbIrg!F#PT5HBZ^$^fl{2L()VsV4b@XkeY5`Nejd@58U8R?FXK4y8DgjpB-wrMGm@wM4~s>>bm*!cDCC)0#%q3(YingM!E?WX4c>@Nqq(*3L(l~8HjV%*JL2fIa&X$LG6L3n4v4KtS-VAfIT-0~_9RG$g{&>60TwgWOV_X9{^psaq6a-a;e782p!-~zq8K@m)-cG?{aeg&&U6@%g~3XESlmKUn;1-b)9{)ID+Wa*P8dab*S+h*nO98&U^10`F%AoPww8jx5G8_&x5a+pH40^&#ddvCAaFTmh!M(M7=)3+QV09`Ae&q2UBFpANa%W`v*1JJ~q2J77nl|%SIC!7ME_dMR=hm`(nGE_Rv3o4uKZN%-kuP_NM1$;w2)BjPs^EUpCh%|aCaWSh=AHWf#74yp=m@OJ>_U29^;d;+nmq2~3^98Y*~#gb3TAOihH=Bd?~{h;>A0lJOMIPAY7>PVRk0+z?4aV&F5xUW7Yj#)1RKH0Ia&hVxnea~|dS+x+jrTt{|$)_>wY9(ZUY)N-7JOL;HK<(>rN)(^9T+UL`7a(+(sL0lXLivK;azMF(BA&gd0DkLln(_M?|NJfXhlbw%}e?sF9*9;M!pZ}TPZlS%s+TRdjuVnRvxL1L!LP!HwW-0j5sq9U;SPrL&yu3uc0w^}6w>W%9fp0Kck|qn6(%0^3gqHg$>@*os9~|NI&Tt`)ioXyp$2HaOi><_-F%Z}M@LyTic?Z-D!k)Oz2z;kTxiGsf-yz{$Qep!XvfyG&NNe4Rs}#;2H1{$m6R1>c;#s}~N6LPyVSxW(i7o1w>~45C2!@}$L)djuR((27S(7R?zuO;ClO10K?!cDopsgYnk8l%}WUka8unaCB!0PzB^#>zpbAN=~?I{Ix-YP2-^&9SJ8tMgyFc|jN=DVaOc2ZVFe2!@Qiy))f`U6tn1P}(&i~J#eZwyrpRXA)mHpY<%L;_y`+Ek*L!xq7K`U1sM|G*^+y$>Gh@e_75Z9u5W)86)=B}4Hj!DSPa`xO)OxdjI|VlMMLsR^l|g`HiJ<02HncL+?L6;N2%Y8(z71m;ps%?#H2FmyxN+C5SAI!_YNLA8D70aIr-e$KLO;V%r8@cqcc61u(e$ITn`YI8>c_lqcdPV}LLh5%qmy&Tuv6pfw=VpK0_M7f*0}H6Y8xd{<(B78Lg>wH?c=fQ8gAcDWkqAm7S=({ZpEW?)T=yoK3Gn$G|419F32T9?k`aAM_`eJ>!8}#qfR>4H*nsSTDABN5I!kD@~A2gEB+uxUaun!q~TKb$@G9fKl6>$LNzcjD)=T^ur|?=7|^WdC%HHkxq~7p@3x26v(3VF)N}>R2FT6NDACoc51(+;*4*-Z&UT<65*FbsNG{WKkVdqMcSv51}Vnm3kA8M$nG>FS-C)hsiuRfE6Gu~rBZ;Uk|hH?=qQX`kbvicwyKf|88G>se`nDY0m%=@9%(l-pyS-$VX+J%#w=AAAMGLm!DBQ~oRfqDoPF7Lds5-!xajMNkPNiPj)uTn1fWvqcHme+Ix8L>DwvS%sf2Z<(M)n6M>WRf9D&VDJYo!o#v|I7?@YxjeT@|`k(oI=5paKZ+s^FqWK#6M6wok`RaBxP1nOBTkQVnJsGfLN2rY(T^*b-n64kRNCoPq(2}Ne)zD^fdr*L!45B9)O{b;GpxjfpUTE_i>z0a|kWnfEjcs(>^tZ-BoBGZ?t`!Ol`x@ugEQEuY*2Ox&9Oy6(3laYF5`3V>X6x-$AhO2!9&1C~k>)H)Vh-ks_5wgfyT!!fDbp?uNrGatiIaBq(Nl_R`qN538x7JO`;W!1x4(v+ZjrzU5K8cvgT6?B!$mJ-SiYI6ijo;jv8Ek@h?t!Nb{G27p{_E7(~3yK(>yW8$;@dGO?zI$z=Mp6y$8OF_YvTB-|+r~z1dj9mdWVC76Tqm1gQY`T(q*QA2U&Z0aQ}8&whW-!_ny^*}&fWsIYYM9A$exIyR_OsOyEIV1M%#qeuBjl+$sv;hsX94CRb5k5B*XFT>oKi`yLMAtWnG@{nx@KAxVY?MQeH7T50F%gIRs^-kyB&nN4FIdq_rEFTBy`trXYKCJ;!=W{po*rTD(=p5!J3lgZm%y~8&b>F!LtylG@1-@*LNGK+`Q_f~2N5g_vYI6n;Oe-qSgha$(XS>QQ#5iRnAt?cOw|F@+HagF)ysmtQEJ9rYx)p>sBLvHf(+$31q)N>R8a4E_t;Er1}I!IVL#|=k19#|Y_Iz=V0T8qA#R#yNG>fT(D;#oYmBY*XD~Rpyzn${O#QU66_s(Wkr~>tw+A5pFe`v2^6f31l_jmj-*3+Dp!E_9JIy8zspN0tm61*>?TN!O_;?;wJ-9kp4hOeEUEi#xw($@NHk<8l9O?mCVNn{q@N&mJM;w@8-)ZP6e0}Hlg#nEF8rzE4{ltU4SfioK}Y#OHivKS^eno(SP>Wu;R%|tZxSnsUGNzy`G8>wy1op8)<;U+6N}8dZHj&r|0vNi;ZxY+f_X4+zVhhCHn6ALM?1O`_f+E=nXURd$4+UJRsOOArwbA>kM_8a~9!PBq(06=mjVv_`{!fB)fHz^Y&s(@+(J8WilukC#r^p^6GCjwWzD&A@w`GH|L8nKlUJ&kl?#wyKnhj3TTAd@uUf~s$In$vB*`jsoQA$K-JCdo1$zkg*&{F;&tHanQF(+3jJ)91Di&(3VHR~V%VPbT7izqK9VPMI)~(?vr_A>m#2jPGABX23c5dYALlWNf9IJyRH+3OlB{evVzuL8c1BsuQdPa1ax}?@^V9%X-HwPBcaW-3#V*_w)H^sa=FAk{%GR7WSR=u>e&V8vO$HDI#6eAW<)*5VNT}hSFO}=&iukyf#&ah6V}-Q&Z#UCU`Wyo95s9^Vo>dcsneBG?;8J-1ix7o_{ROI?)1_&9~-#ue+f09dX;n#YW)#_+(tUN)LCO-H`lkSP$uEI{2Pd!2$A>VyY!4JhQb_`gUg-gcJwa?`-lw!UtLTD+9&At0&AfALxzJ95<#$JPKj#(PY3>zYjXRwywkEe4vpXJkwI)kFI@M-EU+mP?2NcXnrIZJFI+o>@D)(-VZ18nV3+V#-0(6nOxv3-=GeP565S#M+eSm=Yr$+?(slkG}g{vV{SR03(*!q_{LkTFBezxsQ~d4E{kyLzJrv}8;_3C~5MCNXn}VWbjtm&5n6=tZD!2e(7!qcUJE)Jaejj>H2lY%1Cn#UQV2#vid7fyu7w_r2>2VR$Huu|qT(9mMo>^lC6fphJ_+_p<5u-v_$DeoR0o~d6{i5asRC)L2qQ7DuOh^pm);Ogg>Fo2#mG)e)UVbX~b~F`79S3XvdWpv%zV?ofldCrSchzDKA6)x|538FSfx6PRsqf-R+#6r6QvT-U28vB$YtGr>`wGaMCI#gMvUsQ%4Q*D)#EW&Ut&^XtAqZ~zrqp#$KGu5>6$CvEyUi)W$Sr_g$U9wolXG4;6Qd8@|Qz5qR(en}z8L-}e-iQK*Me@OOq0OL2{k6F0CmA!(o-!I(YyfFPj~tGc&Hr1}Vg9V39?nh3sHHU%amSZ_{-oI&=%$H#(-)J7**47a_NNdY{tcRHwIO1PqPP>sYz3t6-Tkd{R|-0oJ>|=`EQ8pf$R{3sMAWfl3Kljj0eROq!+Tp(kVn6lxO%e))Y#Nn{P>Buk?icgwzUv?mFFY1_*0Q$DB)mVkPi%s%u6*ZsYu6o{kmu%1sLotoED5oXe`IO!n&0L5n9~0hXh8pl^p!=cdib*NUWn5r5p_EUJ-seB!z}-0u4lc7*BNbhaTOxC#dhVzenR?clh%koBifu_9-8ywmg{HKTadrn}@$WTAX_GDDe5@jmr_u6rAIDJR^3V1i!d0*Us}$aA_r@Mad)&vNS^e(y|oddc81%(oZ57pPYVLDpZ83xpJ24JSlMO?(lCagA$zSm-@tXBocT==uRtKE5~gCA!~{?k+ACWD2T;l@e9{{Q^G@c+8Rn-4^T@31QY-O00;m803iTcY7!NLpl*|9p{}E#o|a!!Qk0k%pI?-c3KDlq%qdOmP&;}WfUz+!$?bVq|6es%F4(NB@!u;l95CqRI*1I6_Rnx?D5)o*}Uv6JNf$j3*Y;<`&{R`ulwBhc|Nbl3A?7Nu6dK0=>gLt(c6~yEu2MVghgeo&Waur7PWG6c5yayyyfJ4+wy;LC9^yCE!X4sZOrakuI~>^o;`g``1Fxu!jFajpNoAZ?M_SpQ#Uk5-#nM1JO_DSb>c#2nqile;iib~6lm^PeQ)90hi02<-?q3jz$Pf@Bb!JkNDbWF{nlg-b{SkMzmr!38BsDnQmV;d{cH8}Qd1B5z3^%`wHW|<+y%+u19V8TVrZOpnuBoX91G6OQph>JQ7pcm44cimc%QR$p^I37%UI?h{ML4uz~7c}I~&VvU*N%m^rFQh+El#Zm+;0MtSy!8l}^oZZJfi?m+-qxlTN)sUX-^dx(Tk}BradM{YX9YG-ONRP#v_i9JxmOcg9on*Q7pe&!g^rYf%7mUe*xhzT$1!>y>ZC*)|B@S#6e-2!D?|sSu;r6UttF@$XEaUvI|>Kug=~i+s$pQ^dQ-9HJaidvuz!$2L|=iX64!@qkn*o2q`CVC3XfMT3O^cyFqN<44>Ho=SfACm1gk$F@u9<&yQLcs-B6%N%u(UEkVgMHaJWW9Xgx7HI6Wv;A&Zemkl%IWemE4l~2*XV5ccQO>(;jJpD{JYp36OYN{g%VK2Yt7_{eJphA`S-(7f(79AyHN8@QKxNIC|%=ewbkz9Nw^dwAx|>hF6Z=>JjR}vwqxLqs?kD@lCow^RLlCueYH24)UTzDY&f-J{+!@!6Xwk9*epvcsI8ES6r_Jau2$z2zU`-XW#jVhZV|bn&!>SvP8f_F$7k`Nsp$Q1#Uew2pLoVY`u_a+GQ8vYU-`aI&2Uq1@AcQZQ~2*okL*KHB38Mo-dZvzgV__`g6Mre&{|bUBtfSFeLnwEyCy>bhs+IO)y`8`@k}|$?gI&{3dk&}Y$TvrzLbqyNW`-K8(g%3ay)nH&$8Mt0whoW{#9r)g_(0V2d85x=q2VF@6twug2uf4mxtcLm6P<3pA^e+^I1h|;}QWPQzqO@uS}tNB3zc`3~;(Og(fU6--nL2A#>jH7KwZU7&bg9v}pPP)S`CRp*xW`DJ1bLxd;8T0wdy2L$aa)tIXH#K;*B6X9K+6RUyGIQwKY%Qe$@CEl0ybp3{$NiBLpK+sU(g3b}8)dS1%y#{!P5WS*8|{OvOP7hj0*!ie0I%{zrzQg0TfPxoN^UtgOx^IBm2b&Ku$d^23OxaP>;R)MO?k-yZgli+;le6}^$6bgpuD8A|HL5Z0&ha9x4pnWyl_48jMbYzLxCF)n8Z&X_c?Klbc@@{=z!a9W+60%tWI=vWf*{P~Yt%MID{UaCq$?&AJL{uCrFx#1;ye*dm{3)L-EZQegjhl32n6(dQ>xFMnwaVcnhv&(|VpM2kx?W9BsK6qTvA4bkWM~<346pw*iF*vFIZ1JS=pH>W)6Y@{$`60VHwM!{jh;}S9afJ2!d@k>FjGM|-^A5oX#(Y+9p}AK){li#z3)%mEd>qAsoL%#Do9pT`W|#E#hJ*^lLkj=@Xxe%)5bd!Xj*gl=;pHwd}i%Wyz-&~k|MrmE^VfPw!PfdBf5D=68p#K9#}vBWa3lStZ@wC+*o`}jDe=fUAy)E)`D-dyN87l4N|{7Q1cc^#L6dgLLr~2uuye}KP7z(Q$h(W&gU2?eMpg~@k=w@YGpNkb${K57qlDf`CfsUX8d60G6nQP%=61%k7CN#X#cp?eth51WwdHXhJY_RhH+gqaJ1QbpTqq-e0;*M_Fk6?wSG2sMZbnI=qbBani2!Qvz>gT$yl#T;X8AmWD6KDq!is=lz@X9jYn!`-8YA>FYt~H;;8_q=Gl)7oGh{-Y6P@FY-!Xa$6p%kxX`q_&8r&T7z~HnouGo%^@on8ngi&h!B_b~oPn06Q!+-oJ7Hk*cj%638l2=F_g;9{2<-7J@6UKrV58+;E)QM??s}rrB0}v)mNwp(!Z*8NFg$5ncWeuAk#8Q8zCeOa9KS2Q-jG3+TU?L-VIR8iM`zs4>c@6ESEBv5WI*CZPKtX=lsf?#&C@Y@G&syomI=+atadrl3NWLp_Ug!m}-gbq4eJk~P=+cHI43SxzFFfsF0{dO|DvfK`9#Q)vVpB1_DI-`(wo=94bG>=G0(w@5Kx+0lZ=ixqw0-3)Z@)nmGC)(_stCqBg;q{CUuK~A~ry`a%MCRboW0jrnZaZlELP+vJPVMiPT+bG{UrR5l~JRjk2DoBU07kM$7H~V35YO{vHKQfTz$+GI)ji_?T?$=i<25wxoD_Pz&0AEf!5*K#0!Ap5H9LNk#FW&)Q6h$2<^+X~AEKz($yq(!O&esLRW^uHVdCVoYwzp2d-@=b}|r}8s~=vcT_5A>tXg5`AJ$^d8_JW!W+rvrHR@FWBWj)A`YjPrzjGc3QHY`&bG05U5XYRNVIxGzSt_~*X?DA}zdza_f^9_5MLP)(iyn@4sWd#^Xc+%jv=DX(G}uh&!fnct5-p5jBs#P$2w?)H-T+X2lXJ6g20r{K$*nHyrd%|Q0>AZpiFgJ=rR2f3Vn3_W*kjL%~L#M;C~l0!PdGQJhJ@1KTpZ9N6rgJzJB8=f6H-wfxsa{XuB){ikJAwy`mAe`wYYH9ZC-9T0WtrFDTko7Np8#x%ree~$B}5n!qJ0b9Nc8N6@pr0jgjz@j1+&z{D9AaUtik4zMRsb0YHb4f2`f70=s(j5cAt9PI88KGh^kDi~?X98wr$M9dEH-Z1V7@gr81#sN^iqF4euP|03=p>$r1l`i6NUa$vrkE7=AqZ{RUr2o0?zB3kJi|7r|=>X}Gw7?PI!?Yl{{*fY)f|!IFECjB&!wo+mq234u6!gy!w{C_L5l_gniaKD6EtbCGci{t%wQPWKhJNQqA%i@;@YO<+8R`~V0t|u*@4zhd;RzXKJvUFpKF@*(r%k7i(1u`lu)+3AAq#jojDO@-c_TiOi4oHkXh)Mm_K(@oWZYr9B_`Z62P}SiQ%+3{!Nc7f^i7K9aglGAV5M0z=EchgODwiwYEHaq>>3$sZpGi@Ny~@akk%Ux`a@vjyZcP&+#L36HmuFC5OLOHl(pz;8(w%Xd8VSAj2>TD__-R2;kKDn0xk`Lo(yNU;Kn&L98mW9Y)Z!c4)+Q!g|wnmtWLa1H5m#1#zFf(m%@hBi25(#gHWS%?y=~RKlt#%{75;Of>ETVmA~IwP%X~4B%HGTJ`y>GI*H{_ah`bo%KHIu_r7w|oMRS0c5Ze!Za_mdwih>C`gdKvMBrMeZq_cheZuHElx$zkdRCp(NxQdfmKeNJcAKx>|HrJ+O+UelSgCzymdx=-JkBoIb=A>D1DSf_HOoPB{@!x%Nn+*Axk-WL{Z#-){sZ>W4SSDGVrJw=vnrGK%&SO{X}YwqWo)2h9N?6MFajC+GQidLf*7LVGr@CC{YzC>5Uv=br8Q}S%Bz9@NCJRleD&=0bEE6IAI-8gheTrpy)1ut41|FF3+1-S!94*RJSF!V#5$GuDIzRLL}SFf`d1V!^#(nqP-S^d>5`C=>P+%;F`ly`-OQcP8}Y(f?J=ZX;{O>k~dsbtZ!7i_IcWgTY-cuRN4Ai}&AGv8LRi47;gDi-MmcoatK!NaGH=e1rpmR^!~x7f3cwBz)zjz{W&RJGfKWZa4JO~-Du*|s5HyiATj2nF6P*cXSbcA~w;=WW?DOW3OY)x}t$0@7Fux1Ig33wKR-z3@6oN43Mv5{C|v!R}Q8K{&Vr$&P;y+Da{B(XH(#({gj5Zo|uthdSMu%%_-x>wJFABR!xrfB*%{30^vL?I@Mmo)YM|j2!7Z=DL;QLApdadTdJ%KEER``O<@qgj5H`5n>~J%oTol>qMbKVbeG0f_(SwJc?0)HenT|JIbvXuB>L80v&o!P(M|Zn@4x0v+ko$=LtaE4*9-WM}IFQkUKbb!zU$$vOfmaF^`TDh>CUQXQpI;l+cslQT=evXfz1!FR@#NsX`!nZ4cYf-QH66)j*OT0K!jOs!L{t@fkJShD1ah_W%{%|b+yj8gxx_55Z(Lx$(J#FGn<5)s}F$*rs`6@JW3L41B>_uC)o`l3_t@y(8lux}?CA1VU)3oQP7?^P;d0{=@`cTTzLt*t8n7G?LQ@9V+GNr_V_O@b4%|6Mtv*nPX_SJAN69MnKss;EOEnwh(&u0Gdwqnv{Hx-lX{irw~9Fr>7iUkk%y~-OcgnuqC7B^3I(U^|*$S?1n_GL2_#L&j%O6ofscZ93qvG*`I)Zz^h@Z?)~+OvHzy2A3yRy1?2z+T!}fE<7i`XJ_f*S^RC&Hlz5V6D*>FeBFJ?*eZNnKK~*CbJ<_&cD(Nf&Rxph$1Zi@B*C}M#%%^aQ-UR0w{*kjo~Q#0>-YHHnw`8`r5Q`|E_+J|_P|=o_e19eImZG$s#ihNcT=j4v`ZquW6t%U9CPNDqDUu>4UEd`wv7va0F8)W*PM;Y-taT5U8}Uabc_KJW?euCB+z(rYs|R!xZR=ePbO_kbJAa+rEnJ8svAeX-^_gBxSqUTJJ`9M{B_H;`z3knFSU`In^#txhyWY)!96G3}_{*G;`ps#D;Qx~_+`(pJ^qhsH3|#=I|CwI7O_>etLtvT;GEZej3nJka?mGEz~1EU)kOVo?e}58yskO&w+AgqsdVn=`)}ty*K&??E`F@x8!!%Sclf?o)c4SebD^gU+3~|D%R$;_i|(o;7p_0n$;-=q}~m^KqF4~gn*q8O7yVd{xLTch9CCQxr}do%q`gg(Y@xHZ-+B*#`qnb$uefNp0Y5UucJfkp{`>J-<=Xfb^szycDZBJT04Dx?#xvQiaIjcGxQ0(XHl6!k7pu|>&L-8D@^}|;Q~6&x^E{m6R{-mQDM{#66Qp{*fnfLK;}{1fpNKVur19B+qZulXipb<>F4G#;jvmnvlRvJyG00vY$0O!G0rP1R|qKR-YIu0q!QfCrWS2SMnOU}@rhH%EH)}$WbzB4;X5yuL)$kspx(X+v_C~axz$kRiNm$Pdgs*hy!a7V7Q1h(_j3|U&kCPW7i>dv;Cw1cuo%Y*dt^m!67U;~7}QKOKqY7WopYiCxNA}H(?Pu@C=0rmI?F`I%`+ZHk|+BiOPNJGR+0qO3!@X=W>a8R8~x8dkFm~A<6`@jmq5kk;$E>r8oIv{4z7snheSn*!{tl_Xi1feUrU;TdxJ}u(AtmJwvaf@s7rA0=}*TeWn|p*<=lYh;JR+aEtGPLY9VWuUFbpR6eJg)9JI~uLv!nhC`!OGgxzwSc#vF=`gFnlB9uYc=@T~f;z%*5_q}3$rZokP^{+>4W&4m@t6*%cei?WNn|=JwSK^l7cUp~RV0zSZ0F0QxaU9U!QLuIT2lj^RaVh<$=}SiFICe@dyp-L^22UjEUe1m^E+vM$$oORDW1)EjkLf(*DTVey&8Bt`Q{gk^8j%6YeH$5jmWME*w{!R9))C+@|5neIk%t|Q_5IyXW?>IQwqft4LAby3&C}Ph>+`gst^B?}BbdsT?6JIaJ>PmDoGZKtbJQY5`5sKc=wzh}x}2spR==g8*X4vw<>nH4I=aP=v7P{5~Ai1|0f`{@*-lFN3tM1=`Rc3=KgTss8&FDb3rh_^wHwM|dk+j0DDH}>g~{V4FbqDi%+oDC-`7rX{TgQ*6bTeuo(y9;C5}h80KQ6^r-1gR5`IGDZuP=Yqu>)_EzO-Ned80E70tp?nuK#SaU#+2S+VTXJ}y1l4`RcT5IM10zE5-I8%TPRcT~JQ|w^7jcUNL1l@M&>5bQ+tmuH#y+cmrpxg{`jXaBziII0T4{=wYDaM&^_Kp&dH5opF*qiW1oR-nowXnu^fc_CJkhGat3GY@0?E^$BAIofGlq_3Ha_BlY4fl+XYO0b1E??F0(|5cLt&zS*>MQ=(xk^vqP-tJn(C4rKa9XgtwVij~@Q31Caqo>AT}qsMZHp0x!-0d8WSRfX_Evd9$A_F>??!LvL|#r-wm&VpLyJcm=L48tQxLlCU*$lQWCS5HOz?lJNQOJJyn}k45+m0@WA)m~2$IQ(@*`$N+x+?&#sGiEtz8fR^K%YSi}k3H`iC!UKd&oAtT|VUbPb-@H>6dZ_TdxH8)df0R_i(KHnV9P<8-Hr8VX`EXvB0~t-WY}WAV9e`VO_N$JCDabxjNGfdYf{N$-;Vr`n&?R#%@A7IB&dwh(ZK0AeIjWeur-K3GBRMsiiHXRiwV}JCz76)@{AC}wkN~!F7RQeA{g0bvOLaF>(1kz48I0F`rrOV=q~;Sw_=|n0)1rZozU|H)(nrW9X7oqO6EX9sE<2kh1q;vXZk_k&hq-$`625}|xauoA%D+D^;}i|=?usc?zAgn$$qluBnHdmb{yc8Ekc68ngv2Tj(Qr}U*Z+NSCq!>|FHn?>htLVo++mjqS3eD#J8wyY&{l1Y{_*vHBJibElBvjg@JRXKN;|yiU3JQ+`~rMQRk5V+Y3S|6zV|{yI;dRAu~qp+!mG}2^yRf_n6+o4`6E6$j2=EXeqt>Fa#U$P8z|*C%IW&cF)|&D2A&@L5lO<|2mG1q-KdyUW!r70NQXnbDQlt*Ut#N#*pESj2Aq33_0pjs1=8Vb->x_^e!Ft-qv;40SM`;>CGWL?PSz1{iq3|Fwl?*4BqBc>vpD10TTsjB=eg)i#plN_U-4$5p<7O){BPqH=ruo^=h>bMaq>l)0jw?f;Pl*WdCw2PV_Zz+rcJ@w&kt%!&}HDvh+kWDfyfvH#ZRXke>~(xxIIM)2|PT?AOX5NOx9gs^%#*EcV=4;9>eIEcPMXj9T`AumQleGS24z6OGRsY*Oj51pteQrlxL!n=6B*)`ra9@jCN&si+m8+8Enb4t*P>pM^$M0jt9G7u$y>@$okGslM4XWYcGU;;Gw?R|URozi&;&{+=H(H)jh$dr~I;U2Y|Gj6Ype**=YhoqeyB-ltwxaMRT0_5J8?+l)XBQ!vd|(R0JcDR2kivLhC|~KR?~2RLQ9JVy)eztPphPFK|lHQo-eXTJdDz6xL=a_vjX-0NpJA#aZ(%d~SD9htrgdoUFq9BU}~m{wbGpc6S)uEay8>+&PKaqq#Ay@fA>!aU|(uMF$!L&-$gmp&(&Ssh_vD7S22Jol5)Yik6-2yNlSSkb7(0RGupVn4Jsb>S8)@==2Ylx5-p&uzW3E|E>Whq#T+>yMLgcfG)*dbrOTdZ&XH;sbH&6bj^?2fhTun8nEx9V0dc&&rv%9G#YFdub$b7%<>a=iyjj2nXje2@j9pX&5a)0_^$!KpGwR<{dxkw{k62Z-`N6t_G_nCGIwF`b%y)X6OFiiYh(K{RT8wjF7ZAK|BZdauYEgX$1p!N{fUn$2~I2q4vMXF0ty%(oj%ftwc{o-Q5VSYe^5&U1QY-O00;m803iT9UV3Xq0001l0000A02BalZ)t9Hb1rUhc>w?r0E7Sl0000007U=*000000GsR=>KhQr$WX>mt)7xvoLr=CrJ!yTYN)QGpq`drR8o|f7oT60k_r-cOUx-w1&SAEBo?Fs`5Kx!3bhIp0WJn0002-+0|XQR000O8001EX8}eu#aZm&RK+pyN7623gZ(?(0a&}>KX>V?GUt(`za%3)UaCrd$5CA~X1^@s60041N1ONa4005Mod0b83_x~kBqC`}vq-a7KBq~}6g(eD-G#XM;LMlljMWvE7D@EhI=Z+zzL{S+^gNUL*X`V!i-?{m`@4DYVe?1;=-aX&zan5V+bIx9`z4kum9cgS~WNOJb>C7Z=1qa7d_U;PWG77qf*D9=#Q8?`C?%{5G;*hJmgCmD;wRJw_Nb*xhZBIIqzbmS(U9&<)P4(YD8cHi<&ddCN{s=xbra7fIw2377(C=u13*G6%$7;zwlf8WbG6Nh#Q!W-QI5VKi;Gl;wQN6_DUusT*&LH)85DBRi!>46Uc%*{o&d|&E4GN+{vh0*(Q<;V#ZZtYQwv^@#i8NQ<^7JK*slvw}|3JZhW3^(TS6-6p&2Ly^O%PQSF>>eNCyJji}}*w5LAt0%!QE;Dc*1GE<>E_?COo6EoE47$c?GvSW~m>l^<*l9?z?8Pq!77~g<90YDFnQEa_~p_J>G=YAK+V3Vqf&HuFZ5AtnPecBi+ygDy)}mcL-SJ?WIg|nH|e>wF8fw+N!@Q>?ZE=UyO#C7^kD9Bj=phpa%yISQm2-vsACA17o@7~pT3p?QfIeMzZQC(%e{;4uUjHU1;e_X1;0Kc&j>u~!4M>%lHRj;`A$5}%N)a8S|S0djRnGEEyzPDRi75@puvH6kDIIMp|Yl6*_gEC@yh9UK{#Va{WvKT--w5tp1ApVOq_N$1w!F;`3j(&?AD&yVSy~^f%DJzclx3_wq@m(bvSmy^{KT(Q0uarHxmG^-Lfz+m&m&ea*TkjjdgqrpAhp~GTxP03Ns%K9$3l95#v0{8l;_?;xfrT55DZtP_5));LdbTp?=iig}bMGHd>LVf4Q$J%>(Yjw$xM%zGs%Izit4BSi_xlhq%cFZ{dk^+={_o~|d0`qnK9{*!ST2^!j|!Bo=%vv>?HqqaLm280)OZs6&4~{C7TGI|tw;Sw68g_utYyIZYPPMpHtJtpuu4U9ArpdSUKc+sxx?i)lr1xl3bCMg_Urp>=@c%{?GpK$Za{%s(>s(>ic#mojEile0#v9t?>iMEzlF9r({5At1N!vAN`X)c<$M_>Y8c0`&e=r5J0W{vXxfvyNP*!Pxbg(^D!Exja2fM~u3H4$EZZzs%i*`decs$FN%IFmz9Lew$4)moJKw%GgC=z?V0DhohpgU8iQxXk0{I_jlWu+>jf-i`UU=(!#V26wut__bzTO>ZI89$9WA=Kwb9-!(eVam!CV(!7?kLLgd=zDPlbOi(Zt+`j`+fZ^>z$$sJsi|yJGcF)WAD;+Kb*cPgLV7n?i&S~|K&wFXDM!==gdt83_(oXfviX5=Z^Y-g`iT>fzm~%^24h5upXdp4eWnFXu`ZQ}tm))~|(ZS)swD>f-D>r^^fU;(>3=?vUUz;`@cjEH%0-0NL&#}NO-KAJDa>T|t1f>oFaJ2lxNZR*%2vl(Ih!E25bsm}P5P@@FJC?rdjFr_YtlPa-yVNThY4z3s`B}1=mTF;nAacQU_nFfeg&0&jOUEEilVvT-~n^@^y2aJ?@gb2P?-XE7RAzc@4m+6Kcc30{F+6D_lD;!W0jB#9?8AcF@peOJCS{sGmu}7ZmNz;Az+Q%rG{m{(C5rB-CZ7QK?CQA#r->`WBlp%p~uDYbg*c6@H~F&f4oUAZrxJWPe}&MliSheS&H$8-fo)gPx?ut`i|*Q)a%^%HD`jpTV7&8F!jv5($(l^lFs}*K03sPfVk_*m-NuLv`vmK9oRtuqHR)9yx$FOydpW!2(F;Qtd2gBwp8TrYfb)IiWBhQOv=)sI^+)yMDV}PCP3LDrAtT}eaOfG9W&VjG$=fyYB&2lawEgqFE-2Qp#I`uKoB4LlWv3Igi9g}ShqYyKA4I8#SGD{<%^lHUu98(TqgPizXw@+Y33|oAGtNTFXts0<=66mSdDqK;cumhkX{neu-A*YlP@TnsT$>CP5i87(n|fq-j_b4GoZR4xUa$Z1OOu|+w=YwK&r*Q;s$~0$e$+D%)0MPpCl&5*xbgVXMbzV=L{a`mwztIjWu~Vx>Z#fEvc)umfM*pO!rXo!PkGR6^mH2yPV-Owyr2_xelI(6PMI990utRv+4-ixfy?Obw9tM?GhXnquvZsqjGNz^x~`=r{NeRp#U_B%pAKd4{Dp>YSywHpwf2%tsYxF25E>oxV-VCacwH@YXl=s_tgY2(_F7j!rymVAp2gCXsS&$podr>lks%Z@UjSF+61C>r$-uMlVrH(>(5_s-OK2IjkxLhaC11}s=IrDccTXbP8KjW0;l3!uRFv$n_g450q4RVRkN7*IiP?*ZDAO4P3=kS)1Tium_?+kg7s>d{x+{uviSK;{;GwFP6S|MrJn(}%@r5dS-?G+`I&U-E7I!ZSJz?!{W}c;j{yZ@#{RO$7@L+4rQaW(b?@%SS%h}7+RQ(MdA{fN|s4v*A*-Fz4CIvE}Zr+QofZ6Cb(o}ohVhzdpRucX4R?sxs3Iy^pnea`{SekvS2?S5t9d*n}lM5=9dAfQbB8O=Bl^>d!n%nt<2(QcpnV+ZQjm(UA2aF7P`A}YR5RYv{8mmV2tcG6&u#ZQeP8N4o=HvgTH7eI%{Q|HdRppNZguJ9fbDViz<|F$o_ByQzd?ou2@YB1hD*>V%+F9|`wh^*FLBzeDhu>=^WN&ezxkaGjrTL(7TWl5`Sm+$kt>9mP{guYtl!7x_^>g*+efE={@zZ3W0?wrtE7-mUBEYAxQ7b*Pe=a9`=PHWlv6fmkp60whV#wSH9=hds)GF4L<86QC4VleB3Hh@e%WF&A6f2n-e4SgmCI=(U$3!+7~rB+q!l8Db(@{X-@T`+GNE*CZOQEttn-}t>i)R)A`719_)DaJL>|(6ZO7$5Y-ldMopdsY^L^u>bu&73)00mwqkJwxfVrw7HA;1@sk5y#r!rY@)(bwerN(Jbp&pU-D*)3;}l}EY;7p;&Ei3MKR*o1dx}DvVH~njgmDPM?LIm6VLnCQ1m}FZ>QNPtfWIbz<6@Tne?fZ)jAQp$h+<4tmCd!pw~>C*YC}YX^nBE5b4obz;cFU*r3KhX)gnJulG0J_O^3O6?%jIM!0U440bf$IHUoCOQ@IyTV7uOZOuD8b$OPN#2J^PR!gg`|L`^#rtfY@`eLVy7vV!R|**&?GiTh#NbkteM&o7|hL4}-vo`^|TkRMi~{dyovfUH|s+BP2j>TQ%|x1-7VZ`Ovr-VgrcO?uMlyQPmUpuze>46Dzss6Rw7-uZ4i4bt+9#JB39{)Uw=`3ASr!CPf_%VXIL%bwMxz0gt73Zf{2aFtc*W$y6;GZ0h_{zSI-fiTa*pi|b9H!_fVZ@AG=Gj%2mBLg3Ue9nRe|M7&v^_~D*Emxs0<9A15Z9G6a;Yx2$Espkkfe(`?ChR(LHt~wVla5<+wxXGFV7LC8Q#EkR!gw=@xPj#rEGG(2j8WVYwNM^MJIsY}?U0%E25$h!D74luzlH--9&7?1vW@G%~ghvB4WInQIJ6JfJ#C4+A7K4(>>ZHGVMif7If_0d&NvUgEmoi|v^Rx$d7KCz-zwUuY#lwwE_)h8aw~Ywla_{#ur&a{B!0TE2!!6s8^V93{Tqos%X1{Qsz8&&odzZBSji-Qt8lMFt@&d@hYO8Q&h-~zyp-iH$FU6z&{g&8E9$`bKQ>Jd`7M|rlqqEFuo`{K@3ueRTW_);U%S*VI~#eQ+CI0kF*d9x|7D{Cu9tb4k2Nl+q5#X-Dm3sq`ig!P@%~{dnU8KfR5!>)UVNmp>A_wCE)=ZX7u${8<&?dbe<%!%Xj>9Zm>w2o8Y#OJk2*Lms~dmiPzzW1IA3A5kK4TwihPz0;@A0x-->q#Z+XQQv+_;a;i1W3kg`*SiD&&#Qs3?!1{@JI+X1bEhoK7ajUOSX6WjH1l%GcmtQR<7@KU(0~Tt38&1Q!qa+*werDvl^odNo88sjmdjA#W`0`ylN!{sp}ju)(J&Qc$;7e39`$HXbD*B`Am_xVVf$Rvla8j>LcgN>Zh_mp3lkY<+2nm@1EIynJUc&Ih9Ev%8Hm53~SDacCDj=(aWir7cHtvpS7M2zQy{NR>z|L{=vpegTKi8+(lyQMxMIOq`x3aEc`M*h{dH*`q4k&tWn3wfo$8jAQ023QmvS?bk>?Yh;y`E#Nj6HdyGvQGD6y9|!c(vH$+L4mW5OUQi8%Zhe$ip4CcAbeG1?=2V9Io*a|wq+Ip3P&T0pL|138KCCEJrzo!L(l$A8`6)Ue$G1I3^N9lrK?|O@YHP{Ebc3;5N5*mxJ++{li02uc4g(|6VUS-+xZ&?%ptryv@>Zxl4pZA{!*e)C0OIN%|Ke>CF@X?N@3@$&re1}KdZVK3nZ<)}sz2k)YRkU>j`sMU#0KwX)dh5`qaqgStf}|g&&vJ8?K%W*0k13r4beJyqI5JEH>o61d4LM#Z9a!3ZPwWbp8^=!DqOh3-%_in+uK&2i<~E9RvCas0uCB>wU_RXdPBk8mGxBlEA|P>}8d5%dq7I^*PeDmcEN4QG#FU4>;*YHxR(0H5kZRMkf0A4Qk4|C0HLasI`D*QLnc_XeG2XVO6K$BaAgnaJzUEsC=s@7sg-b&4A|TPes<<$9U7#vu$!tFkusO53@cGEU*cE%VqhXWeHwP=$WpoI_VwyoJEi77azUH0&ThN-u7YWqb89zay5B^m=kGpSa(i;|I5ECKo{KUGI1;l(ahfFh5V_&RvWx3z;LDeP^6U-dw_XPxarsPxS>F$|nMbzUH!nd`H(=nMlKm{i6-H2%=_=-Bq9!x_p<%@T7IhNO8yWU#s#gI4tzI8@Ugq&39{L44TnuS&wKjOo2pc(PeP6Jh1`^BKS3TpY+vtrSdG(iU@9Lc{8KQZ}Z|(2ZqBt>Naw79&i~;7s-;qBXl6Ns7L)<5}vm1Hfv-P*=7Az1?nry?&N#XKI>0e7++}SX@YIlo4Fy@i{{X&<|exSnRTQ_D;R>AXL-~N3{wFLnxp=CzQOUO%CwtbVYAYiue5BbCvYoBR_7?V1HVS1@1pnMU_~X?|wNvKRJH^8@|i+1?FaBzKeXZ;YIK$=_mcQQfWNvaT*!PLS1$Qyj>>gRsIP1;>Tx>9U|v_^doN^GgVNht4PlLE#@?M{GD%5m5w|uFu7(jy?ZnK$vmrgTg{~p`4M@E*Pm81pybJ$2m6Ts^pp80^_TsLUkq5vGF4v?i26C}7hP|eFqxbnDV@c99Y;}kWcQE-A5QLDn0^8CHD|x?;~50-pO-bUJBB(r`TaII4hI%j6^?vDE|5hFxcr^~`QRImLTpfHSw@2G74rJ}pO)0~8AR?Q|NC1<9Sy_+HJ&I(WB+UGJ$GwxrbBW39iufSsNXTGT>Zc5Sa30$Jum1L09Q8Mft*FU)NduYOLmR%7AWxLn_`KDe4ugxUTm!FSyQZ}4NYC!1!{4rL!HU+XfAL68ts&{3o3$=S*%_dZ`t)U>-oCx?ZjUu*zWT2p<8Bhd05ldGT&edc&8S*7%_SL#_dPT2lrATqVwL(=_|4RuwGGd%WPQ!ZaBT~eHf0uLM~~q?#gTeJgO_*<~O5%uvNEEl{Wg{{C5%Z4p#lX9MWHvT;^Y*q>cWeV6H(>Oa~q8H&rYf_QZOQ8{g5J>OBky7@D_E-w^lbl)r!bN?D2pqm0E$DXl?V&e;cM?8%0j4ye_z!F4q21bb-fq`-pq58^j$&~F&ki5?s&pu*KvqFX$9e2B`K-`UeF326SB-jMnL{lH(jcgc-yu(991Vr2`~TNJK7n%!H)U=9wcau|1nek{->ZPUa_^194y51seQVvpk{Ouy>x`7BOGuw=eU$QU-vIiJ7?D$kbAkwn*pQQAQja_-a}z(G1PxAi9EvC_M81COxweB(XwWa*ms-QKuSVNz?6d4eI>?Esb=?WQ&DGQA^iX530|V}aSZTF-V!VdtjL%n{m=N8zM{ukh1P9j!BaEQZ}6Gye=xL~%(JYykIGAt4^q4ey9fe;O>zhJv*T5Wo!u$nNH=NU0FuUfaLqY?t;~4C!D&E<}hFOc}?A{cR$mOp7uCafrsZbcz^->uR(g)XWPiq>4_*nNl?BrRGlX}@|KZ$%EnW33yD$s}Az9(>U;UhY$i`{mu?QtS>-{4xc%(fkrjB}T@E?PVtUYtFV629Lm05e^H9`s?tHvSZ(J?MsL_oHAxit2t)^kVNI$hjNz;u53yoAt6tnJf@@$-d+VsGqsp=_QKA1DRGsm9>iyR`tH^(Bs=g0i(B0&evx;k?%>ipIe^VX+`4nmDjAFYc)om#ut24xo*Af6Zp|Y3{OMpA+1>z^FK>^ZL!Ev@MzPip=x_*DH3ZE^o$2e&g-4P8IZFS>#xvZyN0Z*Srv|IOt1!W8o%fNQftasfmu#;HoX!G}@a%Cpg!%gVoS;pO{VZ5;@>ayuotUpJo0dQ7*i1lPmHMvxbkvzVFQ;MEJpx!kk-uA)pw4f9zPnu$r9o@_`^}pZkatv?o79qdN3q8{y6Fv9&DW|V!{BovId_#CDea7MIhtv6eb*2mwa=G$45y_Tk()mM*8Y*@9M>k*sfdCe9Z@wSkT-oO21Z%K7>-ukSR1J;DOHZ+$bvQmnzTuZb>CT?uf0)J0;XG?{loJ7(-iC6LP<7fLI+MuQ=flQh{asQ=EwRi9*L(!puC#-gJGIp@!L(R9$09_=}ig!;ehD*t(-%7EfW{XI5^QNNJsLMQ$A4B+hh7}P`kUT$Br+(MXe6r_Q9Ikj3Q(odSHNUsE7Nx%ffnDEfpKGdueFqNos};J^05IpkLpZyE+|AV9G)qI7c;`iB{RawFzHBVhNd>@*v7^ba;uf1a?np~2=dlT0ZWp7)Px$^sh2=&*ce<8j4c^aGp7fiJ(C4rxw#GYYQYJ{*s(J9B5Y|GVy@4(P`Obe?BA&SXK?=+r#h)#%594u1TYzmE+O({fo;599u7LV6^}T9XPX2QS}rjmG@Gaa-2@9zFsj_9w*m8zAS@p+wIS;FA4J_jfPPI?->*#Y+4%;QLXTar_$co;O=I3#ZcH$d+pT3*xwbv{39WCHxQ_rqdJmOGRV7<@=c*QJvZh@S90@v=l&YEfO9pro)7T5*=HN?6Gd+dExP1O?wu+5J*4Cq+|bonl8gKVzHsVJwB;w82uPI{d9Q}L4^{DeWjIZ=qtj~O+P(WCxEnTJ}e33H88kNgY?M?A1n-F#<8yQE%RI`tffKX8$YjiUy$z=ylA!kBMs^!3)^&`AfKdlP5j7hIxLMBd%QLo>o!Bz<_`6qVt`I@^{q#q7=L+V%vO63CP)VsjYU~td_esa3F8>n#5(VCE#%E|{9;KAKujZ{@>BYU}2ivINSh`haLlOFx%gdxq*#`+YW#E)--hfUZ9`80KViVXUPp(j??O8f~(%DHsOXbbXRwSmJM#t6tzWsA%@iCp)Nb6MpTa{l`_$61=PHPrUbWRto)(?bY~#?Gy%FoT};wPMG(*6LnXl$1_1mPGwSlF~-;JEU0hGWWnQU=R4ArQ@HU_whcn}>ez6pVasj1J1N|F^07GcN{g7N!{qbSHx`l;@$h5X{V!YX0GnoboLCac0rSQB?ceSN%>d@gge=A#vXZ^za!xt)zoad_f=7tP0zm)5+X$m}Md;m(f(aXxt7AKgo3+aHnRuz~a0BQKG^lAU*8hAIub$pn)lgXgVN-P~NyAn)f==9(yfP4zM<0^1g*~WwoCV3pf}+0cz3iU`FVwT3eA;3U9ZciqU&b2E&D}R&opfAj(Ew1}f59`yE#&&Yv_iL{5+J@K2*E#Taw2|{%ofn-&v&=AGQ&v=3P9yWqf^{>!>CMPJg&otsComvly6m-z%jg3&T>h4++cRO+r=`=(v@u`Xznzi%QHKSYi4}SglhV2Id;Fh&IjO*grh4i8Iq!M)=RCb~pZ`1om6nI+xF@2{D^ew?-i-u&99J$pD}Z_!)AwJTZ$tx!n@6mDdEU!=H{V(AdkGD;Zw}eCkPrLWeD8+xPO`l(rPhQmh(xaU+^uO&3mquS4+lhRp#BTT%#s>{7~tU>+&rlb`HJ?iLYMe(O(&`(S;?c;0Cv4x*Qd{&PD~|MD557*o;wQNsN1{=`iO0d8HRL>q^L}&GEYulqv~AK~bJ9OF2g!tnAQx(>Z`FE9n|K~A7okoScayz)4e4-WUbyXeE^_hh^7oBv>2TccBDK#R^)DCo&Dib6fWx9T`$`t0e(H>4A>j*|5dYI@TSgah^GyAE@hT>~_4CqjdWr37)z1@5zQuy&n%;L>ndq;o?fO(T_fg^E?SPrb-l4CMm>wPaP>7hA-{tP+d5`9eZ)$}v0S}*rPamM8uLzW&p4&K?1~Zo``d;TlUopxI{_`w`^cw@O)+nq-|6rFG#oV=n4ioDe+tELqw_2pUe-Q&BwF)c5dG_Hf4-~667Gh59f2it5Kh|V$r$~DlIX}8>a7-)!{aA;*nm~mE8@kLMNMC;W-+I|wz3HA+Pg_f=@J_7m=a>zTuaK$ezGX;2!t(7i`h}72nR7yY{}Td&r9w6fQPB@@-h+F*l?DgJMB~ErdEO_=Dl0hELW8cSvtQS}#C^#23Xi8Oj-&tkeGS%;m@WOxZ1VbY_U*fcU>&AYy54HN6BAzKo)y|&j{VtREhn@qhz0!T&iuO7js3Zg|K^oVZ`t7Q8oS|R5B6uHR>6<=Vg#6{pHNZhME`JFDpTq71p;z~?#di}g*@9LPrhk{fX>k8Yb-O72h2VE!H%5&a^8Uiu9v>?`eWHm3ti>*v!3d#uCcJ}5b|Ntgj=MRa!GIF0d~_u8&CGk~<4Gs^=peryqQFSVWt6#}lacg10R@LtQ0g?%g#O>h)TCNTcT+YNhUR^-A{7nd(HULY6UCVh3tg_w9BmU#mGLtIGI?Qic1SZ{xbo)LzevyZE67Y!WUosPUI8ZxO!~U{DYnNn6R<$=MOPIj4x^YF~zKh33a2g$!X6pKKA>|v5`?0Om%Vp=`4bI^T)aC154#|p|pQ@m0v5N`xyOJxzmL>vxxS3FGmDyo&A{j?=*OujOE;8S>H18YU^^yug#`_H1qfo|m&;m+clYG_5A*48xzp@HC{NvhnR7V7C5s%FUV5~f&%=E8v-wB4h6Mv&mD`S74nRFu{(A5)5oH4VqsnSmo;>cKak%!+HzsiARll#H580vjrAw@a1!wcDW4|xKe8>52jNk{-KL=+X%6N|cN^AELX^RR1{=WXvK3s`9qqBogZquMa$mVgCc|7$E6}Og)KKE#_j34GN4n{5^H}|r-0v%%dc8m`V^VH4u=WaA))8T^3LiO4cJnyv`C2ULB$AD$J$#uO0$mL!AVl-wkC-xO2Tt=Oo?*v6xGvUFD^#`BJW4>;SoL`(qut53CjQqA5^jF(BFWM%vp*&vYnqfHR>x@s-$&$?k>^CTE|5}SW3qFtcJ8h%E?*o(jj_9Bs+136bi*soZrYU!+foH$a_isj94r|b1n{NH9Avx^lkrvzJ$@!$;xZEz{nT6aVcIpQ=^7^*g&C31_s6Tw$Nx5@>8PIJP+p(t^xp4CKS0xXbVD!QK)7>c4|LEgzmCqFxXm5;@ls8Aeu{pvr|C>E~Vm+dHG5U?a2VRCM{UBhI-fn7E1?n$28YW)0mu%NqQDK}8>TJt4S$C$G2A^j9IJB6J-2BU%zEEvCSg$;L*k1>Aa^9n$knQ#TI%!nuHS$^KrfB&ZGeFA1NaXwp)c@vUt3XUQ1CE?8Q|p&R{kHe_X*$O-;pT8$P;x!;9FukON&8qZGmcN?=v{1=jE`bv=u$Qm6p70(^2+A&RIP?>XJn}mxAtLUWfD*Qf%DTs1@?~(7HJ~LtLp|eH`@>ppseX_>VrPvwC>?MZKU6xk+v$Js|5X6A-yV9*Mpp2^olbyhtQAR5-|U3u!IgXyW%tN5q3vx<@Ozi%>B@(7oBJ|)i_9e1peg^%%6%jHF8+hRCy&NZ!F%Y+Zvh$f1FNnDz3No`=bzKcFz;{KI(?~GDgobLrT^M~6uGIEY125FmtRXp?7uzC^L-U^T*x8shv%oSFBf*h^(OtF;v0+4(7{4f|5J1o_UDMDVEjG1gw+1JI|F*}iUf@K78P|t}8f1_^e41yKI-Q*7y0vzlZ^ydL;^jYG`pEk{@2%DS%2ce|oL*mfS}1}6*G!$KelkPuR-&qKGLQ*7pI+9bccUNUT$kKCtch{&&{^cAJG6rM8rjfj5)$3>9pB3q@Q`<@)g(ZhK2UBt1AW5Jziv-;lL!!=qjleFHqSoTg~u;!7N>#AsYfebiy^1i<>|>L(_n?-tg=~B$OWHNzcB$iEYWebx0mC2-`QmE*(oD*SgIhJE4v(ds)S5s_Dcr%^(E^w)Ua;Dsdwb&F(Gz3@#32%#-9q9)$;NU3pn3tD_?{0X(BI{`A^G*Ip!hOt*eo9z7r&CPr#bV{g3wOq;QWTaG>jl+A9M1=7-9>+Kb$5Uc0CgIWLg^vPt^lS>(%zb<^*@p@Bl6iS`$s^`kkvav3@qPw&1bB6O6wzIz4>#H3DwbTMkLvWBiTb>hDK}$@zlah5C?4AdA%IhlANJ+(MF+|qW=YT{#=~wN|K_siJY|0<4GO8@OZN%ld9Nndy!;|chh2h?@^@O{dHK8U?jFpb!_^VVeLr$B-k3DX+PfK0_er-VLlX52ominLIhP3q#^1|#1!I0x53h3mK>Dlh**8Ca=0_h=9cMPkBK_6up4T6wE@OVojJx(^Ndp^V*%utsgfS1E{dt^j{F;DwP6iG3A*jdc(==AJCJiR(Xt{)bMxLu2)McMRgX@=CdvyUQ~^ph69J#^&-&@XMY%ky^l!~|944AHC6sQ+jB6YF!2Srhg1*J>Huc+UE}DU}W0$$s6Fc-G7AcMV;7-A;h}^XF!^JoT9|*JV0~jcFj!x#;%LcjOoM&yt?|ga#QuIy|j*qt4=sH&&d~CCA&EQ&ry2k?WgkdOa+qgJYPfM*Jq!X=HGGmY6*Q42RT%jmoiI*&#GhYhfm+TQ*#1utA*(NB1sqDQ5!bz1smk^czdJY4h)mV?k1A=`5=pxzbgS**ESy?;uA>~P~GsPy+Cf@7p_eGt`>lA)S+S4Y!YZvhi`4o%0dv)H@Am*K;n%M!=KmO72$#z3JaP~n6^V9=3lwF@5+x^Nd)c;lQ6O1#NK#9-S*t8k-k9Kz!nw?=mOKs}MO}~*BMvAF;Z)L+gy^;pa$LOzix?WIuq)mZHsYMrU2ps1RlRx)*D8L>Zum0(PqpR$@G7-Yq!7oZuyKcpq}U&vkAQ8~#*#cHC>j{yFl{*<(*96%yi;ADrTuk87VX4Z3SZ!2HP%pH=eI+n)^m_%^qSm{`YI`V;e1!0cuF2gv!9!pA}>#b%!OtU1@EkM^(spJP7#eX8=7w(hX%7a51uyWQ_jBXU>*9zcmK+H;x84JB|j(UL7eLotb*}%SAyN_av5OvxXmJmXMe0|Nc4$_cqXhDth-B$V}7qVwB%G#5(|EK+a-9t!s|jd|D$Cg8#w)!&Qm|JSY7+4$Bh7Klk(Y2EgXmE+>dlF`b0qS%Eg8cO^~--_V83BuOsI(z`Ktkx4u*`G|)r?A(u&OBzX24E2s%%`}ojdETg|FBntDd$pJZkmz4}C5I@9JNXK|mp5oXr1IWwMIGc&_WEyh%QOg9ui&kGn9$-A@IW2z20v&R|s-s{$=Q~c1I@uHViC6^kFZx5rT{FmekWSO1SZ&NB5b(hLsTd8Oj{KSS$p*PHWm={GWYU2+Gw+)x&;A)s|JU0w;OFkRc-|jDHyX+*NEl4cb=?T@B|s4(I!*CFFdzjrbj!k%WBT3#$cIJL!;~J{qM`hnzFcRJM@wBf|Zt+1yO-dDq8W80rpVz^0h3k)0-(XUTMP@w71$IOFctYZxD-DDOH;js?Fi?~PbmjPYbQIK>OGf%7;$8^CySn4i2uI2R`Jm_!zrbH49%einHhpBl!BOY!&sdR{g+{=|pt?;b2*gQ$IsZ-*uN3fH-p3b&KeIXqpOO8tAL?ZvZA**6i5*;}66?QA~ZHou_rm8XEb^aChzBE(=JBwwFkNR&~!`WRbQ4|*V4>^zx%EVznqGkvrN-9mohQlZcoKLSiSYMcKSRjJh{Ena^*_&6`W!GoGbyFq`}yE2lL}A_xkp}Y68j{eB@%kW1VC>Iq)l_(*CUnZ9!kb8JDzg(I>8Zoj&>s&iw|NWPiFJ4R`r~^&czu2BlW#Z1_8^yJm3_`T-^H9qYtpa-f1azWmY+J`(crHV@w;#cNG%=oY-_D~mChn68?ta&%iTnIj13B-w+-df+3;XSFlDR9B3&Adi(T><}XFPqTtMmz}GTbJm-m=Mup2n<9@f@7rdmG%a(Wft8NgT)W#C&&g+-SI~iT-I9)BeA3H5=LY67Kyc^%)0gBhek*CT%@;8z@^u)Gf8+Sbty@_W<92`n^1jB$Yv(9XAl^hOD|II3@n4T-{XI8Cfn(3L=KT>x&Uw!?{38_(j=x{JR|>i3MtvuLcLL6}=N+(Iiri;rX9+`)2GifE`mE;Roc0`gNP`QcF?+Wd{QyHSj_;{I9XQ|J>7I@8>EvUfbd2#YPxYZ6WSwU{a?T58Oi$BZyp#QKMDi#*_4U*8lKHXKQK4YS;pc#6=o`D`lhWwt{==dw|g}KmHR8({I(&F?Oa{;HIIPxkLHL)@%R(Y__CaQ9y$JJ?-}$VoP7v$r;zhLySXZoAsA0yCX-iXbl_aKo3R+*oqHzbb`Aqhy+2T^M}=XWSSbqXKDHPoCF8e{yW>>GFg#1bFtQt6k)&KXC3_$G-#!ucRkX12KNylrY!2TQtbEoi}BKjqx0xU8_$Aj?Y^68RPr6M|@i-z<~4QKrJ#A^CM^7(Yl2J6L~-u^ZU6QiL#46GNI_id-kN&7=JJBnT%=|3yR2YII|k#YZq?s9#5n~tkw04HRGs<9Da>bvld>yp5s52`PlG|95&uRL(Z3CQ(``i0Li8Lzr4Qi_$$tQihLe9?RzPM@vY}2UxjxN5VCaR19zUf(8PFgf(GH;K6=cjOX0nXEWxs>#zXtt}^V{gp@(v8}-(&Ma)|Y3Ui{q=*{#UOk#CXnk(J#(p!FpfUcO$A3scW}MweG;a>)Qz2Cco33sy_ci#Mr@q0KA5b3Kq`+ft-areJ?&VHop!t9Cb&gY2STP$E;T1+}{zJnFb^Iqg}Td@zeD>LBezUz;+=J4##>^s`rN6rWMK1FNr^VH`^@=?PzYJd`WJCXhbg^SH$mf5NzZ=_@1MhZRcYJygeZ|CmaDqCKPaix+U%~l4zCt1aob?K$+vvwQ?N`XAL8UBtV{gGa*u?igbuwV8#4Wv2p8EOFvs3JSA2T37ld)f>5q-kvwvfn2QJHY@7R6>T1NmyB_r8;zv%qQR)rY#S$iqILTwHV{8}2XLv-Q+6&bA4K*O(p!0sE6@}P8ocXfk2HJ#wQ<{>(jpy9YZTsmH`A$><{l;i)D?Otj16r+Z_N2>U{yLi=^sDY_CZvwOUX>|?yzQmt)Vao4uz?~pKd%q_C!?M}hfvFg5t@Ia%3GfA)y!HrIzryBzt5g;8%sjY8E2x-{=3f#9e8}ji^$aGZ`6tJ`-MvI?Drt&$#E6ryp?=_^XTXwK2xIaRllTxxs5^Zwa1szitL{&iDU+@1R1n`ElEVKI~6U{cfr~F;VwRsX(7#cjx$_r9k?z))@gIJnJkRpWUlR|Ce{vF@C%4=jK_C3v9h<@N>U{$LzVrX^5c&b3d$vCdO9&{`bto&f#CT4<`T{vWn((K9@vd_uIya}#!Sa6DNS6r4A9L-y{Hcfml(=2in|andE)@*@2+YWW6KQpaKk8!sy{vfXt({9YlodHocG!n}CG%8l+RmJb?`bD`Aa@H(n=Q1H0!24!a`uEF=hPn_yHo%Do`$}H^WAj|YXWA=KQGPA$9PU&>y`djFJhKs{L63iP1gUS!K3_CHTTyTKQaCf(Eq(pSA_8Uag$cCzuWeqpyA@}QD|$=-Xs?2wS`O&LYQh>8@YC{dA;Lc@xFuk-5j?KcRD!STfJ_LX?~-*XuezWo~#rxE^Kor|Tk{Y$qh-k12@l~Os4wr&KYPVC=;TFZd=ckX(Idb^+{!+OhdSo^%}tpi`lzv~m@;&}f0bxnGGSd^xyawj!I9Jl5&AKXL#_Doq)IBqe%!k~?U)}ouWc|~Lb&X&2@2V&n~MT)QHbh+L3M==jp-w`Q#yad-Nofk6A;V<*Rsr^H$%?n(|L(E#s+avOUisx6aTt!_uQQ48#pa7WZqLi#nP}kWX<>-8@5b9PGs>pMpe$~ZP^_5)_G;P#xwZ4J#M*Qj1T1?v?eN#YAP^#`sSZi1cF%1X0g!6EIs94c4mHu}h`t37vl*Fdkk@}nEaB*`Ei}5_3!@gR#VElbB4>DKnW^!7C>p1QEPTj}S{9sE+@f9<|8*~m70K@C=zdyah`613R7jG&2`##@7Ub@-i*RLj81PP*BGS5el@@I*8Hz=l^=c;Pr_~G>ps}!0`;4oLjLB9o@AHpA1EK^3?FV`j@UlH}8?rtxKrTKlY_Os%6+Wtqgg65wbJB9Q1{bQfskbgb|_#LlWwhh;1BJS37X90`}cO3ghivR3tsJ*k5t`La+a^7oDC+hwPj1~fYOmEXVl3$4S`<*TNdmi)?=Pglb>G{N6CA9jSE8TWPRsxDn0Z0@-*YiG98dUFtRGg;&etwRk>Y1A4R)BXFMvxe4QBol$R||%Fg^Ub06smZyS|bX|M{K%{*lnKLeM^R{c4#S>WZ8UvsKweuwAgNYIHPhqz0`uiEQb2x<2ZGPLhSJ)tJb&hu0eyvXPH0*omMf7+Ah7z?SwkJkht{m;(x&yC6)aUOHD~8BRA^T*{ko4c24=CX!z{a!D(~t6BzfDh3Da=wa`p12=QJ?TS0Nt^x7@6{{Yqj{J|Gb#S~43ge&Lj$A~XOIgYN&Cl{NL~ap3U>r+#6hvUgcAP(Sl0bzY->z)Z+&T@v;8Nd2!dKVC;}H{&E{QYjF1vOSGZC)UT4r_27HV`ihBwD0D084&w^?P1i3bu>D+{O>u}Cgderf39;CH2=vV1LP~>bHt@m3B>QdF$~AMaI9Q7u(=A>G%-2H=i~U*cjJBa2C^aIRjl?pQv77Aic|=@>2+E>|EMzRmT`?+>SwNl8x`P>{X$NNw`_ZVFFyzPMANbtrK5iEa(CxVms~g{FO=@Ii*$~5eLRD5J`biN_E?(LW&P9dmi?X)jL8R2mu(uiH=v$x<(KC$MqNj=D9cuzBjtT}>tA>oT?EIe8zN3pojszD=69dJ>s>}Co|h$-XQnm>T?c!v@V8Z@a~vBdxlPPmIdD>U-{+s_QP*Q)a@VWP0V025xg6>~`#wE$am|G?S&5Bz=16@6sGsN4)P4Jw+w{50<){;VUZ#!mA?`zM!+ug;kLWnpo2{t@@T$VY;KF<4guMqV-S}5g-?N8r>nn9|-qsrS>=34MInfup<673g@w7Of!BW~eqtJbvpR13$H;#+tK+ayzSdC&_$K^qMziev`7_DX+V5_gc&5)6V0h)}#I@rA@Z*SOH9k74f+YArI7s>ZaUEFNE@$8X4BhIG;+?4`Cp6A0-`Nns`GB$NMb`VBb4e0vpZNK4~D$Cu`CB>8I3v8Bu?PYp3sT(RY>T~g);7e<*K%Jg)s5V(%0Dk=O;(cDY?)N|BxS}mvNb8>>Yl`EEbto;S2+SkcD|4lBeE10-y-wj0cyvJ6bLkY$o5W{b_cM#jfRAlJtTP??%9Q#-i*x?X@6#svA!nC+y`yu_1bgTVM98WuMU@xVew|F|Sh`8_(eQF#h!y4hELPyhVF-DJ$xONwaQ+R6g4g{Kkd#26BjK#!=0rt~@Z^G<=%!5cRV`krg>P`B3A+HoLnY_3C}}?^|OEK%IwC^wW3Li9ho)|E_a+i;yeE?<9N?e^~@XeN8Z#{8SECG}6b~eepIG)&liS(5M(WkkfVgIzn0cr^b&zRFBjUOY8e4n&`g7kAK}A9D-sjdgj@rY-8_PKvi7>K(PX=0og=Ij7V;)NiHc%1a+90HTk_?f0m=a2@yBty&0+te=;-(IZ!=ev4dZN#y|PKCW4xjkvxOb+1%oi)r<*RFzRD;?}lLQ=d1(`b>rniI>!;`{(xluMeO(UVrYSPD-m-IcT4MJesVB;p5co{D-2PC7I&pqb<#+S>w(V8raI-FrW4sc_cf1!*UX@t^UtQzgKD&w6zkc6Apx&-nn=`^+MEf1R55VhKpA}uO160>XkgIpq+Dd-NNy9I(rT~zIBB3F44|~DqP1mYxf;4n{)=(Y#smH|f6!ubQ)1qXI&oh0erFJ@P>#2(^&;ihZ;cQOFbswAynXRZ~e?hq!#l8iN04|vX@|}QjuL|6xVB7Kf(|Xhb)x$y(FO5n+i{0Q2uRQem7L)4!5pmicD}3Qv-1Qe-t5H|eK6L#|s~@b+e7UTy9_Od>MuWQWg8&e`&XJyR3U%$nE1d4E4Tg%_g@QHjaekzG&SeLVgo55O^|>j1)T48Un7%4U!m6(cZk2aQ@$=_aTlQRwfv-yX_8UogbHgqvk6picLtr}{cfe{~ms#POqllU>^zB?%JTrovlbG~dQ?S~P)|c6=ij?=XX=KLzCvHaFRCr78&ILbs_h`?`ccl1dqTlY0ivd8?O>y8s-99YpgFRaij1E59lm8Rv=dgd48@vyORVf=2_q3y~7;;5KdM*^6wl4tXDyhFG^+RuC5&=Y?^9C!_otz$+q>4pDc&^|%BT>{ZWS^%<%Tb{Bqr^iEQoWtiuf5H5x5U8*cEUX0ZoI|1Phpjx#rzQhyhp*OqE(B8L$E?kgL^f%9>)-=>44dWOEm91;AHFmSl~i?|xTrBc%B4*ZwPFcAScZH}R9YwF0E;6Y+tI;%R=}J|^TPhO8~-lKlxF#T)gp>kH0jyZ*qWFncm|FZVv2(~LTiPa2$(0$Wy9FPn`=eV^C-3WcHw@MfC2DulUDOfH=o6Jc9bB^6b|FUt*z=ZTdG4DX!bjiLNQqE*|8TUf&^o81=`y6>{4o6TvQaIC|+`)QLJ*^U}$*Je^&;kTW@x-gC9Or9f}2_DaL`|MhnP&lMp4KTi_J25$K=t2G}D$9>~$jtV0$?N%OnrO!lx55BGI+oe$t|D%w#dq*r-&G;6IlFlC;Q!keCyTrjZOI;JsL#W>fu0J~PF&>!4o@u63%UP(!CB1{cEb{^A5orsH5v;1G4wgGaW)#2|^-)&Ri-mV(Q69zb*@NevFPWu~2q>ba**352cb-oHjAHPNg98c6~a>}OA^0EU+`Dmq|R8{lu!~z57=TH92k(Y+!eUcq#;-IKWaod4)sCz6I-OqC};cxtg6zX@A?)wMzCBlH^1GWch|Mhnri%15~lA9*pTBuLOr>#n&ULP`6WB*0Uil?QeXw336lZ#?gyEX48S_pDCq_<8@zlEl=vsfU?uu`FIDQLN7)!JPt+)ZUb?#aJ^zgTwI$LKhLSJ@Pxv~iA+IODKh&wxg!@1x06*_Por~T)sGn6K;>~F9nt^2-1%)D3JAakl^1k1*@eS)Ie9Mzq*TNVMF+KhVCM2gSoG9wk5b1>ORatoW9v}gVj=vsCMpbMS~qUs4#auOda|FlyfTWGZ+Mo}$BoF}$ptsKX{H_EKZe|rcHK-a^u0R}^@?WeQD6T%JfpnV3j|yaGO>{QQVp=H{1M>yg+qA*@zR0&_8s{f;)6mySdMXcBew2*l#&wxi@Aa1tlwY&U+cJfG^2GWJhf}g2tvn~4>t4DM_!@;=g2BI`E#h#h5w#?`XCOhGR^FDm!NLY$Ql_OI8DET-Y14J^)0h#6h-VG(SK0$ZueR0cffc$q=s}Js?lc85vCUkME}edY1BJC#JgE=Q8~B=%375zU?)~uQ)iz|JlWkbnZ#id*WT62w^&384T~CzAi2zjUhi7tgK$?md26t)}t>31a^mjv!>wcSY_n8j1zN?{0(8SC&z<1jKqzvzyChBJUDbh2N*67?n2jl|QX5g=K>`d)@qA6vh~>%1gS6wG}tfc9OeOFop^F|{KG_Oj&|XY50rV^#O~VMhwAnHrY$&_dn3i6P_Z+gMth+rSyr<(-BqZ+pfAAN$Rh^Q3cCA`almk^eo{Ipn~mzb5ys*@x*JOTbe?Pi@0Zn<2Rb#n9T*Cukt&Q{FZeGSpBFxNyIZZcp^6v_2nEp)4-5ZY5bKJj;~bv-RSIk6{2OLPIWn>{_W5EfEgJI@OwUHdi@l2jdnrHX2V!oKf$q4)Tzs~-)MFm_;zF;HfKP-n%sP6FE?8P7!wW41W^~eZ0crlB@y_SO20fWgF2hGL_)*qWZ2C(`Q;rcPM((ExHpA1|A!2a8{!2j<%7B!wtRPJ3A*r$NfUKtRg+tM-+e%B_+iG@WYiUodw!G+2!MyOeXp56qfT&mKt>2;|IY5sJ%asctgQElN9jj`wI`+X=3UeSt6DOotSL~(;rlsS9qVX)c4xbnnGg>W-|TYSMo^zHeQdy|m<-WUhhKiZhV{6T8^0!KXLrY^+)HIT(t*{n3YFWN%d3@AL2H-G3^42xALnN)T2Ir$TIdNyBEk)Cs0}n>wvXLchyJv`@w87JM)hkQXjfmH!X?aAUI@`?|=Ik){*$lFC?~HEF89<<{I2Lhjp=te(+rTVnAj@!*)kK*3mNcNUncu5eN0Q9%H;o$dk+8d|~gVPlAf>OLrt9(O+lxu27&^`z##TVKsG2kkp@UD=*#FSX-!3E|OiAjn^+_QQ38MxfApR3Z*@f#p@IG+-q05L)hAm#?z$w4|Iha_OJQr1BZW_EtJRMeGAO!@=U%4(DD>M8{qjY&)CH7HQu4L`s7`J92hs~s;t%%1!`K(v!4Wz8+WR9dxBpq$m@Y+a~|r%_xvk&BD8<1NKRJyZ=Fn`116w4*^#NZAMg8hnP(ZRhc#?`CbJOm1NnSxZl6_TD^j`4f+3*+Cs&#>P!zU!^mSz1L&+fshlNRFzJKZz5R>Yw_qZiUYU)=2vrfRZt*EZw1cFA|!B&Duk@Yr)G^fxJw<2h5T%l37V5U{VzZm%Pr=V~d_YcIJ{p#cWf#yBzMNLqjCQshJyK;Y>jfSjyPZ4Epq&#FOJB_h_=9}=;;|@tw1?`@>Hu6fmhjwvApEd5p-^s(vpyb#D4J9AofD{>>tmU9a{KO;fJU^eN*543;RLBlK87AUYu*~KrR9{EZw#-C&Li3AY3#S$+Xi2RU1T?ScR7(qN&<8zT9oM$3GYd^0w5P9M5|Mo|nDz|)+cz^A4fQ9Gp8+JDRH$OM@fg3IE`sT&Ff8$dxmOkc7@qxJ#=7o>KXlKXH$DOAh1knEOGmOvGE-=4i>QX3t5dCs)id4_4)6i3~>R}Wt7!A~(bVj}^-BPz*R5uoaK3+GmRzj|bG(OU~IU|8~E<^W+cH?p-z`4KT1{BGbMMmx7vU?JrNuoyk`xfcybqZaR3^c3yqt6AbC-x>?02E7+|#i5^y$a{T0lK|hex2^i6f#-wApVJ?kx_KU~0=#mRd$50vnd=t|31tWPlHDN6wj8;umGN2gaDyv^_vibh9z;Dx>`{;Tj2C28$xiR4psugW7OKGL4@*O{==9D$A`&?&Xjne7>a{uS|MTbu&peKQpTn4M;J=1-Xbh>QPO;kr4<=4ymo!hWtjH(9=QNy;UXm$MVlI~kwtrxq*z?{|(rGE+D_stoluXdMv!fwuV8{9E$KIi?e-_aFWWhukHnH6x!Q=O~0S|5?mLf%N2`Cc+L`|HiWxAL$qmi3jTEnUjaq_r%I(O`rA5akw+NR_Tf=-j_wVyX(PY6JY$6tS*;}cHZs?`duk*14P||A#S{HShQwqN01}vt>;dYi$yyH2df4G4cvj~*KNa-^>2LlnbNX>bYHmrWa8=PfAIj+eZ8TuQR>DZ_!5vb;HZvvI!j#>YBvuD@4&|iyx)-%Je~^f2)G#or&k~Py^fTht6#h-$w53GsOH?`KKuXWrCJ}Q{r&Ef|Fg4Gh3GGv9%2j?sl4+(|LVz)t7Np)&qOXi4;=LoCU&H{@kCwk-`tKs^wa3kB=z%Men2dKsXN5QsQ0xFp`ApX)lz3)SliVrEf|h=9_TsLz&jfVE9E?uPAVg}bXGHHa2*VXpLKhU^nalJg-nmthVx=TfAP3x{!Ls@4PP`Ze#;dPL>}8$4_r5I`sHlW`Jo98lj~QF9722Uy6=w+Z8C=Ml=vUefjUvIQr`7EWb{X*up6PB1n1XTJ3@IDV^_uu@)&DezTZ=8cOd$%N0Rb?xe6JLJ8t;`Q&N;%^ii}kBX^O1lXegk_wHO5xeVJ9E1XVJVGBMx3KR&`6=pg3^;QOi*zQC@*Q>@?6ln$58=mpdLNPMKoWj|Yc}$^VZV`9&3;LfwRnqtBZc%bDb(+ah3ZS1Y_ISpUvGsZrqY}M(>YY1k~LfDnCN%3zM_7Pg91I0z#beSxWnHeLt5wY#($}cN){Cmc+ORtzMaf72=XpKdu3ujU%-|$*VL59x>X`@I1@rb?gx?>8A^sHFf1W6acH0?TpZE^t(W9M{8@!rz8N48tesI}9EzbWy5Kk$uus_u2y(xX?gnT7x&ijssx<4vBZQ=1ifs{8fmB01J%1Fpqs2o-y&R~u4;|9;&T-rV}JVcW<2fut0NTogqHVIrALeZUu=bZ<=CNV$1h|_^Q)vUMLXRbH;5K|vICiq1DB^O@wuLV@zpVkbA?9F4=>D2Nd2R~Do)&{_kr`eBJ>Y=aQ^Q+jpFkX4}g*`bqyO*J@${byVscvgaEOhvrob2TGv+8e~%*yUf6EVnKMNDiGF`wpDFMyda9s)EuIfL=jCinObaSYA@yP)sA201~Dn|Ws^=J8RJ2%i++}+Lb7WILQ`dQaPZ}_b1esz``IqkkQs}RN7A5t#8Sr3M&M@&9`H0Tiw6&fdOBlA%w{HtpuB0&0i+)OSr^4NaICv`2IG0?fMB$dMx^{RN$ExteEptt2}o+u0Q*g6P`nx`az?5>sbYi^)U^i4K8V*!k}jQdRTP$&AQ6dPXzqAro{H0rz*;i~gBPC(RGUV0pPEPYwc$C=0OP_)3@I9`pq$^|y)l%l>?xO%K_A{400$@`(*$Ya;mAK7wQEgF=z)Z3o_j(T{A$s}WSEQDA(GA$zc$6jqJsAfEn2kXN=qp#&JMIN*8bq?+>^9RBo*?$*xqCc6CYzT;R^xBt1Adi_B7@c_L8VPAZdG|FPk&Cv4e(^ulLIEP*+Sn1f==b2qJ4}ZYXnD;`Vvv7`^Y5b!`e3QJvWb@w{cORxCm&XbT7Vthe8abEc;Eb)tuv?UFVgDK2^}NVjX&aXV?&-Z5c|Bm<#^x8#6lsxi=J@(w$5&gx5#5+&zcn0Ci+3dHTzZOkI)`T{wEf6D}tesHFC@Sv&cE29!bZO_C>(`>2t5uz9SdOI07-U`4=LPf1`R#(IJ8}XM$7~RA0!}@YYfsxg99KNO}AV14BVH2so4dE9kYc_>_H$sF<1kg@X7S-hsT`th-e_qN(JHv(&b(S1+0;Q);gDQ$RpXto+6!o<|fLQ;nU!hL)WhoW(gP!aAMwkLg{d!nWGC@fYyjf~|LvnKt-iXTB-&Xv^1^yn!x=VT;A&!ijPqZn@W$<(vnLSeU6T%IXIr5IYipe!5d9kmx1gO=3g$4^4u)sc<(Ykul;66cKF`260*L;-iP@z1I)^J_hxE0p7yMK{qh{*32z-9rfee4!zaj_MvfC?0wXaJo_y%R_qVY-f9dk8bbY^R%?R%<6wAX;U;)!73H74{P3$!xd9Qd<*S3d?%CNF+ltGxq>?JXUw{I*!5#IJNpvkJ-LbJQM((GAo@DHK}Im@jJ*QKSyL@({YqH!kn5h*2Wu=}X$SZF{8!w4gZlZAv)*eRoMGuqhQ%sA@mP#((dRr?DRN4e&d_z!YzdX5aBqthJ3_^j64f)N9uE}8jV=M%NSTf!@5qw_!o>n-E{5HDS@a(C3rf_}L(j5679RGT|bk8SN8z9!V=$$zJs!~#Z=mQ6U&?i@nQc-^wUpvEC=SJ%z{BQ+w8oj~-i`hOONHN;gLl=*Ft`lE(zeE7E#mXg4ZAMNb{1T>RA@HVMOQ7Nj>O?=^tg%R#)N`z$k4Ap$XmVVqGfSb>VOxC`InC6pjepK90mN6(w;t6+UP@Znlz-@y5lkB1kThmO&g{sI(thZ54$Pca*Qj(9lujqi*?3hG4vhTcGZAmXymisF6wU2nX;Y-a(2?}To4KSORTWuWdbzFY*o0ToiC%Vq)oX3dqWNJe%2_^>6$n^M&m5_VJ*m$g!hm1ogRfGN*QN=z;vOqN(>%{fq1Miy+ATeEp>f96x^~j<+=38Gg$&xjLOiJBj>)OU9nCuA^~j+DEk0MWWsDNrE5jvEkd-W{>uqKK@lXm^m1t+TJZlEkn+E>3t5TK84r&#_uhQ8lyv?Tvz*;{nLce_wk#d(x&NC>@??qygmbf~IsWSlN#($)ygP2ZRjqv^Nrg5seX%K=&@pVcYBSTW8$}_VaPiI#^>33HNub+h&qslA{0p6y*BBhGV%b?mt5{*Jbe4e`62oj>ZZ&6qI4wB!0_4;%T26kXX&N8ie@{{!F2YjrGg=7XZYPyZ+$rIVMos8uWW2+XXZ6+v2*IK5Wdj)*qu~Y=PjQaU74sic$hNN$taNgiesCn8L7PShw`aYgw%h>JFCKYj3)%fo&`1Ph9ZyA=3z%9*kAmVY^sdhl4u}aqvJ|}=gI=nnLm*e?g@D$HX(z5t(eda?W)M&l7UVI0gX^~x1}Kn~IIJV=g*-;^_6S`95P5h@NcCW)X3nOjYM8^@rkJ#}Qat|+*gn|V=Vc3PXU;`(Z|^Nx>UjZ{h?*fDT^&Tk~ePnL|0ISYirS@C@vV;x9!biH1C$!&-RKT6Whd||YIZpfUES2>0@dpBH#O+c4lVtrgD>WE+s$zU7d8mK#jlTE!WCVB^OKO+RqJBhp&)vb{7&w{Wd2){&avFgFSC_?u-=Kb@VmRua!$q2I*ONft0egbX9ElHG&h9T5qJEdM-;8XiMDAjHw?v_#_9Be_?lafyBl+bl^mla%I)hU8O=EgC&F_@v0BfwhEgnUn&iI^h%e%{NV0Hgjobd$e8Xp@gnm>0GWY_ZV5{^BmXD}U@9GK|yBq>LLevjGx`aH|xZL#FnJ1Az_#0M}cuY}K(PHj1g%)qH_ao}_FObD&?2lHx4Ue(oHwEqF{oYZkfMiWKMwvY^RqKHhzNl<@V!`A7`|K6;47vRhRI-K{{J3@+O?Y<;8_t;!=2Dj())ax=c@acHf*U@ek_6KE1HO4;1XPrS1+OkLgt=B;Do=hO5epy{D~_bJ&;v+RP|HoKX{!9(d3{Rk>g5_y+&^4Ep8^uB$y%MyzF2c0`3P&fOe#@%gU2SnV~xkY$iriygkdRG@PlH1L=+Y{|PQ{!Nqeb@`~rKV!W8IfBKHIA<=U+xbBt42>8OGG;fdv1FMgVo$go%>Q~r?%BEu#SlU_4%L63VV9_<9b@H)@agw(FnMB1!9V#(awIIOExm=t$+w8T|~08@9_9xEq{ApuPI3$3_?4VKbM|NE_8*$jTP+A*wId=jmB>~GQFXF$*B*yS!ieYy~e82Mt>mUa|M;r&W__1Y4kE7@Z@`LT)nL6T5cPX@jpB0=Ty>Vyh8A~SWQBHGmMRO@t#gEp!d?+_Kk&JTwgplSmq7ZeL-lu3KdI~W_qbbb`@sGvM@E^oXlL~Kl9UIx0)V=!3i^2$xrOlGM(zlOYWG^rbZfLTKWILEmsAvF*z6n);6-j(-!K11XM_S8#Z!D-ZOAP|y~W7I3E+G*bQD~WyH*ye+!qfx3k$yXea@1|SDR0kPq&+21fnnQBq_e`H#hTQGd^cpz7^j=w114PL7X?x1BOdBeb5^u^?eX$Ys~HS1FQof(n(vdx-dkm&AvTB04Fi-$$+!;b^eAYaD6Zqyy^r*6-+2F+t(^>o;U1QK^8bA>sUS|xzgo6&5qPSmwxop#B)*}&MrN9vx!k^gkUFL}Mj0e%-g@YE1QU1aT;_gy_VaAR_PwwMQXqMwTMO>c;Gb(8N|gZiNsiCE7|{SNssA2edwMA5c&Gv_2>s{ljk=WD!&LsJkG5?)CV*MRi*fy;n?bi2Iob{UBvnLc_k0vr7NgexfS&}*O6Ou8NPqxEsaT>CKi*iDwv?6R6ug+J8JYDjK3A;da9bwJ}oW2T6zxHO`pBp7KD1n`G;JBtoA^hgB_ely_uh0VCm3W(hCkQy;o4M3b|`*)RNNGQvR@A`&@Wx73#!(JTWI2M7vXl$83jQ1URbLuFMiXA-Qc+oOqh4-z}K4A7%)CJOb=PheENPV5Xiq~X6*RX61L3E)3Plcdn5b5|rx*ba-y=s#b|dGke|x=qCldwkcz=J_{RlZ{XdmUqX6k!P^k?{HNXnnR_E7xmls>I~zAULf_}BR5FT5XGfLCr?ge)E2*YR=+z3oOj@YtHG#88hs))zK!?y|-OsLSn<-hFuA+Xg!hKYi;7M|tAUZLC2%*-b2#2{iiwlfnH=St+z9sl{tVjfbCF!hXt)pvk3p-@`vI<&%Wq{Q2ZPMXc8Bf=v~x}NfXIim2q5aA+K3@vU9WQ%$J@SIw~)!<26d8oGU{HW`OHZy{yFCjdqquNK3$4-is_Ap(|`1bCCVxhJS2bDrPg?M-_s$q@56mX+DTuUs8Bg_3FtpY2w(Yu&-KNU|MST)AGl$?TX!xP?UdfH<5k-q0JGzws{1yeo!Xhcr<^rIY5hanTaa7a4|aqas7Jw?H>zJA+aR|nrQLO0L*4(fdmnxg!cFQE;We;TXf7UlG_>f)@1kC*x|z4O+X8ABZyp>k$M`yxsNvRwpDzLtH~mf;?R*{JZr)$$41C>Q*0%LH|4aL0_AxB+gu%_%9)c#?NyItFuJ8km*pIXQ!}wf8K0^gl5Qqn)O{oOo{L}IX?81PEBXcL^5qI6$m>^;t4XS4?o;E%uac=l!Ja_s?t+x|K?*15DJFeJy80^A9+Qh2y`wW!w96c@A*>*ZSTLX4J3gueo#aup4asqiZ-b6!uR)eLgO1U#&N+KJ@#T^h4BliPs*>_VNe12#e0nO4K=CtG_bI3x+I%z<8B%)QR~zY7+s|=LPs#@1h>ReO{yDdkjcM|GsB5iTdlbgN#PJ@sMsP@~G@6+G!k;*6_7F2}(C>o-TfmI`#9`Q#)b-GP=uu0O=f)@Jo6;z6dA6LrhGbqAs^=1%uRHXCUGZVn$GZT`T^K#lZvCR-aLxS%N&~B5rb(uHF|a%xCIuZ$Z7fnfvCqYP2xQt>VkQFG!}RT=T7S@B9EQl{Pw(-eIm^6f1CZO7WEaEWD1o(nnI9n*X{S?$YUoHM?@>lZD82(^dUtN^p7b9Omw;ac7WXs!Q9>EsHdoU80}wl2?{?CxhyM1P9y4jvfBF4&XSa>1$Yq#BJ)QNg!`tAv^_VA8E4hDOv*FHj|^U94ilnQgkNN9er#Z0yV^^~N>uhtF}Xj;doelh}iscBiYN7eIqV7T|bFWdpS=!8S5C);-!k$*~eHLUS@s{2!F$uJ9ysevA5b#Yse0!7|$eo9LDR@DahIcb-RG;maBpqBgkVCm$&jf_xFPSNQS^;r2GXUjwE-DKcqfl3%aC*JSOc^4OyPSutG^BZp}L6E}|ZER%irhDl6R_Vj}swHu%|zZ=-VFavHk;4c0mJm`W7lHk7e#(^f$Nq-hT>tNsw_+18?PIP2f_t%YxJKcx==VqbFMCE9sBrTzU;I_mpO-Ith?IDzONSEx;ah|Dz0kBrCzME~aBf$>n~kiwvwL+YPS@VUMzd@|>JG#`cb5Ot!sHrjyD!Kx1uqGAm)9RcFvnUjCP(+&YajIbCLFby6TebB;rILIf0|6(DIb$Bp$PqZ%gF#fY#1(fBDmB=jcu)VRb)WIQf;~?3)ib&qUp{X4^nGuhzWln+tMF-42VJkDi7C`sy$c*ojCTI^ghrE+D*H_%Ba)7x`olsm~%F3^whkdWOus|MWI{j)Pat?BT?T`GZ?Nh5Xa^_5=#OUg-+!hGPp3=b?U2aFqyKfEN&bu>>7ZFZ*bn$nw#TwvS6yL|yJngDDSpFc?nhY-AKdoxj4@@#$bV%`f_x9rf7tl12B+V!-AhSAX*w)T!H87u8pB5WKK-yUYpHd!20e-giubM=xgA8@HlPe2<)?&B12jjMIkz^lSOjH%FJBu!TbxI8U=gp}xH}acJ8{C*c1U6~UE(`UJb)C22i(NR75uW4MKS?&*v-gHpaA@bD;C*L&0zC3RBo$OnRZ1{crb7079exXm6_^oP>oBy~vVo;h1>>>_tY!}fOy5~KE{^Ub1ra|erKp}B2-`SW|Im%4A`SS6DP_f9&F{uD(XlRXjfU3SnI(!`CW3xE9|cMYg$jofb8e%Klg{9@kOwGO#U)6rns_m4ejQ8zwYkD;ETl5-=U$qigPztr_ap#C(0`Gog3Z}6Dd>#qM4_5AE35I5)#!=sYFg9VY(dg*x*h0H=gzfkE*vpe#bU-RJO9jTEJu)Hpy@-ylucB*#IKcc|%METZj_Q+!`T-^Jwt0Vwx^t@=!D&#Ja-JhL*{V{~VJ-sd7TTowYHuCb`GfUVrck12~7t~J-5A#uS?11pw{pv)W*w-+nxxlNqyTkgV_%zN+L)J}ay+G_t(%_vO)a`j?cb2jGgZnT2oS-epT~9acdm`o@3?J%5hHliL?r6e3wj?2fR<}9k4Dy&*^7OS+3KUT1YA$@ti@Zdf`>#oj2m9;k3=?Chf9g(nGP%qEwhwuf?>~gsVYutc7};+D!84PK58cIcQdXx^gR3{$!B)zi9oJOwIz`&IHfM9XfQ*hwy7?pIvFc~ml@iUKwEE#vmdIn<>Sg#I)%tk&8v*fe9*>m1MO`B4gpJFO7$}|&y8n?B_Z58P$*o0F)O{lJJ4O0msGp~P7#4OJ(fsNPT6kakHCfBNYtPZ@5q+gYzAD|Y{1u&wJy=v}A8<6m`>OvA+o`YMN{c_qY{T&hUFoskmwAICb%9e-An~CTcTJj+Kh)a)>KLd%f7kNu0uF|^gW>z1f(>tFv;K|mjZ_}Kb~6G_s-*}RoPJ1=HFi9EoWz-GPXWIQb&v;Q0FqJ(3()&#g7_@2DAid0wR#+vKjtbX>0~$R^co_F62wFLCu*xS284vepLeWF``7S6+mGm2>pWuhGsto{zSEkxno>k+gd6F|_mD$2&}=cikay>9x~KpOErNOFvq_(Dj95ugY?)PLTSuT(bJPb59`c{8w%OIj4#;n!|Z56z(cLxytB-c3yM7v#cyI3cUMIWcQN#cC{R4lP>*3fuoJpWy=eYTZr$hCPM-c=k_W4kXszTI@e1JSpks`EnJCq>eg~6Ki_B%ME>FmVYD-V<81H3a~FuqEy^*yj&>4x&c5rtpxVH)WSa=uc|WJ)nqRUXc!#=<-mb*?FRs_rzULK0tD`cv2kl%EAGBugKp4htDOW=hh}v9Sz&0S3JsbLi^R$aP5){iG}IBJBG*Dk*}689=OWrngB%j0$(2LBfZ?6EKFALBWSLbjU(uvF8?uiSJXOtpw*jc3;d^BoNJqmrxgQa@21(^a8n?>Fd(uQNLd=Y5Q})4_+}hjn*v${L|T~fHJ!}7>K&#Cm*9usk`F2_j5St>ljPeW=E#|tr)PTPUwZ3sNXgCHEQ@N4(ft<*E|_UeRTMpt$Rcgi2Jo1dUq1-Ir8n@{H_)=*!(B%&Ml{ifBLb5%sSc$7a*R)PdmXLb*I+$i)zmu;jo`)ac)o_ggT2Ui|Pd~U)VF_x4I%5^+lSxHRm@5!nvaPE5)6t&$^2!T6Tnj+sG|FUS2%+JnZ|p!(?kTt?s&+59+eVG#s{3`HFs5eRwrDo`+${()a}-8WZ{`GqQ$wbbU^M3S$Y3jq>UB)Kd#O^9?JC%_)!uOvZNx)Qc77$w&Y4BB3mR<*6jPf@B2P8_B|qGE1@VYq)16BqNI`*qJ5!w=b7{VT=Tx?k8?if`*}XkeHmls``q`nFwGt)I*@~W>bDeUbdD#i40K~-=tREYUvHXw#vktA753x$iF|i=+V3X`VbJxew?0-D_swdIN&PolqCnhz(sgeTa@x2Rs%J0M^%XpMjNJV}{G%eD6zH5*jy

      o<{T&UVrt!_0q2+XFd?W?VL;|yvltjdd3WWOuM={f9#zZjO=P2{91{es4tU#Xb1c`youvqktfV_)(nb!z*WD;IZM>h-zGg?Iu@?=gL~U+W51uJJ3l4<8498Oe>f-l*no8K0m+_7U?{cd>P$fH*=ZW=s1gS;xy@l>Jm_QGPrHT^jwZui`1Q7?2|3XRtYa++1dpet-*iSFOYAip`x=-58ZuBCpn@J{;n(`D^NcCnYx~H+-H-P%Q`TR-y404o-*sXy-pBL{dyHRC<5Mp?f8yc84@92V4mfBcn~>}@8x3`31;I(b#-CrX$haDBD=a`A%5%MwL28)_TMh%?*IBQ35f3#UuN_o>SNyl`Mc>r)C0BB^#>;UQXb~b0Bdo5DTPnyMRu1NiiKuPp(4LixMTu7P=S-o)H`4c6U$sY(cfuPliBbcgiLwKiroiZjSF&lMkBJ+)`&$mg(mo&dNurM>GORvg(UU}*3wE0eJtwHRTCMR~Iy65!o}izFoU+^K*WI5KII5BxmP|Ldg2FOr#ZaVTe!~+cPY%R}LM<1IbZIYex_5I>k6I^}F7haYOP()RQGdTJeOm{_&=W47ATRy7-4e#*4vS=+qC216_WUbp!Vz{|>pb4vj&c6eou5A0?+G6cbx0^n;JUY8%g1C+`$J9oS4wr>|JMimdKfLAN{P30@&1jUe>6>Bjsks|2QPbbFwQNx1;Zv>@j&$Z*Aqb>P@m!k{XfajIXTO;o~}>z&JJ~x;=LqD*N)RM*Fzup8YnGs${+)rGc7z6X3!swW^GLMiM0X3bG2G9&M}RWn-wQrfxBr}OY0_#(?QVa2xp5oNPJ>%znq0}nt48#c=0R{s#c$NtK!CZERVj^Cyj@Lm*x}Ss4V0O<`-gZ421sK{pSM{ao*nDPLOuQkf}y{cGMn(3X}Af%x{e%xf+f=dIDs^a9>UP=1}xZu1L&E}{>b+m9GHq597*gzlVF#J*RQRVxv4T+Y>g5uocs@~5Cpa7`N6I-HweY{vNi@GNVVQ$nSXP#UTn4muAz70~}#IqH7gy_@=%X}>ScKz1X{U~ygYZiu!-x^JVriy?&5|PM-o4?yTUQLJFwUPW=43IA)H@FRcr$9KzskX;QkjL!HRTnAEhL`+|;Y;I?-ziebt_rn*m>jKYJ}o>q44duCE4Fn73yR!FhHc2@)KrhUwR?kc?+UlHmB^FyoS9OV2SG@WjLDuEJg+1^Z};&z~Mpx?QCsX~5Au^l9g2T$h-WD1C6aGM?H=UJ2UU=s68}?^mwBPT6T+`ay0d=3{e4Yf=NMf-H>wy4_=M8tS}svU?^=<5#`>Ia6l{(ONZVh4ocwNfuRvBDtax|yPAdm`*Ef?QX5%Z#aNumk$-kM%Ro~o-a5o^q^zwdF(oXaxVjp44O{bg$BdO~HqH4%bS0+|@%h-c*(rDF<;{Wk6)e2U1v8H1l5VE3LU6lp>O3Sz*#s9D$Jp63S9vX@~pchVGWeEk|F1|=@2K1}+8$zM&qmi(s;DzZ=3i4N>HAWtJNC>6P)O?{ue4UH?kaSgqwnCZ;b8Osb<{kx;DuLS*vIFDN*WDc(^+^mKS(XZNnm#U0T+k^Jl(-&q>@cz3b)lZ(k;{m6BPU^&+!gEibm#R>k!bqT-J^bLjF;`MotD$vLJwtI_Nt%`zoua;GKS)k{nbLqXh>mCQLH{QkF+=1Rj%#*(0k_=qOtXbMP&~rZI?_yuKngpq7e0GoN&O-&6;v*e&Gic98v2=48?no$+?^#=d=^-O-o+EVY{^oVM{N52dhSbshVBNSV1K49VS8kg0Ud!4|3vhN7*|A&ip)~oDg5S$g_k+N^b480h8H>OuVb{{$CqOlj4l7P%wIX?u;|?hGU=d(w)5_NK4Utybn3iSA17WAgt4KQ!iA&b!}xX{JGo|4rL#WmBOm&&PhA66JDo81F^r7EQax1Qa;N+HW3d!owbomDv{rcTfJSeKLv>SV;VB(14}$_MQ=P$f~{SD@}+O05AeF#Y;d@l0X`qh$&NxlOF0Nal{@!kDUj+D3AI#Qm#W>qX|9uIqkAVU1EPwYJjMGDTm*fOfA`Cq$tIFDqaW1H(@vDrd!u4tIcio-nEn=dNcCV5k|JR4j1ii(F!oSQ{A`^&q#;u=_Tcjmq*m^mGhp$tvBwd^fd)WDH)V*NOnZe?M^%$q;8q36sAN`^HS4#bnG>r2~^;FxYU18A6w*GVo3Kx9?y+9+7jaJPOT5#!wZkd-a>cPwle^|I(*jqwClx^&ndO`_Fl+7_cX&Mkf0T)QeAsFu^8Cry`!Mtz@6HIpG_C9_&<2Xgu3$T7>3On5tBeInKf{fZ%xB=*h57KnK)RjTMeCo-N1a~r$EmxDo9rQ0JH`PzHmwGM3c1)>eEg)DLj%DQ1_3kIQ>NqvQi2z>vH*4#Y77YT=n0b2aX?|&3@Wj2q6Jv*uop3MngXASccyzm%CxZW^8Lu`Ll~|#ya)hKS&#E2E0D(*FKiHq3x_K%FUvxQ>CQ3l-)XWei3YvD{9bD=BOlu_=X2*o0#J@Y9NOE>V#3@lP(WhzZ6+%9RdYl+FLew!daeQd_P%{~fv?@mc71t8}?rTO*hd>rgf-?5vWuD?flyW}UHLn)xWR-xqWE9CmRLJ?uq=OdXZX>q}w=wlI6Kc?%YGa==1(AMlCH$KUl97uU*rD^IWZ^h-MJ9j++?x}`kU+DgdXBKVnF8I+Vgb%bz6(xx4Q3)gY8oeao6eg&F=h|nbkH)hJKRSeBYk>(kDC61c;7e7dsf>Oil081OH%hug|GD9hRLKExcaZJHjiDpsjRFA06DC{%Ba!#+Pqa(*{=g`aMImTmre%3KH}buN>WY(gK?o1YdmdK?KvJ@h6E^gUk2E1fd(aUeX!b6#8kJ?9wb(vx#C$xy~*eu_fQq!GBuCO!guAkJA^4C0#Pq-!D}lMsB135c^=lk1T-bbKIIvS05@FE)k{c2p?8i*|Cb^{fTqsns`q*-1mKT#|`AP@9Q{!+PvD^bo0epM}9oYI2uMfZ#CaW=YirfE2bi%;IU2D$nbCE#Ci7ENE{G(nw50*p|0hFw${DL5ays?%r=hPMTzk;iyR4x`oaTGSfeLww_t23GS8rW&a{4{s~5PFN80zz8qy=rrJuLMbw6qRC^YYIq3x^eXTkdql!s|n>v%&J%k{@`r;*Igbo6fru-Vg3R6AnXzt&ih(;kvaIlLT6#1n1Hf6wT@*5qAtH_D@6yXB)kawx7RcIyM+y}e+X<_s3p#4|>aknFK9im|<$rsp(LP5H|#F`_&xic>Y!}+@Xa{p8@o*SF4huS}ifWtWsbMG!8pV#18`?MhjeB}aqtfbLf#CHn~#x73;FYcyYzZx;lt*^bw>=UVQZZe^6P6>Tx^7Za@4PsINm9Y>#$ySQz8*$ZdrR=f~5uY>UjU6K3nGsp|%9tJ;XqMN^P<;{^$t!)7yKwU^p6yv<`>Ob+SK#PKW@jTA(``emFpx128>x*HPZH&tQ$Q)Neu=dY51BtFWpimw0L0}og32W6SG*N2puUBnkX=aGBQ^Q&y$Fk{TnK5`AcMSi!kK}dNZ$Wz77mlC?ji9X%ecp_-8+Y5(~#rSD`@6BU?alqlla;@OS>knQV8wl1;go@_J`$i80E%MJ}n^)cVl}4M}C>$2J$i)TUS{&O;fsC>x`k&d5U#nnd%KVi@o6n*oggp53a5?*y6OicX@b`66+#(m>9b45pl{b)Q?cCfbWk;ChsCY>pW?@oa?de>LZNh2rf)i1GG6_v>}!cDV<)G^-iGz?p$>I)Zp^ID3#~HfgU7oG#atsN95{xsgS>M!*eLTJ+pFvmN=|9`%5UIv;rBti-6Gj(j;+m4k70Fl3Gse6%qR)OM)i**;#x8uHLayqbxw+w721Fk`Sn%K^`dAeo*X?m>10d!kgz4aZ*EYGJlFURa+Up}5fc%H;qVaR?&gbJg(Q#zhsu5ObbUFRzuV7})8X$OHE)Ghvk=GKA%eIVvenbwP0cAxNJ8iQM*T?e{#}2q4!lGl=v;A0y`6cl5@<=fttF{3YmJH4KOM*A69uP7|N)mlEV{Urmba^wWX*c2R$D41I}%<>g$`Sqki|+^uj^1bvBCud&n+3=YH^u@(I9K4Yqp%6jLndRoKHDh|;FHoQ+{x}*i;f(sn#a{N}GNLL5C`IoZcPj6UG6}8)(cz?}EcczTmARykq6&2`X{l@9GHRmJXapC475xTknVqV2-)>vrStl=!b6#ZwX9Ls3K(j+)DJa%Bb54k_}Mo+2FAf8h3;ai5K6((upd0e4WAcj=Po#B~phX_PP=_64z?QG*>$cn=9A@*&bd~P}jl1;a04x;B2`=n%9-=u)o({lpbPNFAJHC9es&>Z?Vx{KcM!E?`uO?)y_x(-mnZz6kW1FlOvKeVp)gob*bs)$E;KI^-7et=!VABg?J(!;p!{N}JPOx{V2(5C;9;4AC2|aP!t^Kd@qyk9GPf*cHISPV>?xB>H3+R`tn$W-NYM~UL0(bKaTNOKYFQk#y=2jk4SzNyp8-R1E=4U3*o@v$|p6k8{<@E4Ey~jF&d<|f291a$2dn##XCqN@j&cP&&y(*M}|UWCu&oGs3R<`v-LMEJP359B1N+1RvFN!pwQ-W6QVcH2F@)zzW~LYvR|@&3koO==rFaNSjx#SWM?*W5FMfGo%6aW9I5jy8JHB(Sj)y#E%Po=}o7xGApYSuuasb2iyo*ko7zJ0V0UW`X%IJK&cH4xt2?U7pg34MlmAAY$T4#Vfu;@U$37Wv_a=I<|Thyj6VkrrEC|3yyxJ+N{oLYzyI?D|{2i#*o7_hMXc8t`lyTop5mLwkV`z!KXgaW4+N_vx`%)L@0@f@m6J$dN(_aMeW7RVGx7XX`r5xM?;WE+;65p{cpvhir@9M@((%wD{vzxBU)(=@=i=;p;9?3K^_|@(_!xP5>4WEG%g7MEdAr%q`^brTQFhgta5rE<=p8fO|C`|7PKJ$!@Fv+(hx0t18_Mmk-ZFaI8rrNc9I4Jj9_4J(zT>1EQ6M6B*-pXa;H5T`6C9+A-~~RxWQb1vb7C)ACFRfzhpABg-ISbv_KaRcYpmSaS|A-SZp9WU>+Ll*GAI4`V5%Qd0HW}iq7|bZ1-wqGJrtCzc2UY;=b0z;8oO9f)#?CXWpp%&x9jhjbYb+a-mIELy*3IE{o%}pkxOL6)YqpO!FY_f|K$lh_dMtKCG@$34Sc;Q&KIwR*N;c;{5{w23iXp~rm`-hkCp2Hx22g6?Q{N`EP9t8ckqC>Kro1!vz+a0!McDOz$yIZWdv*w*t5M@4}DCS7&r#8@auzr?~>o>V=@n3Mn@_qK|1H#m9rPni--yP!YSzjL0gDZ?Z_5;L-2@iL-%rm*!t&^+9W9^H$0#1jHg3OSL8E-A|M*q(uBgAxE^4WvKU_%YHA{a-f#cnGrqymBC%j7Uy9G#E4Ou>K#dW)!PCa?n;RyMpebcv$ab2Q60^OX`VDY(k4ovZ|>zS&q(^~YFeU}+odEX|(s$%a=Ycr5%=*_DAmLY-CQW2@6Jf(}AZ|AKMul*Ucy4}CI$X7mW&imnY8b*ycayaDw-}=z^#%?fiLg*=X8pcWVS2@1N2i7W-lz;n#*N^{UtNdjg1U|LbbbSoaThz=HgEnu9fX_~%EP*#LPU0M7=Ug=Wx;s&=xD(^KEB=Q|^>6|l-}6IbXFYPy>-+UB)}?~fjlD{8bmyT&Um?xwBuF)rFaLW9d6?7Y!<(qjhp(&-vd`1a3)nMKCjUI$5wZne3rz%KJSFozBXwujNPcLEq^tWu5p%78R@$$N8QRSEL^uAin2C&}=8e)%V{&FEJbOQg3@-#u{8LAU!^4f3SFvm18@n!$Rjs}oNw0~h1D$*}$8%^UVW{W^+u7)SpZaNZCXq2me3(ai-~)_#lEbM(Jo^?FGFv=$#tFTR8RL*$Da>4w9Vzj5F5MbLBBOBS46TN4enIuG>BGCUVKv0r((J^^Td-$EYv^B&u5ch@%!F36n-=q_I0}pW%IyD_-$i|H?LDb=x6%^i*BZrgsbk((r1u4f@=|9=70$HUEQ;LbW8D;Es5ej_YxS5}klV)nj@zCT1f-Dk(`SC;xg^ntyrd@rW*dbhtiB>A=AE3TzRzDPo`5Y2$SK`bg&XfC!O{EFH>V`tzqfhdDgSIbG&a63OpHYC*nW8LPwMj#@p-VoMc04BafdvAr4|scYjY6pYrUdAj+FaazzQSBpL!(ZB7Y7Gi%B@ahl8I&GpmrdM(=m?DD;BnD>5qj-N-Y}I*AuY27;^fV@t6aK&st7Eqfz+8u9m)RTBdu+WI@LSs<4YBfn=FO@zkKoiZtP$SJN`E;o<^~>vJF`)ICIk8ypIi^bF>+8B&!5NKTUc-`jy`cc}soE7TK+N&uqo9wu?U-+VM}0rLUwRYE!Gu2MKV^3z<6scHURE)X7lz!Kq{q+&d$`Te4{{0)V-fg{>aG;qI*HU~#53T}4qcJEt>@zkF>sD7yUzk1je{^&V<*H8YO3`vF$1;wu$X6W+7Se^ysQ$Mfvo&Gy_)fqkEUa{NCX0{9<_J__)BR}$dYkUNs4G?pNh0XBwxgOD-Qu>qneKs#))XIqKj^8-{HZ|EBS~<_Fl275fJKdi6R9*^%RMHgJrki+u)R|S=%x;InwnW)3^INg!*6>oFb9Z}q#x2Eoh<>lzPb30==3|!6VaRFUb8FIo=6n_16m@p|)1cUDSh2Y|NIz|d$RdQrZ-4(mW*IPCrOd2oEvZSndi52TykzK(_rtv72<6`=oAuDiDG#+L+`5DKAGkR2AUFNqu8-FrO^GV?3TuMFBQUaz3T`mJa;1(L#4K#E;^By-w&e5{JV-u%4EY18f!~Gn+g?OFSqJ3e$@KgW#lgRIeocFPM83I;^Mf;Pwa6iyWil^bl#wgg#vuRB48J?fAeoxrb{W}hxs9e0Vl^c2GLd_qK#1xqAckd|(!~H|S)VfFi{*mBNUB1Do1IUT~17GShp?;&n4(kNua!t;)QlJO+Q(C*{eg2oPHKr=`V{n_~TT94j=k(m5iFsW6jkL>!zBt2`#M^E?!g&48`H(KADsLe6d)EEMbJDE)0_1f!gFr#^+nvXwc&;ihU$MFOV+0Ui{{;{6dg|BFC)>U6Z?Hzek4KN;P;a7IlMmd_-?QF+$8vVfb-qPBN!*~JvCmI0mBMb+l!tcKinebd2^pO96l+VN?JkJ|G#C5GpyJGh{kXS=;jV|#XY;%Z0p?p^ENLC4yn~r@j-4$99$;`!q0@!nv&k1iLN2gwchBsL4D_)<-361K@!qsP(xHs#W7%&fWrOzzfl`*=lW#%jV*+^>2Xy@+VA-)%+as6L<)Jyq&ngVXz@^?zJS*wWJ>?CWH3A0`f#|EzqlI21D75{-5Y?~ltu8#xM>j9P;8Djz)=&!6#z}EAy+N)-G(s*h2IBm`bOi6Omc_&!W_lW0ZNJ`cHbAc%|9$3BJc~PgS|zc(@(Hd>n{UqO3;VuU_p+ZxAEV{lAz&y_t9g@xbGxLnlUhqN~g_rIxmQxBeZIDsaYijRd2XSRPS+2OY*>-=DinU2RfvC4$MZ+ANq29f{ZTNOaPNyLH^yVS>bqVWISzRGo-vZ&qmLca_@kNWoD5f9zpkutM9+ydOcdPy<^TTOP9P`x;hvkPfXC9ks=@Z?4=%*uUnU!PQ=Z>B=76sc@i{yD#f3IMXfr3SJ5wpMQQY4f7*8LqgHDXIam!SxeL*0kby&jv^VOmRK>H3dZzD_Gm%})X6rnqazSC%evox(%6(*jA*T(nVOE(tkNck1Y#0lzlvP_*SjZ#h@XbyGps0h$shbD4C$8WT9XBDl;0h;vaXx_Jr_zHvMqYJMPnl{{`Kk8z&c*T3h6YX~G6s5QJU#yD@7_h!{>j|71OP6yAgDqXyu=)aczF9u$zZMaz;g>lME-qv&7n+SzN`{(!&3MRLP`6uc6(_XpNW+uu@h6BzG?u<*(ucBh-Sx$Y+fFya@G`2Y8eQg&?8kX9CgOQff;gje;jjDRCBVDdQ>sxRL{fFomcGkxSsJACiY(f7ijQs0tqaO^Tz3&fod^x>%{k`v6ok6UTv^jb{$ySTJfS*k1j*Nx!*xgIkuQy-hJfh8QaYaeA{bvOmlSR(j$q;4yvLVz|gvUrjwN-H-u#ZtC}qFY7OI;Y%CZC4Xmw;e69o&sE5|1Q`!8s+)tB=Z!k?QOx_AA7JPCJ>vlDxss#qeZjo1_FwY$ZkIi2b&KzRzQsg3zrG3oC;b0fiBePZz&qEXa!Z)X6N5k@8OE(N@{ck^TOtnXTT!ZvD3r2>#rnnLIjQ4|&?dLsj7YDu>3~zIT#$AJ9)G|#;P+}GOjwCbzMa~sfYSWwEog`DVD(09%aXwTm>$ccH7q)8vReBUshc{83@68TXdhl1hIal_68Z{%^EDp~Cok-&G(bmhQfwsz{14s1gSg7uSQJDvLWyTAln58%+a)&625-d{6nWLVAI4{~B(iFh_5&t9tX*mqqhsO^(5?LLa@rU`st(;ke3H%UMJEt$~wPFGx-&k~OVa_>jM`8&uz8+;_|vr*soh8}Nx3(?bv`oz)hbfD^05MKg%5pkUU`#l9`q}45dG$P1<@0Tx|kNR45+Ejei=d6hySChQ|MoQTllG7EB&b%Umt`0>%-Y6-JtXf^}*5%eN}sx#!ZTi4?KTnykQv+#zWMR?hg+F)+4L65}zUu;@60-Kq^zrKK<($r?+VKg8R!9_$p@TuBVDV;}!PfGDju}i231Oba`JyzKefk2Aq^Hzsjdyith)q->SE79YJJ!X3J7FI$zDph^({s1T~_Nat`B+dnIDU`pXZN25FyVv&1-;F&1jBXAcF+ThR>P9=g|gzsH??yGWSu>D*|&2jdYxrY<5R7Yjd1N_fN?k%!xI3SD-h`juqUXqXJf8QR?yb%Z+&9(k6;4L2dzDR@4UzJUxx|G$-c(Yr<&iY|?P&487CTDL>*A~#$RCT|RLg&IRWeIGUSsBY4O8}T*XwElY*=?;th+Z(CvTdxK}bV->}?FjB85p!FY_Ju>rqw=tB5!^3om{@Z2c~dlG9{9PB&)IU3J9Jn&EZLR-@A%WNjb1ys$mc$&I<;%20#QG4T^Id|$j3|ICe!i_{(d)F`?5)5wWT|`>VBlTRc3;G^AmxR|pywuraU*G^jrTv1Po6w_Nb<>BYr#yhj-?X(tU*h#FFFM%f2U}mUTnjymzGP~3de>L=P;maxZ^-cx&rgZ{8TIFpux@8U;7w)Z`orskHwwgozV_&noptCxItRBVADK_0J)cG%K~7fX_utW%4iz?vEaf|pGw9t;xkvrpA^Nrj#v-rC=D+v7JsakXkL4M9;kra0*WW_6Kz$nx>90d?Idm6_Ud*|H(q7X7j}^!(1?Tge$v$A>GH;&w2hU0CG_>_P9tOeJ20f?QZ^$?N?PTByi2!}xqaWV=Mo#-rdJM!Dv=_PYW^`;Zg$r0%KF|II7WLBDc5@-6inPXeufp!+oPW1(x4^|eyrzKUpY+7-I~X1YFi1x3m5Oyn_}#1-@_LX)>rGJz?DRJDDB|29Feo1OY*%%EQiFWzh0x58*c51Odl2iaj(+vz{_U6I)g;>d_nUNenst)>CS7wGuy>=fTjO2yrSa28BtJj0hCDF_$5{$p|Jz5iCn6PG;6C;7F5w4q{j+n5OfS8_$;Q}p;xyhT{!5;*Tz>$(e*3}9@+ER&UPI%-a5yKdx?a-`{R&<{L<>hW7hbPzjq`VI_wmcOswg>m5hS&|YJUflGC`l-m92kE>^zf>&Et|1WG!n4;tRm63-jvrQ;tOd3_##AnHm#(|M`oOPx)TRNt72bxFENm!Hf8I*P);AUu=C6B}|5);?8$jRmdfuFkRJV&V;su7Bz?VmM(I~m=8hh!)~;GzjkzW9H$kE`j$NL{;$8EHO85%;jp_;KM>Y>FxX#Oi}B=T9bbEYdpPX6p0`wzZl1z}m(gmX$x+}ssvwcE1mme+sjBc&Jq~niCKy#ikz4(|_{q>U3HA&tSjjPBoJ1a8&a!mi^!u?@HVyfRYouEug$(`svfV!mp-0s{ZWK1O$b_%`uamp!>Mmc2-WQ^n`N8z5X^ORp`y!9HXMI2Zb}$HCZ~36h;=0IFC+_ytJ4ZmnYeOeXO{YaJWMd-T|1ugbbmV;Z^R!>&L|#Pwop|`zV;4}=g8N#x$JwR152S#@QJ*wt5$i?%IZ4YXQH}&EO|u`Xm;TSk##CFTC#q5)KFX$m(D(i2gEgIr|HGOIygX+z(FvU{c!H8~GghaQE02#bu$eo8s22*p2+F>Yq0Gt&z~@G`0H49ptlL8K>Udih+Z}UBxTzA-||)=;rb|fi^ef*gNFs%|8V5=cj^@r1gGdVe}=ga}?+Dsw3g%e6>k(#9nCaG*zR9V>cwy(0(gDIJ?b-Xj;6Ppt7t@dV;I=7a|N57AGg&3n6pL16z9ckP?VRazcq#`{LVH{~O?!93_i13U~m^7P*i#M=m)u1!9_Hd|wx$M_KW@*_<*bf%ALYFrcfuB<2KPx1sv;*FLse4(L%){O^Yky~u``5aoo+#^_5se9{M(s(QjvwT9~X8^~FUYoqr6^M#dJ9~o1Zpch?TaWo@IHyDy7bFC8&BPZq?vTTch^rB61@9FwoIIl>(r$C|pycu6j6&H}(Nto!A`ou%QU%tW`H}t5RN~uEC@2Jo9vNf+i(Va_15AJYLpvFP`9k1wvF2s{K9CK>{#i9Qdd~g2plz#@JfVU;uAFoS?{jg7Ygq*NL1wFsfXG(7&&6%qMSi3PLz>&nx@9@YRaUA6n5#wrYYD%J=W4va&j#KF<3g%8Mzw$UrR!rh_0#0ExLZ8996xF@E{~qWw6ntEQ+F~{Dh7}o-XYfoZp)*u)1mU!iR1FM=s6V@DUE+FQ=q?g@cURY`b=h9-xrUsSx_!xdPpt~z2YLrMaiL)UO>!~pJ~AR)6R9)_ycFg$j>9Pcz@TCUzH2iA@J(b*g=jP$cb}dp6UqjZsMKOGQ)K>)*q@7V~ByHCq4>uu;RMB>*7y;yB7~CGhLD7yU2IHWu3XmlLEY6oZdDC=rcs0+0;Mj@M@soYGpL~OyrWaN)uNpFy|LCaWxh_L5y-#nKGOOx5}*_a2KK{RNdUg_Oi?ymKZ(1{3HO^mFwgBFkvNKkTbFTd&7>PFMX1Eo(@DW81hxO<2(fs$$69ntMo){kr<1IUD*wbQssJicb`HcyNE0HC^%?;2lL-Nk4?rn&8i>q4epBq=DfZu_e|;LlfKz?KrSy9?rA&x+fKL77Chtj@RU&^IE9cNy7FQ?gnvGdPX%J1vWTvpvFh*%vo{4Kpnja3st`gyS*}@pY~P*?Ao?QjuSb5!yRUUZBpY6ytA03kuym2ni}P$6)A5JHlWr^x*>rxT=iAUB_oN8EnrK4mhVE*RCAgGaR*QVCdlp$PDGP}Hn!+{~i~J7f5`mHVT*y7G%a}ig-bMK9)N~=lh-j1#72)~gt32gdA+}I(?vrGB$b|V$`+Ib&uN6kXM?Xua-7@H1PKB2RIFh2ltLTE%T66R+m2D2UjYs4D>r0l3-sRabQ=wdy1R7FT4R$5dmBX|B@{WwlMI`}%Q^6ufrG8&7INyZul81a0j&G2&#qjG_us|M_AZYc45_O6&(aT}w^+RADvP@t4r$fm@p*LTZc)3e`!jN*KuRaL$(kEE$3XiPq5HA4{iVyy$d70^u?>49g2%Edo;Es8%srYY`tSKpVlDC^t~lq0CKBXEuM9Xq7ms5?X1{+(2E0-D?D(vJ?i?^^>p7K%Y>2I|_i@;Y9!2y==s%ecpLe?z>{^QXS{EgAe!saG1p6m?N`}MGmy`lXEdCndw7l`62ING3AZ2+JJo~`xL;8fg)=~42qHruUFb1~-D4{RyP%?2WtV#f)uJH(6-KEV&rDYE;q<~QgU(_KU^r(1;m(SC-k>GP_y>M+E@`B{89b1MdaA8)2O~f1hs^d%W^6{xG2qiY&z3Kdl`uzFAHxE==x%h6Ip+^ztj?a98U}{A3z~%eMuX%0R&npxT0S&iZ7g*7Y_SulcH}pk9Ay@e|8GYnitb=n3hhl)ar76a^4Ec3+vhZ{51YkVG$eu-4M|p4+m%QDc6eyj%#ZgD+SEkkvS@d6~LreB9b*<0HQw~){%llH`P4&f@bqVN2wL9CT=H0TO_mR&1m_6t}L>=Yevs{?itH@fyg`U$BSK|2nW)K{_>N9_mE+6d83(|#I)o_S3zE`Lzj`y*R(w3F|7zv)YqWk}*)Ajk^`C@X}WDLBkEPE5kg7;T!JbA{=Fac!m6)iiKj{L#gf&#;i6woku)DgaoZobmFr6wG`>5!fB;7|86x<0XY4kaBmpa7FYSE)$}-5hf!o#qR>vViEXFB^`Y^S$!-^?{&Vu#51GGYmzqFlA2&no14^xe(tQOlR=^dZ~;DEGxpHf4Rj{Mq#`^(T|v0FADB9-fPjJJD1G%&WQS>9Sa42o(OOr!gViae7ikQeLoZV6wkjR=k0{S_MjBl^CIB&hX#zNYMA-}{~;YT_@pDw$I$hUofY-Vv7mtI;VepnEBZ`JWBr~X$t+;K{34uSSrPVK);kvYZVD$*voN=okboHLp51`&}QIHeg^1!VS77j6#T0Awxc!>9#j!q&Fb=U(NFrFUA)}k$ZskD3&**|n1xan__`*!Mc!R0QyO&>7MoETr7sB8*Mo2uSj0TW`S~A;=<%o{C;1}Tb)05JQpH9S#<8rMehGNhtta<4Dy0Be!J4udn$1K8&+Bu2_LNY3R{$7Ja;oV_W4ksdk(Huualm}B$h4NO&+WPU3hX4YBwAlD@m1(8+y^yYta_UYk`Wn0ne)h7`j?C{rja1Bd1^}_{rv1I68N;=pxhP-b39;qjzX|%a%3+5Onah@)*luXOt%YToY&*8P8v_S?~8X9cg;*0S+Po7(t8q0$39V=dOtwfI^_C0Fqb7AlO?xc(|!N(6GpW~K$E%I`$1u{=#B0OV?a&nDFA9LjWcjlQ~DmWd!xQclR`q<;A@fN`XB%sZ&{)gv}fv+CKd~u+FPd#N;mWR&A!uLJ;#hC@&0{7ZJdZ3SO;aJ%;A(RU*PLOg+EO8$!-*DH{_Ob$Ks?_yl)<93Q9DSp$Y)}Gk3x@X31tSl;={n>~{d@eypy6V50`t-txnB3ICB=g4?-$-$LztId`)mCt|F{G=A|;dM@Ed*1zvbeAbFY)()S%SR5n<%S9N5m2=|GGXk~Tt5qvbDB$RK;?Yu#)ydKxj`u6IKwyje)C)Z<3}^52(JZ#i<{g6maf*#Y#olkUsI`n>aj^SI(AjTLx3Bip@VDXRC6$Zf2Zd5N6JTj0>8`qJOA;H{zPCmwZ{v9?cQ;HUY!iccqy+mK0(59{Kg^~T!^wra>jM8#Ajr;{LYk7jGE6x|%92QIf%O4C5`@yxBKbpF$7f7gH6=l@%`yBm47&%$wj>kQaa%PnvH3c;O{a|&fMo!dMw-si=PRI7cq0V&qRLSalUv}g|+%3CFkV9YcP+=V`vn>2?F6R*P`yVdm484p5qRz%r9leOiYwgsE0b}%*l)VaFo)u9~aWX#@)K6p{$nru??2|U?kieA~fJN6IjD0>-rY(;GLtlG-95YA%iI)yt*P@yQ=a{5s*U_B=mOHkw>^PhYGikr7#cI%h&XgH#54c?bUeftXqUid1dE8z8=q+0m=*b1jJ*2CDJY`=uu*D|^9Erge$;hv&tYBCx9uL(A56C3^Kz?F>)wTCBN#M@>F(b|e@Bf*b`JrxED%5dIrVM{WPV`5e*C4@e#xJe&$>=#OYrd|Sj-vq4x5GjieMW(3oVGR#Hq7VMykbCau}N=R@r^YXcKFWKYSoS8(MYTsPLl{$0ih)rT`Lr+WBh|3BB06XSuHo3x7&?{CuC(7{hmqV3zv=Ob^I+F`^pn+huwXBNJx)72*i@f>(&1&tP51+^mNrkp)<_SsobcUo3pW(#^qK+W2q~Rr{9?uh_T%{b?%CbPc@nXo`UOZ1E`qH~t{NKN;W0>DH!8CM;If45A3_aJ)W{tjd`_5(?4&D;@=HXJA6N~4Jdww<^9~LVG-&f4<26o`}xtfnxwofF0#8m0~h!^NlmrQnPl7KjWb5uuzj1rcrhe^{QQB_OMl_M5Ro_EK9~gBN0%x5dxE@WvRopvllok9S?IGxD{|N8R-w~u)bHb?%U5aCAW#0mt{wW5Oq;K?tQxuUUpbQj@k}tIK7cFJ-KSa7JX@wA8@RUz?D;f_oa}vnJg6uS4o2)H9nwU_jB*xKhNj#e$KV``wZ>%T5H|weFG;yY!G$$b&!5!j0&gNU%YNFa@Vw62$xfzKPZ_WwK5vR^(Zl`z>9L$cVNgNx*>(sKZwY8pllC;GcTqi--xT^Ul>x7db2tPRHkeb%+?}b@rSp*y7Vg!Hpa;>Ju-zlvHr46BMFHAzm=QRw`iSg*I!R6Y>`#ow6Y9!U1u2^g-U>Pp~e@@P%>{Gms#zm&eH-kGM8QZgtPCCyR$`U-`%pdYU4kYF3vp*hvHTL`c#k&4xE%Tg5!ZTTnDp|b1E&Y9xGK*fLLeR_7J&($i=o&4uBHfuHXZt+}Cdbt{LXZcfjGR(GlHwczvP{ZI$W&`0z>uXn)2w$dj7PE=fT@L|d+BFWJ0gPjC8Yf`05D->H}r5DKf~LFltM`r#R|9~;mM=RE)4lKKS{|C`-WKPv*HhyaTg^hvbQ&KQn_e!g{WyPhM@ROhdETr3g;PhPz$JAEE~8Z~Oa{O%RU$@OZTLH+Q$1(wR25`pMX&Krk(vN9*Jyl_1QPSzb!98{iSTxugt(*EYIcTx>D5n!55rC+>{_3$+!Vmj@*QQ&d>`di^0q&oa>4~-w5j)5eFeY_VMP;dRY`;}{X9Pr(ouaPLU$SFRqQMHf{|O^W%j!uS+g-zB=NP58PE8^!RY4B|KzCsUwyv}V#ri+s@gL7_$^%4Ed=%nnja|r>5Zx!;dmLSg%=XchHgmL;7sZC*hRBF^t=~BVFaD!-2^cMB=p>Lf3)kJ_iaX`Br^;I&i5!EET(R)7?X&3YanycH3GRigcyN-NyUZUG!HdhF2We-fO*~nLKg+wy$><@z>)+y`cji?uW+_dHF<8YWNH}ERCfchutTplBb2u^?4`X{I_d}H!q>~IvPuBk#1xl7;wKJ&P54Dh{TIPWMzeZF*YfG=M>u!oVVkG9BNf+xc*|4k&q?(U7QuMQz!5$mnv@>I~fC23~phwEA%T8@v}meT)s-Yoz*is*-X^kpz4KJHV#br$tgk7PUa6v9A1g>Uc8G}Md#R35R24Tmh#KPd;tP$&AQ7pO*Xoo$X7R74l=?PMZtda+IyR_QO_+3YHLuA`QN$7HKe|f%cZJ@XmRlF;=?(#V$}J5ZMnPpQX*BNqv-OSpI>m%_=Hvrs|)Svk*eWo<4ELaQ5Ehn0|X1ifXv*LDQMx>G_=Dm3vrFV{$3`79R(4|HjY<}^}{#M%CWPhsJ3=daDAix6I4{^-K0MA-=N>x|p!PTDt&t@5>f^)nLgt*mjFk;eN{K6p4!^2ESZ?_)IGI@I}xZfeNd#Q{-QJ3#8|?Hu#Bj3Jc>Rku=2rfrdPI%+z3A8n(6-Knxg4YtTLN5sBuO0b~8;C5?EA5zZz2{xGjUK9eqbLP*aPLs|v_L?5-+#LqzJRhvtb`|ftebdnd!L)FQ2ui%!D}eWHFlcM}vn>J~-wL$J6`;-@?$_tdih@h0Kg5LFqaPuY7jK5y+_qzvnr)ma`uQQk6gM-DgQr2?CO{f_rg?6lY1@wknEcS_7PT5Vq1fq5Zq8^j5Pud|_97=xMSX7{lc52(^=^9DE#!f#>zeP{d4#}mp)Jik(ddUbfBw@wjI)mSdo%j^x9UvekIrytuocidPg?gIEp?;2*hX;bM$A~~^NeXwS+r~vET7$@m~$0<66aoDuZn@$liR&MokgE{AEG|@TE)R-Yi%oMXY|R*Px+hxdep}$j-ki{vmfofORY(U^xoV#{LhdFh$t=x7XQzWj?+@1zv_i}CAr94Cj(M;(0vCQTT6^Q{H&Ysp4h(4zRe_dU*h!64=@iK?3yYL`Ucu@o$b3qT=EOpg6OV4YP$9+TZSic3^>Z3S)A2uf=k4-k-ozbswY`-7WYP2BoZBfzR=NmjlZ>gSHj&D{x6u!P%2A~*=wwZ0603TYRPfsBqS#m&XYX{Ks=<8}&hkT?xvA%ndShk*jl_yDsV>pIoHPY?6Vy%zOaHX$>2~$5hqqRSxp90F$!!Bdt@WI;MTlg08Ng+JgbzDCJv?>r!0&>OD-jHh1P*;SBB%3M^`DHmVGVrTFJ?M|>gINP_B<-lUa65zIuDrR>sxMB%K-1={8A|-{%Nz!&6Cb#kEegfH#_s9ZeC-supNc)48A8!i@$5CK?O{IFpA`<7U@X4UL(?C5pe}B;s>O5;2i=LaapHs6P+TRQ#SIACkEIE=F4h*0?8*jzy-|pd8m1e)+cCNvdGNgV(4i9)M^lTy_Ci~}}u~gJOm*nX5b4SDR8zt>Q>+t%4jplFZ{V|;Uv9yP%6a5#vX2*k`vi)SH9r6s3JJ7-A#uI-#SLc#)O=qdz5$o2X!2DyP`XhqK2|l?#Cl;w9aiqv0{c4PG9?nMz$8B^uEc0S(scjGZi%aur|ubi#4JOTB_Qq8Pa?C+O2pD3t}ewGx~^{WiUz-m6F&jR03eBF}Sq6&)lPuEsyN;&@8TGl%|#L(lc8(_2JHeJZ7Q)mlIV#Cu#cm|a5ZGtOk*ZcdAY1AOCBVs_}qta(taRx=u&UU=K?qkw+ow7qCzyskHH&5?%HjAHc*7urK=jIq{M1?Hd6Zd<(0`wv#?L=FNt(;Ye^vaL!HSCe^pI{|tAqIa}G0F&e()qzR;rU%zY>x8ui(h&3G3x8?KUrH~ONU1Si7L~M^#AmGT(0%wk#{-$^0Hr|&t;wRk59Elz`K0PQ{e>k$yrZSkAe%vj&wH0l|zN<~@AN1FH)*HCbXn8^;?dEU-M4h~#cIhK>m*Dkxvn1S;fvA&;aK`m9Vt><%{khZ)W_W}g!u7F=eVT42_H=l*TE@;Q3VG~^UqTSwg30N76(NFpKvU95p2!rS1}-a&CDq|C$y*+zyE78z{m#8~sT*@dwM@+NLvx~FDf~Kk>I~{10}t=qpdSNrnwl#gj3aj`eV)mGxh4)8%Dfa$`=IXWQ|&ZR?MmMtRS8Dt>?phMGG{Y@|`YZ_H8>n4kgC#xqkC^$0ZudPy$>u4L?T+?$6wkt?0VlLBW7KV6Cn$NM@S{GEO6PXvgyucBX0K|Wb<#fiV!JPMo(7WQc0LOtx}(4uu;qG7%X&?@Xv-<35pzqK?L@`4uj@*hLp?eW|AWp(jT@p`Z((iC;Ej$rpm`6LjO-Hz@GMs>5)&N6`L%XDuH_1k}wO?7-&ock;^u{cqU>=u{o(TdC1;R-HY??Cl9!8ubuE7rePU3*wM{!=Bqth}=faB;T2cS_XGtyXTr4=0jNR2D?duWsNx=^BFw=1$a(5W&#Ce~yWr;x4LHrO$UZPuV{1j+Ifg1|1^P5{x_bbz-_3WU5Yozb%NNeOMTYu{l+vhSk`#bh?k#klk{5n50pT(&YGw49Qrh4%Gm8uAMctY9Wf^f~H8{-?fEB5WBw6|c7sIj8QT@IK4A6i^KwE#ASOL&hgeqK-wE2Y#12xIu=I_<{E(Li;wdTO(LoccDXJ8$)kIo8acr_Chg5C_I!chiapiH33qeit{M$TKrxdc+4BwWyYhosmUN~c+9|kJ@UYgmbWD#g;dDj{EcC+L8@cdqa57^bWjb@KIwV}$J6PSZpz}{49GXik}xj7@ic8ld-dXFk)Xsa*m|9GesG6eghb#;_WSMK0d^ATN4fu{nPO8kER(O9`rLr}-mk`$*BoNOCUr%dYd9&Nf&IZ1?}&%KCu?dKo=2aB7W^Mp8z#b@S2tITkm|;-jxSql&rIg*o5(t%PyQXJen>K?kbRK(`*k#q`;LLNdkmJ-!RAosp4p`RHOcsbDt(U)w|_&O$UFXP5(Dv)+axG$(_0iK68SZuA+Na%EF0g$l&_t7t0fn;#zY)nbp!PCquTm~{|2DtVW9MvFaz!v6ddiJtZ+=n8zY07+Jfz$VXE^=3~cO@v|RfO6>28M_VVeD+SlPj@g&@QL7kGT@bhHa1ip+*&6!rKqU*RJp~kX%8{@Bnbn09|4Rkpe9W6le0|`YYpcGNMgx1;?+Ets`A^pg+m|1)E*3cFmFJ?K`zcG*v?&h$E~)hv^F{7T`@oY^RhR&C8-zAFbD{2c<0@}^e-dz?&UN<+K+buWW3gvKg$l_sV<+mRQ6G-4Q{~E}!IS&9#E%ytFMa#1syxGRc{OQb3WrsIBSpz`l6F7j!9rYoeGt%jE8)wASEHnaMVJ+T52}`BK34M5Ovd!=QCor?WuCz0;Y1mn6{2U()XMeJ$FVvE=mI2iDG>8k-!etY3yt&>GG?7sPFP?%IVWfLS=$Wsyn_l`X@O`AlWSUBl3_Tt7V8I(w1qpy~hKup&z23CZ8AuPUrAv>@Yw-g7p<$IQJmnh~qnP+-VS4uu^?)NDzsyh`Krpo*4MzF;hhQiare%mr(Q%#lnx?Y(*;;`h2h;a>>#saX{o}Tyj94ZccknRh>$Jl^Rag@Asn5i#>A76*nh=Nzt|!!K&!9z2WQT0HA=uqumd)SD?=*+i|reHB>OM7}HA6Lp`qalX|rP9a1`e2d^jb)tWHj2M4Y&K(&g#s$(4WswYKGx7hPRB1dPEPXABev~uw7v{4MGJa*3cE{8s!mAWt7mlzAHSg*G`j-k%O_b{S~FCKO~egC$eR43+Pvg70dMgrK|#dfuvK%ea+-bdfEKbK_>bL;2zp`Nz%qtmK06i_ib?zPx~)PF~X`o_443SYBz^$(KruZZ<%3NM}0KP8gnpXd{sdx`5+>adfVc~}HsMkzRJ@CtE)QR8u*YLRFInT^_E?NT(pf1KqK?$@cgpbaPcPGza#o%eh*~8iy64Dlz{tvM2=#bJ`0Gvgv}RF_kO`NIB%E=TQBL_Tm3^sA~eLY^TwV8cGVjd~;3HR@a^9YLV$v}KR&ef>@KG7LZh>Q9mu$c*k}z{|Lzbcq4f-Gx%tJ(^%bcF%%F`-AA`qgp91h!R^9erCWhQ~$@)rF{PJ|zIq$aEz(M4$prmiYlK0}kcS_;3z*pSwle4fn&n1%pA7?$5EayY+^5)@Qlv9}qa|HRN&9|UVWY>cl*-IF1H|S5Mrc=pc6y=d!H18Bi2GPTz{1(a2pyPU)qzG-w!q`-R^bd5P=gx)bt+ap1y}ukut4^}xDiCu>9#z~^7~=~O4wiMn~;j6{gub?2OFKI-!Sj$0h_NCs8^jzC*d4g>q~>w0Ss6&U#w?zUE_UwS1x7T`t$>EeKh?he$&kKDR2*-nRQUj0-Nd*rJqy@luV&N4yeukiPh705r~_i9@Nx1<1ZzH{pg>bK^U_-d=A!RW$@4FUYfGsOP=9dxbkKTYb_vwo@h;sQE&7s#1BQ$Wr+So3Q`gbEXK9(ZKPEJ2=OQ`84CataA7YAq6Y#bf0;e9=Z9+-)%CBX57nhEe`jm^1=n9+9gphiJwoMht37W&ZeWq9}U_U;MJ;#s}T%Qjl%yUkKwyRNBgLH8`%?@;q(B_Ya!`3?+KTM#Xv)f+o8am(I*LVxqmB3VaXNU3uAuy7AH0pIHZKQ158_L#7>lrfqqy5#mpW-hy3!tV!n_qpW%s&iTmT}fjH;wWr%)Un#%Ti#w39B=k#_SQeQ~BZY83D#surJ`M+RKOGOfX&IC6O65nre_j)EN*ZsxYuVM-}=rEkbchBoA`dp;lK9uyF0p>&d=4S9BpJ+B(l!$1u;IikUIfqM7Um$ySCiZ0ttoXGwE9@NoKb_L3HN7?<9x_)K2+q0r|9_ri9SJb?`kAZD0n+;0$-fk?{Yfya^F*$dv=8e%96PQ!oD9VM7cNAfOOGcd@|siOhmj;tM;PivZchYzUQgtgyeH*%5&1X@*XUq4f4R%|`=}H7Ki*{wSZ|`WRmc+kZxC3&+(DEDDvT8i`xYWc$=KXsiiD=XPro%%)F-GDJiUbdJ_}BVd|3V#c`0ch_l+_s3Iv!tbN>^-{k~_PjyBOesE}x&Giy>A*PZyv%9*qMX|Sp~s&Fy{dC4+rK~!G_9dhT-lnOt@90sBDwQc2VnIQOG&}@1O)=eodHNRw1%Ys+5_`6x#@Z2B4%`aG~@bBXWOAD=2|LH`Zpr)tkaCb2D?D-d1-~Od>?vrqtEU0rC`tdLr>*Up#hrAiOY(5Nnpk2g;Ttwsp>b*(^qEE$_cgQ~}rCMUw45=V~HzL3+2YH6b6VW_M1E&Ws&1LUkebkhQ!#!s|IG0HL<I;ffJOou(kmwLgyFkjta=xs+JANt!L_(yas=`nY;A?;W^j{jJWon2fTp;C3sEub%?aYLXwh?c)7UVH=_i^KobCQ62zw7L;o3JkZX|P%2*K5g8v|aGa0X@`{wayz`ic&dwcQ?+XPV^n97N9};Yp(2*si+Tf?^-UPNC%G(SGv#rMcva^S^teId!9abd3OC3(_Zc2yY3=)-OQ8Nul6hh_F9SUF)TsudbKgZkM2BwHU07_dXJE#CGADc5~KuO;aL69Sh9?-~t4?h0S<;;o=%3S4{9o5Qmox#;-|y89LNG%&1Z-l|bU{&~N7x5(c888ETH?TM%vat_1QcuP3@`~AIrugBiGcpYK8J#B4{$-w#VNz{Mu$Um@f9u=MyZ4J(@Bjvr9c-cgKrNYX*i)Xa=;(f!WZoutn_V>P_WKm=%>Z{Tu%6G13fKOfUsynyPkKU5w9XErSz-=R8;An)L<9hMdyAsJ1;H;zUMb42=-LXciFBK>&_Rcr7L4Nok+phVcIUT_9WfEy_y&O#Mzd;+P0JdZULXNg~&M)`<_d^v}1zZjRgf!-K2gx+nPF^-m^fad+K`pBy!GzT?0S<-eGeid)zon+BZ}^Uvu`EMLG!FW_eq(aGbTBD&zOso&@@T4z&$0!u#IPF;08Kp6{$Zr2K1cHtK(cZp~I%Ooh2_TRbFAkj@(pz0Ml@PK6ahMyupjqo19lrEVFcG}!FDO4OSRdFEF3>w0Tm1`y|sLjIwC<)VSN@jfPWm{xTyl|Y|5N3V-B^I0I2epYPU7MYcWT+wASDd6tc>LX@_d@{UCtgR_B4VG_T9A7O>|4-LnCa`}oJqemUf={$0pwA+%9EFab$)Gab?3`hTKKCRZD7eXdS=;e*Ubo0CaL+FqWX&mFD!B%I7FYc!U;mFi4`R=!9q*Cq_9;#a4yG#byBSEmFTXNQ1sVw*qd_kfWG^?~Y9TrNfyk0r~p1$Wir=&&>$}Ce(`uYFI2lj_Ue1%R#A_1rLW5bX7u;e~7%?1*cOXykn`$&L@~7x@m`1fY-rvI8H2}Ey5g8qQ0f-S|;SKH9ThU4|Cdyx0S_|Eq#8=x}SX`sj_%fpUM+VCJhopU834nQx4?jjqUqOidHB3kG=o<;zWE6mDd5>d##r(C4bnKEVpFDL@>*5zIu++5JmQ`$;hs6d#;)K7SVV>?h4f!_AYCLP4S){eS!p-%L<7JkJ5qF-+7DE7yh^UW}QlNt*G+KTQ3{6<}GV*ZwK_PoYg{;!`A;B^L9M^^k|r9p#FfY!bi)DxX{PnwryK+WV+*1lHcuE=s$q848^@PF9-pxy%cikJsFl~Xu5|GXNwZmd(lKZ(9>3i%^#{53M?%#ejd$?<}SWAz%5))w5=Ev7lw(6n_w@?_t~bSnsl+6jVVJnU5T$lvlf3xQz*+0g<-jw^8p;NNJilkOG{%1bO7ElnxZ{l?tCRRG}vd69Ci5nYVzeC+*$4RMuXK7F(T(-Z;5U+o-zH;^nGdc(_(W>cbLY>Ibxa7*Es=<^)!6jf}H#W}yw?M=%0yp^t0Zl4MtzUj%fkowewmwcCMw~`s~*3pK6r=$j5)I1FXPZB`|I_6cZmsgIYmLMlaX7tcv3}vJz#-D!n+HHo}&Ln9u4g)4Ox$pj+z*W@btC;Cz5#IQhO>ft-RGW1Vy(Sq+OFcaI6G8IT#7uvgH_j`vl=#ZM&d0z+lM3Rq^eP?b45cQZki|GI9QwCP7<7^&oQr`DcSrUEz&b`#?SV@JoPitk1Mo4+}Yig71y=ib*z;^M;X7suI(uH~K6VQ}^na|X~q!AZXlF@Z(x-d{%Y9}=l_SJZECFMiU#Vee;V#nr@g`19^?l-pV4tMK;hWM5wztnwdso+F9tSBEO7H}x&(@ba7O!en#Y@1x8L439Epz~TobrQN}}-`7)mTvot?2}BM@)O{!N2S*LN2m(sBKYQh(O4`9}u4Uaj@c}B_=DnpHwi!d7A@&8Gf>}U2ebL@d0QHgmTcz~pvY)qWZw;JwLLQszTzL6@Q5xvf*pEL_MV-h=8Kh@G(zuaiEsL~HwY1UFswoR14!<1z@CUE2U?@G3wIvsn{dEmI{n7vJt+ST>GN8e}V#C^9q<%D?)9igrrRY$-VAbK)FC@;1KDw)lpTWr=HhYYEiNcS^5>iYccyNl;AMm}=tRTv97VI(&UZbB&>f`(}`qKBODKK38+ElI!b%P)~$T6MGL*gR&>0M8z7@$z;o?v2vI*}KUuE2sV>*9GfJV$+_#dwA-o1+@e8rFHZB1ipNnx%GaWg6r*nz>%HB-Pc=-k-DSTRQN3iqwf=k@DNA`V8J*nb0TEDIczcoU`|Y!`DljbKtwOPfd?L@=T?sx~qr^4Ty8$2N&V%V~%w4r?Ka8Y8zL}av7k$;?=D{xh^_LIgOdMk@g?G)=O-v>1M!MwV&SAq}+xny<)>qHaBi(WbZ4m!TWwx4=!pungYFRdlYFa55sM2l2-TQcbU85awUSDYtQul7gXgOa0`)O5`vU)l^TQL0X8>wI6Q;o`q>(vZ+miMkbg!ngSk3r;_OCOt{&OZYDQvd0y(RA{?4>u}~Dfk)(Nh%~BtFq@yLK`@gY$d~CD##s$=0pDlm+?riv~-!kTe9`mjqT6`Y?h|GQ!bj_+~zD?iYp(|~a_wn8ix{m+tM?WZVZfWbcPQcHdu$EWYpMM}+l6&<|0UN%=v8dAG%OyO45Rd5ZhGwAt^MYt1}SYCe9>%cz^%Hc%KKmiV|Yl!5-Q)Kr|_pTLBQH-EoN6{7#NbQ_24ViqS4HoPDG3w>B{+?mZ$jKRzSYccdGSCsWT#vl#&L;osvJSXK%jVM2Gs!NCSvuQu`B9KFl^xS)zbutrt#jedeYeWA}?+Vr&j5t7pV%1+&)w<}D*ZGQ=@(c|U1C5vdUV%QVPtNcKuz$})eadzL^yv+DEo&1PK;*=9iy%kYNEob7Vb2SQJgO*3lK<6l?OX{g;H~~V&3b@3=RdDg{`c=o|L6au*5L(fA|5PAgZn`V5*t>de|n35T=4mHNT{dhjekPD<=ICO!;cv-96KIl@BsO$K>yKh{!u#Yu-S4VR0Gcg{!FrreD;C?5y3oWBiC?UYjD{7(DX|tbY9<7qf>_KS|U!TrTTxdfYZ0_3)ZDS%m2wwGf0Ic`Tkb7BeDLRQ)kCN*~^Lh0dkZQ!aTx%p*mP;QJaCjO=!-paau+2j3*A@65$F|7xeA81U)1CuN^A>IK#^i|m4!P#Rt5+_N8bqTc>!Dhn3n+}N3t&%7K!R6li{NR#aCH_2L@p;(F^eAo7jo`J%q9Bza|dzkN?R1PN(eCsOYsJedxU%S-vz;`-&TRAuK5)rTZIfo7@abH~Tu0sB4Nvo`@xxs)H$!nfH+lRWytoP#8&P*W2N$cCFhdr2Y#P7#~>2^u!%l)Vm{mcR%rNF(0>%Hlxk)xEZq|T9&XLE8e??w|zjxoW&PS!V~4fTXe-}HZ-W&u$jVY?N1$;rAO1q!Bx^W{4y#A^uJHYg_ceIPwf%w(1O6QSTz%6RuTS)Us?uS?0bYMSHPSj2QRkGY#{%Pv2SzrYM25xfAutc|WR7sHTJEp1nLj8qud^LU5GY+YC^fQd0LAMNW8YXRhX7k_A>`djuu5aNH->XFe3>K$MqKZV>7G;QND*7N{iB;q1HRZ}mL!zMrCA>kp&Ph;*MrdfpjeO*D*2#Brba{XJ95f*_GCv2H>*ZmygoK)WcM1Ji{ov99o(V)=Z2bW0MK1HY*9oy;xoJq)${zF|A{}+=t8fY&>s}J7F^2xvfPvDJO{s7;%qO*SE%M3jbJ8a^UrgiFi`tNKJBfN@$Cv4F{I%x58d6`sR5Le!Wdrtn@Q!jpS>SUQPp1BS3cHrk6s&<;odmamZ8LA$v+>icS?Rd;ff3sk8Pto!SQhpavfBS?#6`~9HFP!cr?HdMb9eTYj4QkHSWxNeR|H3q(a|7P#aCrR4*tP@ce?VAAiuyhST6fUYKQpUHeD-h_9$$tKWF+2Ya4A{HnuHOB(CgiGHq+`}Ves?xn?V+cz51nJB8KZ)#QMmCC8@Cf<6-l5UR>9DQnDwm+&K+4HS%^1@FQRKS}l%CpOpdIiN?bYSeO3El=Y*nJ`>Jg2yPni#6CFepT`}EmTZ8>PXi?yas8@hN!A7K1$iK`Ns4v%E9#FNt9L={CekaJkV$uAR()8L)P#?Ln;k&C3Nex3E}V{^XAknaag=MkqyjD7x(3}@bwqi57f~&xzHJ({cvCfUVoEjqs155d|)kc@zirhpXt62rSyl{&!v40x=9O>TQU|N*d0^D7a0EBKq(M>dlQ24p%fXVe8ylo5ZKcT~6aQdg;rvVGXx;6k`&(YptV5wc6HPs4(!F@I6SXk80epddZ_aSfBGfPSTcC$IdNx`4jv7a{9QD&LN5n?s(x+#)R%ak3J3MpkAjgdBQb|1xl7N{Y_s<=N9u)3cgjQfPwA9>?OPK`af8uTDSkCLSsp5hd(J_^jn3z*c_X5xZpagT4^(K&aEAz-(>$~0MTc)=PfDcL7hv+t}zR8&7BhJ%8+x`u_r>Q^*PY0q*3kEfSjZFHG}7jM;^GnyZG>;2x*_o`vvm|`}f@YGBPPd3a|4ioV#?*eI|&iRCO=DhPv&By{mUJS>W5~!+u_e2DJ}*Ws%mY%;wg_v)}Je-!ffo(mtTKG~60YVnJ$?z&*{UsOOXkv`bP`;C_u=L9PqQ&&q*^V%4dfK245V$SpsGt>dB>rgP?@E(+*V%UELLXRizhGZ>QzA@!*VQto9n-IQ}@)zEgQsE^OrUsijPzZd$*oI(-fkdi*?XuAfJr@t-%hWISfV+;^^j-;wgWtc$0-L}FQx-_v5hbT<0jV;8sQ%(^i*D+t6o9*^L-EhfL_6OnYSU6?NjAZ~E6PP+!%@`ca5{^8W9=zg|s_`cMKV3O>Zgr3Vd;Z?yQ23Zsf3=@WD`V;z6LPF>)i6jou0*~;a10AHQohuOnB(XCOI%DK@>&Ye*G^w;vm*6X)RFQxznTipo<7wnfIbgauey~Kl?GEA2Xkyl=L&5Zm#!Dor$eFnR`suU&_7W>lPR7F+`bN9&g@11ysOoVo*g@>o(frilSac`aQ%wdcXPXt2FhtpaYhzcm-TXN`@K6I=|J>N6`a6zszb`ZHrqL80_0%EV^_lE(wpMpy{!h|Aqg|^|Wzz3__#Bqde=C91hgz@9mcE+>O^;4YGz^gX;EXK#cTbMZ547uITkoK*XzN$%zA+WnM9B@FB=ORcxuH%xmT5rAJ+@whw4Zor$DeCSD`(0-CW&&UN%9+iR+U@yJ;8(n{18`kyX+c?gt1b(M<19{{vqdi2UAfYDr9uj1)n3aiwn06}Ug*$i#Z=%Y3LV{1znq|YVA?1R>Ypw(m1Uw%w13*bN{2s28M|MT`tRIaXZccnT_$`ONotOEL%zy>{5xZ$FAILXpJ+(cLcWS$RXLpWA_oME=InB_LB85ee_7yoIS&Nvu5Yz%kdRDQNt7a;IA_YruhNhO151|I6`w&~l6>*UeydUn$GUs%>LvI_JD?+jZ3GiDyh+b7g|&-Mdmp|Dmq`wC3T9j4ar&@1^CL6y&QP=Z;=W@yUUZY`giluOR2JryV^ed-7oDf!VRDo5(pVTfw3l^L)5cNY5(Xz|KaV0g^Bqo0ZTjq81nc$LyXPoT4X^AYruD_gc+(L5bwZOfNtEJHt&xmlZM=Vkow-*b^$cy{|MlqzPyeksESEg@32TJ_HT2Ii^hxv$+~Su3f9Z4o7R#Ye=jOV@)}JzgI7gUs9LN0v!2-q3i`np~Ib@kYKKj?TYe~5xnag<&92LcJoIPB)hB)PM@*8>c(^94xu--Idfj=Me2{9iwO3Q?QBRYYzNPJlMWyJz-(QHsuFxV$Y;u9hV`!h8M`U_p1pD{@5KYj|-FzGztY4Th9+LivFPPBD9;>+e?_jPBYIUpl;3UV7-|=Z=KwxdAx@Y*RQnHT|ay-OojT*@#gy7$XAY!51;64NQ1KEp|ZR<C)?X3%aeG%}L;Y{Hc*Y`JUkY{f+w=5q4s8ASHtt~gssHrXngdD??&NXi#aUU%QN;RwQgJ>=UTfr;dkuAyyx_~zlLau$S0ZFc!Rz!Lej)axHU)kvT`E)bM!w3F(NTYLKNUu9cb;5%3;BxpJG%EG4TxMQE>c|d%Gg-Rj5d5PjJ{eJp_f<{F{Q707|glXZvSWeTV|B`#SzANhn>r|zssh2wTtEfZ6bXZlntCYHQRgIU2XEQ&Ge>$7iF@0p(g$2OWTmlh!H_jxVm6L-plnyG|?&jyf}Hhk;x9OB95^cSulMqSfF_qKay4wx^KuMsEp$Ei3wJ+kOR-v9pHMmo>vFF3L^EFYexcU19@q5qQm8+UxKE`ade%8X9R|MAsZEx*LcfBmmgVE;UkBmYSIedluLm6ukf!WXmb#i}Ho=pSFs{(d`x-F3K=P>;Nsn>#uy1594L5kLP7^=j>%k*XG%aGD5Ukw%X4`S|7uYa|Qg+%^kDWui{xQEtx7fl62;&G1IP>Wz0Xn=#4*qTa#34EgH*oeg`6?eanSCeL%JjmSS+!`5#V3M+uxq?X5J`*45oc92fG`P&pYF|%uWp(nmRL-%HWdrd0XygRC$n2!3JtjE8PH>SZ65efe-A4uG_YuSz7pXr=)6Nfe^(eZfHy$rLAe%5Be#OMD<)p^Hb^}l~yNU4mp>_o||P)Ny@nbA-g4Mda@SrL`hk|LX|?0s(}MT<&Okq{CpQD~4z>USTXZ?5y}pU>m-dYs4mT<5-T=ly(NbDQsw6mnFr&+4DXepIMFn(H}Ip#LJsXrHpe)%@ixDL@L!KF42W@bfe*`Ffyjo&A=`O>5OsX7iyFY3baI&X777Jy5W-rB;$$We_J6}NJgi@+}4=V$~s@=V1MwQUPhi=n}KV#DYAsDCp!b=z5!%~3~F%b(^W&!jqAEmQtW17~irmM^6Fg9Ev-Ee}WO@IA@uL>Y-&o>hAAt-ne2a*&tEiEw=xTmTX@pVD@t67VVBNvg~nBAXXoRM->-h9O!W&b)kQmxMKAr9oJ^bQi{%-D`~JDt+`?`p^r`*^!$Y{Ap5*)0sF%+GA`eUa0`8kK!;hD8kLSXm;nLw{%h8@YbN8`k*5^T|IQ5k+iA&!-7;u`X$cIe{1;*|HXy*a}x#aKF1t4@`hUt(wsozDs6}4rs5bmk>)OPBlo$r46o>{C}4DNbYS_Vk-{)oAUTsagF_mg5izKZ*P&F){kc4{>6by_lyI)wH|Z0hA|V{?>Me4kPl$^Wxa?Vh{8IRmlnGbumQ>ql^qMe7%nyDr+3V^-+%coDGPWact>k5I$!*!pBc3%FwA+v|G7*@M#DruAI?+&eU_j_thft_CpQfv*;{_vnVM(%Y~IDc}v?J5qmpQig{dz&I1T9bvNhaaP!rb})5I6;RIbHn{(*E6Sein%}o2X7wC2#Z?rE)VUTb310c!1FwqqZA~6@C<&=`ev7ww-x3C@m`NQiuONB(@yx7S^!H^E4~+aqWwABi~0l#*yjT8#MKu~NqOx3yryQ)il*{*N(N9rAY&{T!AAj(YMaW&6tsUf&8Dr-i3;~a&v2ISL;I79%>}xfXy9!aJ6g7q)JL>Ivq`6r4zoAZ6wW907p+?LAW)TkuA$A<(OgRMU*+88OstSA04K3>u66myS46%}k5M5w#x<%#M6jQ2fPkvjFpmNAuQNZX6`fKN2qJDe{w!TN;d++#tg-<46=o%f6d7i;oe2A5#oJMs6jOEVv2^Sk$r9Y(&oQ6ehzMU{PyJEkLY&=&csUCoqp`Hn)Uf6D$hfZTHK7RzTiz6iFaF_WlQk*_iq=+5GsM}Z3k$|nTvkgrD1Xl`jOr9#zhj){D4);m*WAu7`0T6SfWfM>rmJvFiySos^m7bqXCdC1l1h{Yd5LX05e_T;P)Xyh$HQks=f%>R8JHs*LD6=b0zjE@ZQ}eaGNIaG_vrR%8=#ZH4O@ECm>Mz^Ymc2D%!0FVcgd9cWsI^LlHZn(;U@!K~@rKL4_+Xb#!i>Z6u4ybtS+cS!NfYCP>u%^;&os-24kNd%{@%z%Eo;AM+UT&~KZ|;zgioWsa(=g6_O3$syL^*xW)dl1t9rv-uZSX$@OaD<{gRZ&F89*8@JBIJWc~f1rG*?7G_p0x=L!{iVzw=}?m)e6?5D^E_WNfxM})Q*sb5xTkY4^`1qS3AoQa;0L_ZZz;GM)XI!t&wAy(q+{f~dTbO?^GKFk95S)XEmrXc6=8!N{S?8=A9BUxG$FXSbSo?15__Bq|>;m?}V9Mp}ggtjoYv$=7v;iosfsL%4#P8f~v7h?SPHAezkv=rSO~Lsd(ArBGe`JI&R2wq{7y!*S)=@KBY~!PU`ICr$c>_R#Dtf)FXcu#?^8#;GNoQ9i1NJoL_os+cRe~foPX=f#)ATbm>(7-WJ1&)AOcmV%*cA6N&4J_}Tfn#T>j3+GwWUiy=lUnq$A9P@yURWoxSt-pw!#bf>f7+!v$NReRw6I>r3muO2i|k3J!({#@7eh`uLpIakNs2j`!;Xp>R*MgkY|QI-(4T`oDP9(P*x`8jT3#hpFCo~)%!o>_HRWV@N~@=)~jd2stwgT9n<;DT{<4tqGKL*`S3RDkN*c!e2}PXSOEoKr{Au!j?`z~&u6^(xOO2B{dnq0`C!_?^j&NBu=kgtr`+#C&>q51n3PZq;tkrL!>o{7h(7Ne6BIZY_*(ngcC@pwEV;|;91S?0ysdoajyzCg8<1C-NQcb9#0pbV|0}v!nX+3T11dj!dX%e)`zCQ-oA1el=Hs%t6J5A(62H$G2lGKn?-9R=6v>__MjN+w0Z7S9KhSzis=MS6e*SoMA#n0%m<(P-JBjOrpa?2PRvSAxpq&RKRX?0{D+XEiK}E#|?HqSnWB9a^0u+_LbCLeI@3UX0mphbc@c2MYf#DsrKUsWJzrGzEQbGeiMeGq_}W~Syt@_%>vlrd2wrrCfdoIAKEgwtPlbop6A-U2<`k!&oN>xFM@%$Kdzk>Ks%*Q%QgJcErutZJD=T<#m~9+-I4L}GZct;>??ob0NT%)YMgwunF_)$=K9LoqWy_oO|yz?}Y4TK8eXzr=hY9CS^M58&s`s^ZbjWjm=a~|z)c`FojV{tJMbG;VrLHiw}WII(hQ6M*X>8k^OQGeI@`@*$ADu|Am^L;Ks`-!+?M+*%cKP23f^GEwLem)e0Ogc1+mEIpPBlTg3QMWjCfB`4C-C181vZwXaDM#*)78ih5+b&Oj9po#@ofRBkXoYZqNHCT_zLE;~bE>bU2-Muc)M^Oxta4M6>dwpk=O6xa4(kV9M8oqSfv-gnOCR0J(q?l7${7G_o`7ni^g)6Q3GIj%3rlXhy>?E?4~XtdjT8S>S;oaAb$s=}#$!n?bXPaaMhWT4F4eHtKr(P?nV^~-1GX<-M9|<>WaxH?$dNCER#vUAGH$s>Z*B~pS=nlh<=Jjj>tw>ZEqnp!9V65lzsOA^6pWu_1j|$+JufU5*I`WK6W&WFw4-2Q}nw66JU-@~JTNd>fLF1#-ASH=5rvrBxRkaKDtN3SnyDS(fcE0@r$NWA2q@7n&f5YFpzi)UU%orpX8_Y{F>sFT{t7E(UE#mGe;aSGfrQn#Xz{8vO>b`ksi!*{&7YbzQ^2*$gOO%NHj%`$}G*S5C1?1XQ&j36GEP89Z65`dd+|^%b}S(0?0E)%W8`adzdg0dyrYKPnuK1KL2u!vw$cE2`@)ZxL&BsHNU+8-sN}bzv0C7C5ZtPwS`bwZJqm^6d%mxyO_hveqa66Dp;-f26a=3_dkSrC_vOZ&OJ`*_bznyE^`kRPB*XHTSc0uvzZN;{>?NPTNllJZcbGMt9_%hZ!Cmfj*(xc#uhl-ronsG+;BaH^r&SM7|6OyeR;a%iq8x(sSwYBGMjjDb(aKcFsl2zO*ADHBm(58(8%KlqI>V1u-fb}Zu(d#R1<|X4#fgq4%lJ`Luax|6;fCEehi_*c3B4EMAMcZ=2}+1Nn5Ae_7Z^E)MNaJ=eHI*Mx(%GHzepF2V#!wH+dltdOr3#-9Wg(ISYJ+CQV_80N9-ui;-+y1W?HuN-|*wF~puA7<^oU$>J2;JQ0cPZjx!?&%zr%HC)9$v*h@TLbghCqwNRy&`ldJg|Fb-WJSb7wo@5qy1$6Zto0ve|(4jrQXOU-Gc87$a=h2ui&`Dw7y|og4p|6EEt-3=)ANI@>SsZr*Q=uCBQqLept;Iug}}uu(9NHDdA+54ixxyt3O`iHF8wv$1!I=_V=|$f&G_2LqC#@$ZoOFrF3xT3A|%ng1i)On;ahXo6Y|V%1_*oKwh%X2?@&`W=wJTGk(0jgq|l+#=`=QZrf|VHK=RRlyl-<%Zhv+{RU=g}z!qMygkxu_HVtbijFP!oyxINX4|WRhHX>ewwRJj;~{YGW0gm1u|GaxNg?$-ag%;sXUGMJ*X3T5l{4sflu_;O3mM>3$hYijhrbUN(7SBkfTD4dOrBEs9^Dn_wW)@p1kZk;aazabZDAakSV+bIqLfvkAj|FI<$s#ioN@QI^j=jZ(zVgb1)7#PivXCSrZdVJXf!on}+@?q7S_NXBKoPZTNM(<^R|BH3^l%=2v~M++|7idR|Qp4Ms)a(WfjaxeBijZBxIpQ?D5OJ$j1XxS+mkW>z%k0SZ`}JRga!K;1`NXE!sQ3JMzLrZQ5s#0PA4P#~t~-GZJ6s1x(KjL%ac+3JL4`+l@1Ktl6yM<)%w9X`p5UxGaI;$_fg9y%SyRL#$=9Y?(_f7>kCa|}@M8V(ocMQ)K1Iv;<+g$c*>YBaZ-AP*3A(_#l%pci>osP{hdfUe(CqhY5Kh_U)8EJ(@^mpgbmG1Z_5o+d0gpyNT}tKr{A)KrTh;L1%GV@~{hG$O1oYiLnm&ko_(ep3F`)}zi`efCr!;6>QO!V4L2GIQPZY;@19nF7Hc)$aFF_~frACmIPO(o463SYiiQ;GsIcLGAm^Ao3dZao!hii%z5SfibC3S!OgkJBKeru(VRVUl0S?2dkl104qW<#{wy(f-l>xw7}f84&bE{kRe-KfGlk+^6Y114cp{yyjj+`-|Tn^sOmppA#3z*Yl^5>emt;uGWlWLE7^m|Mn}mkBbTYw0@#q1VI(SoU2LkR$_kVSHWWVt+9HW_yV+3NAlN@At(D>-#v5w5mF!2-jg#k1Lsj;f=5=Pf*0-lDaHL>Mui3q++o(|)*+t|X%Fi(=}@)fuFruBXn$zyfo@^;`N(mZ7I#1Z+Q0S4r1G0o1`zXpzmw+U9KXFmRnndbqFYxz6keSpu0t&zZ?9yIaWdq=RU`*+Z4+A8#mNcfe9kmE^x7=6&4xN}Zaw`@#Y3zbd-G!GwdixYEIuGe6IG(&KsiVGQncWSJlrEq&%zdJc&*gwS|^aBK3q$9P{{tiu0G5NNT@_!is!x4w19oSldlteRPh%3h}!v2c*&QrK&3=$z1|k=BkFZ--upKnN+6fFefz_HyJ?-sOK?ysg99<^K4sMY^MiHiTzK67xz@TEYJKHT@IE2Uongf)C9wBdVlL`6f8?mhyGsKeCR4#Idu{R~HS|Xr?NvCwoz1=NcO~*;79lUSUoaO`dO(NGU<Nt1xfsM)||ToLLNz*Zt&ER*L;X&DL(YSC`5Jty;^3T~AQ|sNQY+fyDyP9rw-lk>*0?jE$W;*NyAkdu8e!=eHCkeDNQFN(R#W2A{?#!}m&VPK>r9;$>Yh<$EX5qlCkj3b~YA&={;Pa>iWdF#0I>yBKpmv$lUB+Z73=6MtYTpa(Nxdb_i;1gj#3fy!v@e9{PeI9!QUz|k+;yu^qh58C>@n_y6w5d9;Yb~f()2tt?FQ)_1*S5_QxvOGy<_LcT100v1I@h)n`6`LWVEEiACR}2e-8mPI{;R!P?)GH{vOt^}>}{@reAO6E&)=O`0@4p%Y(JEu|4Q#K_Y#4-r7*`?`k3`%QeB=$gw}WOV&E6bJe`q@>om+(r~3L(fG88W!;c*GaLr2Rx!0(`pJ7t}%pUdrAuX}!x3sB#1q@PO_wTW&`?PobdW~W2*vk3o(}`*OLz3gLC_w$ocI)rk;@s3?T9{2G^1L9*CWJs=+=FPW9zGL*f?pfvU2O2~&B9^01T!J`Yx?U&$I<>0&4Y=o-7FyTH0_dcf9Fb6bw9bL1c-Ro8d9IALOr(&YL>+ywR~>k-LGhWQf!Eu)mqAbbqxBM{s?t5&0CgwWIlQ<-)-`38s7?`i4KHZW-JFjGa2q1%o-T*L?CeZ(BTje)eO`R1GCFy5CT)S_~f{dbx#veUpr7X3wvp~2Kw8yVndbLW5tsgHV*&iyramocG2Icn~+i~FbboHbuO9xh`+rMj4+%2DfST{>4^XpeRY5dHrQ)>}>M)%$mrhI^F4*pkf$W!?8q>x@aqD_#|4U~zwe|75_w`*!K1rf=n6YD59GonH#}k0CE99sY7fc0YA$p28&>`iqEsZ|_(d%+t}l?(c@2bMLPuQ|B}tj%n*@=Gq_^$%aK%Xd5tKxA*b{op9f2eX0*O`#ntjy=qCLE_6gJ&_R|3x2bmYb|ci6?VoX;XA_&Fp2jx6HOKW?Uw@Pixt4;=twvR$Q^<8L>^~%1dKoZsjCP&*g50?AmmPJc6$KbSdoIVPBNtu!;UM?inF>~kRV{1mQ78K8aiy`p-_L&-k*cT@@u?#Lba-F&O6%JS)QSH8;rfiJ`6kVVsJlvDyf-4vgayO_HW&3Ls@05DVl2>EXIo*sAGzzP{0x=#N+nZquD}cE*UFt^xWZ#s=~Vnwa})B_y$_5-=fcW>=vTyux>K#kis4-sFdpu2e|v6v)U%sR3Cn=`hT3$rL#+yUbwTfWNHrSm37EhmV#V1$v;Y`@~fHM$X93BKjfF}?{_89NKOpbPd%?aIA%))C4t6WO{BRzoW`v;+E39Sr{he-^M%M)mF^$!FSnsX!LPVyH%R>=`sF=CQ}`L6PWx0`b{6?+UE+oAgD)A-tv}+T=!-lf%YFg%7cwEfKOr0js{VPV-`suVx;3m>GVx6#PZkZ1HzNzUqFNa=X=<0%vnqSeD&HdmKMe2X=0yLP%jl(Y>8$j~)A9dfk==c~5>`Dd9nTq#VwkmocKl)PLJhC;C6jf1!iDhvu+iBigw$mEX}dp8*?{b=-fD<^Ucg98R80sQZ3G#EsMkRrI)GC8sHCs&DP?2Hf|b6+VBZrBVXvJGL*qN6HT;&R0Q8OCht2FKbN*?vKm)++4EQ95s1yq&;svDNk%vx-CMT%@r^7TO&tNfBnhRM0f)YZcC576(#j+y|8|B@_uDHWdF`?vwDo&GOyQ`e;PA4&7Wk#{r0nhJIv7jUjavN&wjyz?HhitI}(Na`-}(QKh_nNKy7U`eyda2M`yKbgXGult&^Bnj^`|tl3|Fi#v&bpErt*vL+zjNLRA5|r^pN-9B4;Ct56)yGyzjl`w#a1K5}1b4f2rx%b(I2|XY0%sL#8&qd5NI3&P=m1ncwYhS|W>Z?k5t?-Zqbxv7c>X(tP);ex9agC;cuh9HIHP+aNlkc*5OHUCM1{*It*r|toI|mOL>ip`b{g>};hWSxM{cULh9W;o61ViX|BH{-+J`5O=9n0+(Kwjz)ICK5@&;plCGovC(&N3-Vt|1C@3n4kFy89Cf--jW0288a?4N8cAjM%-{J6~QSm3`7j`Z&Se8_7jByYW-#4O(c-t!nmPMMDOE5It3O!b5njP95Q`9F=xEBn)+Wq%pRO)P1I>@{!4?mVtO2F?xEhO{zrc+`+3b*h1(@op>E_WxZ$%e1JbS?&`kJ>dgLLcq)aO&WJNt!ta8Bn{<1&!b!-O-JNbj=vR`a!OQM@f6iDB$CAZC+j#=4%o2HfBGhg2mf$1NnZ`t=E@4{_~RtY8^q(1vD}KcsjB2*rR+pm^c{UOs1i}^15Vu<531Ixz2fDqZ9Jj660G9EIlR+&Odr#_fh1o$W`i;ay1sjf8w;|d4=5NwrvHMrdA19+{@1%VxeD4@2ar2&hFBwdX_m0kguxsgmq?~DuY$pNuNYgk*_}HXT9SrrNFCrt;d(Q;yS9)+Pd}Z-!tz{c^~gK)NL~a;=6lkK+Fw$5RE)W$q6bsn?#42^`H7QgOJBAcJ_4JTQK1A?_bNBN%IZsqdC?YuV4b<|A;5`bKvIo8j+jBn#ym?Ux1u*c0mKJlCuO_7OCAAGeW*1=9+}hEd}B{%2AH>gHs2Q05#paa9z{LnjIcG;+5_kRl(FAq^6yP3oXA&%AOBN21;kI=t2+Hbd(Li6H8Mz`LW1PhAMcaUp80r{vNb{-p9-1F^={cJ-eMjy*wM1@tJ!{Y6<=2=%kMB{T!^twE<9)A5al<{vioa_9t82>;NBc+e$L?%D%z*DUCN?`m(S93^oZA-`GC}y%>Z->AX#aVg2gwponP9%vxY^?yss2uj(*EKK3won;gys71xi0CcM_TSG`EPE*_e|7fcT`K;Q-J%CQ%ANGiLXw)dtbBdF7;OK*XK)D3J2r_dUz$5@f%x{xDBP+oAm-)jmI+lj-n*Kl$;%4g6hsvw>ov3IlkCtsajgq5aygmTA0u!GJe%%;p2GXuqY?+eHjNCUmS?+v2ec?H^qsCh%RJ1qs$7;ZIGGuZVVtOWv{|_%!b#$KA+RM4vB}_fgQbra@|^&cFSxONW@F%)cpqst(bR3-fu1dQO|nWH@^C_1>i=zSGwSZf(wgJ~snmFYTMjSc-Lp^cnMe6z*liM2K%=GnbyWhx|N=E(HpFa%um(Aszb6&Z{!76vZ;`P&UA2yFk+37B7O#-v-%`8QI+-HgTXTkT=q1|;!Qk^BnxsJD%$*C1)!|P>#>=oA{Klpcs&s2V&4{X|FU2+YX)<2}`i7>e+5V)x8)}SI@|5&Cx>XRiMw%qOeenAZVIs4?UrDS$6;6gYvK#h+6oH)5trcR4lz|p(6BvPJ*$nQq$xSd|#dLQPmVJOo!6yC(hMAsGt7YmP0Ae1{eFqZGL>H6aJ`g@&&MqcYELYMtmO%&f+zvo}fUD&rc4CX4Ku*2Hnt1q(g$bcziE6sjuL^WyM;eOpwglINWH4b!1hCZXSDK%z{*fw`#hixoLerCzEI0Wq)2vZ~Lf76`$R`OHJ@R?%^Fb6k$UFo>rs0RmwPTg8k>*dMuC*d$KS2a?HeaKFGnsa}x~sH7{S|R2#nc2tVm1ITpNh_EdSsAm!O|MbmYDM1w)_rl{v)+0*xBV|7%pN&*Pl?09Q(9N%x&5s|?iUMaA9_oPX}J=EVT4IH_8JOeg-Xb2yhl{2k}>pOGnDda%o4C7WKRn(nrvOa84E&!#MtLM{JqyFfY%)!)!6iD!_YTfV$?HO}n8oCBv^!0YIx?}uT27EJKDWorvKdpOqz4E-{o&yGax%RX7p&n(YQ_U|?0EVTZa=Ess8#^v_%qT5}!}GjC+*Y7|>X2~|lYLI%eLEqx|2E$DF7Nr--u4WbR27!t)I>YiBy&6%3S$D%Pn}wX&qd_#y_b%MniE$P(}W79b!uSC;VO$Hpty!Ta?L`$s;W6B*YrBHPwZY4tynm%)0Szjayg#~&s&rd;u2Apn=^9BjFkhyHe1sa+E5>FPm>biEdb7x&Kj|9)Hk05ljRrpx!V8qE*ru%4^p0lL&lruC`#!C>-#{R)zbrq>@TP5=4KG9A)G4dxBY6yxWXw=TIcd{PJ0jiU#`1NO~f4lCMesUy#YTinDGwMYD_J!a7yB}nuZfKCQt*43#QHnp5G&iBXGAF(LRwf;WpVry8l%bsje{QQ}K)?h2v+oz-bKUk|Br@rC4a`UGKI+TCbvV}B-*0tEg)J8^t{GiVnbzMPFM0Qe{a&I9S{@9(O_^Swh${@9$O4fWiz2L-Qm3z99VR)pWmztCou|Bx-h+C2ZajsrCx0qW+r=JrB2QZ`r3kA1G=po`qR!eZD{@VR3jCEd56-sYeNFdV(Cjp(!!O;(ehGWf&bfTmOpm<`(7Y`r?R39*`g(p-E}b^L7)bDvr#_KFPAD|cSGksuFg1@Usu}$f8_(}AuzHmOJB?F=ayKEjgwOL_vL`SD&TY9M-ky#AAEM4&V>}zKsL&%0R%0C^k#D&sCm%Rp>4d(w#JsPHHI0{bp&00rKPih-@%s6iLeAEgX)wgouy?*Bt{*jcT1Q2V0WS>n9=@B4c~ivPnE)r|R6ldx=l|*iyL9|_%C4)Qa4^CcUIe#r{~^R&5ZH(U&BV1K`FR(M#(lIrH{k1Z=tE{22OlJ6Hv;Pva|XTG`5Nr(NB%5@1D=x;e_c=D9e2?p%Yyj42yCdS3I585%$=P)6n_wkd}oEV4F-7LR%{gG&RQcVd-{DgcJ_kAz#U|u}*ZKMBf`+dG=kLkj^|~+R`8e_wkyq)amH|S)uK7#wlg`nLh1Qr1XM=j2fxU(u@(<5z=IPY2e7IH8O+QESW9&O=t1#4E4Bt|erD8Qvm-p{FXst{KB7TxthI)pn<_Lc}0~WFmU?zv~zQp{d5%zhC8JNa%djGfQ4P2i4Qfo3FOTLzQWPX?zm$mFObP*M?Fl(DmaQD@_{ptGnNhml|h)Z?oI2H8kXzVXFV#l({)@In?3%=vLGpE*boGba4R~tkOLDh17SEx5n~C3I_$ocAk78J{$E`0mi*&8|bihWV`$3<;YRQeC5?e3>a7=JGs>gbs08T47_9lF>h){Bmz6$Mamc(dF^9@Lvo$DQ{6UJTLP-E*v`{qS8nZfr9*DbPV`&LOk$`>5a5etumjmH~_Y%sc*&l&@kb*Eo6iCKDEMEl-N{L0!P%@EjYrSg1}M`FXSlIpoL#`y)GY65(4#z&+XJ$SwONI6NLbNd>~c#d1J>X|q@<^G5~*-nOEY#Gqc9>-R{+GY674{IcsTLYhHiMP}>^~b-Gb-v|+&8RUD_#J-R$f6I`KUkGvid0PMDf%dVOeBlk*`R2zPi9Ctfdb##gbulK~sI9=iR?8=s5tU-h>o!ffBegMZ@jzQi1qoW2xTq|UWpP#C#oSUl>B$%FK%IjVE6Ah&E(`CRkZDr>6l`$Z4x^EeeRS}x56qW;WP2zllcLz%1hPd+@%jnmyRA9Zf)_bnPtMQ}vZ$t|K2*U|mtGg^9v3c{rm7LNl^Um_<@zw1SZHp$BF3xCo6Yes(#z&QqN_fg9_?uNRo=RJ{P>m;bJy=(^S@V+tX7C%Gv(twyd^q~}Wq7Hd*cLw~j)pM_2jy%&GS^nsLWft6%Tp(ZRgL*(U&HD1zT*$ss&M_|=b>cdSulYdK&t1zxUHbRsbl$KcXi8m~#_~qp^rS9r7B>~t>o;tZmqdNoOK(^13OXpUU#t-%{v_f)GZY!1`)uOxmc^)VGmNvpq8SUlPtw~sPM|*|%i8To&B;Wl|JX6;e+=_vns*h^sNtzFO#2X56c9Xp{h`(E+ZI%0z_r6GDCKWRbMZn78|Lz`&wH1D|LQiwyr$ad_3^XLz%_TIUU`A)=K?Axib^w;m{@P4#z<=l5hP2A&Jk;Y1pAN|Q(_nUARmylBuCu_9#k?fV0QH%w8|wVf&&KgLRw3Ao3B=r$VA34n)zzP_(yzwAmTv!rR8l>WxE_c5{+a}kXEyIRT8nXnD>q$ujlZP8x-XgrD|?Vzx*ZJoc)~Ma^YzCu3;B@8Mz+oD;9A5!|1OYo=ypc_nYq)UW$0Bt5dDz&7ok3I!S%93U@;JNY)Pc~CQFBB1UJ{xK-Jo#aK#DqM@cD!CpMTcK*07^NybmqtIQTIv+!h2&C{HWKs#wKX4O4zhyh|gfW{@{t9bv#=Q6nxVQ9Z_e~kp{#C(|w`BV`5As8-MgnZR(5xnOUhe^sJ3(~6JPL#LU*<>xbQNg?Hp1Z*$n3WU43dlJp9@o3aFcaYye?X7$YSf9iUR+%&+}?Bc=OWU)_{yFFqnK;A6m_Ei{s4PFBH~v)q<%6&IhFTl>BX?d;W~$E2Xa)WVu1brEHsmIG}cRi4QBp`OxNGqFdc04Qc-IT22%@14J{!8f27iaFl8UQi{~WykTke2<~Qn8#Y93;qA>?9wS+CoTM3k^$8^$NHmU(f+5bXiKS$Ot>Gmi(;Wo@?Y^7)qZY?pPD~4+YUKo*{4k$M<$cNZh6Uvk<#4h^@+OUfUfJ1;q*r5&`ji<$?FeJ&$ycj#Qc^jK%K}NkZI2WBK~lEAL6dJ3~oYjRqx~J|qs5qn#fuXBYMN(1Fu1K_kxub)uiufe8jwPTq7DZbE+`8>>?|brXT;qs)B;Ib`16EqBYUQegP;(s{+BsQ+;M)8Nbg-3-p{JHO8YdFImTgqIyyH(GrVtLE7VL&d1xRE0r((dU9a_^k~nDpJ1T=C92-y^UPuxit{V7Jc)X;=FPVaHB<;qKRWV67U&QF95=lA%fcYW?d)AKgNCmiHc>w)%+cAHf~1FSz)6#ejzyvWQ)TYGM7mFqj+?Uws9`ZUw=m1w-|MzFHim40=Oy6_4#oY>W74WgtSx_fzUn8@&Q-Wvlyek%@$Ok(@qqq2%>I~w%lf=B^`+Q8=P@yXE0B))>Za7g1O2qYn&IKYml#M&1r^PbgTyUno++qqO{}QjT%_y69D>c8plGH@K-!A&e$oV2@>|SachwM4D%c~Vp%5eIvV+hh_~sT&xdmEuIr6W7=I+~W`8OfkQduxvgIT4q2k5GuOocoAkjH8R8QOl(QN_FsMXb=?+&m2OKPO;Nq^{-icPsw;}pnpP=Q#t`g7H?wX`NOHK0%RL6>d=(kr%n&)yta?#%kV1K-x=^Hb+BQBJle^5PGE)T-ZaZW#Kzj-N9yP+Fb|*w9XW1=DNGD&kr8a0lHZfwp60mY8*-K2W4df%@L1XPP5tgof{4hM(aouEqs$9ATNEq^zqo{Q92ZRW_-8HN1doYw_nJFf;DA=@5PZ1XM5dBxRnqGw(LKQh9u;uprpNJ583-~N{-|DYnrHgSiJU~$w-5{{v9{k8j+(cTj#k)ZO(-4k*z~R?wAkrD(?CBW9M>Uy<(0<~m#q}=<_?J4T-+i&sw;7SKZHP@48Ur|3~^7(jwT_)(L*IpgtMJ^)dvH8Bufmh7ZssjS3SFWR5d|zBJ#Xpr3B)?OHreoHIVyIo#(`)t|^;>~T`d6iBU^nZTNI?|x6;UTY`xPA)+AIm^+Je_RtX@d3?`Qm%*E*Rwt^eg-qDahLzVunxDuo02ggF0}Zb^ZNSmkIpW7Jn3J>sSvkPi3X?71ZohC0z6?6X`JgvCrqRFL?GLvwT>Lns##$N2+x)}fv{8k=Iu<||RRyC09=MxF1{DJ2QPVxTHaP`_S6y|!?+hJ7Oy1P(;mt=2}}gAKN8v*@s|UhCaN$3Ko@e-3ov6WS~WG-@_|iS|Lh($hY}UFClb2tQMW7|G9bVdC){?^KZAw|sDwFX~&@q__Y_24otP4LdzV{ienp`(L41KaZq|4N{dDC({HhgPj&f4{`Okid_+Db?ZIM0*ij8rst$*MaNvluPaF^r3>*Y^}ZLFa6WIbXbkq3rC#kQ}ecDB=LG`nM2@APX;WCvS0K!7r8Vd=Kk#)HA#@`xSlus8{XH5vgXY8+%%Z5vP@cQiF^`dv^)P+-{{&ggVhLPmO)vF#Mz)x33TN7j}K~>pXH{zj$17C@KDU&^|P!SD*m2_P&aKIDyw+?Pgqe%`So(?scbS>PT@?fl}84OQ=vGSfo?oi#p-=R8pkFruy2;SLPvK5q_$9N(>PFrG-vE!K|Cgv}v6k6NQJk7#Nxn|sbwA6myXA=CPw(%YWlF8Oe%>g;vvFytko-`P>SBH+)GI+;?0dj6xbd2-9CaK8T(U-v~^CwY(Qj6ricxZJRDroPAf{;7DGD&WF^W>J&D6<07Gch7t8ji~N;xM}W4nbCxNWvlFasPS{s)Epnd7UZkc+mE?7W?cv6XTrVQw~<@Ic~ufR&SpZ~&2dBTxtPbrJ{DLE`sKj(nH|F$pCK2WDBkJs6O#|;pT=!or$o}1Sq3_$7XkaVVW^``>IdGqBTLYa3eVQsPh5J3y4J@$O@(0kRA0*OU&vP%Xs+uV6(2{N93rNKSe`^Ta&`q;VTAY@p@uj-Mb7ri2QlU7ki4-m+~>BRo-NPS96~DyKdBHzZWtJ;7fqJ%*JeP5#%WC@(nJJ79;~PfBr=Ya?#Q;;bP6k>#+0Xs@(Nvs2`i-=wq3a35T{SeO>ek`A21Tv3O%q4&1a50z5oA{8uOwIizD$`_uMo$v_;Bbx8S~9ZI%J$7IvNI78_)B?5I~PS|*BCJ=r4R|KNIcA@X>&5b!z=N;ptsHeO8xZM1b5ADJmy5HU+uWy9O_)@ZmTnFgs20_vq*&o8N=sJiKw5Qm?5z7b2<=xeRQ6n?icM{FYcKIw_bTQ&i#z~%k$QgysLAk>Zz+oQQsgUzGCIf0tk5L@;s#%^^ZmG4;no$0@J;J!ovsXEW2FRlBXVq-!I#}H&L@G-5;^%7N0CFaWN!Y>vrB_npZ|)d-9WurTq@DUHUqxLfyu^E)IXduls0>m1w=ix>2ldXv99K&62M%PMDIQzLfSJGa(_%-EKOf%9IT%4thO&^{6=j;pAyav%9@l}GPxv+*&vWWOLn+Wc9&q&Z;J^Fc)j6}2U#M_XI*6)D<~Yb8pVWKlSIyPQ1g9Kh`TS$33lCgy-Q}DO>&jX}4AW6xYm)Hi10@%ns%NHeE+^%)En7Om&F1Xi9NFpxG}Py=Jo2Z{jLlc~Q|Epr@t$wy^5qr56j)i+W?llQw;FDIJsCxVzg)!@4|?!(TYGlwZu3n#lx=AXuku3u!wc#5@!UPIo)`>C`&Vc8V#;4+-g^cJ9@+fYV)}Y9;}G{1FGE3{*yzW0P3wH(FB(h3B7xvs;pce0Ny+k!W-F|7{8ZPtZEHpv5dNn}wb(~u|HrqhPJKEsHOE{d3ger^JewVM0YJ(RT<>VOX?cZ-cryujg%)+j2?{kfZreyQsMINXV{;$r)L=YqzNA5=5B~9kLc1IGN;ffJ6a7X>+p_B`=Q&NCUw}+(iQ77iJK9OX3JY>|6=_CJ_6csdab6s{;Q&j`WaiG1HE^HdUuDbMnMEP^`GA6|5A3J`h6?d8bZeJW4X0-34cVr;a&+!b}MeJiXx_`Ig#I76+-U1si|xOg2yK%{QO)G_E^epi>yp#1uki#LYBQ-jkhbBi%vJklx5x#LPCu(!j`)0gmblUT;(XLvRSxJoF8-q<4d#z%ixKC&Plnk7edyNmFgqH#}SE6pqs%r6us7FwZyIHqt=_A#5E8uo3xz0wHd!pjqn9;$zz3^!gCtNl5S=Nk1rS(2*zQz4kU=Bh^}`jf3*lvIaF`@{ROjK(oi9eQQ)rJ0@e=U`!s#$9n)Qs2v4jjE0Hm%*ew(kO@v`I*Q&RGJY5ktU3+Z^p>Is(Xzr-c`mx_^aN(PJMVDA@aj2rQ?ConZHQ=A*p{U55KeghD12|Qh9?T3pu}FyXQrT`RwQI<9B$p8qXs{|3gJeG8~IL;89NMd*8MCkZH4UD)5}&d`-3!{krjfMO3}}L9njjW7gAOSWonEqTrj5@5QOPpH^#;lj9W3M@KWlVRieqeKK#cK1+Y`k)F!rD0sU0MZ=S?Sf5C1@Ju%njs-2NSRqey^o#B}78CYxTRfC+`aiDDJf7nM5^YnVHrNag7i0U3I8qiM|c_N>Ol=d1V{VHGDsHw`%BdZfYD5?;Y!R;QqpNp$bW8S0c#oYuRyvW8Sfg&rw(2$Yhu+VtMzeJMvKpb4u+>NQI^R#W#}%aQ_t}u8)GlW`ey;RJ_r7TzAB|Tl?uO;NEFf^(h9q5&eIr9%ci%;H6^d4dm9IJs~&vI095$gC7}cQvcbr?-|YY>x=>J(+i~bzeEn~z6mYy?72Vt)KG`tsaq=JG&_ksr>S2M{bcp4QG4?I6xbZqpW3k*{iGzo(zT*L6-F-YRFz1+;9KXcV=fAWPKbr59dNZ5xsa&`1a#;AdWFjFQA|NwLJG#RXr2L`wy#fZ9+Z~%UA5ty^sa@F(D*LUgVSKFnQ@lNjB`42;BQ)8u{#%@8Js`jAhRi(hEmjebH7cF|jM2UC-RR1v%)mHZInciR`}X8)hR1gGZu<+fF63&-Ipm;g~}mG*)_e6)O&()O_Od89Df7zX{vMOatPbP4Y%uFDsOH{eCW#0cBpYf)tK5b_Y3Tf{fVW%5;u7m8+(dUOr9Bg2Abf>~nm`ry^>)-R@d81ZZ)8I{pMlTWbwJ@xj`Pa#hu2ki>%;(~#!9Ek5&Ir2qDSxk!&=uCg}R+$`!K)%`1-rW=3_E&Q4c>zevbNzI6wNHmkQBtS|B-ZH1wZ6qdGOdJMc5VEIdSGt1N^m$|3iO^BuokLBJ#aMQu1r>J8W8=4mrtU;QrM&+VN;y}?{7Kk?@vX2#gZ*T&vUcD|J{Ql2EnMWUTin$d$ThKo;D7Od`(Av_2i`grv2A*;m1>9t}kzqzt*P`>sL+ZfdAy@1+PZ%y}xOYQCpMkCGZ=vPb@S+eRcBFBiH3BaZq`#J@Azr>MM2ok=vK3iLldV^7kVT%!9i&i|&pvO97Dq%{Ka6%!9-{*-Zs$aB4%$_q{#Hjp*NTx+(*{-}kMQ_<;H<*iKCTM_3kIk>I&iX^A`?JR}>-mgj(jnuqOoKCH(!CNJJ09h}R)A1FVL{`s-iC(I)-40vvs(ev&JX}>;^4f76;~r5rJ7SOoU$5>mIn4bZpZD6j^t^)}6)9k?)jTfXg#L3#AR)7(I}N-Ke520rVt!l|QTNxcB?F2(9~qnWBcGT%p(;B=vVb@7)S@k4QAbJ14LRJHl>_Zx|ESHZ+*CFen;|R)pQWy@~qIzV@xNg`8SEoMbs}VmoqpnqS*g8I=fce&*l3tc>}zzN*x-=6W(rO&UiBE<{~H^qIeZEftunpX(WILO%&+3BJh->EI@j+PXfOqpv>C*vMXaR(!VCvXSJ_S22Q-I@_38Fpwlt@Ann?u;+`kPp#rt10&~Tos;uv*;-53M&Pnvxa^N5Lmd=Q=en*%skyo3a7%7z};sf&yP18^LJRn@v(Ob#9Wm0`4op7Sng~>(@X=k=%owRa`bmy_%syl>kh^2&j7nn~m@7NYuY8RhCRL|8ON=w1%0YMzNfOsf#UIOaaiy71)8zHUFdf$m(dTRa?<{!XFLY*H9r+xpzTWdqHV24)U~N;#;lf+J^rzc$A?KXTy(4|-C!Viko(c5&!Wxy(*kPmpbjy3~2*&xZZ!s9!mz9{oeMECF(0L!DYi@Z~ejEuJEZtfUp}+dGWoWM2Nfj%&IuB+pqSn>mur_8!3mfa@>-Dm?O8!66;z-pAeCPREVdkUmN2^eYM*yaety)2K&5V5l6q!*ZX`--&SYA{e!ooOnzhCiT%fo9B|p1`xyGrZZ@l-ag7HFtThj>^5Ljc`QMimi}xYJD}j}1-s1T4U2kxay8DAbSkiCX8!psWQln!hFULhd!r4C>-y|`At=W@UY%>-ItZ=?&mpSUIXSYp1{fSQkP5poYJuS@dGI7j)R|d<^%WWop-9~-Iv>|s%>Se(FFWbUh8K|#}WSIW`tUUWEXklH#bL6kR?ftC}zBwSl8&By~M?2|}`<~9#BzSpob#_S;>Zk>0#T@4tk|D-DFG$lH?K0gSzP)SC!_h9Ditg_i$B6z{`Bx+1;GUBQ_mes14&O0+c9|4@vfqCT9YuYmXH*^_wT=u85~V)8SCKzYj)2C;vM?CF-+$WWI_fJbzvV_t`51V?=eFjIIL1BVJ(YoP0>~=obS#|3QJ>lUQb^G^8M-|U7p>!{UkS4Ur^C`TFko#+k_S)^>`ni<)%QpSh@1>EtiOlcqL=wEd&c^GV?y7Le$GREr4TuCVPsPd*ge?2@T55Ml;Y=3U0It8OK)uNSpO7x5_5*?7n9-dbZhi8j`@#e5kJbPdoBSnw@|AV^99{faj3EFGI-YQJ!r;@@vzTy=^m6uh;uhv;S_MnvQYW)4CDWN<@F)OL1{2^O826M2J#{L#z>MgAh|~4VLZot>X}3H7td$y-`B~N&I+$ZziRzxP;aP|0}GGOQdMr@xaX;K$8F|HE>!ERUZ2GAz6QEQ*Z2P=!JLxRZ5IsDPK-mXdm0UsF}iNaDVRs5$C{$NtK*@(Qf`&OG0Ye8tPe`JO9B(GkPWvu-p@MQ@?`tfr$FnR`kMpOm>0xudK$@%roj)XQuRS?{@Rzt&4wzX|&QBh~br-PeZO#@ZYyYbxTzd5=a-Ba`cH!_%bMLu|Ees);!oC$uZ}Vx3xHE0qgsnY+%U8mLZ>~UiS08yd{C`=66<~>X1*xrFAkPA_?$|^tVe)9d(7?lG`y)ws-<9Q|qE-~4%kkM;Y8H_Lliam*R_SKH%v`cxu&F0Ftj>Z|%^3NALb$*|RZg>csde(!DxpU>P~p9X3N|`4)2;#Ptw7=z{u7v4f~4@GiQp1NLirWr)aIMhxM+qzrQL^{K)|?;(;@u9;@Z%=KcDc1jl1?z9stL=Op@stb0j@jZ(5gRU|w&WX}E)keftd--G(wfO?EL?+ca<0irMXi!#j1*K!X8r>uzrqQBseZ}|SPU*@R$yVL}@)0McgG#GW%D>l4f!1LY;^^8_&@7=@nbQlX%mOCqq`sZRsWynS1d~;6Z=VE8<)Ah8^k$-zp4iN9K4=qLe#A}bDFd7Mbjy*jdIUnt3<9-h}6p(>9$C$U8qu=S^aSu^v3bZTa21=Quy{TliWAB1DHD^7%!-+nnbt8w%#7gXJ@_%j8Fx!g8%tg8_3qHjG;hf#8;U&$%V`vTY2r|;6sf{YrjBX=55M@{}dkf!011HNNxgi75}NA)i_uuEB!1P(-FIBVowwEcYP_)#)@evtDi)KMvmI%b}TQ-IiiTht2g7Wq@8y;Nm-|KmMxYoqO#O?6+`GFYUh;vZ?vq`{h7q4i01mnD=X^>Ga>+cb9Sf8Um#+xmYS4Wp+z<#1(?0(b<@k*3XUzaTCOsX9?vkkcs{hW^-$$_;Z4@4blsH41G?E}nYNpSH=kw^C`IC8(eG|){?{p44n6nMJnP&3n(WFSwqqC~+sxfk7R1bT6+f9ZCqM<8=Ly%j)ZuR`3?_~BqMV(_F<)f)ZdOIG*K`O7s%=@jFM~HX6HdTo*z3}ywk~_#j>;|`=hD{25wdT5Wg=2p4Tlq`pr|+ae`_AKHc^vbap+0NNvf&IM<|rkPgL1Wxk0PI=CYNr~l}NxXJy&$r8|0Ik?kfG6wGUcSBN;2tF}FzV#Jo@2hsaQ$P2Rm>1=>6Mlh17pPJk`tsk1-iVLm;Uc`AF!k0juFyZ(@hIdagr`iA_#fVH1x?UO(c_0?vN+Ahj5_n9QQvfM*C8;qNG-L86qev&Xgt-Y$9#kVhvuh$FtB)cA3bj5%KqXG~1T;T8@fi~vl-NvlX7vtI>_l$F`}*h~i7-!Ze3sQ~>OcE*(6`rm5-9*jg=D{S%q#RaiyS_^Aq_H~xoj+RKn}zl`3+(j5Mn%Qy0Zv5)EmtevFyua_Zy#hiX2`~r=$#A$_8ffnbazddE&&J4n5vnaJD|6FMo@}Px30e^O*k_C&R_IVg#=6J6%J$xw!4y@N36Dh~~(iUBj>A&1bU@jD_^{5i-Q~?^+$@gYbVXNu<@m0a7moyKr+BC5@6Sh-clJ4Kbzu)5UQ@ng-4%CU~?_0&8quS*fA3yLT!J!|+ra$L6{t@R0;5(^mt+0v)w4w*pGDK)xL1`_L^;-}h`!vV`k7$qT2cE>9d(!Y*6}OLe`mvj;L@0d_NcoA3*47-?<7IQ#-Xp$gQ$x}7k#7e&LqRJ^O`bCO3^M!>^M(Qptnx6da4-hHjM8kN^(@#Ok2IswE^v-BHkK9g5jWClh~J0fcJ=q{tWyfap1haLCmHW^VbR120h|+5-i!{zj^0-%==#J*YO`XoCZrXhgF`|V}9?j8c{mNic>l3E8Zz>#roB%ykOtQ6RdsE-~8~~La4h+PKDIS%8@{G;W8<4jye@nLR;*7I4i$YX8Pr&p}sN^{kgiyiUPr>Qzdqap}kATdd)0;D!cE*qPwWC+)kJCJa&r&o?R;EsdS8EtTd=&*cT7?wYY@K%{cbU48>xHjAXd-7K0%Sh~XQ)VRgqZPZsY*Mi2Vm)x-;ci@4fqG#Z<{BvfpWjRAGDz-u}HyJTQelXD6JDe0F*6zSZTH4r{z_{vQ2=d?XHEeckXk6IRtbX&YZco$%YBn?9tK1M*X0vV1EEh<@8nBgpN}9!rW`02xf32WD4s^be`x`}rtYg96`{t@@L(1nXD&!}&)u`zT;2e4wN2H}X8fN(^(2;$d3XrT(=B#z}{zdW*AJx{>tp);A}P{$L#^5`yGCQeo`b4K*)Q%nOtsw%a5ZWx#OE*XRYV$R}#G(-&es&7LOpGFguKgRzGenrVdQ!0d&pej9>OKb-!eX{U351ccs+v_oz}88>TNgULX=E6sO9Zq=h-8h5EuVDFhTI{xX%&8E(4=i5#S5cgkl9-+Q^z9?k(!0be}4w2!Qr{)pRAE?lp3|AwRgi?Bt!|!w8I@=`;h&a&}gZYB!uQ&f*2E>1N7ukIY{p50-sHWBGn_B>ekg!TP0HKnchA)nh;I;WOLlHl3|e^34*4*k$S_m%Y}GJF2o-|rmyGx*WQ05uBm9djB9n~iqwW`n(f&nQ65DauzwZtF7Vm43`hf*jU%)47bJ&+VrY>vjC8u;yXM=9YuVfwisl@3TsW>SsB!s}5s6H7$qg3;vlf&TSp=!4!1`ai2N=NH!FN$$r-eK|i@}GjTIeJ{PPEomYnq|K}&~wN1np8LzD)!OoMsD{o#xK1o(*b{eLUA$^jT@5I69t3|Em;C2eU{;+~Hq>FsIH!q>MKcT>BhhvpKR_Ir>~oaK@!pnO_D$`SbQbWl0&o32j`Oc*_q=UHAFchf_Nfjchl;K_-BRJX@Md{lrLGS8iQy04Eke^In7iA!DEl$`$;yL_>iR-5492-1UlES$DBdK(^d~D`@om{zxa%(_&_VV`KTg1`7eRzu|Z*ML*y3Wt3a=`VXoP8{PqXZe^Cq<5Z{D2&425Wu#?vmklepiW3B>Kq<>E2}p<`j^vnZx{IiF^oM67Z4&-G?>MDmvBJh$>Z;`AnwCTzmu(K*C^KaPhsYQ=cUn1Yk$;Z#GKKbb7UaqmGv*c`&wM0zb2wXDA2dzp0LY&)O+D4TCUCPr$URYLim*u{G3Gpz!f4iICI{H(rAHoEn?2~&AAZ}^RlMUR}k|)@s84l5f7^`h%i@-V!w#&w_nZZi&NP1b9c1jyu#=$c75;K(n0jtjmFy|sIRsgNpI)+lLgWDHbmuGqK+cwBNr9q!b7E+L}xwJKQDjwNF$djmlT0Y2y^N$y=4GRkWXCI;8Ssxro25Z~0yZrH}m*k4&|4h46z)`S%5$z4?B}2o-JGs@V>~{+DEYME$BYQYPg%AF2`}v>Y_eJcd6mP_W)RX3QKQ3V$>(q(AaBVUXwug;A)>_sf&b2pdAqLB{I#7VoK06k8@VEsplT%ik64xET+jSC_1xUV`iWK&Mt;tYtD7@zoW|pT+q0_?O(}-t;u66x`!4##G7|1Z4uzSBZ~~d`_k-DV5I4Vc**y-HJLPRg=%-&<+yRB<+a{7C>$(XGS(`&G=tj`mhE4t+A4SYp)Ll+%FgXy_SnQs+B8LU1K8^j?x)pKXxI{fucR?TAfr#zF1N+A%p&Ty5em{WI`fX@mtTU{ek%+W5fMV+Epp=?uwPnN{+dBW`)5TUoz9-+)LNCC~k~v@`*RpZwpN(flTkRrnWVx6AseNM1Nc(v+s!=m_|NCy;b!b1%%FjT5Z9D_VhQm-)e86Lfn;vgH0Qe+viuj_lIAwIQ#$wvmeOKc&>=0msv7MJlC5qErEHYuCY0jS0D|DbHXx?xqf$kv?Q95GGI;QA^ja3ecQN9mTx^b#?nz6KZcoYMn6%wL-|&)D3`t8-{z0`@tm&Ex=o`b;EI$nbN+!kA*oTTanlnrkpK7`$-0VsP6-d@+a^$;GiX$=Iu7|9tLD4IrAY;DnG?fp8R%Ef&mNQY>7asCwrI`idgSv~Vcbgba|-+po*9@3<&JW)<3U|fBHeevvp5@Ux<09Aj3I}lhAD%Av|QNad%n3`l0#n|I2@NDM}`Zgyy7a6=qGbo32$JO44XwhB<$jNCqndFSIwh9NxI;>>Ceb#J!?aGWET~hJASWmc#C|9`w}-<{#?9Jr1#7)@`=q_;pXX-1`T}+mDgUS{?0ubc4oJ5}8RKDn-2cv=!;m={B52(1w1FaPG$w7pPYVr&&9HX0&wi?Uj~PtH1%uKBV4G!3X=t&hdDTG{uv)XNQL1k{cU$%pr524XI>Q?kAS1Zfu94;AJkcMyf@@b0^~ZrkZ6&`dXZe4xq;e-ROq=jKa0y7_0@#&ecPpLSvvF44@s{ad?(oQRVAbBWDc}^BYBcr@O-eV?ao;HDl#!PZ!up#{(YV6R@X<3DUjB1f1sBib(h1I)Y3d7>i^~&*5P}@%i9HP=19|kI3ND~2J2wEZz(2Rc~1lDHD*)Xu8#lgs^VO4*R%A*QBk*3yyB<_!dyH)iXKS>x4Gd(#ZNF_E6%T8cc3X1Zs*OL+kb{bUzvH#y&aYb;=NJPv|OxH5px34igMs^v%1`GQBw`B7~hEVrc(pSU~uyBtvnvQ-#%$!8dMmT4o>Mp*Ke-Hd`HYT+*6hXRq~M|v^}V=p4PX2>N}AOM7_L);~x84B~sBkH!`fgVIW^=Snv=`XXoV*vHQE8fb7~kMCG$9@Yt8GW0*byq*XfN0eo{`Z?aMq;H(7V3Nwdk1DYj5xQ>YVBkM?1b{%6;CGv?%J~9qK12Ls8DIOZ~QDY`@xwX^a;NRnWB+8HvagH!zp8-<(j}`l(sQ>Ilzd?`lS>TtnY)-B&$J~S!tREbf1Hsx`4h4!M2S*Vv=Qbx2fO%)>0~yp6#68i@%Vc;w5xn)I39gr~1=&AN+ECztOWyS_OpbSgv*@alf>g-5Jj?UJM&x5ULJ3}ZgUY@KyLtfqM0PT7C}|Ik{eF{n2l@E?T0B(sij|M-RGiOLA)hC0?xG*BX2P-WN6&>`M1AG!DzofzVm3UceV7?AMh-8AMbDet=fb@oNgFE_kOMKlyJj94&aF$|xKNto{*?v&-mIr&5FrlWPaub+{H15sL{r#xr0ILe;m&LGY+F?-*sbmm>*uKB5$^(`pHP8x%4x^>A>?4Pto4!SVH&ur{Z4<(anI^kXQN+r4-L%J%-)Mz;a5|h=cc${PFrLTRCU;6abIt~DLU1@b{nMp@^<<8!c1CEuj6a_So$-i8Ia9MZtgdFZ9mE5#3S@W7K~`QRz$DZkdftgEBRP_#|-jcx$ueLYg#rrA0f@TBa5k(~+V@x@O*E(#_3oD&BOGN`+Vdlbug$nZth=}h`;tZOww?!hD06!_EprDBc=O`GqB#GGwKOk1Gtl8^7S`JR{pJZ`qF@}3w6e1EjLRjjIXX@0{z7$*0K;m}NmP^-g@^Mf%D{?x8L5c{42rL)ge*%%|YX5}wD=1-~6w~;$VFcY~Ex^9%t$~)&zAG9AueMQUzzI~7m^%su3%!xssN9&^RjLp!&d_o~-u`Tj+-fkpa|~O59YAXXCLZgJnY?4@@eG|2_pHgoZe}}aX&=bx@?&!1xUVC!+tlAPl3n&eeR-E7|QjF?clh7^NuXMqN|;h*dNwbV_-;mSfKK<+U9j7If0U@qEe0@axD&j(1hJX$T#9r`J9k<>}$(ii;+*li>tY76X*~T-jE;ti=#d~(;N0noB_kz?yl?MMtj(;U6l2kvf*Qd;JwY|)PHuO-*J>#E)a7L)lMJ>%`8jOzI9}IX}9sl0*<*A{i#-es;EHJzZ1C8PYMYEqk=vDIY8_eOE~IRvlsl&*D=pSO08V_w2mkid7;~YR@u4MV=6qsDTbkUr{9>`%@&hqKGOju1hvMc2}-Ww~j+IGG{4LVIxragqNe;l<$(^Hwzlbc%94e3PJmDPqXe2EAIrZl<6W)`|LwdF|oi6nzitY>+&l@Ve$9>VYQ*o($~2PGa|?>pzTnzvudUy`{z!AkOiQC7`}q`f}3b!9^-eRcrbFP~zzODrZUMPoe>Fe}PLP6u(D9J*VS=bXfc%**Vx4`JY*ww$fgQ0dwyz+&IlZ9rZQtXJN`$27EcSZvJ;kw2!z)+|3(E0fTs>vR+=)S2b6^zaDv?0T08{jpdmb=buQPkdio(1H_yer#r}J+4cByb(*Yot16*W(6*8hI$~Xu{4TVMT5*8XAVD%MxGiwvR1xJqQi3a1wjXNQD3F09~5og%YfyvXATLfBj=L9+U?(eF@SjPn_`WA8$lN}3V)Uc)y^x|$~keI`$Udh;J3(vwcj^S9O%IK_T2HCa&T}iJhj*}(0v`_{1^Y*Dit&`z>*)I!zPf=>Rs>D-*!=;+J5fjq6?S@iTBLjU#TFlX1Pzz9^^*oz3uO4aPGzxYjZksqtGlB9g6AjD0a=U&p(ly`#!(8B4-8+dg(}hh(kXl{u@6h4|dh>H5xEibK7RQ#fS6Z&*&Mlbn@xJOF3y98@(kC^b*QhL6J*|%9m;}2=UMqnWI65~tvKQ~BAg4fHKwxarN|-H@g`%TF&QqXI6a{|VZNxmILOfPq=4e#*;R)e&`+-LICwHy`AkVfY+Rm(d4ZS{RCkaDmzF37#H>L+PA?={y4KU->Xzi!f1V+qO#{W!fBWh1Jaa%ijYD636|)bLiDJM(WOkMfaVu*(yGXTxX%>$fDBh@g?t}YVLp|;7tWm5N&$^ziu?m1)D=lHP2CmMR9IEJ=I&)Z^pl(o(UBFbxFjmf<04;-enQ+c-)+It6_pEVrMr;Nu7WUG6D|gj3U#=>`H|0YRV&8_*$g1s5jIV7%(G}56p4_{gP0}Xm(J(VSEV)^#C99!LinS*sUaNqj^-qmdd;wYPd(#Rd#X9=c(-mjm8Gar;070IbsiuG=f}CtHPTcd-hbcpLk^51i?3_UP+`#znegvqj&m`o#}l6$XmGHeKX!16W4`>8xbP%a9JUnF?Mmagr*|#1JN(;926%26j)_x8J}c_8$7plb6S-FyhCz6`!$eHepJEt>N*Cv&9k%i;Nsx3OX%wj?K~j*@c9fOhpD5B1o#URK}a!R`{x9#U)`RG6O#Fr21FnCQ!BAQ=gGtBI{ufkf$Mkh%n@PKIj2)4*6!NG($#qIxE~&l3G=p0q4_M3o^C5Bkcg^mZys_@fgU^ncL+?`X+>q$AplFi}K7aa?Qud-AIF|LnTM#lpLBzu1;5*FM4b9JPj-AbcIR(PoGW+m;yB|xikS>#OK2zFvF{tt1L7R=trptJzvm^`ZA*nzdmg7b9CLFNJl{GlD$Io0gu{(u{<1%GF8E|@E=WrzRC?dWyq~8RoLD_h2D_sCItz2m?~A%d7VA1ufi`fZkNXVjs9mDU=Z&*zU_m74WugD<#_@t?k@<9hP2w8C+^C~izvlT>aSYg%x04yM0r>}Tx18~^%7btlx54ZDcs@v67i^f#goO>_USrev-jkR^rl6D#X3LV@ojLB$%t$0kE|ty(nf@=n+r=@?Z?btC@|{Tn)^_Wip$g`^p)VR@2M$tzc;`XpxQ}h|w_9+clnOnmarCes$ZcbLh0?MP8blsmY4>_Ao@Xhj2sEocql3lPP>U!Zw`eo{2Ua8JN7Df-+69@Ak~<_Fz775MTFsSJuqqSMnZA1N?HKpcE~`KOn9JJlPf;?e3^2Y`%h0!|I+59Z@D$~dkNZ_O-|Y`6?7HHrqsWJ8*K;tO6`zUwwvm&_C+6;FzBR1$$SyJ2k`#yB{7R=Em$k5d-zWYi;(e&2wh_>)$Z$ktE8xQbx#-&vk(wcOBy%G0$t65*1GDs9Yb?iaMON{HJ_&(}1`~xltMU5c?~6LppS;1p9w`!tqX!Xv{6kfaG5W-BNj|6NrAx7e6r|W5RKrH50iVTF;;GEHw{^`3dzY$SutHVK#FE6WUfL9=Nm&bt%z)S(}^#L|=rK3cRm7>two8i6R-O!}k`yTZQ@JyUOACzbqX^?EjoPFfYt#o2I)ZQeo)k#p353=qFY+2?5*FY3zR59xFJ`Pqj|&kUmcbqA%&@9OU!S&C*!Mi~*7mez}WdUPGF%T=DODc|i1oS*?uv%6Vw#((PCBpfNLH$K}n)jduMwYj|H#xJ1+H&(N*78*4v%80QnXn5U-(o_Q%N-D&HWblhg4Ylf3#C$>#IBHC()b4oS$B&Lx5(wu#z0d`#7$}`~s&K;8opjXV8G_=)v8`H+D(ovEO}&#UP)mY-4Z6ojj;_aDN}+&(TM;#nx}3A(P#gM(_giu@UK!and3~hTghLqkYtW_F*3*=-W$y9cNX2Dmdnmw>XXHTWwmp(`@X9I>SS^O@#Y3jsqj!)F#Y@&Nat%a3A>K=-vh*S2!bHfSxyXk&_Yq;~2VHaW9*djkC$BAc{Tga#=|<-`v-$+&L-u$ivcZxG$McsBdPN`~e#yb9#~oxae>*DE%`qS9*Y{VcLysxIJwn?TA%+~3{=Pr6_ZAh*_8#VPo`W1tq{s^Rv-Gg?sDXLf9Mo6D`w+c@bU69V#BHw{>Z^AeGyY|w3%&(0WCq+5`CzbrwDCWVmE_Bi`U9>Z@laKQ#*I8L->9C`R80-xapV)Rz7=$OWR$kW&So-w|`YKdhhtf6IKmTh~w*T~!V)iM&UJ%K_rvjc=|0*@@?gjxuz1y>v$~_H($9CvBz5(ori@vho?ZXzyRBJRWPF2g!E?eBKq~&tV8|{&P~E370>elo;NP_qePUDPF7SX9980{hm60o;r)o$09{jfjBo7I)-^lD7SsMdr=nLc@;G3av$?M5vPO>k=Xl64F}X$D%qRVW-d~oJL>+NiN|>Vs&?pL&0S#{Fn-3C1lwZWiEbu(C)b4zCUq-ZlS)uWJ&Nl2GFNsd>AYK-^DP+JW{JZ#zVD|1#m!1-GmDpYVH(-=KQ+`_gpSc(}Ft7Rbmv2|vNe0qfN=->3>VcPT>g~M~6d>l5D$d8e|G8t+@-}xGr1{P4Zyn^qWBkvxZpPkpk3FXX|w@gk5LAr_y_hGttPILMnKvn4Jd;-z&x+-iJCWz(#0+oih^zV=fra8$%sM+>b02%m?W*`diJ{_`MM43p=DT!C7HxIjquln19UhO&4bZfXX`xgAW!zY#SkXko|e)&#c|Kd=;@ZErPBFOlDcj4`D)~>=DAUO>6&cV&I*Vn1GwIm_6$b(TqVI&Sh;Pr8OA*^H?6@9to-ZTw6b}dEb{sFCRd`Yg9^QH4I84`4CCNuwHJX~Jz(<1y21z5}O*~UtYd-`c=5zRYT``metj=yQZ_)p}QTn9R=>bd^DVKwq8=l3q!d6)sg!}Wo_9OqoOkLT$)v+@p0J&WgrqfW4-oZqj?&1CDM?DNP?F@2IoE@86!m)2?{H_xuteJKX{U}yQ`pm{ZNBj#=86q8^%_wd%U4=|q+y2wJE0=AzWl=|c_pN2%99-b3Ig|T%h-<)4z-V9{U{!+%EvFC|geujRs@z8joRWTi8G@93ka?~I6979)pNoRo54UJi|qd4x*3U<1)LDUaKn%LXG{9k?%KyKHZ%cb88bC{0BUXY|*oteH)RnDrS>8IhPbiMhqk$LSy@u*5DqkjwaqxL;bU-pb4>~h+23^W<9aUxeJ?PeCg361eUj{zNrz_>4^0H1Q3^{2@DDOu;4+W2n{&LEPPR)S*uMQy}V%}w(4uyUGuEWwz|Jh@9D_oqkW$CD|`z$BLki+R9f!Xt&Xwb4Q)%MX(jy~;+ULKXTqO)~o{RnahX6=rWRT!{gyOPMT2(A}mu7T<_10K5^UDD#o;U`v4qpHgD!0!=F%zOelgmm8x;M>mx)v{XaFgp5)%ZcQgCBsa3Q7(~e?T>tjxgaiH`S4tq6i0POJ`!iAgZ96ofZs{G*cc9d)#j;~H2Q)H#C^Bl9Qul-LX?afXh6)*dBmZwYFbLoWvFz}z4vq4ltW+f&(pbf+KU0grQ$J{Hle=K9}$8A`8-IqYxqzVjvUzUMqlKCz_xuK-_AilnIrM#(^W4fWX^ppzKMx`5~+Irm_8}k9x*03Sp;UH%Zx2z-*M!dTcgcnqX^foAWmvy@8s)XFFP023uI=sG`yBt-hvTz)+M=k?cl)TzJq4^Uz4pz>lv1Tbwz7kYLJ;bo2O>)iUSu&q>PEsfy7APXLnhS3FIw#I9)FHWq*UN2DIeT;AFdCILLJ3F^i5#Hfdc59XCrD7hM$M1=NmVsL*j5=vf4e&Uw1D0^(uDc0C|h{^w?6=14Q2{ah7gW^^g2?bspyT{0|Qlrzfc3vp4@eth_AI3F}u}wB{_^$vlYvbq-v0QFjsZPd~H#_9X90K9z9PU7gp?92Bj|hh+zHvL(6EPSl;{y$V45Bc-yn9KXjaY2EI#n=;|4`Jy99_b{I8-fu0CvLV54kr<=-4w&z3^6b}qxk3S=Ki?)k%xlECH4kfD%MCfWZ3#s^@Ov~(G^djeN8Gjx>ZW7fuQUno%~+ZT#QZmq4*h2@Q`R+oD8mF=q6U}Z9OV4t@ZK}Ri}JyxXZV=-TGU;gJYT@_MLw9j-*1`j$Me~)%CF}0LJMG(+F#G#P58aEeiHYzZe{5W)`s^G$9$ZbfrdzHFEZSG;CjuTqds$0^p%s5CKc@Y`*ovzF%K@@c_k_6F%4Qz+YVViz;iF@Zh598t?-lc54>ynDT@$Qdk@G$Fj}PZVDj1Ed*o>SVjijD9B@{rLs#+e?0R6TiGU-q3tz5YA(Yc^P8RI}`>~MFiJOxf?IM7wHfo^{^p#Ftx$<3f$GL@mpky`GWfVknUy^8ia(a9W&#{csOxO@32K09s2bXDmqpoAL3ltp@yX^#(2`zPa~gn6OowE+j-EN$CDW+fca59$N5TmE)&>u(z=mPt(Jyg11q0aczr4He1(2xr5LQ&0etdr!A}xM2NCb8H^BD?f$Z=WrDd=8^2(2D28QqQd%bB3-uvFrR)D?sL6RPlKg39~IJ-F<&G+;W9KErNhjivi&w&A(S_)WLOc^n)F`ssh?3(DGLxUMV&(~7Rkb?rHTIz^09X7<1Ck2O*L!A|$sH_eHi2iwY9PjSOWaY)$)bl{{(bDVf!ssVYnU>#|E@MJqWSNP5Ao@vF*88l1E++gEyz6*d5cxz6aIFu#oDY1SbdS0x$cNx-y1oF2`F`zH$cM6f5h?jb0W^L+{yV7}`4IgJR@qa5sB_D3+&d!Pb=ZW`AX1Nin=>E>HM93Q7728Kr3;snq>zK@)4v;AqZwd8494Z?17_^UrL^`$9^5$D62Rkw>t*8R>!^M$CiFjVQ%-5+sB<2gznJ=q33ju;?dh~aKe=NfEXg3}gP6j`$18Y{579@lcS`{fb1zLgInI&O^51=^DS)f5w@6MsLOyA#D^s%(q{E{X69T~;_uG>h9e;vZdidG*PA-ED$iYutT0)hQ2gJPDh#2G$U(LI(#(@c|qL1$t96%19zspyvv-au!`yL&u;OH0EQ(-I?UXl-{V{6Y^Ew6)a2Tc;E1oO^gJ&Mr59&t=qsn@Z>$Or97Q4e0rvh)Md2SVaD)~S4#7}>YqEMU(ucdJHywdFe3tH$_3_`=Jat0ac!k2mb5Uj5y51&IB+XEwe!T*BJe|JKWfy`v!p-=|RzxHO#bYrI7UTkR>=g&~;VpSx@IE^2=eJWUJuR>m{%0P{QXP%QcAgtFlWD5gS?ld_wnU(eQ1oUlH$)D(*9ZY#MOV$sF}nYfDRuNpC*X26%rMc13;lX0!2Z{*D58)v;%0c^m2|SC>EWOnM<~7s{0C@J749e)a3^R#)J7-z_=DcC=3k*%hr*%7x<^vu||n#CX15{=>=nCn%7x^L}gOeAEf&6ie&|18J~!$;DKWSEvVwd(4I!4B*#v{GRQNd4IbZb9-P#9Svp9|nVp9wR?6ZyZ3*PpxLdLd+jVD$b(tZN;jEKdDpe+7v7KVK72cSS#V-Cf5^hOzm&dkV`jzL9IU{o1~U3P*R3U*2rP(f=wh{lbYqG~oYaJJ9FD@y^R`)(S=n1LkEo_Z9V^PH;Yu_2BXZD?XRZOVSBIZihynuRXpdpZ$KMD;o7cRX{KO<672w-0$@~>M!yX81Ps6Ijaze`34OYsIS=h=x!khiqAH1%ty{dzw!+(S0GHk)LZ-^>MP|RhtBj2lYyA;L|TdQPI{%Ni7$;ks9e(yZ&|u9KTg{g?7!Qf(#ut0(FyDmf7tJx>WLHFlvMMXj1}%A&&25N$!b?j0np~KWWGU!5R)T!$9!z|tda!iwU|pBGIp#;A|KOFqthnSj#qs+ve}$=+AI&I7*Q9{f4jF7}&N5*J+dAzDG1~Dm3yuZ5ZHqKN!k=;Fit^4LlN8kN$~5T|u-5+-|^ty11jSv@I}SY`q=*)Anp0FpkM|^B+b(k%rxh`;wWU@OSyUGewveZue;U^hV_a@xE%O67q5Jk{jIYQ~+TD@k%`(kk8?vGpCE!6tdr;kKaQ+;>pU-M4Jm?QT5klU+#0%{i1*N<{rKRv!?EZZ048?@JeC*4SPWv{Ooi1KU{rzJXPKIe<6{gc~E2ujgrzJS(Kq98PcF4r6^>`SV;;gWS-~Q1>o@9QP9P3L?2e!Ui9nKSCKQh!NgPs4+G9~F(yf~WFEJcAkGKW*2ZbW=|E0!H~s;5BhMRm&iWymXHVja(aJ(&rczqg$}OUjGx-K=D7ADslP%U_K}llpq!I->0A(3H&9b(u}7JG$A}MLYgI1j(=(t*Q$x66$+I8Rm-rDbN`%mA&|uG`e8I8Umti5l$ONCD8o^AhZGQ>f+4953ObpP7#WylCri@**SFkRv@97`5DPtHZ@jNP66E)mCe7@5Qo~03l$@_r9xEiTgj?@Bz@5-$)(J7EI$0scg``AE?iCJb^ct=bl9A07a7uwI3zi4=uT}+hl!_mhKIM~`@*Q$yw=7u1A^t2I-V{?9EkqoOxAe)mq_}An&CWob@Z}~U^xX|e*d;ndk5k}al0P-Sv?af+d}uGuSI;CH14YX{15{-=D7{|d`2BkL+ASG$yW)$(Apq)Wh>@?R>z)Q|41ttA~Y%aQOB^q^9ugE7i3SS!mijRH4iUhi7c>LF5_43B-E`|0;%o@!61;9pc>lmXYB}Hd?O1wo@!2AvP6D0Bw*-b!5VK$*O&8C5Ak`;4Ik(4i%fvQbXn06RrF&;RRME#Ym(S~dzsVd&nG?wE#u2dfiQmomv$0Q=uGRC?bS*HpS$_d&zzB8(Wjcu(HJbhbSGImb1U+JGu!+EZggkB#9lRL?z70R9BfuEknW)XBmG|M!9K*3(3gHznh8IxOucEj$gkFAH_C2hjh8rASf7vl>dQ!A4G(KRt3Q0-ncIu_6Z^AAt|Y?RU!j@V&+)w`_K9DgOokiZBi4N|MgLY^ty46#FcoCHbHp|nlk|&5XLYUcPlN4;Ei*WCNawulq+Sbjro-Egir*&Mh#SYbv=gSI8PI=P=TN#d;zsEGMSi2e^0xv`-4}7b9Tmz9wtA8YXWo0=;c7sBwYpt@xd&@LGe;crFIgg_*&H-!1A|U6Kh84f2xj0OFR|B2?9Akp*0Pg5-CQ`V20vNb=2@O9kmi5iLz;kY9b#Qr+;aHi=!=Wb_*MgBCg&&zh~90#9x*O{A?cUWD&plM%Pw+Bgm7}py$tB6ge!M^KT^u$dtF8p#FOfO%R0fAqezZQ||YEmP9*dJO(fj;5IrCw?z{+Y=s^6nP}9{cUOAkKmOp{V?**W=twwk|>F7sQ9q50Ns?0)_M{`v%gv)ElgY$M8rN*z_H@TeuwU2elrB^Xs$bt6WMnA#c`fo-d?oQPBsHfWcyEPT9E474{^J_5T>y80jx;->}k(TOz!-oz^cF??{>RF>36)bwP**y`_vvq}1*#JK>j=gC0CJuc(K8T*}){$6E)R7lVmwbR{?I5hw8H_=dF@k8Z#vAVkvhr<3n`r?Pv;h;vc#SZp?ydXTh!MR)`O0&}!A19Vx(AwtaKNQRG+rvS)u+7^cE*HKzI)AP!%&SHG;cN&}~L^>#0n5eI|wyjNOT>m9p8aF|1nq`RBLSgdy}1G>-Cdxn1^4umdK7K;zx)6jaf@+`hDEH~?&*hc}Am<{js1`!9My_#-dCP;i&TYD!7=Lw;=PTiCRH`;fcinT+0q%VB7{8o?!<7Ix+?na2uj)#Lo@_AiFqnwzvf#@66h8W%N$HY-r{2I*#1K=m0gb!6sa>~U+_TZ)x7iR(0s16WY&7*SMDEU_SY|_z~tm;cV3b9jGfEBqiXlHOd$HlUeZS%Md$|DL}Wp`+k}@S%dYN=NPd9tDW__cvNC#-K*68`(+9Ww!T82b+&G;*J@2a0XWinLD#f3MO<%WN=SZ%uHol&ebxLQk6GH1@|KbeyMh)7kzu_8Ic4FY%hYst!@W?DKZM++CQzIuu2@&J~#n*WWmFL>@ujReSK@;#+(29U)z`++AX+x?CpaSVGEH!@W*)f^)&0!e7A{&oz%gChxq1*j31^K`{7U5bykq(S**D`T8jQh|1H{8#5q`-VyQBvF&qmPG*0K2$h(Mn)fh{KSf|G2%@SyL%2&T?e1--pr_MK@C%l-bdDY&K`Ct9y6U6P}h_jE$lPvgiVXEbLF!F@g`O-Pw52=vpB>uZ@6!~i7j)vwj6&n0|^KfZP1ma2PEY-cEfkyST&>{=uU7shH*4jKx2Fm*SJwE%;PhMLfx1B#A6}S|p_zt{4e|Ysz^ss|eI@q!Xd?OG2o^#OqL_QxDub6YVTdf!IaZRiDQD?1B+lmr{!2siEenymUTm$FR{-uxxV{#=YSCjgoDD+PB^arGa%l$QCTb_{WnZKOhXI7p8tnm0-`4#dC-TkZGzBf}qy!g@?IdQ}%-e>6C^72d|bU1ipN&NE$ciaBZEEoy3Ep<{M#ZA`_A*XeyaAc@3eS{x*#gqWuKx>rs+{dFIo%x6OSpUctPPH7^h-ednn>?W4=N3<>GYE=7_Qj4?rA-Jtyj3wq`(0>4n||Kpx&JFId*fTF(-7^wnHi0-0{lCw;X93YSTP>K>e{i{%-20tWI99R5<)#klT!7B2j)~V)h*7Ve{OJAOvfE6TNEISi{=ayMO@Q4kWI8Rd5^%PeLQDL*=MfY=O5uc9ChhFcBsqB9DTr!AHY}kF@gX%QsIN|Nwz8dlQy{E^&OC%A}lw02;u>%@JYwNCf8r`!m@{k}6jb)4r|akfirYx~YI{GMUiwF`~kQejD<{Z8!z$d|Upv|HY*r~TKL@G{=dfw$3zJOi>}`3m(>Sc+p~gaVa2&hBRQrwR95*~o8EWN80=kgT>(4RB2Lz8^RkLqNfn~=-Ztk?fc)irvQBmT0$4DGZi-Ln&4lAx(%jl)`A^xLa%B{GXx>-wt&5_31rC-o`zpuXvOkPcD8OM^KUVIHPMtaJRGHU&;rs{Y96!nki*t0q!YlL`GQSyLLjFz(+zqZJ$ZFAM4o!t^Rg`><`&5)pr9(b)CL_xRBsP;mNRdM6F2Pu9&c(s7@$S0suZkqXI%W&!cLpG%N;6;)5ZeZ7hfmnV)JM5>~_B=BPqcYZS5WSSHflg{;=8a^^-ayS)~3&OV7sGy&3y%%xQp(hlQnWP$2UoQFIf~J`Me0WB1^SMsxl^kEsMTO4fLD-e-ku$l<9rFxElb2)+I3#%!=!@*~9gD&n@s5X`y;Qo$_ngl^*mNxwa$HMYYz9hN^?pOyTIq+>7NQ*V`*0WNjH0<(iKo=R2@-PqShf#PwsYXT{xdhdq0TqYx#pzR=+G)>A^L??Px62Gq(K|E1vRvT&zw$Pe=66X4=#K>yOZY_?-IPD^tBH8=MWl<~ipfKDvd%9(tMCkZi3u@AxCchd3ATRyFOv{P|+!8`+ZDCm%k(s!gJ0IgXyMor4|bjpMlIwjs+t$c*fwb-m;o1M8RLa&xbODc;cjc7a3;unXg1vIjC_gE<^E8X1#1OvI&Q2(J73}FafM|xw!W_9W2{Se=SLiThl7HbPNvA!_M{VE0V>+bI*ruljyQ+>DKY~H{eI3LSVz6;A>TBl1|4_LiBfV@jP`0jyX&1@j{Ek*s2cXjl7Tr*or2cqscY&F`?Z}@k&)rJm(zM`|7ULuc5TDu_aLOC6xEjS&GNqq^mpC)?>Tc$t|<-4Q?sh{knm!B_B45UF$`0E>cKal#BC`#OrnL~l@1nK6qW{mqp8)S3V`flDMX%}M;jPJxbzG4|FEbad)?*AP56>+Y!;Vca%o>yHfcSW2JZVo;iYnTmuJXEi%Bt3_tzF}5^E9vlvFL>!Lnmhh(@aw!CwsiJA`Z6kxprW@BXm~=erH07!ZrhiQ-~X(+rz6#1)`4ZpEl;TN<_qVe7Z~nJM+m3K4Zl5$>94E=`-2?^^2@Wel^vy(|q4DIuLaq+}9E3>|oP-l@@f!xTGwdeg6OIWo;>>14a6*spU1qzwMldA+0MFG*)tN@-D^qokcJAyndSw60HfXOGth9h-0~5!zu9fLdKu7dk`ODzcXrS7L+_wy&>g_aZobN!E^jL6;iZbDpt%x+=8y=7m2dQOW8EQRYms+FxbJA3V(~`h^O8E#3Fs#?_Z>GZ+MWRmB?i~*kwJfWiT~i{`SlbKu4-J`&yDy5elcCzE1d<&a$A2@NFqKFi{1(6o}_}5`BZqSH{x?_+bn%vBN`BWjSfp;eC)0KX4ENe$yg+_N?br|m4hq<88T-zkin3ck7e4tiAZKXPXLZ6Zl`w2b?Jh!zdnd-P`Q6(`}N7WBYIG8@TCo==Y*5rJ9vlQd0ht%-jB|I#@v~Z4G%^Xrcz8eM3n!B^0vy1cE6CqOH9B%0adFoX7^2qRHpfS!9;@|V+X|P*```6xPoF~GoZ#((&WJ93+u42I}h>zCzLVc~WY<6E}Pm-R)jc@dSM_T(A+`Ic)A9CIl!a^RK6B^ks)``VeYj18HvQ`^4o&kn@l$G%$iXFIZBUs%S$dzy%YUFqxV8B$b8Xx~0)W{o%yy4d_2G$72jEFKcJdcM8cVbXi_UfXx{2pu>!dM!V><$w5eD@mM6@*Lx!9sTR=DNtv0s!ggxAFucPc){Hz3(oT?^B>xa`-ay{1io{wp~3GjYA5tRVVzac2glYFt8B>4-m9T~0`~_`$#~kHQlZ1o@+)ET6#V`--*cXB&!e;T_V*fM9!!L(u_SF71J<2b(>SSy{SD^_FFg@{i2;{av>qN6!918Ix7!B!Uny{O`sDBPi!kn=d)Iq-;&D0zdwHB{jluj?YvR6oExt^6FkY0fo`U(Sf^Q3_{l8{GoMKppHywG@ItRDSpYf!9LtUwOZ;3`a5Ik}I8{|uRLEQ_ek__;Bs@1k_9ontTcSuld8Su~3o7>zUpI4l4=Qg*TG+-pZy(zo_{aEw);7gvrGoa94-MY05{W)j<^Yrr0Ojtjs>#Rxx#fax;!POvQJ@qT*uhc(23Z|ITVLsDzTyP)qtGSU)MM13b-sGXEX?G%zy2%*rxgx;;;`~`kHsZYKVb!xsRtyO498tWVjrl{O-t>uKI?zv4s=9thzc)*do8Rp$1wP)1eco@5{_RSfU+wADSwPhNoj5>>k6uTbDnqHjS~baEaKt!BoLf2APJ`F;t(6T(x}&$Y2yV0L%Z4@io1d025Vz+6Ax7_5&(}#RPB4ttoto^@LwzasRe)YdTImRVnY-dn`;gQ}78(+dnXo(t~c{A}`^lzY~b4)U~HuhKd&UZn0%`%I-%z-R18L*xncheRIWraCLmR@MKbk@|>L83pYSOsB$+b-pc;B>(@p?x_stD;lu-IC&vHb}#p;CwF86Tc1e~`2%a2*cy784o}nqMc%%~c}4Wq(8nKC%GW5miVHB-klyHg0>hJiVx1`*w{dWpp{$({B(?uMENcG+kk``CAS-f{rkCIzU>f1Y|ERn>5-V(6MLN>j8hnjnIEtkdgs`iYm_wk0;L9b7#MH^B2toVqe-*hLo>h+|4t0&VqjKc_qDTFrGTz4&;!dQrUfqeUx#Y5Pe{COK8B`wa&)C3FpbHBx}V(EdNZmH4Cup!uY7h*PQRSj}GqF80If6kY5FB_O4hQNr!K8mu@~4LwveBhc8X^)4_7@Ym*iK5TC_M+J279GGJ+7L;soIh)-0;!iV|;88FwFQ*5aP@(PNE2jixCCN#w-+)_D)I1u#-qaInncWy^$_+i9>wOo~nN~OZyQQ<8*2BbXa9nISL=`^^>yKK#m&xpglt*(Lse%V0e^G<2tJgHN;#`AU~9V8!2JdAF@c{1&ked?em9h?;^%#|JSJ!;i5S@`-T9f)&U4JtT)o=7X-(qX;VU2{e9zLM52g-@68TvgAPu(ElaBoIC^EhyqI;_${KS%CCz$UBrEdx2MA)*Q)H5q;p&G??{Nwxr7F?1=ow3oG^~RjUO@09L)x&um@vD0x_?(EWNt>PbnQnTt;grR57n*q{etFe1-ugn_6XbsL01c+^u9p-!mXXMpGg0A?CGmpB^?B)nu~Iv%D-ro@NG*SA9)k!s?jcdZ#y_{Z69utk1ugU@W}t)BZx_Z>M)(zjU}I0~%N9bVNy`pZ}Oty-M>+7F4!wG%c#cc=xzALXyj$2DHISK>wCA_tfp#A87188s#pez9*7Lek1`Mgi{vBT9bGe-9BSc=rgEv?A%22ON-5xXu8Azif)eJPdKp{Q55ju$GUmB~K7f<+hu%ez3;N^-(i@7O76YOd@3cR3;M${n~;q#CexioY3$v6GE@wJ}LSL`PhoKf(CQxOty~Y++mCt{;z)sn<-P_mvgnAj1l@npErTW68N*hn5N1Hq`2U!<31&Phz?L*eZOA;;{sd%^E(}eD|tSM#$tTjJ-;vegd+pI!xtaCtAx017Q0`6et-cRc1w+PFU9$`v${92Sc?g|0xe&TEJHl)I`nKi5|}X2H`V`P7vg#DUUaESKNC3K40NsiiFhuuJNPm`BohdKJZg{rGk*CUFYoJAHgAczfN>!Kx46%U2;j1W$hWi4NKOcdXle0`VzI%T!3b%zzi4o_{#ig!r^))_pnrmI1tSmecp0ab7V?Z`UtVWJ3HEBM>-(xDoz+egG5VY!5G&(m>pZd292A32m=_?@%yC+??svR>wbQLM$_qRK+t!01+?}UTyJ;aC5x1mZgfwrmTWGbnTVT0-oDdFo(Am$MtNe3hF^wj)oBe)W7R>36)4h2X<7~$GhH>L!Dx{uolp9e%9Ef$`Vd-pOEyK)jNRj%d95BBsEl&rcPl&(d|M2NnT1azKSyoMF>x~?8!g(^O(-twI%z%l8lX32(eO2PQ=wve>+|1v-Km+k9vbfgxo}URC*5am7KM)_+8V^p!IVLnm-Pd19>Q9$EncOizVa2b7_G`<65FbLIs0ZYEc3efi;Xk5OR{WF-8Os+{?=?ak*max2*-(?DUvd5f;*eTM`F2N|&d%Qk8Y2#bA5mh^;iGe$ZdE32mh>!L@#ry@xHG~X0@Oo#UwZr5XLP@iGl^R=y8ycv-DtYBYOGUlBw|NZ86XEQ6l5C?}3X@^8@`Fg+9$DmFxy;p+LEBr5W&iXD!_X^$9is5Rc~-6iB##5tE3eI^vNDW84#jMSI#dziNF3nmcyA1fORtl>oDSJslLeB}d~P^Dz?b!b2O?J9}Wb*-*6xIP{usmFtH&FaWH&Krm6u*#nLSSA7az!qO4Cx#>gg0&x77X2gX5qbSltA51*ziZrTXMZ8TBJ`RZ&6q&c-KQQyoDId@ZLW1QVMJ=E$c_*5UF#WFu4^C2fu#Q9dv5(jezoo4WI06SzyycO2Yx}c&nteM?EE1IbWL83{3V;v{Pe)N=f@-uleR!y#GuCS6>O`d#&it-8Q~qtg@i9{lmN(jCa#tx##WL#ekRGQi*XZ5VuLIV$AiujMf#;rGasj&RrC$TBgI`nU#bZ*xLUUVLZkMMF_?hhSY~C}(=eRS+In5(XIJr_RO@PE7h(2v&rA#3DV`r24L=$=_qHA;hd%sBMEO->EDWbMH&~#VQTQw7L8*K=jB~+XP_qo?Q6+cGYz7D4REDNMU*wfBMo}_c@%pv0kU3%F-)T?$c$2jt0w^FqSYu&AqYmn_oZ~q_ydT?qLT9euyi{lLOdjHi-T%c_1FWCNWVHzntcIApvNd>wg#4#at~C^N)i_KFM7`gjm-B=)1KC6Xx|;sqL9w-do6#{xYM2GuL^}dt}F?kxqj`^;KZBlRCawxeFpLhqL0W9*7NP4NH7KB5Qp>M?uKz4r-NMgrgc}M5eGv4@y9PZa0Yt{#-t$*-*gIvQ*JWYd7Go<$ghYxEBi4940lmCoqK~g)N1bZzI}lSLZ>b$yw^rvana(-MX4$#7)Bb3ZX)SNiFb~>&RdxS;Z}?9KrHf#wQ>G20wy`^I>~8El78vYqxUZkP+^_Ze!&zUum!yv!PL!8J!!9IDD8t<@!m34&V9LbDJd~4mVUB-kH2*`7w`xvl0b}1J@drko$W|`_lVFJwTB#-YIFLU8ie_-!$&I%oZ2%%kF}7Wt%Usq3Ek&Ae`v7Uq@?dyJLZ@CM=2rS^XcsRNkKQ<*Q2R_a0#X}*!6p_Ncs$U?>oF*9GD>ZAT=lGAll9P?H~9oWAP=5vA(Ve?i+%6y3Xma9HI-#FDm>g?Nd2yh@!fU0ubTH&HvHP3vS>*^?n5P9%IWXrV}L-o*WqzR)CU+1lHKR_lL0csfzNfgZ}@Az;NPY+CLHr-7U<8yx_3fPYDggm8iwW_c<6{c%FnQ&>119GNaR17n|==Y(t?_M2ZRK3**ruq5c!fk{h0e>E0#U1E2wsy)Mrr9>AQP=E?eIz$Q|ulrbYjSvUuZ*_nIF921w_>Y~#JecF-YAkhP+?iSg@IdHK69iVQGoZdSUz4*8Xgr)}b&#Y}d8L$@G|?>?pO+YO&EVJff0_9jX1{e(Jf~}dao>}DFyjJ!r`QP>cJfFt8-j`Y%$^~^vPKM%%dEL40gAAxC!}{cR}Nm1*>!6S?NZ1r2ynt#|;@zEG%+?-G5#N`4uxE>R$^Z7b;|*#a7Ki{0qM}xi*y1pw5uynzbL_cY*US-g921194t_Um5zhhPhmO28r={=lZ_)CG`<2GZgVy!i0HdVip>i$geWR)%Qp-nQ+G=X!{`F|8VP8nyX|pi@}N`>C;)`I#k3>eP6ayYDNw_kHqVWxLx@@O}WmK3xy(vq0^2y4}Tk+@p^GG7n-~-@%{=#JgaTGU-rc1f_CVs!B=63r+&?oCh1`s^ja;X{>esv_{B5zTb&IZ(x{8dHTscX?GfRfu+?C|goNX3eHz9EQ{DZm?@cj)=sV||jq&kcd6`{p1dA`}t(oih6Y**MaO!)2P!16Kg87%iX09jp@6`QrAdRa^;xHfLM(pG3e9r-HmgBPMM1Hl%_lHQJQZ9VmzoPBZbHt4|xr&zOnF}2@m4l(AbBKp~vhJBI$_CzYipvmbpD5gX;JrFpjw07J(x>7?9AZDHyaE@sV$6c3S?C0mQ!9198NM?q9U6&V>m}Udht#>0(^yO|!WwHpzsVv{@^s890AjXFs<7eI*AHF4$iFtc3jPV)8pZA=Y}9BmVwsuR-KjLR>;rm9?zr=zL9lO%+072x|w)SualX0!9UP85u%!g`LTUM6&?yg)JDOFCc1>GGj*-C720mXu$+)05Pv&s^?EQZ)mJI*9K3$SZ29`g-3TXF~l6%c*QtXG_wyZ2%>fqenySmk`Eyn6`SINoIcz;TBS+*{qJ4ps=Ld4x`x>i{A;0R9e7o`d`fOnQ6`#Mq40(km%ONVUc+{#{ltSl6h{LGD(m9eW-pIP$Tf-%Y1DGk^Xh~(j9?@&f9?uX5;#|o>7Ed-~Ezth;Ar9glei@Z?CJ_C2jhEs)A?m3*g>(L^!;kylJZV-E`!{00@>ULP=98S_*@=GU!Cwi-!)-axdAWVn)gQ>ORyG)kUSU1=;N&Zk+K+JloO!o~=CLUo))EbCQ;=UxR%|@DSd-4~V=j|}I5ey7uemftXV;%-S0fG_Tk1j|-(vuwlhNCSILNXVWKj#5kj>E4H{wA1PtWZetnahd3!$g0E4CuP;(2O0Q9Q!BUQ+vH%vHppwKML4t3eK&(kS~Pb_4lU=MGWo?yMZJc5JtblEC+fsCPFU%Yl}F(^IWq@I4~b+)zk}Y2DN;jPaNKVG$0VLECR_dX9dQUH>*e5{SOIb9SLWQ43Ezy}>;SY9`+{FFlEVJMy&8?Hw)AAd)Lwx{0J$b}RL4!LHe{@WNnSz=F>>KR*?Gxxl+H4ru&tg&WV}b5wlMogX_p9(953hQndt=BJ?uK)`kLco@~z%^pk`vp1*xKJk5wXx90)QtBNFFaR;YJb{%s06~zBo;T{1Iek1$)xj!83_x1UJ8MWng*&GBBb?ur`ar}IpNTCZb?Lu7{;T?V{U_<%8_gxexY-C|3c3m^)p1GLD)Mit#<+Xd7_QZm*N;GI<}D0HyZ7RVk@G{SH?jHhsuEH(!?42+Qp@#bH(F9H-`VhODD9iICtN6{rg*x6wtJ>R07|ZwuAY_H)h`l;{6t(;d@bWwH?G8bloe3dG@kn^;6@NLGv_I8(MR_nrG8+DDj1e#@OPsl0{$ZuD)vFjd<2ijTXA`NeCT}aB)`2*7-P&HSq?zkYE^7+4DaOO%t{mD>6JGy9@XnEY+Z@2;)riCD-+2GoVo98VtGs~FzyEB3_sM(Z{I@Dwe^9!*LD!p<=dq;x2v~3_7#xmz56n`;-(57@>*$>DFt~p3d@g?@{%#ockLrufk)X9y)V@^#VdY+KIoL`D205&rohfd#9()!jijjK;$Vccrl*F8U@GiG>Hd+T#o&;9ccfncCD#6z!F|$&OS7;@_*mct#t3#oXvNoJs{#ysK3|jlo>mr^CiRQ4>t}R_HGD5JMnkCZZO<9&oe9kH-10ShvRW>7*ul@wOGog;_sfj`%}X_61tj$W4H~`{&+Rtyw>n&XlRpg;&VbfJ@8>yib*VZ$$lNQ^g;VxuWkCO@8W>-t4XU#6xyri6|e#cYrHq+8*rtf-6U?-{Q$#DK-5#1)~3(gKRZA8^e!Z-=Kucp1d3gohI18wZj@Ob;q0Zd@Dk8zT&l4O=;{>n%&6*jn?13XjGT;0`{mZ5Pe>zz+*AG%P4lg_t0))KK=Yq_c@1MxprZ?|-I0%V^C&_F_d;h?A);;LRdyqhO6nNaUG0!T9}p-28=iqah=uXxXpMkpKJr4KZNIV|�I;p>;?Urg)R@}W2t7N%!0ONa^*b`Tc{y5k|8;ZCghw=T0QPZnULjEwE=G(9Dc6-L2bn3uTz05!mWppW)IU)}k6mdvhI5z}%s|}i$#`(=$e?{Z%`HW3r;1*T=;1~z4H(~5(qN-p7@Rx3l*kg#}`t_Bu+3rOoxKmm(6U<5L+!B3@!zZJm_V)2-TC&I+|8BfMJIso|guc^M^O|tvdiGWC$cl&hDJwc3viOh3a)qA30EB_Xu)=G@;#CiF_^ceVLEI&J65%0fj&Ku_G;aDKfwJavpjj%uF$AfiCz3#@F$Xi6~lzHV0?g7=~q}kjI%ol|p8IZph{tz~n_gIhI!f}1b&;L2e5d^nnJm!86Mm{{E96Cp@Jp`6_?0#;t5$BcJ-bGa>)x+Ua_@*CMkKnw@&Ku3>VDbCiQX|c=q&}+bkFC*gk@Y7v9PfYU%6_^ni*F3QZZa|N#rr?8XKifWk~o-(J&`6z+TVHobNG-f@lE|+-PyAbydfx}~-I`s-9wTpjel0ubDQ_TzCk!2kPsMrFZR+W}O(g{SLzwf2rf^;*DQ*AVHWmg(A$%bMUr6WwEM4&Dw)J`p1ILoxa;-MC&Mo?U;=k&pHTzEbW^mt5I8uAyo8zEt<@^f(sp4PnAsfAqhS`ocsy$bR1%07VmP*50(n{SK$1dxJ|`f*~%@&O}NM?`Mt6123%z2mrW@~8)kZ*VkAzpO%g!}{5>yN%A>+c$WZHSi<9@;wWfFJ*4yO9|l+C%!v+$FUh06O_}(+{fy0=M_z|PsANifCW!|U`I=0JNQiW{)pGVj`>Xr%wM9|Uz%zS%v26$1?<9SE$$Ksq-YBo5Jz9?Z>e~^=ShKfr!0zj)hW7VqlxF{j@sO-@JIK@u?Mv1_?~_%rhVduj8$NzU9_Y#Cvqj*y2l(>MRoRw+*Awe%J{uO_NNwU@xg7bG#wwfHg^z<_cW#|S>KWu$PacJ=+aMMW&3Q8M)A!LXvRBTo@Rrw}({U?{s!+(@RKz!`|p{Z@iXEqyH?TKxfQC=-bOQ9M>OH^W#x5aIkZ1i7yrHgx<=?xj4AleN1GNXpjO>@vr>}UTt9t%XDG5a{=MILjX(=vJD+54fB8fYi#__vqF1JM`s`7E@DPijx`A4>oc<)QPF<^LZqb@F59s~!DtA4-L>Y0wVRnwPV;{X5sZUp4k@_nUOW4zmQV*0c3a3nkvIQ?ln2=nT!|GoMBk!YBtoK7!UkMV--pKr$ihpVr|xd4psVY4r-9}kWN?u|$C3$zWpnXE4F~~CV(~G+~7@83{oFSBHuL_7z5j%L~>RYAaA+8l%`%@5DSIE9s{x;k+(eUnG)BF^Mc$xyZ7sOVIGp$cPN(ggXLawPa@rMT>fLruIySA2t0nz3U{j_9}Z8mQ#CIR26n%lR~W~6KI_%a;|_z|6Zbz3%tzkXqBtNJBM<>^V?`L72QYu4VCl=F)*8vqhuhu5_^$4Mh_QslGZ%b(^U08;D{^I#&S6?%3=n$f4@iA3R?Mdr?eC9;`P{GGii%^t<4=guM8TFi#k3OW?=IGBBWLN^V@M;M<-X>y^;<96QaRT4f4jFHAkGxHv|JuuvU@#Zk$)4Jo?i|D??%5+)!~YWxRi?_ngufBjND*{g#P8qj>)-A_unjypMz@?I~(b7m+tg+HD$iagPSEsdJhSqmZ{0FU(YW@ht`#)5kZ|Cn6uP;4T!oBE^c!!kTL@dm!(+9mv6F{LYnqPA&93zDMjl2J;>`REe$*m&bW!jm`(J=V2_58;Dn3v5~TO@}A+KD>Mro}PvZVm0Fa5LJ+Y8KAg6c7ugL;fuuYCm`i?SxKuh4EDwto;}qmelNm!Vv{rjS)2Lo=%0=W?Dq+@NES3D>0gL8VFURXUxK@U~PY(vYGiA@J>X6T*cqP2dSQ8F`*<8A|x6v+lbk%g}t4R2mFlgnmAMMY%DvSDfS^l=%nl`=w?T%(Ad<0p1lIVxCp&RpWTb^3@53P%blkbiRye>ey*Y*w8998kK>0s=DT?pFy8<#Yld~64`ZD-#2o9%_yST)xnS{L(F#NWmV0YI#KYR@B&BFc)=`aV?Vln!A|C&WfdjJ6oIc~oi$Y$=J(ft1gD;v_Z%Ia?-LrRmzSF&U@Ho&>Gk6f~f6ORS8`mZPQ7<#Wg?2L{5&6{{RE$|GqRs!S+v!$X$9+3wKmS9B7i1BprO2;{{q@gZ1K`Q;2aDS}k%#cLh+1!784M-Yf>s{jB%M1u7MJ;bStyA4+1nVZBM-S#_B28DT^QIC2ZPlDXTIMndHEp+#|XFI$Ch754+w^Rv5=c)E~<)34kAY@uQL)IIaqvU;RFJgJ9&RX`)jANxz!-QyjuRFObuKw3B5+AicFrd4y|hc@`bcxSB0B9gvzy#wnBj0FPm-aq$2-k23|#(ey82#5yc5A9_9fBDAXFz7BCwJy4e_fP2jShL0}nC^4SXffVDQ6KncVHBiBRf*6qlk$xbQCAP#j0V%*^5s|jFm8?pM=wz*i-GHh8oeLi!?@30|H!!ld%g_dxNc~Sy<23nI#vv^qm$sK;Eh}(PCMWuGjB>ZB8|JVXeo2PT@)9SI5tIUA`~j3%aH&9qmZ@Ubb+LSRfE(txc1Nzg>*lsZ&BBpy#Ymu__&LX1_;?VZinibMQVx)OS{>R7QZ5)}6!*apWz84#nD#D0Ux7X_Efo>V&uq^;I#@G``+X!Q%hRcbUb)idSQY)kynyM7^|Lfd#N;i}YJzTwnC`>2Hhoa|dH;#}3(MoF{BQv(o3k=k*Es6|uh?IUWER<||s?y5W7AsRUJV$cF&0wabdnCiuHV-^o7Kdw5nrvRb|S|K3llP$bx}7MS9ym`Ad2aIPtxhyuqy8@6?XBhOJ|Js5qT7$Ed=R=maQ2|jZ>2vs!#->uvb2UIxEszt5|Zr%xWR`!#gd2YZ)UH$8AfyB!gbvX8^n#dpdM*&|;PzPIVc$4$3^&@mdRLcT;y+xa(q*z@qt0AA02-i$!@Jc<5`_H25$tMQ&tw(ff46n@Xr-1-ke3nJidq3y`X1lmnH6B`^1qTrTxmfjo^PaAPf5-O07fjc`IQ-2Sl{c_5}x*gTAFl`-HmwRX6@;oPqy`S#!9C=ZA`N{w@xiENpL4Os$E!v5GC;Sr;kl|%^O-2IkgPi^yZSv9VdMbe)UJRZ=k;BH~fNzc}$m(LuBm`GH847$Cxo*E7VE=&OBtG8TL^k9C-sp#4{C;m*(7;{kNu&_{UDUjMPJk>`0lEag$CRw+e1>juh`Uki8vn`asPPdBMs>Emk`PwNLhU^wvLZoaGA|KsY+zT&rd^Gr!H3a%-&`MO_24jG-icJq|}IB2bI?mys%=ha)cR=_hc5w!G9^ww-fzB+j3fl9^uWFXeZmK{gFVjr%bb8|Em%*);`R-E75^u6SUgwxBV4BBA9hWCGa||W$FM~&Sq;c7=MpFIh&T|4_ps+ycwSxQ_Ilq#BFJ^La}$t5i1q9FDzOlL+3o9!4m>ZJ>E{|>PEUm3385mzJCU!(ZLa9P;3R{TvD#Y~2a4~(*laU6e9d|*r1v`irKudC)^-2C|?W@@Pw1Bkw+wlgs=q*8Z(Z<@U?JpXj&nBu>B@-A(`%$x)B-iN{+PO0xQiXUdj^3Ud4i7^m<_F6!79P*Va%d0dxGXW;)eCT$4jQ5q&cU5_5-(={UQZnmkG4j>Pi<{ld`%+eff7c%R1WviY^tHkL;)9CavMT=XY~}tt-m8N4<>|Ncw^!as&nhq}VvojU0|Gr)=W0IV57{l`1!Tegr1*K1oNQYk*5^rbGe2Nr~Ta;=Y1@?cwjR;Nl`*aAMIDMDApmx7Xxbj99CgP-p4Gk3p3o#;o?K8FsWpD#Epd4{_F75c7#i3|w8-}gbdma@Ld3wRspOxPMZB2al9_2*CCD0~=Zfl5JaPt_&VS3Z#F<=3}_5+$}cGZOhK^ii<*!dbzvQqIm5Nk}+v_hTeTOGJR31sMR^jEZFe7|>e%JR2^snDEWbYamE)QPnH$lY{^nf*ol^-R<~USC>R%zNG*eO|JRUX5H7$@(L;;XMNqGPie32}Ygpu`l;zk-T)q5cN$ruGrkNW&`14L7R^{@8fGuTyO`MH9I$lF1_+^{6pVIuW&5G;UnkNgS5MVfUr)%72i+(6-h)icUmb|Am^|r6G7$9$ThAe15xyx4&*4sys9Pcf^=XGv`Chyp$_9qcZe!6V5BhNL+@qeC5Pg%(`!F5A+lTqc4?wc_{uI+X2ZHFJMIa}Jm;1N(l#}+;Xr)^+cOe%iGnwZ=2fB4$2@j+uHk>y2fIjrv$vH|aR0;~>2pe$ztZd1N)eTfhevEDsXzwu74LPUewdR8t!E3)zdwo`BC@<=#N$me{7L9*K64TID&qVd*6k0e@ItlZSz=kjzvG{()$}Bm@c3%s?j3yA|Gn>tj7y0Vx-HA5covCnVj`8_g!10rRn*YW*+dAZv$jqC}Pp32B)sfD1WAeyX&#ybL`TdIyb+WH}zwE*IUir$Y_N5U6c8@U=B=#YnIKSO*n|jd3(Hw|GQjxW_to?wjGHZ!q(h2LGRgNN?JCMXCgMFXp8u3{a?_l2-i~(X_uck0^J5h&rIwS!qbfi~2lEC>7aZ_^63{D1T$96%c9(ecqsNYCsCamT?So+M62i9K_7`@NqjUDY~FRN!Ew}ekD2}$TYO#0_|mLVUOO<+lf_Xd&irPC6}-@DgfIdgV2+4dA`M0IKK+AVA9Xe}U7L1+4agzR2>2z54`I1KbVdR-}0!rik8yTSVt*=nMQ}VhE)~Met5LAw<%!n@Y|OK5;OZQ!KAQkrIz7K`euCrio-$H+RUid8VtE~p?2u>d4$Iyjeo2F=X}9tmZsB-lw+ZdNw;=;2R%C3@nu-*JQ#3(XwMzTTwq_yI^1Y3kDGV&_w-^iwIxE<}EBxE_~=;~O>Zzt71(d2552NFvy-m$<6^Z@)m7c68J_hU%phAnFv3XXEj+_!jt;B&Wg4evQ6klsYlv`7UC?V;OLvYQLS`3)Fw|WvjJ}WCClqqv7X|s7H7A^F^jGp(TEJ*{N~VBSS)$<&Uu-cJHVho1em0ZsC$c%6nk?;S^gt4ssDuZ>(n&1RSNxU&CRj3)!S?f6^I4`sBD;qwXRq|7|&65^Rqim(yR3>v6qT9S_XprULJEvB^gO^}8PrzNm{zCpmU&C-Tn&b*|s>UOF7v^FE}w0(F|jyt6AFGax=vA)$zYy3dZSuKq_@pusqB=|>3a_3j&3>Go_0_%&1V%VE?n?8xl+B;o{8u6lwA>;A(Dy!*LLaFFkKD5zZWDSKj#+!Yf3Tlh*x99%wX>*>eDxW6D(FyPIhWU{}^zHyB2?B9jGLW4B;al$lV!~=DL6OL47ko_QX_)xFBYmqC>$9qrD@(M8IA{SZDuNul|V?uR+(Ph6~s81@GFiUYY8^-hT3lD*sM9*(0nvt)F_r@Pj&VW|>=`TALB44F-Jr+vLii6pa&%Q>lLk?M9T_(B3E0N4IKdFuScl;WY(8s45k|AApS;?Zu=o7f>S^E#Mcd78q^`tRd3HfT}K65*-yJ>K0Qj%m1#rK$~w^ult0YtyqZ?YIij?~ZT{Q8zouJcZ{#rU4|=K9TiRR)+i?fu5`#P@gUs?xrrnSn5VoulxgAM76=e6|#Rx%LKfBN3iNKc)duM>)J2~9~{Od#qIMYp@^QtWJRr9phlh)TKz{0&_2LrV!e09!Cw~d|*R)U#1-jgZ5QuYVx{6%OmJSxL4mw@wceJ&x@P>~mZ_f`xf_F&xi(*M)2nP8;V+9miKdBE%XZR0&Z81PPf$$RZ~%(oExSS)hAp>c|CxzRMdF2sANVoL}Z%nn^1ScLc0XUV1W<)mVOtp6It`^qFM{(w0r0j@BUIuAX;`6ukuu3bxp8SR(igdCBtw9SWJbZw(S`iSiL@e&*-v7EJ;_j^~-vOA+r={wxAiRM1pjZXIUo_PoJT2(EvlE1|mK;*;J;xR90se9Tf+@A@BIthdCD1D8IzIVEIN5FKG?h~8!c>i=6Or_0H3I@)NxU35i6h5E1fHuoN8oYHCWG5fOabEWvePEHD0JBWCcS1kT=gR)14$e?A$S#z+6S)leN|D$&ew7A$Xr>bvDIy2D(qDUQ;?Dpxb@9`#e8^WsAL9IRIt)yGAGYlpa*k8Mh0j~F7;s!7>Gwu`<*!VdbScIZ(d0jkh&U_ZsT-=oA5RE$TwSKOWHXCldyX6@ZkNP{+sYMlA4#02S=Ct7|x&Qj@NsQN*H7pB5G*fko}`W^2m&ot)momEO8E=o+zDqgaIcBe4lPk1ojoi9X$d&Op>}*QvRS`)5LM-0i5v6yM9#MPr8SLrhp{8CbGV33bvB>kkVOs9VvopG4=dz^lA^}ICXB4WSo_VWzLoBP~hgtEWV@79I`?I&4qhHhHt)PeJ#culue@H89L*Eaj#Oh$c5)#HbgWI14b#C_333)Bxc(>gaQ2LSJJmH*Kh`O16nc;%Nb(V!IZ(q};f=C6q7vX?{>Tt8a8)65O?SB1?FoR`Yd;7n_0m#8uF)%G8~zuR|bz~N1w&N@3HM-ly$&3iLpGw<3elOfvn#!vOo?wTG70ZrkD)16^k8Gl>cXaaBu40`X2-2E6L2rfC0TU(qCvvEyh9OW2f`tD^Z6`)Or2;e1jR!b3*8l;&83(l`h72((kJylk5l7W{C0K%v+B32TqZGXtz!V|2v*|o;S=3hndMQMql>ed69qK#*pf|0cn5z_cmaBe6Vi1N%8g!cy*_Ic>ht1?;0a;K=u_Kx@KN{eApl3CgBtENRI&xU$)(?p!7o_{HFqge8@bELm=+=B2R9&1)>xVlzu*JGgFNY%ZkNYato2K@**?dPvSiX$iFVgGX~dxEMS>2f#{2Snv$O}oW{Gu!<|W=!+91s&vs{olFvE@0i$wFy9>pK+;!-tqWI&ezx`py|Cs~@>K+K1pKJt~^)7PfW?df2C-FQrVBJ#|Ou>hA1?Q|gKyONSe%DG{#6A{4x`|_EWj41vO?)x*pmya`H4{(?Pai|l1hAzJLWL-*MDe|X9-uCYTeSz?6^jKHS4E)}_7wl0#QIV8Dd0v%XjV8An|pGI-vkQWm`3Y`j)Q9QlgaudcMvj=X=8B)I?1H^$(!Qch|RTs);IwN0P=#xzcK>$yb8ocGHq-VJr4f8JA#R9Jt<`SuSl)QS8^*5Y(>{rc50)QNpZ!eMlfQvd1ZLeZ0r$92}7W0bEQmgTW}`M`AEmz6fw%IyY@eQr>5lncveRbw$3Djer-MB~>VUuz8{U_w8%eyOWcVV7wv_7McfbhCJB&vSEfKE2-gSYpPy!IOG<&+VX4RVT&Jw}@g6`9qiK*9c6?{F80x&&(+Ghpbhub5ShDLZ@&Msy*ZrCSQez=O5erbiDJG>_ag_x^DP^%5RXCqH?dN)g)7VgG%@GlFN1fPz^m!cz+RyJ48efSz8FvhVfT&wc;v!!WkCTZRXGuTL@ejyXF9nNVxl|+p;ghH6k9_r9!F>9}Y#K=MUa0RFAzu;sw}*E!;E=-JoradkS0hul7`5v#pj7x?KKbb1(uizGk>{G89g*qo>Rk!gEe<0TX+a{s!rSxi%bd|U;Xx5pi=R?W!h@Jdp@bhOh)a{w5FiffEv6~+r=lePy_Vf*E`t3RM?|7$_^wyKdlVDXm`}@@wSRcMWESV*DGX=hx%Prmd3w??foy&h0T|k8p=aH|dp^@HN4Xa+LT()9Y}w{^D<1e03yvP@!@Qh8R-&d!L=u=NKX?^754mxn7xSw0cnW;z;e7gi7RR5MC>5T&Fb(7#D$HG{%1WglMZsl#wzLk$TOo4oG!hd!GMtVqXYbv$YVs`LlJu~h+EJ%EyfJ_s#CUxuP!SXE+wrI+w&6hSGiNKj%US1!Ol}MC-!_mZhU6)g#YS|c<2?nGQyvQ+_**jap~dfNuaYy!7_aTj`Lug@tViGQ=zfgX@cQ?9Ot2_lk?8Sqyb3y4l?|3oU1ck)0F))fN6d6>s5Em%avL?T?tXhgk$f&+-LyggpQSU6Do2Ta5tsUM{N{!;yon&-VuhfkCiTQlw;=1l}jDrf+7>(ux8hooj*44{`jnx&E7$cgI8DQsv3p0mn)7Tiic08Hm1T-6wFI4URJmni_cg+;j8Eco2?N9cRPmlJfHvVT+1c9KqaAVi*i-sPC*z6z+`5^`5Nfn490FvagRo&08Y1S=U{RPSF_poHJ+bj&k6(US(;vYs8C?~%s@hl3U#eVh)R{I6680+Gj(+oPT6ZFGqHO>>o*XfMU7L4r&w2PE0f@A_>m$@B@*d1LT~pw8x4^714a}Q`mT%?w?@R;3lx2QXW0A+A1a5LAi+J-DFS@kjA?ljF8yt*EGC?*eCUZAGaug8PY2a+@k3#Ss5ee6h?BZa2exTE>uVP3J-eT(<&-c$7Q$omXsAaeEb-d6j|F!J*M}=bqrOMLMcLPu4TLXUdm!q>_nnG%hl4R9h0hisUnzX#zPF1AgM(`K}&vUkEpY8D(#1@H3jNoHPM-qA#OMK?XcfwfnI*pW;`>uygVI&ig$+;|e&rpf0nlbYOiu6MCXYeHD~Z&+PbQ{ADd0+EP*zW=}x<>4g!k&#&0v^q$q_@*J-h(QkLr3_lP*{X%qs3i1_M_pT8IM18lw2i!lnX0321Xe7dLaOC3!&(8fj-naQ<`JSDrAk)Gh<^CPxyT|*LQu`Cr!C|?RW&I}97e_?WdsH()T;!9+&}E!Yq7VHM3nmbS{!A6riM|L1GuWVRDl0XsiQ@k$vN*J=jt#;;yWffUQsy&jl7h-R*=!$&VpwBc^)kzI6qNuQ_Zs~*s$gNuEJ7#)Grm)tPS9u7qKsGtdHWeLH8Q^@{I%C!j-@ILs2LEkbS*;$UdG+hLEougk2pPg+st~h24=D%K9L=KkmvIAo{o186jUe5Dmk!;(!yHULrjQ`AVX2$)!a9M6f$wJ;lcZ`HFVzkHyw!$)vwrsw?u4t!sJj%Q@VuqvsTmuXa2SPznF$33Zm6FH~L*{-+zgEjq`4DF}#k#*~$qzasobizlCfU9Hv4hO3aT4onO<`z9<76g?L9^j9KZsc6awU*aUfma*WuyFQ>FDQDZdFXqxIaJ(jFsAMbh)vDU%GZ`i{fX++iOOGL6bsdl_Tceo{?LA@MPGK1LZwSm5(|(^p)?GxpW4`6$v>vy3hfGkm*&jHa!UIGf6qhAOKuq@7`id3kn`+y;{`&>5K+-SexH0ChcG_y@y@-v3VFUTuF+Y*7j`zGwXko;G{L9q)DM>j0Ytx5IxLt`b)FnS-Xb9(@@WV-uOo2PMygmg<;W)RS?;7Ghq=AX(sg3nZDE&`o{nqVjOecNq?o38*SzDI3az!wm^fQ-#fSm9`Ehe~2fB{5Z*v{jWeBA{@t9^zCp`j{u&+iPpe|{I4FlH<`4aD>E62)J1psd?x&9O+hxME6$L?49@)z^%-Op6BfHwb{HaeDed$xE-YezOLoqP`6JXl5_{vEm25x(#2U8>Zr@$AefhH|3H(@>Qbr@bX^XbtTHI(asgv&WINRMd(6V-6D-uyFnPyT?XRcWRXD|9Xl^`ZHVUBQJg5#fv1<_mTY^H@H*QB?Erugr%Q`&}XZTIQ^vbf9ZA48(k0uT0_bf9B1UHh9_}5MvM}GIk;hXUp49q$LiJ{f0_&q(=PW!PDZ|}TsQoLd5Z?#se421b&#VRbf@QTT9E-cUrYJf?x;U`|Aa4WO(wiqomOR^hB{F%w6>oC$vdv!Szm(sta;|cYBnrj?b+}(l2Q-0YpcqoZ!PvPFZSJNO`EKk_1H$j*PbBKMv>viXx6z?AjU_q79red6ng^S889?^qvP3=Z*NW7{K_+N6O&nNifO>IvfhsI#!=Qj;*lZ2dFKfVReQ9@aGjR<0XpDSiD17^(=FBkgCJcGQF;B&NoZqWu$HCl4X7ZUA$X7&P`Sdx-aQ&>{&{AWJ@2X#n+&6{Mpx~_UwdF67e~7x=xkecvJnw#?GjJYoPWaK;kXbRp0AwfU|oT_PV2edTduO9Yn1+gSfAc<8o9qYIn3kvJY)8K8*xI(pSvm^lX&yHoevf%7;{A7$NFr<(xBnV(7dhd?qR7w2vs2-{<7xKgr^o|0_J({5+nx>?TPnM(#84j&yrv-EM~6G(+7TMZkq3xAAUac-&^9Q=4*87p)=+uta$pk+#H==<6iFWs~>+vX!Wphi*Qq0US_W{vzT=7tUMEsITn8lrT^RuJGkQSZC!s9MIur91p^GKa3A7!2A`v%U;*IAsNmN6tnZAk*|7X-aD;5lm=6>_O^9y#yl18HZVAALWiH{!+)7m>eAWjb1v`|Fu?Ptv9muVAC-H`>vR~41@__hMB6S?d}7yq27_VpBwI{?8W1(bd(EL%!F_L}yKj|bAgn6KvkM4$imf9P$>`0Fnrjrp-(>{Yv-J7$u8P@AfeD~|sZpB&7#1)_eRYmD=${$tYHl3RX%{j7E%_g>Pzv-(zWIA{e+DoC!y`6SP0Ml6u$_Y--zcVE;cOXEba)a%z0Xu)wtAAa{kK_P|gKkgNa;|w4gF0pA4WV6^{^#IFI3LiWT;cx(Q+J@DEL$_noz)5yO*3@y-2_LhnvJ4>dA{~_cp3wf4KB>u>@Wg78)xnDY_Pdy=#DtNl`Eq??$a|~a%<8zGXA43@bGHWGK)rLKaFk7J065rO8;);7Jy2nikhjzsGVd)Uh&*=xq287Ch4CP%cyDYu#qaCrvu&ndl#@Zg?Pb#=57dj@_l7N8MuYp4&%4W=Lw)OS+pf9`>7cUCaDQG0>PL7#Ade4jl4344odgMUThed@&t}mM%!sDaj%Nf6JIFkK7=42s{ZJ+y1dY(@Z>@58_(`F{>3LBh`zYL0otyvT0f1E=;BwX^Yt5=$bf@yR(#ysN#Wt+uIc{uOd!@7QYiI!-KTc15?jiKIZ~<>I~!3a)`2_&JjnHwN2$m~gkR70@=%ZrlPi4v8uML5{pF?BSO{uxXgY63S$~|fyQ-C*1fA;?8m;P)--!N>8KN{Gd>OY$qE6%swtP;9Hf^Ixf(gi<*K2-uz@AK)zIKX1uM9=s^)T4j;;*0THA=p5+q>$*yZmf8t!#BIDggDCyk}olSF+*An{tIGl)g?L8(0(8I{E?8j_mnV$~xfYvpTcw&cIxWYvl*KF^}>=8NI!?Df1J~$eVOmokr|8>SQNv$w?v8i?|Al+wI8+*rok6g+j#F}itt}7dLw%x&bCjCavhLXMnS56{FkU?+0sv)rqdsT#?oPv(MXoFD7oo5xR$(n#NiNhgqVh<%{30(6)+>BG9%Oq@5u7u53%1Lh>y%{l!Z=SN`2w#z>mENEz3pA|;w$3(v{GtU1q8~E>y3qE~8$y>fUw9nX)1CLw_uXuYIRl8ii_{h5pR&Y-lDBs-KzFDr1^xVa{Lr-Fx?l_ocInqXd7ek9y9=}Ub+w2M2l&m_wNln|^?hcp|KP`gO9G>57Q0Xv{d_q)XAu`7s+PKjHsSo-x3PR|Q@{nwfG)+;)~MgwYnZzDb_z@snI@B&iR(nfzIcHNX>iB+cJ$!Lf7jvgNo2sEhGM7gMvND_iZLs{OwR;`Yfp_&TH$lmu~MR5xPt*ipSQ&vd|zI+VmL53gavcQzHV-0Q~JNmi_V?o&xW~9K3kQY@OQ_)o%sfjy3oglB6S1f4tJ?BXNT#Ng4SmIJ7PG#h9=`iVLXZ;&oc4Z;+Y!b6r{B3_kRdL>1I{}aAHi;tZp^Hi?2c)fnjlw8rcI}v`KJ>D@ShxwLmQbr9AdC%dXl@PFqSK)5n!k1DTFQR0ufawRvUJ!n`tZ^HwK&eR0jilJHViPURm_Q-j^k9SdUQa~lm*Xz@V@vC>gMGY4;(|-AY%7Z)!c&87v3eX^}7xSET1`Ptb2yKbhx>^QZEOd6uc7MMyUfK>m+|gfI_qUNb*{|E?dNs)SETpVb%J(+CNWX9ww%0KsZ<+neSpac)_vY~Dj06PAL%Wt#rvwW_iU1mNer~@Tl?^;4vya>`-evHsYDPfSQuk*6#c;SazC7L)8zf$J&y2_hGRMq>sQ7z@O#}}W&J)mkN3M?n{@OZ1NDOXuzHpq6H3eO9hyzqKNTN*E`G5h8)D;wHi){Qe%<6i-q>$8&}#1XS{0%$rZuG8Rm=f1&z&EGhEQjII(Khd-AS@eg9@Kj}9fEunhb$za$+?`5?+kAH->XYz&|J!BPqL@icAo93PZKxCV+#Nz}=zP2A=8G8^2PH*Hp6~8u!>f5mc8{o|&ZU{G5Xs?yl-X;|xfZAszHbA*oGrp=fg4{=?3_2KQ5eldd^hA;aigHuwq{IB&Gufa9o=P~&-&=^qAc;<_Fj}-^!z5cF3hXB4^^qEZ56Bnsmo>F1=^P6E=iqe*1H~2K9S~>n=*9b6|;VLdm>Z)X6@MU!1`w^ii<>ble{|q3d~}epU$NGBO(8Mxd_LaecMQ?N}HQOdDHz2X%VFromvoWH=z_7n=A0^#b#O40aO@1{?&cj@2N~G`947Gyj?agCA~bd@ew}Y;oq?1&IvEj53q(OTo|4k=qxiN2H77isX?=h4cZS$O=fZ(YUfUuHn<$d!{4xAXq#kJ?pBT6+9d6{;hxMPu{DYzYAirb+9lkaFdg5>Z<2CVou@7R9&n4dhd|!4slhP8Y$AawG*h{j?$RRo>r1d|zv%$jq!&GOvCdMr<+d+Qp|wD77guV6#r6fz6(42?J{A++R$1j7|+XaQz=c=kqNpp-*t;s;dw8YCvksI^3u*YfLY;xbI!66)fbLLltqcjc>zW#S9eJA(N`gwGvIv3g&IjaZHrSvnMbH}CQ9v5!yx4XR~2j6o|wbD$=8G%dh%uQ#*Kt}x2)xs1XY~mjq4!K`gs~E?x`u#^u<`gav`;(lvbN?MbW%(Sl1zB9!ezy6c*#p#Pj2#jj-X0ICJDvvw??!H9*X)wBd65Lye~r{l$;gu}^S>D~2sUPNBe)`$)1vpS^?1abczpO{+zB7F%57OzYxEfhyS*_Yq9NuiVXzL2x>N?$ta)%3N#>b(EIZ$_i<4qRY$gB#?ELdxwx4zizv0_0B&9nkEEma2xTyN)S1zM!%H?Cfp@)LOnSD*?-KeGL|&*Ej?+k>rFY>?P|w`iRDU%%uSJJo~eFXx1=--vhO_CSw`XZwWqhc7VeLOah>}o^uOZxbNv{P<%g5N!Yk1BrWB4dIU>wbG>ryC|LPY)$X5@d&YxkHWB}n`wS>}dm*^|$Va0%Y32Da&V;s++WrMy+X)Gw(`}MlcUDO$huhz8QVng&fDd$L8VgI=^Moy2@ZbTT7-gM;2uEibfq(nZMIm1?Mw2rO6QkjSRNKC$dpQ1e?H<)}k%{0}u|&i7DsoqBQ>@v;*i`VDJ?r;?4f0h}lRDS$b2_;FkotP48+9YA#laKmGQrm-WvcZiUpk33s%$EkRg|vy!a046Tdn>?(pEis<-}EzYS21@0i;7dIcAZKB%2PI}`cp(GL5W7InTrs3f(^8+;>y*heDPh8%b{t?k_`=L9fk!gFO$We($a-_}Df%|y>7OVNlIqeH~O|v!41fs9+sx7F`?%3L<)5?UoDtiRA_Mr5)QSB0&>jwuc{Lx@$^6VbE)acDD*aJswwNzz8SsSh&1;NGB5{52+a@dDmDdOQ&R=uU0a(?C6=b=-=(kM|r4IODrU2KDn&&h9_9@HqLrsZ@#p>O@?N<2|>vD*Qie{)p>(UItH&i>kPTf=#ndy)<$Wkq1c73xn>dNf&g~k&AW?`Ycmai3ep~;2x30;|ag_u*b>p>eujo#v5E`6y#mV%UNmA;(c7jiG^GgWW9qqyO9oZv_J7n_u%pRvEG79U6>%2GTpU*79LO3*QW1aL-@LS?!5+I7+uKh^T7N!L(04(|R+m*W91lH{`yT0mOc|ZpwcA^%pZ_=9{rV`h`l@_F#4wJi>m#b-bbbX>=CNzBR8oZH?=jAON(a8lSxQXp`^_9SQEn&&XydcYl(pJ|(&Nj?nX-ka{4hnJL&B{I6qib;dyr1n8<`WLAOm{dTM9E)Swrza#HIfT8amqe5=W+Z*UrrZ=EO=;WIlR^o<9Pkuyx`}hS-=SXdDy!h^+nOD!-Ln8Vdlhn+x2NuC|5$_~iflhM)WYcrz8_&Nd542byjo5cNunrEy(}c+a$angVL^tJE0Q$RYmAS`wd$rUTLc&_)(HByN|mQP~$d2$(iqUa|qlKToEG|KbTIOuoFpQcNA=II%7mx|cMG@q`O?ao^{7QT7=b3F_BPI-Ug?O+BlZX=2uw@&b1k^);9i&^D^$gThpMv`3qT;~Ac3#DO(ywqLPrOV>|u8p+MM~5;||E76CX^mzUM90k7I{pH6Vx9ehco^yT{;Un}b1U8hJL63pELuBYKYu!M)cDDpj`MPp;SP7v&Z^=6?sv?`Ndv-{=q4RG>bjfZiL*cHaB^Kx-->z2EiU691Fh~ep>%T0*WzQyMRpffb>$?mL8eIR=7Afi8$Mz?Esf`$?-8T;v=P)rM>ahiJj8{T-gTu4ls>=Ta{@Xa%VdEA?R@91ji}$&jFmQg9|%2jKYK|k;dpdc*gx-n6a%?K?6#a)6po5$YY+@e0^ZN7C+HmN4`+?7s;Q?zb4kWAw`rKay1XZ$#bYm>%)jm4hMZGSH~;I<4kpNL84GswMxChFk#k^!V(g^+n=z=T2d{l_)0G1=z9m>S&{5aWyQc5Udk+i^sXWt?jk;aWxX;@uSwPfZM4m^T{L|?N_nWVVl;ctd6s>RgnhL!53R9&LHPFoV+vJrZWSG{TxRlQ78Isz4*j{qmNj>WKL3iJKr5SyniDb?&e!mAEET4`Ck3-w2u+*`ktu|Uu%f^h`gfY3^gwBUUMH$T8%p4BfMjb3y1u^g#Va>`jZX%Z`MEbCHq+)Q$b!Tdw<|Uipv=w_SqEeM7~-%@OYn;Y9eg#whZV`k#Ew*K%Cg*toysR5|LOJ)fWY^nnXRAF9M))QSDALO0V%e}1vESXV>zmHsm&6A}eWi@)B-x|D{QwdGq^F`-Q-K4c^U`Koe)<4p%qHrWq!!Y||yn^POUq>QscPw;xQ?P`qIg#T%G69-DJD{BqQU|iVKBAqcD#)Vzee`qPcM7|31xgM#%G7C=LeSf{!0pqy+LDdoAJ6SMcwBekvjmxT)ZNu~0cO~HPuGg86TdFOtH6QCk=o8Z!yBD&6+>e-q=Vdk6$lsI1hB*_j-)*^p=antN3(P(ouu9o7I)UQ5*tNPvrb(9zJe*p|lEd-O`21F2@^>y=o8A#L@{-bDtk+CMA~g%X)O1FF3c~nE^dGd7&j#LOn0Dn~pV_Xz>qoQ{AbkQBVx74%0SM>PfP6nTLJqkYkn>sg1fA>;n<$OkOYED~oWKNSflDDd96VR;GaPO1Fo+k~=VMnq1~LrUE#*=I)~>2Dq2RXi_Z+^#oM|MtgxhkQl$gBeQ)(mx;<`HJIwCMBpN6M`+&yoOHV{6F#STYA-oMb<^U^+dkvbJ!>oc%Kb#DqRi+|689L(xypHJ7!$Lfi16I*0)pYV2Qf%o3UI-VFVZph2i*@1+Nn+)y;w?&7L18Ct`dj>UFa5;K7KOAklBBK=A(GXDA@s3D(pIPo1l!Mo49RxD{aaT~{T%xk!`X*~zzN-BidtC5RtHB6ISxPr$O@3La}DEqZ1dsWcZ@Z!#UR+s(3R@B4Y8?RMe;PI7dUf8S|$R}hzXL1CY52;y*<0R4{q3`4W`nv4EaS}e-vv|LEa{MciqsYD_@#!R|?RkPaaah`$OxQwzoH6pu6@~aVg8~-mCnG@Z^Se&(nh-w+w7s65+d$!{59*?iUh;8a?zRN~h4RQtUSA!OK0f2Z4khK(dB&*wemr#bV_X*L%UbD9@pa@qUQ9ZJ$@B6&jN>8e9&2Mszk=7>kfVt6P4G(o>-*7#y3J&bPx(b@p#IaXyjTZ$Mlfts`sl_?&^RqRT;Hh5qfR6Q{NI?rHLQ)&Bl7BZ=rH?b;T3}$s7J|aq`z-s!hF+$dnT7rH$9n4Yrf1T`*&NWqP|M1)2rYH2Ws}tTI)>lNicnX9oUUJh8^#*o(m)yZDxa{7bKVKhpW1_KBwEtg!1`FgO@_kt?`tNl-f%;X`%k$reB>}@}kL94*kMj|FcqBP)IEf}^!_?7jD}1LiXLlBy{uVobeIe@Py8iM^()Z^60P+>lw`t!=CfQGre*igzc`f70AtN>;-eVHzrT(iW%p;pVc(NEHykhy2I`xg&pnz01^3##8!0|B#C{)T-3++<@U+NAOXSA2C)dJQUnZ=muysFj6wm8h{7~gX3l_*Y3|iW&;dv2#Hk)|yl*rRwqxdg{OAd{V)pCI7%h&e+&r5;_hIJRX@ayL3&#$i`U)e=@I#2V=f*U6;ZZ=Wx9zW7F|UnToCRb`X;bKek*FE5vNEH5<3fm%+0_&pKszvC^p-g<8@n+6+GH+q}s<9Ur|R#?AUMTeV)8;?Ibisx1Oaps@qF$SD!F5H`=hI|$5rI&23#fDzXBEBOmye=YB3|qLoIGrr>wje1R3@XogmY1PE*uVS0jiou@-cq+KOAX^Y*$3{ZBR{2hVHxfcl#8Am07IG1+OX1h31vNqdb3%vqo>{doc>kW!~wJ3!0tWB=X1?2Y69k?-{=b({mAx)Xag>f$(we1-UXE<_xbu`U`$z3JF|=i#C(C@XNgVHHl<$9>USH0n?`Y}Pu(pE?OSL^JON``*MHD6(oe@ZAk{avef5>2JR_dE{P#lN!uuWPZ4JKJry;zE+{?j|>0~b7Q|Xj-Tu!yPOHByvNp|L)?GI+b-(V6!&J6`-Ub``j{*}7@eKM<^bXI)H;MZ;X|Fyd*0U1HK?cy#&L#CUKcw1R2GB|IrZ35`07SufyvVK*-+MG7I~V&R}aNB^H03W2LBl=^y5oW|7!ykPx4adBE0_z|D51GDWpH!MhagMK6h|3{jWb*7V;IjPgsCK_CHMxMsD$Ql3w1-&jy(j?~L~=K4_lWT#*e#f6<|7$Svf$pj8Zz@pd*P&&I>9>nD@`=KlftioEVK)5v}OVKS6DD`J91{_Zb$eIIqQ|Enqs$p5a3Jd-}O?N`S)Htda@5#+$d@my$k3l?9ByHDr*Nh<)yoy;(r`(MoJX-TkEar*G-mu)58+;O$}5$vW@FkxG}NC={U?m1!-YF9LT38jMZH{XPs)y}EZDa3xOl+>)Cr%c6DP7EXLM2fMvAXE`TjEyO1>{VxQu*7ax*&~h}T6YHRLGLf3PbBS{A(++eqohcjVU>){~7Hr2lPgI`Rzp`|n`DAP?i1EIi(=!#*I~jSZJAe&#+;#^Z_g2Ei*FaGrPJ+xB48iFN3K>s;6!N{_jCn8H^LPsc6kSx~Lu_4(9p)Dx|p=LK11lfR2;8!6*i<$mJuSTL+gJf2m>kGyp8i|7NloH!Uw5$fBdf;#y;S55)aPjMM?6zN})mrm|8%BSo@ym6Ji`nx>?rhd3rQBj9nWVq~w_>{+)5ZpgyKCIU(YsP`=b63K04Xj7{9IqfHIP;QATk_?UAC{at4c5PcUP=3pE=d34$Y37cG)uHNm9iA7_=jCuS2Z99YnxEEVyk4Y{UY66qg~~s1qI&z0LyA?pX&JotQ_0HtY;P?b|K72Ks~wMK1M5=W^G`=`{5FG0Su-Vbfao`FvJ~SWw`6)26y`wLF?FM+dw5<$*rFOnH90is?1JML$Z>i*7@h;k-#k>+f1pm(3o6acgfGYysC8v`^J6fK=`RRX5jsHyj$pSEzKijRQuasOyPf0EIlzIlexD`xSK|1;xPCbIY@AE_VE9q$@QHpgk*~90Pm#uh9CaKg(MQnsQZ}6T(p7M-L!D;6`L*EQ9C&*FN>Pz6a>$sW%#zVhIbf4AHHB7y`lVFw@6{k*5$i4|L(;)3SWV;bA>^y;Q8h1DF_TysxwplFc`*M`D@dWF|c#k06D%k1oah8ku6d)Ncl4H;Q5W>9RTe-HJgCQ9E|cw~b@(d8c^+Q=uw`^xr^UFAYZ-Be7^aI1Pf-cyccQI;W($Z#^`1Va=_|p)kinVzV*_~Z5~T>xv*1F`})|CABaEEpS3gpVHSUGvY{Z>7d=Y66JL_X0Ids*d6m-<7kJ~-QEtJ6?Gtsgqh}+2>HCnJl4v+wYFd}A@CxrG7|;w3_z8E+S+f_mg2UAPf((r>D=fXHhXE7fD3Q*;!O08@9;U}V|`XZ?D_cl>Vce;Y}M44Fgrg_QlS>k>M~?_#qc`o<4sO%CE@eM2tsyY9S~RoxwpxRj68>{;qeX#d42b2yIp^!NIAL|V^-`jMzsHF?xgT9J43?q7?Bl-#@B7pxG!)_O-*Rwx0kcN{F{?L<7y1%}r7rN9r-?~J+XsJryF%<{q)WI$3|u-%+d)J5d{#gW-Gcy-fOIiMWz&DkmrGP~$78aw=|<{aYPFW&FbaLt0-!|mx|+Yu*uF4)R|MpZ3lojBqUvCgk`DibO-eh$ogi~35^f78cCiOhfMQnq3}(!qi1ZEJODAd?S+#X4AzMAmZ{n9{-Jo9!lt@2EpW_gQw{H^>6AKJJD+=Cv`p(3q7X1N=8z1b9VYzIGU#%h3D6fY9qJ0-XIQ^UJK-O$w5kV1L2O$X6Bf-Hy`C(4{L`u*%?6^BrrrVw=_zaKUv6Wr&~+On%KE;mcbYMEjhxW@ho)4hOkHH1bx2-VQxh*jo1tznFd^tF^F)-U|O(x^i|@VZ@;iS=61iAQ_VfB)}3kDLvYfByKO9^>Nsz7fyyLhWkP&NG@S+`en!@6^5(DCcL6yT&pWqn`rFHfb8d$OZ{swuIpoJYOkjf&lv^pqY;-;hn%T4rVr`SVQHJ8&aDBA%P;f7OHo2cNv_Fc`cd|IXzp9*F4AW}efWmr4^H^`E2))Dcb~%q&DwOKlazBnJ89MGibqT!&q=KRnM>?6`Gm!}~A4byW?^9pH@E<8PkrG}sXq4_+tkbM^5X%3=(}P0I75pFCm#v3yjGrS!F#+(~p#K9K(6{9Z<{6r%dU;Oa4^zXF!kzI&IE3`vg#jkaow9(^zo2_^-hEU5G!kJFr~o<5m7V^q-A*UvWzZF76CZ0@|-?vE`Kg%+)L1*bT91pyQsYS#O5=zVxZ$k~I4lXI+!5C8M;frq%MihlVH#~3)XYwx2?caZ<)cj0oE6B9sbT4MR@kEpLs)>NNeHaC?&zp3>h>Z_3L6UM{aGJud#^TNFG`YKPyQl(DP!2Iv-0hbSmSE)zH4nLuTwttbX`DWBVKW8dPo_U`IE_zPpd0~jht`jh^Y+^wF=L>C~rHH>!KIQx;kqJkv11h$DM4a^V)zc^L=UJmddqq&UsOO%)KSLo3)P{Y+ntD)Q{joaLcm72j+_jNVm|27RirnwBxseQc$sfXmoKasDM}KDdSEhpkOMmtlrC+a;rqWm@N`rZj_&ErHAUQMv_@iP3!ZR@70mAv8x>gHoJ@#_iP}16IpSpfoVN@e7FTPI8BtzO&WCCv)(d1k-Ozl*cb5wtSY$=~uG2(aLnk60ce3)u7@?zf4PJ1U{fat@To-VN`_g_SfpMl4asTUcN4GDEfE^WGlbl>oFMTO>Il90i79N)iEVD{Sz4X|!f^#l85gfKGxE7R&uP4vl948R#g&E<;|AgS{4}{wt+GtMvu759Ex7!R~Px=WM5YG$A+^p;u^APuuHq`5!nFSjX#TT}|LcR1ruE6({6a(^`d^2?!h?Bmc#iI;3BA}u5>Hy+zUO%3_><;lel-)t|+JJa;a=?mEF&Z=vhgzS}M}6gBWUpzcMF$P~*Tn1%sIP9Eoi$pllLgbsh4C=v>&iLD#*&sXAZl>m+&VAxQ9L|htTaRTpL2~V$&@*3ryNRZA2MOh;JleLFJitc&LaXMo-;l@Q7xPFQHPun?Ca)DW`l9K(y=5r%!3M2uk~Cnvw@uR>@*AW;4bI%xEw(a^i7O<*+Q99Pjh>%E2@?W8{yacCv4PLANR-Cn)=aTYq)*;dWyc%+je@A1f33+QY(t`BT$Es^&)lo#Jcs}{swOW)FDS~y5gL_CgK?>B^$uK}nh7U#24BCf#JJQVtan@dqybah|M*&pzS<}7a#y=j7OYvJq&zT;aqV50cH3w<13of-UDCLKas8%maA=btbX4Fnc@1ymPxc$!=^}9dFPY91Uz$P9i1*`BEdE?wzgEP3w0Ak1E@6Y`y7)R|XzQ28Rx2f=b^z&wxqDGqbBsDzcx@lbiBdV#SbWOr6z$|GF#?vp0Ve^9k{{);V3iI~d?L-n3ehGT)Y1u4RsHWI|%)S@#SLtC1>K&Pb1b=t%kPQLue!;C%{G@7*@>Y(k$uy#>Zl1DLVJ(Tpm`u}+ke#dz@2#h+};bfQD2esCT1I_K=_ou3I$5IPc^x*ZXvM)lqiv=!E-)!%dK>Z`vm{go}FB&QiORmnnjrxkTU-ouN;D7ILD0S?7{l6p?W<}&?1{tBg>O8keD0NmQkh*EY4ZQvv3BgnCH)-H<{dY**U&NpO^d@yN2q$;8U~Q_et%Ksu#o!In$YFsdGT5|#L2mp^}|f4uS^e^;E#A=xwZd#4h!l#`{s`ZBmVX0w=1h7t^ntNDLKTSTU$?xDWLOxDa#fjPTnWMUBr4hCN?~4E=6CN<(8^;GT_t45-F}Q;$xm`+#GH)VXAk1#k)aDz1BOHaK8@=%xcya&U}YBSx0f69tqE{nDkGRK%K)s#|pU$)tyc+%Un<|k#jvoZY4pYc}17KAHIG`!`%h*W~akF$yJWm9r5+td9xnawPeC*;kJ_t*5d11R7WO0J#sGyi>hEqiq7LDoZ|!6Pxxd1o>?fRjJ7FYOkp(JS1nA}zKc&*lP@$HWEC|ZCO;VXc>FcKpjh#5ohUcqnMN`WV&xrAJ-ZF&)os?3LA=u><)Z`@2xt&W#Ckvr{h4mq(t;b8d=M>af6J`=iMZ8W7+8ro8*c5OM#L{nO6KpPWB(Ac4*I-CF#X;uGc8zE4Y$17sc9epAZ+kN&+*t?pzX_hrQ&;Qe-L+BLV|ZRtSv(cb!k`s(Z5OLd~kG&pAEaov-m&u{Oa`nxTQ4sEIxZ&fxT&*9hpwFd}YksSAR^St@Uhn!PB_YVWa8}-}PJVrbvXU9x|9wt0CpKH-;hdfFB*_F$JX${*S#8Y$&IbU+bhRyfQuHA_Ggwz}IU)gZ9$vUe3D&j+nq-P52B*MT3#aZjRQD2e$%!kWT`F+hhDE*j4eG#1@R+;cN`e;zU59$-LKlk1r8oY~iGTlq@TZk$v=IAs6CPm!K;5BX<&y!~B~n+*D+HWkVPsIQzg#0xG7Wq^jJK-u_9)K_G_^R=Xbnax{)BViO>_w;<#%NKN591(SUk_hS_>)_2@E;0-_eAx29I!b*Mx&E=D$2c~#2p?6zSi;X&^zGyst!V_Hhe(S}Ke9%dY&II}p$RwX%JntBC(JpX;uPZV_y|J;if2c&<=a#z$#q%T%XeKH8s?q2zP0$)%1i#aVM^dzB|-yKF=$STWvB9Yh5|Mj0ZX$M~C`2M}TC(U#y>1{Z9e=)wE@4GRR0XJIDbnG8SU1YaLEavAtCPWz(X4O2R=q0X8+?k)ufBdpi5I0yNZ*!#RpLJ90Axht()X;I?w{!?Qop)l^3)ENp9;_B0`kMvh?{9W1>X1)UI^CBDGT})|)%B4W)FJyz9&MQMnF*t|2~zUYFt2T1&)!{rhsEy~OV!1Ey+(ZFo&@jh18u6YK8MTP|{suaeJ83j}~>R$$(h5kn?d~m17>%_?_`5bP*RcFGqi&9mG6nDV-X2IgShUJGMLwrJRFI`u*Zj9r0Y*-lA%nb2W*#N3=~5#No^;4|f4(!*7~>-SB)hI>!3u|g>;tl>Lj;}JHYZ*(z?bb`a3BW1mlL(A>hE4KK{#{A?Z{S)>)CNt_M{RPJZ9N-$x!qm>CaXi$OevO_%+816#j+ou3@qq=$bx$a@$JeA8y~?J|mw4-@d5Lbbf?*>8#g94$HXw_4u=`nBPfVMUT&bFAZH~{vyg$KjnXSqX4uqaqAHMYz;u^ndcEE%*m=Y5x8h0P>H^-DqappdmU?rY^?Igvgi;Q=QEFG5Z6})+#(&xDJq=ijyR2C@R`g1|Z5_yK4b1J9TGQjTA7o#~^$nzEp+{yi&-XF(Pv_B*M;X!!5`)w8&Ez+U=I)gl=4wQdrCDsc+Jl}=6QFIIGr|?0Z1FcNMkA2>V@7i+Nzo&o$tCH;^1s)+D_H3aOM=u%DoxHZEwW7Xae|T+U&Pj(K6DAlX3VL-I&uD&)&d|%QZFK`bN-brQDjOQY5;h;w2?O;LZ;_yXvi%_?W_Kbg8qQHg&=A*eAD0NK-Rd+gFZDvEx0$bPiR>Vs?#(rETzV}$p{9s!t)F+ERP0HvANC48;b`Bl+*QN_;2Odi0pF4-YNB$P|^N%~)Wd1V;;RWg|>9eL&nDTTWWWn_L(fGbr>Xzd&=~>Wy{*B4O1^B*hou}eAwlknSFlF_w^N5rFr8nL&`93OlTMEbGepJF?i-~hjvEkC9oJ%xg#A8>NKiQ(dfzcjceD54byQdH*uH%q4JIF-v$>z5uU1W8I4gEy7I?=-RC}qT&Z#uNFxSwU0h+yi%uLF;-mP)_j9y{<~wB#rpvVnFFx;K?61QD3=x>dac{o(Odxw^Y>}L>;x@W@1K)Wg6JX9oyN{iMX_(-uI6;Gx_zIALLQbO!_0WZRdVMPp<9z>$eHc`<$-D1>5i*(;w2Y01F$nfvJ=v}Cb0=TnAmWXG9Xm``!y~z%ID{%;p=;Eh2|;6F@f~Wig=HD$yuHIQq-RXyDMKxw3i~zpAWZ!4Oa8NYhFx7eDcw!m0!PQ!40q0b5|{~-aEG1Q^rS_35VA@oIYxab?$Pz_SrwQU+An&p-#C>E8(be>$kfApNA{^MC-f58KCy5LK3D%XK8f8Unhi8h+49O;me`UaZy^4<^uV-x{7q$GGNcRkr(ivcT!$>y3BhFkkzcoPM%+8ykA3N8Sy#KpoPXCQ=eOg9DzrJM~Rz7#F$Du_@vFQ_mcP{A*2Gp1PWHq3TDl@KSB$zcgj760?B|Ztp7QjlM!WlPz%8cyl&nx#XG{n`=`-d{sZ(l6kMUEjXMx&_!dab^xe`%fOQMY#Y>2PF;88OXd1|eG6BgjefxO$I&sv@!z9y5YCMLiIaz1U_F^aw_G%i~j$%WjPtK{p%Fpry-Sog#UXT$0a8OhPBh{qW|`BK%E301ewOB#)1T*DV%#Eb>g`TYe~H{kttROHr9jlL}4w!g6MIg4=}O5V8Md<7Fizs0PvxJEg57F~AjrvVH0-_n{RUWoi{mm2glHQA6$YjH5Xfc#0_uQ$eqD;EAr4LZnksBz;i;BjD4&+csl6hHIjXR3`iZQ_EK<|BJ!Thu2(N)G9l?{oQmAF_3bllzJr#WSE`h1~Jia(KTn(Up0@B}f$5G_J?CJgWQ70H6(k5!S^b+!)6sdl2ynqSrXN@%BTjDoe>ld4&sUaDKQ$Zm0NGEaqMr(6Us2W=rM`V|bUbu>Cg@}c{2ULY^gFzGBENeH9ZvLqZFtQ@{xY_%>lc=00pCyhD(aIr7tWsBJDXTPwkRE)V}X2#$9qMJI_n?bzfXuC>2-|pm1V<5VKvhk9>|mQ>$m*GhG|=(jGSr_U-30%v^}1~pNG{Yi~5AY><{o)<3dL7qH0Z7#QFVwZvX6?mzSWv;``}rPKUv(~unpP%=p-9FT%+!^*&;six`fVxH5|B_S=J~WgZRMvNp04IK8xJPI&MYrKPTs-uvqc@epnGM>MPP#<@9*UKmAiTQC~^uxh!65kO`-peh(a>=rr>D+DMHK&Ef*4>_3P{RYX`!BEI*Le!(wy_Mpxo=jjN~VDitEf+_n>g&mx^rHU-D>}vSFxB>BZ+EV3;qQrfEK3rI`AMrr(51j3Ujw0)_0;b`)*oxwHYk4O)kVvmvQTsz=dKjfYju6T&Ni5hoJ<5|Fj(EUI(Vx=ZY;aCfebXF@c(pdyvv?r~R&HCmq=9mMa=))kDF%q>=IxF|eMPoWPMev?&+i#?Q0L5d(|*K|OoQfquZ7(xb?*<|w`7-bGa>l-D%%4-h?71$cfINV^c(KO>#Y5DRaEp{7T-@&hN9CZNyO`hEMUSPftk}K)+0{N5o=Lk!Sak8i5_Xhqh{Z^u|l|H`wvA&DbpR_l@fXX*#u@UrH<=W%A4f^O$@M3un^RYM}0-s`IPrEf$YzonSlC=^x3cLX7T;;EO(>6%6#+d;K_$<{#G-yH#zX^wYJQ?opI-&IU)j?58Yk%om^PIKMZ&$OdN*ku;Bwlyfw}y*lsoc+eWQcflZKpM2d^a11YZdf|?`zAIV|DCqj!W-iv?RgrB`^tEAxLzj%eI19j?(Ux0$pQb#gThc?>U~4ZA6(vbnNh3-ZL5->{lq>_0dEAJ(KhLjr}=%zuaBw$p6r{eAz3iT#(OQ@o~X##3dT11)4tMf)4ZSPhAf3C;JPSX4w#z^mL?Fk1|(_;Bl<_pXX5~#jlb)|6X{H2JSD%Nl~}Uf{eAFEo6gHU){6xezLiS0lcG%1C5ma)6<(aoJb||R#5G;D{ieASD%HI=dd^%PW1=&eQZPiJy%a9cK>0+USSt~k!#4G?CX}Q;y}ap2i4yDkmqEl1HWE+6MCs>!S0$#s6zsOs%p;u%Y_BUE?(F|nJ@N8_~`@Dli5&gwaxX-IO0M!-L0+rGvU2q^!4XE@pq)pVA(5eqr<&Frm;?&k-y}JgPY`gv-tBy&mIb1z*F>_L3~>B7<=^=$Ah+q~nb0qOz1Khj7Vkm+aFtbh4;>XP-xCl=D+M(79T(<_vH&I~DyG(uO9zel+$)F;Br-8#$9GT`(5_eXOn{#v}L^l!CIOdx$Y5{@DtpNWB)mwQ=IEL&>qDvo?yHm@F4d&Y*dbJ?~RV-T;d6kB^Kl>>I`cg*hpjrjAo786_zxghx6jC;lmb&LC}7I10f!rxwDk(>m?`99{8Q~3T@1`qzXzP+P418S@VmjqGf&*ofg_xw0S1BTC^@OAU?eJ6i?_V8>$7OdWRW2@9_#NQ`WNNiikgxQ`2+;_hCzHM7)pF3;Lf{LC6I_>WfC(lE*%-L{0Pd{@Vpl;d6*|D`!nF9hB%$XfwhQ!7Oq76uVORp_|EcnzlmH&OPN$o+&oUKS{LA3bJI@x4?#@XA@6(39zlwL0cyAbxX^Z$+;b3rt$)*f&t-yu5bY@NGbq4Nb9{+(r_j0y^L2>lUf}5%!72)FLK~23&*Oktt-Gi|0mUb({+ETz?%02PLVQqP@%`CWCIM;Bu|)`V5#P6PWjfz)WRex)FLOrhF0G`2hhtFG$w1UU3rXXaK{}B0PFI}3*WaA_>#+{;{N0eIW;Ba(p19(haFZsD32v*kMw;vp=f2JtT*_v_oXx(PlKO~`PZJV&dyWm9u01xtlo9`Syv6b0CJsCkR;FuAN4zP(__e_p6Ntx$DK`i8mAs5>r8)5&Deigb_&68!)mfUTn$9c^?0On;@Z%xWAuq0~-Q^MM&|=%YS9<$VhfKZD@pi{eE=&_StNB$6^R(6^HdJ|h?(EdYyl^ikeA320*|2(T@YA&+nD6F|?3HW};qjmUDHPxGbA#e*TLyS=JHsL>V~mmqkL+};-kk&W)kaU+)9C-bldYHlS-WrZ^z2VGdd2Hi??KZX2!YYhQw&K!NlS$bizp>!mhgTSvcK~B#7blzFr`&uK*W&ukal=-~-H`ywNG5P+^y;?qfUH};+eOLyqeAB1BXsB!xUJE;oicZcoWm5yfGd}I(aYi}`ii*Uw2AxQa#!=u1;rSbSxjEi(v@s@;`B?#?*qmaUu*c`j}8ZVTc4XPr1S}vxtS(BljTCC*#c0mrs%`9Q<)lXxUkbrA}}QcdAi0#7kQo~baH)}eW?uQ_uF^s&s&P|AmfVWTW2QX^%gR|qZfJbS5IlPur%gV&bXdZZ8i=36YlTsa>x6P^f~`vibEeLzMa@WpRa0iK1+H;TT}nL8)IN=Rx#q^FVAjBfNo9k6oQ*S!uC86Lz3@(i2lYvAdDOE@+p~ex`+55j-`V2Fqjt*#>`00r`-1YzOKX@bKlE7p0#NXWeMgyS$PGa;ldS_npP}CF@)EIj}*~c8k@-5yZ=jIc6i)9I)SEH0822#ovIb*0y*F7f$5ea6U+DC{<>%c#n+&IJpBDVUKz&tGd-C<}k_`CvHNLx(Qh#-Dd-s|Bgw8%p2&2cB@cOe3XlCF4m<0{XuQSyb;`NVv{d~6JAQKE19TB95A^!fvg1V$@EYSAb>J{FC`0Vn!x7W+r;LxhkHa4B&bH01|59=%r-@m$B8*!t_pa1@G=7Rg|pJ)E=qUf$6-EyhP+3+`iov;2u#B=-u(`M8r0I>`XDZ7CBYL(My&9HSEjNee+x{~70Q03fm-E=AqdX-aOR}LYbxYF=*lwcN=U7xdPH|1Qf$OfxzOKRxGc7gvOl)^)fQ9FI3WGc9#Z_K$o}@F%Tr*9yp5Ia57b@x!SNr0W@Z98zdhOr_0qt?rw4y2(7~_0bjw$N#BW)NO}zdp3&{0u@fpO4+e$>qlnKAf6jjBKBTm+Ji=QF#{^0WBb(DRuy}ntGo)S8WtZNFkp`1VJpSL3YN2;rii?#s8M?(ETR)sXNK8m04$4>=ug@_vIL|ZmouN=Jh{0r)cW*gnn8Is87>w_MD34ZoLMb}7%{&oA>kiur=?Z@eNG$aTQuCG`J3H~ycfTu?K;KJR%0{lC|fb3`OBut2`PYU+Y*7+0RkA|b6ZHbiYRtba<;jfoxOb~?{Euw`TZQB@<1YnIQ$mb!;rc>ZU2d+l?Ki(c~1#4sfri1c&v{50e*C*p4Wn^?DaY@PeSVlwh4eTFZ5;eqe#tNl{lh)b7DJTm)84sa$&G#q6k|NSST8#_Mb@aM|i+JSjQlx9>XyfYVSZ-*@Hru5ODtymRU9LWUh#^U>*6fv$2!Ko3ei9C|At7)N#3&yosE@6%BVh$XBnDU2Zh&qJj?BXzUB^UN2?~%`;^lzU0!!&p=oegIzGmQr*e(YqQuMMG>6tr#D?DIzc9{T$ZatNKU!(`j@uJx3C9s}j=J~BBly(d5F$2Y`hNM6|)o{|IVa>cTykrdx@&PwNwDY@`w-qL5Q=3;)lCc4FX2eD3BH@V^5P&CH%`F&t=DxsrR-n(z3{TkyEoS}W>q&*w95g$atON>kVy+~hw1c&cqrY?s3$+_N7!ntr+w(MrpT;xeUXRZ?Kg%1)@_b&G%?tAg~t*O#H=t^`mdz^>-N&la*TRgD-qH*U9rCwdTo~6jq%YlYv{);|Q>cE{2{POjn`h38#-@p}>Yr4w?D&{6JZy6omq&Sz6(xTQrkY^Xmpaidu;@~;-pIV{{m=qTwM%T!yC|FWybrte$0@T~5^8&*8>w0iT~AUr)A;_V*1oxGOfw>f&bOL7|z7#B^{R#i~=Pc@lc+s=cN@AZyFti-(k^wEd8t;G81cc^vDp9I7cd`sJob7^qC#Ms!i193&F0$aEIumMxl)F&(czDeR1-iw7H$LIzC)xrnd(^s!`i7zea_Z|I9EQu^%P*L4X7abYoQTA}7S#I0=&KmFXC4N+q6rwKkq+)29FMzVX3$ZL9*B`o+I`eRY>FbN@*zin#b=9g7#E&tTZVqnYz~lMFQAa5{>Z-}D$~y&I{+x~=SHug&YphlGXT!Sqz-N0X^Jtj#!l4Wi9^9)uGwPH@@i8FJv&@tE^HW;RpuXbI^{&i-YiWIK;eDv1$p5ciPXA}#gdqAeoQ!x^zF(FBMMWRe`rS~^upAXSUfyKF$ceu__Dsa@UrX8?F^vr?nuqd(DY}UCp&KHe|2k*SkMI6K*^hF+o9imh1rsB^n;}0De|GJ9=@ddY&kt#zV>gEQ-flOO?(l3F3zc2rI{|gnYvJo}KHW`#6}qce%B(`1zpv$<2BclA;5*b;q|a)(G&B3*_3`P+wWy`(rB2<3f;~<;Ac!s6$Rq78VnwWy6{1gjE7Ln6JCylp0KectFm5TD1!Enx6XM?&y^{uwAgFW#WJG6(Y=|Ie#j$a(bflxr~N3-Y;UO?>Vx0|%B)(4_zOd0NEFUtUDdgP4MY%KIqiIAlGWE|Evby1$r}7}qX$qtAik9N6?t!T9uEjEk&eSwO6>M8m|a$8|BTgRZi_=Zt1U&0)5`TocAc_H(U&z~j#atEA|wA6xJ0_ypuYhmEl=H0_1Pc=C(?byNTvvy%zgPq@ULS48pu*?3!hz{zINpDu3sP-hj_k+nBT_`^J&!vpMzTd(F*NMH(Jj(aN$!-M8$vI%Usdw6vgUJ8KX_>#doE(_-CVY1v#Si@EG1FrnTDd^ZLz_XV13xC6BGbgnh3~^dd0dLmQmBZihUc6-2)-dIx>24oucWR!AK-M{lE3pcioM}SLWu7GoXL!i=e7}D5I-Cw)HTA6NYe`Rj*%>bbp;14A>65BT>WfA7hPL%pV4=w6;!7E_2kH^#)s_84V@#=gksD|R8DO@Z4|tz>y%d@w{k`4y$UUG`_IUn37lpT8uEZ+Q-)!a)%B$ms+e>xOUw~%w*&5vh8me5#eJmoxY%%kp#$42707dCJxxef7UN_+jA-tj>8^^}XM(x_W*EPL!-a5x7HPsFSb-bwM>yrCNYq$mT57S9`2NI-qHQ2Z)A)S3>YkI}QcsIR=#S4(IfV!$qgk{TOIeb-yxyMocnSaA5`GFe$l9ecmN*oWR!HY~bYDt3&9IL$;fV`UwOKPR_q2=Q05Z*|^(%mo2W|1XDDqb?%r*&;Kt`RmpgPsGV{pJ59g+|6?=7`TG?K6a09>^B}XZjn5ED-ZFBjVksdd8zQ$X8z3@N7PpZmyTZBEJy=C;)nK*GViZzNw-n%<}AKXQCBbG720oWE-Nv?y?x()AJH&}}dFJB~7Z{e6bJqQ$^c!~n-23TvHf(Tlyw)U$dWr1Yndr>p`x+%oMZDQaK5Fzw5;%Jv@jW>aasGK|NCv;I>~+b%c%$xccHGnuSvvHK=$i>r`u^mI2br2Q1BQxhA|jnpM}3a$yVzXC1p7ZeX5T5g$bNkDNG{obVtM%8`7p%KvKH-HY{G#Lkt$zLoJZVlH@(QtkPF*F3qw1D5hs1M1f;TIL9mmi)j`DlzhusSSf34kFD-oY91$mdq&ZwJzb;N98ugWpw2QKMRW|fLHE}M8M;(%7b6{WHT^^AAQe27-A^VK_<8t7PWrWOzuXsL4&S#?U%!P}U>Jc5QP=}B{ax#Ot{JGVSH(_2NeU>H8_!F19N8dkiz)asLUp?DY)7>JU4Mjl45xYSKj$1vosfqL{bELEGgg1o}#$2`dsLBZZ>+c2zjp1oAIV{S01d0J6T!rno?J0Ff-V{HV?G^u%*RLQ2NxegD!v6$Oq$h^BuaTVtx#}XI`%TgT>dq6O1vgqk8&Y>q0o-`dPA4J{jXuE`7N}r)`W5mg_mjQtbAhaXnUjkAFDugq$+0U(F~>@cPLCw(Ybcu>$0uAoF%%z^ZH@QF@U;SX+K-}>7-6(f~JRtp11k_OvoSoB@KPey&TywPlDqlr>!j9^*mnolgQT`pCzBu}^mCmK->B6V6mp>e%gssz-$XUFYkdZqa%x*f=FD7f$X1lK}GkWpyJmo@V{}Y(TH-68ND|W^hFfz4i2J-Zalm*c>Xvj}AIrdqTyR>c)~>q+aUVaIW2%d3{C>KMSkzZ_ymh=8#P_=Mnb3}q>!`1u?htjaDrCY#Ri;NjrS8iJj4SWCv*E__X9qKEx&x`bPuIc^!yWap`zego0)s}b;S}S{~2zMbqNm5|0ur&+(`W5C3Z$teZ^v+@26ClW`RIfZOR;3)GbeaGcSD7XM%XllTUMPQD24Jt31Pd&*J-;6b0bxiwoE?!g?Ioc`MxZ@hQaf14HgQx^O}6=|M*`iXJ2V#UgF8`EwYZDc5;qa6L>ynTR*=r>cS%WxmhtE!r9{c#s#;>hWz4;`~0!B{}f>e5FVG9rS0I6{SJ5-I@y{&4d6eMI92oY4`B8O?ePI?jWLZ0rRy#%pN)+l@Iro)3$cbMIG|=;>$6wmVBrmx$1Jw8T$wMf7TShY(M+40A?NbQ{~>lJaX*vqrk2?h0xxie0p(%^uwiLSa>s@LqZ@Y>068a6;Q(b`On&T0Ol$#+9{qSHb~XJ!{8Ph8#-Hi}IKF(z#&}Bo&-VPf>XQQnuz%)p+VTj@FBX%sV#xJHzJr0`7Ez3AT~PGYt@CoAa7Di20TYai^wD3XJRPjcIk4rsspZafQ_Uag6Km<#p?-@8$E?%ln3~uFP9OYkv8X0vM29ER|Y^{1+XQe9+@r07DJUr)t8HzqVa>x?x5Egf5abuU5zWBEP#_XlH!^h%O(Hu`I=PJzIA)+UpS)hMKr)4Hq!3-**CAz?cVPLq|GwnlY|yXVo#G*c>=er7}g-2KkfsM=B#1J}=bQET;IolK+(>)<0xle|-k>|GMmbFxN02L_8I|ZO&1Ax(J08(3203&9YC7P<$jNSYLB_qg?>{9lk${ejr{NF28oxp#uJVNwHAMzKSDggwYDXjT6BY7oyY!xgOz_F*%S`clbao4}V8j#uN5)cV~m^(JvlT2QaRTcUcc=?(;xOvRj>;XZ0`MQ`cqd^CJiHm2ayX`y&7I(GD%9pNMr(z>YyVH{`j$xy?bXBoB@*Ub*eda?1JO%ePVo-SR=oOz3bxJK|zR2|hE2^1v)h4@+WnG$l3x(^m1Qj-%IhE8aS9R=|BOLDL?1#v_d`bl4Cmgu{j%LCEpy@Vc#zboM~G`5b&N|<%mWow>E}zeP|w)5damU(c}KV|&pQ`daBF3FaUX{MYr%G|GaeVY%A(Y2F)Q0lKFURXYbP-mykR^12$KGx?${awu*aO>hym`=*dt20maxU4=9I<>}$oj53JE~&4rY8S0X-qL_Ef!_<&5_P_Ta531+R-@-ISobmU)ZK`=be}3*WKg8LE_vQ^I&>`!HnFU;TkJu64u0Q_ODJ{hwYS8r$0YOMhN$S!Wy(I7TXnn9{A)zMNOZq_vl($Qp+}9}nKX#<6g048AWrs+KE9Rp&s=Y7)K~8lmwsy)V#1u@=0UytsM97E=ekd7VFUMG*bNKH9K*vp83H~ITnKo*CwiDt2W7Kn+khD>8#YIO`|xDV|DFR1mGI!?B_%!cjfj)$$we7C;B#c{qOBVcf0c3ZypmHce3|`h&%0HKzcIU%@NNA6^Hcj5Z`AeFQ|Wuxodfr$bTuue%*T1x@#p+$u{^kSN%(sJWj@aLi`%V|=jKD-CHV?we)D}cW3A?_zkny=p9_O+&|v^38&&w;_LuB(z|=-+OnKRmxCJ{MvS-nezT1>>5pvZSEAfLK?$*ro_`Fs`RQ;dX5q`S3-{-S7Yjgq(`5Ti8~%^JYAygrmA&hiDsy8`E$lk{8zW%sjGT84u9XKr+-G#Grs&4_z-JR3wDQ6E_kfSyX8c~JDeoH}o>Ty&Kk-G%{tr2ywa>BOpMJ(d)K{B=7H(0?DF9*jPz3`@U#I$-vt@6-6oBH{R|ZEZ`7v_2!L3BaLNNB>o-L-FTUlLrHT|MRA&~RHMJ7ym#^&YIdEu-l~>PEyx++ETS&|W5Py<*TM7B^`Rb%GJueS(8FSx=QT#=x?4Dk<8j51F!X2YgB@!!Pn#XE3jn;z!P(z_Ez?Nke4`@-9qJ>`g#{pT4)Tu{$8(BBb=`fA5=7m;xykC4w9u?CEbSf(`YB-W*GI;X{MqxjFy+cD?Fd67IgbZy3~COyiWLHqrEqZ0{zxMKG!>*dI^D6uX0+|zt;S=6(;X&CXf&mZ^{=oaw%F(v58b9gLezFJrTw1`;^Z`Z`UAEdKPH}ydQtZKez>P+#Kx@_w-a$uwYEC``6MCpUG2wGq1*HKQhh7?}ePhs_v4_-yiN=OgUd>3x4bR&4cQ(Ev$jv$g}HP&TCV{Td}57mcxttQqH+fF5W-KXpy)}9G3>(7U~w%?u%QsxGhH!2#kw-kWc)pPoqRfyNBOW1u5FMx8TxFxJbs1w3|8s-XB6#(grOb;>vwLvSGYw^}eT+eZo(VJ%R%E=74p5hvX!R4z%;X)?yTy3uN0Kn=+SKP{lAl^$hXcTWoSRCKGWJU3o*8}c0sq|a0Il~hMgMHR80dLXna_>K}@M~5LH_rs0{M+B3nxZFnks)vIpkCg*{ZstBJOHsFYZ`i!%8|laNzON(t45hxkE%mHNd>*JysMacffVkC*Km&7&eCX)86gx7CxbBr5=~IdOLHk2z(i&ydISZ1uj4#+wz&~eMOF8covsqib^?eq94)q3k)K|w_Gc~RsV!?8wMn}0}ynf4Md(;(vkxwVp)1L2h=%aADT~XE*uCgkeU-h=__nd)tZr<2b(7x`tl+U@vxA#r`xv?>q?`h#}6p=T}4V@^1dS|uCclWK=ubYTEC&cTnzXhR>gNT2ybs_F+*^q;=yLo(kiYnsoe3-2Vh;?PLkfgu~RlJTs<%QXoT5@4k&||NcixBUzEuL^GHV-UiUr(u}_%_@~yJ5I=O+JwOd9%e3*I2G5Ztqn9kKf$Osy-C?A1+eX($Fx!5CRSwI6IF={fA2%SACz6TL`W6NuJZvP@nJuOJtrey9P_X&_Di|iFv$6;7+n#$~BN{5{i&8!*e(C_dI#{+CM%vcK_zVPF+U>!^xIgia?`+JF|El=J&$o`lfyti~jllFPIY28(-$U$O?W6cS_{>k~zhgJlSg?yK{Qfnm&w+yg#HbU*q@NzEDm1@Adm~J^ehtTm#bA++{iPC+C`XtSjQzE8hKsdhB%Y)VX3Oi=gfMppm3W=Koy(_{}09FE1*Dx+V1K{7tqWih!(xbNhc(U3ol}UDr+#kra_oM3iPj#$=_W3}wtv38g3vqJ$_y=FIbO%wy#YBB>}tp->2w3{jCXWJsm&+^6@k&iDTDyuWAt?&sL|b??2_wfA1@S_Mq!cy#)dzq|;%RrPZgvmj5F+D>CBZ7+h0E352uE$^(;xRsQ>g~SWr)rs;+;IFZV7~)Grn;uEO_v>hZBHDys-o)Tjes_K;!ziO=l@oj9)u{WzCH6nN+P^TcMRbD_dokAkcc3Y@qs@bF9!{JI05gihLB-HGdEUHi4<50*s`BtN=jsXUH{I|Qak`%B~uUa_%0mtt(D7q&ikOJSUF%C^7(_kE{SAhQh-}!Knko6!@KgB=>7P+QWQ2RKqt?A?>Y>kPfpxRbWl0lNA+SEQ~*~$Be1(^NO#2#nXi#O>C?(ar_H6ueCDfr1PAoS6z2C<2aXp=5v*@D1xgrrQ;k-Je;UEjAEtlPaD{_-1Wrq997IJ?+hiwDXskP4ubf1LpW+GS>{n-v_nNnDF*Ed^bhQRlmgUY+V;R%vADRU*axFbbMWsHeJBnU(s?hx!h$2__&X0YtqT9%DgvGQeGgCdpuPEvtKv>6GLhD7T)Q867ol$)oJMB!$9bQGc5acTSKHYs5WS@BuQgNsW6s@AXKId6AbwfbYUAa|e|DWb)%=}4A2!|FuXz}l?jJ9>v{8B~kkEMl?F*)UI<_D9D^rE@LGVT0Buh2^J~?OAtc718d{_0WoxRA^Pse)e@-VkM(5uECqxuEyeq!vB73@V&Q=t+%rGos5$nRN7-_H{KLct01ym5;%V3XxdmqV3&8I13zer!@SKX!i&(VzHXI%b^2s(t`>&(z3BEn_eGrScvi2pkueiSV%Z9Z@u%PkbO($Qp6FfGzw1~mq9t0py6aU*F)+t8@70OusHm3g0Y1%JVk0j97i`vom_HJkwuQZnXJ4S})PZ`1Bi1sDEjcvs{DIlV5EcE;Y+708Tl;o_*K;#`5y9dnK<@pwWDifeUqwcn(q3O^$yZ5ciKpqMOu5Z43L~i{stu0+Y0-XY#0!JnG>X(1pA!|6XFZ3kMAx8z}1>Cy}4nkj@;7v!KDPr&hDtT^I+0-tR0}pGt#+{j?lfBE}K*psan9oix~!eU)QS5&22WKAnE$#l>JRwEV@>M2s)|!PUW4qH!p{{_Ape!XoAq4LbH6Wh)W7w-JQWh_x&2OuVjOo*&DS`UMFsZVs}6l`#XgLiEw11D$wq^IE{lCly?Bo2w#xCD#UUCbr}KU!BA6vKM?M{OSHMe0SB0FN4U3cX_#tc_mQcnqFJ3mIU$>vwn^K$3OqahlNlFjL4sSu#W}{m)L!oalrA{UD%QOK8OZ#?}swK$uRX>Tq+XF|C9!ekC^ig7eMTW%B;|4Xc$Qy^3NH08cjRHi!$K3~UUVV5{HrmTgh4Z5$DdSY+jh(E5F~6=;K_fart;rU7BeDOH?x6xbT(i7BfaA=6?NzvO8x0tGGs5X}&nszLCi7jSLG&B#&j*<9Nu?#W%&W|!!G+=jM-)yo<(aRwa^~-#uNRAv^eLwL1vQ%=?^GTX0gVF|dDIv7(Ea~H&G8~<(M~I-28@?CzH-+UtrJ~UmD}wSeX_10CBHlQcQzXG4gvhru#c0ukOU*B2ZLNHQc@j$M3!R^jj-!G6-_*{urEr_!E6^i#aGDxvO-(_FUg^`o3HD=Te6>3M9#M2i_}Zs$-3h+fpGyg{rHrEH(Z(PNE-cz84j8>ZXF<$uaS()5{DhTBtziro66V%A@o7{zp=X288Y%*DmA6=ofm&&m2zL)0Ph&>!-+Nj`Fg)_+#AYTPSEB!P*jh5wZ_*&!3gYi5H|;)K+d}vACdnb`N6i>Y7F&KN-~fo_LX#BA;14ydjfgfDF@r9iLofIyc)Z)%}L!Bz?dCW7%|&Gun;TtPY56qOXgets=RRXeSa$4Wy|+=-+(INBifgKZ$&osPJ1ULBhQp?FN4Nac=beAkj}@MIG7~yKD*ms#pLFeTeY?um2!Iz6~|V-yD#)u)N!3`Hs#TdnlZVl~%}?2>-%oMuz)FDrS$F`Y)#z+-`5|Cxcy4-gp>O-@qJdWaa+D^!+mL{ceZzXrHuxXh3~LVbpUO*`YltN9Cg@FBOy?Tc_JwqMa{k2JTr<8M@hpMrePj#BES~kizH}W69??XD9TLwl1cETG=vz*0`WKdt$+Wa$O-6Zdd-w-{FSmKZ1+SDj!pzL3onxyTHE~#}8kz-0&!$28n7-oJUMBPu?VORmd^!VpwJ}Ew{rB`AK=b=2c;gkoT>j#Zq|L4eH8EzUBWv*3*SrW?Yp=-E-E80rS~zu7op>(N2W6L9|CVg&i%g6k}{uhRT_*q-0ITj#W?}+wl{Ai@=uhzcT`_dlq~!wQ$$N>!jna7kORWFy`BX@08agN|hv!=F${h_!^zTd5I}gpr??ULj)hp6~(7iquioDUkynir}{(a@Ae^nQ@;&;i*JOIBI6~pgd!|0lK$h!zVt{Br|s1#B2+OV{p<|bdyz%kg2(haZG$8WY^eb`v?TLaBP8!9K11C?JN8>m(wJ!d2@-7CVAIKC_9u%uZnfI>JVi=hU>Nw5RC;Hs`7e)sC#c<@1wVa?Y#@X7D_C_1J--u4)bI%>X^|D39{Pe0P6d>xcc6`NowS9ESh_MqD%oUvWaRwv)jC*$$8W4J%?>`}LB=+aiPBbX7e0^hn50kFQE5X~fbe>NSZ~CiCaGVP}R~ZJcE(S|)Bhl^)O!ci>f&#W%7BlK7k1az!z^3r2yEU>HcC~oSn_=n`Jx_S)8cHSoyYHCTcYG!Cg!MmWB1`=<7OcdAPMCQ@_QKxQK_?F4SV!elUZx?joBisOHCn#a9$83po|s|uZG!|}X(_-@^T778@PuCO}w3+?%vI3Ki}r2^Z{6?;UUGW9KzU7hvn3zgBADxRs2Hii40*Vq9X<9>wl9qn}im-z+K>3mo@#-*A`muxukSHba5G#K9GmLtw|A3FBBRB?rPF*G+so{<$mo^zxyw{n|tF{DeY{?TXRU0;7)2rIo(1XCANMYc=e-@SZrwZM!Q8HoJQ@7(zNP2a+7mK#x^OG&z+?+My(f6&#v_LIKeZMPr&z@+1PEVf78@fsC4%N}MbSD?MnQDGJLFctEzyQh2-V#?Q|kF#8h21@*S+oWun`WQNhj@d-gKu^zG(V0o_>tYY=(|An-)n9ct)-v_w`Dwdt?^4cUhTh291;~pw6nt?rw7Clt4~n+;G5vm^$&GE1jYSZ0e69OhPJCW((+Iy8l?;P-zIu0fpqoN`a&E^^13un^x3VLfdO{Ky8K0Qw(COwMz$2}GZ=iY`rekSGQ<4k=Lt@@k1*^2(@uD?Kj#j4hF&+B&)xMxDjiP_K|#zf%}_H4pcrouOBJj0#@SyMr9|Ay33)xMj7nBVJE52AZAklfkEw{ilNi41n>fuH8eScE(f{t)oPE&3JykpOIyCV}_-Lsa&Hav}$d%%EB7wj$FI3I_qwbu&>_&ThZ)+I1{CIpMC`AXqJD@A{mb$h+V@?hkvTCKskExzGL1CYyF^-Pl|I`o*(d!QVgfF=glD2#8>(&&2PS=Ipl=Ld||{iUy+ZO;V`yoL%T?5-CI`7Ni^8lfJ|_&DpgIEMBGc#Q~uwH#vN9&c5T(!!sjB32@%?>7J+VXfIi;q_Z+S5o`lq$_A}RJC)2kzRAcQh`uyCpZv!gyVd*0L|@&#dX3SSJWCPpg-u=OTj$)r353psldb>U^8so31{4cBzYm87D+Maud>BRX$Fz-RyHsI-3Q-1B}Sha0!Kg##n+<{a|#GwZZ9cqx$}+-5A0wIN{cc`@#shLD(OXcl8TxW??}-1AdWNqnlxv0&Xdb2;sZfJ85jHf5QjbKO_U{80dQvNz~%4NO!{wT`hv^(Lt$wQIqjDl-unj@^?c!%42O{?Z4Sj@xbLukQug1NV>blC&3AP@|yd7;DJN6x_dfKMxUi-xdR^if3!~yW+fB6hI5P<{b-)=Va6s|Kj=iV1#3E%iTE0BE8j7F+kjidzY2wUX1g-`=iL)^MCNYT*B?g(Ep6gK^y`t5)P+%212HRSEODS?sue*HEE@zdgG==`U^fsz|)o(mD~roPjTP~trxr;1w=ifCLlf{G*i)Aozbv7?!eH(Da41ZYVDCLLb1?t&wBaCw}_8?a`Ix&9dYnOF>R?#AL0{|a5v)MhZ~ToFYxFQQ~&Woqki}7_M1S|KPhJ*|9`kzH*o8nAn1v2S{v?%IN1037nkbX0_{bW`T3%_?`GO`svAYh{M>R$O4UkaQJvrTcXVbaoEsb%v&}R0h=3dJTP)a96V>;M+ViSK#L{a>T(O>5Wl!~{L95?@D_>M#%F{6B#Li%!}8D=cyO=eu!bPw^KRnR@?BA}aA$vsq~SQ?aHjRnq5wI6crNC$Y>P1R|MHi9zp3Iuuv{wmnDu#;3WD+aV0b9na>1GUA~0X4~$Jif~5VjRRA@%E9RGD_s{y!qvUv@?%#Khadsc+2S2h(ErWpYGyOyK-6oWFpmZ;G0Qi94e>moKY91c!Q(OT_|?x5kza@dp<`@r9t$2W8+Cl1Ar5+zjj!k3aE8otr;h!swZeI_V23@6xF0BOJ#e+S++^-dt9zI4sPp&G&R0K9(9Vl%as370?YS7`M|c;1`BOTUnnwOF%q#D`BmD)h^@w}5TLR7v@JM|{K__%hsu5-0zQ^W_isOe{7TvSiJg>wG>n^!ksqA6JZI<4_#{wvCl=hNYTa8okarQh;zv$A$US*`W2rduF4CWU%j^#(!u0IIVSX>)=DFAYLJav8kvAi;EDE|O;;AX7h?~M{2l6kK7>IaT@vLAS@&xhPHaS*-IDlW_;=Cu2UlI47Ysm3H!ZQ9V&MUOnOa{&p0H2xNxGp>Jfys;oKcTP++K!!Srp`y0FOOZDV>@hIA@R3Zt6-r{e7pN4V(s?C-5|J`?G>b$lCVZaqaXTd_8{r<#Zb4GerSpld_K?Y6fxG01L`rCvg6%|Plcs*3V$yA@_OMwrq`gV4a#2EFLG%%q$c_P`ulUI{#DQo>Dc%vwsORcbz&r*)g2%F{q~Ybe}8Eby!&xV-SG7BIlFe_58k0B60A`dzJJc>#GHL&ps6{RRT@<6RJqizg5&4zU7(tB%9oMnz}|&%E!E_t_QvzKU`0zw!}D$4b9Uk$uDmW1l5GXj1l=(1XUc6GyC@tBPqtY-H<7{f6K};#1DU3H$d$J_`C-U)&c5bO(nBN8B$(WLd)prq>XFZpr+rX-G}$sq0x_E#zI?`LC-TPS4&40LPjeTZKTvomo7#Wgf)fij^nLJ0e@^rxf0_{qr~NnlHvfP;p|bDogUjR?@S;eYDy>7FAQrzQIb~NoLr)`K81W?X|22*$GWzK>`yn3~PHsMAE1L`|VvBxF?nj&#k_^gx9;N_aO4CrI0iJh#>OJpH;UK~De)UXsU*uz6&HXQ=6G^bs?WxDwhxlDoLukfb#Q}`GK`tMrI#8lcAvEk?|FT@`D!`Kw`4r`TQSCQ&S#MBKR+j>_MS$bkn`!inSOQ>T)47p&tMAjgxne(#YO8<7Cm7ysO)Y%ZhW?>LGQVVUZ#eWBZ0K=i@&iAF9_*3iivl{_KRz7BxWFS-U27T?155b(e&0Tdae+9`ou$QrFz=Mv43mBf(YM+$HUUWINEKW*7$2$Yyk1DFCc)Ha?x|%y$RDB(tc}YrNCwey7Ow-Dh+FY{)(Vc<`4zvVc@NU&t5i#LgQ&KHK`-$KZAbHthvk+0oOG>|BM)5JgtgZtyk?C1w{SF>=WcyD@bRz>lDR6t?j!OQWDOS4(cb_OIh@NpWvM(RxdFwB%156+_z1D(r0Q%xpfhrgtakIL&J$cl5bhhI*a%)?whrfp}$G|t!qE-YvfOP)X8|IKyy^GXHzfEtBVGk#f73%8U0)3_aJV${p@#SW5d8ub994IDpP+<*Jn}cZzJGdSrYGs-Aw(;ckMadITZz)+Af5v-a#D1S~NLL=)5RWq^LmoGR6xD+n~&|cjCZdVX4@e5S%B(z2lp`3Gifj|Etn3I8WM-i)XDYNrc*#qaAG55TC}1XZ4*d$&kKiIaz5h;Pt>syrf0~<37g{<7sXCqOB}0(ZIDK-?Mca;_ycIQO9N3Sm;ncxFGun;vlh1sM7Cw9LUl)kV*4!y_}x;dfgooKp?H1vrY%+$+pfu-{sMXK=uoICsBvc&VV6eaaQ_IViC?dR=calv=FY;-ZiE5cNT!-6@Q|iq1Odf5P3%%EmJzK-oj>SV4XI-17oCW9u`oPw?PdRfYqJjUp>3l~fewF(%sa@_`EO4xHUKG0)aUgW?XGY_I@P9^|kXJ~GN%h#!`JRwbQO$D)#DVaKY+i{#vkB-9woIQQ0Dh&X5sgsaC1#{+Nqnvj{5h{MwPW0LZR5sg!1A%VdyiQNMY3LNsJ&4gq}c;UI63XbN^T5S43E*($~Y9{&lU7%#okGs=W%Nm>9-=u1GfWqLsD#Cig8#fCU;uJ@sp>=IpOC@=`=vlNkDzQC@hCM8q92fmD#uxI%N}z~@JOEU%Thkf0>7J5eeL?Yt|l@6Fqh24xw4`#VkX?+WwTY-#RI1FcZ!g*6g3b9RBQe(`VT)Bo|YF|e+hQf;cWVmcyUe|%AGfK*z}T+FlO~_={A6q9)7`lq@j&Q9Q{C`fi|C)dOq$LcOU2RKMM+h$>k*3(L*{iP*XMrpqtM@@9Fpc8%zVr%t6rnRVERzQ13q8Kvo{x4R`@C}g$}~ow>m7ISy9Dzc8~&_x3!YhipKaGge@N8NOzw(=S{*tfPUzo$C@84%o{9mYPuC9x^z%eNIA_s#Sh+*@m)``&yX4mS?!o8&cb>K$c|!18yLsR3lOg%qgRdpyh}-FjR+BW5REECvK5^t%j6NT9zO<(3qFs2p-`sdaZ}8{L43VJvQt-wlr*VGz4XA`%bxnh&=KPozE5!NrvWgdDBVk}|^vS?04E;lQXF$XS)+k7NyvR2<9Q`4Yf1p+s1Mk-^^om}E`%RvNqf>q|@o}^z0DL7tp3a9O$tC>YTrZQTtHv%Yi+dG%4|eDuj$O24N!;xB9DoS3;ky!?+MnHS5Yu#SuAV7f$_9s&8&5SVl3la;;lRSL)|m4+h>o(L&Hewxgt}XC!;)v-S%iF0*{x3S6d*)N21?M*`K6;ecL&3{`7184s5-a0&3$I+mo62XP9?R7*|^=YL9r3ZFTuZs^MS_mvhwo*Xc)R6w59b;7G|<)%KP&M7*W>x6xB1`OM1t3m-e(d_^(;NsorNhze>1w&6X`S9!|^lovq%4{A!2K=xdH+i7?^yF_~{4&Xe9dmYSEpCczpN*3cgr7$1pn;b!zdp0ESYKk4rFQD0OlT>ZxS>->D2Kb>LMPR=__0v_pw`)Ff`PyC3^ALF+qMxG&s1?`OgbB+RMP3bjpNf=L0`*>!Do``{0p~9Y8GKj;*CwhA)w#R`S-GNFm<#`fv6MMhJGxBZJG7$%&9>2zw9#7dX|DK{D4h%j#l=QDooCSHsvtt%5E($4dSuR8LtQXD`25+`a1xB2d!F5EZX+vWwB;edynU}f<=g-y;GewW?{nO7pvHZ7;VMFX+T6^%|udkJMvtUxR%xcqp0RT*($@EA%Q5a%LW=ONFWm)lztqLctPer`N*;3eWfv-9oruFk8rPuvcoL)UwzMevjmo+-&3n=*aEVR`+aeK%gr>D*R!D`y{MZl5+i{){;iYK}38szuvV?y!onPI0wEuW43AP$M+}_=XI21_vmx=C*VcakC+akY8IzVY2$J^^V&_8cY3W!(@sQO<*9IS{Bygn87(f_k8+{mxy(Km9AOGwZaPVPMN3~?azN}hO2ZJDcR60Fm^k?zWk_jI~{%JWJ;rhv4&j`A^+!-zwdl5}}EeZCog_^By~c8#N%`Y9f1z^A$I{mVGC%Q_Z_323B4c$=WJMk3}@5$7fy1L+{qAH%6$1Q859K-4K5=_Z!qo?`NknWaX|D-KWc_?d__uZpk75H7+*Z_HLcKX&Q9#VLXW4w%DRBdt*h{yioV@xs!tY#=HK#;l*v)aZt1>xV=^e<5~>ohWya@MBw#*Gr@HT`4u0XcwXj9VbqDZY{a+^kH3GQEh7P;gKl-*d(KXrU)&odLEH0{fvQ^(XWy4+z6#w4oD4_8HrG#O;(1GzWNmVKM=C={TF3@*n_~O%M6;3vs=Z;{A8+8fA5s6jp3awSFP=ViWftdQw_PoF&Wd#KT9~MEkcN0RTxC~xOizbROHO&3Fy&vpp1fNqUla+pv(1XntXJYS@p`fw#&{sv|SBq*Yv-t8-;flvV;oUpP6NtL$>J$?E+`5$Yvn}$3<;RBChw7z4+T>x?QCGx`=v&hR@)Gq3dY-awfr$gesx82Ou$NgE$a};nv#S$EFhC`!ln%FM|+=RrL=BtuvC~wcSOTnnQ?#slzi{N`BhJX>dbjMKg@46HTAuN>xF2CE_j9n#J(Yc$)7B~WY!blv=2V|Zj4tE~7=GUJj!K7>O7_OIYb>cp*!sebK%yY{2*G$8ss%LM%YJhXXI@sOQZCAMuY->ga9mhO;bd=kK|D}+t*3%)P04p)6k1fp;JzH^M_$)b29!oJrc#W07hHpfDC($>kE%F^1z{N9kMieM>+ec|*EhH1ekUWpdgCjaq(xtkMBdTI2|TAVQj5R#+dU0xGK`<_&Ek0!`CPfGie)-@T!|6O2tt0fWSL^lphyO6eknLm<$ye@{L<`j=c5eZSu!bA6N5Y|d&!vFmHnBpL_5y@!Jy-uooDY?zM^V+{QdnaxLyMN8}Ye=`(hzgbT7x<<>=4Z-T8LQnk6#&Q3@(xykn<1vprBvfr;ahzx}llw*zt864Z=HAeMA+)fqnI1AL=xKaUxwfkdk5j@Cnn=kCH;4yP^Yz^~M?@a0eBQRQo21}^=S4ppv7UiOuE-xtRF;2w`(23+T&*eXvTkK*J>I4a7M3DZFx5v{IxKTG8CrwE+xA^Osqu{Zf{O>4`Yh1$B|Ua0fvlQ!fMOf^Jv(uSD{fIK@cj1vlIR!c{|SF?txJNV2NwCeiZS6s-{+=mN&|l7J@1ZqAivsT6xn_IJDorLEL;3x6V5Bg0aGWt_;hG_Grm1Y5pg@e!O;5S<_!4!^YvbnP{fVsZ=qV00VQ9T{%sONe)ZSQm#uat7UnNW(@riz|LKz$ykY!$0x0%a#%tX{960YAHj2MUf=ofNW*>2;dfsxSQQ!9|;KZ}&!_XhxcVAn6X+X-11Wu%zoqp>PAIFbg&urGE!JSRb<|mU7pDL?aPOtZA@M>Pye0y!gCwvKyb*5)J@CxudZrF(Yfyd?)=flMr5N~^MzN!t*tGc{o>-j+$ARtI7GbzITPG6!kN?{kqFgyhKDV+(&y~%Y1fClpV8;-isE0bOmz*!e08V$rI`A?pOV}W2Nm+o$z88f!FPDw@vFLs!)%iG?-qLe?P3398P!+9^(>hnxG)j5~_^3K+!gTV5Iwx?Zio^0Q6f$~Br1C}>-%%>bhe26}CcSjT9#tIKM86G^p(m8yjFT*|=Jn4ksem#EotBVgMZFrdiy82H`+S8f(P|OPqUq#=)f975CFiR5o)y>=|snSIxFuPOo;^Pj)p*d`HJ@@W35ZZoBlE({iFseHv8Abnl4IJlrWJj2IrdE%e@qhP}m;b||N!>bl-*Rud-?lQhH&odb`~RMg+VH>kSr{|-JZ%Thw=EvAu;t=G)2W6FbI%j^8sz6muu(9&Ws!m1oSn#*4!A;s?9%+Ns+%zn>d$-C)2t%t485rvSMgj+Zu_DxVjU5BxfjeV=j@+;<&Dm`X2QwogNph)kdNK22y3l2&4Tq_FO;vaqkXr?P;VDcHW0k2&;sq;J#n_z^0R@YPfQfF8@(vZ+P5W#!JjKD@$cSvUv##zAP&xDI)wk&g*<`ikLh_R89u&~dRMRKJ!gNHT>REAgapO1J+U*JG43}}%_qL_rbF(n3eiV)ct5yoo{0M)`Z{9Nuax5X)uxt&0e+)Q_$E;zm0XSISLcsYB}_JCfoH*`UdjRFU4J&SOtW`oL4IP;?=OgNI>LGG@rqEN9f>q3Z}#L(gM@bD8$Wp)kV1m^$bv~IdCQKB=P~GOvYn-CWxknCC5?_&r&Dr%v=BI9GT(yl}F5{N^UCsyGs|%tJ#UXYm2kwe2@LvKAR;(fMnN0USCU5mdBt_F0^`~-O==UD>57r9oN@w&l`qGR3U+Dnnc#28}6j!X~`=XBc@Z4W{&W<+|LNC7?`BjblN-jv>A-W+GCN(t*eFgV_m%;=jVev`?6-hT7r`gS@mdJy|7ii9|{U*~Y#Y>@_I-{rPkU5oL;dx1sSlcVWC%3-;Yxd`{0G&S46*=a^q|m_;SR6a}na!XMD!GZ7>A}S>=~46vg;bPT^Yk_ZA5Vyjr+$q(f^JKfVEJ2|1=qaJZkOEgK9)60Mqc9&DPhY^P!>ZJ>?FcV~ks`V`oV%#M9PiYipGWsw4`HcINwY2^t2|Kf(f~w|r;|}6O@L=1DEO2!yJyej4_z=9XQa+o}|9WK};?woFc9BF&Dm;%+j=8miDX-gdX?S1{39@9XMSQA|R}gvfb+u_gl&w#iGM(EDZ^&$+@6(C;#atPTr#j(RC6&xGprK@EVXZF4Q=(2Ph%J**M`oOcb(HjQEILHWgx|qj>=z}`pAh-Uw>M^ih-RD6;2S&#wkaPlIh&gWioxF9UQFj#5#q9iWrEqz`0%FAY)-`7^ClUl3-%l&!NTKv(qVo2-1Dk^zj|dirh%}IneeYJ{O$?y@$u%)#d5>*kPvNSEI54d0h1?xt?MLmHe;J8^NWm`MkQTVKdfDjkUHTaFmSL3Ngkm8CVEQKzFNf;eoIbBJoal)<<+R8>bDdbsV4?YJ`GpxUc$g*cVUe5>5jED$`*aZxN2aUk+cR(oYZz@9YQht}vj#rELPHB&@)&(dytkpfkuO@XWVN3S^&iPO7sn^f7~H^C~;k58n{o4HobX^acZ*Rf_Tv$ARLRq5ZyK!DV=&rDtV7Ee?KX&vVK9-sfOUf<21>Z&(DMCB+gB!@AW9r$>*q51xTV!&zL30ajwq{i9(2xgfJ~-5_MGRzCDmPdP$4<*uW=LdD1pkqhvvKGgF@u_d&>Gu_tZDHdDi{SXY?_QTZH_o=3TMR)r$qN{kxK;)|fZq?BP5(b1nlC4{>_!IDvk0TEr|g?pr1heJ~a!pg&aH-gNbjQa1Q^Dg=A$qTeIVJ;DrgpeTGT$GYQ)Pv_rxXCyUpL8pJ1qofh>d0C^~z{isZx3b-2MSmktVCaH9%7e7B`_sQ_@f@aoe0%+{aXyqSEl}_6N8E_=np1D`!G;i6)z^Q{AOj&Yh%=4DjsVrwpKVV@f5^yNGR}dRquWZQVsV}f6$-S=ZO?_TGU2Zr-eY_u_Sdf`b0Jpwr~s7-A1y7+(%0uQ`usXa;XEPI9!$D(VeEy1q5=!z!|tjU=i{9R8LWSNEz_9z1GOmU#gcpoPD`>|aUSs@@(Y^-^Z(^FS>gS1MoK^a*hw@LcdM51j16hp(m~ziJw7?%i=J9}d4R?_>2ud}dp&e35F&hu3;GOWUs?zan&V{Hih;db8(WA+I3%0bMN4f~#CZH4^cN1A`AmW<&J%l>rr_n15JdQGDj~(Huq|OY#@Qfyf(F;s58K1^AFx5Z}YQG#BI!>^5F=9@h)e25^mT9#{}Us1u08YyWtU)s1-|zqJ13w=|q5L>|~(&3qvG((pMVzgnbl=NkLneE9hG!9q1l^fQ#im4D3sWJ0ssw5)l2I{sb0mXVNlIu9pr+f&1IFZ^8frmRn9Hk?X1Vx)f*acD^xSas7X2j08(DsxpZ>9j~*K6{WW7dlmx+UrLV2S)#)?A(9)S_X)N&VX50zg!+e7k&Lp#DSQ%%P4se5_^t!!6oEZzQr<^Z6xzyy1Q8CtqS@RBJc5MP(Bdp6f9!MuMSI^iOAkB0yCj$1O89=zC=IkPh&-l`5<^KeeQYP*>%^(WyoM0Jg%r*i#W{R8>?7wiOi^j=v(#w`KLey8HjZ(YmWHPXQg`aQVNXZ)aWSApzeBKu=RnWlN2E9Z4mmk6!|BSXGyE3Fz#ntd(m%PcW}93W!>r}G0!iM{HSoO@y#aFKEz?3N<-`|78>}ZDqX*`0&!R#&3)#;`yvRu!==7{4E09tpZ$D>O!(#ijwKyzY%<6Q{oxLFX#N#aFmdpK!xRZME;RWVpb&k$+Pm>MQR2>N|hdiwtkh>i>#XMLY31W;@7?ed3P$h{M|ZzimGHI1DN`@OtcIhn$oVJHb;oSX1D;C|9#6T?lLF(;ch*b(Wzw-6eWmy01Qm$yW~qsNw>>_skc^|x&ll=5Qnydw{2~03Ifcf^ZwWNQ`EyYG$>Sp~#h_{XG=Z`Z=TA|8^w6UDWH=mix1Mwc^&w;Xhh+Wr$w26^zSxTPyI;L44f4p)aaZ;I{?CXHyXN@34NEADeuA$e(O#?FK&`n>fimAad*U{uoj7kdWc#NxTu1&7AG*K#)obXRL}lc~*{)#H3tbj`V@jI_)47i=?ai2U)ag9o25&L!9m+jD$kb1e@UwA0ih;;?^V^B@r{mjd(kFH@SZaw-78RiWq*swqp_@4wB)lCjeDOiM{mQ(lefQ`%WU!P!JcRZeH|;-c6QclkmuY|9DzvxO`5ZfxKmnp(vFRJct#;`=5tnsTxUlQqCPh!Qd$aiP1k_XE9eul*uo&%c&kyhE2&BQs2`j@Bu8144+(Ye(8Syu=3~`INy(K5f?jD?c*8&Te`ct23GlV;f$Z%${${P7G)X7w)Z@k)$l3|Q<&%uiy(atj2oOkUZ8S?B3{|q;weMx7*Es0GO_}zVV(ElFV#s5rR`bb}=1P|XIiT3`4`SD+X3RgXD>#RDCcB1cw>vt;bYW>`rD~fhvKfC!M4cLO7#y@_7c;+f*3~anp4Cekzyb^b!ouFar&+h>--<5CvhZ~)@=uWAq(Z4UDli{q6dYijWy~-A%zi)!ud-10IXx~O!@lF3R85aE&x63p{JJA9Ss6Wy_VF-j(QgN+z?I~%Al4M^eszyyp0d%vY~XfT%wDt)&GUaS^PcX1-e#t+lteqxkD1a{{7-lK6ZYSs)3h|UB_;p-fG66C{YBC|GVJpoV@tk;`kb2WBR@Dz$>7uWH1;P2?Gg`O$$Hb{j_OJgNuEx$i|wvmlCqip9cdTL*;ugOAJGr!0{wj_*B`m1A&q?oU3^}97Z^|(eZWf%@p+;z-POgkfB)`^&l9@hn}=xs;!ZT$r9|9<9?;h*QAe;P9e;=5tA^W3Amw{b4c9Gv{$xjFg-uEk=$%@3W85}@Osr)mJllrGxq_pkS8wxqB3)9H=ZvN0~$y}0$*zktlx&j!6h{&20_^mfx9G6cltI9=L;@#3ibi5>IJDPV89re9GT`RDQ1+H3spQ{bn!0B_hvjHgOJ1b7z^65$hSEnd;8AcqJq4axInlt@~b~OhVl7@MUd?!+FE)X{k(OSci_39BAC_6-o5n;;y@jADkg6ugD9W$3jxdYx!)(=^OFY|bX2#;);~oY)}4GPNNJ+a|IDg8Av|a&E7TnLN}mr#iw=IS-i!EHCQY9n3a7vyz4d!8lp+orWg4~HSg2r_;;P(`i8v7b1?F9$Lj4J)l=Hg~hw{61z6YkMu-oYJ%xEC;>H$i#vKE~`6Mfu%o0M36aTy(O=g@k{Fvk6P3i-8!|o^ip!+x9i09@^@$oK~x{|2{1$o7PW-IfRl)W+8^%7g&@lzmbhC-tjG4V{l3k@}X6nODW%*Bx%?FTtlIX_%L1%tPK2G3N}=jdxwm-&>+J3#m9|Iby5V5Yu?d7)bG%`*h;2*v7v*#?)61rF}b#ASrNwfQZ}7S)%;|z+p(-_*$K20`>Q-Ue;$}0TU*D4c0R8`QT=CR*zYHD*d+t;$;uFE@RXwf5r-|L(Qf(n?dG$$Dd7CQC*n*j;v@Na>koM)DtOc0@%aF@4@3guB{Cl>QE^?4ckFu@-{gHgLa|5ZFVe8!2$uJvBdnA5-6FW21<)lT>gM+P1H=6!FR4aMp1VKaJtfIoSWR)AvW;4X(YQ$Ej^C*1oDteGjEpDsyo?Ee1kfOJo`1c0JXx$EvA_k$(cB7_W(ZtZXqdBX6hX5AvM<}TC;o)lzbZ@rg-x4V4};)@Vh8Z71#|CNH}I;M|1MCQfB%$j($cs&i_VuAw}n?(51P5*T=-)X3vX)`ui0r6SOrkk4`Wx%;jE$e&|%I)mr?7A-&EF7J5b`zz8ILW(~(B{Lgg6TSSfhaf7FHakyDxSxK@fSl*4ssFUIcK6?uj1^%u-sVVur-LAM?_3n!kxpP$2l+AyA<(jW4~D6{7yl>l+2pVBJ*h6zpStw?MlO{_Gu5TMa_P7Om4D)lYi2`Y3*(LrD5Z|d6^U26NdmYm{z`tkJ+61Fzx8h`r;pSHEnCGpkf%Ain)JvIp@58Ok5@+?rTIECVWT@|A2~|zxwQoG9l-@w(iIfMuhe`g5r8=9KV|1c!`G5M;c|(H&ry4^C$gOe%cXaZR+k|@7Q&B3B{4w4Zuvuy7m@q<7S2NHvBU=|a}XCyayrv`m=Cqrj@~=84skLEswzVOK_@n6-gQNMYUBC8g_S(`CVT$H-5At^q#mqr6a_qn?(;_-Lkh(>JL2+-7{#OLpW(KL<`y>w2B)kqouZ3=%g&#ZjAxcJ&~P|edZ>t>Hho)XLtG;dBE|M;+&Xc!5BE{8PfVLc!Ju`kb5DrOhb@}8S-HTAf|rJ6<+V{LhZD=!cO2sE2$h7R``bkG4>?0+ydn(;gZD}{E)bbhb3*Rhc~2U=@7V>m*PVzyy%A<-yr!}nj-b)d*6=MKbXmYnd@1zd$&*yp8^s~uA8u+FzxSL-xlPPX3n81H`{s8)Nh3YTtvM_@>Ck;P{O&W)2ARVp0BfhbOZ&$d~Fuxpc-UY@rTn#B+rV{M4WlE>D0IxG;EO@Q!+LL<Cx^H?DEG`|?-u(BX4U!p$+Km21V9R#Sq?A444!ptdQe*m*JhzHH|s!)offYcc{G@=}?uWZVJIbd`e6&(RAp>IP29FYiV4XGT>mB38!r0YyYvc-WpDdD@b2LDM4?~VcuO4ZL^~EF~=ClL_*6}O8elJJ;UU}%pnlaWC95q*T_;CVp`j4N$`vwJ}KB^0HjSwFbT%_eSfQIPtgIDh=K>4i7DCl^&lNR>-b+<=3ELvnKAwcmF>fT+xqPXdz6qTWZF*KF_z;S7G>?jhMS|@e7u`e)pA()q&cfq-U4}M|BOY^RWW?HCQ&#=aTxBOk*+e{9)l?usC0V4KUvh{WR8-t9R+t+?zwsSJ?imW1G2|&Napzew6+sUrx911Ga``XL`kmbpEIj%PqI#_+LA1Imr`vyNQB!u#uG3TNk|+z21qqRfZ18Q%r0NPT*yedS}FegYu%kSV&Oa9#eGzY~He7aa6b;odl)uUaasPX2D%;~|sIdyaT_Q5yIr+k)X^V6@yESC=_IfRm`OaMl;Q{X$Vc)aOzfhi;HZNjtUuNOgxS*#6w~;Ts9oVW@8N~->yXHk63vqq-j(~3lw*)X|>6rVqDYyF8-#f8**QQn;*r+p1LNW3^zu_x`>Nq=>JeRlM5Le&y!$I~I1)C;rb#Q1wJZXiI)=p0Egv>vwJwXilOyG!vza&o4z`k6z?a>g#r?=iW%bvhM?TGsd+lC`fDfuLQDrKPG&X57!BKR-AriAXhEOg2w7;ch6d|;>PCAV9AVV#au{r~Q#YC(EQVDrAW0#F(|w>16^;$*(bh-#iNUQ?}({3_q6R=#W&1**onPm|3NZ+hN%hB-q)WtDWy+1-efJc=g+X;6!H(6P9NxKsW@F%8bnZA&UXeCHkFq^|O`8Uv)SaILh+9On-{J1gEW!Z}>8jB&0_cShZd)*GCin=)YKFCWAwEUfdLeUlG!67`pgUqd|RdEu{7B?2IQ?ms+2oXm@T#p#_0H}&;j%|!f8#Ge_?+3!;a-@Ooyda%V~l8(+x3c8-XzhvPo(toDS=F8LJ|HZkKFpfj=G5lTs!xNDwRH~Hdj(tqSLyh*z`-9N`K>DgEsxv^^amh@@xMzHovzdD&1MX_74QgYMN0B~g6T29=8FwJw<`wcN^53s|v%tRaO&_C=asRg(WgR^$C?NjJu!VS@leqAPXbP^W`|sWK3gr;wrKokM*y(-OSy4j+Z9c52YA5nZT2K6Sqzwaab5_%XJQBA^xw|mWjdtcTVxI^DJ=Yne`Y`jE`%4uC}G;@S(=z{nD7*D2G_{t7m-dDX_2@Y7!$7=MCejEY-P63G*%c4MAMTWYsdy7D_nhQT+zWXSKGgPPH`+FK@2PsK6^LH;pjE5VVgO7uO=V!N$hUDVIubPh`PWlLKc|`+hqvJ6O`O*!&{YPw7aJcpUfrga1-M`q5soMEw4?Y0I^pX)u;u66ZM(aY4HI)}fre^SNK=zRJ5OHCZyk);@V2k59N?2#NxlF`AskF{J#fy$0Zf~3YeOW0Dmni)YV2gNt)}CtyuAE)3d%de=s0d%;en5tW+`tRl&WZTz#^}9P+LFt{t-8@4+!iCQJityiDT&`3XW^sVg!`Bg2T{&ekZR!AkAUsYN33%_U5Ls_qsB9?fcgH?tY}{>r{-1L`-llkoR_*^>^dF&%_SP~5zD%)<4Y*$N!$A3vB@p1Y)yv%5bYUIbKq#?e~!EC>3c5gnz?$?OR`L*g6*fSt2m-{y6BjO*A?Q-ZE#KL@s3sbWj5hv~J?v-%oF!vr*x1hgHIRE!8Ul{l7XhfXEg@3dQgy;O}*NAHzc3c!CN5N)~bosnz$Pdr?5Ar{@kpjO5j^{p$#D#ah^GT4%py1gPIittLIjGsGOM}rnhqy2i{}_q)m?m=i$VYr&bu{AJsus@(p2xuWdnf4`g^0hLG0@;hBLh;cE%Npwk&msKwqrs|IxFmVx_txU!a0L!{N6rzH*roPd2emG=S$`&Uj2$VYajWwY%c|ARvquJx}zQ>b79>cQ82|-F!7)}o^K@1lp{{VkFlQucUp_oDR4iNSJJ|Hf|)~6FA#gA^Ck^v_qSL&+(x}X`mNiEGoYPerd>ZA^(KiUPus>oa;w?GIm#7~8*T;zD8{*l9Z+Wk>JBwesk^S`{5VD!W6GnST|bee&azhbuU6zM}!KPxC%3^J*(b*ETq^qM*Xx~k|+oEOL*nU0~DA(Y3tDvnPasuuI$m>R}{PtkM!(WjrgK*mse+Vc3;uiK=Z0EB6TZokB7h6O+$BS=l4pHJj2EZ8ts0ZK6+tNSy2~(@)?`k=%}@b5%!a5)j=LUE{y)UEt7#ZKf&UmC(sWQI%}x58^;^hM{Hm6i$$Kfniu8&@e>P!7I^k+JcfMxgTxOAiQq$mYRuE_p~$aD{Aqe91vBp^PI_5z%KHQ7Cu7S0zCS3|sfk+{G3ej0Y(J6`_z7RraC?P3$_Xh@Z8dpUhP;^nTfXSZ);fXod}jzFGZ#4YrwWnlEJTJzCY@cklr0@s6CAbH|hKagj7Y@0EDyDlHL5AVM6y$N~d;I9gc4QlzIIlf?~>?!PbNAjpYaqsWi{J>3z{-Pc)SQ#)!f_uIWq#>sOagyisQiFR>CAYWxitx|5!_JK-cAxXGvuXZPh#McUyg00lhKuG?-c7oAweNHPY*@KB+m`|TuByF}qWu6lyLF%>3#Ofo^}9s!4}&L}M!ZO2p?dBnr|4|lKeFW^v(LKoLD-il8}|>%11vWYfIwFEkHi&`zDBuPkFC5ZVI7~$MAYN`Ee{S!$)ezL^;fekB6E#Rt!C`mJer0>@!MPKGDZAL(x()2IXg&=`(Ty*h$lVS5?ue62HEr}XQTBHKcF}_?C}8xOp=S3DY?i8EVp&*S*o+(*{?hOvJJ|O^bgVJ?41i9AI1tYP(C+G-p*3u?B5T@n#taS5GQ`Rl2`$BdEDQut%3Y%`hoVxx|=CDZOqS9-h@0yS|GpTnScVLx5*1Xi}>HJ7XJ2lF^uEGw{GX>PY{{Q{8Y()R1gjC-M(qIi6Oo_DDum_c8+ftT2&<#pkI#6Z}16c;6%m1C6Tcx=k@KG9dQ#`2z|Efs;@cX+7T;e$2PEFyh+Qt>8pr5|L{hh%i{~@aV+16{OZqs+20?E1Q0!@dE)YWC^s^%O^)NwWS&C*t0ME7uMe-B%h?O#&%T?(UPheoY!xvY9MfAjYMw{Dbo8T78Xh!U**g01eUbdSEqVj5%h%H|ha>7g!x7Ky4j$yZj{(x(TFeLWWfigO*XghjV|z1h>1xDD9ohU}EDRhuaXW7!;)`N8mgiLQh4oyn4alS31?t{f(i@c~T+*)qZ7Z!Yy9<8`>81dFpx4VNs@WJF0<5LxlIPpJsbqRp<53V?ZxWT{L^F^wZaPHd-9pq6ena^4c-6@#dzx~$q)rc2oi#c7)pAn0&#K+q0KR97J4P@TMmu$q_XLf%$&!d6NuWK5BJgUom#fkWZ4BQ$QeBN>y;*E0ucxRg!pgtxH_c(`m_jXx1Q<7g7G164=hlt-VU4QaGmJf>tjo-M_6nPh$^C@O>sQ{)*6nj2Ahy3c-!r61@ex@M#qK>5GXyiq83w8wgPoRO3mUzE+5}xy)&U6MG@Z-MMF{3vnn#h;P@8BF7NEy(JD(n{_{AUsa1xHG|?+cJ8OxRPk=|nUG;U^u7l4qiR-1%W_Pu>6)hI`$(q#1*C2c$2MBBzgXot=MENm!pE>27r9wgex}d|FTu9F08c1@kI(bQ~Y#QtC%eay{CIPio0D7+pcZwL$YG<|v@v-@y@iGi@5I!*9n)nV`O7B%1DM1<>$jM}vaqa+FW|$IAFTZr}2+UsIhl5Bbsudhhy`v;OL`q7!Y@Qn{>tj_YdL!_vf=<{&&oVibmuK&B649S4Aw?+IBC|Hbwb-|0(zERUjW^^$(d_I$&K!w1dvs+GzstsyOvaMPv?Isb^Nx$7htVPvZ(5k-Wk0fkVCxr@`F)^Vj9&D2F`1pTmakq=7sBCu@Zv-j&_IWhD1}k7?`}@=YE2(wIq`Oqxs>INR#1GjcV`t!AWV?ei=KNd1T5VwBqqnKAMyHY{j;J#eX80_8^D_rYx}oT;`O{NOn5pPXk0^v=ib>TfSw;}GZwwTJi}AlFCY8MQXpG4Vzca$t9|Pqq_vktO3*;+42p&vE14druXicX>bB?=sMXI4Mjje0p?kbl95W(tPCXqa?$1>)wBFL+y)(?I5^w~iCxlT+)T{=COMclR$V)-|Dg2G5t6m~6lR>BCpWL%e-gj^~&RP9GU&Y}DO?_*MSZyr~;mcv1LE+*J~BcON57b2UDYe-E8Od2SwcPrUgLA70MfHR!V>;u?uz(Vvf8Hied^L@RBZdaY?}i~h^UnO$$1l^6w>u@qOC%3-xlB$@{wN0K4_I}r$qM<;fhnnhMt2$5zTDB}_C#ENVyd5Bm@Q}5ck91j*@Zk)?DvTYbCmf&7h7$2eTZ`2c6?-k(LX+zu9Vh%um#sA-p;1!S&@`J)0u*e*GKZ#Rw92ReOsiseg3K>KToz6@u@QQUTK{Dn`%0F*6$|7jnAvj58FpWVaE8_kT%4{E_{4?rjv$sFUH+7>Op+bT=urs5K4Y~L9&Y1HJBDjy(xxuUZ^P#`~G`HP7$V*)u&OhsE;=^OV^M>g^5WgEm4cji23S@rK?0k`Yv(l0I|K@N!dH*n}@5;#2{NJuVVRw{!zJFe6o6HuevoKsX-L#g1&)(W48IFjz%BGs=ucSfTH1nvu2ye`z9^Sc>M+0ZJ(x+*}$GfP%k#J;${dE;Y@)!p>#VtELn1wBm*DSfIguIUAQP&o*u)NT9(C(FpUnp;~>X*$2GWWhD3h{`i2|M_o1#oE7`ts`Mh%-#>#V2yT&oRgr@k<-GFZFb!VDp#E5$BI0-hR|{t5qr|hoKUe9^{JT4fc~oKX+|6z>IelI@kd6w=HlZJ92U$a|PAdFWoXhb=9CT|SiQcVG8j_W4aq26C^rhC+K1`R~tn#7~t|8nDewt5r|q%Lsd2NAw>?6c~OA2iVEAvsC)C?DcCj$6xsunxEq`Syidv%jj4eCE7S+M0KfCusVWn96ecHzi<|YwQw~4}0vk*3S-(hgj>kA50R-qYK*p(Dnwux4yeTWF9g1HHU8&0I9f;f3k&Q;UB@w>g~pFDVO?5gZF3``#V(Od4KNMFZT=~(@82Bw;&O;0|9Jlw}ly5Zzb7V;Z4qux5B+(>*{b0l9_Z}O@O_fJdZf%hYd_)zdI@6&c0l#j5EG(iBuxee=)XWk#ykfD)D!QeShZ@+ayeXVw~X{GNl8lF6{IJa1YXBuV=X`i)=2IFFzJ5IGIA3@Hp>t>|2!EQ*Qg!<}yP2(fla#%pK?aEdxN4u%X2!PDH7`qJdjEz@~Rislv=bpXwCVP>-k#9=QC>^3ebKr=_57Ushv@X-1`m2<)>pSxYCfyZ@cNZuA+Gs?B^W*3{ybFk1$dj_`%?w+$oXS7Z;0abQTLG2rJ5pqtoeS>jajVly_T4aIN1+_#reH?Cex5FO&xq!we%NX7$`LWnusqw_2|Z3BMJ=*UjFKD41q?3zyT4G3bp*;g7<_ZS`#gJc-y!~o17LH#0sZb;m-z53&%X3+{utM!l?g7LXp3>jy^Nw(J4wjs~EWP373$Br2hlO@nMo*bIt+nWui}&uG78zXEmPlygNBI20ffzoUi>$aUSvnaz1)(WP0DPcH{{jPaYZgyc|;WqTv>K4XSf8)huC!yPAu>fR(NTLp+AbusoMLK74qRdMVLQ!Dn28B$4Nezk34TzmxFyBNne0B#sUz|LEUkrZ@m$>vG|P?Wc^-AH7`KDKLHeTmFCefzsBQz{V~-0R#9g>49?KPIZcwUMdG=6_R~MLb3EkI;LqzmAzvbSZem**$ZF*dj#7-@l@ImbaPKPv!&k@dYfC}CP13HGbNWcQA8b%QlfTNBx5)D0)|?e{2jw8&CgH5ibbjxAs~+T0pk8(@Odb_H#nlH>ZtK5h3A^ThRu>i=NG#`T&1z9ZrMGY2Xk4`)a-x;zVDZvt@+$X&;C@^Hy~K_)8xdxSagMewhH}M*Nc+`~J%-dxdg)ZvJQRHv>LIp4#&J1&eYc?TK!P3*fG*gUf@hxZg-V!}MPQAp1pDWM7fK*0wh&`1SgV4Brp=%;lV(fYa?1I9}beBi|PBSh>5m-`H{I(pdXd`}Ghfc3Hy{8iaOI5Aw#jmRlZ9<@i<4#m2Xro}=8z`*?xlSHd~2VYt3&cg^7@PZm0gBU*z*{B?_0fB%s@mD|r^KLRe@MtKr@HA}8HuPitny*dNdB^I5;3$RBa?zI&-Lz4G61weNFXzMaW@n9SLOGP9N@F2eN>0)v0ltY$&|&E!h2afshr*Ii;dh7VG0FCTtuML7%S|49mf*lks5$V{uk*7WVr)I5pfPrz7`$Z`zA^uI~soK!VERcSC`kIK7@6)fH73L?G8;I0>bOzWAso@Lf5>A_o>&d*)Y_U|KJ$MOledGX}yhHjF+&ufkhaQ6bEz9Nh2Gbz!`4(R-&Iezbf%rz{QTLMu(BP-vmLo5N*H`ncoT?f?!|9sLinE }(>s*5pD7fZ`r$r0gcjb^Ogbp}ELFD=MhfV_+Ru61GI<+V{8*StjBul(l&&82*Je`8VY&>hITNIZ16qW~to8~Ct%9P%!bk2_}+E$ok)(2j8^GUugo3k{do)-JJ?M?OI2ME*{rd-E0L@SLC4tkA41lLGOIeppZVi-nQeC-cTA&l<8l-@D24o$xr^ajs}t!b3z&U()Xa{#v>RS^2R2HIZs7>C+y=ijC(HRoYqCT$tUy}KitQ_yVJ8@oR>hJK=h5Eh3TEUdLMbh@RdO;!va{C5g0#Q2~a-5{%%9~|H06LCN_U*I2$_S^`9ox@1(A08fWh)SjHcEDl#X6$Zd22-CJL<8}%CbT_Vk$!=E(TijJY&d``SSpd84+vdSHUkA%88VhLq7RziuTqWb7+`&?c|&KAk^<tPXki~z_65p~^nq#I)a&2qHyZiUZ`+9S4L=x=mRVD=XD!Ne;kc4}j!`U>Us9*^yiuN{Z{0vMJ`kRz>5OtC&+p+#L2nKM^}_t!58Qk0&j~OAdC>>W+o>M=S*UI6KHnxXZ~Ct1Otl%nhw7T}n_X5Y|B{yY_?9sOSiR8CqH71rnY_1#<5EF5U)LVvp+4LJKlT^}{|4FLnYiDGRX?GTUgb{;BuhlV;ju4I7emH+d(BXt;I-tx_f$a6@4E|oL}_S{J}(Uiya#D0G4+^cueexRIVizK&3PT)gh^TOF~S%?!mDrA^IXwR}y$Vis0v0s`k_Yju|*7a!LM}y_>V>T^Wh!=LQ75mvi!_nb0;x6SQKA$~4{Ba}$f`?v@d_E#h;yVLou;4ywk#SrD;@uyPD_Zuj(Av5;FZ3_sIYv~(=|(9BN(EbI<+I;?LjKj7L5e6E$cpJAi>_H+0=CMEd?|YIGerdV>M+^?${j|B3VoJX$Ch%kitjdopjGj6^=R&PVO`cXK{W*&mksO%Hijwf)CcPHP09KeGAalplyca=*EdHKRdg_^c0h33#42iD?crI7Nfnol}=`MC$U$eAXGuCw0YT<_zdHY>RMujyxet{`$&tih(aGmvcPMAdl(^nz~j@i-r60BZgax%+KBNGhO%JO%}3rKfbtd0R1q3chB8oKAjJTHNXAvo_MGafAnd-S71IL`ddAXda(UqAMXE7yn0BW0ESt#7`!yZKH)>AO~0f%gNC0g5*22g#B+P~{8zsp9-!fp)V-R3T;v1cUpizOD!BKz=FeA2$HeCQY&+zm4g=bb^lpIG)`wXY`)$9vA~kZ(f0PwHZh3}?n{N8Yj+qdmg0wp&iPx#|hbMui73l<6oCr+_OxfOhAo4Ni03j@}yNOF`%f9AXIP;9b+4;BX(@r-Zb{vrBTRapQePIXrLfAYy+;B#`}nucltkT{IIBj(qwcXODKFpw7dTMkkGH~%eo4K3`q+$DCd?>d$3rPB%pH0&NXNjEeK^?sqg{LZK9jBxI)=10`~7v*m}(u`wZdDG|aS_PD6+_bXc66!4U$m}fUO+>jJesgidt@|we33R?#IvVBXZNB}=^zD2IvawIhuSGkBBX=wbcLgIQP9ec^}O=KAGOS@zKe>sK<$&5PFv58?B)$#z~0Op@b`?9F|~&^_WZ;@+FNU)0=}rI6ir?d0%rq%F|(Dsp{_`EYR=1o$5CS@xaVmMv^HkkUU4hHj%j-?$3+9ZR0~~v$pP>JtF+`UGy<}fdEd7aFy|PM7fn3wyj<|Jr%a?{23-W1mDx#xX>9_vnaTJXSZL4I`W^*w#v^QjqKg$-CvRCki3myel&C(Y~^v)fga(shG+`Qr><;>aj6|w859122wu-&^?`{P(3`HZR^C{IW~C`CK)K}Y80^gZhkzw}e#0zFp%hbAZN+!l{=u4ou~YUjdKNOBwVtN0P}`EWaJ*Oqe>$Y;rJG7#w(XFKY`q0UAMoZtWP6&LAO?Bny?Ic6CRP2PLi_G^gyW{(}E&e_EzKK52*&Ip;muyH1LZbR92Es?s6qhVvcI-fI;H*Wuw4ZCsuorU6*xfct&0`4j|J0h+>Wujt$5g!KSH~p8ac#&Ih?yTVw-v;`)@BPFkj!vm?%TjnEY7|8vRMaV^1+{%$?+?d@Z*Qh9!H$?>pR8qE7EVR@EPKla~E`uAbC4aG6s7MLLN1)+{O0$F9!1S7i5~*Af8`TKO!uZ1p}`Uf4c4lp=K~alQaP-%)#-=7#)=^vQfBOG9h%W4ps+MCRSYRC<;REzHxFqR~%6;u?pa{O8{oi}5(#uITDFx(samG(PXLBhCjQeuuf27-5{H%{{ztebmoC>J4K!J?lFoV2KsZ0eQGPM(JzHfAOQg=y%$AL9zPV3O?K@-*@ayAz5R6q(O*=)*u&ECIt^t0Pti!^fh2yRIF#v)g9M{~pLebV``3&K0vqO60zx5MPkL$?!Ms_sPkS{pr6TT1SCfoMsalVYJ_JM0M-23<`f9>3d^N`oI-w68H{)YnJsMF$>`N&&#tzGN?#GZzdiIeUPU5B{&r#*@u&uC#^@s}cYgm6xY2?Hxml>GRy5amhyhh6zhZ$FUBC^sjWZ>FQXSs3dle^coj%1xL*HtD}QUuE>mjcIYSOYGqb>sg+;;eI1=!Bsy5K+=&e?nSwg-@#rK5I<9%NM084U!-%-T{xG%2knJJ7bon#txJPXbkgMKcM&hGe%6u@$L)VjanQ69iC=TuaP0_2=tt#?@W74P^ZO6J$pA-xat`{UoQ3DZQdStpZ0$h)Oy(>;mE!mI-*7`Yb7D@uRm}(Du8k@}Ig{u8>a#$&uNF-}-1laFfW<-zNTKF%vX?2O=J&9Xe~15(~K-+th3T@uQX#!&*vNNL)5`(8>OY+vhz0A(qaEdvlAAc4Z;oCg1ZWcU}qO0%7MkbzS+?>dP%iKD%Yr@_j0=G~mrh`*~J5u!JR0Run1u{*CJPW;Sr?-{UJ$h$pRq|UeP<-=8X&apuHstzeYob+w?4(1E{TIBa2Z)^=a@w?!t0J_un|EA|4&m{51u(v!2W1q!ux{tgx>q5L`@fZq9*R(7j_yzHk{P2~j0Tk$`Z$0ie40&(+sK$F8RouCETjtB_r6N4}-?0Q8?tOn=BB?+11md~6ZW0H-a6G)##7*uC;$%)qD|enJ|K53K{W9d|ZDP#A^@~}MRk*tMWG>>QzVWLrAI>URv@G0-{GYtHk7f#l_TAjkB7I15wH`l?<_YukzBJ->j3jU9PpRMmnbR&0cpcrG*{Yrf6qp`9JvaF>;%AoYbOt`nKRA%l?WC{vt^erNx~blZ2aorZr!F~x*LMDoNR*N6Yx{oor9lp32C?ir4sOZrFeHl{%P^60Xyfq&4NQQlggD^+)E>+?cD+wSc7EMg(_F+SIOQ)q=gNTQ9_6PmeUX>mfBcPlGM$AL-#2u-njzoY8k42{PMbT=6RLiyi1^>6CfgO=?V&(!{;92rJ*fAeyVCm=R?*;EDF0aRG|vCJu|umefu&(JT)EUEi+t(3&LC#h7zT{Z-la@;M85R9f5_|LSO)A0TTNGoh4!r<)g-OSbbWdZ4X50zWKVUXzsSHlX-4Q>H!Rp{6x3+$d}$pZq<+zyOMj&qC;KYMYrP&hN9ca2Ye$oDV*8x5O8e1ovH^^!I+u@r_X~(I=UHIMC$DyULeA+@8eYJq^+6v|ZhP!?7_J5OYO@l!*^`PWitcjB?Hep>Ng)SP{(>4D4mQv(}-Dr<&_f)&y?(+dzK^54BdHdevAqq=+dr?NEhTw6^(ng?fJ=vHSL`asc%Gh=Kc`%@m~Zm$t77vYAn`kkbd2*t10kM-gVkbq>j?n<-~)yBnnbAu8D`fM?PcZ)bOZ?v!@#LA87vzM|^%v_wTLyXpmV`QD-y-aT4cy%GrH}Mtcj+zCxa}P)ph9`4I*(v&WcOZb3Pd{6KF57FgabwV+=pPvWN-@SBC>MsG?6`6E7Xy8O&T`Ft?xIcr?rj&dHKzrkkb8v!KmfA2baC*maT5_>2?9{`sUGdcAdj6P`SFBUJrANxx+iy8BR@Q6`l!lvE(LFEt{qJfse_m`JaLM~S&mQEPjj7Thd7zTdxo?37cE@-`rSIj6S94dngr4CK<3}~o0}2;_hw^ywhRNLPVtc+;v~NOkYS*B6#q$44B|$G2OFJySr}5KccSV6;#*wb&WT#f@yR5;xyME3{SBB`BpAL`07q_^r(a!(e$IGZ!JZ6=zl*q-{O6aMjtp!XGBRzo67ss`jxJ)i)mZ3%rS+%J4aALqy}okl9}6-m;{zP+kf-JBu5D?T6u>X(l<^j`kw;Z0-Iwil=Ydy*rOSu}ypGYPxM9JmJXrDO0TnOe7k&P-8Xx{M?{^E6@LY$b+Nlq0>#u5Z@*Fc!B3g3f4NNeVi;($K=(cr8qm7g5#0@=A65N_`L-qha`4V@Wf3_X2%G;AIYc5;r9KY0pPJN{Z=v@Ns`U-^60ucRFmH2pA7!$wK}koVO=U3;Rj_6@>PE?#iab3tJ*+(0%UWnQG6hTkm<;w{QJ&wUaJM?C+(Qu|GvT?*s&X2Z0STqK;L>{9x|twx46}A+5b4SZ~dz)W`e?gd?0za3K{6n?Ekm6NVAp?Gu8T+H{{_yB>9VS<0-hsTWK7&3;ndWUbY=w7tQIZz{OFAbCKte@ybC%X^>iW%jf(!#7R1<_eEORKhVM(`A>R=aiAnH@N?Q^)fZVPXLVD9uj@Fy?A*FoDSSBMh1)75I&xW%8}K5Z@<#a+f8x?dy>&?%ztFCkYVzf{@;cZh?BgvNJ|Q)G%vPZJOy#`JNPBl+aEXy`SzdG0aXj^XfTssnaX&gpKYSMXVkO~8f@0B`lB`;@r}m6kw3?_RXlWB^Qw6ASstu)8qf0U5ug0({pP)5+xa*U49pVugT04}S8MroE?S+cSeTwJq9dvCDE37NIGY@f+SM6oUhi?-@PWhik{Ey71xOdA^K<@ReW33{22rDfv2B+7gfajX9yc1H$)40bQ@OLT4Lzcc6lr$Fcl)Pt4##21_P+u`7#TfBRnlA=7Xi_kQ3|QZR_~|#l=CXGwP%<%kd+ZA0FQ=|4e{Vs9!z8m`0~-*Z>f{(aRg8gM-{XF}*&xr9^tkS3`GFDk+X<^c{O_wDIbVuc__Ohm^@Fp>he;o**AJ3`@T}tBxW0K}@viTdDKKJc!xVuwu5S)KR8-WG0tTvYTsLe%{Mq%4Gj=DiN=G&OKxK;ps;m$MY|Mv?~`y@nO8*Z7D$@bs%iHL6<4@a0L!iQE?a+&U<>*_50Nwx4G|Gh2q&C;k+%B`I*vL3{FQ2664JF3fs#bM>#;d*p29!KtgUfyU{G`~9|!XyEkV>>Rr@n>_G-#+%NX+Sm}}d#VBI^xnf1{0z&no%#juKmE$j58F9=d|&n56(>ddkdJhE^=pO_11kmQr2{{R%rSZQ++=YZ58%dZ%pcS-U?BfO>x4nn?mk>NkNh>$8<&}Z{wTNTG0kiDve3LFx@M2t&c5|6oSK%L&ll!NYDI1DTTk}MyI}$#b=!iP&3)@hUy@51JXk0>&3(+T&^~;&-vdVp6$+FS+iYdk5g)g-+Foiu1vz)TWz6RxU!o4@t_%K2!QyE3bz>b+zeg`n@_+44!#$qI!@%3fmxO&MI{xc(e&~OGxvB+=_=j{<&U1Q4i(|y$d-~Q_E%9~Ry}Y-N(9HeFKj+G42TUKqhlX(XBL?oieYnv7*2)KxpJj7?ci;8nBS)pG9^~Gm*X~c$Opq5z9N(3pa2a}HgUtVUjRM9Ehvg`yx#$0`4b2I9i{uF3y>FI(hG9*=7xe9~zsj`CZ)?3(l9op0H?^WX3C~XX#sb+6R{(kG;UM?!-FbWvZ0%oaw;cDaRQk5g3uZj9_2=z_1=_*_W*Tlp*>Nc?=jCFHS(7rwfGS)2!9P2EH8TOtqnG<8KkJYUYGoV5?Mk=ni(<$gy-N3@o!t}JuuMszr4lE5@#fMeXi+f&c;pbYn^*4{&n*!g`(uex(M?U%Hp{lRQQ;x^Wo=WKP;Tk?Y)@eP>`$F$Id8qB;_Rc>V^PnlxV;X0L^_CzHLy7n0Zw>2{L4kYFvqk)brOEk&q{C8RfcW4sDnW>Q>p28(SK)!({RgkLE+DS1>FZt@!~@dTzcmwa68CNW#p~UN?IQKL)wcuw_)%c7i9Ob7h`f&Uw<%EgukP|B#(&Q>RcUMF&@k?bUd7Ru76wZJ+bczKsFY90!@+i*C@0e(t4Avvk({I}0`WjEAT*Gh4V5+nrsy+&F(qHaQB*(AD$kon$i}=?oO&*%#dBDAPdP_C%`t*mBbt_KtpnATMRIteB^1Qa5Od3k{%0V3Cv-bVd%S>-jFxy{idcb+)X_CA4jQnCl!|mX}OHGc*i=0f$rYetRV6y7q9I>^?e=3@+6cglG_%3tw;oVCj{j{?JWxMVr!B*djwO1_h`ad>g&!4a$86x{DSoXVxIEk;MmL!9Z-^C%@3{56$7AWrgT2kKG1b5hdqKId!PG*#j3>&otC$JShtxwknx-|pjh=DOq{w_n;K{WAwwZOQTF^n380X{BYzXJU2=(yUdIVA$ET$Ey~J_%pv$6&S@P!9MkX8ucfL2bQNgq>fF7-Gy5&oEGtOs>YsA7?_m|B!7zk7xCKo;DM&gzFkK@DdC{uM4zstMeYa%an$qt-efsbz6Xwq!{(}^s?lU@4O_vZ*@@h85pf6K_K4Snltx)h&#?&Iv2ygAF?@=-50sr%lX^??T;dG6L)bCDN?&l$N$WdQ||ubQO>Bw)NUUPZs+Adl+hfzs$-N}lv~%@2JV+V1qLOj?EVBs|a}gYK;tJCE_Z3AKNsRh$^mNKkoH+KBQL@=OI**k8rW0r^s^p7;HdG8WuSp3chnjD9?#ua`gI0~u4V^u)7o{h4R_4;2>hpd0Kb1^!5ZxwW=z=p4zEpvU4&-^?2J)dvOgZmwecE6EAJWFqk#n@CHOtdqX8Ird;R*QmT;wh)kPe9y7{JZnEp3h1~jOq#$7&djd;JPf*VJQX!vUGy1}#q^WSoa#d=7u_Yg7Db8Q3{Sa}lzu#ik?@9rMvI_C(?Z_Jwtt!@Cm*ENf?eBkxc>SkWrrS6>PWj*bFIPhmf5)hwx?IB99VY(~pbVZ!ZHU8P354ul}JqziNe!?eHUtPLhnG9jvF+jy3Z|ukzr#m+^1%!G1F^I>8h&u>Wx&7?KtSgR1Jl=44qE#5DU!2o!v|dL1+`iG*s=9bk{Ha#A`!VA8mwvvxH=F{?p;AlaJO6J!VZnGB;<{G!EVn{`9XS_t%jw>}d>_&8x97$rlV!Z#z7~^`(N9SFxm>%>!Y8)MOn>M9qw37#san53UdSv-r9u(XC=^LzH5dy;87dk~B{GI4Qxj=GQE3nwOy`_^22`X$At54^ND`UK6iMl~_wl{f`Q1Nmuip2$`|PvM-p})S*0ToGWBF4}B3(@Bz&suGaeW%{LzC(w48G7|KcC@}@B-vHMgm_Z#41Ueeg-f$a-blgB)Nje&sKPfU(u9KgUFs`;qe#nI<)&XyW;feP`+Z%i0LcjpVC5)+BDN4Jwc&k@?^aJSJij=F1Hv^78AEi&&>NIsxn?cIj=b7spFy;x&%Kce~P{%dj6V-s`+yB<~$u-2^WL;iQ9-^I-tC)m)t3ei%ZFWe1mXRNSYO`QDMg2Olk!Tv70{j=bxWSDD4~OQmc`D|Hsm`4B0`?tW`Kb;V~27bPoK4-n&s8z1ng+fdav^v?_ZAm!A(CC+&%^Qjy!ol%Um~FU1Y+xd^csyX*_XvA?iK1cd$Tx*;Doo|KDmEO(8zbiT5eqe+8!&GP$pD_!&C95B)+0f8EMtMhLi7X`>QThq{qlSJR6*cJ5~NU;I3&110`S+mSl+Y{_Y@ZP(DA)c(jb_L>KiT~1plkI)CUk8|>Ysfb{cPNNq^ZoYc=%PAUvO%}hr-%bENGh<{n$|w{cn^`(rjRj<)L@uIp(&zOX+vx*l_Cj>PQnFovE!z)9`TSz^|sPjn`KoFZZzhmbfVkng#Av{qDoxW!`d`2RjciU_e`Yb>ErraZV4P`K?icfXwK=OC{5h&w073Z2dg(aUKiB95`q?h82-$Rn{N1OzpWf=@hWwS!eShZ|7Q~X%JijRNGpWxLMK-b_h+J?BXsAD%9u9dM&f!4epN|#QSCM}?U#hfAJPXo8ro5^U#_KFuY;M+0>W!&+is#QxLfuGCBLYU`zMhJ=-O1wzlgwFP;Hp9Z)dzT96!HbV52gQ*`}&i&Q?`|DLatq`tfVxV$?X%dK^b}5`Ag4*uQTC8k!bMIQPh)rMn$j9UBiOXYu%zZeje2a7j{1#iYmlK1$D9rY?sXhTVc`=8TZy@*C_C9cWHUSM)@8qM{$Ya9vawow5&PiL5dmoYc@uQIm@xojGh3cUWeC)Si{hD|dc&yv*M7%&AGN@z-?rgZzw6MkO2Kwt1qp$+iFUH^`5Y8|;pSELc7J%Ik%PAbWohhgr;y0`}_+$`5K}NsxuC=;1<*^w7HDBXqBO{?_DQ0P<3`AKB4}J4M@4@6PgL%G_^$ZPvG^RR5=&s3esSQkkC=TI^@(jDKn7$@hZt7d>Jl-|+Ee8r}`u7MiCHDkZqXu8t?OQ#vFCGB}{JqUEBwr{=dB;#-Z&@Xb_G%`)w)e8L3$|y?cwu`G2F0RzVyJv$*BzN-?^h@C?#T-Ug-P9&d~B_lJx~4ZFr_fTqi1Na=h@#-x9NC4OKxwrOawYSE*AK6q#8M?8aHW?cA(}J$z0TFHj-D*d=w$T>BbY0xGKE=6(7=-N2&9UFPaCpFGk(<)w$Vb(k3P>n0)(FTNV1jDF48=nJfs+ewV5A75#P70=5kN8lVBCyIoiZ#(Az|!aShU;q$Q$JC$72OH`fZr6G*5zgPUXjyDAP;5-gg8y(V(ez<;o{MPf164Co;uxq{dPNPehS4ib6iOJK);+=M&pKZ1Ex4gk`bog~gT4eqo)S28mLa!KOI$;OuC4-F8%ev0we6@0B2T_80iHfJX(@Tuy_u1k(=H?v@_*rliI+7juN-Sw~SrKd0Eho_GhAOsJGam#HWHfs?bV#m&i9ZC{$eIEaXS-_4uBULk+oKC^lFgaTEP%^BQ&keLqcuvhw6W_juGlb+wPGpOWus*L%Nfv#+B549;xIiCoNpml>I!XOE-)q~eaGr3v8H0}IA@IezlRaJ@}{;0Jjt@krD^IaM_gEe1?zd9?7WRyEq6s-L4jz=S8NHEEiwkyH6a?oY<*W4KBoS6uDoWRSv!M8BNQyS~WhTP2iTUy})+zh^dR|3-cC%}gNu&9_X*I5K>5{wn0vODeukNuz=L`|Z10j-vj|c=OIiAe;`%qc(dOzCiscZ}Z@*Y#`%*aZ|`2tUi$Q%7}oN-UV?zA?Qz|X?#0*xs`y;QO^oiXdqwvsE)Ip)F)JboQyfhYll87XzU;B_rZS%`A;_kD|IV2*s{xijqbzGWl4Mt^Szw`>XX&v`!}Os%eXbhpm=>IP2GQ;}`^5vfYO49S_V||E{k*jL@g&ink0Qobpzr-PLD6^J7eS(0$Ql}?wyocN*g-`XzN>YEi8CJh&LtcF&ub2=dpYwS6<|q5{KEtk_6noXjf~t?Ad!`$sP8(tPRnh;Z!$mEn6URzWcOCy0{=58Y28j00aeMRvIpzPVG|7ae*PIU9zC^zNtK;t0DKu{XKC^eoThyLU^BknX1Rq;Q^G}{Ui%0=$m4BqJ`&(nNRUOZTsrkfiCIP!AZkjcdCl4r(B_^2his0ru{8q>F<&+LvU3NSZZ2FkFO){v{s*?3zy+1*I-^M1felOHxddsHEj@YKd<)lUTe4UUNelBH{e@ll8N;S>PFCnM=sLmHMK;_%A0pSYdVx5J#Q5!RX>g%;e0d-yHpL!Qd6&j2P#fT4|MSgPfqm!2u>5wr$;?a*;sQ0`US?%E%GvLuOx9kIT$Ty9&j=EbCK=V9XboVprx>M`DdRNRG>!&b-Cy%Cg>W$y(d@P9mnBXtQQ@2NHP~`RkMj9M*5}rVxfqIYLC-9uEl@5cdy$}0Ckb6d(8acj62hGAW@1sVLfAP@e`xcS`TmLD=24xIz2rpXuW1kpEHD_}Lxgho}Zq^mK0B36+`nxt;O{&m45m0EZRMdb%mdC+Gf{8NVTuTZiY^Ce&k{6C!dy7?F0k89G0lCts$nP9;4skks>gO)LtPQRi$Y1-*R}1759hX!z`ndWQ0YcoY(l-1%Ixd>ZPOghJUlsCH-4@rn`ZP$1)t%_+h4<;$pI-jaOSa%2Pf_5+L1MGrW?g?#+paYK~tW4W1SL{Bfk-eVo^+dFr&p(&54(A6W^1T=%(sQ=A!N{;L`Pt@}*|bw+yc6_p5B$UJa#b&}KgcuFtDBoo~HadWFZKLw~HU@i<|4od9}D}$&vf5=yzH^dpIxo869pcPv)%rg8GVE-|`-V+wZ=*4)xV7)m!YO%>&)0g4kNCyuKv)gM18S!;8SZHDZAGL-~mgOw0s5*V~%GH9UD1eRJO$WMo2L;E&W^Yvfe^jDkB2!kGDCk>#jcs652=Yw6tjOOX!9tLhV@0<;)FZu5*}gppJA5@#zDz>QC-#BAf@2RYFYv9v`=sitn9pZ({do0nP#->d_~ghRy9`)h;t^7;v#i+*`HZKR!*WAuuzZHOTbm2=s-&v^gC2CS*An)-?t}cuxxP}r!wkq!5PTGW9{IC#3+=Ah60l}N%Ib(}6u?R-s?(&KGxQMn*aunz(Fv<}c(9v!C>c8fHL6Z)LN%80sP_zO<+}1F{NlONY-#-r1}@dtY`YY_Iw2q__<^)ldBG6&j3IuH6424!Mxy(!lQtbU39t@Y{NXC%;3uS#Meq1HKynIlJvFPdwhaobK2bwN=K10bukWO$&?2~tg*GnB=Ikh}e#Ba2a2^cf82{xD91H&2USCkWzosJeTJC21hjd-LkgFywZzdbL8k(?Lw^yU>lPsIS&Imz*gU&4B8~F0;a)A)ihKwpV08z}amlq7(3bB(L=;{vw};)Ga2OQC4_A)VlkjfCf~b?F+w=bK}1!FhFdNR=j!z>YUDr{n5R;1h=2>t1qY@_9m|ty)c9PzB1Xa2aHe;9FW?wDd18nR}Zl4@cP{~nzPhI)8LljkFB@a$f;ARnnkl?w*-b8u0#=W@vO3FJ*vsKxD`9HK<#PkG?BuaVB8@%azj_hfudDA3d2M)pQ>yy?;U*KiA`RD0`Y&Dx9_XKB<+CT)%xocv3+scV9`@#rwHn7iGE7G7YGHkJ*jLgKi`%wfCgKUAH5Vy|?i`g&dwI{iCIWvA~z6zDU$vgRE}Oq4OC)^;62dgZH0T^5I@kd?t4v5%rHJ-=QbBJ)gA0HnpvzFM0aD%`Dxe7-hSkZuJwCoG>3AkQW;MVyy0Qh28l0H23gSp-yrhmi%7+;m_9p@g@VRF2K7pO!$~9c)b0f)i~$Y(a>hW-zl<7Zam#Q&ei6cnpO?5U~y#Ei6sJC#(8o`c$C&_Hk8k774S^N^Te8#g&FOvOgOm7(r#}V#(hPfnChCoj|MkSt?BmeM_qJb(y6tFHR)g&p5|&Jf&M7!96WY90}6+)Z;r4={lo6?%hC`gfa-&kl8U<2R(XEv#CQS@Qia}@yN!?ceSWgCMUx3rlujDU>Y`rN)!%+Y>kAWN+kWfIji8^9>dz98%7UxU$&F1E`n9NkhaP7GH}7!$f9Hu61`3q|XE#sDgz72Ve)V5Nog-7VX-M;FCQxxJTboeNID9&DqVyyU_F7cT7t%mpymQu8{yp@uJl2!wFS>hj_qJ{J3`jC7o0Hmwem~0ZWT8WF>tLTbgF3cz_EI6EcLccBE$CcnkK=cq?=m||{_a#?+G9aDKJT^Ru}_vPn67tf=l+>^4$J3soL^=co7?wuwJqM~YClO4%Y7LT`a|36V`pEd_1{v*$D~+SWv7@!Om(9fS=}Qkqd!;g9WCvf54My`_yDP=wfFTKJ0r0NanzhQx5OWr@pJE-gOH3TN?${p*+pzs&Z4QJHfN!Hkr0a{m2fBw>hoXTT4C7B6Syv*NfXG^3gyhTp=sZJEqpli_HrSKDS6=7Q#uAsvl>p&M7QJy^6LW>~Ji3Iq64|vSkf&AeXXId6PfYZaf@1k3fPtZ$V_wq0kx@&KK|Ckd#&Z#`K2fJ9Xk|Xh4)gf6>WuHxIf?1q_>DQckk2gFDy=ZffSd*FwXVU)AAT_pJ|K|^?blaGoMj;A<~es}g30DTGyR5;XUl?(H(tz3*T8|<(H1-`<4M_*ePGZ~e`r6+%dR^4YfJHBqdaa%#r}~#%63m2~A-P>wEb()x{(lF4Wpe8#`3j)!ns`Us$9F0n+;ZYy5d+8_2d3Xi+rfY-4x2yq@#H~t?^!m@aOf%w`H^k(&3C&oT1M@YTRgC31mRtIt@8r$T6mS)9ohyq~pVA~Ve|r^2jNVn=85_z9_aa)w44ESpti63@Z=w2eD%tK5+W3!K|L-})j0_E@)Vk>ZI@o2DS@dW?K8ex)s10a-k8bPmgh8{O!TB3Pwy6<2;dXx89c-bfC_`YJ_(Dk2e|Egl!jZ9i+pGlTPt#8g0hMQ~7LFBmeVn?Ede(ufiap>4ucbX#y6{jH?z&wH&_=RX0^ZkqH_c-Bs%|%*Od!8?y)a5oMXX*HEZ|go-i37PtBiIj%=ujO1iP{lll1gj3A}{p6(3rsuryZbVj|@A9HzNcXB4YZOYE>xq^P7!JYT!$GFqr;Jy+IgL2eMzq>*^w;PeV%c=W^hcfD=5nboD{&!KjwbFb1`Y99hCeddy!J=E-`Z^!R=ik1&xbAr)6aL&aJpPt}pKDPWv$H&x1%nB5rcD#T`=|0cZr@A?YmVuDZH>J71Pr&epB9utaJa?Z46!J5e@hCBJu4@T`f?sum_x@pg8e{s}5b4Ki!bVvQK57syIcZvIViz(=5fNK7SEpnyEwFQb?oP{zWGi{0JND=a4vG$&xE|PEEyhUpmIlHs*tVcf$Vm2&G`85YWSG<)G%~W7;^H%!3kq;i%G3nAHfc<^0Sj;eTfmTIpM}8)}aCm(7+#A$g9i77oXH2%e>{g`#)jwp1HS#x`)Ne?ar2&=C4erRlAFbZi=ARBSIh7OgBapj4AH4Kzc?N7K*js&wCtpBvk&pbw$(fMQ?x-3!5%m?7FX}2n14m;y)*cV!i<)k={a8YWym`MqiSnVo5{cxTcRS7iU$5W-f%nMe?Jh)53@1R!&-9&*0P3Q{1_z%kaALyy9VNqj8K{4TUaKyi9G(jH=C#smo}x}$)}SmnQ7nzC&*OQnGeKKn-Ld;=V7)zLqk=ths_&z>eLA@3o9S!6L{8=POi(4~fwOa+)U5Dxsr<%D=}a&aT@o6}lfU2_@nDt10vgEk8S{B|BOg36RHSr(4xf*PoT!Yqgy_!*1d5O5|^aAD9#o_?}=eL^Q*-G|@gwsnFj>bINk_>PJjrvlaI;nFkYLvz$t&8SI*B|n!48(QJ#MqZt2DsUtXgylq5{2E0rB(f!c-^z5zEIOW{RfYFM)z=P_&H$=ktLX>ST~r;Fr_;&(hyrJhqY~dv6UD%HV?IX*o8rA?k`84C%>HZ^oQUXFSoXMRJx-IV(v^0~55sslgQd57SQvatJLzDZ{9&+BL(4Z#|pJAA1?VW9(fKObIaSJAJe0+lzWsE+qT_36l7p9UQ}TKyxRBd6*%NQtL|gZs(gcz?W4edS|6Y=5PL3j4^J1D1H7L4EB^d2*l5a5OYhbwu4VZS9RS89QkZVH7wem&H@h`CdCarH#&={{#1;U#Mu{q)N8^Jvb>fBJi{v?`O`v<9TI+TOMsc?X8`xaUcE;Bx)s=A>Z5Y;~AZGA6mC_CNy~R^y4EZ+Ej~FuxqK6tXz!unHN}nbqZe^#J&zOF_?_^>0e#x^Y~pFTp3kK(^Eu!Mb$eHuS^GnRiab2`QZI?_f3B@z%N{Tl?P9~j_T|^)0Q~X!2PL0`*Io7S0(O`ZV{mbNLCzQ<+Kw0T~rDi&;&6LMTyjrN~cc)-zqCmX`gcYgZmgU=y#ZggvaJ?2j<#C#>b$w_AB*ErBtz!sPljq~TDMC)jSFak=C2^mZ@ML%A6%oVLP@_iTjk>RW8z*DF0uUlD;Dif4k2M^!i$qx-^EOcFdmdTC(`8f~m{O9>%)89i(u8u7&{QrGqCit>IKyF=}*(&@USKMwqXZDu`&BgpN(~scuK*ckyy21u3tjr}4^K|wp#Fu%m<$%e3`mq`Zp7)OG=k;f-FSdai)?Yf6r4exYH~}i1-u~~7VBB5u-WyLU$?r?`?R25xd9nJ#EzX8Zn2@?PlBHUJ_F2{A{&4wa@^_>q8?4Ae`%rbqPKmI98410illkG)}oe!RYapaAf8yz@GTHonyEOTI8&r)aYC2**i0H>h*MD4Pf^CQW6n7rGvBE!{o;iaB{d`?1PKVHLR6O2-yDV;>+|_Hbf1KmPMr~UYHf*?a&q1#WpC9U+0jORpFbR2LU-*r`rC`!o1*(t#*yi3J7ptZn6I3d(3A^fyCnL^O>-1f7F3H7m-uvMw#UI?U`Y+dDAN7Nv8zP1UTHy4%+SSJ{=cFHVanuzPr#zN4rt~4s~LW%^MNe-;nB?^H7Zg8dZY~ITf@U^}Hs|${Nc@JB;?dW(eVO4N87)5Keu;9Erp1uI`vO*t$t#|^g6rtjva?ult-3;R_etc8ppF=u2P~k@0mL+sSE%+WZ}DXVOYLAvQZd>s=f*~#SDQExELRqD-h{`VVRqV1o3bF!VVU_vE3_xKK7fBV*FVtu9PLKESC35zP}C>BoJq!dhM%vxSbk3?pg19BZR;iEovqDYuSJ+JbJDXftHY3&f8O4`G>i$it)mlP?ngebVs~_qI140XUH%$vLVm609`g{v0%=2&hWRSUsl4W$l~7;;|nW=Z^s&xZ3y`(?koVZWF}MLG86uMC)0v7v543|{AjO3}@O#sqAz*!5=aTjUACvbSo|2#7hR5?vyX*P;3)y_REg`>TfdA*cFz<)<(~L99~I`yKMh?oYA|Hn3pXpQdBFM%b6R_V%*J?fh)my?Q3|N)d9;=9XZY4mOB1sQAp;f&H5QXuk-m9Oc0KZgz?Pgp6^%=lMRH4<^|#@9*Ft^(^G+Z)eon{bszT*1G{o@7!RR8CT)jWM4_%EM!A0pr|Q+>m&tGF(l$R8NAb!0-whg1t0ZPXQ%-)U(D6TaT4TR)P4x`N7UcDH1K5*3)zjk+T3!@=;7dKS08@QN;6Pj7tuv3chqHh5pFa*?`-`;>i$d{57o=K%kt##i_6;J&Xbk}f9H%Ye)86)xRqMg5><)S2pPM8Hf%y$?bB$iupReowhcfKPgs`iMB{3hq4fj~J_q-i`Br@5aA*Ydx8uTY5#tI~DDdFV(>Q-p+(BH|Dg%tI$5jI66-Lr0!Z>P#v!ugSvvsw@(ZXxKR*7b>gCS?>U=xN824qB{BuueH8Wtty<@`e61WbQTl&ZetRsLEP=CtE0`&vcZ|f}ieOV9PZ!HhNbufEriHEuX6P_w9+G-n!_Tkop4PuVvq1)p6c%I!ZocV_d!7pd4trNlLipnF%i2Ywb@l&YJm$>~n*SDGtt99u{HHG+`Q1!1Qf3vys^WY2A6%j*ncH7H2+ef760+zlxk?WL$>l#(JV)0c1DEzeme1BeyIo+cVRr?S`egW4%!4&(H>#fIdr=m*zVX93Xt%S)#MzZJ)>wV-N_>7i$&E*)%l~wUG3ruULqJlb4hL*SW}GQFgwGEZxAtcK*gUp>EAC(31qN@~OE7?{Gxy3K*QpzuBSLpAB|u5K=Rnt7t1OAMEQFo#(e8@eCVcjy`&1t$}vqo;MuiaN`pe(ovU6&GD3z3d{m3&qMJ&K0j34#rr4*>@Sjd^5s(UIA64K%SJaj@_SAGnQP~b{NV+kmuo`^;HwK2o@I>u%gR%6`Mu=+v7pPPU>fp>G&u!fr?+SU52_PW9`-Yv;rpFO_3{A^F{8m?d0{IFc$pLNl+TeLoRk@TU`q|Ur}*xa+6WFaP?IXhg&aN#|8Bj*AMd~i`(DobT0B6>U&nC+^56eJ0I>l5qNznKmGDX25i~?qVz&Pa>@^RM}PnkFUfVnfS>z!qt&%}e&l==GIYWH3UZr}lY5^2B)EUC7(w2&U-QeFXeJycUmVYasG~Bjni>2wVS$m5@}7`Bvgr0;;XFq5tDaiQfaNX~~oMIwWTW>a#I^^bidWBmP>Z`KS(o%78_E=nTG}bdz?9iXk&L(wN_Ct-wxu~zGvc2_77~DF0Umu}Pc-m1MCU&W~dXMRwxDyc&?VvSpW^E_h$DqhKYP}*0zGh8*w8I_kGrK9=qwEz6mL!y01Z3fJLiu^@$#t2kncsVbWoO}j(X2%eS&~fXnci^Zu?*UciVGA^U~=Q!F8xFMe7iGr{*4X`3a85$Yw`H~sBP@_A1t8e?~CfFuc$hr_D|VxQTu}3hzr_h{rPpVt7sh9RsG#I%pC1gR<<&^vzZQ5Jd3+NPaiI-?{dW0x%_59-BJIQpiBf#;jt-n2QO~2p^HX}^%L9|g`F@{5^)@F4^d0v}o4OVGm6tDCC8rW#Ce-Xwg^LA!gj7;uo>xLxPbOS61E*5nQ{fa?EdnTWh!N4$0D00E;*;^(d6>HkaBhdlp-oZkv|U6MG0oT_7)dzJ|k(jWNr??f)TZ=T1@^(<(Zr(QF6CGx7Ni&Ku1-&Z&KXSEd{a;`sDi38iI7dY=f`!^XpY;I0fu*-swX9w%lcHr-FziZ%xl^q?vGY68y{-B>~^JihJS)+8w`ZuxWxftrA4|g_#vm}tHUxJuHTh@6gj1{yUFiMmAmuj8Lt?tSaf*9mVa>p_w%nua%0N>Z4syLxWCVGguLc*9qM--0$g62isi^)0;|>3nsR<#4Tok+d_MbgjuMUO#6#CkY^`hkjju*xF9^uu|5L7skFaz_Vu9#LY#k8O*kM>nIsqWTCllk+zBoah$nD^0yY_Ot~oII)kmugVSemG{+s(WmoCJM>%26)B?sYUz>teA=#T(1)R~9=mzs7PQtG_;KjKnRK#7dONOzVn!;5)|oJ1`q#I=4u#@6xcXnf`zzlWpnN@}b^kfE&-&MoLiDy0;F?&pAjF5qK2Ez>o{tHL-Y9oCS{Lm@^}SuVggN&2*8kSW3WMDpZRQRSnLz$;z0o>6eR8*$Xv%J3!GoZnH@$9ne(GhcvvgpH1vv?a3Wv6!zOvZxBzrrH4OgOmS#))w9jN+rCvMRp@TSDD%wb&Ds5(}AS2E!5Z8fW3`8@uXxlZ51TNuE+FF(4d8|_2o?e4WEps(BEMEOs&kI0t%+gjv4Q8VVP$DB{76XJ|YyHbD&fzz#m*Cn8RmdiZQ`(D8Wy~K$>2bIu&weorLJi$XO$Z!1H>*#~}f%2DGtFeI=k?<|$IO;2hzjeyS6FBhm-L|j}UDQ`m_vh>vK0yb^scweKS-9?pG_;o&%w<4mulVc_^2puxKAOU=V8Cse?>iS9L_LthX6OZx`(mnI@6Y>aH#NOw)1}GpOVtzj^Z@Pl_MBmrA~|0@eJw8Qau@AJ)m4sdWJqzD_T6Tht!j0#R@s|@cCJK>^Mz`I&bnxGpnD9_St<&t3zWq9jMn-dJ?Yh@!Nl_eDseF@s8KeYn9?Ue)rVtMK9P4?)g`AB=WC0-<;*w6Tq!sVt`z=apEnxJOX}wG7Grz8tvwHqyA(f`F)pfeYthfPqbUxwwv$DyO{9zgvsf=0kqpfPUc8kCJPLyjp8%3TjZ7der4y_P&P^J;;D_Ouc-Kk4bdEMrX^K>Ka20(rBBJ1zG~CKOxWh###PDV{O`w#%UZQ`NU=M(-%|#;#}#e4dlwn7=>8g&`#;b=RDQaJCb=G|*ckco=%|4Et1UC>1ni#IsLMEwe8S2onWNOG$N&&TGEw1vIoaPu@}(@|fk=c-Ds7ojhyP^azu>@6NmIdrtqy2w<8GL=8oR?}2=2pBohvVNQYN!AE%z<1druieD^W5`S-?u$1r$P9+P|=(m)K}E`$1V>#MC9kjEiFRMT?dsIP_!&BHm?@>S-E)!TZb7?x=YdTT|4sOLHgRVC^>S#CFzOiznTPj{uQ9=9Y5M{hTjX(dS&u(^vEXCQcGUnn@{O72jAkEVgIc=b1}RC@GhOwj8wQvha9JgC*YXf@s^9T1Ga6)1iyjPFgV%W``!+SAi3UQ!TML3ikZWBp+OwP7Uzm){-My6OTrzjpq+d4n43H@5pY=@MqK(LJD1XA5Sn-}_@zG^Z^pZstZRX3G!T?!cQN9>w^Hu~&TEdr*$X5x=DN;g^u_``?lpbmaHvF;*s>pkf&)ZSUuN)`fK;)5U_lGy2-F|2Ntg`(~w$p(T&LQfpoIJ^eVEVW_bo~amTAmDef1QkC`4^$1J%bbhbPYM`brDYT`nBp4-!)@-ir3rF>}1xe~AWEy~7W7sB@_JvlC0{khZZ(nRts`3BED5k#5^Oy|8+lyf){%im0;qaI?#jrcK25WkeU=FaQzquEkwD(=q_42gh6QSA9}a4EqWwer0)I@|#D->KMGybu|9F#u)q2@b6<-c~DA_oA|1gf1UYrsWVod|J7_ssRmr?&DT#~uw-9dw@=^jej_mPhfjj89a(LpHg!G(!=$WI-0X=J%DU?01~Z(9}5_}0-5sl^1h&(!5EH)`M%zxG#(vA&3jMP#`H##GxFFjDR)j^p9)Uu#up@Ta0)0!H}1W|ujk|0?^T#+tBfCY%gCCZZyUI*N)@UwM}WRtv;-Sr#Ct;`3aJ+2HW&+3@8A)K{|9f%6piD&Hym`EkKCg8eI+0i1twtxUmMs(j7P1F_EtQ#i}>M`NV=QTotcTr!poD@khEMP)+Ppvbp0d>VSjB#(VEsvAAB9j}DUSGcNHz#C6bKTI|^Qi{!j?;Mn}d12~^kb=&HfF(Br6v`g4@Z-&JZx>WxXKGc9z{KGbo2dIJ;Yp6cA9a{>J}X}_K*eGg{=Q-h)Oou|GWb)HzD#|A3iLAW3Laa6*R>x$&QV1?xFm^Wp(t|gi7HQnz+hX?wZD@#<6Q}fZ^=?vIpY1hnjL;au|ANVf!4aplPEDwo7yY1NdWx2=}0+RhNrV{q{lRtWKHvAl`kUy`7oRbA#2W>x+~NA>uL+MTdS>KXsQ4U0>l5-+K-}rHdu+N7?iN!i|5^1K_0&-)lXKB&IZcAJCCOi8okP7fS=W8~Ss}?+eZ`tv_%b-#(>eq~aAFo;4+`j(vdqK;ng>%jX%O**0tBY!Gr$x19K-mE?ZG#hR|L1UZ#wUXn|I2g_)UKTq5{x$J1|w;}b0a(hBrDca2={MT`Y=r`^RoAGO(cmRgduG#^iBMJ;zf!X|QjeM^K+Sa>~9Bo{3oO_M?kVgJZphM>#y_dQ^Se&31I4>KeGBsx>@e$xwCH3^3EAk?RMn1oAw%RTgHT@TWywpCOrD>>ZyQy^8NjAu4;;d8gi9_d1)QNkqE&PxPQ3cm_edVD3@ju4VDR8GjyK~ylTd#QH-bsBhQ;H6GLf`UBn~>-Boaoo6ro+h-k0ZDIMy?w1Nb=hQ2FU)La(=Q5>K2DtTV;!#30Naqo6@6=e3o5NFI$+&jng}^9XVBRsJD#Cjc->7LA^x9lkI)N0;;Zq;(g?lKXm8|8y3%ave2Uhud^~rMl9-5Ccup3^~GJtS5^ObK01d67w;X>Ts9l^&jHD!NfVyY;AeepSkxxuS}OKuqJrsAX8WpWGLQf2PNVfI7Y7Cmd|YR1Rf1e<<^9-6D+mbo?DPb`o4i8Q9%I@+ScU)^b8>ZKxljYfqS7JIn;(;wzhdW}?30&?|jQ$$7iyZqIFdS&TcHRb(=_nZx4xRf3PA|0+bY@XY=M8l1kgBBYeZ4->cBN5_d=j|Q(tw#S;FPAE;VYZ}R+!H#WlN8t(`hI|v{w!PrdQAZQg(~bUDXQLJE(=t8c)>a_`sw;i8rnaMfsQOUW$H@J{tu?*zc4j&VyN>}&%^+)^cpWqd?^(GTq%!8wXzoO2ZaEO1>yv;0#>;193aXLOfjP+V7z4C166TCW1AHwJ4#ZIfNmxeS5aXUItXpQTByyAsJK5u9sVbwEjT?MZDLDg5MtoNh?6^DL*CGvG$o066*koxL(yMgR!v>R3La$+BYTW8xkm&a}o-EWEc5^!umWvp!p`e9TX;)^FuV8Wt{2Ty*bquqQaP3suG%LGP8=8T}7Xt%bE7N=$VS#Va@Pcrfq+J{=7rkk_DT_fnKb}PoW$2yWv_*5EXW_q42;_2sp{ZQdh*$o;{buUV8BG;==S-E629jNauy$|_m-(-hFeRQy+9E=N*bMzfYPv;!lcQ_srbl1^8I~w(Y-EF7ws8#Ok{c{`F;62b%KR;(4Jm5Lvo7)S@2XjZejKxeBPYauN&*av<92w;CM=^(*tM<@9?ND^>`bOkZ7wiZB{G&lmh|AsmJbLL$nrY9R2Xr`X8>=Uoh@5;a?9X3hfXiLeg$n|B&RehivHV~}z}u~stupJ7e`+Y1da8*4pSI^F_j%4|T^kH$Bwu9$_2)bu9s6fiW9Cxw`#Lli^CxXX9w%{NQRhiEyxYOQV>%t}NyRt*y_yN~U(QBtT!6ZT@>}klOM@S}vVFDlk-LxB+QjD4ps0_2WCBm#pSuTRlDsb+I(4^N&z^_89ON-l05QN;;oESWpaN0H2s;(4CGXuy46nzxZW0VEJqaiCv9uR(?^*QvT?%bwcp9({A@-^zVTibh-|igeYy#Gd-evkpyOFiyCw2}y~_ms*w{Jc{>WbzsX7mN(%{K4*50}c$oG5i*s)uI4)+r5H%4ai_`x;dGQ(s|QVV+hcwRG4&zC*Sb>)mo|AO-$IImM1S|jXWemV#Z`G7MP#@GCUB4`l@G|@7)>O*xWk6fkim}>-x=F2|}50C_qzZ(PiYH*UfoGZn>do@`xLfHj6oEa5S3kXF{<)`gB!GN09f7^!MA^#k*`27|e0^V2%8k_2(o(W~U*QJy0ocfHM_CZVW?t={2^6c}ZYsL7vxz{Q$<}b^H6Dyo5oh5nno`0v-%SV~;dQj2p;clMu%EfuF&pXgSS>*ZjDNm5s?ag_!ozz_-cbA>)T7sXO|Gu^Gh2U6!(jGc;$+y-mEs_NMNj?47!UX+SO&=m-Bk~A<$FsB;|BxGfZ|~@fVS;Dci9G!esISCJRwNW(XF*%xz)6P&)K}a(>?>(wdFA5hzvB2VQ+Hz10ETk|r!B+vF~mL3-`apamj9)W=R2Kp{4C>-bZ$NK6|+%aar4T^eKA$XwC@A1k2i+j$z5JV>X4dq;?3Tuueg6)AB+E2FUNILi?w*^B{_2aJ>?%1F^ch5YZt3K@1Zf_*WKX8fp-{p^!T&BZz8!ao7YM^keo+&KIr>o{g%+zOdz-2fphXuUs3g^=7q7idDFok@tkz4b?l*_woIV<+f0hT4iAKh0rS4QR%urQV(Ff|XKpM%q1fD`$BcLX^u%HD(avB>F~BD0bSRQ((NYP1g(_MG&U2~_;=x!>r=J76UEaD>6)<~85psh=z)bX2-3I};@C4$jjx!F6h*{ptVX>deEbYNP&-N|8hwq-Y|^*esP+ND-n*8PXuhP#GgKr9={nlro)j3}-$^5}`<@LZrb|ibg6?qVc!)dEU3R-`_t^*Ymkt`|PvM-uL?6_r31#($~@FK;5+K@p|_#?@Q_(=sNR&1GR6Mfrh%s7wsNoW*_6i%;RUHqCzol%l7`Poo&big$4WMeeyAGwaUvA90^@*xrrV7hT?0HDevLHy7J#X@=FHBP12(4$+}ennCo?(;beo))y~{y^(#gMz?o*eviv5-hkPD_TZRAigRVn;r5AeYfp$0>=GwUKI(859wbaq$(>6rPCR`xbY24J1e{1t#kCx>@fz379uQxEBgYg=(?0)gU<$KTGIa0{UdQJLSK6uV{^oUu8@nkO8eIR<707fP))bCq@@g(2R@e)E<@YqmU_dCW-?tLN8eOL&$Wd6R-_Qbfofr$lc))VhyWAHfJw;ACKN2Rki_l&ACvVRxK|Z%KDL-cnF5K`vSsuHZqjnT&+H5$+FGb6(>Xr7O8`%fCIrP$_6^I@m2@44g#Yz%sQq8wCF)DUFJVEZ-hxMawxQ0cP&od3&T=+f`=(Lt?16l8{ivPv3gUUNd=_F5Md25-l135ZTk;r%Q0Hvq-^DsFX=)MkNAlk~%6iwHqxByZdC*l#t6DvXyvwq%Pf?jK>gS#?5A{sLFE`oY20nZndYd)fo^n2M^SMiL-2cWai>s)w$h>&5N+|L*%IQHKe0hP9ffox_y^5bu8I9LbEcm(oP7e#h7NjgXRYa-77i!qbxwGL3(@|k@KXMEAN6!vR5%Wi-AL;>ms9U-edbgQXabWy9S@W*r$VuP-)I2U&eSY;j;}P=pgJM%#ZxiqJ)XZmXt5LW7829VtXX3qHBe#qGvKTozKKSkz!1NtoO#Qc@ZkalC{q8YeA&|$2UyMP0(&nvm&u8}HiI*p>#)j#Pv@p=LqEL-1?J+~cs`)M1wU>aMrucuu=*&k%~-HO=G0fYNmMjC2(KPofA0}3>`5W4j0Vp}G1a^D#i5%VdpzX?*5y7x=fR}$0=_%P9Fe$1V*sH1LV)q7nTB>>-$nC>&5kXPIur!*)|=&R{J6Fo<>|8eqMM(ZgykbNn;pQ28XxVft&;0GHdOCIp|j^H?-e0*wTVkqao{~wK<^gRrc=R#n^R5^3X{F>}XZ&ApFmr1IP%V?;t4yHM5eMr2&Wc_&h3e;DxX5IMepw0*KJSaN}>)SJ4)+?oC5xQEhfT42&_0{onj#>UX0*G{ZTIxsf`z4QQRy+{Ex+2dP^SrUX{m-?JO&1*55WU+}AVWDXPYf4XJO~})c<JuhssZEW!8~*gZ~+S@7Tb&j6*qo!qAm=kOuJD$qAS0QFU<)w+-}Qvsa+xubWo7iInG`15m|AptCUSfIN{2iNfi-_$DX_2Q=PV|i@gjbE!j(Ga;K?KPw?=7{`Nio-D9`95;F>e9f0Bk9{++9*0f{?`#T_mf-@rcVF;E*JIH!dJeDjBPwH9QC1IKOEyTU&VU)bYfmiu8SIIV0_5+qNsd6Jjt1PVM-$EE3f+-w*0XpbO_6S%|RYMCz&PZX}e|#VaV8ne>8yNOZ;S-)EY51d|4k<(nVQUA?uC|0@(2OUNmoNEav?K)uyxmh;!i3R=@LolzQyhjXE!~GX8tc!%UHT`ZjFVup{Odb`zq50x@nYmLACYzJv#w(-!`{at7D0$aS=#>3qm8no_aw5XNmlM(GDl$cO!pXFoVG5ud9YxAWIbJtTnKdtH0m4r6?#4U9WH+DHi5&71XC`Qh`Ew>b9Ju38q5eTLO@Fkh3t=nP;(xc#xg(Z`XCFL_b^w2lo2#ByKVFhM>$xqjwxHx3NVKi$(IiCpq3!}+Be7j9iyePCH2#xr){!TqMuJXn~g@bLP5jHf|hg4BX>d|;^xCuR*}-I~EJx6<@nK3HAt_zVLWw>29#C+KU&xa`NbC-I!4{4G-ze)#Cb?Vkk6h-!|@)k`GMH^w&)W$mh`y9}F5VfG%@?kDgHEYh*Z9DvCnT>+cAHM&!jAWe3u3F`@3T%hyNyk&j+|=p|E?1%EbV8*jLPyk+4JTNzStU$qQ38jwxiGJ$o3IUi4Wj8cZ_T%W&&t~5}%!CbME6yII_;;OVAO80BArq_(685yUAz!#m4;)qo9W?1euJU(G#IHTXdu?_6#T`n0`!sE6H?S7Kt%nXdBOh`7>P*D+t#ZWpym_oJ&4A)_W##-vB1)ePuImSFx})K?74$7_Tp0!aDUvmk?m`ijOepKG7Sg389wiJ#gjJ`8h|Rm=&UoNDX0qg@F(*-yNR7@wPt4=Z|>ia-T0R;e%Px&zZN+QTof1K2a_LAbodUIN|!0V#<^lhr=w0Qsf0L>&3igXP$iFXeSF&-woPiZ$Q2yoyB?Pz=lt~cUI1e#eBz6xYT{_6C3Wztvqq=I>x8yNP$&s5}`BI-d0)_V0KSSh|iU@^koMgzKM=ub(|+Md-}kdN<#2S@`^DkD>q0srjG&GIjWzFfvW&$e$9xWVJa7r_ZClYG1NRB61}Q+7(o9{FK8yW#P5G^O8ygPb9`o=(iUej`eGm8(>!^;w#=V9C?xt-pYSI-Bj-xj5^rzrE9>#t_aPZK~n>ve-xEXIed&nW!Mg!A1|=G_d;*EbZ1z<9F2ysz!~;Xve395OCqhMw&$7JB%CYyL;d*4@B!U=~&-BtF2mEwtx>WQ?naQ0so%te-x7|fTyKXq65!R>H`hVU3U&)LQQj&j_YvNKWpMV9@0Ik116SX{wpEH1k9mkm>C+=9?5X;$iKbp8f8B*PDw#JfCF{W{!`qfP@j-}bq`$O0@)v1KNk7M<+kKSWNd>g`K2VbAC;X!57_F`HY>MO+)V-CHE8JqK3LfZbf4DI7Hu{#6KDm2l{7?Vr;Fy1ZPxkRGWfQ-%%Jf|J!f{)%$=|}#kOfA^%&sP}FyA#V|6?*n$b#m$86lS%F+P&tw0)YFu|e^8<-6KujE@#E!85OC1Amv!3{MWmM{?5SwIRVAAkWt-I$?YmrRCEaHgH9KX4gGM{UGwAU&i~-A4#6#Th88cJVuodZ3!P%t^I{M)5wu-ExgBv(Gu6p+SO5Kx=kvX!^vhsQ{Xwrxgn?rKAP?Ek(43y6<59Z`BThm2aW$+{u0K5mw|cDYNjJ6>%=<7utj|hx(qRHqJJ{k|M`oq!}Tk&zmC`r4wSsve(g2Izg^@vsKpie$(+57b!ajd@*<|I^I-q=IHu%mj1Q?-(g>YNJ{QSLaevVBO?=CTc0L@>dzLcxJ*D5)xrdFaN156ALF@u~~nv@k(8MrC;8Oyt%x;dc5)7Mw_Um^_bCXSMtBF72)c7G%18b(4FHaVyB(?ES)>4Zjr}*c-W{6zQ)4(;vZ!-jZsfkHdJN58X1|30yd2{CUy#GBkPU(48zh1e7(Y;U*h_gsUVUAbDbR+`BD@o|ur&uhwEi$d-?f_Wr@RZ7=<0b@m+_rad`#?ARvcq>g=C$AP#D6(z@fDE0p(GyNyNqD;@4&H(7GZySouAW%GoN_L}Y3}p79u{7mQ5$!dLD!utvTUal=Y9Vt&|+UL5>Lrlq_{z3XzwLT7BqC5EBZ6iZ;)`j$F~{dUg8`rf8lL!$-brxzEOd1Qx{A9Mf3OLVlL%^xoNw4HK_R7@N|ON94IYG1BC~t2JYje_lbpY3<9t`NTNpTo;wm9EW`SwEo321U%UC$*}rq5c0H!DU4@#`HfIyw*?Tc}u>>AJt<1SAVX6`X{gS%nf@66YiE&Up}pioYW^~%ULk3ln757g+_~j!P&JO@Ov|OzWxaNYx!b}4wS*J#oR`Ss)8C8Ts2Z!k%32Z=4KYY+B{8=7|TSiX!?1TJ5?A24sgdQ_h-^6*rL+&SOx_d`66A1Y@OdF!Cr(M%DmkMOT-?dgLDU>?-$^JH9tv9fN9XInm`#N&zL6w6aHgTXU!edv%Qq(PE-F9m#7ZxhHhw>g%*0nsBOp(;&!=ojomAM%dKhmj#KCHG}SQ(PL)O;;opFEe;G(QjYBC0GTA}ITnnFl(Z!tx-O`4D6%zFs?D8@+D)kO$+oyA7o*#LvA-i;G)zhzV^y{buUP$e&laY>*zsg80rc=FF*hKV;w1nH4M;<ajAa<`NG29vT)hu25-FAN-XuKOrG^O}6kmpSlqv$~TUi2=&I_jz%LKvQ4z-CTavE4jeAGlqhpca^x4I&?!-5@;Q2Os#m#Hs|E{C;NLM~+m@n$L-ge-`KOSfo(lysq2q(s_^@8QtKaNPhExpA1^R{RG{0w=_8uIC%e|Zp1^mt2i!GHY$6Qlm|8DSI7bn%2_``*&^R;VZY6;*zkxzpi%-Ywy#d6>uFU*5g1=MV!f%Ty1JgrPoMlDk~LJSiK>yW4M7)nb01^_}y?Y&Zu>1Q~iaM=)-wby<9$t9f8NdZy7BiZ7F{P3bc0vxF`^;xv}4@PBpn<@+2MaCi|lZw$s$l1LP9wD{m+QLgm;E5@zEdE4}T7X=X7uAn+J@V`2$YwbqQS3Lt0^Wny`kNI_zkYDirzEWpD9pnPidYc+Y1h+$R@6~voNENyGr1ridva5C2JR2`R?i=K?M}=K?%#MM>5TmBlG7`_J_&$4ha^rpf6=QSlIwdaA9{bAuG0BL@n@?$y=;mT9V~ShB`+F6-9q|7neSl$ea2p!JZaQL8Yzp$Tp)hmPxA`rf26ECS&_!0#P@ZueK5{;4f1g+FP>}X6Zw6Nt9`v4)>+jwnsQGP-*?WaK>xfz=!`Xt|8Tor^t)%ycSH2$_JH-;X@rC@P6C}|1!rr(_z=oRqdlLXZ_;`VkhQDIWs^}^@N?{L*zjt*XG~9m>yDE8BX@sy$_KJtmw11dOpklJ#1?hMD_*VAgseOeF08OT{188vt^e4ri_n>*|BU^1iqEIjgX41^ali?5JHlU3>ank^KJaZ3ADHTc=dD~ZkIz&!8ToTX08Urt-l=_!=iromrJ{xu^C8Y*1>>R(`fZlR?kiG0PKUI;Zkz5E;(anVo)W0}GeA<#@ZwGl{M@1b16i}LWkVUQDpD>F`ArGwZ?PjeFk@lWNbfR=&e6T4-WZ<;P5u_01(d!sX_7LDRi4E7TybEEX&~x~)umgK%`R{tFH-%h(E`*J5ej%dW~r_|4jyScSi(6S*ZEG2TrM!ZiW^+?&d-*Oxp-Z(?Lv6u>b>ZXG3Q?#OKSCMM`Pq8%FhyT+7QKs9B);!Hh08^E#^Snx_ubFgKfmUH{GIK-!X^|M-_Mp~h1mIvCe&X0DlldO&v3?!kp##Q40eLgC74)B~hXf*tYxN}gJG`N?L~1J+yii2DxZK)9o2+N6ybx5YJ%k$cbQLEcpPd%kKIH|6-q6F)sza9Q)D8;#O0PiNbof{sKEkmq0ynq%C|p1gb~B%bG?z}SJl8>p`|pVzFG+$MnYe=fNTwqd`;AbPo{O|cLRIPDojD^LI9r0>{iLT|L%IjLTpgZX{w?JJ{7_A%gwi>9vB8Pr!~eLxD4f3NJ`r*-!!=J8{#yjAyz=lMu!_Sh+tkpGp^*%3_WEB%8ehj^6!M^V{*UoV_vfy3JuIzgrwPn8wF4ljPlfhN1AH?A8oo}_QvT|GY7&Uvj~unFV&VO*EX`^y5+ex-sV#`DztXti%s@?rJJ*Jp3yQD2e!I@fLK;JB<&zI7Ywt9?3oZKroJV06!>Tx7Z~jZ;K-YDe*k_-%jdtRYrdIOR%H~Jr4o{8pFR`MtyZr@6pf;ItxnU^qucg`T>#Wj_3X2i0Vw7Ju&{Z|Hok&jFk>-Nef#;X)v-8)N=pLj5Kv;>z0?5@H&E^^3&qS`a3%X8t={NZekcc`P}9IaoZx$q&m@7Xx#yU5vfWt!6O1wi&yV5J~0vkV=&9hwhgJiUjV{ZV(h5kf}Bf)4KL=0-w_zIvJOcT~@k0ntHPCvqpEJ}Iq;_&E}qE%Ke#(xmu>zT)nlLd*wQV;>lQ+Jt;L%g}Z(BM*S)`+nL{)ISTH-+Io>V?kagPom@!a+j=ed5^|(f%GYfzKz^F$Ct0P|G&O?jc<`lTjcnSe=UFw{)___6SMyDlV@74zdfE0^5-k>FVV{ScR%A2kIA00q{Aj&eN{6>U-5#I-v(MSfL!m1XhB{@zkNw~A{#{S%{0_SW!886<=*B1cY)gI-u;w*g?EqBOq23}7@Zds-9)~gc<^UlWI^%CXP5U)LEZAcpmk@$dydF|Zy{x!C;Za%4X`SA0?a7R%T>Z`(sN#j}^=#U^ayljA?uTI}z=#fU~LgS+jRoWDvt9iQa`)Wh7!E4o0tsx%rQ3Z;tm$nk)bL9HGrRXbS_;26ypS~&|i#qDMN|{AvFCVsi3Ej|f7rCwB{lQ=ZAuz*&(l)rEzKYgJFnRHW2D_Flu9+aj{57Q#p2j_;13lZ(VpK8es8jV~(|W|S!8=>3ee-7239|Ala*7>t!0||GUjGoT!|YjGDS7sDE;KWfeJ3A9eRcD}d!cI?6ME98SE^Ux`jus|c7j4Z8(c<;W!B1}zH0ACNqaYy2d@0Q!5XiKe|+CYtNEm_6nS24t4!EGPCwGT^x_mD=)B$H@K_=E-}il)e4g%5N&~XLy>2GvebVP8p_~reW0cR)o?zaOm$!b&?`Ob+hXHek2Qcps1?{``VOtKg*2jiaQv3l#y8T-&400y+{(ggTv;5}#=VcocT_)AbTU?{;V3JIgViJOuMNW7FTnubXlp-GA79;4bQ@C1JY}$fg9ps-p_=i$DSNMI|KRM8|yD8tsvfC(~CpN%Q4Q|w*5A5tl@#p52G3ldyMmoKMqSte=yP~yp3|+Vfv_E{T=21^$*%Jg!;-ypC?p!?z`%!@ql}tRF9nWXu|fM5#{{Bz%{vE5{ocE>tMb2vuwq5FdY?G*^moPmn$a|{8|>EYG(nw1))lWkPluXI*5&1kk&}K|j4B44SpBuLQ-!kMM+p7LD|3K657aUaxpScHnvGv`A?VwehffDk=aBuX#Qrkjc*UfNij?)MkX6y+KJVuM^V(iF&2ozGJ&Qj*K$Z`FE7fKX<)MyBH8>v=byfh3MRptRUBbVwOv*pDdwM<;M3q|W#UdyBSj~^1!HMG@_lGII^!H1)KNUYihiQX8#+q-Dlll5q83T?Q`mxO^=ljNV4E_@6<$%TorMCY0$cugt)JlBFg+*$K@77pS`rv%nC1*Ftgx*)nmEw;fcir{obP$7CsW=_`%BsyAumK*1dq1#v(fRd3M!)4M%av>!T;(tprs-m{ys9ZYcgbb%Hyfc(=#zT%q2#QayOR4IjWzHfbT`qq?ZJUArYw&PX-a#4R2CjspA3ERV+fI4ci*fy_u-9qR(#c6Hcf!xn<^`?iXX%Hvg+Uqv~ufu&3eP2A94wmv=U+23b_eVN%PdG@y$@TvYt%F#IFy-d*7nUMnqb9^73Q^EV$Y(FnTqaYXLgjy-@DE$PLcgDqsUtmH<+H8UL0n{fE%U1@!Dr7_0o;a1a3aC%ube!@<6&|RLPq|ZHirkM7?317Kf%HAnp!7l39bT&LzD5Y&u6`{Ge2)BK(Ef3=(`hh0Rz7;6G~Q20C2wc%6*{aqa&@xGMdakZX8Ud8`|?!2pQF@wox3Tv^ws1Xh;k=Jh!*7Hij5f>8M$yu{p%0=7)ssL7a1jKS0;R@I~ZtXhWC@bVe6XdhuI=OpHDKVugHGZOU9{!4e=h9(S*!S$AN`NBYu<(RI5L5JUzeGq9=Nm1JlQ9l4Rd@BSbzM2`-62hVGH!1av|0%RQEtb#6O<;TG(`g$%itRA`jp1sIN$W+m!SGH{VcNotT_WW(?&)M)IcS`nORpf=^V!xdT;6caJaG&G=jPu0LEBU^&1u);ceEQ4}l=Z+JH(yVT6+*&Qiw>nI5*Pl-fRw=c^QwQP78+|XHe7WwDukC(=J{`Wq2&7}CIj=gBPH--u1IWPeS&pYh&+c7?Pm<>whRo`ZopQ^N%>%_fv#u$1;QH0C8P{z$ZxFzr&u65!$K&rs_SJH_EriMT>mDt3LN4eExucMlMcR;?HBxj@Zr%ZRP9Y6)SJ2*^{ek*q&Z;B(?~i7HQkHb+{9fegi9Y+(@DyENjqK0HiNhUnX9km{yNk^F#&daX+4X(iM-O-bXnZP=L$A%q~)qWD~q&zpS^6Q*sn{uks7VSp_q#&QxQurX6_3xD@_kq=iA-?!dR>Cnhwr%JrPr;Zh!`F;)8ub#i#Z`h|HfWy;|CL6p%{_UF6MX?Ma{Lpmfw#-Fc(b@FZ`(tVrXg~ZE|7tQ`pIrA?C7^-pd+8gkN0GNz*8cuOd|y)cE}-6jLA6!OCsFFaXPIB`DNkgJ{N!)mqx4@6-1cjt8V|Y;%W+PvrT8+1RJ5)f;DhYQLCKeS$nz$zQhH=3gvGX!k4=9fFK{=q>(0%BlvDmz_PKaJ_hzlXmUoK=8){iTCMx*3zp9OVhl%HztatUyKu*?iW_oAC{vhplr8;EnWiIn~I?eK^{5Cb+Lp?Y>IUS7d(~18X*r@1Nx;)F-kBLzdZ=bD?fC^F-SvnI3AS@Eu{F1=GxXRj;y1>eTzfC?@{{ic-3_TpB%%0yC-^{d|i+Cx!rR``Lv_ipu8sJ$l!bA9;6|bLN0tvTdlQ?a-WB`Z!*a0&x6skPEOfij`#DnyUn_292>gim@O7Rk)NGWm=d~;D>`TWDT7k4J}qTR-F`k4DYYg&UyS@LZ+b?Dfpv{81#+kdOn&YxzwMe0(xgy)kLxYk_PuAn>gI~hDHj%D-Y5O^R_QQ-Em5F2Ga1kK`DojPx$I#BuP>r}dm8Gi=3k3AYi@GE-bwZPy-yMUc=+6@i?lBCp|hcEU{6-~KTe(_F0L1VH<3tYHKOjy?dp$srNH?5o=LR=$?o%LH=&|8F$brK^54oprK?4IeM7i7$MGagJDhD_GNs2l*#z?8|JCljoPNNeY1MGub?dabB|JbKZ4(A#AN@Gy2Pr|7p%LO!%7#Pb;*p)67s`g~`>%`z#~!#FkY3_Y@sP_HF-~L5IowTZc2R8KmJQ^SW8g&tQKD0ZT2auU&xHu8@6o<5yQP!`>^)fd?PZr-k-f@X??s9_urdo+_nQ*5sZM94z>X1V#9~xU~(%`x6YoqOj$eA}%yH=&pA$WXmRq8e5#BEEyCGyI`o!uVA;mGMZHFK1R?>oBchvW`d^ch9R?qzUcrX)I%U1^S*{GMY9~DoC(4fKX@Y-`mmB>lmshdoPb5e^gwR9q1Y`0;1{<>^OHnU*y<#a(8DNY0t^eGDJS}MACEq-rC~w|(r>u`1HV>>{^RK*Q3E9rutwZ1NoG=*-2Nf(BbOh6)&E>LVnT1Z{;;3;`d!)vuP8>ceGG?U&f$LF4Wo?=P}%o%b!*B*Wb^C#Z^(QqXfwJ4GBLkeaeQ5Ly}G#zoH*I>2I4J#)Ac6`<(N%QAb^K3HR3}=0_7MIzFAUqnyhNw&#yKAr$SewfiC8#yPcXoJb*W2el)kI&sc%FC&T)WBB%JUA<_QA;ciM@I_XRGxrYlGv0wI@N>ldT*2$VLE#!k*{_&_y4#-JAd4*pB$aY>SrJaEMZ{LQPGwZUzrTvh5i4oq9f90GRuAVgb+R4#cbdRDBCuL;&SJC0_Go$#e)_6bVoLhm?Te4x%MTL(BuaL{^^q#VW&{qp?U2bYThMzlo52uYI%>=TZE@3?CC{bVFrEK`_zsY;}BE`=tyMgxOBo}Nf&7PD~*0spG^cQ}7IC{l!Rf;=uvL59SO90yrXC+VNAg2W+6-;=V35Fm0pI%&zdSHh6$Mp{sX+XS=KAL%`2PP9j*)5t5`SYg^f4Gf$An9`RkNw1RV4D0uu(}!Zz7FSfrJr~%kp6J*KcK$iMCmFl8~5LNhiMf5Ppy_KZ`SCuK~r}mJvagP2P10cT9!m|;b_B|=I7f{cWt>Q>uhI`QrL{83sgXS_t{x(1BF`hSCcSgVTV8hJ(KC`Ys)T?CMua!@@P|q@8z4pR5+jKhon#173B>I-V+#1wf%tFZ<#jOHxo9cQjH+5J8L3GDi#7kA53FLfNmrIFr_t1UbWi~uWX2*nSBA-#Jl;JRg2QO|1dd;Qi+ow_AOj{rE!R+c3o9=VSNqv(uNeBl|)GZ36tSe5b4!6~e%!H|>TgAt!qP{9Dv`^gMm<4@zR?b`4fO^Sc$KECVo9SRGec+}05#*}-%vHT)v*DQT_gWiSJQqpYS6q_Lg@Li78n1CsU)^e6yyemcCXn-t&D)Ug4>M5+C}IP7zV@dia>u34tM^&)VD_W7rKa~$M}=BG$z^@x!xRIapq)+emy4L8;j>BzAIAD63}hp3eigen`*ZlBc=CdI}KX+waV7$>lPL5yCTzH^f)@DeSP#&#qufZT7AR1axJEG5KQliXlX{itT*=acp{HhWX-iY_<_=gF{mUyn|Pito3DN8D}j1xUCRkEqfJaWVjjr(N?GrkmDQviS;>a_`+L8C)Wg5;(o(zsWe*Q3RUK*uDeGV#9Bj->Bm^SgzZ`4i@s3!geDqD)*X=Y(S4e>lX)W)3?^UV6kxs$YH|2AZa`V3CaL|zfu#J*@n=&K6zF`Q?}f2w?YdRHnNY$YE{+A5%4TDR9ayL@ymyp~O^@!d?>H+(Nl*}0YpWId7P8RRR72}uK?H|z`Cjb0TazjkWPNB$ZftjI|eKhs00lmGVV{IOm>&xL4D@v6winKOr?ugHE0P7ZVkJ!F&qwFbGShvdyW6SHBDU5k1XWqmB@^w9_V{^r27gMFLIf|38)(OdaZg9&6G7@sEOYW9v+;iuT(|Gdg2N|~}BXKOIaU;KaiS?r?tWd6MWiE)+TFhbAcp6SBT2~p6)*hZ68T7Hh2n=jHTb#fht?%88_5#A@6x*X_s(xUJ*FO}Lsgk`x5ibR*0POc2<6Aj6YOPhvsU`E*~Kg|=A^K?Ch?6P)W*C>_0{HF*!$P-aIpvKrI33{I&qu%pd&t<^R+zUA3u3W(Xh%#02hZlq>`hMlfHig%9(IRA;rqR8}o9BMAL-`zbuf>JgFl;6Zxp73yTl^rUBX4I?xF9RpI>3(^uj_gan9fVL?a;z_T2x;>=+Ko1qYW-BU&g|CYNrg-!j`eY^zwwoX0E8CCXMJY(lWUaajy5plpu^V=ynu+jpB>y@d}4f$JVnMVf-5c2)MkLX7LDlUh61M4Us4E`@a=5n4ymHQtpnq@0bNfO{>Gyc$9T2yN`R1eWbxm^;3as$D>b|<)X3c#uhRlo=%UF--kNthOF#RTxpJ|{yFRx>ZOO$GP{y~<-w9^H&>sg>;s;hzLl?Xhz)PveF*yv!HeUlyl31kdyVMf!#D13muO&<&kHa*Q@kjXF&9P>&j*t>Y|v{X2nCq{ECn>4;xk>FEywRt5jeD*`K7X1@+Gt4Y4Zwcs3Xs)yKDmBTq7$;Mt|l0~?o<7L!aVK39P(?%3yiSgmkHb?SWNW0X8Tbj=V#O)zBm%to$z`;jyEa|TpicB;2Ii#p`PTKAA1i!8X_efq^U7s`5+SMG}wuV_H_5sd)kWWDsr4F(L2t@CW3hCKDWyRl_`j%Zy`rytMpg@qNkRTJ|CnWRwd&vnSjb4L-mY*9boyLrfU7mMFk*~kO_ibbk#<0(ENUr!dt5AeaRIKtC};wLuO`uE9>#X{KkwZrIpDE1}H8(BCa_B{jiCbfBIr&D~r7~!+7ZOwxG_05MTbCK&Fk$rmQJqWxQ^kj9E2Pyrvt0uF(8a5H%cTK)(z)$2y9;N@z9puB~i_Xd+zmd276?2zgA_TIZ$(Rwme&pkw6?IaX;2|}V5$com@9)X;@(~BJM7}ZSGmw+(0D2=dQ6I(_ir-XP@6V%RwG5czWl;NR6s4cwomC?itvL{5yQ|$}DWz}D$iB}ERVK`>a^J1I2RYd%U~L*3j%jZ4^*@Qc%5CuPt3^C8YWVs0T`KY|(#56xmwb>^2%TJzjlBKT8v`?CAUu*R-^cZl0H;Ea&$-;s{cKOQh)V#OoZ6wXAFpR7FS47M%}Vub!&Z3M-I%X-?_B@5OQ)HT(8K4KH65>GK#;!$+jaOM~AUtS9IWxfp^HYG>)Zr|KW=IL!FaDom1bCb>Ri_U>@4@SnJ`t6)ELd&nQld@SuO!k%Zm%XCdP@GDU&2JL(9*B{^#cRmKYg-!Ev3Hz{cTIa$Y;oR|S*-|sy~F~6rv>{)&HcP6}Cm*2bF7W1{Kprg6@Dh*a2dMS)qh3iqtVBXh!lmWid1Nk=daKBIW;hwFZ19E`u_m!=UdZ}<>bYD9!59XZ`_WK1#{NsO<#eU_FWy5H$riADu#dG^KH)-2agQ!W~7Zth(WzHVY#15XJ;mmeZ^(6Q7<*GTzl`(DH<%eGM1lvgmUiBS53l`ct0n9Tu67gih7AzykYsVQ#m3%+}?@0$a#*zXqBgV&{Ou$N1dBVSG9m>bw+z^8(Y@5w5tql7Nb@jjKAz`A~K+3rKAm)NsXd!l@4pjTY7GMIz9D8_Ks0rI?|vuaRe%xBay?avRJNhT8Wqs;WYv8#})N6HpQj^x3zPxVKJuTlEfq>RYQMzcYB;uXgglyj+?Wtshfgx+wHd2M3fit%^oN#j;^@L_sQ{(bdw%6cHj&Frs&5ZVv9o9uatoa}S695Uchr{D6Hm#BYs$c=Jj-OL2CKZ)y6ieIi(^Dhl|8d&^M5B=Ut(Jc&}>9>jRt9;?!?@MmD9~U`M&2DZwp`VSbXwIKeuaf&{(!}_j)FS1&B@%tT$n(iQ#ccSp>37LxZTx%ke99;f9<2FtRoj~4cM*4NLzPfc0E(X+6c4>eeS1PxZH=|D5XgCq4(0F3bL;aBGhqEd60}it&hi@7c@uABit>U{5=FOo|2W>@L4($Z^?$$-d5iR;@6yEce7bu?=FA-A;zLb&-NgJz<#5#L1HI^*`hDk*he_H@cz#Ug{O>|Mr&%2uKKo1?8)PJ(cFZ}CoLr|qpTvXR=_`Bp`ywAVQ)=nBSpv{?`_9U6MXn)yVm;(2gva@_FHUpA&sFw+v8d8K0~S2V8#w2P`eaK{wB4k;nUL_9lQz$V;*a|AarMbS8kic{H>e$^^rybUwo&(Ez{N#|54guDKC7bw{iAQ>z_ZWMelcOl?+6Yy*6TANq_*m0X(Z|&@|4jEV|E{w%ZQQHaj!ZbV$@|WZK;*@p_fIs((|~!oV6rs>`Gp<9#*5A{Aj`OGqZmbZk-o`Z6**9>(06<4PvoRujqOS%JZQG6*QWH-$$Xk#+4zhN6^#82#>gtTe77<5Dd2u0cksxi1Dk{*Ka=Xk$j7T6`V$|U0qJ8hOO9!yUaDDNaORnK7TA>3wS`dDudcOC&z>(J-ruDg%Li{Gzx29y@vn3S9Q|lw79fqfg^|&|DdIs6Ftz>S&s!spRy{s_j2;u*Q(t+NpG8jkg|-pzZ}p@nRk=4PIxTUw!+RSZe9Eu0xZHr8?0*^bi4QwY>J_pcBIhTb?`)kTg!+UeC&}Ab&(FQKK+5KJ28fr>T;uat3sHVwtGVUC?=z`)?~y)`1x=%4c3zakzwb1z`2Jji4u=n0Z0b&|`;adu62_CZ9Jt9%k-xE>(l_u?Ypv^eCJglzS^VZ9C(kX@?AdVhePf8nSL8~a>-v0ea^Z5u=_7kpP%mjMkg4m4;=_US)=OeFkynS?-WTKuAl_U+yFBy%`eGTYq{FjkYRqYSF~8@V9K5WimI?N~XCsFw_2*gZq|>epWQppHgAH-rNjBYg?#dB5j9u#`cETFhmrmEb?=4@N12awB*Z<5xz0}5iIJP%A??3+{2h>00^Y%rK4Oab@k8(6oFFjeISF|pM3t=aGKbRMV{Nod>mE2m6@kQrT8tm}z3r%$N(=Q3&uPM{P@QydBB_@|>U7_5aso8UypbBvkOi(umz&#OqyAiX((;#K4|UX?F|ESM`Z-|BKNpZFz<5fe`t)nv%mXjqq)%1}sDA=gI<6&I6Yp<}W9xyp80YO7Q%`<=!-aNwmf%S_atdm_z-t5>zM%bPA-}&{|fo2&pnTpxTQhOUcJy$N~oih-!6aosW}5oa^808JEM-WIQv7@DL)H(O5F}ruqo?HT?;q&KcT~Pm7lx%exWWR>-SpL+CwF%2T7&v(i`liX&p|ZJC(mj{^)C~cr~G~A}6`D8Oq@2lKtsFE*C<`S*v6v$~q*u{#>G+2I?d7w~Y>=E)sOEfz5>(u<)pGf`>kGceywIPU%@-zJC8lT`A=HF0B{zAJUJO^Coh||vUkO%J{CuaIPPvi@#n1KBAiZ-vU_u1enA#?xsNy>GCAAMb!$b;>ca(+&c$lXJJG1e;zpvEy$W8o##QDnW>aWf&zv#`;bAVf}{qck&11EWuKEy^kVkvsR~-ko$W1Aff6Jh^Wla`HU#C{`8_X~4JX2=d%lRoYM5=#Vd^r}a4)^$fXw{oW==REOprgZ!~yZgz_}6CV331h2Y4=^NPJE_avszU4ip32Kx+I1xUk7p>0oVB*G#vd5{&jpH~6GbRgQ$Wi_mFBPw!>ZO$R$wUa|*L%KPy@Y&lhhtPsY#JEYgKL3%*1zk_A%xhwo(xFI{9?kV_tv}}fQFZ3wQ2p=!FSJ^s4K0>PWJyv~;+7>Ug^(puqLLJ8u~e4q3L*P8hB0Q0EtSerDHW1J$sV#)Qk0bRn=|k4r~CZ+r|WuL=Q=azoN->y*S$P%E0WJ=z}8l^**}0*OTH@hp57(@@uj={aM>xkvsib{r>848W3?f-3Q1Q-JXB=LJOVaS1B?R^~uN@2OoPYCYVznzIB#G{*qma`_ocnLyU$<7ae^}nViXtHLQSYWn{fxGg3gT1gK=`}AC)N4Sh*~7m6p;x**Pqe(PviLqrWV&28fO8~FJ3{avpQRIIN8S_8;%}{x~IGcbrJJw(W2RIG$7{P4Kt7vc@tJS9pX|JdA}v;D4@(+EGf=}@vNTM=vAnT{4MOC-o4C%s4Ew@YO5eWKVErYzf&Q{mnKIVxhPY;`J6XfZ=Nkl#kxP;z6FFT2GC!!8&byEhM@vC)EjKH|lypx;b53}{gX!dA^)l>g}d_kG0tH>WJ5d9X>>rqGT^cmrix1~W}6{DZUgF1(pXS%wB4xIX8l3v;$Lt|PvGC?Nq_Uv;}$cf(*y^{r2>kq7~ia{N9p8eu3Oe%!AHlKd9KE?C*lvrlA_dSd|N%L{vQ0=5bs{fQrpMB`Rz1^mGp4>Bfa&FJr`uXHO4FMC>Z*r2B=8JlZAisRC`GZXSom=zNMl|4^n;#t6P0~>XR!V2M^WfIbLiGa$$TvkPZAyK}gb}afVS;7I9Y&Qu2RIkN=4R`J<|*X7r8%D5UkhRL*XC=KllZwA4~3{I{Kar##}j9V8TkDPKmXBBDKMn#Pv2yZdTH$HU>d(x2E0(CcyF3QeM0!NRqmw#vHpi9A>XxiV|*=x3cFVQme^{5I!An$_}xN18uZ-k)+-Re<1JTie&xoO2U<_sOQ}CmFA@HmGuoL@>^raBnGcVjnZvh2ovk;dTBVu}kopUV`F(?Piy%v?Y-&yh^3S(;>*HjK;f;#uwP4a*OTr%V+{+YD+b1bTe}_8c5#QA{ch_YAebGx@^>XBOugfS*ZMNRf)`wYCpH=RQ>t;aa|m8i6*`I=G{zC(pa~otqA#md1~{*RM5BSIF@LgYpV)*{ur=GGGb>LR>ile$cDez81AV5e7b;~_Hd*-@L8DKVZLSq4GuA&<=yvEB0GPb0Xhui)T^6YljcVYiF}lzGT~6O91&njZy`EGY3GOU}Tv1a!$&;wB*xR46UlT=eu4}!<$N`cbGyhh!H6#@-|D60%M2b@__wQA)@Xh#d{dz{44_LKX>YWb-W=`$P(^x^8N2BqhWbR!m5dD1lq3EG({DM}yw*9~XM^kU!&&*85gNhl|?0^P=7%C;Hwaotdy(eSE3b81m$S5TCu1EC}Nsoai4%o+ZvtyTB@hXX1Ps6FsE*`Byo^J0BIny3WY9FO|sE(;9q}_|hPd*OMpxFzTqwdzt%;?qxu3{~Xrc=g7x{en0J}Q#gIQxyqq&lGOR1vao$@reWRWQMxDEMnbw^i$Y&sY$-@&Y3h`Oa^>gTTBHB9Jl-aI=(3HiRk`%gY3u{eI?NhDr5;xVA-Q3$T@B3^edMt-JsFl9qP5pdzO4_Y@5#|P{e7<0r2fIpFLhS>(P1=5b*;n<)J0Q|U7l_4VQ~CT^GIJT%=@2zs~eUO(bNzJdLZ@B!OC``agflK-l`hv%7Nda0n*^QmRwrT@jFy0v`RC%EUI0e%t?B*4UY)M&f+9X|GcNq*s?rkC^m|8c^%*7O4vPKpITxL<`jhv?@LwW4wS#_u$sF52tqAw}(^!(dR(r<)qciT9GP9h1`^bf*#dx^BmyKMz@u7l-Qyf0GKfc;+H+UIoV0qcM9sBW!*?7O~|$0=YXvWga|fx3mrZ>@Vyg)5hZRD+hF&hZ?)XLHDc1`{(4PCm3iUBryGJwEx94!#DJ7q=}#K6L2V*>5pSXgolRUU~vK<@K2BZh-c1_WJv7nNS2b3-yeR=d-^@im9A=6F)W~zxR3j8Gg2&JR^Ul`NAjEMSLF$qSg!K!EF9Ni&EYqAGy)z`?->Ry;=_*drc!J=5m$pEP&wkLtpeP@%+LWCpWHnQ3!;ujK&+}H7Q3wakmsf>4VTgwUhY$zqW2sSD%vtI~&FqE;@=j$deX#{mn(yFQO+nV6@tx39Z&CK{Qk89Ul-_nEdtFOnjVe%$b+~gt*Tb0z$v+b@Uw?dhqz}wwH_Nyhwa1Xew4c*7c#qQS1M0|pbvRYdKpjQQIZf**gvAG#xqc)b)6IX}n7uzbbTT6KEoqMAZO>k+;Mo)~$kCxS&?x_SN_gdGLx~JnJ?E42w-)4GY85}43@PyUWnIh|59*e{#9Nm;Zc>5p^C*!={^-tf-R11-J@efm#>{}^bJd`y!irJ66W!cWp=7mhS6K9valEk?jE^_N^EP$)h+IPMgqK?X5x>F{mvJl*-Wft#TkH?G5OU;%K>qly_r1+js691&Re%a>ZMc=E4k)-(UWM3hTA`yOu>GXD=_ujM;y`MBmfwyU5p6>aB4Yrh}aVU-Z3t%J!hNeh!{e)%qWo!LckJLDceC%0RkAFN1bePj~&$J`YNlmJCJoMlE!A%V09`k}bFC8d?r=EYs2b@XqEB3n2XP5?TIjlP~6m`_)iEGPhKV?ADtamHDNPg`0u^E*aA1ItTTzhwte79mmcx3pq!GOl{5r{*+uv6@cff)_bJ~`>%eujLHtZr3L9vvR9;90q(7x@HB`=IGG11`QSvC8g3-g8^>iOyCQ5dBZxRmg=ew=Lq4D}=!x*PrBuBbRwPH&<1Rt*>ILudmfd{{FxtzHM14@ZwK%uh@+L>5y)YucoYR27K9ExS}T%<57<6jpeUI3M6#I1h01X{dc^cVtu~gA1ZvfFpIM0Eb5|W+tyi99yI89-Mo@l7Wtr3Xo>qE9ctFyzb^d;xvsK+Qn@}8hXvW@Y-azknr@+<*&GY}zVD=R^1Ram$d5CwKb?Jw2IX$13BsQ-9(81E*WUU+bRhcj9gOk#a*^kuFHSST@oCZbPxAP=$Iqm+rIfNDNIYe)?J?9*0)lmo`|S&1V8(+L7klyhJEhmiuGvupPDDeXAL_;zro}1M!O774Lb7m|5^{d*p=w^0zG%h-5_D&ijG-hnQD7Tup_jch%1>mLOlNeqUlI`|oGX+smo)G~`5_XOJ%s)H+v+$~Pj<(`~g`cAdTd?LQFat$?3P^mo<0XMwQcy+*Y{yd8CknYakfjpw;VZK1f6H>H!u8(eDZjE^4=}UP`bCqL538Mx}A`|eAqJ`=3hxY{8$_L)L->O&MPUfam_lFL!`J9QMa_SgbLxRUj-x@kmucT3r{>k1JQv~+oPW#&)uXhv~5WqbSwQnD?C8*UsX+;n?%e}aDRB^fh>M*L5bvF>J$q`&dbi%y+YDm3UcR9g%rYE@trrTzasxGpSs}V=^`L}E1M6az9ROw-=velVSbBxxF^Pi#Hh5V>mAY|vRnW8Qqr8D4yj~D%R&mr&*$_OJf83aT$4wI`ntM0K6yOe{%oJY?SnKpe|N09m&EU{`q}k-Q630It;HJ;)zC`Tk|CPa&)dd$#i05{Ylpj<~bnv9zW$Tq`IdiTqM?Q0m4wv8M?uqY1zTR#u?};lDPAu@wl>O%$->qdGFkvoP#^UseA1_B9_)2*D9`^b>*J|l*g)}@5Q4g1@Uj$EnDto(KME>~svA*6dDKP#pmG{I$)K{-I#+-VwIs*t_ijbcqUsEOZfG$T0=q2~I+exEt=}TjcKqD2b{UdybwUN8cT0DG+z5Y^kcZq#5BJ~O0h`l$_LI>jc59%UsiQsd8qsaspo7h%mdDKxFDi+BN7g!vBdkQ!5ys~!tV;Y4JI={KTo?LIg>R8=N_WFD5W4Ham8_3Hx$MIDSviE~tBGw%>q&a{Idp-u8%7B9h@?PbTd^m}G%+DkWSm@n(b^%B}oSB#XZP@xs_t)o-#z#oHi?yT2nXRwdRJs*5x{>@DjQ<22yF~}}^6&{MC*SONC!4_iPK|P)7y&yevtq%76=A*$QK%enUe4mo!u0N%q>4&z7TZIqazVt#N)f2+KPw=W8Qx`S92Ls4)$ex=tE6?XgWqRY{={;{@&c&&s*^36Nb-|^BNS{|RtVF+b7ns!`E>1KKd9E*DNxtIZ!~!b^MLDLbX`%olmUO*U&dZMkGkcE*kr)wY6`rx-#6g)-TxoIU(7pOO)ML9tLy1JoyZ4Nd2cej*y|BdkYs8EFMyoz87yS$NuqA;)-e)i3-j_O`hR*u0YCTmjm@?K0!)xnVZJxgMO~y35H!7hF$>tQ#r@?8=;v_HH(vD8`vOqg@T*aRG@s~#fMf2S`-MRCXDif@>hn!Kx4w@~hNATaQm&+WDs%RW@ZyXNpzxWmUt*42XWzMB$DJsgIZ98&kcS6PtT;AE1)*uZmj+8n`MAJydrDks;1M^%%2GofytMU2C3`<$yu5ixFc5j-6<*IK875@3-})jsjy&+<)=>M6EErs}cbkeg)`JoLb?!Wcoce@uKCB-j>U()!7Q&kKbD0rY$QP`2Tlr{PGV~yd-HZW{P{kgS4kQ9ZM{VPyX^gb?Hk9R1-!`Zj&NP-Z=pgKvun2k5Av?6K7G$)G@z%eElFHPs@H0?{LSd2L*2Z0ea5?y%gLPb-MoPbGlPw@E#gT2S9Ox~(j9C)Sw>@=_>7#pexTh%;J^9Z>ASIh?3{}FPOo=`@TYS4sU!orQ-;cP`RZgiNe{TMX^wH86|$pyI@8i2S-q@ly#{jXv{zt<76sz3ZEkp~jQO~i+qv{<^;C{8+(CIfo_L?c9sVyK%cY7ud2r0+Mh_jrLk@p)GC=-hGTB&Jg$XgHFF${G!1HtdV_)xzc(;97fp~o3<~a@H{DmA}P$^QsVd&hytN7U0`;o!mdi;V^SN14je1~B&Se|N{pG@i>d~f9+@$ybO5OZS7NWKkk1=*jdPXWrEUZasb87(S%L{63l%;4NcB{Nzs>FqEGS42>P(A79yO5{XU<&+k5YN1vajIz**}A=b}tG!b$u5vARpFPJH0oDeZ3KPTl8mOoJZrtZQCfW3{XEYT5)$NsqZgq`Ju*x6o}iQ_Ha9?o{Ifvn?P@+!kUcG!e?uczxAE#R&PlIBCcs9j=ZY={bSQdbRhb5y5?g%ig<5+OpD6!$+ULgQF9cYex-X|^lz-=0Wkzq6Z!ds9S4wQMvXHB*L{637DFlIIL-U<{kgsIKrdg?^z$}+JQu^wsb9OzQvn^{Yd;cpF{`-^-@`($QE1iP>^O@Ot8u^K};SZ-jQb8~}>D*=yY2WR{IA{o1XMIS4)Z*3`oh%F3Vp?s*hqw?NCX{=lC%u)uUeen#Nr_&!zxUTw5i@{7_%Dgrn`{S^W^NjK|xtH&_wrsStHS=W#9{>X|AV3GJeW3|LTlQY3H-@*{DtHpG3Vz^5fk+r`b0*LgmvP*|A_VG=JMdG1I4RD0frS$k5w~h!n0!ua?U)D3k>iUI$6`+g1Sg~M`YI{%Y1k}IjT?=f}HTH{m93@UXklDR_jUqjB>2Ck%onkYM7ko-Guio-(*3fWlS=sKG6Lz>YvY!ZO6R_(_u#V)UTcb|9@Qkimy-R77DBh^o)FMkNm?&l_}wC?EPTEt~`q{w@`kjA)BKd-fcC41l0vO*$3>J93v6?!epuCFKr^QvtPTCu3F2p{{*&q;84C}GSc4E0Z+azdqwZ8{M1VV-s1@vQrOm#ybeK+%iFH4=i{`51TM*HcvB-u|(NmsIbx?af3_?&};N^sl89o`1Ido>EsaIt;$mUad3>^_9<&GtGQj47j_{Z}=c-K90uHHfpg#J}4fH@6o!B`s&<9&*$IXv*1tqBcEs7r22dpvEbt>g`D?c4XMx0_sABHohOqxasGXqNxoj`5noL{r@@w5h3$H61dhOFm4Pko-dBt{2=lVQ}gS{GTAdT$!Ngsh`jBx91_vd1NlTQWiL~0Qx32{b}t)UL|v)NqBo9aOUE=qrUp`xA%(S$|UI8IJm2TRA==m_^tg+dKwUZGb7c=H#}?$FnE{={JCmbIa$a#b%A(Up}&BMRg8bjDC4z18ELmVBGw*DzbDaeC(R;IEtKztFN_Tz1dIF8p3*x}Uyc3ElUl=<1Sbc6)4!7PZc@rEYW6qM!0&=><&0Y7&c8nS?z)=^XAGOqmE1&bHI-AiOp6LBRUX#Dq&(n8{g1itt8&0v@A5GV7IMMaY2K0S=etohX--Bt@*OKz?yt3Cz#PwQ39+w{H%qELTD>nHl>SQoar%y&Q~$}n-Zx9r;_s63gDVbtJEgMUSBG~+=4>I==M(c&d^M7wdj4%6X&2NXqZRBQ;Jq{mUEM$O`#ACqofcl^PcmUcsMmuD2U2}hr0W$UT`DkpR!vmf{Qq_GuPSoj*XNH_lO`m;tgiy2bt~yG@3F;89zE1c-EHGXyNno+D!66PYcr|eF#chHrfxpi7X^iTYWl!l6@#4a63aj(=o7?VOziL>-y>3(7zKxoo%5L&0?TbZo`&UQ&K=O+Z#3e}5*l`)%o8-;CUNOSCugkvAoqjFngBz~2L^M|5u?KNlgd#1f(d1W$f*|2OxrTdT}mklR*`0sV>bk2ak}PWTiU$>f8@oqnlSBRo&-56M%0Z7fcGsgDeDr=NS(6ch_NKA-8+==XJ?f8G^aNCs=7;C>G398*D!ij~pnAY`(;^RzIj4(gd&o5w=-`kNE`X8tnLeB`or`vey%$jo$hPUJ;CFHGEF>7yJlVQ(0&j-bx*kWyItYX+U;>y<=`o0)GoA$LrK0eOxmE`E(bZX|eC{K6Cyf;YzLwVI&53O#Uob})m*sVB@{h{qFtQWqB$!h=ZXx3^!Tjy3BObnBf;295EK{BeFfU#&g=*Wg_1|pv5Bql+@`>6t^0V2WN9^kpFCsraozU{4HV=~Nf|05!qG*7lYdCP>)5SvP}}5AFC!tyrwg0&Y#M2nk>0XD)xgQsT;iGVOYR!?x*^QpZDHx3tM|zQ#9({8p@O3sUt*B_3<&Wo)JEtmOv>+EYX_T9uBl$D9sgE(DrSjmAnv2bNE$T5MuCZ!16K=8^-81&1?s8maq$E(94=S~3JU3>d?ke78cIxrE0$6*EyWqzioYN=6yjmo6B>|34J(M@Rin?h0RQ#W13sX7!?#E2b)48nLAUrsd0p96(+p|ddyR`Xt2K*edIQ@Xv#7TbXHHVZN8nR*c3Qvh|0mxU+_KSNYo(mVXHrn0Yi=Ru>owRMwgWvltl2nhQ9&>j-nvkT-gpX0lJwdlnkMRwS3JUb+!w;{C8t)aTy95FoTGk&a04}AcHyp#!N8-NqNL}@U1faYMN!-?o`p086S92FD1;Rt?Yno3XC)N?3`V4rKu{+C(l)n?@u@K-l%>v@RJF*mc-KQ~;)R)=t{rHkUCMw7;megN;u#WwEtx4N<{yg%Bm2;Q9w#$Qnz!=qn4&=o8(QV3v@_jQW?pveo@={y6Sd)(h3)U#7wsay_RnWIB2`>P{cULvf9Y@{eH?RHf@8)>WH5#8ZAn7Q=?`Z+_qbzv#)aq^TH0Jxd_Fj$u(VPv(pHPNeNZhG%#A8A;7v^58y)%zAS4da5>2`!i9{dRkoh@ffs;3$=EiyUD1Wq4q9CC*espc*j7Vyke@nH5L@0nLV-JVkbA^xKKPH#lrC45JtC894L_U=Egpx=hNMJIY>p!#YGaOP}~>eXY!f-Gp&8601x(5o|R7yVlKwjCbl+0A}mZPc1x_yzfkM9y&UDF`?h#yx*${8(L!0N|=bENuUAt9O0Dtb&4dRv|FON7}R;rNz{N0LCgQPgmwF7F|%y%h3_~6FdAwMc$sL1TgfTywz_ouXx6F$opr?S9WLGN4nD$<ABe(h^6m-Zg7dqyKhgohzK0QBC-iG~r4HaW|kIecX@7DVIw&Cz`S0=o!igXTniFzsiarK87F%~pb+Wz28M$W~*>8wC}0W{sN8*)F6+&jx6!IhTC@sl~X5!dB8>>p6zqBNLJ)b_a`k6eOJW5UTklQWmIX(93pO$mZo)mfbSYW`u=ImCOGXH^amb7^dfk*^+}m2Pn;7l_Ar-WB=$^!$LV^LY^E_@H`+G;+e{VW$O?Gj~|98TArTANl8RJ_yF?*Ts^2SqXjVai)NiceC4uT*}|=v}ke?jLdQhz(WS(ee5lrP8Ct&&`Cyg%l|J19C^MdXvwa-z+ncaWHT2A6$i8B4UQf!$vHzSi=2oPG-kU)22odBFiaeW@c_?6QP&G*Ti~47yebl(&dMaG7pV1T0fc)*9Y1^X~Iba^Lw65(lWGs@K>Xne4W7iw%_|LZ@EAL2n0;Ze+oq&`a&gKLNgw^$CWxG<1hZ>iB5Olv<@W0Zz(=*i^D$uIN_V)Yo7tP6rZ~os~}&=UHr!3B?SUD{QNy@A)d!+Y3AGa>$BlovCLBS-`Ef6bU%MQ?-Y$w?@`x@dW`V-Z}g=@kN4$(TOt1c_!(dOYcH%B;A+}v*>)7;U0b}SI%iKaVKTsPK+_!ahL^5NYj?Y_AfR0@VU-TXwPZ|_>KD1)fD}_ZdF`{P$F`Sz?9AJe40}qKIvsk3=c$Vqw*R{_1NPSU&vv+ueEzXjE~j%SFu#0Sdb$-kQ9m&%mJMdrL(<7fc>dsDwr{=MX&|<2Y1T+3sUNU=)Zg+t9a1xl1S*wCaWnmM*;mgqz?Zk!G4UblE@Ho}Dv=N2xuKc|k7K-x|L@T3;_EEXin@QsU>52tqVFTEB@WK*dw!xn0OMM6gFmiYlqPX}6s;7H$7~#y^lC}x^c|>@;$yMLp7lxwQQ-Ryk=Y6hkVmgEeB&XM4V8x|+ROGJzwy#`;TI3~^NrIk?IHCEuGT#7zcG`}@v8??AL7u(-V+5^86armrFym#`8V0P(Uh(1>x~dFcz+S~)qeI1sh`CHV*X_7GSpW@K6I5|9K>7byuZdo{UfV*z(UeF30ywX{?=I{*K_#%g)b!?o`mRTHm^p0VC4+A1s)X8pj030hf6QgjLFD7|g!^~@|2nSCDGb=7W7bn3f;vi$wf6U>UHRaZt)P?Qg?y>A(O63b3;JI>*f_N#zuq99W_>vhYIjYqX&~v76MS1FJ)Dw2wM>LNyaM%1$k=Hv?!zFzf(#|m2yB7Y+M`D-y>HguO~J<&Bn{%3KG-wtmY3_N|lPKU&=&QEdiE}%oZ!;sE^4aq5#Z!u7|}()GcS(3zt|h1&IFLTMXnJ+YsSwsF+YY*5!&i%1>)*>eOW#l=T{2I-!o7s9Vs?r^8C--!pHy@jUtMymj*v84zx|z3^@e&V|%*S8?Ok%?E2gNygSfhOy|ejz^mXA6S@Q!B(3e;h(i_$-adWrIEUs_JrOB21I|sb$q`k*P(_E3LJ2AGuw0@c_pt+$r7DxaA=mOyXZ~wc?hG4xdqa|Vf6>Ao^=?Hs&U$pclib#{2Ke~%epa7I@EH)YlbTWnp#5a%_31RmD3FZd-(F?{iifBNz7c%SDx|6H2mo&W>yPkCFD@^pk>-}2rR2o6@hN-wGASddv&W6z7^Nz5mKUI(ubD(nr=`hr2w)e?P%!lTm46C`ihXI8D!KM><|0y>4gX*K)67$po8a!75RA7rkPVU)F)ClaUv*K`C;h)JHqyANmV_zX+po{N*l?d?9>Fv((?X(c#*bEv#FlzRO-w)$yb93}A0FW+pF3e$_$Rn_9|*x#rG4407?lm2Dil6qs~PWXrJyqF9h=88Tod2-<&cdXHu(A3L-Wj&v@=W65e_8+$XY^wtWN4!yAQL9;>v%Tpc-m<*(@Ol4#oTw-Gwvz#rcoT(*>!_~+L1mQXvKjoo7nGh;ytRi7x_L-9`oL>>7ckO>{;6(C?B-p}t}-%dD5yEO;MVHu)p~^;PY$zOmsSu~6r=K6X(Z^2_T2=X_q41osRw6*P7re`p-MM8Gp0x_4~+bXy6z&j`=&8W#$5O$CL12tghq^e}4)cQ#B|NXy8sCd~mC615OIN(0+zonIG8{tTyA{VL^;pu@5%8;J*|sH2+r=oIA>4EW_Ory)BNb<{>Z-`C6Mv)3bmapPJR@OP7kV{b#?n|yq2QQ0PVSk4)&q(z9xb36B$A~ZCAIFfd5>9zA!QPKa@YCvSrSLq&+{cK+G;m4C{MzJ(eA$LjFYT*z$kQ*F9r6l!-_Oif#%>H)@VcU`VH@hDA^Sh+_XP8yXxT1H1|7Ll#5hICg9S4~?s+*1Vf>2l9Z(331){I(`zY#=FMY2amX{{NdM!28$1LPZR!e%ER;5FbVe3;X%<<*F@8MBZ$t+g8SYzFE&6i-_Dqo>dr5S;Kz5JGZYo`MLu+v9DM+5DSZo$2O(ulj2nRTFW}86QOOYa`?g;s&k)@rBZ22(%&F6HwPnET)@R)!W2l$*9Lo0JKFI|6O1>usb;yJ0if2z-u{i6s3mtiSen7y=v^Y3;T-SJ4UvmRr)GbymO$nfd?Y-CCzVx~8d|ri0$v2*v6K)K{N&XO2}_xEZ=QLgY!q2n|5fSzDnpiu99U#hdTw_0~$l9mk58Gp4AMH^XhgueH}S*9|zd$FA=xsCh4oT4sMV03s?|4;if7+j`w*(Fm>s#vUtdIhkk0_qU${n)6&iBs#(=N^3nmcteXfZlU$V#zMp4=MkRNtB#&b3Dj{1Eo-6?Ufj52L`I)E$riUPIkwvT)&X-YNF|eL8PZP%0@7rrD>sW-AR6+GUGxZA5)F^7%&Js1_ZFc~Fnd{QvPc$~wKGvl!5kT2SE8?Lt?LAkTSAX|h~MXVx2$KJDh-tC?weN`ttJnKsiljA4T*ogXSM*ig2^MCSTvMo(weH7{+iv5$t8e=hF{X@F2^&oPhZtu|EM7Wx$TQ2b)^NbJI*QQCgr2%D)qiH}Ja$^2OpdtkI%v+64s>L|jmRe}A!g5$X+2}Q`|9~$X9^07d2|FBgzX^!OF8P~R*h>igw|8~d>^-O-Y@6E`c39zDZ+s7@u$fLiQ4zG$!1EOx-WQa6ZvG%qm&k_pgm3P06AnB_e=dvAn%Bf(deCLCb44$XKuYc}WS+;(5&X{cXKtA8^z&BS|5ZBArh(DK7+C(p`>?GdsZWsbJ)TGavp+irxI0mw>^a!*Mk6W>xEAn9q+}w$8S}t|Yas;|Qhc=Uc_SAo>|5(pMuo!$dt_KH$a}MstGlIXAa@}0;dc^$x4E9Hnf-hAo9ouk=Y#yj&SHT#Vhk|dQPcc14*3wT(vO9Wyr=pR$mQQ1nOH6pLlKzVHCl#eWOwJF!T&8sP#zODSLERVfP)E(&SnA>^N#pqZuQ`O=#ydSPZyOzqX&QHDO5%CuddQr7D9GObF0S!AKZtrs(AKysDV+%glIltUcaZ1jd<@ke&xd;sMMm?lAt&;r*WSm%);}3a3pe9>?RtEpwC2nt_ix(A4-OA>h|}QW$46ef1pmjowe)tlPj<1_Bf_WXQZ4E$B2Vu$nFm2)>%CmVQ7`$98zqSaFu{FEc-H~ayu}AK_K#;a=fkFFkw5uK^Bfrs%@$L?;^0%8p{^{+FWu6tdZ=k2309gL3G#;_e{W-{#`={G=~1b-%XT5Z-|)53-H!rCws?32{lWEp<%e3{!9gnM9Zl4`lSPVO870l`kYN9wVR2o;cGOoL7q3Oitfa&9o|rv1d+jnOylGQg%JF20F0@5Z%lB3G@F0jayftWkJvzJt#W^jUUr%yhFiTxCb^&-vPHXXj68J+;|@*P#GU!Y#vUYKY1Vn!+~bUE<%M-uV_bq)Nbk1}AcL}_R($w!o^tKgoI1uJK^E3|wj&EM(j+!!U5&G9Ah@J8;Fa{S??RW!K6)1B`12k+0e(qF^B#&RLZ+d$i?f@OqoXl?^+5d6G{ck%KTn2yO=4jD>hq-~-6a7zU>y2UY4bA&sfvauC+te~z5GLHXN5Mka`z(4TF^OY;9rx?!oUNrkc%1u%XD`Rw!$eTvs|z~b_iL&iPGcbwf4^*tsRGL>atUpS5W>er}(_H2_p$S!{%tUn8NRBOD8MpPXGnz=tnmLwqWPd@2N708FNC^_+OQmC)q9=_eM)A~AG+vcrQqJsLQQp>@s(fMe@d4@_Voq*wSt<~Dp-yk)_7_$^+mM?H%bXWq*Kj~i^qU=Hzkgrq={yN=M_zNZ`0}lU9Pqh&*P$^TdAP}&cgr(#p?i>$I^BJm%^g8|KCYI3m%YR8WSxi}3wp?0nYkLuz7qSWocNeI9r?)*QB7RgIk1|mS{+$HlL6ljbOpaQM{dyWFtkf7AI_c9J6vpuyy|?i+8(y=!&?S2K_Pjw^kZe@MBItxN(I6nSN=8XC4u8+-5xh{fc^MoJIzsFeGj;6@SrFc%>GJT7aBlabWL)G`s|~5oVgVzLXbb@9U2{d$AGcrGRv;0BY(c!{zL83eE6lCCVllA&VTHeaXx;@D;Cz<6tCUVMVhl*Q)VPmo(OK-npz5B$dgYO)X6VRhrl)Cze-5!yNJxbS=_5BU~+Us(vOs9lzL+%cRPj(-pX>CVs^;w1nzw~U6TU~n&cuiCs9XDJil))UYZL>lb65dO~v~!5_?=V+CC3h0RiQ5hRD;lvzlJlGeC69IpcYxd5f3CvNZ0^&WBl*{OddKA{Wuw+^G3B4i0`Q{~2bB>lZQqLZc%IvID+feln93hk24^_H8sBUN3Qxl8ME2?fbW_MmJn3aMI(&UccqYdGam`N>)<;n^%&8>wcY{&l=X-93bjC87ojKnm|Mk{;%;3Zg42nrU3|1#(XR-BF`=!Yv+49I`M=r#~f1<*Wuklj`0Xv1vnk#Pg;br7S)`nv*!H{JD23hm()^U5@vM@Zq^$kPDZd1akL?BX_eNr4%UVaq^Xqg7N-5|0AGha)kkpmnpdqOpx-S#d7KBW>l1P3Iua>wtQ0cIJ%@u)nd8l*pJA2OM@-d*Xctl*DhI(e!PuH;uU~+tkAqeZt59L0ZAFO{J?(R17S6f1gFIDIJCk)0z$E`0WUC;6So-=4I&ipLZ2rZ4W9Agu3Y@_Ph%pHRDj_U9}(-xl~`nIh__teN*`B}wN15l6ISk>(68S}iHLC>MHO+GuF(!8nzl_AA==`*g^xd@1ELiu%gCO5@03Sq2bwf5)z1d}%QIu!AOh-(>gQ*K=?hby3I5*wkycqCxAiTX!6tl&70lrPX{k9)7AFD|lgveB0sicK6Mxuw&>|$~y_@!6!d{kK)MiK2S8IOx#QMcVgYL%FRs$uZ`8DkQ<)oCRypk$BL=2ttEobbOiN}$&VZEVh)*{^}^~Ua`xqK}SX0au?+E)er%%yN)(>SjmiK+KE#5rMom@Oh<@B?A^D1n;)GM9MP~|3aCdy`c2ug)_+WC%?x3czPZ7G`(u~^2T-inwClH4BG^7-5d2*Mhy8%n+Cy(U#ajS6|Up!D4!FC3)#>28_&Z{N0C1^ckDW;NCl$5^Czi~uW*Yy_0f?WfISJy);Cah8B|_eX>6PeM8DvsCCHclt{o8?r^B^j4~cs@sG|~hOxyotUoSD&sBR~6ql^%}E5S_I?kT>*;Wz3lBA-C)E}B`}W}demGY_;V#}!^`IHucj9uu^0Zd>SJK==oxbt!yAQGT)zw*nqPciK^|eQT+I^wJfz94WcPk>Fah7}5h#mtDJ^14r{LcrBt$%72^JQF^@SwNto`5xSx4cqi#)^3GRV+C0W(xH{T&dC5!NFvZ&pztq=ST8IzrxoiXORKy?E?3}H`D_%GycZ@N~ge48Ic#W_9H*o@J8WH75n#Wow9yKDc(1tZbYRp2V~eU)Vz6=O&{?7oQ_)~=&H(qDyg+*l?RchM67*eZ^nec3(|H<{dj-mt{3pEx|0AzJ&sc|>Z{=2PxD*VQbGE%^5_wBSI=>C{^RDqJv3SvDL}*ns@I|Jk}?!zg$!hXrj*b!KVQ^W#GI85?JUTG^rtalsIRVDl|QPt$_Cojy&A!jsIMr+hm1OuXyEbMDdod9j8olz{w_!PVJ-wQUB9pJL_K48*XdjN$~?Fndg0@WaMUxq#P-%6)n~x5)%ibXU&6T16#eTf{`4qlxT{~Q{S?n{T_&6`>(CAOwBhJQ=RxFxL$?dY=B2<1qA@rXbr%ta*DlV0M`b~x%Np_f*t#k=NlIry_|lA%8}0D>6j5fsHr|sBLLwiR-&uj*XQIFE+^lsp_!-JQ7(a;m>eY-+uF2=QFdpobra{Lz)d^i?0jITj;47Q3-q93w)Wu=T?A>Mz_;D+7e$h#i{#i?%qP~oT(AzI6`AK!`C!7>#-FzAcM0^5fBbUBtttXz84AVDFQeDN66S|giEdzY)Yc6ZMA`cw$=5G|tf{=hKvg-y&aV>3uofmdw!&TYO{3E3PL0Q3bVI9ge5VfrNIwpjANhn7)-l;Jc460)dxJW)-7VL#rK_w5yMU77dZ9^SZVEgX0x-A1tKfnHZ;W6@iUqr-y8%J{H9o%(59m3y};CL`P4s=!T23(kpeDqy5|9-b*@M$_&P)O2CM84^Pe+JCzuzQtDs+%JG$69!^VAhEgqXCj0JK?uY<{kTbdwaIcIY){|iPRmG+_ixQ89nvOG>#zeFRNJara2eHkIf3=W02~vufl!JLkt*;tT5EsfcZg{x_R%e3`YV~T$yk82zAtzquXN^*Tn%vZtEZ44ahahO>bzYCWGbE1ER5aQ7_poka>JQIs^XB{@grp0DVDSWV&2*gtOqrws|fU!pKLB7Y|CYf6s5$z2!eaig#JE7bpoe8Wa?EUz$-z(nTf<8mn4z;nungVF6N|Ro|6)S*;uMpjt;nE42`L+B~C$4t5MsCI%JdBY*ly!E4U5C=g&jXc>~eI{0!sSI)T`Aig^+vSuZ6fAQwR1uIiH{X}tb7hkQC1vJg5`;UZ?r!4-k?SoA=%&L|?FgFWz6fuXMM}r3At_rd)a>&bEcY0oAKi|Kz{AVOqp^oY`S=(d9-WL;dtKS?)Za7wRGsuDg*W(V(E)hfSam)AR7T)X7ZqT|))Ed_>!hi3RXFNFEyq3oz)deZh-?{pCq`(m?<*!<9B;WN&qi_5EW`L-;)4Gx$lz+T~Pp!MeG7HXX(Ij^GBG2Iu&MrEY4f{SFTR{;-zPgCozEYb8wUol}VFupk;riT3FZSQBkI(jVKTMEs$#2WhT%E^>M-9&;>8>w1Hk%9>Ks8q!^1YAGCBpFXI`iu>5dKgpEawBRYb?Gz{uiYQkagBQ&V+!Am5k})YBW91q&yYvIR=;em*cygWTY3xcAK}?L4VZuvuo$i0}>?bcI#(n5X0Y6xLhd6ZJHww^%oL;#IbeA?b|ljcaie2Tj}d|g>Q-D__0rs`sN(XM4w#bOM)T2&zDjoQ6~^{;ZHnIgXP}^uj+qCJ&-3*Cb~2?6JB-Sx^>zZdDOytx877_0WqI>DIM>d<+P8DLFWIX>bv7|e!u^fXlPI>qb)*ckR<7db}5n7PLz?fmG<6y&wI6~C|N0@5K<`;Mbl0c4YTk4y5GM~=k@c?`{DV%T(9eO?)$#Z^E%f#&r<|l?j64)I1slRkbTl-R05a%n=M*Nc~;enqFxv?{qG0IPoAH<&^|q{^1_PM=wfDJr}tu8;7^Bp-42KwFP8SqZ7l?4bH%kw@1lLqaDGa=%|-(nU&DMqA;gLM%kvX-i2hU&{KOXRb~w;*jznD%_UXJ=>y&c-;&UxRTeBaC9{fxQp=ErCst(BEWcFny2Bfrli>5=qoR~(!4iStN+kP5+d{F~3<_k<8y{+I?IdP0h}{&bzi37s9H4r`(8S22U{$j797-kXXfGVPFBD(csVyzBDSH4?hwG;lLH;9Y(k?*|Kb6H;cF=LD8s>~iE+gkGG;uOj$sRDU`-1mjmRi6+gb!%JW>lQ8slVILo1^V=OhFG_)%`Qko*F@E)Gi~ai1=`xm{B>xn~i->+1U%2A_tFvnhnZ^A%{(Yl=N@ewDd8>ram4=9fCnec1e`>D8^|i>mp5@gwr*RenZ)^Y8%pBxhvMV)sJ;$hUkbO)O;KkXCZ9_zHPyI}~$_goanby``ZIFIz!FC7H@c=wB4M4YHk>l!Em`-YSYt0xgZkag?D2fq@Q&iMmU-<(5xLXYcpmx3|%`!b7Y#ASY6nRv|nd>xW*a?Nc+eC0@wzJq-X{GNByPTdiCl=I&og+=nIES;#u50OX7UcJfL%%9DQ8x-jve(Ysx!`0jZ$a6kzq%eee><_LF4lZn?LNfQX%3uNF?nh0XgXSTpbE=K(tlwIEw!IVms&K=7ChO_+qDE^b`GcAoIZXB{dtYPJ{&nBq8n|vRQ59djSN#)bQD&h&;;4H@eF26BP=48F%up;XR!L7eClbA|bRZkWF-s)rP(YW4%lIiC`k%QNv~&vwLJ%M2`bwU&bH6;tJh??`c~sl;%uuVr8*B9v>Bk9b;rQJ%|K0$5bt9+5am>c{u|BTW8IgE(rQlL<*r=>(%_{OYkBRy}y30V!W=%B}EEXdyI){AP1(q|M?H(r&+$MQLz8=v;y0&i~>4n!ju+wR2Z7V57@(PrWv@bKbq!@UpK(K*TSTkCF1&^_(8Foh^YQ{2>W%co0{^^=Jd@I#e1%SRrE(oOlh#z!}`d3FSI97R~)9zfEW+Wk}ae>D|NM4KGClEiA_WNj_?Zo){w#9*6q6^JuxTpkn@TM5gx$V<)3uR#EIq3$FOd&iG7q^Y9Yg`I2G4tzD-b8nDUai6;1_&|+Cb7_@K|6K-R{T$LSO0*sUPCKLDldHu40&2$Msf))X$Nq)24csfUrBJM|$i}QilkC&fE`w%*2SKm^A$U6}Hfc6m=8!@hHr$Mrvu#4C##Cwn49%aNaKsE;!^^o*h34MTzONwEc@rL`~Nb$Ww&-jeb9wi`Tzo9ILAMtAafF|#vQrI03yZfpq+K14Ke^prq-5vC@-6TDbf^6F@-pY|68l>~F#`l7I!?d^4-gMnb5MM{pngi8&+%Afm?#k{X@%Q8n-r=jm6RRq7wmG>TQ!+00#{(||wtNpI>C!9mxMcnrZD>BbhK}Xu&%tc-lzkpNAj4u@Kx%NL#S%Yyfu^nsg?er4URbemQ$jrAoG2@?ss!5q#;h|SZc3jz&?rBTqoNQFIN}oVKDbK?!Mp4hxu@w#}h?6b_kb%f>OrE_ok%#M~l?cdpDOtXD^SPN+RO7{l&L9riH>p-SP#m79qbns2<~9)0PN?u8+)6*q=LdK*JpUcxAw;6v?Ma&^mbU?wmX5ua|mO)VsuHK+(iCj-!**d;{mcCpvbH7r(zx(X*Kl!sb!AsujFo5k8gk_yXUgX1WS7O>;1VkO)$shQ+?AzZtAuCY=3G>2tsHGt8&peooY$=6{vObkAq&zx-OfhesjnU9CARTwW3is`r7MaD%*QS7R?fT>+=h1&X{cJM$Jv9@&V$4HLf751hR==^LJb3n8Jobw@;+&l4gf8b%!2C`rqw5yl_w6~E<2_7e{(f5(47%0O&I>PRI;+|+;Cahop6({JrwyO!vg+4GaM6O}z8R@6jUQR)o&1C`Ue)bnn$2PT6SYM^Qj5`$Le#XLa1}E0VL$JmwvzYnl2dnm$FOzLf1&&9>mOHkizq|K-_a&2#EFk(&(cDS#mfWR(KP2RX-r(DhvKP^A^=!v(4UI5)NR#yPg%fDE+t)s}-G5F4UP30>NeV^#^SNVS#2t)T+U!097X#O`4yG?ba+x#cOhae;v<_n%=XY2thkDd59Xnr`MT`Kyg9|J{lBA|bnl#<>*AnL0#^lV4cC(Rd~KbYWur{%6y|S1_ChU2&+>dI8{3^+$x%EO=E|f8L!x3k+&q?jvp}OcoAo!6eNnbtZ%HpIq1ymSYdouTM8A(UIA?bO#J{<+ap2e%~u9s9Z$pXE-8rgx;?z6b)i)kZ~(LC4_uGyIT0`ufQ+IJd!44}Y^lfI^=m$0r-?zXrD0hnSa4D3{2hCT7bbs-f-SWM-cw$Puk`NTb>AcfGF|u1t#C))wJ0vs@O^bA@R@yEobmzJ)8yyFwmB>ho~Jp8pU%a2S4*{A@M|jyY?AMZ%yY)|5a)Fk)`im#4FK~T3@~GMkfBOG~M#Ax}>Psyh5s$t9s_)SKWZ+O+ZTBu2@wF17&+YeQLOT!dA^&wazxvScL7H|RTw?dT_EH%6m2P5R55tfG%wu+!&|2hI`#fYb6;{!pr_p+K|0?8HAHTF|pS(^7BbUGpzpfz8{#-LkmcIyydf7-#uu1+A?faj~xnanCh8flsyn`-&aNL#|nOhH7n$1SXArYC=JtL(~hOC`pF)8$A;;+mT1<-+cNY4l<$Y*9zW7K^$LNlGtFv^ndmfx=SL2a6F-Rzr>ir>PNgs0mtW9NSAx9p~0!l&0>>QI6h?V;o4vIbkNY|U!+RnWBJe7&+S@V1VsOtcaIT&bfUIkTBVp(ZxT2k-^Q0G#wSN%#4FC(}ZTQ^|)tk9wH`y}5mgN^3Aq^|-#FTv09y?wjte$=!zhO7X@Xhrgfmfc0Nvj5}%YEs<4;WBz^}{U1GzMjkcwX^5(DkOuvATgE0x`ENe0A`6Lp^g!poKl+X$E_t+RUV}XI95J-}eQxBf7jtn1KC|aLyAc{06j~KuX6BZ!#+v9H`FbNn^fGYU6zs$9W!q0JCcxJJ(EAWbZavOgw=NS8jMkpx5?p%E$X{mFjo@wUKpI6LB4b;=F>AaU0TBAioXu#r$YtTOdj+U4{K`}*U?JlAT>~G+t7uTt#(&+~8SSR9r(R{rawgAAZyT@aL%XG4PjC(2Qv};4^g?@%;P;d0^ZLiKnAK;^h7?~d3V*!TC^(j->#mTE{2_`@WOqtn3WP|U=uyl?{t&k)T1$RmCS2k$v%j5>_966_WDn$mV6WcG9Fi^*aSl?}{Lk)Z8cBMsyeZq$t*LP8+|8ACq%*CB%;|9XxnZlL55$>QR$uw2uSgLoT77LdH%$`ScEhkj-B*R-qM2hsSR;%dVG`t{p(gf))zorsp{wTRl!AYX2sFieMiwggdUph*<#S2a_9NfO45&Ac=25P>n2_6Fy{MgqiLx`Aa8N~uwFuf!2mBan~W|}9@M)Qukc%=CqQ6Kz#``*@}rNIgjr4hwCT#qyx{qb_MY^dL_<;`t_>q!;6bm35BJ{bLe_iwEjuIKe9wU2MpDG;xfa!9-jc@%N)?#$#N7c}oG_6H)5BJy7L`q6>Vd%L#)dCslLmJ~%Q12%mh&SCdNoC=7xN!JhsQl=^PynXnE_`jgj={JAU79W1h1(9;!#0Ig)f66dgP-1lfa}1zv&A16ZBmM=!pnmWCj)S?#Pa-$ZS>8S;9&}dqzgWHL|L@ma&yxm{p~59wXOQQ34(mB8vSq{1y1}x{Z-{4nSa-SEA|K>VX)XR5c?Z~fqIuQ5CPX!QvC_VVjvYNrF|6Mdi;$zR7D}QWo1(nYF-REb}e>qvv-!|xkvGfB!=pufEw|uBOI*}CzI6)!lkuKc&;Vx%75IVf#-YyM@}j^+cGXR=oGZsY^@v>iORnkdk{p8d#Q3fkX9YGkpYDRaNFqWQ)OBF=s@XInUx4xK+jI>~D`38a3JbssatWfuED#+RLM?3ds@*E7F#zjaZOAe4Vpq)ZL>d3mG0ldBgc1Cjs5cMSLWi{62C59Ve-+sP5Zx1>IR>ihPl2nXf>(I0?!0(rs~qfL6QJ_XQmfz9Bu6{#LDy=L(86!Y^v8r^FDic}Y%k+I#+g9dj`vGblJ^(P|wO|G~}hf5Mu6{~mn~cm{MHDDti_UrStLDeEgRq8dr!v#p-b9Hia%^rvWhxNO#vpI6gfYLevs(*JuyX*DnD&?O%0{OS_gt?lQUgrWBgkoi05`E3X3zSYcHUV2vq*j8#U0BPhE4|HQU&Zi~9dgwV(OzM{xmNzwHw!}$AtSA^cR!Qo+MC3Vp>c_&$)|gUmf$~}W^liUtt|7Zz_w$y3sP||GBHrOY$mA6-=x6*%eRga=y*KtelMmZ7%k&%i&<=n4{XWgvOM%CN`A4^t^cGr|?s>KI4i#)A^J|qQ5Kjv8SC^hghpCp7IaZcvA3{(6hZF;(-H)1DRib?e-SFK@i{O=eb`C=bae;Hxpb9Z}aFRK7*0=P3_jmo8T9#_(9^{3A6O%B+7GQkotpB_6HswTCf4WjdjPr8(D|l+L2BX&__F9kgvTnJKOyyQU5RoC5PikzL@f4q7fntF;2;QD77oCjrT+7^~bM9a&*s3q7(i}ouD_bWuS2hdEHclle?#4W*l!IoYZ*23x;9RJJWkc%h{Bv9nT>Lek0$zh|b+j!Q&#|8TygM+L3TJgJ(l=EiZ^@NdoJO0Xf#Y?y!mrDbSL7cH_7Y%zzC^z8!$8D&J-#e(sriO-gZioJW5hxO+!HS4}Kjcei7xlHw;TraU}V)l-3$Z>xtmQHL`klm(OL?DG$6AijUmY30LKc@TMelG9fo@fU*QJ0iI#P#fBveb?rHc)#Yw&!QvyDO9LiapcPJbENeg-&45wFAY@Vzg&^ZN4#@mebXg51{@dr8>i)G_MphyuNwG=}Cm3y#XKF1;s?j2B%Ibw-C;qbyozYhkc!o6fpncsKt{!3cQMoZWz3v!dXmN@7lPl*2-Yj`v^kJV4)z!36*#C?4~pNmo8Ph*C}mo!q{;*PN+&zR>&uc6n;b_Wn2sOi@hCF%u?4a?WbA#S>FbNNqY255&a-ga~j;@rYw)(h941|N?V>ppEqJ?#}IXl=R^A#mYv$DUioG_+6SQ}bm%<5_i@8$=M_NeB)~rh&QfLQj_z*__AE<;2v5IiiHF%QeftTQm{x@4o!rZKoGY7q?y?_y3o^5odV6hr`;fDUTJRasTgrQTxnkV-mFfp4oEa3GVYZ?mJfZ38e#}D`UM3apxp`oyxFm@H%rz^^P~%^HQ=bm$z3wgen*n+Yh1L$_L|H+`TC9(sn@B*%tAes~9T#e^4PiM5XoE7gAkkm5}u#rr(|CqDN>w@zLX4v4n!=eKeEZZ-tTqWGgy84;+@cL#v!VV9mjK6{V_QT(Qbqv=~__$GY6yikAFb>Jei;EAa;cUV+JYj$AQ$ZSwSSCL52nyGCvKZDv?(l;S;^_)rJmRpRj*vl_$l=Zm&8y?8<;uWkyPlH_&d50V!ZY}|hMh9q+B^=`sXo7h81@J^^R}8_&NzrZxkL3-iEwOX+@nz6!UyrxhCl)w;I}~(e8Nvi@q%AIaS`YPaW;EJaji#g=-!>QP}s5@lK`5$$6cKVqPsNQ24T=#N^hXrH-Uk_MYD(!rcIvOZrDaU%a@;yeQitZq#xg`j3M~lyVQeT)m1M?PfUo8OHu0bZNM1DftZ+Xq9!l~9f8>v*}CzrFj{o>Biz;)kgnpY>rNp7xGv%Pkk4!_#xO<0W}KUw{4_x86h7!aJozQD8-d58_sC_d;csJ;n-nQ{T}rfjbmPr&sMd7P156i8lY%g*VCJm-=cXWO5HG*GhJByYH%#9J~R^(-x>gZ?c+z2lO|LrOkgp4)Yw!Ro`}*May5?L%wQJJ>3fJTO{#w*UQGf2gD%g0*<+q|CY$4$hudlJ`A^SL&F_fc-noaOnM#NI!lJq>&tlyik;fHwodFklp4n4KeUME&tfudjoPo~i@B{WLnExZjbg1Rsp&(|t^_?FnUns#x-1WnB0+i3`bN+W0aW~`O7VC;MFib4=?YM;a{O9xKs*h&FnT(XTo4z4#0z!5}srf+Y$~bSrye7kDPK|T96xhHvU9!moasLX#_~!LASo}fA$E^nO(oOcqM49_l?;7#)i(e2Ac<`-Tmw8^wn?9i%EQ4{Ud!BLfr<2bBq4O%#gnpTb-yOWq{C$=V-q-L)Jc)XQ)3ZMTh&n|s4a6gj9o|*b(g3F3wj7&}JdF}>sTzJT8)&(IgJoW0K2rTmqR_kWe5g1*k+<&(;u8WgOWD&YK=kto$U^?Mc)JCsfE*2WMVQx(1tR`_%QbG*AUY7|^{!Kh-!DD+MWuuR0<~c~zgi$p==}|BaEI+u?b$V=$Onjf!=~;qsChV$Dnim7np~mnaQ0FnY`1z{#pQuGq1SxtOB#GNmlwLaf;Kykp>&dATue5EzFEH0_7(Cgq8?^TaXt_ieE#W(E45!yxKu!aedbP55v2YvgsyU^JdJgK$}dCe|B@F`TFrdl>R^wm0s!x6CYo*2i`0^HBvot;P1ElGl#f$Mf9N+Ld0(G~qWG94aDP>*#}(cev_${Ts~zr#(4<6p~~<1tn+)(b+oftfsdLjlV1}3I6};jKX^~gdEKW*gJ#W*QI4ekFF#7+KQW@{Kt>hU?f|&_{**D|MBc2fO#x7av^d{h$2eigg>Au6y%Zqy=C#(NJtM>{+9;+p*qKn_*k6VAB%Qte*AUR8Z3u7uS4`_F=vzSIKD_d_Tg5oj5{qd`jU%maNFQ+V-1k@LWO_}zjxR&#PkB?&-tMB~RRJ70N&Npr=Pi6t-?jilh|oVoF;$WDA=1BcSP3afAxL+nrtFJCxpHw!J@yfesMoTenr%ouS-k^=GR%|nh@6U$@MgdXANh=`p^HWlI)O2dDlI3sp`oGZYJ$`mxa7#pW2r-Pp?wo?`!oFyu}#LX{(PkTxCcD;ye*?3;D@dKySd$ayopb+T?1ts81R&~xo^1KwI{R6A`0IGmVA_`gNq(mg}cH~1D=Son;2&fT3B#?gj6>M{SAfV>d}YL9Q+-AL+}w{z>Zu$Rnp-&T#U_XQ1copbii=Z|uvv-$+F+afr{%UYpPS>SP$T$4om7BZ_3WA>$$ICpkc}o47zJK-oMrC5*2Ynz-tsCvhwa@&k3Wb8@kxU0?{Y4>9My37V?pj1bef*OISzF{Mp6?_C`8kt;Xb>*fj=V@w?^g{Ee+Ce`JJ&ZOzasiN4VC180RQBwWATWKX?HC%Xea=Q_?>?xx{#+amPkFVk*9*~N58Woq;5@)s*?P+4Vd*@bE#xOa%PirsE^AoQC6x`_RWpEdAA)m558+Q~UJcQ94)^-TWN43g=m(8Gml4WeyxHRe5qj25}|Zhvt^91u)%z#qj1boM(f_N_LI8RCwL_T>SF_#Qg%6NDnjjXYYx%$|wGj^6*2JeDM89ho-0IwLPPV8~3h_DibV%)`We15Bm@&^1#-=@BtBOHxF$R{dMPJw%r2Rks#(HRoza~&Hg}>9;%v3g4B}o;tO|4`kB1Tj~YKu2cF~cJ8ZHLKko7^{Dwgej2Zr|(?5p%ij(;Q14adKy6DBRAyOU=D_-%D0z`kUdH;|nREHW^db`uW?1)y&^M{BVzWu^A(@X~ATQb`j8OK83hQpXqe@34c)C7x(=|Y02z*2>ois-%&vPe@l{X`T8`Y-BupSz}v#3?Y0i_WA#fOaZ6_a{m{$p`+Cve1@V7>`}|Z6IDD!cc@%~?b^UuYG3NW$c^z*&B#%5ce6>yctJf5mlpDJ-)QLPn+4X|dDjOO+WM6e=K``Q77n(nGSJL5IOn=}7WyDKQZ}`{R!GOM!^X*$m^<~4|z7c0u1cRtujN2GL@&rO3>i$R!RMA~aZ`UCoAoj<*>rz;Gs)D3GGFEZHo-KJ9z-ZjLMDio@gtW-;!OMzaJiYXUtvJuoS5W$2hi`27;ct0#XN`1tSmEPi$%Xr)Q=4wj$rj~HJPpB>(?X_m$ud?0?|)Q^j*v>uI|RzD0M0gN_-xyIb4eC=b2VXk-d=x;hFuFI8Q{A&nP=`%fMe#!PdcbEiCa*!3oCTDx<}x8>X$Fz8CqVz(krt}%$ps*%XzuZ(?=ARKJ!N}c*X)zf_X57ZLY9A4pdE<3nZ~?u*x$AJp1Tn~_d@H5;QHr@(6{G^me^sOzi6??x#M@!VD*j0Rf0yyqn>ay-VoW64T|dmZ{_om^25VyK4og;L-6OArTQd&&O#5FI~+$Tz?-)Cpluc6DG+L0G){&3Wt2_BUl9*IIr?GBkPhd^HCAM=An_300bdSp21tf~-ZO2Cxcj(_km5f#*!$?@%3dyvBQ4-P^!m|U=DCTXeD9ejj_(%?3Ou2c0PMl74Dk-cV?59M1v2-MTA`8K`^9Oq^X$JW;IrUd7OSsE*g?dJdk=UC*k}=UkW`7D)^@s@9+sieCr26{(L5{p7;BrySy9XMkhPFM?cZQ`Hajj4OOSa@-PXFPD5t?}ZxgSd{CMeDtzsjPUyw;MRm!;6yksn;_>Fk0&|I|Ij$r-Q*CMlKNdLPDW9{_Y=PWzp4z@M!P;&Uy45UnW2DD1xW8_a#8g1MMrOZ;&r}@Qh!!yPnF*x5>^${ExFql3qwyex6?x{Wal7v~Lx`^dCj7=6$3-wsAQZm48M-!#UmfvNnvTop|FK^Y3{Qd_8z7HD(E}U%}MOHh4)o{5bi!q;MPZrEk6GuBWZehTFjpHi-*al7aq4actIyQgrRYyhd^}bRTNJVCpaa*UKPArZA|s(t+g)R(SB3Vk)W5cJTp}Kf9pyqh>u~)#Sv1RKf~gQGx{IN61@ps;yMD(PJ7j{$lw|h51k58M`t;m8l?!Yo-eU>dk%v6)Zhum+s1Rx-*T@LnCGjHW_ts_uNqoy+0QxR3m#CQhK8rMNYmgY=OGclKExf=`%Hx0=x{-{T40cr2RmV;pk$rN05dsCv~3!xPwv|%1Bah`!?l%ecYdD1b#}1ncVBxJ4lWAE<5rP$#m#m_nD=HRf@to3o@8BoE^*K2;GG6GR>Gy}Uyw)j7D!cDJ;{Q-HEs(1exyDr(k?f)-pzwm16mS3W28E%;1u>$849rUOGrA3e_U3oZ@5SWLZ3{JlpnQpsBy%cn+~izi1&yqyNOIbQ)RIF5^6~xuh_UW;r;h#ZjkJ-|LfUET+e28Gyf8=P*`&@yd!uWeq_Ml76+Q+^s=vDiAt1mrfu~=&?wb(tzkQGZTwAs~=1+9d116h@8(r{PV*BAdU1Y>&#_^X$AaO+?*sdDbkJX~qnMh^EQ^ItT>Zz^q#%Cf?vMI+3MoMJdoO9kIN19$6_ZK984w}Gx$@6z9N!l;dPwzb4lDnmc^L6Go|}gi<`uxmZtsF6y@EPlekBICzXl40z((Q0zlQxWeB`y!V*nhf9i<@oi|5&y5hPC7g)d2qGY6LBJcF~2?=7{yjbCv^}f(n;3H=EH!ki+vU^;#G?u9yqat0-rA3U4Q#A@-(>(59H4<&u>akrRI4@BEI6MfmFqL8W4H?-dZGH_gCOj*R}+(K9X5#J%f2uMe8faxR<8_r`_o(GYa09b*U=eu$#$%{MzwD+etiR^h4l{cQDFZ1S8}-iYgvWMe--4xi^k08K|ze$xCAur>g1%r?WYOLH?(1#Fo_%Khd8rL6&*W{akuta0Gdj4U^XSZ!7|yo2z|oeR1*!S|1ADwcndUN%{Z;|1iHF2fE2uBE|zqeOnSLJ1U;1z{ShbGe)7vqb39SzrS6Y3FDk|+wzYfkJ`s{_=iMtp~7gos9+h!Z9;!#s9Dt&fd9PX_h}@(#3{Ayhtp;#pc*T>;QJWzlPzIuRpec1aK@*6X*TIzY5y+cA3JL3P;I!+1#fdtF{?iO7IYfE=@*Ls;%kAq{ZT1Fn*XH>l-*BBoJ!F)1II!wM4v^}+lJbn|*b|{@PnV0eBuSrh<#1?%R2noEcuhZULEd6@Z&3BEdlsmAoa!L>E_?xM*~ZD-INt&^ACqWt#aw+sGn$`!|Sxi)2rfuxc_&^$N58@DxCK6rozOAH;Ff8k++1)UiS4qoe4I%@##rPhzmEt3;xr&ES;{>LBwOES{sjZ6oTonen-3v@|kOaM~l`hp#srAM8_0y=5bQf){n_I9!*>=BlRg;<#uOj`DHo?@z>uoB;~8$eYHe=z|I+ZpI>Np`hw5hEM1`#Wf%-BJttDXV?u|gP$CwT-&L;6BlVRd`ZA{MNMY$tn4dsgb&sL@O-2Um`_pj=`AnJO)rFhNa#(uis;?1$did$PX6E@v>d5F}x1Wfw$-J*1TT20=QC%lVw@SM})@q{+ja647%Y*p%>hy0dR&g%d4xr}%M)Kw<(4v(dh$7RM8PKiQoq;1wsoL8Kh<&4>Aa=(ST}P1VVB^i;&#S6lrO;G@HaL&5{aUWiK)j#T#~+;F+Fd*mhZ6WUYprVZ{vK-rsAIH7WWc0H%g`WCJG6b+JwlC>XP(2pNaDF0*Tn+zfm%^y2s5vTc{w0&HY4sYdy)0z_z*ZMs0m?JA2iWI-P-Va1vo_bR@K`b9Qyi|O)+TnA0)qUQ=h3~~`WVq}!FpslB4Kv8Ea(31C@BI)2_u{@ynv(L{2_2_k{uod&Ueup=xO{fJ=!E`g!_j0o)3Ir_vL%im_!bhyVD8&D7o;r)ZNzI0ykGceXM=6Ii!DtIaYEPV{qUjLB?k{80kN%Mw&Jo9dkpWL1ntje!K|jvwpLMwigbLa}E7+6jsgG_NKO`9qe0_IocL*X6B>FD6K28FYhiX-kBp#UJMNjnklLnmW*AvE)F`gs(O}R1SZx+0^a@;veMII6rvUIQFgFLWuzV|PL)MqV@qLg|@i~^$^zb{?}Y5;I~gD?qw>W-3jJo68N8C*R|ICfNlr9U9Xi1aleoe_^;ed_!6saP-d%%vD)ZyPwPNzp)HvE-`O=~x);s0h$AtkTv(m=`tW2P`ghg1kbb4n0^lpQn=a+W^>DB$d(z~`v?|7!>CZhh?1u1r(%Q&vBsUcWK9>7pmwZM$r{8QFTeLbEipRaeQkyaEbaZh44!_cLuv75q7e+lzcIoef2#C`bq3sbWQuT|${Kdja{1vPwCgozX(HN9&Ol41!XOcdeDg?BKi|Q$8$WeS(qOu5?WP6+jN4qSzPcu$Bn##d1w{DdHPA)K)81=E6DsBQ>{HBCja%9t#jNE`(dtGz}43n4s5aOo_pw}^$CH3OIOb|Md1uygpw(UU3QZ@GM}$axYzrdL<~Dg$0jdKtQnA)m2QEvk$7z&tO{S-xoJ5lkyk1-Lxs{gOWIa9Bc6XFGAvP(4usy}!D7VYkI0_m7(4+60ZkV_d?)3x|D|S^cn870*eH9NHS!QbpSFoF1_nmUUw6^akDu~l{A$ff266S$rYH9hXC4QxH@r=UrTdoWO}F4YL|!`Qi)`SJ*jj$64#)F}-Y7Zem=95l?$SN;5Z9VNK4Nb~fuEtl@2$@uUYL}BP5K%Y)Z`}Hk7*!&rrp{<~ct#a9*Xlw#NYAgG!0p_uJoPUtS)4FTS`n{O@X>!1C$EhmuGQyd=f(B2-s?gZ{0cZx=dlcV$YZMZRrk<5AneEe7kS9Xr~6DI=2GCz))}vlrMUi!*?yN*vZ?UI!c)AK57)^$&-|l7_()y+l}m_+@5t8KsLp_GVPl;;gNK93aIy)#EWKOJcpH!G?4*B+ue8G$U}I&8n0ei@ZY~bOX@!&xj2m$-dq5Ob95Ag9)l^0#tCnnfaS{81d43{dQYpXu$m0N8Tp&m%kyJC7kk{4!Q56{6xDEf0?cI{`C|C!q%#sYfvHO&8Fv;zUB0X8uttE77|)_Xorf`?wW3Ujs~U#jy+T@rR89U?_uwtDl>W^tC?YO>*F>(t(%I>ZThbwNH5eQUq%LBCJvRP0Wm0FA4xr>X_ld9E&r{{fRO}0OA{V#;9L<@StV0f|kL(flWx0`ECW2Ng8VEEW|w#1vHcuvD3>OHYESV#z_9mhC{4s(0h7nAj09@-@03a@47vt{MM1Ad&cJnv@XyKhxSn&4HRk#rAwa~BwUTiDFKg7~G9u!j_u65(1Pz=gKJ&ET+$E{NI)>dt-a`DIe`I9BZstbdBTtH-5c^?OF61>yU8;6Re135H&IQ(mKy05mbi`ke2&AR%rb64TaVh7!$Y;(uNy-P+(tz<>ZC+Ui;@=u~X!TCffrz`0koulX?`3|n4JZE7bvc9cvwn}Cf?y?c0ijaJL!$lJS4VKf!elz<$KW#LEv)xElmh3+I*bQ-kUy|~&pjEeeZJigah9F`~VcF77poQLJ7nfsV$>JpCqZ}GWA-(QbY6yT~H=ZLAqbrSQM^iYAdf1JVbDbf$R+$HFs%g(p?uOf~o{A-QvNnowZw{mv;_9qWxThfD|RF(d2=fld`@vP5pVGOH&cFh=$57}?qyev5xrrxOPj{+x2<6F3pkI8c2MVU&3p(bD^&GAiR0H-=YM^#LV*>`Wv-RP@uMrQt#YPNL3@q#!TNTzTYtfO6N>>F#3T%lmjobA=+2xvmIPXUwhv~ckY7#uJ#qV3mIlOq+9V(HEBAsb1^uopxOq)RX~#I$ml1mJxzF=}cJ1uhz6Y59oVd}ryO`_0UehMKitjZ%dG`BrTomy{ikswLVPDj7Pp&RBO}avzQBEGFDEhGp)s7_v7cvOPm42&@#WZ7BM(C@<`W6W%azM954!TVWS?@m7-z={%kEdos!00QBw}oo?jW1ObQP1VA+@>_+V8(txlSO%4aH_&d72e~Nra=DE!`{{Qy~#D1=E=9<&i@L_UD)lecv?&^GFQ*Wv%g0vkaOY-($f5sMFaPzAa!_0a2gbiJ&{~9azK4Bw;@a3L5Mr!$x(RNqNnDH_IhiZnQ2z3TAfqa)Ihf%sEg`$?XW6pcKZFh4f*zPa7d3zZ9N#;7KE}#5253o<|o*KymNuF$&-l1xIF@Wnosu>Gqneu12UPZqU%u>r;oYR)|!JP*|C-XDxwZ)&?(fsYn^$cP@8%~={oyQb^_LKK`|MV3@V4S$P_zwF0&Hs8i(k6kcD5x|Rhh>YTP)Yq9+|f;gd&aRS=L&R5v?q5jAESabQRA~>q?v^_Wh+ad2uCXI99`5og?#8TuqA%HM+#yuJ-+ui`pLSqKN-m3IA!K5iXQS3t1)TZQko9mxA-v`n#gtjz1`D3{W(xKWwG#nHu}lDT+P%%s8mdymA*wkBY7~Axrqxeh7TTMcp+cSaHAho|565`%#s>GBJx<-Ii=fZy#NMi9f7`V^beIR)(k%%W0(4Ft2SX<-OGPp;Dmq}rHC4;ATF}$Yu}g;!&n&H?7UBL>5Vd>$#IhV!zovrMXb``lgr3VdR_#7k~VQMknS4k8aqrN0AV{iYFQpk-Ca_A{zVq7e#85vDBZej?~9eJ0mMEHyq5)3+pKK0dK^ca0T9sBX|q0#8Di>Rd_3|#x-~w-i~YW4qS)hxE}As37o_Yco%NOyYU{p7w^MOct38&2k=3B2p`5r@KJmWAIB%~Nqh>Q#%J(Zd=8(-7w|=V317xna0|YQui@+X2EK`J;oJBQzKieS`}hHVh#%p{_z8ZBpW)~D1%8QN;n(;Lev9AX_xJ<;h(F=a_zV7uzv1ur2mXnF;XhDI0|XQR000O8001EXJzjciMF0Q*ga7~l7623gZ(?(0a&}>KX>V?GUvO_}ZgehgaCrd$5CDV#00000002b*00000005ip7wQ`j$;eQ~P_3SlTAW;@Zl$1Z6KbfgqoAIaUsO_*m=~X4l#&V(cT3DEP6dh=XCxM+0{I%6ItsN46ag*N0AV{@6aWAK2mk;8Api)Ii=j>c004*p000jF6aZ;$VP|D>b7^{Ib1rUhc>w?r0Ehqp0000008Rh^000000GsR=>KhQr$WX>mt)7xvoLr=CrJ!z;X`-&9pq`drR8o|f7oT60k_r-cOUx-w1&SAEBo?Fs`5J~g3Pzeb3bhJk1Fi;f28Ip%3=9BJO9KQH000080000X0Kgd(FI4~l0FVFx01^Nc0ApcnZ(?d?V{~74VRCRTZg6=401yC>0000000010000000001+>=)`A5Xs0;#!#)El3JWxq;934Zj)xAuA`uymS0p-l$aNvUzCyx5_e0?DNY577iT0EqyqUGMmm~03bhIp050{jF7I>>`0sE2u{};F!qFZ8P)h>@6aWAK2mk;8ApjH||D;0z004mi0018V6aZvzUvF@9X>DnGWnXD-baH8Kb7^C9Ut@1_WiD=Tc>w?r0D%Ai0000007C!(000000GsR=>KhQr$WX>mt)7xvoLr=CrJ!DuWT>vApq`drR8o|f7oT60k_r-cOUx-w1&SAEBo?Fs`5Kx!3bhIp0WJmrP)h>@6aWAK2mk;8Apn9c_|roG004mi001Tc6aZvzUvF@9X>DnGWnXD-baH8Kb7^C9Uu0=>bZ>HWX>V?GE^csn0RRvHfdBvi00000LjV8(00000o9q|r8xYCJP{vTLo|0OeT%>NLpk9+?sIH@+o|a!!Qk0k%pI?-c3KDlq%qdO*}(?b9N0D%Ai02%-k0Az1pZ*X*JZE1RCUuAf7a%paJX=8IPZg6=401yCy000000000(000000001+>=)`A5Xs0;#!#)El3JWxq;934UXx^~uA`uymS0p-l$aNvUzCyx5_e0?DNY577iT0EqyqUGnmP)#3KRh@MgUMt0|XQR000O8001EXf-U&dLjV8(fdBvi7623gWN%+@aCB*HX?kT}W^!R|WpgfWaCrd$5CDMy00000002V(00000005ip7wQ`j$;eQ~P_3SlTAW;@Zl$1JlVqr_qoAIaUsO_*m=~X4l#&V(cT3DEP6dh=XCxM+0{I%6ItsN46ag+q08mQ<1QY-O00;m803iT^E%?(z0001i0000U02BaZZ(nb4bZKpAdSzc@VQg<=YGq?|Uw2`0a4v3ec>w?r0D%Ai0000007C!(000000GsR=>KhQr$WX>mt)7xvoLr=CrJ!DuWT>vApq`drR8o|f7oT60k_r-cOUx-w1&SAEBo?Fs`5Kx!3bhIp0WL-WP)h>@6aWAK2mk;8Api_qfO$&*004*p0015U6aZskY-wV0VRUJ4ZeMR=YGq?|UvqF_V`*+@E^csn0RRvHhyVZp00000O8@`>00000o9q|r8xYCJP{vTLo|0OeT%>NLpl*|9p{}E#o|a!!Qk0k%pI?-c3KDlq%qdO*}(?b9N0D%Ai03HAo0Az1pVQ_G4d0%gJbZlv5a$j;~YGq?|X>V>WZg6=401yCy000000000(000000001+>=)`A5Xs0;#!#)El3JWxq;934UXx^~uA`uymS0p-l$aNvUzCyx5_e0?DNY577iT0EqyqUGnmP)#3KRh@MgUMt0|XQR000O8001EXF>zM+MgRZ+hyVZp9sm>oZ(?(0a&~28UvO!7Wo%z{ZewL~bYW?3ba^graCrd$5CDh(00000002e+00000005ip7wQ`j$;eQ~P_3SlTAW;@Zl$1ZlV+i=qoAIaUsO_*m=~X4l#&V(cT3DEP6dh=XCxM+0{I%6ItsN46ag*<2yg%ZP)h>@6aWAK2mk;8Apn9c_|roG004mi000{R6aZvzUtw@?Yw?r0D%Ai0000007C!(000000GsR=>KhQr$WX>mt)7xvoLr=CrJ!DuWT>vApq`drR8o|f7oT60k_r-cOUx-w1&SAEBo?Fs`5Kx!3bhIp0WL-WP)h>@6aWAK2mk;8ApjH||D;0z004mi000XB6aaQ*a$;|DWiD=Tc>w?r0D%Ai0000007C!(000000GsR=>KhQr$WX>mt)7xvoLr=CrJ!DuWT>vApq`drR8o|f7oT60k_r-cOUx-w1&SAEBo?Fs`5Kx!3bhIp0WJmrP)h*<6ay3h000O8001EX>IWHfnH~TDASM6+4gdfE0000000000fB^si003!jbaH8Kb7^C9E^csnP)h*<6ay3h000O8001EXT51v|MgRZ+fB*mh82|tP0000000000fC1Sa003opbaH8Kb7^C9UvhL`W^!+Ba%E;NZg6=}O928D0~7!N00;m803iUp(R|OwApihiBLDys00000000000001h0csxr0A_MwZDn&`a&%vGZ*pa3E^csnP)h*<6ay3h000O8001EXJzjciMF0Q*ga7~l3IG5A0000000000fB|(u003}rX>N3LE^csnP)h*<6ay3h000O8001EX8}eu#aZm&RK+pyN761SM0000000000fC2VF003`db7gXNVRUJ4ZgXE^Z((v|E^csnP)h*<6ay3h000O8001EXap$=wxB&nFI0*m%EdT%j0000000000fB~S*WpZ|5bZKvHb6;?8X>N2bZg6=}O928D0~7!N00;m803iT9UV3Xq0001l0000j00000000000001h0aKL(0BLSyX=7z`UvO_}ZggK`VQpz{baH8Kb7^C9Ut?iyWq5RQX>N0AV{Vrpe$bYFL2a&RtgaCuNm0Rj{Q6aWAK2mk;8ApjH||D;0z004mi0018V0000000000004ji2$%!_WN%+@aCB*HX?kT}X>N3KX>N0AV{>0)Z*pZWZg6=}O928D0~7!N00;m803iT^E%?(z0001i0000c00000000000001h0i2iw0Az1pZ*X*JZE1RCUukZ1a%paJX=8I=WNCABZ*p{LZ*FrgZg6=}O928D0~7!N00;m803iT^E%?(z0001i0000Q00000000000001h0XLZh0Az1pZ*X*JZE1RCUuAf7a%paJX=8IPZg6=}O928D0~7!N00;m803iT^E%?(z0001i0000M00000000000001h0mhjG0Az1pZ*X*JZE1RCUuJS)ZDn&VZg6=}O928D0~7!N00;m803iT^E%?(z0001i0000U00000000000001h0a2O+0Az1pZ*X*JZE1RCUt?ixZ(?d?V{~74VRCRTZg6=}O928D0~7!N00;m803iSjT!48?0001p0000U00000000000001h0pywl0ApcnX<~9=bZKvHUvFY+Wn*+-b8ul}X>MmOZg6=}O928D0~7!N00;m803iT^E%?(z0001i0000U00000000000001h0e_nW0Az1pVQ_G4d0%gJbZlv5a$j;~YGq?|X>V>WZg6=}O928D0~7!N00;m803iS|aaQ+60001p0000U00000000000001h0TP@90B>S*WpZ|9WM6P;cx7x~b#7y2a&%#7ZghDrZg6=}O928D0~7!N00;m803iT^E%?(z0001i0000R00000000000001h0jQh=0Az1pVQ_G4d0%p6XLW30a%p;DbZKvHE^csnP)h*<6ay3h000O8001EX6dnJhLjV8(fdBvi3jhEB0000000000fB`t21ORqra$;|DWiD=Tc~DCQ1^@s602Kfg0MP{i0Jxn50000', } mrcal-2.4.1/doc/data/figueroa-overpass-looking-S/splined-0.scale0.35.cahvor000066400000000000000000000006131456301662300261740ustar00rootroot00000000000000Dimensions = 6016 4016 Model = CAHV = perspective, linear C = -0.0000000000 -0.0000000000 -0.0000000000 A = 0.0000000000 0.0000000000 1.0000000000 H = 706.6353735000 0.0000000000 3017.6396080000 V = 0.0000000000 720.6420364000 1957.2919280000 Hs = 706.6353735 Hc = 3017.639608 Vs = 720.6420364 Vc = 1957.291928 # this is hard-coded Theta = -1.5707963267948966 (-90.0 deg) mrcal-2.4.1/doc/data/figueroa-overpass-looking-S/splined-0.scale0.6.cahvor000066400000000000000000000006131456301662300261120ustar00rootroot00000000000000Dimensions = 6016 4016 Model = CAHV = perspective, linear C = -0.0000000000 -0.0000000000 -0.0000000000 A = 0.0000000000 0.0000000000 1.0000000000 H = 1211.3749260000 0.0000000000 3017.6396080000 V = 0.0000000000 1235.3863480000 1957.2919280000 Hs = 1211.374926 Hc = 3017.639608 Vs = 1235.386348 Vc = 1957.291928 # this is hard-coded Theta = -1.5707963267948966 (-90.0 deg) mrcal-2.4.1/doc/data/figueroa-overpass-looking-S/splined-1.cameramodel000066400000000000000000014113451456301662300256010ustar00rootroot00000000000000# generated on 2020-11-14 21:49:57 with /home/dima/jpl/deltapose-lite/calibrate-extrinsics --skip-outlier-rejection --correspondences /proc/self/fd/15 --regularization t --seedrt01 0 0 0 2.1335999999999999 0 0 --cam0pose identity --observed-pixel-uncertainty 1 data/board/splined.cameramodel data/board/splined.cameramodel # # # Npoints_all Npoints_ranged Noutliers rms_err rms_err_reprojectiononly expected_err_yaw__rad range_uncertainty_1000m rms_err_optimization_range rms_err_range # # 81 0 0 0.6134012329940268 0.6244081560660618 0.0006823949868365514 320.65554441161197 - - # # ## WARNING: the range uncertainty of target at 1000m is 320.7. This is almost certainly too high. This solve is not reliable { 'lensmodel': 'LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=30_Ny=20_fov_x_deg=170', # intrinsics are fx,fy,cx,cy,distortion0,distortion1,.... 'intrinsics': [ 2018.95821, 2058.977247, 3017.639608, 1957.291928, 0, 0, 0, 0, 0.09635712204, 0.09404657554, 0.9993324525, 0.1688631115, -1.963361845, -1.066081999, 1.784866335, 2.100520933, -4.549558728, -4.092381993, 2.990260121, 1.938631768, 0.1447273961, 0.005455009208, -0.0007978624287, -0.002625856292, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.07723829595, 0.4587187292, 0.09307439919, 0.2087216263, 0.0154881859, 0.1478380322, 0.03075235416, 0.151714017, 0.009480677967, 0.1351917582, 0.00496267885, 0.1220434297, -0.008887385655, 0.1024226858, -0.001797970523, 0.09394620416, -0.006597483547, 0.08531003869, -0.04241255281, 0.118083759, -0.1176137079, 0.1078155468, -0.0180819227, 0.01439416381, -0.1477293971, 0.0339973354, -0.09735680289, -0.09143395577, 0.03251740719, 0.1769533334, -0.1697681405, -0.2235771083, -0.7566250127, -0.7780820157, -1.163561119, 1.985702533, 0.5740964308, 0.7102922499, -4.080781858, 0.7043775289, 0.3326100905, -0.3531402915, -1.125717216, 0.171029503, -2.496750201, 1.408250358, 3.105442379, -0.8080020431, 0.8603659039, -0.6047581604, 0.04889229266, -0.03452608696, 0, 0, 0, 0, 0, 0, 0, 0, 0.106593189, 0.1903878446, 0.07263001549, 0.1748426878, 0.05928309832, 0.1619530564, 0.03463152943, 0.139738303, 0.01916137052, 0.1211786499, 0.004683647399, 0.1039241118, -0.005558456744, 0.08778651161, -0.014553423, 0.07217904772, -0.01917654001, 0.05777051572, -0.02211753539, 0.04368435374, -0.02435235608, 0.03215140756, -0.02719262059, 0.02108783229, -0.02535368344, 0.01164959443, -0.02653544432, 0.003357642448, -0.02577260251, -0.005230223969, -0.02551334949, -0.008855714774, -0.0243616719, -0.01522561806, -0.02620799436, -0.01949767245, -0.02968823581, -0.01983689428, -0.0325320036, -0.01964896884, -0.04070553867, -0.01736705832, -0.05612424757, -0.01346427185, -0.0506212512, -0.01356880388, -0.07966185716, -0.03507321498, 0.04643416257, -0.08758243721, -2.100671273, 1.851595772, 0, 0, 0, 0, 0, 0, 0, 0, 0.09827416703, 0.1773525688, 0.07957781201, 0.1597715965, 0.05532496377, 0.1400412196, 0.03850040001, 0.1240284792, 0.02182844105, 0.107118291, 0.009687563553, 0.09076553411, -0.0003010313564, 0.07573083952, -0.007757921785, 0.06080888471, -0.01334597214, 0.04688629048, -0.01706628109, 0.03382090614, -0.01853185534, 0.02150966469, -0.01834242355, 0.01083091725, -0.01805147958, 0.001095512199, -0.01637589968, -0.006925901978, -0.01507621959, -0.01338518392, -0.01421108924, -0.01914560431, -0.014159713, -0.02256569629, -0.01559807699, -0.02481221384, -0.01821663737, -0.02676862396, -0.02298393245, -0.027084363, -0.02982696901, -0.02691692839, -0.03765443655, -0.02545254502, -0.04948579404, -0.02343948422, -0.06718716787, -0.01321733397, -0.09513894061, -0.00342374663, 0.09387289911, -0.3198367686, 0, 0, 0, 0, 0, 0, 0, 0, 0.1132572837, 0.1701937131, 0.08094499012, 0.1415663358, 0.06097210158, 0.1269068421, 0.04175911472, 0.110134056, 0.02663357797, 0.09457872459, 0.01417381178, 0.07965904596, 0.004194565642, 0.06465693851, -0.003140550503, 0.05082771968, -0.008133466028, 0.0374583639, -0.01077704414, 0.02482337778, -0.01189002328, 0.01350274965, -0.01149660227, 0.002895900193, -0.009724580792, -0.006167833175, -0.007752157128, -0.01404249264, -0.005467243246, -0.02074738914, -0.003859635652, -0.02585906383, -0.003036398428, -0.02979426898, -0.003738739727, -0.03269356745, -0.006319119467, -0.03404477647, -0.01049467585, -0.03451846534, -0.01670391117, -0.03484241742, -0.02661008585, -0.03254870516, -0.03584725172, -0.03234924212, -0.05140963261, -0.02912230792, -0.05784922481, -0.03107184578, 0.2644884108, -0.2091787285, 0, 0, 0, 0, 0, 0, 0, 0, 0.1105296827, 0.1417490727, 0.08570172594, 0.1288273687, 0.0647431508, 0.1127681705, 0.04599275932, 0.0980788072, 0.03118897802, 0.08354628364, 0.01910071761, 0.06965198446, 0.009465356827, 0.056075619, 0.002273127795, 0.04278518502, -0.002405203258, 0.0299993863, -0.004836185975, 0.0183457877, -0.00516430417, 0.007252685572, -0.003923633304, -0.002378393649, -0.001750099328, -0.01145296694, 0.0009802747206, -0.01865353304, 0.003903770067, -0.02536468569, 0.006128240639, -0.03042893342, 0.007166165129, -0.03438120349, 0.006870648246, -0.03736100301, 0.005134589989, -0.0393370068, 0.0003288587426, -0.04014524447, -0.00571262535, -0.04037164433, -0.01445008419, -0.03964290917, -0.02528956168, -0.03856936806, -0.03955851775, -0.03453276268, -0.05691583543, -0.03570582529, -0.212541744, 0.1013578834, 0, 0, 0, 0, 0, 0, 0, 0, 0.1164652846, 0.1320387297, 0.09122237299, 0.114655301, 0.06968748331, 0.1009247711, 0.05155281291, 0.08734352803, 0.0365215952, 0.07411704656, 0.02432238385, 0.06110126119, 0.01480676724, 0.04839022236, 0.007838108273, 0.03625820171, 0.003393853204, 0.02461644359, 0.001414761411, 0.01349448824, 0.0016270763, 0.003359195883, 0.003019620652, -0.006185620272, 0.005992668022, -0.0144179108, 0.00912279472, -0.02186300102, 0.01273030054, -0.02799984866, 0.01508844997, -0.03306641021, 0.01697186547, -0.0374062945, 0.01693833186, -0.04014181724, 0.01460058362, -0.04250522035, 0.01103474137, -0.04381690829, 0.003884235165, -0.04406628024, -0.004094080685, -0.04522547713, -0.01536424256, -0.04339119372, -0.02794036694, -0.04503614188, -0.04558254593, -0.03676298184, 1.539656475, -1.509084379, 0, 0, 0, 0, 0, 0, 0, 0, 0.1247157359, 0.1152430677, 0.09636120605, 0.102441971, 0.07570863658, 0.08953293763, 0.05740940168, 0.07743338994, 0.04238288641, 0.06544587188, 0.03037175965, 0.05378818894, 0.02083727099, 0.0423744212, 0.01380635848, 0.03105911011, 0.009615608243, 0.02043141044, 0.008027550717, 0.01060824776, 0.008167499016, 0.0007973446349, 0.01032635044, -0.00775989646, 0.01358299839, -0.01560284089, 0.01707279874, -0.02232471351, 0.02087908869, -0.02880856698, 0.02381612568, -0.03385261981, 0.02559686664, -0.0381843708, 0.02561724979, -0.04168166637, 0.02390020741, -0.04442552365, 0.0194223361, -0.04606394895, 0.01321207923, -0.04801276714, 0.0039097553, -0.04761373519, -0.006090641665, -0.04964001714, -0.02257809945, -0.045461033, -0.02416566986, -0.0614656529, -1.652782383, 1.622163435, 0, 0, 0, 0, 0, 0, -0.04176399001, -0.05595229424, 0.1297166391, 0.103095833, 0.1034664328, 0.0900097314, 0.08269306707, 0.07918724385, 0.06393344167, 0.06819097361, 0.0493067202, 0.05767939762, 0.03670966603, 0.04723907924, 0.02737744285, 0.03705617179, 0.02032296548, 0.02717578004, 0.01603270797, 0.01741271408, 0.01457799982, 0.008556913647, 0.01505174702, -5.452027213e-05, 0.01734310434, -0.008037579638, 0.02054035906, -0.01545773383, 0.02468779882, -0.0223178977, 0.02830628269, -0.02811714312, 0.03164142551, -0.03356087393, 0.03344256916, -0.03806697897, 0.03350017607, -0.04186707738, 0.03131120354, -0.04499317465, 0.0273319347, -0.04805056419, 0.02031076149, -0.04904189132, 0.01169646835, -0.05194236588, 8.563795727e-05, -0.05159258701, -0.01269033796, -0.05455194061, -0.02774582105, -0.04984835749, -0.03989658725, -0.4577700447, 0, 0, 0, 0, 0, 0, -4.041555366, 0.2089655323, 0.139790502, 0.08614597936, 0.1109481138, 0.07889523535, 0.09021593164, 0.06862139671, 0.07180126534, 0.05938315843, 0.05663537317, 0.05012427534, 0.04421377032, 0.04113223483, 0.03441570572, 0.0321885796, 0.02764984797, 0.02380324687, 0.02318141513, 0.01524342647, 0.0215031292, 0.007286966337, 0.02208882264, -0.0003253186382, 0.02403642202, -0.007722187619, 0.02761188427, -0.01474216203, 0.03143625855, -0.02074483069, 0.0352901756, -0.02707251429, 0.0383406546, -0.03205638419, 0.04027975895, -0.03732216533, 0.03989637503, -0.04125023651, 0.03793534151, -0.0453285531, 0.03331952794, -0.04823068246, 0.02650354318, -0.05151137411, 0.01725144836, -0.05358358004, 0.006372523857, -0.05576537491, -0.007438691174, -0.05659888786, -0.02666086875, -0.05925160112, 0.05265710692, -0.04506823323, 0, 0, 0, 0, 0, 0, 1.094257702, -0.08826978383, 0.1331776124, 0.0779771202, 0.1217843347, 0.06649939911, 0.09829627751, 0.05858120901, 0.08003562922, 0.05055822526, 0.06460014405, 0.04279127656, 0.05207013248, 0.03501053272, 0.04239662023, 0.02768530638, 0.03501936873, 0.02020217957, 0.03061755638, 0.01321800481, 0.02872727617, 0.006254551862, 0.02905709645, -0.0006240418048, 0.03070783056, -0.007073018871, 0.03401157222, -0.01340271146, 0.03795746166, -0.01961458009, 0.04135593782, -0.02504503816, 0.04413886202, -0.0308378852, 0.04593373633, -0.03560923925, 0.0451638797, -0.04056033608, 0.04283417719, -0.04502902195, 0.03816890152, -0.04912836393, 0.03076435309, -0.0526395351, 0.02165786089, -0.05600439163, 0.009168217285, -0.05886471568, -0.003948484817, -0.06082386259, -0.02113208612, -0.06436793999, -0.1079787793, 0.4093102867, 0, 0, 0, 0, 0, 0, -0.3703176641, 0.1586074174, 0.1638659289, 0.05884524289, 0.1286303381, 0.05488772167, 0.1081564315, 0.04756687464, 0.08928640494, 0.04137650319, 0.07359868226, 0.03487260044, 0.06077678301, 0.02881987638, 0.05081690433, 0.02230002318, 0.04347417823, 0.01658599988, 0.03858947035, 0.01068381329, 0.03611722237, 0.004928732149, 0.03622523798, -0.001042091003, 0.03751957518, -0.006674106487, 0.04040408138, -0.01274002686, 0.04362552329, -0.01824836763, 0.04675854008, -0.02405915171, 0.04898631808, -0.02954036089, 0.05006153404, -0.03497091054, 0.04942055066, -0.04035362206, 0.04654034119, -0.04516019089, 0.04114120242, -0.04994123513, 0.03380244281, -0.05450063305, 0.02405020308, -0.05846558114, 0.01218393616, -0.06226221899, -0.001327810737, -0.06511681708, -0.0217587447, -0.06829481944, 0.5724201295, -0.7898476633, 0, 0, 0, 0, 0, 0, 0.05393333212, 0.1347798816, 0.155571798, 0.04895714235, 0.1409148516, 0.04185377852, 0.1179928015, 0.03645467331, 0.09866198363, 0.03164061198, 0.08328675609, 0.0263762775, 0.07016186045, 0.02142621108, 0.06005286451, 0.01659088684, 0.05194946562, 0.01192623276, 0.047042161, 0.007236507451, 0.04391585171, 0.002496664376, 0.04330544781, -0.002429866421, 0.04420011446, -0.007786536242, 0.04626325661, -0.01292878065, 0.0488575551, -0.01847768014, 0.05114126873, -0.0238069102, 0.05300460266, -0.02935658634, 0.05337547081, -0.03507907953, 0.05217184107, -0.04051013781, 0.04853226119, -0.04617643724, 0.04311091914, -0.05176840283, 0.03485289066, -0.05679029539, 0.02548022659, -0.06152761747, 0.01237756674, -0.0659787964, -0.00176037595, -0.0704146149, -0.01794948774, -0.07199698728, -0.7231995936, -0.5471051509, 0, 0, 0, 0, 0, 0, 0.9835229985, -0.2883370524, 0.1845343154, 0.03258271018, 0.1497463991, 0.02762858231, 0.1287970526, 0.02450706502, 0.1099534957, 0.02031308325, 0.09309481756, 0.01711571714, 0.08012349807, 0.01309109466, 0.0692040494, 0.00942366062, 0.06123839248, 0.005942740323, 0.05543303959, 0.00231639371, 0.05193221474, -0.001355387215, 0.05030759829, -0.00550089812, 0.05048200764, -0.009773523475, 0.05183424448, -0.01501939236, 0.05336504472, -0.01962225007, 0.05507225517, -0.02496794799, 0.05588151203, -0.03065696973, 0.05538221882, -0.03675715686, 0.05356398903, -0.04238645716, 0.04955630041, -0.04860268069, 0.04313218856, -0.05455162281, 0.03514290816, -0.06046165391, 0.02427088789, -0.06582678766, 0.01186981146, -0.07129430164, -0.00255848772, -0.0760949994, -0.02121650241, -0.07777880419, -0.09286296169, -0.5047771216, 0, 0, 0, 0, 0, 0, -0.2895879657, -0.04155432655, 0.1630786491, 0.02425667487, 0.165816294, 0.01230749664, 0.1401451585, 0.0104860352, 0.1207596027, 0.008282723379, 0.104565003, 0.005575895091, 0.09040442793, 0.003219816942, 0.07925214253, 0.000761653618, 0.07027124317, -0.001858808035, 0.06411061168, -0.004586671982, 0.05968831608, -0.007428635128, 0.05736995892, -0.01077583517, 0.05667967723, -0.014834825, 0.05681532988, -0.01869153717, 0.05742542189, -0.02380660716, 0.05807747988, -0.02874613225, 0.05789123837, -0.03427920561, 0.05671803738, -0.04030290256, 0.05366960261, -0.04617026504, 0.0492700324, -0.05256055269, 0.04218829224, -0.05911931312, 0.03337218582, -0.06539162161, 0.02321303526, -0.07115942102, 0.008424071587, -0.07758569428, -0.001042735336, -0.08034334445, -0.04650619228, -0.1011959189, -0.6533085765, -0.4534200701, 0, 0, 0, 0, 0, 0, 1.015581028, 0.5963993192, 0.2179286789, -0.007147345449, 0.1714407747, -0.00216547566, 0.1515193288, -0.003840335482, 0.1325437832, -0.006049669303, 0.1152979029, -0.006578448087, 0.1008805788, -0.008678514236, 0.08926792682, -0.0105246236, 0.08010672948, -0.01164608859, 0.07279585359, -0.01354178178, 0.06751685342, -0.01520046945, 0.06417025009, -0.01816628376, 0.06233602388, -0.02110883617, 0.06126543439, -0.02504178724, 0.0609725437, -0.02931545183, 0.06026395762, -0.03422195275, 0.05937655826, -0.03987272985, 0.05664568331, -0.04588675767, 0.05326608732, -0.05196763947, 0.04752199379, -0.05889017316, 0.04031891551, -0.06557295336, 0.03071674604, -0.07224841007, 0.01788847431, -0.07938106926, 0.006499789995, -0.08519995448, -0.01400775887, -0.09304281732, -0.0166711407, -0.09117684746, -7.484022921, -3.550389987, 0, 0, 0, 0, 0, 0, -8.843765872, 5.110548726, 0.278930404, -0.07119881069, 0.1751380606, -0.01172864124, 0.1691557237, -0.02481669518, 0.1460413727, -0.02166590648, 0.1273182723, -0.02336960853, 0.1127784768, -0.0218546998, 0.09934493716, -0.02265670327, 0.08879651644, -0.02242884298, 0.08110841279, -0.02462318631, 0.07534178037, -0.02641392389, 0.07062476711, -0.02795267476, 0.06793038093, -0.03098653122, 0.06572764462, -0.03402873429, 0.06374426041, -0.03804590365, 0.06214877666, -0.0427306082, 0.05897708398, -0.04815287957, 0.05667585052, -0.05384964734, 0.05116881826, -0.06043054304, 0.04519913627, -0.06718197033, 0.03669632579, -0.07414775932, 0.02716635728, -0.08083366947, 0.01566406042, -0.08759963632, -0.0008795191043, -0.09581608729, -0.01357702772, -0.1004239753, -0.0199494411, -0.1054453066, -4.396176392, -1.614527433, 0, 0, 0, 0, 0, 0, -1.339168334, 1.681459361, 0.09189498919, 0.06795067211, 0.2076090049, -0.05267875536, 0.1636307711, -0.02811851623, 0.1539159328, -0.04060859516, 0.1322212428, -0.03086413121, 0.1217569478, -0.03994607641, 0.1090713428, -0.03721418756, 0.09936029685, -0.04071430764, 0.09137270205, -0.03868925185, 0.08322093749, -0.03940230845, 0.07817038905, -0.04135410766, 0.07305088459, -0.04289820628, 0.06856097427, -0.04569961066, 0.06643813619, -0.04929738404, 0.06261795988, -0.05340363653, 0.06072796984, -0.05974493017, 0.05317946756, -0.06507894152, 0.0497203459, -0.07181334054, 0.0412292748, -0.0780710943, 0.03306471027, -0.08493315045, 0.02022729566, -0.0933410947, 0.006003119189, -0.1007565762, -0.002253881741, -0.1057750289, -0.0389249297, -0.1230398762, 0.007810154328, -0.08876671615, -5.877077423, -4.718382118, 0, 0, 0, 0, 0, 0, 0.2255763283, -0.04592560109, 1.865619955, -1.322007172, 0.09135394107, 0.07351293836, 0.2969998089, -0.1577147299, 0.151884313, -0.03075073955, 0.2050022496, -0.124382265, 0.1238422425, -0.03492443832, 0.1348652704, -0.07183956498, 0.0881407338, -0.02511851946, 0.08485749938, -0.05471932051, 0.07473529438, -0.0476523671, 0.07631740821, -0.05108694733, 0.07737988982, -0.05750576856, 0.08226959459, -0.0604626097, 0.06568113136, -0.06578445548, 0.06910464046, -0.06949748036, 0.04534324753, -0.0669851157, 0.06409184906, -0.07843071212, 0.04095703505, -0.08280518579, 0.03739912613, -0.09135442899, 0.02258708894, -0.1026198969, 0.0231945809, -0.09942749479, 0.00519668435, -0.114831579, -0.02155458705, -0.1203485509, -0.01550444873, -0.1335065117, -0.07000316347, -0.1165860665, 1.088586321, 0.3936259735, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.0004364328199, 0.005438202047, 0.4443877762, 1.387962343, -0.5581952769, -0.05789343172, 1.052411399, 0.6532268064, -0.989443637, -0.9260812409, 0.3777867216, 0.2422021111, 0.7174813992, 0.1808502179, -1.292215705, -0.4620976877, 6.878633109, 4.200690837, 0.1713457284, 0.1008723368, 0, 0, 0, 0,], 'valid_intrinsics_region': [ [ 207, 211 ], [ 207, 3381 ], [ 415, 3381 ], [ 622, 3592 ], [ 622, 3804 ], [ 5393, 3804 ], [ 5600, 3592 ], [ 5808, 3592 ], [ 5808, 211 ], [ 207, 211 ], ], # extrinsics are rt_fromref 'extrinsics': [ -0.003085813935, -0.02344039539, 0.01925826984, -2.122663466, -0.1269510497, -0.08424971908,], 'imagersize': [ 6016, 4016,], 'icam_intrinsics': 0, # The optimization inputs contain all the data used to compute this model. # This contains ALL the observations for ALL the cameras in the solve. The uses of # this are to be able to compute projection uncertainties, to visualize the # calibration-time geometry and to re-run the original optimization for # diagnostics. This is a big chunk of data that isn't useful for humans to # interpret, so it's stored in binary, compressed, and encoded to ascii in # base-85. Modifying the intrinsics of the model invalidates the optimization # inputs: the optimum implied by the inputs would no longer match the stored # parameters. Modifying the extrinsics is OK, however: if we move the camera # elsewhere, the original solve can still be used to represent the camera-relative # projection uncertainties 'optimization_inputs': b'P)h>@6aWAK2mk;8Apq(J8FQH)001B+000gE6aZ;%baH8Kb7^C9E^csn0RRvHASM6+00000nH~TD00000?V0yK)?fVp6%|n;87(T5QbJUcCmKc?Br}_gh^&n4L}p~~i;IiPyzKq7D=K?uBqNelh)N&dzu(dN93iJq0w=JimSTrOPyciPD?zI?9RKT%SUw@UrTz9h->HhE4muSk+{*{A1Eh9^i;{VxiAI1V4lrLfW^UTnFy6b9a$*yX!E4-$VWt#8FQLcW{q!8y~v$mE#zH*@zQ8q5=^+Jb(AsH)7@q4!jhCe7cxQHZ%lI5bH=T6<5;TzRtFuGt-uHy<`uC)50ev&_+k7SHP-T|#f{kE%V4_K!UK!7Yz3&K7)Z_cX%)?fd?}{+qVRalHE6SO6q`>i4OdLvZv(yh2%L2`DydPZ^Xn!$6!J=e5#c5UtEt(44J@PdRPw|K`y&v&Ah;YmzTV9vlfp0dAnSF*A{l?TKy82KrmbwDGCtwM5n<*Z=DO}VA}JCN8C;elPQ*UgAApx9)7}OWt%fnt)E^R?I{A@vrdOON>XtqT&ki{tQwlVUx&>dsK!gDd`sR%SHR$9A9I0>J@h{Y+b^-vrKk3#v386`pzk}HR_u8^wd6rzANB{wc@pd;&Hw)FOVZF{T_8MrMcY8|-nKpnLVSV=?SHO3@bh5Qr@MA2{B1+Fa-EU>kMHE7XiI>SYhh2HWGYS?j40c-KfdyG1Jvo+lQ5@0gFmwM*;gdF_*+yXM)bUSBM(79Mn9hzf^GbKT>2R-#dzfy7=t=mV#dMV=qvkHzLCftOD`9)eUWVee7H7#zvb50W#tL)G1dlc%_1Q1@ZM%;Hf`q`M`@b#*BUM|aW=#hwX9=jO`tt35I3XwH=;wE7BNB;8*}K1e|EZn72UoiOarXPcr;Pr_misrA9bVR#{;OiZ(vh!a#hgEHTQpv#tIP^`?t=2OD!$6xv5gP|tn9bYprl;hrxmAC$Q-$g>8)UXggUP<|IXqkY5hg80wZz4hYJ)!&B%^KY&v${^v7)@hf5CYVp%#Vx8+2-4Xz@kga`sVtBR|Sm`=<-7QW5sp%~d$~6cH)H$C7H6oyBvA=M?c?Eo6Wp8Be^@0mKlYW|rm%y#0w5})R!gwQ=p2TiY0I$iZ*BYDL(BP0%gzC{;0E>m)NALL~zmZ#?)0T8l;tHzla1255{@5F9cLhvz{iNW}%e~W}wGSE3a^@KN76drY{NIES{!8=c6UgR9oa0B?u|bseXCW2qKr%!&^%Wf!X@FTi@Y25N+}ouRNa%%`8`HoF!`D*B^Ra8@*Imn@#Gg7OaH74#s@l*J6Rmb35g>Xesb?s1t9!L4-WG2kUVbIrg!F#PT5HBZ^$^fl{2L()VsV4b@XkeY5`Nejd@58U8R?FXK4y8DgjpB-wrMGm@wM4~s>>bm*!cDCC)0#%q3(YingM!E?WX4c>@Nqq(*3L(l~8HjV%*JL2fIa&X$LG6L3n4v4KtS-VAfIT-0~_9RG$g{&>60TwgWOV_X9{^psaq6a-a;e782p!-~zq8K@m)-cG?{aeg&&U6@%g~3XESlmKUn;1-b)9{)ID+Wa*P8dab*S+h*nO98&U^10`F%AoPww8jx5G8_&x5a+pH40^&#ddvCAaFTmh!M(M7=)3+QV09`Ae&q2UBFpANa%W`v*1JJ~q2J77nl|%SIC!7ME_dMR=hm`(nGE_Rv3o4uKZN%-kuP_NM1$;w2)BjPs^EUpCh%|aCaWSh=AHWf#74yp=m@OJ>_U29^;d;+nmq2~3^98Y*~#gb3TAOihH=Bd?~{h;>A0lJOMIPAY7>PVRk0+z?4aV&F5xUW7Yj#)1RKH0Ia&hVxnea~|dS+x+jrTt{|$)_>wY9(ZUY)N-7JOL;HK<(>rN)(^9T+UL`7a(+(sL0lXLivK;azMF(BA&gd0DkLln(_M?|NJfXhlbw%}e?sF9*9;M!pZ}TPZlS%s+TRdjuVnRvxL1L!LP!HwW-0j5sq9U;SPrL&yu3uc0w^}6w>W%9fp0Kck|qn6(%0^3gqHg$>@*os9~|NI&Tt`)ioXyp$2HaOi><_-F%Z}M@LyTic?Z-D!k)Oz2z;kTxiGsf-yz{$Qep!XvfyG&NNe4Rs}#;2H1{$m6R1>c;#s}~N6LPyVSxW(i7o1w>~45C2!@}$L)djuR((27S(7R?zuO;ClO10K?!cDopsgYnk8l%}WUka8unaCB!0PzB^#>zpbAN=~?I{Ix-YP2-^&9SJ8tMgyFc|jN=DVaOc2ZVFe2!@Qiy))f`U6tn1P}(&i~J#eZwyrpRXA)mHpY<%L;_y`+Ek*L!xq7K`U1sM|G*^+y$>Gh@e_75Z9u5W)86)=B}4Hj!DSPa`xO)OxdjI|VlMMLsR^l|g`HiJ<02HncL+?L6;N2%Y8(z71m;ps%?#H2FmyxN+C5SAI!_YNLA8D70aIr-e$KLO;V%r8@cqcc61u(e$ITn`YI8>c_lqcdPV}LLh5%qmy&Tuv6pfw=VpK0_M7f*0}H6Y8xd{<(B78Lg>wH?c=fQ8gAcDWkqAm7S=({ZpEW?)T=yoK3Gn$G|419F32T9?k`aAM_`eJ>!8}#qfR>4H*nsSTDABN5I!kD@~A2gEB+uxUaun!q~TKb$@G9fKl6>$LNzcjD)=T^ur|?=7|^WdC%HHkxq~7p@3x26v(3VF)N}>R2FT6NDACoc51(+;*4*-Z&UT<65*FbsNG{WKkVdqMcSv51}Vnm3kA8M$nG>FS-C)hsiuRfE6Gu~rBZ;Uk|hH?=qQX`kbvicwyKf|88G>se`nDY0m%=@9%(l-pyS-$VX+J%#w=AAAMGLm!DBQ~oRfqDoPF7Lds5-!xajMNkPNiPj)uTn1fWvqcHme+Ix8L>DwvS%sf2Z<(M)n6M>WRf9D&VDJYo!o#v|I7?@YxjeT@|`k(oI=5paKZ+s^FqWK#6M6wok`RaBxP1nOBTkQVnJsGfLN2rY(T^*b-n64kRNCoPq(2}Ne)zD^fdr*L!45B9)O{b;GpxjfpUTE_i>z0a|kWnfEjcs(>^tZ-BoBGZ?t`!Ol`x@ugEQEuY*2Ox&9Oy6(3laYF5`3V>X6x-$AhO2!9&1C~k>)H)Vh-ks_5wgfyT!!fDbp?uNrGatiIaBq(Nl_R`qN538x7JO`;W!1x4(v+ZjrzU5K8cvgT6?B!$mJ-SiYI6ijo;jv8Ek@h?t!Nb{G27p{_E7(~3yK(>yW8$;@dGO?zI$z=Mp6y$8OF_YvTB-|+r~z1dj9mdWVC76Tqm1gQY`T(q*QA2U&Z0aQ}8&whW-!_ny^*}&fWsIYYM9A$exIyR_OsOyEIV1M%#qeuBjl+$sv;hsX94CRb5k5B*XFT>oKi`yLMAtWnG@{nx@KAxVY?MQeH7T50F%gIRs^-kyB&nN4FIdq_rEFTBy`trXYKCJ;!=W{po*rTD(=p5!J3lgZm%y~8&b>F!LtylG@1-@*LNGK+`Q_f~2N5g_vYI6n;Oe-qSgha$(XS>QQ#5iRnAt?cOw|F@+HagF)ysmtQEJ9rYx)p>sBLvHf(+$31q)N>R8a4E_t;Er1}I!IVL#|=k19#|Y_Iz=V0T8qA#R#yNG>fT(D;#oYmBY*XD~Rpyzn${O#QU66_s(Wkr~>tw+A5pFe`v2^6f31l_jmj-*3+Dp!E_9JIy8zspN0tm61*>?TN!O_;?;wJ-9kp4hOeEUEi#xw($@NHk<8l9O?mCVNn{q@N&mJM;w@8-)ZP6e0}Hlg#nEF8rzE4{ltU4SfioK}Y#OHivKS^eno(SP>Wu;R%|tZxSnsUGNzy`G8>wy1op8)<;U+6N}8dZHj&r|0vNi;ZxY+f_X4+zVhhCHn6ALM?1O`_f+E=nXURd$4+UJRsOOArwbA>kM_8a~9!PBq(06=mjVv_`{!fB)fHz^Y&s(@+(J8WilukC#r^p^6GCjwWzD&A@w`GH|L8nKlUJ&kl?#wyKnhj3TTAd@uUf~s$In$vB*`jsoQA$K-JCdo1$zkg*&{F;&tHanQF(+3jJ)91Di&(3VHR~V%VPbT7izqK9VPMI)~(?vr_A>m#2jPGABX23c5dYALlWNf9IJyRH+3OlB{evVzuL8c1BsuQdPa1ax}?@^V9%X-HwPBcaW-3#V*_w)H^sa=FAk{%GR7WSR=u>e&V8vO$HDI#6eAW<)*5VNT}hSFO}=&iukyf#&ah6V}-Q&Z#UCU`Wyo95s9^Vo>dcsneBG?;8J-1ix7o_{ROI?)1_&9~-#ue+f09dX;n#YW)#_+(tUN)LCO-H`lkSP$uEI{2Pd!2$A>VyY!4JhQb_`gUg-gcJwa?`-lw!UtLTD+9&At0&AfALxzJ95<#$JPKj#(PY3>zYjXRwywkEe4vpXJkwI)kFI@M-EU+mP?2NcXnrIZJFI+o>@D)(-VZ18nV3+V#-0(6nOxv3-=GeP565S#M+eSm=Yr$+?(slkG}g{vV{SR03(*!q_{LkTFBezxsQ~d4E{kyLzJrv}8;_3C~5MCNXn}VWbjtm&5n6=tZD!2e(7!qcUJE)Jaejj>H2lY%1Cn#UQV2#vid7fyu7w_r2>2VR$Huu|qT(9mMo>^lC6fphJ_+_p<5u-v_$DeoR0o~d6{i5asRC)L2qQ7DuOh^pm);Ogg>Fo2#mG)e)UVbX~b~F`79S3XvdWpv%zV?ofldCrSchzDKA6)x|538FSfx6PRsqf-R+#6r6QvT-U28vB$YtGr>`wGaMCI#gMvUsQ%4Q*D)#EW&Ut&^XtAqZ~zrqp#$KGu5>6$CvEyUi)W$Sr_g$U9wolXG4;6Qd8@|Qz5qR(en}z8L-}e-iQK*Me@OOq0OL2{k6F0CmA!(o-!I(YyfFPj~tGc&Hr1}Vg9V39?nh3sHHU%amSZ_{-oI&=%$H#(-)J7**47a_NNdY{tcRHwIO1PqPP>sYz3t6-Tkd{R|-0oJ>|=`EQ8pf$R{3sMAWfl3Kljj0eROq!+Tp(kVn6lxO%e))Y#Nn{P>Buk?icgwzUv?mFFY1_*0Q$DB)mVkPi%s%u6*ZsYu6o{kmu%1sLotoED5oXe`IO!n&0L5n9~0hXh8pl^p!=cdib*NUWn5r5p_EUJ-seB!z}-0u4lc7*BNbhaTOxC#dhVzenR?clh%koBifu_9-8ywmg{HKTadrn}@$WTAX_GDDe5@jmr_u6rAIDJR^3V1i!d0*Us}$aA_r@Mad)&vNS^e(y|oddc81%(oZ57pPYVLDpZ83xpJ24JSlMO?(lCagA$zSm-@tXBocT==uRtKE5~gCA!~{?k+ACWD2T;l@e9{{Q^G@c+8Rn-4^T@31QY-O00;m803iTcY7!NLpl*|9p{}E#o|a!!Qk0k%pI?-c3KDlq%qdOmP&;}WfUz+!$?bVq|6es%F4(NB@!u;l95CqRI*1I6_Rnx?D5)o*}Uv6JNf$j3*Y;<`&{R`ulwBhc|Nbl3A?7Nu6dK0=>gLt(c6~yEu2MVghgeo&Waur7PWG6c5yayyyfJ4+wy;LC9^yCE!X4sZOrakuI~>^o;`g``1Fxu!jFajpNoAZ?M_SpQ#Uk5-#nM1JO_DSb>c#2nqile;iib~6lm^PeQ)90hi02<-?q3jz$Pf@Bb!JkNDbWF{nlg-b{SkMzmr!38BsDnQmV;d{cH8}Qd1B5z3^%`wHW|<+y%+u19V8TVrZOpnuBoX91G6OQph>JQ7pcm44cimc%QR$p^I37%UI?h{ML4uz~7c}I~&VvU*N%m^rFQh+El#Zm+;0MtSy!8l}^oZZJfi?m+-qxlTN)sUX-^dx(Tk}BradM{YX9YG-ONRP#v_i9JxmOcg9on*Q7pe&!g^rYf%7mUe*xhzT$1!>y>ZC*)|B@S#6e-2!D?|sSu;r6UttF@$XEaUvI|>Kug=~i+s$pQ^dQ-9HJaidvuz!$2L|=iX64!@qkn*o2q`CVC3XfMT3O^cyFqN<44>Ho=SfACm1gk$F@u9<&yQLcs-B6%N%u(UEkVgMHaJWW9Xgx7HI6Wv;A&Zemkl%IWemE4l~2*XV5ccQO>(;jJpD{JYp36OYN{g%VK2Yt7_{eJphA`S-(7f(79AyHN8@QKxNIC|%=ewbkz9Nw^dwAx|>hF6Z=>JjR}vwqxLqs?kD@lCow^RLlCueYH24)UTzDY&f-J{+!@!6Xwk9*epvcsI8ES6r_Jau2$z2zU`-XW#jVhZV|bn&!>SvP8f_F$7k`Nsp$Q1#Uew2pLoVY`u_a+GQ8vYU-`aI&2Uq1@AcQZQ~2*okL*KHB38Mo-dZvzgV__`g6Mre&{|bUBtfSFeLnwEyCy>bhs+IO)y`8`@k}|$?gI&{3dk&}Y$TvrzLbqyNW`-K8(g%3ay)nH&$8Mt0whoW{#9r)g_(0V2d85x=q2VF@6twug2uf4mxtcLm6P<3pA^e+^I1h|;}QWPQzqO@uS}tNB3zc`3~;(Og(fU6--nL2A#>jH7KwZU7&bg9v}pPP)S`CRp*xW`DJ1bLxd;8T0wdy2L$aa)tIXH#K;*B6X9K+6RUyGIQwKY%Qe$@CEl0ybp3{$NiBLpK+sU(g3b}8)dS1%y#{!P5WS*8|{OvOP7hj0*!ie0I%{zrzQg0TfPxoN^UtgOx^IBm2b&Ku$d^23OxaP>;R)MO?k-yZgli+;le6}^$6bgpuD8A|HL5Z0&ha9x4pnWyl_48jMbYzLxCF)n8Z&X_c?Klbc@@{=z!a9W+60%tWI=vWf*{P~Yt%MID{UaCq$?&AJL{uCrFx#1;ye*dm{3)L-EZQegjhl32n6(dQ>xFMnwaVcnhv&(|VpM2kx?W9BsK6qTvA4bkWM~<346pw*iF*vFIZ1JS=pH>W)6Y@{$`60VHwM!{jh;}S9afJ2!d@k>FjGM|-^A5oX#(Y+9p}AK){li#z3)%mEd>qAsoL%#Do9pT`W|#E#hJ*^lLkj=@Xxe%)5bd!Xj*gl=;pHwd}i%Wyz-&~k|MrmE^VfPw!PfdBf5D=68p#K9#}vBWa3lStZ@wC+*o`}jDe=fUAy)E)`D-dyN87l4N|{7Q1cc^#L6dgLLr~2uuye}KP7z(Q$h(W&gU2?eMpg~@k=w@YGpNkb${K57qlDf`CfsUX8d60G6nQP%=61%k7CN#X#cp?eth51WwdHXhJY_RhH+gqaJ1QbpTqq-e0;*M_Fk6?wSG2sMZbnI=qbBani2!Qvz>gT$yl#T;X8AmWD6KDq!is=lz@X9jYn!`-8YA>FYt~H;;8_q=Gl)7oGh{-Y6P@FY-!Xa$6p%kxX`q_&8r&T7z~HnouGo%^@on8ngi&h!B_b~oPn06Q!+-oJ7Hk*cj%638l2=F_g;9{2<-7J@6UKrV58+;E)QM??s}rrB0}v)mNwp(!Z*8NFg$5ncWeuAk#8Q8zCeOa9KS2Q-jG3+TU?L-VIR8iM`zs4>c@6ESEBv5WI*CZPKtX=lsf?#&C@Y@G&syomI=+atadrl3NWLp_Ug!m}-gbq4eJk~P=+cHI43SxzFFfsF0{dO|DvfK`9#Q)vVpB1_DI-`(wo=94bG>=G0(w@5Kx+0lZ=ixqw0-3)Z@)nmGC)(_stCqBg;q{CUuK~A~ry`a%MCRboW0jrnZaZlELP+vJPVMiPT+bG{UrR5l~JRjk2DoBU07kM$7H~V35YO{vHKQfTz$+GI)ji_?T?$=i<25wxoD_Pz&0AEf!5*K#0!Ap5H9LNk#FW&)Q6h$2<^+X~AEKz($yq(!O&esLRW^uHVdCVoYwzp2d-@=b}|r}8s~=vcT_5A>tXg5`AJ$^d8_JW!W+rvrHR@FWBWj)A`YjPrzjGc3QHY`&bG05U5XYRNVIxGzSt_~*X?DA}zdza_f^9_5MLP)(iyn@4sWd#^Xc+%jv=DX(G}uh&!fnct5-p5jBs#P$2w?)H-T+X2lXJ6g20r{K$*nHyrd%|Q0>AZpiFgJ=rR2f3Vn3_W*kjL%~L#M;C~l0!PdGQJhJ@1KTpZ9N6rgJzJB8=f6H-wfxsa{XuB){ikJAwy`mAe`wYYH9ZC-9T0WtrFDTko7Np8#x%ree~$B}5n!qJ0b9Nc8N6@pr0jgjz@j1+&z{D9AaUtik4zMRsb0YHb4f2`f70=s(j5cAt9PI88KGh^kDi~?X98wr$M9dEH-Z1V7@gr81#sN^iqF4euP|03=p>$r1l`i6NUa$vrkE7=AqZ{RUr2o0?zB3kJi|7r|=>X}Gw7?PI!?Yl{{*fY)f|!IFECjB&!wo+mq234u6!gy!w{C_L5l_gniaKD6EtbCGci{t%wQPWKhJNQqA%i@;@YO<+8R`~V0t|u*@4zhd;RzXKJvUFpKF@*(r%k7i(1u`lu)+3AAq#jojDO@-c_TiOi4oHkXh)Mm_K(@oWZYr9B_`Z62P}SiQ%+3{!Nc7f^i7K9aglGAV5M0z=EchgODwiwYEHaq>>3$sZpGi@Ny~@akk%Ux`a@vjyZcP&+#L36HmuFC5OLOHl(pz;8(w%Xd8VSAj2>TD__-R2;kKDn0xk`Lo(yNU;Kn&L98mW9Y)Z!c4)+Q!g|wnmtWLa1H5m#1#zFf(m%@hBi25(#gHWS%?y=~RKlt#%{75;Of>ETVmA~IwP%X~4B%HGTJ`y>GI*H{_ah`bo%KHIu_r7w|oMRS0c5Ze!Za_mdwih>C`gdKvMBrMeZq_cheZuHElx$zkdRCp(NxQdfmKeNJcAKx>|HrJ+O+UelSgCzymdx=-JkBoIb=A>D1DSf_HOoPB{@!x%Nn+*Axk-WL{Z#-){sZ>W4SSDGVrJw=vnrGK%&SO{X}YwqWo)2h9N?6MFajC+GQidLf*7LVGr@CC{YzC>5Uv=br8Q}S%Bz9@NCJRleD&=0bEE6IAI-8gheTrpy)1ut41|FF3+1-S!94*RJSF!V#5$GuDIzRLL}SFf`d1V!^#(nqP-S^d>5`C=>P+%;F`ly`-OQcP8}Y(f?J=ZX;{O>k~dsbtZ!7i_IcWgTY-cuRN4Ai}&AGv8LRi47;gDi-MmcoatK!NaGH=e1rpmR^!~x7f3cwBz)zjz{W&RJGfKWZa4JO~-Du*|s5HyiATj2nF6P*cXSbcA~w;=WW?DOW3OY)x}t$0@7Fux1Ig33wKR-z3@6oN43Mv5{C|v!R}Q8K{&Vr$&P;y+Da{B(XH(#({gj5Zo|uthdSMu%%_-x>wJFABR!xrfB*%{30^vL?I@Mmo)YM|j2!7Z=DL;QLApdadTdJ%KEER``O<@qgj5H`5n>~J%oTol>qMbKVbeG0f_(SwJc?0)HenT|JIbvXuB>L80v&o!P(M|Zn@4x0v+ko$=LtaE4*9-WM}IFQkUKbb!zU$$vOfmaF^`TDh>CUQXQpI;l+cslQT=evXfz1!FR@#NsX`!nZ4cYf-QH66)j*OT0K!jOs!L{t@fkJShD1ah_W%{%|b+yj8gxx_55Z(Lx$(J#FGn<5)s}F$*rs`6@JW3L41B>_uC)o`l3_t@y(8lux}?CA1VU)3oQP7?^P;d0{=@`cTTzLt*t8n7G?LQ@9V+GNr_V_O@b4%|6Mtv*nPX_SJAN69MnKss;EOEnwh(&u0Gdwqnv{Hx-lX{irw~9Fr>7iUkk%y~-OcgnuqC7B^3I(U^|*$S?1n_GL2_#L&j%O6ofscZ93qvG*`I)Zz^h@Z?)~+OvHzy2A3yRy1?2z+T!}fE<7i`XJ_f*S^RC&Hlz5V6D*>FeBFJ?*eZNnKK~*CbJ<_&cD(Nf&Rxph$1Zi@B*C}M#%%^aQ-UR0w{*kjo~Q#0>-YHHnw`8`r5Q`|E_+J|_P|=o_e19eImZG$s#ihNcT=j4v`ZquW6t%U9CPNDqDUu>4UEd`wv7va0F8)W*PM;Y-taT5U8}Uabc_KJW?euCB+z(rYs|R!xZR=ePbO_kbJAa+rEnJ8svAeX-^_gBxSqUTJJ`9M{B_H;`z3knFSU`In^#txhyWY)!96G3}_{*G;`ps#D;Qx~_+`(pJ^qhsH3|#=I|CwI7O_>etLtvT;GEZej3nJka?mGEz~1EU)kOVo?e}58yskO&w+AgqsdVn=`)}ty*K&??E`F@x8!!%Sclf?o)c4SebD^gU+3~|D%R$;_i|(o;7p_0n$;-=q}~m^KqF4~gn*q8O7yVd{xLTch9CCQxr}do%q`gg(Y@xHZ-+B*#`qnb$uefNp0Y5UucJfkp{`>J-<=Xfb^szycDZBJT04Dx?#xvQiaIjcGxQ0(XHl6!k7pu|>&L-8D@^}|;Q~6&x^E{m6R{-mQDM{#66Qp{*fnfLK;}{1fpNKVur19B+qZulXipb<>F4G#;jvmnvlRvJyG00vY$0O!G0rP1R|qKR-YIu0q!QfCrWS2SMnOU}@rhH%EH)}$WbzB4;X5yuL)$kspx(X+v_C~axz$kRiNm$Pdgs*hy!a7V7Q1h(_j3|U&kCPW7i>dv;Cw1cuo%Y*dt^m!67U;~7}QKOKqY7WopYiCxNA}H(?Pu@C=0rmI?F`I%`+ZHk|+BiOPNJGR+0qO3!@X=W>a8R8~x8dkFm~A<6`@jmq5kk;$E>r8oIv{4z7snheSn*!{tl_Xi1feUrU;TdxJ}u(AtmJwvaf@s7rA0=}*TeWn|p*<=lYh;JR+aEtGPLY9VWuUFbpR6eJg)9JI~uLv!nhC`!OGgxzwSc#vF=`gFnlB9uYc=@T~f;z%*5_q}3$rZokP^{+>4W&4m@t6*%cei?WNn|=JwSK^l7cUp~RV0zSZ0F0QxaU9U!QLuIT2lj^RaVh<$=}SiFICe@dyp-L^22UjEUe1m^E+vM$$oORDW1)EjkLf(*DTVey&8Bt`Q{gk^8j%6YeH$5jmWME*w{!R9))C+@|5neIk%t|Q_5IyXW?>IQwqft4LAby3&C}Ph>+`gst^B?}BbdsT?6JIaJ>PmDoGZKtbJQY5`5sKc=wzh}x}2spR==g8*X4vw<>nH4I=aP=v7P{5~Ai1|0f`{@*-lFN3tM1=`Rc3=KgTss8&FDb3rh_^wHwM|dk+j0DDH}>g~{V4FbqDi%+oDC-`7rX{TgQ*6bTeuo(y9;C5}h80KQ6^r-1gR5`IGDZuP=Yqu>)_EzO-Ned80E70tp?nuK#SaU#+2S+VTXJ}y1l4`RcT5IM10zE5-I8%TPRcT~JQ|w^7jcUNL1l@M&>5bQ+tmuH#y+cmrpxg{`jXaBziII0T4{=wYDaM&^_Kp&dH5opF*qiW1oR-nowXnu^fc_CJkhGat3GY@0?E^$BAIofGlq_3Ha_BlY4fl+XYO0b1E??F0(|5cLt&zS*>MQ=(xk^vqP-tJn(C4rKa9XgtwVij~@Q31Caqo>AT}qsMZHp0x!-0d8WSRfX_Evd9$A_F>??!LvL|#r-wm&VpLyJcm=L48tQxLlCU*$lQWCS5HOz?lJNQOJJyn}k45+m0@WA)m~2$IQ(@*`$N+x+?&#sGiEtz8fR^K%YSi}k3H`iC!UKd&oAtT|VUbPb-@H>6dZ_TdxH8)df0R_i(KHnV9P<8-Hr8VX`EXvB0~t-WY}WAV9e`VO_N$JCDabxjNGfdYf{N$-;Vr`n&?R#%@A7IB&dwh(ZK0AeIjWeur-K3GBRMsiiHXRiwV}JCz76)@{AC}wkN~!F7RQeA{g0bvOLaF>(1kz48I0F`rrOV=q~;Sw_=|n0)1rZozU|H)(nrW9X7oqO6EX9sE<2kh1q;vXZk_k&hq-$`625}|xauoA%D+D^;}i|=?usc?zAgn$$qluBnHdmb{yc8Ekc68ngv2Tj(Qr}U*Z+NSCq!>|FHn?>htLVo++mjqS3eD#J8wyY&{l1Y{_*vHBJibElBvjg@JRXKN;|yiU3JQ+`~rMQRk5V+Y3S|6zV|{yI;dRAu~qp+!mG}2^yRf_n6+o4`6E6$j2=EXeqt>Fa#U$P8z|*C%IW&cF)|&D2A&@L5lO<|2mG1q-KdyUW!r70NQXnbDQlt*Ut#N#*pESj2Aq33_0pjs1=8Vb->x_^e!Ft-qv;40SM`;>CGWL?PSz1{iq3|Fwl?*4BqBc>vpD10TTsjB=eg)i#plN_U-4$5p<7O){BPqH=ruo^=h>bMaq>l)0jw?f;Pl*WdCw2PV_Zz+rcJ@w&kt%!&}HDvh+kWDfyfvH#ZRXke>~(xxIIM)2|PT?AOX5NOx9gs^%#*EcV=4;9>eIEcPMXj9T`AumQleGS24z6OGRsY*Oj51pteQrlxL!n=6B*)`ra9@jCN&si+m8+8Enb4t*P>pM^$M0jt9G7u$y>@$okGslM4XWYcGU;;Gw?R|URozi&;&{+=H(H)jh$dr~I;U2Y|Gj6Ype**=YhoqeyB-ltwxaMRT0_5J8?+l)XBQ!vd|(R0JcDR2kivLhC|~KR?~2RLQ9JVy)eztPphPFK|lHQo-eXTJdDz6xL=a_vjX-0NpJA#aZ(%d~SD9htrgdoUFq9BU}~m{wbGpc6S)uEay8>+&PKaqq#Ay@fA>!aU|(uMF$!L&-$gmp&(&Ssh_vD7S22Jol5)Yik6-2yNlSSkb7(0RGupVn4Jsb>S8)@==2Ylx5-p&uzW3E|E>Whq#T+>yMLgcfG)*dbrOTdZ&XH;sbH&6bj^?2fhTun8nEx9V0dc&&rv%9G#YFdub$b7%<>a=iyjj2nXje2@j9pX&5a)0_^$!KpGwR<{dxkw{k62Z-`N6t_G_nCGIwF`b%y)X6OFiiYh(K{RT8wjF7ZAK|BZdauYEgX$1p!N{fUn$2~I2q4vMXF0ty%(oj%ftwc{o-Q5VSYe^5&U1QY-O00;m803iT9UV3Xq0001l0000A02BalZ)t9Hb1rUhc>w?r0E7Sl0000007U=*000000GsR=>KhQr$WX>mt)7xvoLr=CrJ!yTYN)QGpq`drR8o|f7oT60k_r-cOUx-w1&SAEBo?Fs`5Kx!3bhIp0WJn0002-+0|XQR000O8001EX8}eu#aZm&RK+pyN7623gZ(?(0a&}>KX>V?GUt(`za%3)UaCrd$5CA~X1^@s60041N1ONa4005Mod0b83_x~kBqC`}vq-a7KBq~}6g(eD-G#XM;LMlljMWvE7D@EhI=Z+zzL{S+^gNUL*X`V!i-?{m`@4DYVe?1;=-aX&zan5V+bIx9`z4kum9cgS~WNOJb>C7Z=1qa7d_U;PWG77qf*D9=#Q8?`C?%{5G;*hJmgCmD;wRJw_Nb*xhZBIIqzbmS(U9&<)P4(YD8cHi<&ddCN{s=xbra7fIw2377(C=u13*G6%$7;zwlf8WbG6Nh#Q!W-QI5VKi;Gl;wQN6_DUusT*&LH)85DBRi!>46Uc%*{o&d|&E4GN+{vh0*(Q<;V#ZZtYQwv^@#i8NQ<^7JK*slvw}|3JZhW3^(TS6-6p&2Ly^O%PQSF>>eNCyJji}}*w5LAt0%!QE;Dc*1GE<>E_?COo6EoE47$c?GvSW~m>l^<*l9?z?8Pq!77~g<90YDFnQEa_~p_J>G=YAK+V3Vqf&HuFZ5AtnPecBi+ygDy)}mcL-SJ?WIg|nH|e>wF8fw+N!@Q>?ZE=UyO#C7^kD9Bj=phpa%yISQm2-vsACA17o@7~pT3p?QfIeMzZQC(%e{;4uUjHU1;e_X1;0Kc&j>u~!4M>%lHRj;`A$5}%N)a8S|S0djRnGEEyzPDRi75@puvH6kDIIMp|Yl6*_gEC@yh9UK{#Va{WvKT--w5tp1ApVOq_N$1w!F;`3j(&?AD&yVSy~^f%DJzclx3_wq@m(bvSmy^{KT(Q0uarHxmG^-Lfz+m&m&ea*TkjjdgqrpAhp~GTxP03Ns%K9$3l95#v0{8l;_?;xfrT55DZtP_5));LdbTp?=iig}bMGHd>LVf4Q$J%>(Yjw$xM%zGs%Izit4BSi_xlhq%cFZ{dk^+={_o~|d0`qnK9{*!ST2^!j|!Bo=%vv>?HqqaLm280)OZs6&4~{C7TGI|tw;Sw68g_utYyIZYPPMpHtJtpuu4U9ArpdSUKc+sxx?i)lr1xl3bCMg_Urp>=@c%{?GpK$Za{%s(>s(>ic#mojEile0#v9t?>iMEzlF9r({5At1N!vAN`X)c<$M_>Y8c0`&e=r5J0W{vXxfvyNP*!Pxbg(^D!Exja2fM~u3H4$EZZzs%i*`decs$FN%IFmz9Lew$4)moJKw%GgC=z?V0DhohpgU8iQxXk0{I_jlWu+>jf-i`UU=(!#V26wut__bzTO>ZI89$9WA=Kwb9-!(eVam!CV(!7?kLLgd=zDPlbOi(Zt+`j`+fZ^>z$$sJsi|yJGcF)WAD;+Kb*cPgLV7n?i&S~|K&wFXDM!==gdt83_(oXfviX5=Z^Y-g`iT>fzm~%^24h5upXdp4eWnFXu`ZQ}tm))~|(ZS)swD>f-D>r^^fU;(>3=?vUUz;`@cjEH%0-0NL&#}NO-KAJDa>T|t1f>oFaJ2lxNZR*%2vl(Ih!E25bsm}P5P@@FJC?rdjFr_YtlPa-yVNThY4z3s`B}1=mTF;nAacQU_nFfeg&0&jOUEEilVvT-~n^@^y2aJ?@gb2P?-XE7RAzc@4m+6Kcc30{F+6D_lD;!W0jB#9?8AcF@peOJCS{sGmu}7ZmNz;Az+Q%rG{m{(C5rB-CZ7QK?CQA#r->`WBlp%p~uDYbg*c6@H~F&f4oUAZrxJWPe}&MliSheS&H$8-fo)gPx?ut`i|*Q)a%^%HD`jpTV7&8F!jv5($(l^lFs}*K03sPfVk_*m-NuLv`vmK9oRtuqHR)9yx$FOydpW!2(F;Qtd2gBwp8TrYfb)IiWBhQOv=)sI^+)yMDV}PCP3LDrAtT}eaOfG9W&VjG$=fyYB&2lawEgqFE-2Qp#I`uKoB4LlWv3Igi9g}ShqYyKA4I8#SGD{<%^lHUu98(TqgPizXw@+Y33|oAGtNTFXts0<=66mSdDqK;cumhkX{neu-A*YlP@TnsT$>CP5i87(n|fq-j_b4GoZR4xUa$Z1OOu|+w=YwK&r*Q;s$~0$e$+D%)0MPpCl&5*xbgVXMbzV=L{a`mwztIjWu~Vx>Z#fEvc)umfM*pO!rXo!PkGR6^mH2yPV-Owyr2_xelI(6PMI990utRv+4-ixfy?Obw9tM?GhXnquvZsqjGNz^x~`=r{NeRp#U_B%pAKd4{Dp>YSywHpwf2%tsYxF25E>oxV-VCacwH@YXl=s_tgY2(_F7j!rymVAp2gCXsS&$podr>lks%Z@UjSF+61C>r$-uMlVrH(>(5_s-OK2IjkxLhaC11}s=IrDccTXbP8KjW0;l3!uRFv$n_g450q4RVRkN7*IiP?*ZDAO4P3=kS)1Tium_?+kg7s>d{x+{uviSK;{;GwFP6S|MrJn(}%@r5dS-?G+`I&U-E7I!ZSJz?!{W}c;j{yZ@#{RO$7@L+4rQaW(b?@%SS%h}7+RQ(MdA{fN|s4v*A*-Fz4CIvE}Zr+QofZ6Cb(o}ohVhzdpRucX4R?sxs3Iy^pnea`{SekvS2?S5t9d*n}lM5=9dAfQbB8O=Bl^>d!n%nt<2(QcpnV+ZQjm(UA2aF7P`A}YR5RYv{8mmV2tcG6&u#ZQeP8N4o=HvgTH7eI%{Q|HdRppNZguJ9fbDViz<|F$o_ByQzd?ou2@YB1hD*>V%+F9|`wh^*FLBzeDhu>=^WN&ezxkaGjrTL(7TWl5`Sm+$kt>9mP{guYtl!7x_^>g*+efE={@zZ3W0?wrtE7-mUBEYAxQ7b*Pe=a9`=PHWlv6fmkp60whV#wSH9=hds)GF4L<86QC4VleB3Hh@e%WF&A6f2n-e4SgmCI=(U$3!+7~rB+q!l8Db(@{X-@T`+GNE*CZOQEttn-}t>i)R)A`719_)DaJL>|(6ZO7$5Y-ldMopdsY^L^u>bu&73)00mwqkJwxfVrw7HA;1@sk5y#r!rY@)(bwerN(Jbp&pU-D*)3;}l}EY;7p;&Ei3MKR*o1dx}DvVH~njgmDPM?LIm6VLnCQ1m}FZ>QNPtfWIbz<6@Tne?fZ)jAQp$h+<4tmCd!pw~>C*YC}YX^nBE5b4obz;cFU*r3KhX)gnJulG0J_O^3O6?%jIM!0U440bf$IHUoCOQ@IyTV7uOZOuD8b$OPN#2J^PR!gg`|L`^#rtfY@`eLVy7vV!R|**&?GiTh#NbkteM&o7|hL4}-vo`^|TkRMi~{dyovfUH|s+BP2j>TQ%|x1-7VZ`Ovr-VgrcO?uMlyQPmUpuze>46Dzss6Rw7-uZ4i4bt+9#JB39{)Uw=`3ASr!CPf_%VXIL%bwMxz0gt73Zf{2aFtc*W$y6;GZ0h_{zSI-fiTa*pi|b9H!_fVZ@AG=Gj%2mBLg3Ue9nRe|M7&v^_~D*Emxs0<9A15Z9G6a;Yx2$Espkkfe(`?ChR(LHt~wVla5<+wxXGFV7LC8Q#EkR!gw=@xPj#rEGG(2j8WVYwNM^MJIsY}?U0%E25$h!D74luzlH--9&7?1vW@G%~ghvB4WInQIJ6JfJ#C4+A7K4(>>ZHGVMif7If_0d&NvUgEmoi|v^Rx$d7KCz-zwUuY#lwwE_)h8aw~Ywla_{#ur&a{B!0TE2!!6s8^V93{Tqos%X1{Qsz8&&odzZBSji-Qt8lMFt@&d@hYO8Q&h-~zyp-iH$FU6z&{g&8E9$`bKQ>Jd`7M|rlqqEFuo`{K@3ueRTW_);U%S*VI~#eQ+CI0kF*d9x|7D{Cu9tb4k2Nl+q5#X-Dm3sq`ig!P@%~{dnU8KfR5!>)UVNmp>A_wCE)=ZX7u${8<&?dbe<%!%Xj>9Zm>w2o8Y#OJk2*Lms~dmiPzzW1IA3A5kK4TwihPz0;@A0x-->q#Z+XQQv+_;a;i1W3kg`*SiD&&#Qs3?!1{@JI+X1bEhoK7ajUOSX6WjH1l%GcmtQR<7@KU(0~Tt38&1Q!qa+*werDvl^odNo88sjmdjA#W`0`ylN!{sp}ju)(J&Qc$;7e39`$HXbD*B`Am_xVVf$Rvla8j>LcgN>Zh_mp3lkY<+2nm@1EIynJUc&Ih9Ev%8Hm53~SDacCDj=(aWir7cHtvpS7M2zQy{NR>z|L{=vpegTKi8+(lyQMxMIOq`x3aEc`M*h{dH*`q4k&tWn3wfo$8jAQ023QmvS?bk>?Yh;y`E#Nj6HdyGvQGD6y9|!c(vH$+L4mW5OUQi8%Zhe$ip4CcAbeG1?=2V9Io*a|wq+Ip3P&T0pL|138KCCEJrzo!L(l$A8`6)Ue$G1I3^N9lrK?|O@YHP{Ebc3;5N5*mxJ++{li02uc4g(|6VUS-+xZ&?%ptryv@>Zxl4pZA{!*e)C0OIN%|Ke>CF@X?N@3@$&re1}KdZVK3nZ<)}sz2k)YRkU>j`sMU#0KwX)dh5`qaqgStf}|g&&vJ8?K%W*0k13r4beJyqI5JEH>o61d4LM#Z9a!3ZPwWbp8^=!DqOh3-%_in+uK&2i<~E9RvCas0uCB>wU_RXdPBk8mGxBlEA|P>}8d5%dq7I^*PeDmcEN4QG#FU4>;*YHxR(0H5kZRMkf0A4Qk4|C0HLasI`D*QLnc_XeG2XVO6K$BaAgnaJzUEsC=s@7sg-b&4A|TPes<<$9U7#vu$!tFkusO53@cGEU*cE%VqhXWeHwP=$WpoI_VwyoJEi77azUH0&ThN-u7YWqb89zay5B^m=kGpSa(i;|I5ECKo{KUGI1;l(ahfFh5V_&RvWx3z;LDeP^6U-dw_XPxarsPxS>F$|nMbzUH!nd`H(=nMlKm{i6-H2%=_=-Bq9!x_p<%@T7IhNO8yWU#s#gI4tzI8@Ugq&39{L44TnuS&wKjOo2pc(PeP6Jh1`^BKS3TpY+vtrSdG(iU@9Lc{8KQZ}Z|(2ZqBt>Naw79&i~;7s-;qBXl6Ns7L)<5}vm1Hfv-P*=7Az1?nry?&N#XKI>0e7++}SX@YIlo4Fy@i{{X&<|exSnRTQ_D;R>AXL-~N3{wFLnxp=CzQOUO%CwtbVYAYiue5BbCvYoBR_7?V1HVS1@1pnMU_~X?|wNvKRJH^8@|i+1?FaBzKeXZ;YIK$=_mcQQfWNvaT*!PLS1$Qyj>>gRsIP1;>Tx>9U|v_^doN^GgVNht4PlLE#@?M{GD%5m5w|uFu7(jy?ZnK$vmrgTg{~p`4M@E*Pm81pybJ$2m6Ts^pp80^_TsLUkq5vGF4v?i26C}7hP|eFqxbnDV@c99Y;}kWcQE-A5QLDn0^8CHD|x?;~50-pO-bUJBB(r`TaII4hI%j6^?vDE|5hFxcr^~`QRImLTpfHSw@2G74rJ}pO)0~8AR?Q|NC1<9Sy_+HJ&I(WB+UGJ$GwxrbBW39iufSsNXTGT>Zc5Sa30$Jum1L09Q8Mft*FU)NduYOLmR%7AWxLn_`KDe4ugxUTm!FSyQZ}4NYC!1!{4rL!HU+XfAL68ts&{3o3$=S*%_dZ`t)U>-oCx?ZjUu*zWT2p<8Bhd05ldGT&edc&8S*7%_SL#_dPT2lrATqVwL(=_|4RuwGGd%WPQ!ZaBT~eHf0uLM~~q?#gTeJgO_*<~O5%uvNEEl{Wg{{C5%Z4p#lX9MWHvT;^Y*q>cWeV6H(>Oa~q8H&rYf_QZOQ8{g5J>OBky7@D_E-w^lbl)r!bN?D2pqm0E$DXl?V&e;cM?8%0j4ye_z!F4q21bb-fq`-pq58^j$&~F&ki5?s&pu*KvqFX$9e2B`K-`UeF326SB-jMnL{lH(jcgc-yu(991Vr2`~TNJK7n%!H)U=9wcau|1nek{->ZPUa_^194y51seQVvpk{Ouy>x`7BOGuw=eU$QU-vIiJ7?D$kbAkwn*pQQAQja_-a}z(G1PxAi9EvC_M81COxweB(XwWa*ms-QKuSVNz?6d4eI>?Esb=?WQ&DGQA^iX530|V}aSZTF-V!VdtjL%n{m=N8zM{ukh1P9j!BaEQZ}6Gye=xL~%(JYykIGAt4^q4ey9fe;O>zhJv*T5Wo!u$nNH=NU0FuUfaLqY?t;~4C!D&E<}hFOc}?A{cR$mOp7uCafrsZbcz^->uR(g)XWPiq>4_*nNl?BrRGlX}@|KZ$%EnW33yD$s}Az9(>U;UhY$i`{mu?QtS>-{4xc%(fkrjB}T@E?PVtUYtFV629Lm05e^H9`s?tHvSZ(J?MsL_oHAxit2t)^kVNI$hjNz;u53yoAt6tnJf@@$-d+VsGqsp=_QKA1DRGsm9>iyR`tH^(Bs=g0i(B0&evx;k?%>ipIe^VX+`4nmDjAFYc)om#ut24xo*Af6Zp|Y3{OMpA+1>z^FK>^ZL!Ev@MzPip=x_*DH3ZE^o$2e&g-4P8IZFS>#xvZyN0Z*Srv|IOt1!W8o%fNQftasfmu#;HoX!G}@a%Cpg!%gVoS;pO{VZ5;@>ayuotUpJo0dQ7*i1lPmHMvxbkvzVFQ;MEJpx!kk-uA)pw4f9zPnu$r9o@_`^}pZkatv?o79qdN3q8{y6Fv9&DW|V!{BovId_#CDea7MIhtv6eb*2mwa=G$45y_Tk()mM*8Y*@9M>k*sfdCe9Z@wSkT-oO21Z%K7>-ukSR1J;DOHZ+$bvQmnzTuZb>CT?uf0)J0;XG?{loJ7(-iC6LP<7fLI+MuQ=flQh{asQ=EwRi9*L(!puC#-gJGIp@!L(R9$09_=}ig!;ehD*t(-%7EfW{XI5^QNNJsLMQ$A4B+hh7}P`kUT$Br+(MXe6r_Q9Ikj3Q(odSHNUsE7Nx%ffnDEfpKGdueFqNos};J^05IpkLpZyE+|AV9G)qI7c;`iB{RawFzHBVhNd>@*v7^ba;uf1a?np~2=dlT0ZWp7)Px$^sh2=&*ce<8j4c^aGp7fiJ(C4rxw#GYYQYJ{*s(J9B5Y|GVy@4(P`Obe?BA&SXK?=+r#h)#%594u1TYzmE+O({fo;599u7LV6^}T9XPX2QS}rjmG@Gaa-2@9zFsj_9w*m8zAS@p+wIS;FA4J_jfPPI?->*#Y+4%;QLXTar_$co;O=I3#ZcH$d+pT3*xwbv{39WCHxQ_rqdJmOGRV7<@=c*QJvZh@S90@v=l&YEfO9pro)7T5*=HN?6Gd+dExP1O?wu+5J*4Cq+|bonl8gKVzHsVJwB;w82uPI{d9Q}L4^{DeWjIZ=qtj~O+P(WCxEnTJ}e33H88kNgY?M?A1n-F#<8yQE%RI`tffKX8$YjiUy$z=ylA!kBMs^!3)^&`AfKdlP5j7hIxLMBd%QLo>o!Bz<_`6qVt`I@^{q#q7=L+V%vO63CP)VsjYU~td_esa3F8>n#5(VCE#%E|{9;KAKujZ{@>BYU}2ivINSh`haLlOFx%gdxq*#`+YW#E)--hfUZ9`80KViVXUPp(j??O8f~(%DHsOXbbXRwSmJM#t6tzWsA%@iCp)Nb6MpTa{l`_$61=PHPrUbWRto)(?bY~#?Gy%FoT};wPMG(*6LnXl$1_1mPGwSlF~-;JEU0hGWWnQU=R4ArQ@HU_whcn}>ez6pVasj1J1N|F^07GcN{g7N!{qbSHx`l;@$h5X{V!YX0GnoboLCac0rSQB?ceSN%>d@gge=A#vXZ^za!xt)zoad_f=7tP0zm)5+X$m}Md;m(f(aXxt7AKgo3+aHnRuz~a0BQKG^lAU*8hAIub$pn)lgXgVN-P~NyAn)f==9(yfP4zM<0^1g*~WwoCV3pf}+0cz3iU`FVwT3eA;3U9ZciqU&b2E&D}R&opfAj(Ew1}f59`yE#&&Yv_iL{5+J@K2*E#Taw2|{%ofn-&v&=AGQ&v=3P9yWqf^{>!>CMPJg&otsComvly6m-z%jg3&T>h4++cRO+r=`=(v@u`Xznzi%QHKSYi4}SglhV2Id;Fh&IjO*grh4i8Iq!M)=RCb~pZ`1om6nI+xF@2{D^ew?-i-u&99J$pD}Z_!)AwJTZ$tx!n@6mDdEU!=H{V(AdkGD;Zw}eCkPrLWeD8+xPO`l(rPhQmh(xaU+^uO&3mquS4+lhRp#BTT%#s>{7~tU>+&rlb`HJ?iLYMe(O(&`(S;?c;0Cv4x*Qd{&PD~|MD557*o;wQNsN1{=`iO0d8HRL>q^L}&GEYulqv~AK~bJ9OF2g!tnAQx(>Z`FE9n|K~A7okoScayz)4e4-WUbyXeE^_hh^7oBv>2TccBDK#R^)DCo&Dib6fWx9T`$`t0e(H>4A>j*|5dYI@TSgah^GyAE@hT>~_4CqjdWr37)z1@5zQuy&n%;L>ndq;o?fO(T_fg^E?SPrb-l4CMm>wPaP>7hA-{tP+d5`9eZ)$}v0S}*rPamM8uLzW&p4&K?1~Zo``d;TlUopxI{_`w`^cw@O)+nq-|6rFG#oV=n4ioDe+tELqw_2pUe-Q&BwF)c5dG_Hf4-~667Gh59f2it5Kh|V$r$~DlIX}8>a7-)!{aA;*nm~mE8@kLMNMC;W-+I|wz3HA+Pg_f=@J_7m=a>zTuaK$ezGX;2!t(7i`h}72nR7yY{}Td&r9w6fQPB@@-h+F*l?DgJMB~ErdEO_=Dl0hELW8cSvtQS}#C^#23Xi8Oj-&tkeGS%;m@WOxZ1VbY_U*fcU>&AYy54HN6BAzKo)y|&j{VtREhn@qhz0!T&iuO7js3Zg|K^oVZ`t7Q8oS|R5B6uHR>6<=Vg#6{pHNZhME`JFDpTq71p;z~?#di}g*@9LPrhk{fX>k8Yb-O72h2VE!H%5&a^8Uiu9v>?`eWHm3ti>*v!3d#uCcJ}5b|Ntgj=MRa!GIF0d~_u8&CGk~<4Gs^=peryqQFSVWt6#}lacg10R@LtQ0g?%g#O>h)TCNTcT+YNhUR^-A{7nd(HULY6UCVh3tg_w9BmU#mGLtIGI?Qic1SZ{xbo)LzevyZE67Y!WUosPUI8ZxO!~U{DYnNn6R<$=MOPIj4x^YF~zKh33a2g$!X6pKKA>|v5`?0Om%Vp=`4bI^T)aC154#|p|pQ@m0v5N`xyOJxzmL>vxxS3FGmDyo&A{j?=*OujOE;8S>H18YU^^yug#`_H1qfo|m&;m+clYG_5A*48xzp@HC{NvhnR7V7C5s%FUV5~f&%=E8v-wB4h6Mv&mD`S74nRFu{(A5)5oH4VqsnSmo;>cKak%!+HzsiARll#H580vjrAw@a1!wcDW4|xKe8>52jNk{-KL=+X%6N|cN^AELX^RR1{=WXvK3s`9qqBogZquMa$mVgCc|7$E6}Og)KKE#_j34GN4n{5^H}|r-0v%%dc8m`V^VH4u=WaA))8T^3LiO4cJnyv`C2ULB$AD$J$#uO0$mL!AVl-wkC-xO2Tt=Oo?*v6xGvUFD^#`BJW4>;SoL`(qut53CjQqA5^jF(BFWM%vp*&vYnqfHR>x@s-$&$?k>^CTE|5}SW3qFtcJ8h%E?*o(jj_9Bs+136bi*soZrYU!+foH$a_isj94r|b1n{NH9Avx^lkrvzJ$@!$;xZEz{nT6aVcIpQ=^7^*g&C31_s6Tw$Nx5@>8PIJP+p(t^xp4CKS0xXbVD!QK)7>c4|LEgzmCqFxXm5;@ls8Aeu{pvr|C>E~Vm+dHG5U?a2VRCM{UBhI-fn7E1?n$28YW)0mu%NqQDK}8>TJt4S$C$G2A^j9IJB6J-2BU%zEEvCSg$;L*k1>Aa^9n$knQ#TI%!nuHS$^KrfB&ZGeFA1NaXwp)c@vUt3XUQ1CE?8Q|p&R{kHe_X*$O-;pT8$P;x!;9FukON&8qZGmcN?=v{1=jE`bv=u$Qm6p70(^2+A&RIP?>XJn}mxAtLUWfD*Qf%DTs1@?~(7HJ~LtLp|eH`@>ppseX_>VrPvwC>?MZKU6xk+v$Js|5X6A-yV9*Mpp2^olbyhtQAR5-|U3u!IgXyW%tN5q3vx<@Ozi%>B@(7oBJ|)i_9e1peg^%%6%jHF8+hRCy&NZ!F%Y+Zvh$f1FNnDz3No`=bzKcFz;{KI(?~GDgobLrT^M~6uGIEY125FmtRXp?7uzC^L-U^T*x8shv%oSFBf*h^(OtF;v0+4(7{4f|5J1o_UDMDVEjG1gw+1JI|F*}iUf@K78P|t}8f1_^e41yKI-Q*7y0vzlZ^ydL;^jYG`pEk{@2%DS%2ce|oL*mfS}1}6*G!$KelkPuR-&qKGLQ*7pI+9bccUNUT$kKCtch{&&{^cAJG6rM8rjfj5)$3>9pB3q@Q`<@)g(ZhK2UBt1AW5Jziv-;lL!!=qjleFHqSoTg~u;!7N>#AsYfebiy^1i<>|>L(_n?-tg=~B$OWHNzcB$iEYWebx0mC2-`QmE*(oD*SgIhJE4v(ds)S5s_Dcr%^(E^w)Ua;Dsdwb&F(Gz3@#32%#-9q9)$;NU3pn3tD_?{0X(BI{`A^G*Ip!hOt*eo9z7r&CPr#bV{g3wOq;QWTaG>jl+A9M1=7-9>+Kb$5Uc0CgIWLg^vPt^lS>(%zb<^*@p@Bl6iS`$s^`kkvav3@qPw&1bB6O6wzIz4>#H3DwbTMkLvWBiTb>hDK}$@zlah5C?4AdA%IhlANJ+(MF+|qW=YT{#=~wN|K_siJY|0<4GO8@OZN%ld9Nndy!;|chh2h?@^@O{dHK8U?jFpb!_^VVeLr$B-k3DX+PfK0_er-VLlX52ominLIhP3q#^1|#1!I0x53h3mK>Dlh**8Ca=0_h=9cMPkBK_6up4T6wE@OVojJx(^Ndp^V*%utsgfS1E{dt^j{F;DwP6iG3A*jdc(==AJCJiR(Xt{)bMxLu2)McMRgX@=CdvyUQ~^ph69J#^&-&@XMY%ky^l!~|944AHC6sQ+jB6YF!2Srhg1*J>Huc+UE}DU}W0$$s6Fc-G7AcMV;7-A;h}^XF!^JoT9|*JV0~jcFj!x#;%LcjOoM&yt?|ga#QuIy|j*qt4=sH&&d~CCA&EQ&ry2k?WgkdOa+qgJYPfM*Jq!X=HGGmY6*Q42RT%jmoiI*&#GhYhfm+TQ*#1utA*(NB1sqDQ5!bz1smk^czdJY4h)mV?k1A=`5=pxzbgS**ESy?;uA>~P~GsPy+Cf@7p_eGt`>lA)S+S4Y!YZvhi`4o%0dv)H@Am*K;n%M!=KmO72$#z3JaP~n6^V9=3lwF@5+x^Nd)c;lQ6O1#NK#9-S*t8k-k9Kz!nw?=mOKs}MO}~*BMvAF;Z)L+gy^;pa$LOzix?WIuq)mZHsYMrU2ps1RlRx)*D8L>Zum0(PqpR$@G7-Yq!7oZuyKcpq}U&vkAQ8~#*#cHC>j{yFl{*<(*96%yi;ADrTuk87VX4Z3SZ!2HP%pH=eI+n)^m_%^qSm{`YI`V;e1!0cuF2gv!9!pA}>#b%!OtU1@EkM^(spJP7#eX8=7w(hX%7a51uyWQ_jBXU>*9zcmK+H;x84JB|j(UL7eLotb*}%SAyN_av5OvxXmJmXMe0|Nc4$_cqXhDth-B$V}7qVwB%G#5(|EK+a-9t!s|jd|D$Cg8#w)!&Qm|JSY7+4$Bh7Klk(Y2EgXmE+>dlF`b0qS%Eg8cO^~--_V83BuOsI(z`Ktkx4u*`G|)r?A(u&OBzX24E2s%%`}ojdETg|FBntDd$pJZkmz4}C5I@9JNXK|mp5oXr1IWwMIGc&_WEyh%QOg9ui&kGn9$-A@IW2z20v&R|s-s{$=Q~c1I@uHViC6^kFZx5rT{FmekWSO1SZ&NB5b(hLsTd8Oj{KSS$p*PHWm={GWYU2+Gw+)x&;A)s|JU0w;OFkRc-|jDHyX+*NEl4cb=?T@B|s4(I!*CFFdzjrbj!k%WBT3#$cIJL!;~J{qM`hnzFcRJM@wBf|Zt+1yO-dDq8W80rpVz^0h3k)0-(XUTMP@w71$IOFctYZxD-DDOH;js?Fi?~PbmjPYbQIK>OGf%7;$8^CySn4i2uI2R`Jm_!zrbH49%einHhpBl!BOY!&sdR{g+{=|pt?;b2*gQ$IsZ-*uN3fH-p3b&KeIXqpOO8tAL?ZvZA**6i5*;}66?QA~ZHou_rm8XEb^aChzBE(=JBwwFkNR&~!`WRbQ4|*V4>^zx%EVznqGkvrN-9mohQlZcoKLSiSYMcKSRjJh{Ena^*_&6`W!GoGbyFq`}yE2lL}A_xkp}Y68j{eB@%kW1VC>Iq)l_(*CUnZ9!kb8JDzg(I>8Zoj&>s&iw|NWPiFJ4R`r~^&czu2BlW#Z1_8^yJm3_`T-^H9qYtpa-f1azWmY+J`(crHV@w;#cNG%=oY-_D~mChn68?ta&%iTnIj13B-w+-df+3;XSFlDR9B3&Adi(T><}XFPqTtMmz}GTbJm-m=Mup2n<9@f@7rdmG%a(Wft8NgT)W#C&&g+-SI~iT-I9)BeA3H5=LY67Kyc^%)0gBhek*CT%@;8z@^u)Gf8+Sbty@_W<92`n^1jB$Yv(9XAl^hOD|II3@n4T-{XI8Cfn(3L=KT>x&Uw!?{38_(j=x{JR|>i3MtvuLcLL6}=N+(Iiri;rX9+`)2GifE`mE;Roc0`gNP`QcF?+Wd{QyHSj_;{I9XQ|J>7I@8>EvUfbd2#YPxYZ6WSwU{a?T58Oi$BZyp#QKMDi#*_4U*8lKHXKQK4YS;pc#6=o`D`lhWwt{==dw|g}KmHR8({I(&F?Oa{;HIIPxkLHL)@%R(Y__CaQ9y$JJ?-}$VoP7v$r;zhLySXZoAsA0yCX-iXbl_aKo3R+*oqHzbb`Aqhy+2T^M}=XWSSbqXKDHPoCF8e{yW>>GFg#1bFtQt6k)&KXC3_$G-#!ucRkX12KNylrY!2TQtbEoi}BKjqx0xU8_$Aj?Y^68RPr6M|@i-z<~4QKrJ#A^CM^7(Yl2J6L~-u^ZU6QiL#46GNI_id-kN&7=JJBnT%=|3yR2YII|k#YZq?s9#5n~tkw04HRGs<9Da>bvld>yp5s52`PlG|95&uRL(Z3CQ(``i0Li8Lzr4Qi_$$tQihLe9?RzPM@vY}2UxjxN5VCaR19zUf(8PFgf(GH;K6=cjOX0nXEWxs>#zXtt}^V{gp@(v8}-(&Ma)|Y3Ui{q=*{#UOk#CXnk(J#(p!FpfUcO$A3scW}MweG;a>)Qz2Cco33sy_ci#Mr@q0KA5b3Kq`+ft-areJ?&VHop!t9Cb&gY2STP$E;T1+}{zJnFb^Iqg}Td@zeD>LBezUz;+=J4##>^s`rN6rWMK1FNr^VH`^@=?PzYJd`WJCXhbg^SH$mf5NzZ=_@1MhZRcYJygeZ|CmaDqCKPaix+U%~l4zCt1aob?K$+vvwQ?N`XAL8UBtV{gGa*u?igbuwV8#4Wv2p8EOFvs3JSA2T37ld)f>5q-kvwvfn2QJHY@7R6>T1NmyB_r8;zv%qQR)rY#S$iqILTwHV{8}2XLv-Q+6&bA4K*O(p!0sE6@}P8ocXfk2HJ#wQ<{>(jpy9YZTsmH`A$><{l;i)D?Otj16r+Z_N2>U{yLi=^sDY_CZvwOUX>|?yzQmt)Vao4uz?~pKd%q_C!?M}hfvFg5t@Ia%3GfA)y!HrIzryBzt5g;8%sjY8E2x-{=3f#9e8}ji^$aGZ`6tJ`-MvI?Drt&$#E6ryp?=_^XTXwK2xIaRllTxxs5^Zwa1szitL{&iDU+@1R1n`ElEVKI~6U{cfr~F;VwRsX(7#cjx$_r9k?z))@gIJnJkRpWUlR|Ce{vF@C%4=jK_C3v9h<@N>U{$LzVrX^5c&b3d$vCdO9&{`bto&f#CT4<`T{vWn((K9@vd_uIya}#!Sa6DNS6r4A9L-y{Hcfml(=2in|andE)@*@2+YWW6KQpaKk8!sy{vfXt({9YlodHocG!n}CG%8l+RmJb?`bD`Aa@H(n=Q1H0!24!a`uEF=hPn_yHo%Do`$}H^WAj|YXWA=KQGPA$9PU&>y`djFJhKs{L63iP1gUS!K3_CHTTyTKQaCf(Eq(pSA_8Uag$cCzuWeqpyA@}QD|$=-Xs?2wS`O&LYQh>8@YC{dA;Lc@xFuk-5j?KcRD!STfJ_LX?~-*XuezWo~#rxE^Kor|Tk{Y$qh-k12@l~Os4wr&KYPVC=;TFZd=ckX(Idb^+{!+OhdSo^%}tpi`lzv~m@;&}f0bxnGGSd^xyawj!I9Jl5&AKXL#_Doq)IBqe%!k~?U)}ouWc|~Lb&X&2@2V&n~MT)QHbh+L3M==jp-w`Q#yad-Nofk6A;V<*Rsr^H$%?n(|L(E#s+avOUisx6aTt!_uQQ48#pa7WZqLi#nP}kWX<>-8@5b9PGs>pMpe$~ZP^_5)_G;P#xwZ4J#M*Qj1T1?v?eN#YAP^#`sSZi1cF%1X0g!6EIs94c4mHu}h`t37vl*Fdkk@}nEaB*`Ei}5_3!@gR#VElbB4>DKnW^!7C>p1QEPTj}S{9sE+@f9<|8*~m70K@C=zdyah`613R7jG&2`##@7Ub@-i*RLj81PP*BGS5el@@I*8Hz=l^=c;Pr_~G>ps}!0`;4oLjLB9o@AHpA1EK^3?FV`j@UlH}8?rtxKrTKlY_Os%6+Wtqgg65wbJB9Q1{bQfskbgb|_#LlWwhh;1BJS37X90`}cO3ghivR3tsJ*k5t`La+a^7oDC+hwPj1~fYOmEXVl3$4S`<*TNdmi)?=Pglb>G{N6CA9jSE8TWPRsxDn0Z0@-*YiG98dUFtRGg;&etwRk>Y1A4R)BXFMvxe4QBol$R||%Fg^Ub06smZyS|bX|M{K%{*lnKLeM^R{c4#S>WZ8UvsKweuwAgNYIHPhqz0`uiEQb2x<2ZGPLhSJ)tJb&hu0eyvXPH0*omMf7+Ah7z?SwkJkht{m;(x&yC6)aUOHD~8BRA^T*{ko4c24=CX!z{a!D(~t6BzfDh3Da=wa`p12=QJ?TS0Nt^x7@6{{Yqj{J|Gb#S~43ge&Lj$A~XOIgYN&Cl{NL~ap3U>r+#6hvUgcAP(Sl0bzY->z)Z+&T@v;8Nd2!dKVC;}H{&E{QYjF1vOSGZC)UT4r_27HV`ihBwD0D084&w^?P1i3bu>D+{O>u}Cgderf39;CH2=vV1LP~>bHt@m3B>QdF$~AMaI9Q7u(=A>G%-2H=i~U*cjJBa2C^aIRjl?pQv77Aic|=@>2+E>|EMzRmT`?+>SwNl8x`P>{X$NNw`_ZVFFyzPMANbtrK5iEa(CxVms~g{FO=@Ii*$~5eLRD5J`biN_E?(LW&P9dmi?X)jL8R2mu(uiH=v$x<(KC$MqNj=D9cuzBjtT}>tA>oT?EIe8zN3pojszD=69dJ>s>}Co|h$-XQnm>T?c!v@V8Z@a~vBdxlPPmIdD>U-{+s_QP*Q)a@VWP0V025xg6>~`#wE$am|G?S&5Bz=16@6sGsN4)P4Jw+w{50<){;VUZ#!mA?`zM!+ug;kLWnpo2{t@@T$VY;KF<4guMqV-S}5g-?N8r>nn9|-qsrS>=34MInfup<673g@w7Of!BW~eqtJbvpR13$H;#+tK+ayzSdC&_$K^qMziev`7_DX+V5_gc&5)6V0h)}#I@rA@Z*SOH9k74f+YArI7s>ZaUEFNE@$8X4BhIG;+?4`Cp6A0-`Nns`GB$NMb`VBb4e0vpZNK4~D$Cu`CB>8I3v8Bu?PYp3sT(RY>T~g);7e<*K%Jg)s5V(%0Dk=O;(cDY?)N|BxS}mvNb8>>Yl`EEbto;S2+SkcD|4lBeE10-y-wj0cyvJ6bLkY$o5W{b_cM#jfRAlJtTP??%9Q#-i*x?X@6#svA!nC+y`yu_1bgTVM98WuMU@xVew|F|Sh`8_(eQF#h!y4hELPyhVF-DJ$xONwaQ+R6g4g{Kkd#26BjK#!=0rt~@Z^G<=%!5cRV`krg>P`B3A+HoLnY_3C}}?^|OEK%IwC^wW3Li9ho)|E_a+i;yeE?<9N?e^~@XeN8Z#{8SECG}6b~eepIG)&liS(5M(WkkfVgIzn0cr^b&zRFBjUOY8e4n&`g7kAK}A9D-sjdgj@rY-8_PKvi7>K(PX=0og=Ij7V;)NiHc%1a+90HTk_?f0m=a2@yBty&0+te=;-(IZ!=ev4dZN#y|PKCW4xjkvxOb+1%oi)r<*RFzRD;?}lLQ=d1(`b>rniI>!;`{(xluMeO(UVrYSPD-m-IcT4MJesVB;p5co{D-2PC7I&pqb<#+S>w(V8raI-FrW4sc_cf1!*UX@t^UtQzgKD&w6zkc6Apx&-nn=`^+MEf1R55VhKpA}uO160>XkgIpq+Dd-NNy9I(rT~zIBB3F44|~DqP1mYxf;4n{)=(Y#smH|f6!ubQ)1qXI&oh0erFJ@P>#2(^&;ihZ;cQOFbswAynXRZ~e?hq!#l8iN04|vX@|}QjuL|6xVB7Kf(|Xhb)x$y(FO5n+i{0Q2uRQem7L)4!5pmicD}3Qv-1Qe-t5H|eK6L#|s~@b+e7UTy9_Od>MuWQWg8&e`&XJyR3U%$nE1d4E4Tg%_g@QHjaekzG&SeLVgo55O^|>j1)T48Un7%4U!m6(cZk2aQ@$=_aTlQRwfv-yX_8UogbHgqvk6picLtr}{cfe{~ms#POqllU>^zB?%JTrovlbG~dQ?S~P)|c6=ij?=XX=KLzCvHaFRCr78&ILbs_h`?`ccl1dqTlY0ivd8?O>y8s-99YpgFRaij1E59lm8Rv=dgd48@vyORVf=2_q3y~7;;5KdM*^6wl4tXDyhFG^+RuC5&=Y?^9C!_otz$+q>4pDc&^|%BT>{ZWS^%<%Tb{Bqr^iEQoWtiuf5H5x5U8*cEUX0ZoI|1Phpjx#rzQhyhp*OqE(B8L$E?kgL^f%9>)-=>44dWOEm91;AHFmSl~i?|xTrBc%B4*ZwPFcAScZH}R9YwF0E;6Y+tI;%R=}J|^TPhO8~-lKlxF#T)gp>kH0jyZ*qWFncm|FZVv2(~LTiPa2$(0$Wy9FPn`=eV^C-3WcHw@MfC2DulUDOfH=o6Jc9bB^6b|FUt*z=ZTdG4DX!bjiLNQqE*|8TUf&^o81=`y6>{4o6TvQaIC|+`)QLJ*^U}$*Je^&;kTW@x-gC9Or9f}2_DaL`|MhnP&lMp4KTi_J25$K=t2G}D$9>~$jtV0$?N%OnrO!lx55BGI+oe$t|D%w#dq*r-&G;6IlFlC;Q!keCyTrjZOI;JsL#W>fu0J~PF&>!4o@u63%UP(!CB1{cEb{^A5orsH5v;1G4wgGaW)#2|^-)&Ri-mV(Q69zb*@NevFPWu~2q>ba**352cb-oHjAHPNg98c6~a>}OA^0EU+`Dmq|R8{lu!~z57=TH92k(Y+!eUcq#;-IKWaod4)sCz6I-OqC};cxtg6zX@A?)wMzCBlH^1GWch|Mhnri%15~lA9*pTBuLOr>#n&ULP`6WB*0Uil?QeXw336lZ#?gyEX48S_pDCq_<8@zlEl=vsfU?uu`FIDQLN7)!JPt+)ZUb?#aJ^zgTwI$LKhLSJ@Pxv~iA+IODKh&wxg!@1x06*_Por~T)sGn6K;>~F9nt^2-1%)D3JAakl^1k1*@eS)Ie9Mzq*TNVMF+KhVCM2gSoG9wk5b1>ORatoW9v}gVj=vsCMpbMS~qUs4#auOda|FlyfTWGZ+Mo}$BoF}$ptsKX{H_EKZe|rcHK-a^u0R}^@?WeQD6T%JfpnV3j|yaGO>{QQVp=H{1M>yg+qA*@zR0&_8s{f;)6mySdMXcBew2*l#&wxi@Aa1tlwY&U+cJfG^2GWJhf}g2tvn~4>t4DM_!@;=g2BI`E#h#h5w#?`XCOhGR^FDm!NLY$Ql_OI8DET-Y14J^)0h#6h-VG(SK0$ZueR0cffc$q=s}Js?lc85vCUkME}edY1BJC#JgE=Q8~B=%375zU?)~uQ)iz|JlWkbnZ#id*WT62w^&384T~CzAi2zjUhi7tgK$?md26t)}t>31a^mjv!>wcSY_n8j1zN?{0(8SC&z<1jKqzvzyChBJUDbh2N*67?n2jl|QX5g=K>`d)@qA6vh~>%1gS6wG}tfc9OeOFop^F|{KG_Oj&|XY50rV^#O~VMhwAnHrY$&_dn3i6P_Z+gMth+rSyr<(-BqZ+pfAAN$Rh^Q3cCA`almk^eo{Ipn~mzb5ys*@x*JOTbe?Pi@0Zn<2Rb#n9T*Cukt&Q{FZeGSpBFxNyIZZcp^6v_2nEp)4-5ZY5bKJj;~bv-RSIk6{2OLPIWn>{_W5EfEgJI@OwUHdi@l2jdnrHX2V!oKf$q4)Tzs~-)MFm_;zF;HfKP-n%sP6FE?8P7!wW41W^~eZ0crlB@y_SO20fWgF2hGL_)*qWZ2C(`Q;rcPM((ExHpA1|A!2a8{!2j<%7B!wtRPJ3A*r$NfUKtRg+tM-+e%B_+iG@WYiUodw!G+2!MyOeXp56qfT&mKt>2;|IY5sJ%asctgQElN9jj`wI`+X=3UeSt6DOotSL~(;rlsS9qVX)c4xbnnGg>W-|TYSMo^zHeQdy|m<-WUhhKiZhV{6T8^0!KXLrY^+)HIT(t*{n3YFWN%d3@AL2H-G3^42xALnN)T2Ir$TIdNyBEk)Cs0}n>wvXLchyJv`@w87JM)hkQXjfmH!X?aAUI@`?|=Ik){*$lFC?~HEF89<<{I2Lhjp=te(+rTVnAj@!*)kK*3mNcNUncu5eN0Q9%H;o$dk+8d|~gVPlAf>OLrt9(O+lxu27&^`z##TVKsG2kkp@UD=*#FSX-!3E|OiAjn^+_QQ38MxfApR3Z*@f#p@IG+-q05L)hAm#?z$w4|Iha_OJQr1BZW_EtJRMeGAO!@=U%4(DD>M8{qjY&)CH7HQu4L`s7`J92hs~s;t%%1!`K(v!4Wz8+WR9dxBpq$m@Y+a~|r%_xvk&BD8<1NKRJyZ=Fn`116w4*^#NZAMg8hnP(ZRhc#?`CbJOm1NnSxZl6_TD^j`4f+3*+Cs&#>P!zU!^mSz1L&+fshlNRFzJKZz5R>Yw_qZiUYU)=2vrfRZt*EZw1cFA|!B&Duk@Yr)G^fxJw<2h5T%l37V5U{VzZm%Pr=V~d_YcIJ{p#cWf#yBzMNLqjCQshJyK;Y>jfSjyPZ4Epq&#FOJB_h_=9}=;;|@tw1?`@>Hu6fmhjwvApEd5p-^s(vpyb#D4J9AofD{>>tmU9a{KO;fJU^eN*543;RLBlK87AUYu*~KrR9{EZw#-C&Li3AY3#S$+Xi2RU1T?ScR7(qN&<8zT9oM$3GYd^0w5P9M5|Mo|nDz|)+cz^A4fQ9Gp8+JDRH$OM@fg3IE`sT&Ff8$dxmOkc7@qxJ#=7o>KXlKXH$DOAh1knEOGmOvGE-=4i>QX3t5dCs)id4_4)6i3~>R}Wt7!A~(bVj}^-BPz*R5uoaK3+GmRzj|bG(OU~IU|8~E<^W+cH?p-z`4KT1{BGbMMmx7vU?JrNuoyk`xfcybqZaR3^c3yqt6AbC-x>?02E7+|#i5^y$a{T0lK|hex2^i6f#-wApVJ?kx_KU~0=#mRd$50vnd=t|31tWPlHDN6wj8;umGN2gaDyv^_vibh9z;Dx>`{;Tj2C28$xiR4psugW7OKGL4@*O{==9D$A`&?&Xjne7>a{uS|MTbu&peKQpTn4M;J=1-Xbh>QPO;kr4<=4ymo!hWtjH(9=QNy;UXm$MVlI~kwtrxq*z?{|(rGE+D_stoluXdMv!fwuV8{9E$KIi?e-_aFWWhukHnH6x!Q=O~0S|5?mLf%N2`Cc+L`|HiWxAL$qmi3jTEnUjaq_r%I(O`rA5akw+NR_Tf=-j_wVyX(PY6JY$6tS*;}cHZs?`duk*14P||A#S{HShQwqN01}vt>;dYi$yyH2df4G4cvj~*KNa-^>2LlnbNX>bYHmrWa8=PfAIj+eZ8TuQR>DZ_!5vb;HZvvI!j#>YBvuD@4&|iyx)-%Je~^f2)G#or&k~Py^fTht6#h-$w53GsOH?`KKuXWrCJ}Q{r&Ef|Fg4Gh3GGv9%2j?sl4+(|LVz)t7Np)&qOXi4;=LoCU&H{@kCwk-`tKs^wa3kB=z%Men2dKsXN5QsQ0xFp`ApX)lz3)SliVrEf|h=9_TsLz&jfVE9E?uPAVg}bXGHHa2*VXpLKhU^nalJg-nmthVx=TfAP3x{!Ls@4PP`Ze#;dPL>}8$4_r5I`sHlW`Jo98lj~QF9722Uy6=w+Z8C=Ml=vUefjUvIQr`7EWb{X*up6PB1n1XTJ3@IDV^_uu@)&DezTZ=8cOd$%N0Rb?xe6JLJ8t;`Q&N;%^ii}kBX^O1lXegk_wHO5xeVJ9E1XVJVGBMx3KR&`6=pg3^;QOi*zQC@*Q>@?6ln$58=mpdLNPMKoWj|Yc}$^VZV`9&3;LfwRnqtBZc%bDb(+ah3ZS1Y_ISpUvGsZrqY}M(>YY1k~LfDnCN%3zM_7Pg91I0z#beSxWnHeLt5wY#($}cN){Cmc+ORtzMaf72=XpKdu3ujU%-|$*VL59x>X`@I1@rb?gx?>8A^sHFf1W6acH0?TpZE^t(W9M{8@!rz8N48tesI}9EzbWy5Kk$uus_u2y(xX?gnT7x&ijssx<4vBZQ=1ifs{8fmB01J%1Fpqs2o-y&R~u4;|9;&T-rV}JVcW<2fut0NTogqHVIrALeZUu=bZ<=CNV$1h|_^Q)vUMLXRbH;5K|vICiq1DB^O@wuLV@zpVkbA?9F4=>D2Nd2R~Do)&{_kr`eBJ>Y=aQ^Q+jpFkX4}g*`bqyO*J@${byVscvgaEOhvrob2TGv+8e~%*yUf6EVnKMNDiGF`wpDFMyda9s)EuIfL=jCinObaSYA@yP)sA201~Dn|Ws^=J8RJ2%i++}+Lb7WILQ`dQaPZ}_b1esz``IqkkQs}RN7A5t#8Sr3M&M@&9`H0Tiw6&fdOBlA%w{HtpuB0&0i+)OSr^4NaICv`2IG0?fMB$dMx^{RN$ExteEptt2}o+u0Q*g6P`nx`az?5>sbYi^)U^i4K8V*!k}jQdRTP$&AQ6dPXzqAro{H0rz*;i~gBPC(RGUV0pPEPYwc$C=0OP_)3@I9`pq$^|y)l%l>?xO%K_A{400$@`(*$Ya;mAK7wQEgF=z)Z3o_j(T{A$s}WSEQDA(GA$zc$6jqJsAfEn2kXN=qp#&JMIN*8bq?+>^9RBo*?$*xqCc6CYzT;R^xBt1Adi_B7@c_L8VPAZdG|FPk&Cv4e(^ulLIEP*+Sn1f==b2qJ4}ZYXnD;`Vvv7`^Y5b!`e3QJvWb@w{cORxCm&XbT7Vthe8abEc;Eb)tuv?UFVgDK2^}NVjX&aXV?&-Z5c|Bm<#^x8#6lsxi=J@(w$5&gx5#5+&zcn0Ci+3dHTzZOkI)`T{wEf6D}tesHFC@Sv&cE29!bZO_C>(`>2t5uz9SdOI07-U`4=LPf1`R#(IJ8}XM$7~RA0!}@YYfsxg99KNO}AV14BVH2so4dE9kYc_>_H$sF<1kg@X7S-hsT`th-e_qN(JHv(&b(S1+0;Q);gDQ$RpXto+6!o<|fLQ;nU!hL)WhoW(gP!aAMwkLg{d!nWGC@fYyjf~|LvnKt-iXTB-&Xv^1^yn!x=VT;A&!ijPqZn@W$<(vnLSeU6T%IXIr5IYipe!5d9kmx1gO=3g$4^4u)sc<(Ykul;66cKF`260*L;-iP@z1I)^J_hxE0p7yMK{qh{*32z-9rfee4!zaj_MvfC?0wXaJo_y%R_qVY-f9dk8bbY^R%?R%<6wAX;U;)!73H74{P3$!xd9Qd<*S3d?%CNF+ltGxq>?JXUw{I*!5#IJNpvkJ-LbJQM((GAo@DHK}Im@jJ*QKSyL@({YqH!kn5h*2Wu=}X$SZF{8!w4gZlZAv)*eRoMGuqhQ%sA@mP#((dRr?DRN4e&d_z!YzdX5aBqthJ3_^j64f)N9uE}8jV=M%NSTf!@5qw_!o>n-E{5HDS@a(C3rf_}L(j5679RGT|bk8SN8z9!V=$$zJs!~#Z=mQ6U&?i@nQc-^wUpvEC=SJ%z{BQ+w8oj~-i`hOONHN;gLl=*Ft`lE(zeE7E#mXg4ZAMNb{1T>RA@HVMOQ7Nj>O?=^tg%R#)N`z$k4Ap$XmVVqGfSb>VOxC`InC6pjepK90mN6(w;t6+UP@Znlz-@y5lkB1kThmO&g{sI(thZ54$Pca*Qj(9lujqi*?3hG4vhTcGZAmXymisF6wU2nX;Y-a(2?}To4KSORTWuWdbzFY*o0ToiC%Vq)oX3dqWNJe%2_^>6$n^M&m5_VJ*m$g!hm1ogRfGN*QN=z;vOqN(>%{fq1Miy+ATeEp>f96x^~j<+=38Gg$&xjLOiJBj>)OU9nCuA^~j+DEk0MWWsDNrE5jvEkd-W{>uqKK@lXm^m1t+TJZlEkn+E>3t5TK84r&#_uhQ8lyv?Tvz*;{nLce_wk#d(x&NC>@??qygmbf~IsWSlN#($)ygP2ZRjqv^Nrg5seX%K=&@pVcYBSTW8$}_VaPiI#^>33HNub+h&qslA{0p6y*BBhGV%b?mt5{*Jbe4e`62oj>ZZ&6qI4wB!0_4;%T26kXX&N8ie@{{!F2YjrGg=7XZYPyZ+$rIVMos8uWW2+XXZ6+v2*IK5Wdj)*qu~Y=PjQaU74sic$hNN$taNgiesCn8L7PShw`aYgw%h>JFCKYj3)%fo&`1Ph9ZyA=3z%9*kAmVY^sdhl4u}aqvJ|}=gI=nnLm*e?g@D$HX(z5t(eda?W)M&l7UVI0gX^~x1}Kn~IIJV=g*-;^_6S`95P5h@NcCW)X3nOjYM8^@rkJ#}Qat|+*gn|V=Vc3PXU;`(Z|^Nx>UjZ{h?*fDT^&Tk~ePnL|0ISYirS@C@vV;x9!biH1C$!&-RKT6Whd||YIZpfUES2>0@dpBH#O+c4lVtrgD>WE+s$zU7d8mK#jlTE!WCVB^OKO+RqJBhp&)vb{7&w{Wd2){&avFgFSC_?u-=Kb@VmRua!$q2I*ONft0egbX9ElHG&h9T5qJEdM-;8XiMDAjHw?v_#_9Be_?lafyBl+bl^mla%I)hU8O=EgC&F_@v0BfwhEgnUn&iI^h%e%{NV0Hgjobd$e8Xp@gnm>0GWY_ZV5{^BmXD}U@9GK|yBq>LLevjGx`aH|xZL#FnJ1Az_#0M}cuY}K(PHj1g%)qH_ao}_FObD&?2lHx4Ue(oHwEqF{oYZkfMiWKMwvY^RqKHhzNl<@V!`A7`|K6;47vRhRI-K{{J3@+O?Y<;8_t;!=2Dj())ax=c@acHf*U@ek_6KE1HO4;1XPrS1+OkLgt=B;Do=hO5epy{D~_bJ&;v+RP|HoKX{!9(d3{Rk>g5_y+&^4Ep8^uB$y%MyzF2c0`3P&fOe#@%gU2SnV~xkY$iriygkdRG@PlH1L=+Y{|PQ{!Nqeb@`~rKV!W8IfBKHIA<=U+xbBt42>8OGG;fdv1FMgVo$go%>Q~r?%BEu#SlU_4%L63VV9_<9b@H)@agw(FnMB1!9V#(awIIOExm=t$+w8T|~08@9_9xEq{ApuPI3$3_?4VKbM|NE_8*$jTP+A*wId=jmB>~GQFXF$*B*yS!ieYy~e82Mt>mUa|M;r&W__1Y4kE7@Z@`LT)nL6T5cPX@jpB0=Ty>Vyh8A~SWQBHGmMRO@t#gEp!d?+_Kk&JTwgplSmq7ZeL-lu3KdI~W_qbbb`@sGvM@E^oXlL~Kl9UIx0)V=!3i^2$xrOlGM(zlOYWG^rbZfLTKWILEmsAvF*z6n);6-j(-!K11XM_S8#Z!D-ZOAP|y~W7I3E+G*bQD~WyH*ye+!qfx3k$yXea@1|SDR0kPq&+21fnnQBq_e`H#hTQGd^cpz7^j=w114PL7X?x1BOdBeb5^u^?eX$Ys~HS1FQof(n(vdx-dkm&AvTB04Fi-$$+!;b^eAYaD6Zqyy^r*6-+2F+t(^>o;U1QK^8bA>sUS|xzgo6&5qPSmwxop#B)*}&MrN9vx!k^gkUFL}Mj0e%-g@YE1QU1aT;_gy_VaAR_PwwMQXqMwTMO>c;Gb(8N|gZiNsiCE7|{SNssA2edwMA5c&Gv_2>s{ljk=WD!&LsJkG5?)CV*MRi*fy;n?bi2Iob{UBvnLc_k0vr7NgexfS&}*O6Ou8NPqxEsaT>CKi*iDwv?6R6ug+J8JYDjK3A;da9bwJ}oW2T6zxHO`pBp7KD1n`G;JBtoA^hgB_ely_uh0VCm3W(hCkQy;o4M3b|`*)RNNGQvR@A`&@Wx73#!(JTWI2M7vXl$83jQ1URbLuFMiXA-Qc+oOqh4-z}K4A7%)CJOb=PheENPV5Xiq~X6*RX61L3E)3Plcdn5b5|rx*ba-y=s#b|dGke|x=qCldwkcz=J_{RlZ{XdmUqX6k!P^k?{HNXnnR_E7xmls>I~zAULf_}BR5FT5XGfLCr?ge)E2*YR=+z3oOj@YtHG#88hs))zK!?y|-OsLSn<-hFuA+Xg!hKYi;7M|tAUZLC2%*-b2#2{iiwlfnH=St+z9sl{tVjfbCF!hXt)pvk3p-@`vI<&%Wq{Q2ZPMXc8Bf=v~x}NfXIim2q5aA+K3@vU9WQ%$J@SIw~)!<26d8oGU{HW`OHZy{yFCjdqquNK3$4-is_Ap(|`1bCCVxhJS2bDrPg?M-_s$q@56mX+DTuUs8Bg_3FtpY2w(Yu&-KNU|MST)AGl$?TX!xP?UdfH<5k-q0JGzws{1yeo!Xhcr<^rIY5hanTaa7a4|aqas7Jw?H>zJA+aR|nrQLO0L*4(fdmnxg!cFQE;We;TXf7UlG_>f)@1kC*x|z4O+X8ABZyp>k$M`yxsNvRwpDzLtH~mf;?R*{JZr)$$41C>Q*0%LH|4aL0_AxB+gu%_%9)c#?NyItFuJ8km*pIXQ!}wf8K0^gl5Qqn)O{oOo{L}IX?81PEBXcL^5qI6$m>^;t4XS4?o;E%uac=l!Ja_s?t+x|K?*15DJFeJy80^A9+Qh2y`wW!w96c@A*>*ZSTLX4J3gueo#aup4asqiZ-b6!uR)eLgO1U#&N+KJ@#T^h4BliPs*>_VNe12#e0nO4K=CtG_bI3x+I%z<8B%)QR~zY7+s|=LPs#@1h>ReO{yDdkjcM|GsB5iTdlbgN#PJ@sMsP@~G@6+G!k;*6_7F2}(C>o-TfmI`#9`Q#)b-GP=uu0O=f)@Jo6;z6dA6LrhGbqAs^=1%uRHXCUGZVn$GZT`T^K#lZvCR-aLxS%N&~B5rb(uHF|a%xCIuZ$Z7fnfvCqYP2xQt>VkQFG!}RT=T7S@B9EQl{Pw(-eIm^6f1CZO7WEaEWD1o(nnI9n*X{S?$YUoHM?@>lZD82(^dUtN^p7b9Omw;ac7WXs!Q9>EsHdoU80}wl2?{?CxhyM1P9y4jvfBF4&XSa>1$Yq#BJ)QNg!`tAv^_VA8E4hDOv*FHj|^U94ilnQgkNN9er#Z0yV^^~N>uhtF}Xj;doelh}iscBiYN7eIqV7T|bFWdpS=!8S5C);-!k$*~eHLUS@s{2!F$uJ9ysevA5b#Yse0!7|$eo9LDR@DahIcb-RG;maBpqBgkVCm$&jf_xFPSNQS^;r2GXUjwE-DKcqfl3%aC*JSOc^4OyPSutG^BZp}L6E}|ZER%irhDl6R_Vj}swHu%|zZ=-VFavHk;4c0mJm`W7lHk7e#(^f$Nq-hT>tNsw_+18?PIP2f_t%YxJKcx==VqbFMCE9sBrTzU;I_mpO-Ith?IDzONSEx;ah|Dz0kBrCzME~aBf$>n~kiwvwL+YPS@VUMzd@|>JG#`cb5Ot!sHrjyD!Kx1uqGAm)9RcFvnUjCP(+&YajIbCLFby6TebB;rILIf0|6(DIb$Bp$PqZ%gF#fY#1(fBDmB=jcu)VRb)WIQf;~?3)ib&qUp{X4^nGuhzWln+tMF-42VJkDi7C`sy$c*ojCTI^ghrE+D*H_%Ba)7x`olsm~%F3^whkdWOus|MWI{j)Pat?BT?T`GZ?Nh5Xa^_5=#OUg-+!hGPp3=b?U2aFqyKfEN&bu>>7ZFZ*bn$nw#TwvS6yL|yJngDDSpFc?nhY-AKdoxj4@@#$bV%`f_x9rf7tl12B+V!-AhSAX*w)T!H87u8pB5WKK-yUYpHd!20e-giubM=xgA8@HlPe2<)?&B12jjMIkz^lSOjH%FJBu!TbxI8U=gp}xH}acJ8{C*c1U6~UE(`UJb)C22i(NR75uW4MKS?&*v-gHpaA@bD;C*L&0zC3RBo$OnRZ1{crb7079exXm6_^oP>oBy~vVo;h1>>>_tY!}fOy5~KE{^Ub1ra|erKp}B2-`SW|Im%4A`SS6DP_f9&F{uD(XlRXjfU3SnI(!`CW3xE9|cMYg$jofb8e%Klg{9@kOwGO#U)6rns_m4ejQ8zwYkD;ETl5-=U$qigPztr_ap#C(0`Gog3Z}6Dd>#qM4_5AE35I5)#!=sYFg9VY(dg*x*h0H=gzfkE*vpe#bU-RJO9jTEJu)Hpy@-ylucB*#IKcc|%METZj_Q+!`T-^Jwt0Vwx^t@=!D&#Ja-JhL*{V{~VJ-sd7TTowYHuCb`GfUVrck12~7t~J-5A#uS?11pw{pv)W*w-+nxxlNqyTkgV_%zN+L)J}ay+G_t(%_vO)a`j?cb2jGgZnT2oS-epT~9acdm`o@3?J%5hHliL?r6e3wj?2fR<}9k4Dy&*^7OS+3KUT1YA$@ti@Zdf`>#oj2m9;k3=?Chf9g(nGP%qEwhwuf?>~gsVYutc7};+D!84PK58cIcQdXx^gR3{$!B)zi9oJOwIz`&IHfM9XfQ*hwy7?pIvFc~ml@iUKwEE#vmdIn<>Sg#I)%tk&8v*fe9*>m1MO`B4gpJFO7$}|&y8n?B_Z58P$*o0F)O{lJJ4O0msGp~P7#4OJ(fsNPT6kakHCfBNYtPZ@5q+gYzAD|Y{1u&wJy=v}A8<6m`>OvA+o`YMN{c_qY{T&hUFoskmwAICb%9e-An~CTcTJj+Kh)a)>KLd%f7kNu0uF|^gW>z1f(>tFv;K|mjZ_}Kb~6G_s-*}RoPJ1=HFi9EoWz-GPXWIQb&v;Q0FqJ(3()&#g7_@2DAid0wR#+vKjtbX>0~$R^co_F62wFLCu*xS284vepLeWF``7S6+mGm2>pWuhGsto{zSEkxno>k+gd6F|_mD$2&}=cikay>9x~KpOErNOFvq_(Dj95ugY?)PLTSuT(bJPb59`c{8w%OIj4#;n!|Z56z(cLxytB-c3yM7v#cyI3cUMIWcQN#cC{R4lP>*3fuoJpWy=eYTZr$hCPM-c=k_W4kXszTI@e1JSpks`EnJCq>eg~6Ki_B%ME>FmVYD-V<81H3a~FuqEy^*yj&>4x&c5rtpxVH)WSa=uc|WJ)nqRUXc!#=<-mb*?FRs_rzULK0tD`cv2kl%EAGBugKp4htDOW=hh}v9Sz&0S3JsbLi^R$aP5){iG}IBJBG*Dk*}689=OWrngB%j0$(2LBfZ?6EKFALBWSLbjU(uvF8?uiSJXOtpw*jc3;d^BoNJqmrxgQa@21(^a8n?>Fd(uQNLd=Y5Q})4_+}hjn*v${L|T~fHJ!}7>K&#Cm*9usk`F2_j5St>ljPeW=E#|tr)PTPUwZ3sNXgCHEQ@N4(ft<*E|_UeRTMpt$Rcgi2Jo1dUq1-Ir8n@{H_)=*!(B%&Ml{ifBLb5%sSc$7a*R)PdmXLb*I+$i)zmu;jo`)ac)o_ggT2Ui|Pd~U)VF_x4I%5^+lSxHRm@5!nvaPE5)6t&$^2!T6Tnj+sG|FUS2%+JnZ|p!(?kTt?s&+59+eVG#s{3`HFs5eRwrDo`+${()a}-8WZ{`GqQ$wbbU^M3S$Y3jq>UB)Kd#O^9?JC%_)!uOvZNx)Qc77$w&Y4BB3mR<*6jPf@B2P8_B|qGE1@VYq)16BqNI`*qJ5!w=b7{VT=Tx?k8?if`*}XkeHmls``q`nFwGt)I*@~W>bDeUbdD#i40K~-=tREYUvHXw#vktA753x$iF|i=+V3X`VbJxew?0-D_swdIN&PolqCnhz(sgeTa@x2Rs%J0M^%XpMjNJV}{G%eD6zH5*jy

      o<{T&UVrt!_0q2+XFd?W?VL;|yvltjdd3WWOuM={f9#zZjO=P2{91{es4tU#Xb1c`youvqktfV_)(nb!z*WD;IZM>h-zGg?Iu@?=gL~U+W51uJJ3l4<8498Oe>f-l*no8K0m+_7U?{cd>P$fH*=ZW=s1gS;xy@l>Jm_QGPrHT^jwZui`1Q7?2|3XRtYa++1dpet-*iSFOYAip`x=-58ZuBCpn@J{;n(`D^NcCnYx~H+-H-P%Q`TR-y404o-*sXy-pBL{dyHRC<5Mp?f8yc84@92V4mfBcn~>}@8x3`31;I(b#-CrX$haDBD=a`A%5%MwL28)_TMh%?*IBQ35f3#UuN_o>SNyl`Mc>r)C0BB^#>;UQXb~b0Bdo5DTPnyMRu1NiiKuPp(4LixMTu7P=S-o)H`4c6U$sY(cfuPliBbcgiLwKiroiZjSF&lMkBJ+)`&$mg(mo&dNurM>GORvg(UU}*3wE0eJtwHRTCMR~Iy65!o}izFoU+^K*WI5KII5BxmP|Ldg2FOr#ZaVTe!~+cPY%R}LM<1IbZIYex_5I>k6I^}F7haYOP()RQGdTJeOm{_&=W47ATRy7-4e#*4vS=+qC216_WUbp!Vz{|>pb4vj&c6eou5A0?+G6cbx0^n;JUY8%g1C+`$J9oS4wr>|JMimdKfLAN{P30@&1jUe>6>Bjsks|2QPbbFwQNx1;Zv>@j&$Z*Aqb>P@m!k{XfajIXTO;o~}>z&JJ~x;=LqD*N)RM*Fzup8YnGs${+)rGc7z6X3!swW^GLMiM0X3bG2G9&M}RWn-wQrfxBr}OY0_#(?QVa2xp5oNPJ>%znq0}nt48#c=0R{s#c$NtK!CZERVj^Cyj@Lm*x}Ss4V0O<`-gZ421sK{pSM{ao*nDPLOuQkf}y{cGMn(3X}Af%x{e%xf+f=dIDs^a9>UP=1}xZu1L&E}{>b+m9GHq597*gzlVF#J*RQRVxv4T+Y>g5uocs@~5Cpa7`N6I-HweY{vNi@GNVVQ$nSXP#UTn4muAz70~}#IqH7gy_@=%X}>ScKz1X{U~ygYZiu!-x^JVriy?&5|PM-o4?yTUQLJFwUPW=43IA)H@FRcr$9KzskX;QkjL!HRTnAEhL`+|;Y;I?-ziebt_rn*m>jKYJ}o>q44duCE4Fn73yR!FhHc2@)KrhUwR?kc?+UlHmB^FyoS9OV2SG@WjLDuEJg+1^Z};&z~Mpx?QCsX~5Au^l9g2T$h-WD1C6aGM?H=UJ2UU=s68}?^mwBPT6T+`ay0d=3{e4Yf=NMf-H>wy4_=M8tS}svU?^=<5#`>Ia6l{(ONZVh4ocwNfuRvBDtax|yPAdm`*Ef?QX5%Z#aNumk$-kM%Ro~o-a5o^q^zwdF(oXaxVjp44O{bg$BdO~HqH4%bS0+|@%h-c*(rDF<;{Wk6)e2U1v8H1l5VE3LU6lp>O3Sz*#s9D$Jp63S9vX@~pchVGWeEk|F1|=@2K1}+8$zM&qmi(s;DzZ=3i4N>HAWtJNC>6P)O?{ue4UH?kaSgqwnCZ;b8Osb<{kx;DuLS*vIFDN*WDc(^+^mKS(XZNnm#U0T+k^Jl(-&q>@cz3b)lZ(k;{m6BPU^&+!gEibm#R>k!bqT-J^bLjF;`MotD$vLJwtI_Nt%`zoua;GKS)k{nbLqXh>mCQLH{QkF+=1Rj%#*(0k_=qOtXbMP&~rZI?_yuKngpq7e0GoN&O-&6;v*e&Gic98v2=48?no$+?^#=d=^-O-o+EVY{^oVM{N52dhSbshVBNSV1K49VS8kg0Ud!4|3vhN7*|A&ip)~oDg5S$g_k+N^b480h8H>OuVb{{$CqOlj4l7P%wIX?u;|?hGU=d(w)5_NK4Utybn3iSA17WAgt4KQ!iA&b!}xX{JGo|4rL#WmBOm&&PhA66JDo81F^r7EQax1Qa;N+HW3d!owbomDv{rcTfJSeKLv>SV;VB(14}$_MQ=P$f~{SD@}+O05AeF#Y;d@l0X`qh$&NxlOF0Nal{@!kDUj+D3AI#Qm#W>qX|9uIqkAVU1EPwYJjMGDTm*fOfA`Cq$tIFDqaW1H(@vDrd!u4tIcio-nEn=dNcCV5k|JR4j1ii(F!oSQ{A`^&q#;u=_Tcjmq*m^mGhp$tvBwd^fd)WDH)V*NOnZe?M^%$q;8q36sAN`^HS4#bnG>r2~^;FxYU18A6w*GVo3Kx9?y+9+7jaJPOT5#!wZkd-a>cPwle^|I(*jqwClx^&ndO`_Fl+7_cX&Mkf0T)QeAsFu^8Cry`!Mtz@6HIpG_C9_&<2Xgu3$T7>3On5tBeInKf{fZ%xB=*h57KnK)RjTMeCo-N1a~r$EmxDo9rQ0JH`PzHmwGM3c1)>eEg)DLj%DQ1_3kIQ>NqvQi2z>vH*4#Y77YT=n0b2aX?|&3@Wj2q6Jv*uop3MngXASccyzm%CxZW^8Lu`Ll~|#ya)hKS&#E2E0D(*FKiHq3x_K%FUvxQ>CQ3l-)XWei3YvD{9bD=BOlu_=X2*o0#J@Y9NOE>V#3@lP(WhzZ6+%9RdYl+FLew!daeQd_P%{~fv?@mc71t8}?rTO*hd>rgf-?5vWuD?flyW}UHLn)xWR-xqWE9CmRLJ?uq=OdXZX>q}w=wlI6Kc?%YGa==1(AMlCH$KUl97uU*rD^IWZ^h-MJ9j++?x}`kU+DgdXBKVnF8I+Vgb%bz6(xx4Q3)gY8oeao6eg&F=h|nbkH)hJKRSeBYk>(kDC61c;7e7dsf>Oil081OH%hug|GD9hRLKExcaZJHjiDpsjRFA06DC{%Ba!#+Pqa(*{=g`aMImTmre%3KH}buN>WY(gK?o1YdmdK?KvJ@h6E^gUk2E1fd(aUeX!b6#8kJ?9wb(vx#C$xy~*eu_fQq!GBuCO!guAkJA^4C0#Pq-!D}lMsB135c^=lk1T-bbKIIvS05@FE)k{c2p?8i*|Cb^{fTqsns`q*-1mKT#|`AP@9Q{!+PvD^bo0epM}9oYI2uMfZ#CaW=YirfE2bi%;IU2D$nbCE#Ci7ENE{G(nw50*p|0hFw${DL5ays?%r=hPMTzk;iyR4x`oaTGSfeLww_t23GS8rW&a{4{s~5PFN80zz8qy=rrJuLMbw6qRC^YYIq3x^eXTkdql!s|n>v%&J%k{@`r;*Igbo6fru-Vg3R6AnXzt&ih(;kvaIlLT6#1n1Hf6wT@*5qAtH_D@6yXB)kawx7RcIyM+y}e+X<_s3p#4|>aknFK9im|<$rsp(LP5H|#F`_&xic>Y!}+@Xa{p8@o*SF4huS}ifWtWsbMG!8pV#18`?MhjeB}aqtfbLf#CHn~#x73;FYcyYzZx;lt*^bw>=UVQZZe^6P6>Tx^7Za@4PsINm9Y>#$ySQz8*$ZdrR=f~5uY>UjU6K3nGsp|%9tJ;XqMN^P<;{^$t!)7yKwU^p6yv<`>Ob+SK#PKW@jTA(``emFpx128>x*HPZH&tQ$Q)Neu=dY51BtFWpimw0L0}og32W6SG*N2puUBnkX=aGBQ^Q&y$Fk{TnK5`AcMSi!kK}dNZ$Wz77mlC?ji9X%ecp_-8+Y5(~#rSD`@6BU?alqlla;@OS>knQV8wl1;go@_J`$i80E%MJ}n^)cVl}4M}C>$2J$i)TUS{&O;fsC>x`k&d5U#nnd%KVi@o6n*oggp53a5?*y6OicX@b`66+#(m>9b45pl{b)Q?cCfbWk;ChsCY>pW?@oa?de>LZNh2rf)i1GG6_v>}!cDV<)G^-iGz?p$>I)Zp^ID3#~HfgU7oG#atsN95{xsgS>M!*eLTJ+pFvmN=|9`%5UIv;rBti-6Gj(j;+m4k70Fl3Gse6%qR)OM)i**;#x8uHLayqbxw+w721Fk`Sn%K^`dAeo*X?m>10d!kgz4aZ*EYGJlFURa+Up}5fc%H;qVaR?&gbJg(Q#zhsu5ObbUFRzuV7})8X$OHE)Ghvk=GKA%eIVvenbwP0cAxNJ8iQM*T?e{#}2q4!lGl=v;A0y`6cl5@<=fttF{3YmJH4KOM*A69uP7|N)mlEV{Urmba^wWX*c2R$D41I}%<>g$`Sqki|+^uj^1bvBCud&n+3=YH^u@(I9K4Yqp%6jLndRoKHDh|;FHoQ+{x}*i;f(sn#a{N}GNLL5C`IoZcPj6UG6}8)(cz?}EcczTmARykq6&2`X{l@9GHRmJXapC475xTknVqV2-)>vrStl=!b6#ZwX9Ls3K(j+)DJa%Bb54k_}Mo+2FAf8h3;ai5K6((upd0e4WAcj=Po#B~phX_PP=_64z?QG*>$cn=9A@*&bd~P}jl1;a04x;B2`=n%9-=u)o({lpbPNFAJHC9es&>Z?Vx{KcM!E?`uO?)y_x(-mnZz6kW1FlOvKeVp)gob*bs)$E;KI^-7et=!VABg?J(!;p!{N}JPOx{V2(5C;9;4AC2|aP!t^Kd@qyk9GPf*cHISPV>?xB>H3+R`tn$W-NYM~UL0(bKaTNOKYFQk#y=2jk4SzNyp8-R1E=4U3*o@v$|p6k8{<@E4Ey~jF&d<|f291a$2dn##XCqN@j&cP&&y(*M}|UWCu&oGs3R<`v-LMEJP359B1N+1RvFN!pwQ-W6QVcH2F@)zzW~LYvR|@&3koO==rFaNSjx#SWM?*W5FMfGo%6aW9I5jy8JHB(Sj)y#E%Po=}o7xGApYSuuasb2iyo*ko7zJ0V0UW`X%IJK&cH4xt2?U7pg34MlmAAY$T4#Vfu;@U$37Wv_a=I<|Thyj6VkrrEC|3yyxJ+N{oLYzyI?D|{2i#*o7_hMXc8t`lyTop5mLwkV`z!KXgaW4+N_vx`%)L@0@f@m6J$dN(_aMeW7RVGx7XX`r5xM?;WE+;65p{cpvhir@9M@((%wD{vzxBU)(=@=i=;p;9?3K^_|@(_!xP5>4WEG%g7MEdAr%q`^brTQFhgta5rE<=p8fO|C`|7PKJ$!@Fv+(hx0t18_Mmk-ZFaI8rrNc9I4Jj9_4J(zT>1EQ6M6B*-pXa;H5T`6C9+A-~~RxWQb1vb7C)ACFRfzhpABg-ISbv_KaRcYpmSaS|A-SZp9WU>+Ll*GAI4`V5%Qd0HW}iq7|bZ1-wqGJrtCzc2UY;=b0z;8oO9f)#?CXWpp%&x9jhjbYb+a-mIELy*3IE{o%}pkxOL6)YqpO!FY_f|K$lh_dMtKCG@$34Sc;Q&KIwR*N;c;{5{w23iXp~rm`-hkCp2Hx22g6?Q{N`EP9t8ckqC>Kro1!vz+a0!McDOz$yIZWdv*w*t5M@4}DCS7&r#8@auzr?~>o>V=@n3Mn@_qK|1H#m9rPni--yP!YSzjL0gDZ?Z_5;L-2@iL-%rm*!t&^+9W9^H$0#1jHg3OSL8E-A|M*q(uBgAxE^4WvKU_%YHA{a-f#cnGrqymBC%j7Uy9G#E4Ou>K#dW)!PCa?n;RyMpebcv$ab2Q60^OX`VDY(k4ovZ|>zS&q(^~YFeU}+odEX|(s$%a=Ycr5%=*_DAmLY-CQW2@6Jf(}AZ|AKMul*Ucy4}CI$X7mW&imnY8b*ycayaDw-}=z^#%?fiLg*=X8pcWVS2@1N2i7W-lz;n#*N^{UtNdjg1U|LbbbSoaThz=HgEnu9fX_~%EP*#LPU0M7=Ug=Wx;s&=xD(^KEB=Q|^>6|l-}6IbXFYPy>-+UB)}?~fjlD{8bmyT&Um?xwBuF)rFaLW9d6?7Y!<(qjhp(&-vd`1a3)nMKCjUI$5wZne3rz%KJSFozBXwujNPcLEq^tWu5p%78R@$$N8QRSEL^uAin2C&}=8e)%V{&FEJbOQg3@-#u{8LAU!^4f3SFvm18@n!$Rjs}oNw0~h1D$*}$8%^UVW{W^+u7)SpZaNZCXq2me3(ai-~)_#lEbM(Jo^?FGFv=$#tFTR8RL*$Da>4w9Vzj5F5MbLBBOBS46TN4enIuG>BGCUVKv0r((J^^Td-$EYv^B&u5ch@%!F36n-=q_I0}pW%IyD_-$i|H?LDb=x6%^i*BZrgsbk((r1u4f@=|9=70$HUEQ;LbW8D;Es5ej_YxS5}klV)nj@zCT1f-Dk(`SC;xg^ntyrd@rW*dbhtiB>A=AE3TzRzDPo`5Y2$SK`bg&XfC!O{EFH>V`tzqfhdDgSIbG&a63OpHYC*nW8LPwMj#@p-VoMc04BafdvAr4|scYjY6pYrUdAj+FaazzQSBpL!(ZB7Y7Gi%B@ahl8I&GpmrdM(=m?DD;BnD>5qj-N-Y}I*AuY27;^fV@t6aK&st7Eqfz+8u9m)RTBdu+WI@LSs<4YBfn=FO@zkKoiZtP$SJN`E;o<^~>vJF`)ICIk8ypIi^bF>+8B&!5NKTUc-`jy`cc}soE7TK+N&uqo9wu?U-+VM}0rLUwRYE!Gu2MKV^3z<6scHURE)X7lz!Kq{q+&d$`Te4{{0)V-fg{>aG;qI*HU~#53T}4qcJEt>@zkF>sD7yUzk1je{^&V<*H8YO3`vF$1;wu$X6W+7Se^ysQ$Mfvo&Gy_)fqkEUa{NCX0{9<_J__)BR}$dYkUNs4G?pNh0XBwxgOD-Qu>qneKs#))XIqKj^8-{HZ|EBS~<_Fl275fJKdi6R9*^%RMHgJrki+u)R|S=%x;InwnW)3^INg!*6>oFb9Z}q#x2Eoh<>lzPb30==3|!6VaRFUb8FIo=6n_16m@p|)1cUDSh2Y|NIz|d$RdQrZ-4(mW*IPCrOd2oEvZSndi52TykzK(_rtv72<6`=oAuDiDG#+L+`5DKAGkR2AUFNqu8-FrO^GV?3TuMFBQUaz3T`mJa;1(L#4K#E;^By-w&e5{JV-u%4EY18f!~Gn+g?OFSqJ3e$@KgW#lgRIeocFPM83I;^Mf;Pwa6iyWil^bl#wgg#vuRB48J?fAeoxrb{W}hxs9e0Vl^c2GLd_qK#1xqAckd|(!~H|S)VfFi{*mBNUB1Do1IUT~17GShp?;&n4(kNua!t;)QlJO+Q(C*{eg2oPHKr=`V{n_~TT94j=k(m5iFsW6jkL>!zBt2`#M^E?!g&48`H(KADsLe6d)EEMbJDE)0_1f!gFr#^+nvXwc&;ihU$MFOV+0Ui{{;{6dg|BFC)>U6Z?Hzek4KN;P;a7IlMmd_-?QF+$8vVfb-qPBN!*~JvCmI0mBMb+l!tcKinebd2^pO96l+VN?JkJ|G#C5GpyJGh{kXS=;jV|#XY;%Z0p?p^ENLC4yn~r@j-4$99$;`!q0@!nv&k1iLN2gwchBsL4D_)<-361K@!qsP(xHs#W7%&fWrOzzfl`*=lW#%jV*+^>2Xy@+VA-)%+as6L<)Jyq&ngVXz@^?zJS*wWJ>?CWH3A0`f#|EzqlI21D75{-5Y?~ltu8#xM>j9P;8Djz)=&!6#z}EAy+N)-G(s*h2IBm`bOi6Omc_&!W_lW0ZNJ`cHbAc%|9$3BJc~PgS|zc(@(Hd>n{UqO3;VuU_p+ZxAEV{lAz&y_t9g@xbGxLnlUhqN~g_rIxmQxBeZIDsaYijRd2XSRPS+2OY*>-=DinU2RfvC4$MZ+ANq29f{ZTNOaPNyLH^yVS>bqVWISzRGo-vZ&qmLca_@kNWoD5f9zpkutM9+ydOcdPy<^TTOP9P`x;hvkPfXC9ks=@Z?4=%*uUnU!PQ=Z>B=76sc@i{yD#f3IMXfr3SJ5wpMQQY4f7*8LqgHDXIam!SxeL*0kby&jv^VOmRK>H3dZzD_Gm%})X6rnqazSC%evox(%6(*jA*T(nVOE(tkNck1Y#0lzlvP_*SjZ#h@XbyGps0h$shbD4C$8WT9XBDl;0h;vaXx_Jr_zHvMqYJMPnl{{`Kk8z&c*T3h6YX~G6s5QJU#yD@7_h!{>j|71OP6yAgDqXyu=)aczF9u$zZMaz;g>lME-qv&7n+SzN`{(!&3MRLP`6uc6(_XpNW+uu@h6BzG?u<*(ucBh-Sx$Y+fFya@G`2Y8eQg&?8kX9CgOQff;gje;jjDRCBVDdQ>sxRL{fFomcGkxSsJACiY(f7ijQs0tqaO^Tz3&fod^x>%{k`v6ok6UTv^jb{$ySTJfS*k1j*Nx!*xgIkuQy-hJfh8QaYaeA{bvOmlSR(j$q;4yvLVz|gvUrjwN-H-u#ZtC}qFY7OI;Y%CZC4Xmw;e69o&sE5|1Q`!8s+)tB=Z!k?QOx_AA7JPCJ>vlDxss#qeZjo1_FwY$ZkIi2b&KzRzQsg3zrG3oC;b0fiBePZz&qEXa!Z)X6N5k@8OE(N@{ck^TOtnXTT!ZvD3r2>#rnnLIjQ4|&?dLsj7YDu>3~zIT#$AJ9)G|#;P+}GOjwCbzMa~sfYSWwEog`DVD(09%aXwTm>$ccH7q)8vReBUshc{83@68TXdhl1hIal_68Z{%^EDp~Cok-&G(bmhQfwsz{14s1gSg7uSQJDvLWyTAln58%+a)&625-d{6nWLVAI4{~B(iFh_5&t9tX*mqqhsO^(5?LLa@rU`st(;ke3H%UMJEt$~wPFGx-&k~OVa_>jM`8&uz8+;_|vr*soh8}Nx3(?bv`oz)hbfD^05MKg%5pkUU`#l9`q}45dG$P1<@0Tx|kNR45+Ejei=d6hySChQ|MoQTllG7EB&b%Umt`0>%-Y6-JtXf^}*5%eN}sx#!ZTi4?KTnykQv+#zWMR?hg+F)+4L65}zUu;@60-Kq^zrKK<($r?+VKg8R!9_$p@TuBVDV;}!PfGDju}i231Oba`JyzKefk2Aq^Hzsjdyith)q->SE79YJJ!X3J7FI$zDph^({s1T~_Nat`B+dnIDU`pXZN25FyVv&1-;F&1jBXAcF+ThR>P9=g|gzsH??yGWSu>D*|&2jdYxrY<5R7Yjd1N_fN?k%!xI3SD-h`juqUXqXJf8QR?yb%Z+&9(k6;4L2dzDR@4UzJUxx|G$-c(Yr<&iY|?P&487CTDL>*A~#$RCT|RLg&IRWeIGUSsBY4O8}T*XwElY*=?;th+Z(CvTdxK}bV->}?FjB85p!FY_Ju>rqw=tB5!^3om{@Z2c~dlG9{9PB&)IU3J9Jn&EZLR-@A%WNjb1ys$mc$&I<;%20#QG4T^Id|$j3|ICe!i_{(d)F`?5)5wWT|`>VBlTRc3;G^AmxR|pywuraU*G^jrTv1Po6w_Nb<>BYr#yhj-?X(tU*h#FFFM%f2U}mUTnjymzGP~3de>L=P;maxZ^-cx&rgZ{8TIFpux@8U;7w)Z`orskHwwgozV_&noptCxItRBVADK_0J)cG%K~7fX_utW%4iz?vEaf|pGw9t;xkvrpA^Nrj#v-rC=D+v7JsakXkL4M9;kra0*WW_6Kz$nx>90d?Idm6_Ud*|H(q7X7j}^!(1?Tge$v$A>GH;&w2hU0CG_>_P9tOeJ20f?QZ^$?N?PTByi2!}xqaWV=Mo#-rdJM!Dv=_PYW^`;Zg$r0%KF|II7WLBDc5@-6inPXeufp!+oPW1(x4^|eyrzKUpY+7-I~X1YFi1x3m5Oyn_}#1-@_LX)>rGJz?DRJDDB|29Feo1OY*%%EQiFWzh0x58*c51Odl2iaj(+vz{_U6I)g;>d_nUNenst)>CS7wGuy>=fTjO2yrSa28BtJj0hCDF_$5{$p|Jz5iCn6PG;6C;7F5w4q{j+n5OfS8_$;Q}p;xyhT{!5;*Tz>$(e*3}9@+ER&UPI%-a5yKdx?a-`{R&<{L<>hW7hbPzjq`VI_wmcOswg>m5hS&|YJUflGC`l-m92kE>^zf>&Et|1WG!n4;tRm63-jvrQ;tOd3_##AnHm#(|M`oOPx)TRNt72bxFENm!Hf8I*P);AUu=C6B}|5);?8$jRmdfuFkRJV&V;su7Bz?VmM(I~m=8hh!)~;GzjkzW9H$kE`j$NL{;$8EHO85%;jp_;KM>Y>FxX#Oi}B=T9bbEYdpPX6p0`wzZl1z}m(gmX$x+}ssvwcE1mme+sjBc&Jq~niCKy#ikz4(|_{q>U3HA&tSjjPBoJ1a8&a!mi^!u?@HVyfRYouEug$(`svfV!mp-0s{ZWK1O$b_%`uamp!>Mmc2-WQ^n`N8z5X^ORp`y!9HXMI2Zb}$HCZ~36h;=0IFC+_ytJ4ZmnYeOeXO{YaJWMd-T|1ugbbmV;Z^R!>&L|#Pwop|`zV;4}=g8N#x$JwR152S#@QJ*wt5$i?%IZ4YXQH}&EO|u`Xm;TSk##CFTC#q5)KFX$m(D(i2gEgIr|HGOIygX+z(FvU{c!H8~GghaQE02#bu$eo8s22*p2+F>Yq0Gt&z~@G`0H49ptlL8K>Udih+Z}UBxTzA-||)=;rb|fi^ef*gNFs%|8V5=cj^@r1gGdVe}=ga}?+Dsw3g%e6>k(#9nCaG*zR9V>cwy(0(gDIJ?b-Xj;6Ppt7t@dV;I=7a|N57AGg&3n6pL16z9ckP?VRazcq#`{LVH{~O?!93_i13U~m^7P*i#M=m)u1!9_Hd|wx$M_KW@*_<*bf%ALYFrcfuB<2KPx1sv;*FLse4(L%){O^Yky~u``5aoo+#^_5se9{M(s(QjvwT9~X8^~FUYoqr6^M#dJ9~o1Zpch?TaWo@IHyDy7bFC8&BPZq?vTTch^rB61@9FwoIIl>(r$C|pycu6j6&H}(Nto!A`ou%QU%tW`H}t5RN~uEC@2Jo9vNf+i(Va_15AJYLpvFP`9k1wvF2s{K9CK>{#i9Qdd~g2plz#@JfVU;uAFoS?{jg7Ygq*NL1wFsfXG(7&&6%qMSi3PLz>&nx@9@YRaUA6n5#wrYYD%J=W4va&j#KF<3g%8Mzw$UrR!rh_0#0ExLZ8996xF@E{~qWw6ntEQ+F~{Dh7}o-XYfoZp)*u)1mU!iR1FM=s6V@DUE+FQ=q?g@cURY`b=h9-xrUsSx_!xdPpt~z2YLrMaiL)UO>!~pJ~AR)6R9)_ycFg$j>9Pcz@TCUzH2iA@J(b*g=jP$cb}dp6UqjZsMKOGQ)K>)*q@7V~ByHCq4>uu;RMB>*7y;yB7~CGhLD7yU2IHWu3XmlLEY6oZdDC=rcs0+0;Mj@M@soYGpL~OyrWaN)uNpFy|LCaWxh_L5y-#nKGOOx5}*_a2KK{RNdUg_Oi?ymKZ(1{3HO^mFwgBFkvNKkTbFTd&7>PFMX1Eo(@DW81hxO<2(fs$$69ntMo){kr<1IUD*wbQssJicb`HcyNE0HC^%?;2lL-Nk4?rn&8i>q4epBq=DfZu_e|;LlfKz?KrSy9?rA&x+fKL77Chtj@RU&^IE9cNy7FQ?gnvGdPX%J1vWTvpvFh*%vo{4Kpnja3st`gyS*}@pY~P*?Ao?QjuSb5!yRUUZBpY6ytA03kuym2ni}P$6)A5JHlWr^x*>rxT=iAUB_oN8EnrK4mhVE*RCAgGaR*QVCdlp$PDGP}Hn!+{~i~J7f5`mHVT*y7G%a}ig-bMK9)N~=lh-j1#72)~gt32gdA+}I(?vrGB$b|V$`+Ib&uN6kXM?Xua-7@H1PKB2RIFh2ltLTE%T66R+m2D2UjYs4D>r0l3-sRabQ=wdy1R7FT4R$5dmBX|B@{WwlMI`}%Q^6ufrG8&7INyZul81a0j&G2&#qjG_us|M_AZYc45_O6&(aT}w^+RADvP@t4r$fm@p*LTZc)3e`!jN*KuRaL$(kEE$3XiPq5HA4{iVyy$d70^u?>49g2%Edo;Es8%srYY`tSKpVlDC^t~lq0CKBXEuM9Xq7ms5?X1{+(2E0-D?D(vJ?i?^^>p7K%Y>2I|_i@;Y9!2y==s%ecpLe?z>{^QXS{EgAe!saG1p6m?N`}MGmy`lXEdCndw7l`62ING3AZ2+JJo~`xL;8fg)=~42qHruUFb1~-D4{RyP%?2WtV#f)uJH(6-KEV&rDYE;q<~QgU(_KU^r(1;m(SC-k>GP_y>M+E@`B{89b1MdaA8)2O~f1hs^d%W^6{xG2qiY&z3Kdl`uzFAHxE==x%h6Ip+^ztj?a98U}{A3z~%eMuX%0R&npxT0S&iZ7g*7Y_SulcH}pk9Ay@e|8GYnitb=n3hhl)ar76a^4Ec3+vhZ{51YkVG$eu-4M|p4+m%QDc6eyj%#ZgD+SEkkvS@d6~LreB9b*<0HQw~){%llH`P4&f@bqVN2wL9CT=H0TO_mR&1m_6t}L>=Yevs{?itH@fyg`U$BSK|2nW)K{_>N9_mE+6d83(|#I)o_S3zE`Lzj`y*R(w3F|7zv)YqWk}*)Ajk^`C@X}WDLBkEPE5kg7;T!JbA{=Fac!m6)iiKj{L#gf&#;i6woku)DgaoZobmFr6wG`>5!fB;7|86x<0XY4kaBmpa7FYSE)$}-5hf!o#qR>vViEXFB^`Y^S$!-^?{&Vu#51GGYmzqFlA2&no14^xe(tQOlR=^dZ~;DEGxpHf4Rj{Mq#`^(T|v0FADB9-fPjJJD1G%&WQS>9Sa42o(OOr!gViae7ikQeLoZV6wkjR=k0{S_MjBl^CIB&hX#zNYMA-}{~;YT_@pDw$I$hUofY-Vv7mtI;VepnEBZ`JWBr~X$t+;K{34uSSrPVK);kvYZVD$*voN=okboHLp51`&}QIHeg^1!VS77j6#T0Awxc!>9#j!q&Fb=U(NFrFUA)}k$ZskD3&**|n1xan__`*!Mc!R0QyO&>7MoETr7sB8*Mo2uSj0TW`S~A;=<%o{C;1}Tb)05JQpH9S#<8rMehGNhtta<4Dy0Be!J4udn$1K8&+Bu2_LNY3R{$7Ja;oV_W4ksdk(Huualm}B$h4NO&+WPU3hX4YBwAlD@m1(8+y^yYta_UYk`Wn0ne)h7`j?C{rja1Bd1^}_{rv1I68N;=pxhP-b39;qjzX|%a%3+5Onah@)*luXOt%YToY&*8P8v_S?~8X9cg;*0S+Po7(t8q0$39V=dOtwfI^_C0Fqb7AlO?xc(|!N(6GpW~K$E%I`$1u{=#B0OV?a&nDFA9LjWcjlQ~DmWd!xQclR`q<;A@fN`XB%sZ&{)gv}fv+CKd~u+FPd#N;mWR&A!uLJ;#hC@&0{7ZJdZ3SO;aJ%;A(RU*PLOg+EO8$!-*DH{_Ob$Ks?_yl)<93Q9DSp$Y)}Gk3x@X31tSl;={n>~{d@eypy6V50`t-txnB3ICB=g4?-$-$LztId`)mCt|F{G=A|;dM@Ed*1zvbeAbFY)()S%SR5n<%S9N5m2=|GGXk~Tt5qvbDB$RK;?Yu#)ydKxj`u6IKwyje)C)Z<3}^52(JZ#i<{g6maf*#Y#olkUsI`n>aj^SI(AjTLx3Bip@VDXRC6$Zf2Zd5N6JTj0>8`qJOA;H{zPCmwZ{v9?cQ;HUY!iccqy+mK0(59{Kg^~T!^wra>jM8#Ajr;{LYk7jGE6x|%92QIf%O4C5`@yxBKbpF$7f7gH6=l@%`yBm47&%$wj>kQaa%PnvH3c;O{a|&fMo!dMw-si=PRI7cq0V&qRLSalUv}g|+%3CFkV9YcP+=V`vn>2?F6R*P`yVdm484p5qRz%r9leOiYwgsE0b}%*l)VaFo)u9~aWX#@)K6p{$nru??2|U?kieA~fJN6IjD0>-rY(;GLtlG-95YA%iI)yt*P@yQ=a{5s*U_B=mOHkw>^PhYGikr7#cI%h&XgH#54c?bUeftXqUid1dE8z8=q+0m=*b1jJ*2CDJY`=uu*D|^9Erge$;hv&tYBCx9uL(A56C3^Kz?F>)wTCBN#M@>F(b|e@Bf*b`JrxED%5dIrVM{WPV`5e*C4@e#xJe&$>=#OYrd|Sj-vq4x5GjieMW(3oVGR#Hq7VMykbCau}N=R@r^YXcKFWKYSoS8(MYTsPLl{$0ih)rT`Lr+WBh|3BB06XSuHo3x7&?{CuC(7{hmqV3zv=Ob^I+F`^pn+huwXBNJx)72*i@f>(&1&tP51+^mNrkp)<_SsobcUo3pW(#^qK+W2q~Rr{9?uh_T%{b?%CbPc@nXo`UOZ1E`qH~t{NKN;W0>DH!8CM;If45A3_aJ)W{tjd`_5(?4&D;@=HXJA6N~4Jdww<^9~LVG-&f4<26o`}xtfnxwofF0#8m0~h!^NlmrQnPl7KjWb5uuzj1rcrhe^{QQB_OMl_M5Ro_EK9~gBN0%x5dxE@WvRopvllok9S?IGxD{|N8R-w~u)bHb?%U5aCAW#0mt{wW5Oq;K?tQxuUUpbQj@k}tIK7cFJ-KSa7JX@wA8@RUz?D;f_oa}vnJg6uS4o2)H9nwU_jB*xKhNj#e$KV``wZ>%T5H|weFG;yY!G$$b&!5!j0&gNU%YNFa@Vw62$xfzKPZ_WwK5vR^(Zl`z>9L$cVNgNx*>(sKZwY8pllC;GcTqi--xT^Ul>x7db2tPRHkeb%+?}b@rSp*y7Vg!Hpa;>Ju-zlvHr46BMFHAzm=QRw`iSg*I!R6Y>`#ow6Y9!U1u2^g-U>Pp~e@@P%>{Gms#zm&eH-kGM8QZgtPCCyR$`U-`%pdYU4kYF3vp*hvHTL`c#k&4xE%Tg5!ZTTnDp|b1E&Y9xGK*fLLeR_7J&($i=o&4uBHfuHXZt+}Cdbt{LXZcfjGR(GlHwczvP{ZI$W&`0z>uXn)2w$dj7PE=fT@L|d+BFWJ0gPjC8Yf`05D->H}r5DKf~LFltM`r#R|9~;mM=RE)4lKKS{|C`-WKPv*HhyaTg^hvbQ&KQn_e!g{WyPhM@ROhdETr3g;PhPz$JAEE~8Z~Oa{O%RU$@OZTLH+Q$1(wR25`pMX&Krk(vN9*Jyl_1QPSzb!98{iSTxugt(*EYIcTx>D5n!55rC+>{_3$+!Vmj@*QQ&d>`di^0q&oa>4~-w5j)5eFeY_VMP;dRY`;}{X9Pr(ouaPLU$SFRqQMHf{|O^W%j!uS+g-zB=NP58PE8^!RY4B|KzCsUwyv}V#ri+s@gL7_$^%4Ed=%nnja|r>5Zx!;dmLSg%=XchHgmL;7sZC*hRBF^t=~BVFaD!-2^cMB=p>Lf3)kJ_iaX`Br^;I&i5!EET(R)7?X&3YanycH3GRigcyN-NyUZUG!HdhF2We-fO*~nLKg+wy$><@z>)+y`cji?uW+_dHF<8YWNH}ERCfchutTplBb2u^?4`X{I_d}H!q>~IvPuBk#1xl7;wKJ&P54Dh{TIPWMzeZF*YfG=M>u!oVVkG9BNf+xc*|4k&q?(U7QuMQz!5$mnv@>I~fC23~phwEA%T8@v}meT)s-Yoz*is*-X^kpz4KJHV#br$tgk7PUa6v9A1g>Uc8G}Md#R35R24Tmh#KPd;tP$&AQ7pO*Xoo$X7R74l=?PMZtda+IyR_QO_+3YHLuA`QN$7HKe|f%cZJ@XmRlF;=?(#V$}J5ZMnPpQX*BNqv-OSpI>m%_=Hvrs|)Svk*eWo<4ELaQ5Ehn0|X1ifXv*LDQMx>G_=Dm3vrFV{$3`79R(4|HjY<}^}{#M%CWPhsJ3=daDAix6I4{^-K0MA-=N>x|p!PTDt&t@5>f^)nLgt*mjFk;eN{K6p4!^2ESZ?_)IGI@I}xZfeNd#Q{-QJ3#8|?Hu#Bj3Jc>Rku=2rfrdPI%+z3A8n(6-Knxg4YtTLN5sBuO0b~8;C5?EA5zZz2{xGjUK9eqbLP*aPLs|v_L?5-+#LqzJRhvtb`|ftebdnd!L)FQ2ui%!D}eWHFlcM}vn>J~-wL$J6`;-@?$_tdih@h0Kg5LFqaPuY7jK5y+_qzvnr)ma`uQQk6gM-DgQr2?CO{f_rg?6lY1@wknEcS_7PT5Vq1fq5Zq8^j5Pud|_97=xMSX7{lc52(^=^9DE#!f#>zeP{d4#}mp)Jik(ddUbfBw@wjI)mSdo%j^x9UvekIrytuocidPg?gIEp?;2*hX;bM$A~~^NeXwS+r~vET7$@m~$0<66aoDuZn@$liR&MokgE{AEG|@TE)R-Yi%oMXY|R*Px+hxdep}$j-ki{vmfofORY(U^xoV#{LhdFh$t=x7XQzWj?+@1zv_i}CAr94Cj(M;(0vCQTT6^Q{H&Ysp4h(4zRe_dU*h!64=@iK?3yYL`Ucu@o$b3qT=EOpg6OV4YP$9+TZSic3^>Z3S)A2uf=k4-k-ozbswY`-7WYP2BoZBfzR=NmjlZ>gSHj&D{x6u!P%2A~*=wwZ0603TYRPfsBqS#m&XYX{Ks=<8}&hkT?xvA%ndShk*jl_yDsV>pIoHPY?6Vy%zOaHX$>2~$5hqqRSxp90F$!!Bdt@WI;MTlg08Ng+JgbzDCJv?>r!0&>OD-jHh1P*;SBB%3M^`DHmVGVrTFJ?M|>gINP_B<-lUa65zIuDrR>sxMB%K-1={8A|-{%Nz!&6Cb#kEegfH#_s9ZeC-supNc)48A8!i@$5CK?O{IFpA`<7U@X4UL(?C5pe}B;s>O5;2i=LaapHs6P+TRQ#SIACkEIE=F4h*0?8*jzy-|pd8m1e)+cCNvdGNgV(4i9)M^lTy_Ci~}}u~gJOm*nX5b4SDR8zt>Q>+t%4jplFZ{V|;Uv9yP%6a5#vX2*k`vi)SH9r6s3JJ7-A#uI-#SLc#)O=qdz5$o2X!2DyP`XhqK2|l?#Cl;w9aiqv0{c4PG9?nMz$8B^uEc0S(scjGZi%aur|ubi#4JOTB_Qq8Pa?C+O2pD3t}ewGx~^{WiUz-m6F&jR03eBF}Sq6&)lPuEsyN;&@8TGl%|#L(lc8(_2JHeJZ7Q)mlIV#Cu#cm|a5ZGtOk*ZcdAY1AOCBVs_}qta(taRx=u&UU=K?qkw+ow7qCzyskHH&5?%HjAHc*7urK=jIq{M1?Hd6Zd<(0`wv#?L=FNt(;Ye^vaL!HSCe^pI{|tAqIa}G0F&e()qzR;rU%zY>x8ui(h&3G3x8?KUrH~ONU1Si7L~M^#AmGT(0%wk#{-$^0Hr|&t;wRk59Elz`K0PQ{e>k$yrZSkAe%vj&wH0l|zN<~@AN1FH)*HCbXn8^;?dEU-M4h~#cIhK>m*Dkxvn1S;fvA&;aK`m9Vt><%{khZ)W_W}g!u7F=eVT42_H=l*TE@;Q3VG~^UqTSwg30N76(NFpKvU95p2!rS1}-a&CDq|C$y*+zyE78z{m#8~sT*@dwM@+NLvx~FDf~Kk>I~{10}t=qpdSNrnwl#gj3aj`eV)mGxh4)8%Dfa$`=IXWQ|&ZR?MmMtRS8Dt>?phMGG{Y@|`YZ_H8>n4kgC#xqkC^$0ZudPy$>u4L?T+?$6wkt?0VlLBW7KV6Cn$NM@S{GEO6PXvgyucBX0K|Wb<#fiV!JPMo(7WQc0LOtx}(4uu;qG7%X&?@Xv-<35pzqK?L@`4uj@*hLp?eW|AWp(jT@p`Z((iC;Ej$rpm`6LjO-Hz@GMs>5)&N6`L%XDuH_1k}wO?7-&ock;^u{cqU>=u{o(TdC1;R-HY??Cl9!8ubuE7rePU3*wM{!=Bqth}=faB;T2cS_XGtyXTr4=0jNR2D?duWsNx=^BFw=1$a(5W&#Ce~yWr;x4LHrO$UZPuV{1j+Ifg1|1^P5{x_bbz-_3WU5Yozb%NNeOMTYu{l+vhSk`#bh?k#klk{5n50pT(&YGw49Qrh4%Gm8uAMctY9Wf^f~H8{-?fEB5WBw6|c7sIj8QT@IK4A6i^KwE#ASOL&hgeqK-wE2Y#12xIu=I_<{E(Li;wdTO(LoccDXJ8$)kIo8acr_Chg5C_I!chiapiH33qeit{M$TKrxdc+4BwWyYhosmUN~c+9|kJ@UYgmbWD#g;dDj{EcC+L8@cdqa57^bWjb@KIwV}$J6PSZpz}{49GXik}xj7@ic8ld-dXFk)Xsa*m|9GesG6eghb#;_WSMK0d^ATN4fu{nPO8kER(O9`rLr}-mk`$*BoNOCUr%dYd9&Nf&IZ1?}&%KCu?dKo=2aB7W^Mp8z#b@S2tITkm|;-jxSql&rIg*o5(t%PyQXJen>K?kbRK(`*k#q`;LLNdkmJ-!RAosp4p`RHOcsbDt(U)w|_&O$UFXP5(Dv)+axG$(_0iK68SZuA+Na%EF0g$l&_t7t0fn;#zY)nbp!PCquTm~{|2DtVW9MvFaz!v6ddiJtZ+=n8zY07+Jfz$VXE^=3~cO@v|RfO6>28M_VVeD+SlPj@g&@QL7kGT@bhHa1ip+*&6!rKqU*RJp~kX%8{@Bnbn09|4Rkpe9W6le0|`YYpcGNMgx1;?+Ets`A^pg+m|1)E*3cFmFJ?K`zcG*v?&h$E~)hv^F{7T`@oY^RhR&C8-zAFbD{2c<0@}^e-dz?&UN<+K+buWW3gvKg$l_sV<+mRQ6G-4Q{~E}!IS&9#E%ytFMa#1syxGRc{OQb3WrsIBSpz`l6F7j!9rYoeGt%jE8)wASEHnaMVJ+T52}`BK34M5Ovd!=QCor?WuCz0;Y1mn6{2U()XMeJ$FVvE=mI2iDG>8k-!etY3yt&>GG?7sPFP?%IVWfLS=$Wsyn_l`X@O`AlWSUBl3_Tt7V8I(w1qpy~hKup&z23CZ8AuPUrAv>@Yw-g7p<$IQJmnh~qnP+-VS4uu^?)NDzsyh`Krpo*4MzF;hhQiare%mr(Q%#lnx?Y(*;;`h2h;a>>#saX{o}Tyj94ZccknRh>$Jl^Rag@Asn5i#>A76*nh=Nzt|!!K&!9z2WQT0HA=uqumd)SD?=*+i|reHB>OM7}HA6Lp`qalX|rP9a1`e2d^jb)tWHj2M4Y&K(&g#s$(4WswYKGx7hPRB1dPEPXABev~uw7v{4MGJa*3cE{8s!mAWt7mlzAHSg*G`j-k%O_b{S~FCKO~egC$eR43+Pvg70dMgrK|#dfuvK%ea+-bdfEKbK_>bL;2zp`Nz%qtmK06i_ib?zPx~)PF~X`o_443SYBz^$(KruZZ<%3NM}0KP8gnpXd{sdx`5+>adfVc~}HsMkzRJ@CtE)QR8u*YLRFInT^_E?NT(pf1KqK?$@cgpbaPcPGza#o%eh*~8iy64Dlz{tvM2=#bJ`0Gvgv}RF_kO`NIB%E=TQBL_Tm3^sA~eLY^TwV8cGVjd~;3HR@a^9YLV$v}KR&ef>@KG7LZh>Q9mu$c*k}z{|Lzbcq4f-Gx%tJ(^%bcF%%F`-AA`qgp91h!R^9erCWhQ~$@)rF{PJ|zIq$aEz(M4$prmiYlK0}kcS_;3z*pSwle4fn&n1%pA7?$5EayY+^5)@Qlv9}qa|HRN&9|UVWY>cl*-IF1H|S5Mrc=pc6y=d!H18Bi2GPTz{1(a2pyPU)qzG-w!q`-R^bd5P=gx)bt+ap1y}ukut4^}xDiCu>9#z~^7~=~O4wiMn~;j6{gub?2OFKI-!Sj$0h_NCs8^jzC*d4g>q~>w0Ss6&U#w?zUE_UwS1x7T`t$>EeKh?he$&kKDR2*-nRQUj0-Nd*rJqy@luV&N4yeukiPh705r~_i9@Nx1<1ZzH{pg>bK^U_-d=A!RW$@4FUYfGsOP=9dxbkKTYb_vwo@h;sQE&7s#1BQ$Wr+So3Q`gbEXK9(ZKPEJ2=OQ`84CataA7YAq6Y#bf0;e9=Z9+-)%CBX57nhEe`jm^1=n9+9gphiJwoMht37W&ZeWq9}U_U;MJ;#s}T%Qjl%yUkKwyRNBgLH8`%?@;q(B_Ya!`3?+KTM#Xv)f+o8am(I*LVxqmB3VaXNU3uAuy7AH0pIHZKQ158_L#7>lrfqqy5#mpW-hy3!tV!n_qpW%s&iTmT}fjH;wWr%)Un#%Ti#w39B=k#_SQeQ~BZY83D#surJ`M+RKOGOfX&IC6O65nre_j)EN*ZsxYuVM-}=rEkbchBoA`dp;lK9uyF0p>&d=4S9BpJ+B(l!$1u;IikUIfqM7Um$ySCiZ0ttoXGwE9@NoKb_L3HN7?<9x_)K2+q0r|9_ri9SJb?`kAZD0n+;0$-fk?{Yfya^F*$dv=8e%96PQ!oD9VM7cNAfOOGcd@|siOhmj;tM;PivZchYzUQgtgyeH*%5&1X@*XUq4f4R%|`=}H7Ki*{wSZ|`WRmc+kZxC3&+(DEDDvT8i`xYWc$=KXsiiD=XPro%%)F-GDJiUbdJ_}BVd|3V#c`0ch_l+_s3Iv!tbN>^-{k~_PjyBOesE}x&Giy>A*PZyv%9*qMX|Sp~s&Fy{dC4+rK~!G_9dhT-lnOt@90sBDwQc2VnIQOG&}@1O)=eodHNRw1%Ys+5_`6x#@Z2B4%`aG~@bBXWOAD=2|LH`Zpr)tkaCb2D?D-d1-~Od>?vrqtEU0rC`tdLr>*Up#hrAiOY(5Nnpk2g;Ttwsp>b*(^qEE$_cgQ~}rCMUw45=V~HzL3+2YH6b6VW_M1E&Ws&1LUkebkhQ!#!s|IG0HL<I;ffJOou(kmwLgyFkjta=xs+JANt!L_(yas=`nY;A?;W^j{jJWon2fTp;C3sEub%?aYLXwh?c)7UVH=_i^KobCQ62zw7L;o3JkZX|P%2*K5g8v|aGa0X@`{wayz`ic&dwcQ?+XPV^n97N9};Yp(2*si+Tf?^-UPNC%G(SGv#rMcva^S^teId!9abd3OC3(_Zc2yY3=)-OQ8Nul6hh_F9SUF)TsudbKgZkM2BwHU07_dXJE#CGADc5~KuO;aL69Sh9?-~t4?h0S<;;o=%3S4{9o5Qmox#;-|y89LNG%&1Z-l|bU{&~N7x5(c888ETH?TM%vat_1QcuP3@`~AIrugBiGcpYK8J#B4{$-w#VNz{Mu$Um@f9u=MyZ4J(@Bjvr9c-cgKrNYX*i)Xa=;(f!WZoutn_V>P_WKm=%>Z{Tu%6G13fKOfUsynyPkKU5w9XErSz-=R8;An)L<9hMdyAsJ1;H;zUMb42=-LXciFBK>&_Rcr7L4Nok+phVcIUT_9WfEy_y&O#Mzd;+P0JdZULXNg~&M)`<_d^v}1zZjRgf!-K2gx+nPF^-m^fad+K`pBy!GzT?0S<-eGeid)zon+BZ}^Uvu`EMLG!FW_eq(aGbTBD&zOso&@@T4z&$0!u#IPF;08Kp6{$Zr2K1cHtK(cZp~I%Ooh2_TRbFAkj@(pz0Ml@PK6ahMyupjqo19lrEVFcG}!FDO4OSRdFEF3>w0Tm1`y|sLjIwC<)VSN@jfPWm{xTyl|Y|5N3V-B^I0I2epYPU7MYcWT+wASDd6tc>LX@_d@{UCtgR_B4VG_T9A7O>|4-LnCa`}oJqemUf={$0pwA+%9EFab$)Gab?3`hTKKCRZD7eXdS=;e*Ubo0CaL+FqWX&mFD!B%I7FYc!U;mFi4`R=!9q*Cq_9;#a4yG#byBSEmFTXNQ1sVw*qd_kfWG^?~Y9TrNfyk0r~p1$Wir=&&>$}Ce(`uYFI2lj_Ue1%R#A_1rLW5bX7u;e~7%?1*cOXykn`$&L@~7x@m`1fY-rvI8H2}Ey5g8qQ0f-S|;SKH9ThU4|Cdyx0S_|Eq#8=x}SX`sj_%fpUM+VCJhopU834nQx4?jjqUqOidHB3kG=o<;zWE6mDd5>d##r(C4bnKEVpFDL@>*5zIu++5JmQ`$;hs6d#;)K7SVV>?h4f!_AYCLP4S){eS!p-%L<7JkJ5qF-+7DE7yh^UW}QlNt*G+KTQ3{6<}GV*ZwK_PoYg{;!`A;B^L9M^^k|r9p#FfY!bi)DxX{PnwryK+WV+*1lHcuE=s$q848^@PF9-pxy%cikJsFl~Xu5|GXNwZmd(lKZ(9>3i%^#{53M?%#ejd$?<}SWAz%5))w5=Ev7lw(6n_w@?_t~bSnsl+6jVVJnU5T$lvlf3xQz*+0g<-jw^8p;NNJilkOG{%1bO7ElnxZ{l?tCRRG}vd69Ci5nYVzeC+*$4RMuXK7F(T(-Z;5U+o-zH;^nGdc(_(W>cbLY>Ibxa7*Es=<^)!6jf}H#W}yw?M=%0yp^t0Zl4MtzUj%fkowewmwcCMw~`s~*3pK6r=$j5)I1FXPZB`|I_6cZmsgIYmLMlaX7tcv3}vJz#-D!n+HHo}&Ln9u4g)4Ox$pj+z*W@btC;Cz5#IQhO>ft-RGW1Vy(Sq+OFcaI6G8IT#7uvgH_j`vl=#ZM&d0z+lM3Rq^eP?b45cQZki|GI9QwCP7<7^&oQr`DcSrUEz&b`#?SV@JoPitk1Mo4+}Yig71y=ib*z;^M;X7suI(uH~K6VQ}^na|X~q!AZXlF@Z(x-d{%Y9}=l_SJZECFMiU#Vee;V#nr@g`19^?l-pV4tMK;hWM5wztnwdso+F9tSBEO7H}x&(@ba7O!en#Y@1x8L439Epz~TobrQN}}-`7)mTvot?2}BM@)O{!N2S*LN2m(sBKYQh(O4`9}u4Uaj@c}B_=DnpHwi!d7A@&8Gf>}U2ebL@d0QHgmTcz~pvY)qWZw;JwLLQszTzL6@Q5xvf*pEL_MV-h=8Kh@G(zuaiEsL~HwY1UFswoR14!<1z@CUE2U?@G3wIvsn{dEmI{n7vJt+ST>GN8e}V#C^9q<%D?)9igrrRY$-VAbK)FC@;1KDw)lpTWr=HhYYEiNcS^5>iYccyNl;AMm}=tRTv97VI(&UZbB&>f`(}`qKBODKK38+ElI!b%P)~$T6MGL*gR&>0M8z7@$z;o?v2vI*}KUuE2sV>*9GfJV$+_#dwA-o1+@e8rFHZB1ipNnx%GaWg6r*nz>%HB-Pc=-k-DSTRQN3iqwf=k@DNA`V8J*nb0TEDIczcoU`|Y!`DljbKtwOPfd?L@=T?sx~qr^4Ty8$2N&V%V~%w4r?Ka8Y8zL}av7k$;?=D{xh^_LIgOdMk@g?G)=O-v>1M!MwV&SAq}+xny<)>qHaBi(WbZ4m!TWwx4=!pungYFRdlYFa55sM2l2-TQcbU85awUSDYtQul7gXgOa0`)O5`vU)l^TQL0X8>wI6Q;o`q>(vZ+miMkbg!ngSk3r;_OCOt{&OZYDQvd0y(RA{?4>u}~Dfk)(Nh%~BtFq@yLK`@gY$d~CD##s$=0pDlm+?riv~-!kTe9`mjqT6`Y?h|GQ!bj_+~zD?iYp(|~a_wn8ix{m+tM?WZVZfWbcPQcHdu$EWYpMM}+l6&<|0UN%=v8dAG%OyO45Rd5ZhGwAt^MYt1}SYCe9>%cz^%Hc%KKmiV|Yl!5-Q)Kr|_pTLBQH-EoN6{7#NbQ_24ViqS4HoPDG3w>B{+?mZ$jKRzSYccdGSCsWT#vl#&L;osvJSXK%jVM2Gs!NCSvuQu`B9KFl^xS)zbutrt#jedeYeWA}?+Vr&j5t7pV%1+&)w<}D*ZGQ=@(c|U1C5vdUV%QVPtNcKuz$})eadzL^yv+DEo&1PK;*=9iy%kYNEob7Vb2SQJgO*3lK<6l?OX{g;H~~V&3b@3=RdDg{`c=o|L6au*5L(fA|5PAgZn`V5*t>de|n35T=4mHNT{dhjekPD<=ICO!;cv-96KIl@BsO$K>yKh{!u#Yu-S4VR0Gcg{!FrreD;C?5y3oWBiC?UYjD{7(DX|tbY9<7qf>_KS|U!TrTTxdfYZ0_3)ZDS%m2wwGf0Ic`Tkb7BeDLRQ)kCN*~^Lh0dkZQ!aTx%p*mP;QJaCjO=!-paau+2j3*A@65$F|7xeA81U)1CuN^A>IK#^i|m4!P#Rt5+_N8bqTc>!Dhn3n+}N3t&%7K!R6li{NR#aCH_2L@p;(F^eAo7jo`J%q9Bza|dzkN?R1PN(eCsOYsJedxU%S-vz;`-&TRAuK5)rTZIfo7@abH~Tu0sB4Nvo`@xxs)H$!nfH+lRWytoP#8&P*W2N$cCFhdr2Y#P7#~>2^u!%l)Vm{mcR%rNF(0>%Hlxk)xEZq|T9&XLE8e??w|zjxoW&PS!V~4fTXe-}HZ-W&u$jVY?N1$;rAO1q!Bx^W{4y#A^uJHYg_ceIPwf%w(1O6QSTz%6RuTS)Us?uS?0bYMSHPSj2QRkGY#{%Pv2SzrYM25xfAutc|WR7sHTJEp1nLj8qud^LU5GY+YC^fQd0LAMNW8YXRhX7k_A>`djuu5aNH->XFe3>K$MqKZV>7G;QND*7N{iB;q1HRZ}mL!zMrCA>kp&Ph;*MrdfpjeO*D*2#Brba{XJ95f*_GCv2H>*ZmygoK)WcM1Ji{ov99o(V)=Z2bW0MK1HY*9oy;xoJq)${zF|A{}+=t8fY&>s}J7F^2xvfPvDJO{s7;%qO*SE%M3jbJ8a^UrgiFi`tNKJBfN@$Cv4F{I%x58d6`sR5Le!Wdrtn@Q!jpS>SUQPp1BS3cHrk6s&<;odmamZ8LA$v+>icS?Rd;ff3sk8Pto!SQhpavfBS?#6`~9HFP!cr?HdMb9eTYj4QkHSWxNeR|H3q(a|7P#aCrR4*tP@ce?VAAiuyhST6fUYKQpUHeD-h_9$$tKWF+2Ya4A{HnuHOB(CgiGHq+`}Ves?xn?V+cz51nJB8KZ)#QMmCC8@Cf<6-l5UR>9DQnDwm+&K+4HS%^1@FQRKS}l%CpOpdIiN?bYSeO3El=Y*nJ`>Jg2yPni#6CFepT`}EmTZ8>PXi?yas8@hN!A7K1$iK`Ns4v%E9#FNt9L={CekaJkV$uAR()8L)P#?Ln;k&C3Nex3E}V{^XAknaag=MkqyjD7x(3}@bwqi57f~&xzHJ({cvCfUVoEjqs155d|)kc@zirhpXt62rSyl{&!v40x=9O>TQU|N*d0^D7a0EBKq(M>dlQ24p%fXVe8ylo5ZKcT~6aQdg;rvVGXx;6k`&(YptV5wc6HPs4(!F@I6SXk80epddZ_aSfBGfPSTcC$IdNx`4jv7a{9QD&LN5n?s(x+#)R%ak3J3MpkAjgdBQb|1xl7N{Y_s<=N9u)3cgjQfPwA9>?OPK`af8uTDSkCLSsp5hd(J_^jn3z*c_X5xZpagT4^(K&aEAz-(>$~0MTc)=PfDcL7hv+t}zR8&7BhJ%8+x`u_r>Q^*PY0q*3kEfSjZFHG}7jM;^GnyZG>;2x*_o`vvm|`}f@YGBPPd3a|4ioV#?*eI|&iRCO=DhPv&By{mUJS>W5~!+u_e2DJ}*Ws%mY%;wg_v)}Je-!ffo(mtTKG~60YVnJ$?z&*{UsOOXkv`bP`;C_u=L9PqQ&&q*^V%4dfK245V$SpsGt>dB>rgP?@E(+*V%UELLXRizhGZ>QzA@!*VQto9n-IQ}@)zEgQsE^OrUsijPzZd$*oI(-fkdi*?XuAfJr@t-%hWISfV+;^^j-;wgWtc$0-L}FQx-_v5hbT<0jV;8sQ%(^i*D+t6o9*^L-EhfL_6OnYSU6?NjAZ~E6PP+!%@`ca5{^8W9=zg|s_`cMKV3O>Zgr3Vd;Z?yQ23Zsf3=@WD`V;z6LPF>)i6jou0*~;a10AHQohuOnB(XCOI%DK@>&Ye*G^w;vm*6X)RFQxznTipo<7wnfIbgauey~Kl?GEA2Xkyl=L&5Zm#!Dor$eFnR`suU&_7W>lPR7F+`bN9&g@11ysOoVo*g@>o(frilSac`aQ%wdcXPXt2FhtpaYhzcm-TXN`@K6I=|J>N6`a6zszb`ZHrqL80_0%EV^_lE(wpMpy{!h|Aqg|^|Wzz3__#Bqde=C91hgz@9mcE+>O^;4YGz^gX;EXK#cTbMZ547uITkoK*XzN$%zA+WnM9B@FB=ORcxuH%xmT5rAJ+@whw4Zor$DeCSD`(0-CW&&UN%9+iR+U@yJ;8(n{18`kyX+c?gt1b(M<19{{vqdi2UAfYDr9uj1)n3aiwn06}Ug*$i#Z=%Y3LV{1znq|YVA?1R>Ypw(m1Uw%w13*bN{2s28M|MT`tRIaXZccnT_$`ONotOEL%zy>{5xZ$FAILXpJ+(cLcWS$RXLpWA_oME=InB_LB85ee_7yoIS&Nvu5Yz%kdRDQNt7a;IA_YruhNhO151|I6`w&~l6>*UeydUn$GUs%>LvI_JD?+jZ3GiDyh+b7g|&-Mdmp|Dmq`wC3T9j4ar&@1^CL6y&QP=Z;=W@yUUZY`giluOR2JryV^ed-7oDf!VRDo5(pVTfw3l^L)5cNY5(Xz|KaV0g^Bqo0ZTjq81nc$LyXPoT4X^AYruD_gc+(L5bwZOfNtEJHt&xmlZM=Vkow-*b^$cy{|MlqzPyeksESEg@32TJ_HT2Ii^hxv$+~Su3f9Z4o7R#Ye=jOV@)}JzgI7gUs9LN0v!2-q3i`np~Ib@kYKKj?TYe~5xnag<&92LcJoIPB)hB)PM@*8>c(^94xu--Idfj=Me2{9iwO3Q?QBRYYzNPJlMWyJz-(QHsuFxV$Y;u9hV`!h8M`U_p1pD{@5KYj|-FzGztY4Th9+LivFPPBD9;>+e?_jPBYIUpl;3UV7-|=Z=KwxdAx@Y*RQnHT|ay-OojT*@#gy7$XAY!51;64NQ1KEp|ZR<C)?X3%aeG%}L;Y{Hc*Y`JUkY{f+w=5q4s8ASHtt~gssHrXngdD??&NXi#aUU%QN;RwQgJ>=UTfr;dkuAyyx_~zlLau$S0ZFc!Rz!Lej)axHU)kvT`E)bM!w3F(NTYLKNUu9cb;5%3;BxpJG%EG4TxMQE>c|d%Gg-Rj5d5PjJ{eJp_f<{F{Q707|glXZvSWeTV|B`#SzANhn>r|zssh2wTtEfZ6bXZlntCYHQRgIU2XEQ&Ge>$7iF@0p(g$2OWTmlh!H_jxVm6L-plnyG|?&jyf}Hhk;x9OB95^cSulMqSfF_qKay4wx^KuMsEp$Ei3wJ+kOR-v9pHMmo>vFF3L^EFYexcU19@q5qQm8+UxKE`ade%8X9R|MAsZEx*LcfBmmgVE;UkBmYSIedluLm6ukf!WXmb#i}Ho=pSFs{(d`x-F3K=P>;Nsn>#uy1594L5kLP7^=j>%k*XG%aGD5Ukw%X4`S|7uYa|Qg+%^kDWui{xQEtx7fl62;&G1IP>Wz0Xn=#4*qTa#34EgH*oeg`6?eanSCeL%JjmSS+!`5#V3M+uxq?X5J`*45oc92fG`P&pYF|%uWp(nmRL-%HWdrd0XygRC$n2!3JtjE8PH>SZ65efe-A4uG_YuSz7pXr=)6Nfe^(eZfHy$rLAe%5Be#OMD<)p^Hb^}l~yNU4mp>_o||P)Ny@nbA-g4Mda@SrL`hk|LX|?0s(}MT<&Okq{CpQD~4z>USTXZ?5y}pU>m-dYs4mT<5-T=ly(NbDQsw6mnFr&+4DXepIMFn(H}Ip#LJsXrHpe)%@ixDL@L!KF42W@bfe*`Ffyjo&A=`O>5OsX7iyFY3baI&X777Jy5W-rB;$$We_J6}NJgi@+}4=V$~s@=V1MwQUPhi=n}KV#DYAsDCp!b=z5!%~3~F%b(^W&!jqAEmQtW17~irmM^6Fg9Ev-Ee}WO@IA@uL>Y-&o>hAAt-ne2a*&tEiEw=xTmTX@pVD@t67VVBNvg~nBAXXoRM->-h9O!W&b)kQmxMKAr9oJ^bQi{%-D`~JDt+`?`p^r`*^!$Y{Ap5*)0sF%+GA`eUa0`8kK!;hD8kLSXm;nLw{%h8@YbN8`k*5^T|IQ5k+iA&!-7;u`X$cIe{1;*|HXy*a}x#aKF1t4@`hUt(wsozDs6}4rs5bmk>)OPBlo$r46o>{C}4DNbYS_Vk-{)oAUTsagF_mg5izKZ*P&F){kc4{>6by_lyI)wH|Z0hA|V{?>Me4kPl$^Wxa?Vh{8IRmlnGbumQ>ql^qMe7%nyDr+3V^-+%coDGPWact>k5I$!*!pBc3%FwA+v|G7*@M#DruAI?+&eU_j_thft_CpQfv*;{_vnVM(%Y~IDc}v?J5qmpQig{dz&I1T9bvNhaaP!rb})5I6;RIbHn{(*E6Sein%}o2X7wC2#Z?rE)VUTb310c!1FwqqZA~6@C<&=`ev7ww-x3C@m`NQiuONB(@yx7S^!H^E4~+aqWwABi~0l#*yjT8#MKu~NqOx3yryQ)il*{*N(N9rAY&{T!AAj(YMaW&6tsUf&8Dr-i3;~a&v2ISL;I79%>}xfXy9!aJ6g7q)JL>Ivq`6r4zoAZ6wW907p+?LAW)TkuA$A<(OgRMU*+88OstSA04K3>u66myS46%}k5M5w#x<%#M6jQ2fPkvjFpmNAuQNZX6`fKN2qJDe{w!TN;d++#tg-<46=o%f6d7i;oe2A5#oJMs6jOEVv2^Sk$r9Y(&oQ6ehzMU{PyJEkLY&=&csUCoqp`Hn)Uf6D$hfZTHK7RzTiz6iFaF_WlQk*_iq=+5GsM}Z3k$|nTvkgrD1Xl`jOr9#zhj){D4);m*WAu7`0T6SfWfM>rmJvFiySos^m7bqXCdC1l1h{Yd5LX05e_T;P)Xyh$HQks=f%>R8JHs*LD6=b0zjE@ZQ}eaGNIaG_vrR%8=#ZH4O@ECm>Mz^Ymc2D%!0FVcgd9cWsI^LlHZn(;U@!K~@rKL4_+Xb#!i>Z6u4ybtS+cS!NfYCP>u%^;&os-24kNd%{@%z%Eo;AM+UT&~KZ|;zgioWsa(=g6_O3$syL^*xW)dl1t9rv-uZSX$@OaD<{gRZ&F89*8@JBIJWc~f1rG*?7G_p0x=L!{iVzw=}?m)e6?5D^E_WNfxM})Q*sb5xTkY4^`1qS3AoQa;0L_ZZz;GM)XI!t&wAy(q+{f~dTbO?^GKFk95S)XEmrXc6=8!N{S?8=A9BUxG$FXSbSo?15__Bq|>;m?}V9Mp}ggtjoYv$=7v;iosfsL%4#P8f~v7h?SPHAezkv=rSO~Lsd(ArBGe`JI&R2wq{7y!*S)=@KBY~!PU`ICr$c>_R#Dtf)FXcu#?^8#;GNoQ9i1NJoL_os+cRe~foPX=f#)ATbm>(7-WJ1&)AOcmV%*cA6N&4J_}Tfn#T>j3+GwWUiy=lUnq$A9P@yURWoxSt-pw!#bf>f7+!v$NReRw6I>r3muO2i|k3J!({#@7eh`uLpIakNs2j`!;Xp>R*MgkY|QI-(4T`oDP9(P*x`8jT3#hpFCo~)%!o>_HRWV@N~@=)~jd2stwgT9n<;DT{<4tqGKL*`S3RDkN*c!e2}PXSOEoKr{Au!j?`z~&u6^(xOO2B{dnq0`C!_?^j&NBu=kgtr`+#C&>q51n3PZq;tkrL!>o{7h(7Ne6BIZY_*(ngcC@pwEV;|;91S?0ysdoajyzCg8<1C-NQcb9#0pbV|0}v!nX+3T11dj!dX%e)`zCQ-oA1el=Hs%t6J5A(62H$G2lGKn?-9R=6v>__MjN+w0Z7S9KhSzis=MS6e*SoMA#n0%m<(P-JBjOrpa?2PRvSAxpq&RKRX?0{D+XEiK}E#|?HqSnWB9a^0u+_LbCLeI@3UX0mphbc@c2MYf#DsrKUsWJzrGzEQbGeiMeGq_}W~Syt@_%>vlrd2wrrCfdoIAKEgwtPlbop6A-U2<`k!&oN>xFM@%$Kdzk>Ks%*Q%QgJcErutZJD=T<#m~9+-I4L}GZct;>??ob0NT%)YMgwunF_)$=K9LoqWy_oO|yz?}Y4TK8eXzr=hY9CS^M58&s`s^ZbjWjm=a~|z)c`FojV{tJMbG;VrLHiw}WII(hQ6M*X>8k^OQGeI@`@*$ADu|Am^L;Ks`-!+?M+*%cKP23f^GEwLem)e0Ogc1+mEIpPBlTg3QMWjCfB`4C-C181vZwXaDM#*)78ih5+b&Oj9po#@ofRBkXoYZqNHCT_zLE;~bE>bU2-Muc)M^Oxta4M6>dwpk=O6xa4(kV9M8oqSfv-gnOCR0J(q?l7${7G_o`7ni^g)6Q3GIj%3rlXhy>?E?4~XtdjT8S>S;oaAb$s=}#$!n?bXPaaMhWT4F4eHtKr(P?nV^~-1GX<-M9|<>WaxH?$dNCER#vUAGH$s>Z*B~pS=nlh<=Jjj>tw>ZEqnp!9V65lzsOA^6pWu_1j|$+JufU5*I`WK6W&WFw4-2Q}nw66JU-@~JTNd>fLF1#-ASH=5rvrBxRkaKDtN3SnyDS(fcE0@r$NWA2q@7n&f5YFpzi)UU%orpX8_Y{F>sFT{t7E(UE#mGe;aSGfrQn#Xz{8vO>b`ksi!*{&7YbzQ^2*$gOO%NHj%`$}G*S5C1?1XQ&j36GEP89Z65`dd+|^%b}S(0?0E)%W8`adzdg0dyrYKPnuK1KL2u!vw$cE2`@)ZxL&BsHNU+8-sN}bzv0C7C5ZtPwS`bwZJqm^6d%mxyO_hveqa66Dp;-f26a=3_dkSrC_vOZ&OJ`*_bznyE^`kRPB*XHTSc0uvzZN;{>?NPTNllJZcbGMt9_%hZ!Cmfj*(xc#uhl-ronsG+;BaH^r&SM7|6OyeR;a%iq8x(sSwYBGMjjDb(aKcFsl2zO*ADHBm(58(8%KlqI>V1u-fb}Zu(d#R1<|X4#fgq4%lJ`Luax|6;fCEehi_*c3B4EMAMcZ=2}+1Nn5Ae_7Z^E)MNaJ=eHI*Mx(%GHzepF2V#!wH+dltdOr3#-9Wg(ISYJ+CQV_80N9-ui;-+y1W?HuN-|*wF~puA7<^oU$>J2;JQ0cPZjx!?&%zr%HC)9$v*h@TLbghCqwNRy&`ldJg|Fb-WJSb7wo@5qy1$6Zto0ve|(4jrQXOU-Gc87$a=h2ui&`Dw7y|og4p|6EEt-3=)ANI@>SsZr*Q=uCBQqLept;Iug}}uu(9NHDdA+54ixxyt3O`iHF8wv$1!I=_V=|$f&G_2LqC#@$ZoOFrF3xT3A|%ng1i)On;ahXo6Y|V%1_*oKwh%X2?@&`W=wJTGk(0jgq|l+#=`=QZrf|VHK=RRlyl-<%Zhv+{RU=g}z!qMygkxu_HVtbijFP!oyxINX4|WRhHX>ewwRJj;~{YGW0gm1u|GaxNg?$-ag%;sXUGMJ*X3T5l{4sflu_;O3mM>3$hYijhrbUN(7SBkfTD4dOrBEs9^Dn_wW)@p1kZk;aazabZDAakSV+bIqLfvkAj|FI<$s#ioN@QI^j=jZ(zVgb1)7#PivXCSrZdVJXf!on}+@?q7S_NXBKoPZTNM(<^R|BH3^l%=2v~M++|7idR|Qp4Ms)a(WfjaxeBijZBxIpQ?D5OJ$j1XxS+mkW>z%k0SZ`}JRga!K;1`NXE!sQ3JMzLrZQ5s#0PA4P#~t~-GZJ6s1x(KjL%ac+3JL4`+l@1Ktl6yM<)%w9X`p5UxGaI;$_fg9y%SyRL#$=9Y?(_f7>kCa|}@M8V(ocMQ)K1Iv;<+g$c*>YBaZ-AP*3A(_#l%pci>osP{hdfUe(CqhY5Kh_U)8EJ(@^mpgbmG1Z_5o+d0gpyNT}tKr{A)KrTh;L1%GV@~{hG$O1oYiLnm&ko_(ep3F`)}zi`efCr!;6>QO!V4L2GIQPZY;@19nF7Hc)$aFF_~frACmIPO(o463SYiiQ;GsIcLGAm^Ao3dZao!hii%z5SfibC3S!OgkJBKeru(VRVUl0S?2dkl104qW<#{wy(f-l>xw7}f84&bE{kRe-KfGlk+^6Y114cp{yyjj+`-|Tn^sOmppA#3z*Yl^5>emt;uGWlWLE7^m|Mn}mkBbTYw0@#q1VI(SoU2LkR$_kVSHWWVt+9HW_yV+3NAlN@At(D>-#v5w5mF!2-jg#k1Lsj;f=5=Pf*0-lDaHL>Mui3q++o(|)*+t|X%Fi(=}@)fuFruBXn$zyfo@^;`N(mZ7I#1Z+Q0S4r1G0o1`zXpzmw+U9KXFmRnndbqFYxz6keSpu0t&zZ?9yIaWdq=RU`*+Z4+A8#mNcfe9kmE^x7=6&4xN}Zaw`@#Y3zbd-G!GwdixYEIuGe6IG(&KsiVGQncWSJlrEq&%zdJc&*gwS|^aBK3q$9P{{tiu0G5NNT@_!is!x4w19oSldlteRPh%3h}!v2c*&QrK&3=$z1|k=BkFZ--upKnN+6fFefz_HyJ?-sOK?ysg99<^K4sMY^MiHiTzK67xz@TEYJKHT@IE2Uongf)C9wBdVlL`6f8?mhyGsKeCR4#Idu{R~HS|Xr?NvCwoz1=NcO~*;79lUSUoaO`dO(NGU<Nt1xfsM)||ToLLNz*Zt&ER*L;X&DL(YSC`5Jty;^3T~AQ|sNQY+fyDyP9rw-lk>*0?jE$W;*NyAkdu8e!=eHCkeDNQFN(R#W2A{?#!}m&VPK>r9;$>Yh<$EX5qlCkj3b~YA&={;Pa>iWdF#0I>yBKpmv$lUB+Z73=6MtYTpa(Nxdb_i;1gj#3fy!v@e9{PeI9!QUz|k+;yu^qh58C>@n_y6w5d9;Yb~f()2tt?FQ)_1*S5_QxvOGy<_LcT100v1I@h)n`6`LWVEEiACR}2e-8mPI{;R!P?)GH{vOt^}>}{@reAO6E&)=O`0@4p%Y(JEu|4Q#K_Y#4-r7*`?`k3`%QeB=$gw}WOV&E6bJe`q@>om+(r~3L(fG88W!;c*GaLr2Rx!0(`pJ7t}%pUdrAuX}!x3sB#1q@PO_wTW&`?PobdW~W2*vk3o(}`*OLz3gLC_w$ocI)rk;@s3?T9{2G^1L9*CWJs=+=FPW9zGL*f?pfvU2O2~&B9^01T!J`Yx?U&$I<>0&4Y=o-7FyTH0_dcf9Fb6bw9bL1c-Ro8d9IALOr(&YL>+ywR~>k-LGhWQf!Eu)mqAbbqxBM{s?t5&0CgwWIlQ<-)-`38s7?`i4KHZW-JFjGa2q1%o-T*L?CeZ(BTje)eO`R1GCFy5CT)S_~f{dbx#veUpr7X3wvp~2Kw8yVndbLW5tsgHV*&iyramocG2Icn~+i~FbboHbuO9xh`+rMj4+%2DfST{>4^XpeRY5dHrQ)>}>M)%$mrhI^F4*pkf$W!?8q>x@aqD_#|4U~zwe|75_w`*!K1rf=n6YD59GonH#}k0CE99sY7fc0YA$p28&>`iqEsZ|_(d%+t}l?(c@2bMLPuQ|B}tj%n*@=Gq_^$%aK%Xd5tKxA*b{op9f2eX0*O`#ntjy=qCLE_6gJ&_R|3x2bmYb|ci6?VoX;XA_&Fp2jx6HOKW?Uw@Pixt4;=twvR$Q^<8L>^~%1dKoZsjCP&*g50?AmmPJc6$KbSdoIVPBNtu!;UM?inF>~kRV{1mQ78K8aiy`p-_L&-k*cT@@u?#Lba-F&O6%JS)QSH8;rfiJ`6kVVsJlvDyf-4vgayO_HW&3Ls@05DVl2>EXIo*sAGzzP{0x=#N+nZquD}cE*UFt^xWZ#s=~Vnwa})B_y$_5-=fcW>=vTyux>K#kis4-sFdpu2e|v6v)U%sR3Cn=`hT3$rL#+yUbwTfWNHrSm37EhmV#V1$v;Y`@~fHM$X93BKjfF}?{_89NKOpbPd%?aIA%))C4t6WO{BRzoW`v;+E39Sr{he-^M%M)mF^$!FSnsX!LPVyH%R>=`sF=CQ}`L6PWx0`b{6?+UE+oAgD)A-tv}+T=!-lf%YFg%7cwEfKOr0js{VPV-`suVx;3m>GVx6#PZkZ1HzNzUqFNa=X=<0%vnqSeD&HdmKMe2X=0yLP%jl(Y>8$j~)A9dfk==c~5>`Dd9nTq#VwkmocKl)PLJhC;C6jf1!iDhvu+iBigw$mEX}dp8*?{b=-fD<^Ucg98R80sQZ3G#EsMkRrI)GC8sHCs&DP?2Hf|b6+VBZrBVXvJGL*qN6HT;&R0Q8OCht2FKbN*?vKm)++4EQ95s1yq&;svDNk%vx-CMT%@r^7TO&tNfBnhRM0f)YZcC576(#j+y|8|B@_uDHWdF`?vwDo&GOyQ`e;PA4&7Wk#{r0nhJIv7jUjavN&wjyz?HhitI}(Na`-}(QKh_nNKy7U`eyda2M`yKbgXGult&^Bnj^`|tl3|Fi#v&bpErt*vL+zjNLRA5|r^pN-9B4;Ct56)yGyzjl`w#a1K5}1b4f2rx%b(I2|XY0%sL#8&qd5NI3&P=m1ncwYhS|W>Z?k5t?-Zqbxv7c>X(tP);ex9agC;cuh9HIHP+aNlkc*5OHUCM1{*It*r|toI|mOL>ip`b{g>};hWSxM{cULh9W;o61ViX|BH{-+J`5O=9n0+(Kwjz)ICK5@&;plCGovC(&N3-Vt|1C@3n4kFy89Cf--jW0288a?4N8cAjM%-{J6~QSm3`7j`Z&Se8_7jByYW-#4O(c-t!nmPMMDOE5It3O!b5njP95Q`9F=xEBn)+Wq%pRO)P1I>@{!4?mVtO2F?xEhO{zrc+`+3b*h1(@op>E_WxZ$%e1JbS?&`kJ>dgLLcq)aO&WJNt!ta8Bn{<1&!b!-O-JNbj=vR`a!OQM@f6iDB$CAZC+j#=4%o2HfBGhg2mf$1NnZ`t=E@4{_~RtY8^q(1vD}KcsjB2*rR+pm^c{UOs1i}^15Vu<531Ixz2fDqZ9Jj660G9EIlR+&Odr#_fh1o$W`i;ay1sjf8w;|d4=5NwrvHMrdA19+{@1%VxeD4@2ar2&hFBwdX_m0kguxsgmq?~DuY$pNuNYgk*_}HXT9SrrNFCrt;d(Q;yS9)+Pd}Z-!tz{c^~gK)NL~a;=6lkK+Fw$5RE)W$q6bsn?#42^`H7QgOJBAcJ_4JTQK1A?_bNBN%IZsqdC?YuV4b<|A;5`bKvIo8j+jBn#ym?Ux1u*c0mKJlCuO_7OCAAGeW*1=9+}hEd}B{%2AH>gHs2Q05#paa9z{LnjIcG;+5_kRl(FAq^6yP3oXA&%AOBN21;kI=t2+Hbd(Li6H8Mz`LW1PhAMcaUp80r{vNb{-p9-1F^={cJ-eMjy*wM1@tJ!{Y6<=2=%kMB{T!^twE<9)A5al<{vioa_9t82>;NBc+e$L?%D%z*DUCN?`m(S93^oZA-`GC}y%>Z->AX#aVg2gwponP9%vxY^?yss2uj(*EKK3won;gys71xi0CcM_TSG`EPE*_e|7fcT`K;Q-J%CQ%ANGiLXw)dtbBdF7;OK*XK)D3J2r_dUz$5@f%x{xDBP+oAm-)jmI+lj-n*Kl$;%4g6hsvw>ov3IlkCtsajgq5aygmTA0u!GJe%%;p2GXuqY?+eHjNCUmS?+v2ec?H^qsCh%RJ1qs$7;ZIGGuZVVtOWv{|_%!b#$KA+RM4vB}_fgQbra@|^&cFSxONW@F%)cpqst(bR3-fu1dQO|nWH@^C_1>i=zSGwSZf(wgJ~snmFYTMjSc-Lp^cnMe6z*liM2K%=GnbyWhx|N=E(HpFa%um(Aszb6&Z{!76vZ;`P&UA2yFk+37B7O#-v-%`8QI+-HgTXTkT=q1|;!Qk^BnxsJD%$*C1)!|P>#>=oA{Klpcs&s2V&4{X|FU2+YX)<2}`i7>e+5V)x8)}SI@|5&Cx>XRiMw%qOeenAZVIs4?UrDS$6;6gYvK#h+6oH)5trcR4lz|p(6BvPJ*$nQq$xSd|#dLQPmVJOo!6yC(hMAsGt7YmP0Ae1{eFqZGL>H6aJ`g@&&MqcYELYMtmO%&f+zvo}fUD&rc4CX4Ku*2Hnt1q(g$bcziE6sjuL^WyM;eOpwglINWH4b!1hCZXSDK%z{*fw`#hixoLerCzEI0Wq)2vZ~Lf76`$R`OHJ@R?%^Fb6k$UFo>rs0RmwPTg8k>*dMuC*d$KS2a?HeaKFGnsa}x~sH7{S|R2#nc2tVm1ITpNh_EdSsAm!O|MbmYDM1w)_rl{v)+0*xBV|7%pN&*Pl?09Q(9N%x&5s|?iUMaA9_oPX}J=EVT4IH_8JOeg-Xb2yhl{2k}>pOGnDda%o4C7WKRn(nrvOa84E&!#MtLM{JqyFfY%)!)!6iD!_YTfV$?HO}n8oCBv^!0YIx?}uT27EJKDWorvKdpOqz4E-{o&yGax%RX7p&n(YQ_U|?0EVTZa=Ess8#^v_%qT5}!}GjC+*Y7|>X2~|lYLI%eLEqx|2E$DF7Nr--u4WbR27!t)I>YiBy&6%3S$D%Pn}wX&qd_#y_b%MniE$P(}W79b!uSC;VO$Hpty!Ta?L`$s;W6B*YrBHPwZY4tynm%)0Szjayg#~&s&rd;u2Apn=^9BjFkhyHe1sa+E5>FPm>biEdb7x&Kj|9)Hk05ljRrpx!V8qE*ru%4^p0lL&lruC`#!C>-#{R)zbrq>@TP5=4KG9A)G4dxBY6yxWXw=TIcd{PJ0jiU#`1NO~f4lCMesUy#YTinDGwMYD_J!a7yB}nuZfKCQt*43#QHnp5G&iBXGAF(LRwf;WpVry8l%bsje{QQ}K)?h2v+oz-bKUk|Br@rC4a`UGKI+TCbvV}B-*0tEg)J8^t{GiVnbzMPFM0Qe{a&I9S{@9(O_^Swh${@9$O4fWiz2L-Qm3z99VR)pWmztCou|Bx-h+C2ZajsrCx0qW+r=JrB2QZ`r3kA1G=po`qR!eZD{@VR3jCEd56-sYeNFdV(Cjp(!!O;(ehGWf&bfTmOpm<`(7Y`r?R39*`g(p-E}b^L7)bDvr#_KFPAD|cSGksuFg1@Usu}$f8_(}AuzHmOJB?F=ayKEjgwOL_vL`SD&TY9M-ky#AAEM4&V>}zKsL&%0R%0C^k#D&sCm%Rp>4d(w#JsPHHI0{bp&00rKPih-@%s6iLeAEgX)wgouy?*Bt{*jcT1Q2V0WS>n9=@B4c~ivPnE)r|R6ldx=l|*iyL9|_%C4)Qa4^CcUIe#r{~^R&5ZH(U&BV1K`FR(M#(lIrH{k1Z=tE{22OlJ6Hv;Pva|XTG`5Nr(NB%5@1D=x;e_c=D9e2?p%Yyj42yCdS3I585%$=P)6n_wkd}oEV4F-7LR%{gG&RQcVd-{DgcJ_kAz#U|u}*ZKMBf`+dG=kLkj^|~+R`8e_wkyq)amH|S)uK7#wlg`nLh1Qr1XM=j2fxU(u@(<5z=IPY2e7IH8O+QESW9&O=t1#4E4Bt|erD8Qvm-p{FXst{KB7TxthI)pn<_Lc}0~WFmU?zv~zQp{d5%zhC8JNa%djGfQ4P2i4Qfo3FOTLzQWPX?zm$mFObP*M?Fl(DmaQD@_{ptGnNhml|h)Z?oI2H8kXzVXFV#l({)@In?3%=vLGpE*boGba4R~tkOLDh17SEx5n~C3I_$ocAk78J{$E`0mi*&8|bihWV`$3<;YRQeC5?e3>a7=JGs>gbs08T47_9lF>h){Bmz6$Mamc(dF^9@Lvo$DQ{6UJTLP-E*v`{qS8nZfr9*DbPV`&LOk$`>5a5etumjmH~_Y%sc*&l&@kb*Eo6iCKDEMEl-N{L0!P%@EjYrSg1}M`FXSlIpoL#`y)GY65(4#z&+XJ$SwONI6NLbNd>~c#d1J>X|q@<^G5~*-nOEY#Gqc9>-R{+GY674{IcsTLYhHiMP}>^~b-Gb-v|+&8RUD_#J-R$f6I`KUkGvid0PMDf%dVOeBlk*`R2zPi9Ctfdb##gbulK~sI9=iR?8=s5tU-h>o!ffBegMZ@jzQi1qoW2xTq|UWpP#C#oSUl>B$%FK%IjVE6Ah&E(`CRkZDr>6l`$Z4x^EeeRS}x56qW;WP2zllcLz%1hPd+@%jnmyRA9Zf)_bnPtMQ}vZ$t|K2*U|mtGg^9v3c{rm7LNl^Um_<@zw1SZHp$BF3xCo6Yes(#z&QqN_fg9_?uNRo=RJ{P>m;bJy=(^S@V+tX7C%Gv(twyd^q~}Wq7Hd*cLw~j)pM_2jy%&GS^nsLWft6%Tp(ZRgL*(U&HD1zT*$ss&M_|=b>cdSulYdK&t1zxUHbRsbl$KcXi8m~#_~qp^rS9r7B>~t>o;tZmqdNoOK(^13OXpUU#t-%{v_f)GZY!1`)uOxmc^)VGmNvpq8SUlPtw~sPM|*|%i8To&B;Wl|JX6;e+=_vns*h^sNtzFO#2X56c9Xp{h`(E+ZI%0z_r6GDCKWRbMZn78|Lz`&wH1D|LQiwyr$ad_3^XLz%_TIUU`A)=K?Axib^w;m{@P4#z<=l5hP2A&Jk;Y1pAN|Q(_nUARmylBuCu_9#k?fV0QH%w8|wVf&&KgLRw3Ao3B=r$VA34n)zzP_(yzwAmTv!rR8l>WxE_c5{+a}kXEyIRT8nXnD>q$ujlZP8x-XgrD|?Vzx*ZJoc)~Ma^YzCu3;B@8Mz+oD;9A5!|1OYo=ypc_nYq)UW$0Bt5dDz&7ok3I!S%93U@;JNY)Pc~CQFBB1UJ{xK-Jo#aK#DqM@cD!CpMTcK*07^NybmqtIQTIv+!h2&C{HWKs#wKX4O4zhyh|gfW{@{t9bv#=Q6nxVQ9Z_e~kp{#C(|w`BV`5As8-MgnZR(5xnOUhe^sJ3(~6JPL#LU*<>xbQNg?Hp1Z*$n3WU43dlJp9@o3aFcaYye?X7$YSf9iUR+%&+}?Bc=OWU)_{yFFqnK;A6m_Ei{s4PFBH~v)q<%6&IhFTl>BX?d;W~$E2Xa)WVu1brEHsmIG}cRi4QBp`OxNGqFdc04Qc-IT22%@14J{!8f27iaFl8UQi{~WykTke2<~Qn8#Y93;qA>?9wS+CoTM3k^$8^$NHmU(f+5bXiKS$Ot>Gmi(;Wo@?Y^7)qZY?pPD~4+YUKo*{4k$M<$cNZh6Uvk<#4h^@+OUfUfJ1;q*r5&`ji<$?FeJ&$ycj#Qc^jK%K}NkZI2WBK~lEAL6dJ3~oYjRqx~J|qs5qn#fuXBYMN(1Fu1K_kxub)uiufe8jwPTq7DZbE+`8>>?|brXT;qs)B;Ib`16EqBYUQegP;(s{+BsQ+;M)8Nbg-3-p{JHO8YdFImTgqIyyH(GrVtLE7VL&d1xRE0r((dU9a_^k~nDpJ1T=C92-y^UPuxit{V7Jc)X;=FPVaHB<;qKRWV67U&QF95=lA%fcYW?d)AKgNCmiHc>w)%+cAHf~1FSz)6#ejzyvWQ)TYGM7mFqj+?Uws9`ZUw=m1w-|MzFHim40=Oy6_4#oY>W74WgtSx_fzUn8@&Q-Wvlyek%@$Ok(@qqq2%>I~w%lf=B^`+Q8=P@yXE0B))>Za7g1O2qYn&IKYml#M&1r^PbgTyUno++qqO{}QjT%_y69D>c8plGH@K-!A&e$oV2@>|SachwM4D%c~Vp%5eIvV+hh_~sT&xdmEuIr6W7=I+~W`8OfkQduxvgIT4q2k5GuOocoAkjH8R8QOl(QN_FsMXb=?+&m2OKPO;Nq^{-icPsw;}pnpP=Q#t`g7H?wX`NOHK0%RL6>d=(kr%n&)yta?#%kV1K-x=^Hb+BQBJle^5PGE)T-ZaZW#Kzj-N9yP+Fb|*w9XW1=DNGD&kr8a0lHZfwp60mY8*-K2W4df%@L1XPP5tgof{4hM(aouEqs$9ATNEq^zqo{Q92ZRW_-8HN1doYw_nJFf;DA=@5PZ1XM5dBxRnqGw(LKQh9u;uprpNJ583-~N{-|DYnrHgSiJU~$w-5{{v9{k8j+(cTj#k)ZO(-4k*z~R?wAkrD(?CBW9M>Uy<(0<~m#q}=<_?J4T-+i&sw;7SKZHP@48Ur|3~^7(jwT_)(L*IpgtMJ^)dvH8Bufmh7ZssjS3SFWR5d|zBJ#Xpr3B)?OHreoHIVyIo#(`)t|^;>~T`d6iBU^nZTNI?|x6;UTY`xPA)+AIm^+Je_RtX@d3?`Qm%*E*Rwt^eg-qDahLzVunxDuo02ggF0}Zb^ZNSmkIpW7Jn3J>sSvkPi3X?71ZohC0z6?6X`JgvCrqRFL?GLvwT>Lns##$N2+x)}fv{8k=Iu<||RRyC09=MxF1{DJ2QPVxTHaP`_S6y|!?+hJ7Oy1P(;mt=2}}gAKN8v*@s|UhCaN$3Ko@e-3ov6WS~WG-@_|iS|Lh($hY}UFClb2tQMW7|G9bVdC){?^KZAw|sDwFX~&@q__Y_24otP4LdzV{ienp`(L41KaZq|4N{dDC({HhgPj&f4{`Okid_+Db?ZIM0*ij8rst$*MaNvluPaF^r3>*Y^}ZLFa6WIbXbkq3rC#kQ}ecDB=LG`nM2@APX;WCvS0K!7r8Vd=Kk#)HA#@`xSlus8{XH5vgXY8+%%Z5vP@cQiF^`dv^)P+-{{&ggVhLPmO)vF#Mz)x33TN7j}K~>pXH{zj$17C@KDU&^|P!SD*m2_P&aKIDyw+?Pgqe%`So(?scbS>PT@?fl}84OQ=vGSfo?oi#p-=R8pkFruy2;SLPvK5q_$9N(>PFrG-vE!K|Cgv}v6k6NQJk7#Nxn|sbwA6myXA=CPw(%YWlF8Oe%>g;vvFytko-`P>SBH+)GI+;?0dj6xbd2-9CaK8T(U-v~^CwY(Qj6ricxZJRDroPAf{;7DGD&WF^W>J&D6<07Gch7t8ji~N;xM}W4nbCxNWvlFasPS{s)Epnd7UZkc+mE?7W?cv6XTrVQw~<@Ic~ufR&SpZ~&2dBTxtPbrJ{DLE`sKj(nH|F$pCK2WDBkJs6O#|;pT=!or$o}1Sq3_$7XkaVVW^``>IdGqBTLYa3eVQsPh5J3y4J@$O@(0kRA0*OU&vP%Xs+uV6(2{N93rNKSe`^Ta&`q;VTAY@p@uj-Mb7ri2QlU7ki4-m+~>BRo-NPS96~DyKdBHzZWtJ;7fqJ%*JeP5#%WC@(nJJ79;~PfBr=Ya?#Q;;bP6k>#+0Xs@(Nvs2`i-=wq3a35T{SeO>ek`A21Tv3O%q4&1a50z5oA{8uOwIizD$`_uMo$v_;Bbx8S~9ZI%J$7IvNI78_)B?5I~PS|*BCJ=r4R|KNIcA@X>&5b!z=N;ptsHeO8xZM1b5ADJmy5HU+uWy9O_)@ZmTnFgs20_vq*&o8N=sJiKw5Qm?5z7b2<=xeRQ6n?icM{FYcKIw_bTQ&i#z~%k$QgysLAk>Zz+oQQsgUzGCIf0tk5L@;s#%^^ZmG4;no$0@J;J!ovsXEW2FRlBXVq-!I#}H&L@G-5;^%7N0CFaWN!Y>vrB_npZ|)d-9WurTq@DUHUqxLfyu^E)IXduls0>m1w=ix>2ldXv99K&62M%PMDIQzLfSJGa(_%-EKOf%9IT%4thO&^{6=j;pAyav%9@l}GPxv+*&vWWOLn+Wc9&q&Z;J^Fc)j6}2U#M_XI*6)D<~Yb8pVWKlSIyPQ1g9Kh`TS$33lCgy-Q}DO>&jX}4AW6xYm)Hi10@%ns%NHeE+^%)En7Om&F1Xi9NFpxG}Py=Jo2Z{jLlc~Q|Epr@t$wy^5qr56j)i+W?llQw;FDIJsCxVzg)!@4|?!(TYGlwZu3n#lx=AXuku3u!wc#5@!UPIo)`>C`&Vc8V#;4+-g^cJ9@+fYV)}Y9;}G{1FGE3{*yzW0P3wH(FB(h3B7xvs;pce0Ny+k!W-F|7{8ZPtZEHpv5dNn}wb(~u|HrqhPJKEsHOE{d3ger^JewVM0YJ(RT<>VOX?cZ-cryujg%)+j2?{kfZreyQsMINXV{;$r)L=YqzNA5=5B~9kLc1IGN;ffJ6a7X>+p_B`=Q&NCUw}+(iQ77iJK9OX3JY>|6=_CJ_6csdab6s{;Q&j`WaiG1HE^HdUuDbMnMEP^`GA6|5A3J`h6?d8bZeJW4X0-34cVr;a&+!b}MeJiXx_`Ig#I76+-U1si|xOg2yK%{QO)G_E^epi>yp#1uki#LYBQ-jkhbBi%vJklx5x#LPCu(!j`)0gmblUT;(XLvRSxJoF8-q<4d#z%ixKC&Plnk7edyNmFgqH#}SE6pqs%r6us7FwZyIHqt=_A#5E8uo3xz0wHd!pjqn9;$zz3^!gCtNl5S=Nk1rS(2*zQz4kU=Bh^}`jf3*lvIaF`@{ROjK(oi9eQQ)rJ0@e=U`!s#$9n)Qs2v4jjE0Hm%*ew(kO@v`I*Q&RGJY5ktU3+Z^p>Is(Xzr-c`mx_^aN(PJMVDA@aj2rQ?ConZHQ=A*p{U55KeghD12|Qh9?T3pu}FyXQrT`RwQI<9B$p8qXs{|3gJeG8~IL;89NMd*8MCkZH4UD)5}&d`-3!{krjfMO3}}L9njjW7gAOSWonEqTrj5@5QOPpH^#;lj9W3M@KWlVRieqeKK#cK1+Y`k)F!rD0sU0MZ=S?Sf5C1@Ju%njs-2NSRqey^o#B}78CYxTRfC+`aiDDJf7nM5^YnVHrNag7i0U3I8qiM|c_N>Ol=d1V{VHGDsHw`%BdZfYD5?;Y!R;QqpNp$bW8S0c#oYuRyvW8Sfg&rw(2$Yhu+VtMzeJMvKpb4u+>NQI^R#W#}%aQ_t}u8)GlW`ey;RJ_r7TzAB|Tl?uO;NEFf^(h9q5&eIr9%ci%;H6^d4dm9IJs~&vI095$gC7}cQvcbr?-|YY>x=>J(+i~bzeEn~z6mYy?72Vt)KG`tsaq=JG&_ksr>S2M{bcp4QG4?I6xbZqpW3k*{iGzo(zT*L6-F-YRFz1+;9KXcV=fAWPKbr59dNZ5xsa&`1a#;AdWFjFQA|NwLJG#RXr2L`wy#fZ9+Z~%UA5ty^sa@F(D*LUgVSKFnQ@lNjB`42;BQ)8u{#%@8Js`jAhRi(hEmjebH7cF|jM2UC-RR1v%)mHZInciR`}X8)hR1gGZu<+fF63&-Ipm;g~}mG*)_e6)O&()O_Od89Df7zX{vMOatPbP4Y%uFDsOH{eCW#0cBpYf)tK5b_Y3Tf{fVW%5;u7m8+(dUOr9Bg2Abf>~nm`ry^>)-R@d81ZZ)8I{pMlTWbwJ@xj`Pa#hu2ki>%;(~#!9Ek5&Ir2qDSxk!&=uCg}R+$`!K)%`1-rW=3_E&Q4c>zevbNzI6wNHmkQBtS|B-ZH1wZ6qdGOdJMc5VEIdSGt1N^m$|3iO^BuokLBJ#aMQu1r>J8W8=4mrtU;QrM&+VN;y}?{7Kk?@vX2#gZ*T&vUcD|J{Ql2EnMWUTin$d$ThKo;D7Od`(Av_2i`grv2A*;m1>9t}kzqzt*P`>sL+ZfdAy@1+PZ%y}xOYQCpMkCGZ=vPb@S+eRcBFBiH3BaZq`#J@Azr>MM2ok=vK3iLldV^7kVT%!9i&i|&pvO97Dq%{Ka6%!9-{*-Zs$aB4%$_q{#Hjp*NTx+(*{-}kMQ_<;H<*iKCTM_3kIk>I&iX^A`?JR}>-mgj(jnuqOoKCH(!CNJJ09h}R)A1FVL{`s-iC(I)-40vvs(ev&JX}>;^4f76;~r5rJ7SOoU$5>mIn4bZpZD6j^t^)}6)9k?)jTfXg#L3#AR)7(I}N-Ke520rVt!l|QTNxcB?F2(9~qnWBcGT%p(;B=vVb@7)S@k4QAbJ14LRJHl>_Zx|ESHZ+*CFen;|R)pQWy@~qIzV@xNg`8SEoMbs}VmoqpnqS*g8I=fce&*l3tc>}zzN*x-=6W(rO&UiBE<{~H^qIeZEftunpX(WILO%&+3BJh->EI@j+PXfOqpv>C*vMXaR(!VCvXSJ_S22Q-I@_38Fpwlt@Ann?u;+`kPp#rt10&~Tos;uv*;-53M&Pnvxa^N5Lmd=Q=en*%skyo3a7%7z};sf&yP18^LJRn@v(Ob#9Wm0`4op7Sng~>(@X=k=%owRa`bmy_%syl>kh^2&j7nn~m@7NYuY8RhCRL|8ON=w1%0YMzNfOsf#UIOaaiy71)8zHUFdf$m(dTRa?<{!XFLY*H9r+xpzTWdqHV24)U~N;#;lf+J^rzc$A?KXTy(4|-C!Viko(c5&!Wxy(*kPmpbjy3~2*&xZZ!s9!mz9{oeMECF(0L!DYi@Z~ejEuJEZtfUp}+dGWoWM2Nfj%&IuB+pqSn>mur_8!3mfa@>-Dm?O8!66;z-pAeCPREVdkUmN2^eYM*yaety)2K&5V5l6q!*ZX`--&SYA{e!ooOnzhCiT%fo9B|p1`xyGrZZ@l-ag7HFtThj>^5Ljc`QMimi}xYJD}j}1-s1T4U2kxay8DAbSkiCX8!psWQln!hFULhd!r4C>-y|`At=W@UY%>-ItZ=?&mpSUIXSYp1{fSQkP5poYJuS@dGI7j)R|d<^%WWop-9~-Iv>|s%>Se(FFWbUh8K|#}WSIW`tUUWEXklH#bL6kR?ftC}zBwSl8&By~M?2|}`<~9#BzSpob#_S;>Zk>0#T@4tk|D-DFG$lH?K0gSzP)SC!_h9Ditg_i$B6z{`Bx+1;GUBQ_mes14&O0+c9|4@vfqCT9YuYmXH*^_wT=u85~V)8SCKzYj)2C;vM?CF-+$WWI_fJbzvV_t`51V?=eFjIIL1BVJ(YoP0>~=obS#|3QJ>lUQb^G^8M-|U7p>!{UkS4Ur^C`TFko#+k_S)^>`ni<)%QpSh@1>EtiOlcqL=wEd&c^GV?y7Le$GREr4TuCVPsPd*ge?2@T55Ml;Y=3U0It8OK)uNSpO7x5_5*?7n9-dbZhi8j`@#e5kJbPdoBSnw@|AV^99{faj3EFGI-YQJ!r;@@vzTy=^m6uh;uhv;S_MnvQYW)4CDWN<@F)OL1{2^O826M2J#{L#z>MgAh|~4VLZot>X}3H7td$y-`B~N&I+$ZziRzxP;aP|0}GGOQdMr@xaX;K$8F|HE>!ERUZ2GAz6QEQ*Z2P=!JLxRZ5IsDPK-mXdm0UsF}iNaDVRs5$C{$NtK*@(Qf`&OG0Ye8tPe`JO9B(GkPWvu-p@MQ@?`tfr$FnR`kMpOm>0xudK$@%roj)XQuRS?{@Rzt&4wzX|&QBh~br-PeZO#@ZYyYbxTzd5=a-Ba`cH!_%bMLu|Ees);!oC$uZ}Vx3xHE0qgsnY+%U8mLZ>~UiS08yd{C`=66<~>X1*xrFAkPA_?$|^tVe)9d(7?lG`y)ws-<9Q|qE-~4%kkM;Y8H_Lliam*R_SKH%v`cxu&F0Ftj>Z|%^3NALb$*|RZg>csde(!DxpU>P~p9X3N|`4)2;#Ptw7=z{u7v4f~4@GiQp1NLirWr)aIMhxM+qzrQL^{K)|?;(;@u9;@Z%=KcDc1jl1?z9stL=Op@stb0j@jZ(5gRU|w&WX}E)keftd--G(wfO?EL?+ca<0irMXi!#j1*K!X8r>uzrqQBseZ}|SPU*@R$yVL}@)0McgG#GW%D>l4f!1LY;^^8_&@7=@nbQlX%mOCqq`sZRsWynS1d~;6Z=VE8<)Ah8^k$-zp4iN9K4=qLe#A}bDFd7Mbjy*jdIUnt3<9-h}6p(>9$C$U8qu=S^aSu^v3bZTa21=Quy{TliWAB1DHD^7%!-+nnbt8w%#7gXJ@_%j8Fx!g8%tg8_3qHjG;hf#8;U&$%V`vTY2r|;6sf{YrjBX=55M@{}dkf!011HNNxgi75}NA)i_uuEB!1P(-FIBVowwEcYP_)#)@evtDi)KMvmI%b}TQ-IiiTht2g7Wq@8y;Nm-|KmMxYoqO#O?6+`GFYUh;vZ?vq`{h7q4i01mnD=X^>Ga>+cb9Sf8Um#+xmYS4Wp+z<#1(?0(b<@k*3XUzaTCOsX9?vkkcs{hW^-$$_;Z4@4blsH41G?E}nYNpSH=kw^C`IC8(eG|){?{p44n6nMJnP&3n(WFSwqqC~+sxfk7R1bT6+f9ZCqM<8=Ly%j)ZuR`3?_~BqMV(_F<)f)ZdOIG*K`O7s%=@jFM~HX6HdTo*z3}ywk~_#j>;|`=hD{25wdT5Wg=2p4Tlq`pr|+ae`_AKHc^vbap+0NNvf&IM<|rkPgL1Wxk0PI=CYNr~l}NxXJy&$r8|0Ik?kfG6wGUcSBN;2tF}FzV#Jo@2hsaQ$P2Rm>1=>6Mlh17pPJk`tsk1-iVLm;Uc`AF!k0juFyZ(@hIdagr`iA_#fVH1x?UO(c_0?vN+Ahj5_n9QQvfM*C8;qNG-L86qev&Xgt-Y$9#kVhvuh$FtB)cA3bj5%KqXG~1T;T8@fi~vl-NvlX7vtI>_l$F`}*h~i7-!Ze3sQ~>OcE*(6`rm5-9*jg=D{S%q#RaiyS_^Aq_H~xoj+RKn}zl`3+(j5Mn%Qy0Zv5)EmtevFyua_Zy#hiX2`~r=$#A$_8ffnbazddE&&J4n5vnaJD|6FMo@}Px30e^O*k_C&R_IVg#=6J6%J$xw!4y@N36Dh~~(iUBj>A&1bU@jD_^{5i-Q~?^+$@gYbVXNu<@m0a7moyKr+BC5@6Sh-clJ4Kbzu)5UQ@ng-4%CU~?_0&8quS*fA3yLT!J!|+ra$L6{t@R0;5(^mt+0v)w4w*pGDK)xL1`_L^;-}h`!vV`k7$qT2cE>9d(!Y*6}OLe`mvj;L@0d_NcoA3*47-?<7IQ#-Xp$gQ$x}7k#7e&LqRJ^O`bCO3^M!>^M(Qptnx6da4-hHjM8kN^(@#Ok2IswE^v-BHkK9g5jWClh~J0fcJ=q{tWyfap1haLCmHW^VbR120h|+5-i!{zj^0-%==#J*YO`XoCZrXhgF`|V}9?j8c{mNic>l3E8Zz>#roB%ykOtQ6RdsE-~8~~La4h+PKDIS%8@{G;W8<4jye@nLR;*7I4i$YX8Pr&p}sN^{kgiyiUPr>Qzdqap}kATdd)0;D!cE*qPwWC+)kJCJa&r&o?R;EsdS8EtTd=&*cT7?wYY@K%{cbU48>xHjAXd-7K0%Sh~XQ)VRgqZPZsY*Mi2Vm)x-;ci@4fqG#Z<{BvfpWjRAGDz-u}HyJTQelXD6JDe0F*6zSZTH4r{z_{vQ2=d?XHEeckXk6IRtbX&YZco$%YBn?9tK1M*X0vV1EEh<@8nBgpN}9!rW`02xf32WD4s^be`x`}rtYg96`{t@@L(1nXD&!}&)u`zT;2e4wN2H}X8fN(^(2;$d3XrT(=B#z}{zdW*AJx{>tp);A}P{$L#^5`yGCQeo`b4K*)Q%nOtsw%a5ZWx#OE*XRYV$R}#G(-&es&7LOpGFguKgRzGenrVdQ!0d&pej9>OKb-!eX{U351ccs+v_oz}88>TNgULX=E6sO9Zq=h-8h5EuVDFhTI{xX%&8E(4=i5#S5cgkl9-+Q^z9?k(!0be}4w2!Qr{)pRAE?lp3|AwRgi?Bt!|!w8I@=`;h&a&}gZYB!uQ&f*2E>1N7ukIY{p50-sHWBGn_B>ekg!TP0HKnchA)nh;I;WOLlHl3|e^34*4*k$S_m%Y}GJF2o-|rmyGx*WQ05uBm9djB9n~iqwW`n(f&nQ65DauzwZtF7Vm43`hf*jU%)47bJ&+VrY>vjC8u;yXM=9YuVfwisl@3TsW>SsB!s}5s6H7$qg3;vlf&TSp=!4!1`ai2N=NH!FN$$r-eK|i@}GjTIeJ{PPEomYnq|K}&~wN1np8LzD)!OoMsD{o#xK1o(*b{eLUA$^jT@5I69t3|Em;C2eU{;+~Hq>FsIH!q>MKcT>BhhvpKR_Ir>~oaK@!pnO_D$`SbQbWl0&o32j`Oc*_q=UHAFchf_Nfjchl;K_-BRJX@Md{lrLGS8iQy04Eke^In7iA!DEl$`$;yL_>iR-5492-1UlES$DBdK(^d~D`@om{zxa%(_&_VV`KTg1`7eRzu|Z*ML*y3Wt3a=`VXoP8{PqXZe^Cq<5Z{D2&425Wu#?vmklepiW3B>Kq<>E2}p<`j^vnZx{IiF^oM67Z4&-G?>MDmvBJh$>Z;`AnwCTzmu(K*C^KaPhsYQ=cUn1Yk$;Z#GKKbb7UaqmGv*c`&wM0zb2wXDA2dzp0LY&)O+D4TCUCPr$URYLim*u{G3Gpz!f4iICI{H(rAHoEn?2~&AAZ}^RlMUR}k|)@s84l5f7^`h%i@-V!w#&w_nZZi&NP1b9c1jyu#=$c75;K(n0jtjmFy|sIRsgNpI)+lLgWDHbmuGqK+cwBNr9q!b7E+L}xwJKQDjwNF$djmlT0Y2y^N$y=4GRkWXCI;8Ssxro25Z~0yZrH}m*k4&|4h46z)`S%5$z4?B}2o-JGs@V>~{+DEYME$BYQYPg%AF2`}v>Y_eJcd6mP_W)RX3QKQ3V$>(q(AaBVUXwug;A)>_sf&b2pdAqLB{I#7VoK06k8@VEsplT%ik64xET+jSC_1xUV`iWK&Mt;tYtD7@zoW|pT+q0_?O(}-t;u66x`!4##G7|1Z4uzSBZ~~d`_k-DV5I4Vc**y-HJLPRg=%-&<+yRB<+a{7C>$(XGS(`&G=tj`mhE4t+A4SYp)Ll+%FgXy_SnQs+B8LU1K8^j?x)pKXxI{fucR?TAfr#zF1N+A%p&Ty5em{WI`fX@mtTU{ek%+W5fMV+Epp=?uwPnN{+dBW`)5TUoz9-+)LNCC~k~v@`*RpZwpN(flTkRrnWVx6AseNM1Nc(v+s!=m_|NCy;b!b1%%FjT5Z9D_VhQm-)e86Lfn;vgH0Qe+viuj_lIAwIQ#$wvmeOKc&>=0msv7MJlC5qErEHYuCY0jS0D|DbHXx?xqf$kv?Q95GGI;QA^ja3ecQN9mTx^b#?nz6KZcoYMn6%wL-|&)D3`t8-{z0`@tm&Ex=o`b;EI$nbN+!kA*oTTanlnrkpK7`$-0VsP6-d@+a^$;GiX$=Iu7|9tLD4IrAY;DnG?fp8R%Ef&mNQY>7asCwrI`idgSv~Vcbgba|-+po*9@3<&JW)<3U|fBHeevvp5@Ux<09Aj3I}lhAD%Av|QNad%n3`l0#n|I2@NDM}`Zgyy7a6=qGbo32$JO44XwhB<$jNCqndFSIwh9NxI;>>Ceb#J!?aGWET~hJASWmc#C|9`w}-<{#?9Jr1#7)@`=q_;pXX-1`T}+mDgUS{?0ubc4oJ5}8RKDn-2cv=!;m={B52(1w1FaPG$w7pPYVr&&9HX0&wi?Uj~PtH1%uKBV4G!3X=t&hdDTG{uv)XNQL1k{cU$%pr524XI>Q?kAS1Zfu94;AJkcMyf@@b0^~ZrkZ6&`dXZe4xq;e-ROq=jKa0y7_0@#&ecPpLSvvF44@s{ad?(oQRVAbBWDc}^BYBcr@O-eV?ao;HDl#!PZ!up#{(YV6R@X<3DUjB1f1sBib(h1I)Y3d7>i^~&*5P}@%i9HP=19|kI3ND~2J2wEZz(2Rc~1lDHD*)Xu8#lgs^VO4*R%A*QBk*3yyB<_!dyH)iXKS>x4Gd(#ZNF_E6%T8cc3X1Zs*OL+kb{bUzvH#y&aYb;=NJPv|OxH5px34igMs^v%1`GQBw`B7~hEVrc(pSU~uyBtvnvQ-#%$!8dMmT4o>Mp*Ke-Hd`HYT+*6hXRq~M|v^}V=p4PX2>N}AOM7_L);~x84B~sBkH!`fgVIW^=Snv=`XXoV*vHQE8fb7~kMCG$9@Yt8GW0*byq*XfN0eo{`Z?aMq;H(7V3Nwdk1DYj5xQ>YVBkM?1b{%6;CGv?%J~9qK12Ls8DIOZ~QDY`@xwX^a;NRnWB+8HvagH!zp8-<(j}`l(sQ>Ilzd?`lS>TtnY)-B&$J~S!tREbf1Hsx`4h4!M2S*Vv=Qbx2fO%)>0~yp6#68i@%Vc;w5xn)I39gr~1=&AN+ECztOWyS_OpbSgv*@alf>g-5Jj?UJM&x5ULJ3}ZgUY@KyLtfqM0PT7C}|Ik{eF{n2l@E?T0B(sij|M-RGiOLA)hC0?xG*BX2P-WN6&>`M1AG!DzofzVm3UceV7?AMh-8AMbDet=fb@oNgFE_kOMKlyJj94&aF$|xKNto{*?v&-mIr&5FrlWPaub+{H15sL{r#xr0ILe;m&LGY+F?-*sbmm>*uKB5$^(`pHP8x%4x^>A>?4Pto4!SVH&ur{Z4<(anI^kXQN+r4-L%J%-)Mz;a5|h=cc${PFrLTRCU;6abIt~DLU1@b{nMp@^<<8!c1CEuj6a_So$-i8Ia9MZtgdFZ9mE5#3S@W7K~`QRz$DZkdftgEBRP_#|-jcx$ueLYg#rrA0f@TBa5k(~+V@x@O*E(#_3oD&BOGN`+Vdlbug$nZth=}h`;tZOww?!hD06!_EprDBc=O`GqB#GGwKOk1Gtl8^7S`JR{pJZ`qF@}3w6e1EjLRjjIXX@0{z7$*0K;m}NmP^-g@^Mf%D{?x8L5c{42rL)ge*%%|YX5}wD=1-~6w~;$VFcY~Ex^9%t$~)&zAG9AueMQUzzI~7m^%su3%!xssN9&^RjLp!&d_o~-u`Tj+-fkpa|~O59YAXXCLZgJnY?4@@eG|2_pHgoZe}}aX&=bx@?&!1xUVC!+tlAPl3n&eeR-E7|QjF?clh7^NuXMqN|;h*dNwbV_-;mSfKK<+U9j7If0U@qEe0@axD&j(1hJX$T#9r`J9k<>}$(ii;+*li>tY76X*~T-jE;ti=#d~(;N0noB_kz?yl?MMtj(;U6l2kvf*Qd;JwY|)PHuO-*J>#E)a7L)lMJ>%`8jOzI9}IX}9sl0*<*A{i#-es;EHJzZ1C8PYMYEqk=vDIY8_eOE~IRvlsl&*D=pSO08V_w2mkid7;~YR@u4MV=6qsDTbkUr{9>`%@&hqKGOju1hvMc2}-Ww~j+IGG{4LVIxragqNe;l<$(^Hwzlbc%94e3PJmDPqXe2EAIrZl<6W)`|LwdF|oi6nzitY>+&l@Ve$9>VYQ*o($~2PGa|?>pzTnzvudUy`{z!AkOiQC7`}q`f}3b!9^-eRcrbFP~zzODrZUMPoe>Fe}PLP6u(D9J*VS=bXfc%**Vx4`JY*ww$fgQ0dwyz+&IlZ9rZQtXJN`$27EcSZvJ;kw2!z)+|3(E0fTs>vR+=)S2b6^zaDv?0T08{jpdmb=buQPkdio(1H_yer#r}J+4cByb(*Yot16*W(6*8hI$~Xu{4TVMT5*8XAVD%MxGiwvR1xJqQi3a1wjXNQD3F09~5og%YfyvXATLfBj=L9+U?(eF@SjPn_`WA8$lN}3V)Uc)y^x|$~keI`$Udh;J3(vwcj^S9O%IK_T2HCa&T}iJhj*}(0v`_{1^Y*Dit&`z>*)I!zPf=>Rs>D-*!=;+J5fjq6?S@iTBLjU#TFlX1Pzz9^^*oz3uO4aPGzxYjZksqtGlB9g6AjD0a=U&p(ly`#!(8B4-8+dg(}hh(kXl{u@6h4|dh>H5xEibK7RQ#fS6Z&*&Mlbn@xJOF3y98@(kC^b*QhL6J*|%9m;}2=UMqnWI65~tvKQ~BAg4fHKwxarN|-H@g`%TF&QqXI6a{|VZNxmILOfPq=4e#*;R)e&`+-LICwHy`AkVfY+Rm(d4ZS{RCkaDmzF37#H>L+PA?={y4KU->Xzi!f1V+qO#{W!fBWh1Jaa%ijYD636|)bLiDJM(WOkMfaVu*(yGXTxX%>$fDBh@g?t}YVLp|;7tWm5N&$^ziu?m1)D=lHP2CmMR9IEJ=I&)Z^pl(o(UBFbxFjmf<04;-enQ+c-)+It6_pEVrMr;Nu7WUG6D|gj3U#=>`H|0YRV&8_*$g1s5jIV7%(G}56p4_{gP0}Xm(J(VSEV)^#C99!LinS*sUaNqj^-qmdd;wYPd(#Rd#X9=c(-mjm8Gar;070IbsiuG=f}CtHPTcd-hbcpLk^51i?3_UP+`#znegvqj&m`o#}l6$XmGHeKX!16W4`>8xbP%a9JUnF?Mmagr*|#1JN(;926%26j)_x8J}c_8$7plb6S-FyhCz6`!$eHepJEt>N*Cv&9k%i;Nsx3OX%wj?K~j*@c9fOhpD5B1o#URK}a!R`{x9#U)`RG6O#Fr21FnCQ!BAQ=gGtBI{ufkf$Mkh%n@PKIj2)4*6!NG($#qIxE~&l3G=p0q4_M3o^C5Bkcg^mZys_@fgU^ncL+?`X+>q$AplFi}K7aa?Qud-AIF|LnTM#lpLBzu1;5*FM4b9JPj-AbcIR(PoGW+m;yB|xikS>#OK2zFvF{tt1L7R=trptJzvm^`ZA*nzdmg7b9CLFNJl{GlD$Io0gu{(u{<1%GF8E|@E=WrzRC?dWyq~8RoLD_h2D_sCItz2m?~A%d7VA1ufi`fZkNXVjs9mDU=Z&*zU_m74WugD<#_@t?k@<9hP2w8C+^C~izvlT>aSYg%x04yM0r>}Tx18~^%7btlx54ZDcs@v67i^f#goO>_USrev-jkR^rl6D#X3LV@ojLB$%t$0kE|ty(nf@=n+r=@?Z?btC@|{Tn)^_Wip$g`^p)VR@2M$tzc;`XpxQ}h|w_9+clnOnmarCes$ZcbLh0?MP8blsmY4>_Ao@Xhj2sEocql3lPP>U!Zw`eo{2Ua8JN7Df-+69@Ak~<_Fz775MTFsSJuqqSMnZA1N?HKpcE~`KOn9JJlPf;?e3^2Y`%h0!|I+59Z@D$~dkNZ_O-|Y`6?7HHrqsWJ8*K;tO6`zUwwvm&_C+6;FzBR1$$SyJ2k`#yB{7R=Em$k5d-zWYi;(e&2wh_>)$Z$ktE8xQbx#-&vk(wcOBy%G0$t65*1GDs9Yb?iaMON{HJ_&(}1`~xltMU5c?~6LppS;1p9w`!tqX!Xv{6kfaG5W-BNj|6NrAx7e6r|W5RKrH50iVTF;;GEHw{^`3dzY$SutHVK#FE6WUfL9=Nm&bt%z)S(}^#L|=rK3cRm7>two8i6R-O!}k`yTZQ@JyUOACzbqX^?EjoPFfYt#o2I)ZQeo)k#p353=qFY+2?5*FY3zR59xFJ`Pqj|&kUmcbqA%&@9OU!S&C*!Mi~*7mez}WdUPGF%T=DODc|i1oS*?uv%6Vw#((PCBpfNLH$K}n)jduMwYj|H#xJ1+H&(N*78*4v%80QnXn5U-(o_Q%N-D&HWblhg4Ylf3#C$>#IBHC()b4oS$B&Lx5(wu#z0d`#7$}`~s&K;8opjXV8G_=)v8`H+D(ovEO}&#UP)mY-4Z6ojj;_aDN}+&(TM;#nx}3A(P#gM(_giu@UK!and3~hTghLqkYtW_F*3*=-W$y9cNX2Dmdnmw>XXHTWwmp(`@X9I>SS^O@#Y3jsqj!)F#Y@&Nat%a3A>K=-vh*S2!bHfSxyXk&_Yq;~2VHaW9*djkC$BAc{Tga#=|<-`v-$+&L-u$ivcZxG$McsBdPN`~e#yb9#~oxae>*DE%`qS9*Y{VcLysxIJwn?TA%+~3{=Pr6_ZAh*_8#VPo`W1tq{s^Rv-Gg?sDXLf9Mo6D`w+c@bU69V#BHw{>Z^AeGyY|w3%&(0WCq+5`CzbrwDCWVmE_Bi`U9>Z@laKQ#*I8L->9C`R80-xapV)Rz7=$OWR$kW&So-w|`YKdhhtf6IKmTh~w*T~!V)iM&UJ%K_rvjc=|0*@@?gjxuz1y>v$~_H($9CvBz5(ori@vho?ZXzyRBJRWPF2g!E?eBKq~&tV8|{&P~E370>elo;NP_qePUDPF7SX9980{hm60o;r)o$09{jfjBo7I)-^lD7SsMdr=nLc@;G3av$?M5vPO>k=Xl64F}X$D%qRVW-d~oJL>+NiN|>Vs&?pL&0S#{Fn-3C1lwZWiEbu(C)b4zCUq-ZlS)uWJ&Nl2GFNsd>AYK-^DP+JW{JZ#zVD|1#m!1-GmDpYVH(-=KQ+`_gpSc(}Ft7Rbmv2|vNe0qfN=->3>VcPT>g~M~6d>l5D$d8e|G8t+@-}xGr1{P4Zyn^qWBkvxZpPkpk3FXX|w@gk5LAr_y_hGttPILMnKvn4Jd;-z&x+-iJCWz(#0+oih^zV=fra8$%sM+>b02%m?W*`diJ{_`MM43p=DT!C7HxIjquln19UhO&4bZfXX`xgAW!zY#SkXko|e)&#c|Kd=;@ZErPBFOlDcj4`D)~>=DAUO>6&cV&I*Vn1GwIm_6$b(TqVI&Sh;Pr8OA*^H?6@9to-ZTw6b}dEb{sFCRd`Yg9^QH4I84`4CCNuwHJX~Jz(<1y21z5}O*~UtYd-`c=5zRYT``metj=yQZ_)p}QTn9R=>bd^DVKwq8=l3q!d6)sg!}Wo_9OqoOkLT$)v+@p0J&WgrqfW4-oZqj?&1CDM?DNP?F@2IoE@86!m)2?{H_xuteJKX{U}yQ`pm{ZNBj#=86q8^%_wd%U4=|q+y2wJE0=AzWl=|c_pN2%99-b3Ig|T%h-<)4z-V9{U{!+%EvFC|geujRs@z8joRWTi8G@93ka?~I6979)pNoRo54UJi|qd4x*3U<1)LDUaKn%LXG{9k?%KyKHZ%cb88bC{0BUXY|*oteH)RnDrS>8IhPbiMhqk$LSy@u*5DqkjwaqxL;bU-pb4>~h+23^W<9aUxeJ?PeCg361eUj{zNrz_>4^0H1Q3^{2@DDOu;4+W2n{&LEPPR)S*uMQy}V%}w(4uyUGuEWwz|Jh@9D_oqkW$CD|`z$BLki+R9f!Xt&Xwb4Q)%MX(jy~;+ULKXTqO)~o{RnahX6=rWRT!{gyOPMT2(A}mu7T<_10K5^UDD#o;U`v4qpHgD!0!=F%zOelgmm8x;M>mx)v{XaFgp5)%ZcQgCBsa3Q7(~e?T>tjxgaiH`S4tq6i0POJ`!iAgZ96ofZs{G*cc9d)#j;~H2Q)H#C^Bl9Qul-LX?afXh6)*dBmZwYFbLoWvFz}z4vq4ltW+f&(pbf+KU0grQ$J{Hle=K9}$8A`8-IqYxqzVjvUzUMqlKCz_xuK-_AilnIrM#(^W4fWX^ppzKMx`5~+Irm_8}k9x*03Sp;UH%Zx2z-*M!dTcgcnqX^foAWmvy@8s)XFFP023uI=sG`yBt-hvTz)+M=k?cl)TzJq4^Uz4pz>lv1Tbwz7kYLJ;bo2O>)iUSu&q>PEsfy7APXLnhS3FIw#I9)FHWq*UN2DIeT;AFdCILLJ3F^i5#Hfdc59XCrD7hM$M1=NmVsL*j5=vf4e&Uw1D0^(uDc0C|h{^w?6=14Q2{ah7gW^^g2?bspyT{0|Qlrzfc3vp4@eth_AI3F}u}wB{_^$vlYvbq-v0QFjsZPd~H#_9X90K9z9PU7gp?92Bj|hh+zHvL(6EPSl;{y$V45Bc-yn9KXjaY2EI#n=;|4`Jy99_b{I8-fu0CvLV54kr<=-4w&z3^6b}qxk3S=Ki?)k%xlECH4kfD%MCfWZ3#s^@Ov~(G^djeN8Gjx>ZW7fuQUno%~+ZT#QZmq4*h2@Q`R+oD8mF=q6U}Z9OV4t@ZK}Ri}JyxXZV=-TGU;gJYT@_MLw9j-*1`j$Me~)%CF}0LJMG(+F#G#P58aEeiHYzZe{5W)`s^G$9$ZbfrdzHFEZSG;CjuTqds$0^p%s5CKc@Y`*ovzF%K@@c_k_6F%4Qz+YVViz;iF@Zh598t?-lc54>ynDT@$Qdk@G$Fj}PZVDj1Ed*o>SVjijD9B@{rLs#+e?0R6TiGU-q3tz5YA(Yc^P8RI}`>~MFiJOxf?IM7wHfo^{^p#Ftx$<3f$GL@mpky`GWfVknUy^8ia(a9W&#{csOxO@32K09s2bXDmqpoAL3ltp@yX^#(2`zPa~gn6OowE+j-EN$CDW+fca59$N5TmE)&>u(z=mPt(Jyg11q0aczr4He1(2xr5LQ&0etdr!A}xM2NCb8H^BD?f$Z=WrDd=8^2(2D28QqQd%bB3-uvFrR)D?sL6RPlKg39~IJ-F<&G+;W9KErNhjivi&w&A(S_)WLOc^n)F`ssh?3(DGLxUMV&(~7Rkb?rHTIz^09X7<1Ck2O*L!A|$sH_eHi2iwY9PjSOWaY)$)bl{{(bDVf!ssVYnU>#|E@MJqWSNP5Ao@vF*88l1E++gEyz6*d5cxz6aIFu#oDY1SbdS0x$cNx-y1oF2`F`zH$cM6f5h?jb0W^L+{yV7}`4IgJR@qa5sB_D3+&d!Pb=ZW`AX1Nin=>E>HM93Q7728Kr3;snq>zK@)4v;AqZwd8494Z?17_^UrL^`$9^5$D62Rkw>t*8R>!^M$CiFjVQ%-5+sB<2gznJ=q33ju;?dh~aKe=NfEXg3}gP6j`$18Y{579@lcS`{fb1zLgInI&O^51=^DS)f5w@6MsLOyA#D^s%(q{E{X69T~;_uG>h9e;vZdidG*PA-ED$iYutT0)hQ2gJPDh#2G$U(LI(#(@c|qL1$t96%19zspyvv-au!`yL&u;OH0EQ(-I?UXl-{V{6Y^Ew6)a2Tc;E1oO^gJ&Mr59&t=qsn@Z>$Or97Q4e0rvh)Md2SVaD)~S4#7}>YqEMU(ucdJHywdFe3tH$_3_`=Jat0ac!k2mb5Uj5y51&IB+XEwe!T*BJe|JKWfy`v!p-=|RzxHO#bYrI7UTkR>=g&~;VpSx@IE^2=eJWUJuR>m{%0P{QXP%QcAgtFlWD5gS?ld_wnU(eQ1oUlH$)D(*9ZY#MOV$sF}nYfDRuNpC*X26%rMc13;lX0!2Z{*D58)v;%0c^m2|SC>EWOnM<~7s{0C@J749e)a3^R#)J7-z_=DcC=3k*%hr*%7x<^vu||n#CX15{=>=nCn%7x^L}gOeAEf&6ie&|18J~!$;DKWSEvVwd(4I!4B*#v{GRQNd4IbZb9-P#9Svp9|nVp9wR?6ZyZ3*PpxLdLd+jVD$b(tZN;jEKdDpe+7v7KVK72cSS#V-Cf5^hOzm&dkV`jzL9IU{o1~U3P*R3U*2rP(f=wh{lbYqG~oYaJJ9FD@y^R`)(S=n1LkEo_Z9V^PH;Yu_2BXZD?XRZOVSBIZihynuRXpdpZ$KMD;o7cRX{KO<672w-0$@~>M!yX81Ps6Ijaze`34OYsIS=h=x!khiqAH1%ty{dzw!+(S0GHk)LZ-^>MP|RhtBj2lYyA;L|TdQPI{%Ni7$;ks9e(yZ&|u9KTg{g?7!Qf(#ut0(FyDmf7tJx>WLHFlvMMXj1}%A&&25N$!b?j0np~KWWGU!5R)T!$9!z|tda!iwU|pBGIp#;A|KOFqthnSj#qs+ve}$=+AI&I7*Q9{f4jF7}&N5*J+dAzDG1~Dm3yuZ5ZHqKN!k=;Fit^4LlN8kN$~5T|u-5+-|^ty11jSv@I}SY`q=*)Anp0FpkM|^B+b(k%rxh`;wWU@OSyUGewveZue;U^hV_a@xE%O67q5Jk{jIYQ~+TD@k%`(kk8?vGpCE!6tdr;kKaQ+;>pU-M4Jm?QT5klU+#0%{i1*N<{rKRv!?EZZ048?@JeC*4SPWv{Ooi1KU{rzJXPKIe<6{gc~E2ujgrzJS(Kq98PcF4r6^>`SV;;gWS-~Q1>o@9QP9P3L?2e!Ui9nKSCKQh!NgPs4+G9~F(yf~WFEJcAkGKW*2ZbW=|E0!H~s;5BhMRm&iWymXHVja(aJ(&rczqg$}OUjGx-K=D7ADslP%U_K}llpq!I->0A(3H&9b(u}7JG$A}MLYgI1j(=(t*Q$x66$+I8Rm-rDbN`%mA&|uG`e8I8Umti5l$ONCD8o^AhZGQ>f+4953ObpP7#WylCri@**SFkRv@97`5DPtHZ@jNP66E)mCe7@5Qo~03l$@_r9xEiTgj?@Bz@5-$)(J7EI$0scg``AE?iCJb^ct=bl9A07a7uwI3zi4=uT}+hl!_mhKIM~`@*Q$yw=7u1A^t2I-V{?9EkqoOxAe)mq_}An&CWob@Z}~U^xX|e*d;ndk5k}al0P-Sv?af+d}uGuSI;CH14YX{15{-=D7{|d`2BkL+ASG$yW)$(Apq)Wh>@?R>z)Q|41ttA~Y%aQOB^q^9ugE7i3SS!mijRH4iUhi7c>LF5_43B-E`|0;%o@!61;9pc>lmXYB}Hd?O1wo@!2AvP6D0Bw*-b!5VK$*O&8C5Ak`;4Ik(4i%fvQbXn06RrF&;RRME#Ym(S~dzsVd&nG?wE#u2dfiQmomv$0Q=uGRC?bS*HpS$_d&zzB8(Wjcu(HJbhbSGImb1U+JGu!+EZggkB#9lRL?z70R9BfuEknW)XBmG|M!9K*3(3gHznh8IxOucEj$gkFAH_C2hjh8rASf7vl>dQ!A4G(KRt3Q0-ncIu_6Z^AAt|Y?RU!j@V&+)w`_K9DgOokiZBi4N|MgLY^ty46#FcoCHbHp|nlk|&5XLYUcPlN4;Ei*WCNawulq+Sbjro-Egir*&Mh#SYbv=gSI8PI=P=TN#d;zsEGMSi2e^0xv`-4}7b9Tmz9wtA8YXWo0=;c7sBwYpt@xd&@LGe;crFIgg_*&H-!1A|U6Kh84f2xj0OFR|B2?9Akp*0Pg5-CQ`V20vNb=2@O9kmi5iLz;kY9b#Qr+;aHi=!=Wb_*MgBCg&&zh~90#9x*O{A?cUWD&plM%Pw+Bgm7}py$tB6ge!M^KT^u$dtF8p#FOfO%R0fAqezZQ||YEmP9*dJO(fj;5IrCw?z{+Y=s^6nP}9{cUOAkKmOp{V?**W=twwk|>F7sQ9q50Ns?0)_M{`v%gv)ElgY$M8rN*z_H@TeuwU2elrB^Xs$bt6WMnA#c`fo-d?oQPBsHfWcyEPT9E474{^J_5T>y80jx;->}k(TOz!-oz^cF??{>RF>36)bwP**y`_vvq}1*#JK>j=gC0CJuc(K8T*}){$6E)R7lVmwbR{?I5hw8H_=dF@k8Z#vAVkvhr<3n`r?Pv;h;vc#SZp?ydXTh!MR)`O0&}!A19Vx(AwtaKNQRG+rvS)u+7^cE*HKzI)AP!%&SHG;cN&}~L^>#0n5eI|wyjNOT>m9p8aF|1nq`RBLSgdy}1G>-Cdxn1^4umdK7K;zx)6jaf@+`hDEH~?&*hc}Am<{js1`!9My_#-dCP;i&TYD!7=Lw;=PTiCRH`;fcinT+0q%VB7{8o?!<7Ix+?na2uj)#Lo@_AiFqnwzvf#@66h8W%N$HY-r{2I*#1K=m0gb!6sa>~U+_TZ)x7iR(0s16WY&7*SMDEU_SY|_z~tm;cV3b9jGfEBqiXlHOd$HlUeZS%Md$|DL}Wp`+k}@S%dYN=NPd9tDW__cvNC#-K*68`(+9Ww!T82b+&G;*J@2a0XWinLD#f3MO<%WN=SZ%uHol&ebxLQk6GH1@|KbeyMh)7kzu_8Ic4FY%hYst!@W?DKZM++CQzIuu2@&J~#n*WWmFL>@ujReSK@;#+(29U)z`++AX+x?CpaSVGEH!@W*)f^)&0!e7A{&oz%gChxq1*j31^K`{7U5bykq(S**D`T8jQh|1H{8#5q`-VyQBvF&qmPG*0K2$h(Mn)fh{KSf|G2%@SyL%2&T?e1--pr_MK@C%l-bdDY&K`Ct9y6U6P}h_jE$lPvgiVXEbLF!F@g`O-Pw52=vpB>uZ@6!~i7j)vwj6&n0|^KfZP1ma2PEY-cEfkyST&>{=uU7shH*4jKx2Fm*SJwE%;PhMLfx1B#A6}S|p_zt{4e|Ysz^ss|eI@q!Xd?OG2o^#OqL_QxDub6YVTdf!IaZRiDQD?1B+lmr{!2siEenymUTm$FR{-uxxV{#=YSCjgoDD+PB^arGa%l$QCTb_{WnZKOhXI7p8tnm0-`4#dC-TkZGzBf}qy!g@?IdQ}%-e>6C^72d|bU1ipN&NE$ciaBZEEoy3Ep<{M#ZA`_A*XeyaAc@3eS{x*#gqWuKx>rs+{dFIo%x6OSpUctPPH7^h-ednn>?W4=N3<>GYE=7_Qj4?rA-Jtyj3wq`(0>4n||Kpx&JFId*fTF(-7^wnHi0-0{lCw;X93YSTP>K>e{i{%-20tWI99R5<)#klT!7B2j)~V)h*7Ve{OJAOvfE6TNEISi{=ayMO@Q4kWI8Rd5^%PeLQDL*=MfY=O5uc9ChhFcBsqB9DTr!AHY}kF@gX%QsIN|Nwz8dlQy{E^&OC%A}lw02;u>%@JYwNCf8r`!m@{k}6jb)4r|akfirYx~YI{GMUiwF`~kQejD<{Z8!z$d|Upv|HY*r~TKL@G{=dfw$3zJOi>}`3m(>Sc+p~gaVa2&hBRQrwR95*~o8EWN80=kgT>(4RB2Lz8^RkLqNfn~=-Ztk?fc)irvQBmT0$4DGZi-Ln&4lAx(%jl)`A^xLa%B{GXx>-wt&5_31rC-o`zpuXvOkPcD8OM^KUVIHPMtaJRGHU&;rs{Y96!nki*t0q!YlL`GQSyLLjFz(+zqZJ$ZFAM4o!t^Rg`><`&5)pr9(b)CL_xRBsP;mNRdM6F2Pu9&c(s7@$S0suZkqXI%W&!cLpG%N;6;)5ZeZ7hfmnV)JM5>~_B=BPqcYZS5WSSHflg{;=8a^^-ayS)~3&OV7sGy&3y%%xQp(hlQnWP$2UoQFIf~J`Me0WB1^SMsxl^kEsMTO4fLD-e-ku$l<9rFxElb2)+I3#%!=!@*~9gD&n@s5X`y;Qo$_ngl^*mNxwa$HMYYz9hN^?pOyTIq+>7NQ*V`*0WNjH0<(iKo=R2@-PqShf#PwsYXT{xdhdq0TqYx#pzR=+G)>A^L??Px62Gq(K|E1vRvT&zw$Pe=66X4=#K>yOZY_?-IPD^tBH8=MWl<~ipfKDvd%9(tMCkZi3u@AxCchd3ATRyFOv{P|+!8`+ZDCm%k(s!gJ0IgXyMor4|bjpMlIwjs+t$c*fwb-m;o1M8RLa&xbODc;cjc7a3;unXg1vIjC_gE<^E8X1#1OvI&Q2(J73}FafM|xw!W_9W2{Se=SLiThl7HbPNvA!_M{VE0V>+bI*ruljyQ+>DKY~H{eI3LSVz6;A>TBl1|4_LiBfV@jP`0jyX&1@j{Ek*s2cXjl7Tr*or2cqscY&F`?Z}@k&)rJm(zM`|7ULuc5TDu_aLOC6xEjS&GNqq^mpC)?>Tc$t|<-4Q?sh{knm!B_B45UF$`0E>cKal#BC`#OrnL~l@1nK6qW{mqp8)S3V`flDMX%}M;jPJxbzG4|FEbad)?*AP56>+Y!;Vca%o>yHfcSW2JZVo;iYnTmuJXEi%Bt3_tzF}5^E9vlvFL>!Lnmhh(@aw!CwsiJA`Z6kxprW@BXm~=erH07!ZrhiQ-~X(+rz6#1)`4ZpEl;TN<_qVe7Z~nJM+m3K4Zl5$>94E=`-2?^^2@Wel^vy(|q4DIuLaq+}9E3>|oP-l@@f!xTGwdeg6OIWo;>>14a6*spU1qzwMldA+0MFG*)tN@-D^qokcJAyndSw60HfXOGth9h-0~5!zu9fLdKu7dk`ODzcXrS7L+_wy&>g_aZobN!E^jL6;iZbDpt%x+=8y=7m2dQOW8EQRYms+FxbJA3V(~`h^O8E#3Fs#?_Z>GZ+MWRmB?i~*kwJfWiT~i{`SlbKu4-J`&yDy5elcCzE1d<&a$A2@NFqKFi{1(6o}_}5`BZqSH{x?_+bn%vBN`BWjSfp;eC)0KX4ENe$yg+_N?br|m4hq<88T-zkin3ck7e4tiAZKXPXLZ6Zl`w2b?Jh!zdnd-P`Q6(`}N7WBYIG8@TCo==Y*5rJ9vlQd0ht%-jB|I#@v~Z4G%^Xrcz8eM3n!B^0vy1cE6CqOH9B%0adFoX7^2qRHpfS!9;@|V+X|P*```6xPoF~GoZ#((&WJ93+u42I}h>zCzLVc~WY<6E}Pm-R)jc@dSM_T(A+`Ic)A9CIl!a^RK6B^ks)``VeYj18HvQ`^4o&kn@l$G%$iXFIZBUs%S$dzy%YUFqxV8B$b8Xx~0)W{o%yy4d_2G$72jEFKcJdcM8cVbXi_UfXx{2pu>!dM!V><$w5eD@mM6@*Lx!9sTR=DNtv0s!ggxAFucPc){Hz3(oT?^B>xa`-ay{1io{wp~3GjYA5tRVVzac2glYFt8B>4-m9T~0`~_`$#~kHQlZ1o@+)ET6#V`--*cXB&!e;T_V*fM9!!L(u_SF71J<2b(>SSy{SD^_FFg@{i2;{av>qN6!918Ix7!B!Uny{O`sDBPi!kn=d)Iq-;&D0zdwHB{jluj?YvR6oExt^6FkY0fo`U(Sf^Q3_{l8{GoMKppHywG@ItRDSpYf!9LtUwOZ;3`a5Ik}I8{|uRLEQ_ek__;Bs@1k_9ontTcSuld8Su~3o7>zUpI4l4=Qg*TG+-pZy(zo_{aEw);7gvrGoa94-MY05{W)j<^Yrr0Ojtjs>#Rxx#fax;!POvQJ@qT*uhc(23Z|ITVLsDzTyP)qtGSU)MM13b-sGXEX?G%zy2%*rxgx;;;`~`kHsZYKVb!xsRtyO498tWVjrl{O-t>uKI?zv4s=9thzc)*do8Rp$1wP)1eco@5{_RSfU+wADSwPhNoj5>>k6uTbDnqHjS~baEaKt!BoLf2APJ`F;t(6T(x}&$Y2yV0L%Z4@io1d025Vz+6Ax7_5&(}#RPB4ttoto^@LwzasRe)YdTImRVnY-dn`;gQ}78(+dnXo(t~c{A}`^lzY~b4)U~HuhKd&UZn0%`%I-%z-R18L*xncheRIWraCLmR@MKbk@|>L83pYSOsB$+b-pc;B>(@p?x_stD;lu-IC&vHb}#p;CwF86Tc1e~`2%a2*cy784o}nqMc%%~c}4Wq(8nKC%GW5miVHB-klyHg0>hJiVx1`*w{dWpp{$({B(?uMENcG+kk``CAS-f{rkCIzU>f1Y|ERn>5-V(6MLN>j8hnjnIEtkdgs`iYm_wk0;L9b7#MH^B2toVqe-*hLo>h+|4t0&VqjKc_qDTFrGTz4&;!dQrUfqeUx#Y5Pe{COK8B`wa&)C3FpbHBx}V(EdNZmH4Cup!uY7h*PQRSj}GqF80If6kY5FB_O4hQNr!K8mu@~4LwveBhc8X^)4_7@Ym*iK5TC_M+J279GGJ+7L;soIh)-0;!iV|;88FwFQ*5aP@(PNE2jixCCN#w-+)_D)I1u#-qaInncWy^$_+i9>wOo~nN~OZyQQ<8*2BbXa9nISL=`^^>yKK#m&xpglt*(Lse%V0e^G<2tJgHN;#`AU~9V8!2JdAF@c{1&ked?em9h?;^%#|JSJ!;i5S@`-T9f)&U4JtT)o=7X-(qX;VU2{e9zLM52g-@68TvgAPu(ElaBoIC^EhyqI;_${KS%CCz$UBrEdx2MA)*Q)H5q;p&G??{Nwxr7F?1=ow3oG^~RjUO@09L)x&um@vD0x_?(EWNt>PbnQnTt;grR57n*q{etFe1-ugn_6XbsL01c+^u9p-!mXXMpGg0A?CGmpB^?B)nu~Iv%D-ro@NG*SA9)k!s?jcdZ#y_{Z69utk1ugU@W}t)BZx_Z>M)(zjU}I0~%N9bVNy`pZ}Oty-M>+7F4!wG%c#cc=xzALXyj$2DHISK>wCA_tfp#A87188s#pez9*7Lek1`Mgi{vBT9bGe-9BSc=rgEv?A%22ON-5xXu8Azif)eJPdKp{Q55ju$GUmB~K7f<+hu%ez3;N^-(i@7O76YOd@3cR3;M${n~;q#CexioY3$v6GE@wJ}LSL`PhoKf(CQxOty~Y++mCt{;z)sn<-P_mvgnAj1l@npErTW68N*hn5N1Hq`2U!<31&Phz?L*eZOA;;{sd%^E(}eD|tSM#$tTjJ-;vegd+pI!xtaCtAx017Q0`6et-cRc1w+PFU9$`v${92Sc?g|0xe&TEJHl)I`nKi5|}X2H`V`P7vg#DUUaESKNC3K40NsiiFhuuJNPm`BohdKJZg{rGk*CUFYoJAHgAczfN>!Kx46%U2;j1W$hWi4NKOcdXle0`VzI%T!3b%zzi4o_{#ig!r^))_pnrmI1tSmecp0ab7V?Z`UtVWJ3HEBM>-(xDoz+egG5VY!5G&(m>pZd292A32m=_?@%yC+??svR>wbQLM$_qRK+t!01+?}UTyJ;aC5x1mZgfwrmTWGbnTVT0-oDdFo(Am$MtNe3hF^wj)oBe)W7R>36)4h2X<7~$GhH>L!Dx{uolp9e%9Ef$`Vd-pOEyK)jNRj%d95BBsEl&rcPl&(d|M2NnT1azKSyoMF>x~?8!g(^O(-twI%z%l8lX32(eO2PQ=wve>+|1v-Km+k9vbfgxo}URC*5am7KM)_+8V^p!IVLnm-Pd19>Q9$EncOizVa2b7_G`<65FbLIs0ZYEc3efi;Xk5OR{WF-8Os+{?=?ak*max2*-(?DUvd5f;*eTM`F2N|&d%Qk8Y2#bA5mh^;iGe$ZdE32mh>!L@#ry@xHG~X0@Oo#UwZr5XLP@iGl^R=y8ycv-DtYBYOGUlBw|NZ86XEQ6l5C?}3X@^8@`Fg+9$DmFxy;p+LEBr5W&iXD!_X^$9is5Rc~-6iB##5tE3eI^vNDW84#jMSI#dziNF3nmcyA1fORtl>oDSJslLeB}d~P^Dz?b!b2O?J9}Wb*-*6xIP{usmFtH&FaWH&Krm6u*#nLSSA7az!qO4Cx#>gg0&x77X2gX5qbSltA51*ziZrTXMZ8TBJ`RZ&6q&c-KQQyoDId@ZLW1QVMJ=E$c_*5UF#WFu4^C2fu#Q9dv5(jezoo4WI06SzyycO2Yx}c&nteM?EE1IbWL83{3V;v{Pe)N=f@-uleR!y#GuCS6>O`d#&it-8Q~qtg@i9{lmN(jCa#tx##WL#ekRGQi*XZ5VuLIV$AiujMf#;rGasj&RrC$TBgI`nU#bZ*xLUUVLZkMMF_?hhSY~C}(=eRS+In5(XIJr_RO@PE7h(2v&rA#3DV`r24L=$=_qHA;hd%sBMEO->EDWbMH&~#VQTQw7L8*K=jB~+XP_qo?Q6+cGYz7D4REDNMU*wfBMo}_c@%pv0kU3%F-)T?$c$2jt0w^FqSYu&AqYmn_oZ~q_ydT?qLT9euyi{lLOdjHi-T%c_1FWCNWVHzntcIApvNd>wg#4#at~C^N)i_KFM7`gjm-B=)1KC6Xx|;sqL9w-do6#{xYM2GuL^}dt}F?kxqj`^;KZBlRCawxeFpLhqL0W9*7NP4NH7KB5Qp>M?uKz4r-NMgrgc}M5eGv4@y9PZa0Yt{#-t$*-*gIvQ*JWYd7Go<$ghYxEBi4940lmCoqK~g)N1bZzI}lSLZ>b$yw^rvana(-MX4$#7)Bb3ZX)SNiFb~>&RdxS;Z}?9KrHf#wQ>G20wy`^I>~8El78vYqxUZkP+^_Ze!&zUum!yv!PL!8J!!9IDD8t<@!m34&V9LbDJd~4mVUB-kH2*`7w`xvl0b}1J@drko$W|`_lVFJwTB#-YIFLU8ie_-!$&I%oZ2%%kF}7Wt%Usq3Ek&Ae`v7Uq@?dyJLZ@CM=2rS^XcsRNkKQ<*Q2R_a0#X}*!6p_Ncs$U?>oF*9GD>ZAT=lGAll9P?H~9oWAP=5vA(Ve?i+%6y3Xma9HI-#FDm>g?Nd2yh@!fU0ubTH&HvHP3vS>*^?n5P9%IWXrV}L-o*WqzR)CU+1lHKR_lL0csfzNfgZ}@Az;NPY+CLHr-7U<8yx_3fPYDggm8iwW_c<6{c%FnQ&>119GNaR17n|==Y(t?_M2ZRK3**ruq5c!fk{h0e>E0#U1E2wsy)Mrr9>AQP=E?eIz$Q|ulrbYjSvUuZ*_nIF921w_>Y~#JecF-YAkhP+?iSg@IdHK69iVQGoZdSUz4*8Xgr)}b&#Y}d8L$@G|?>?pO+YO&EVJff0_9jX1{e(Jf~}dao>}DFyjJ!r`QP>cJfFt8-j`Y%$^~^vPKM%%dEL40gAAxC!}{cR}Nm1*>!6S?NZ1r2ynt#|;@zEG%+?-G5#N`4uxE>R$^Z7b;|*#a7Ki{0qM}xi*y1pw5uynzbL_cY*US-g921194t_Um5zhhPhmO28r={=lZ_)CG`<2GZgVy!i0HdVip>i$geWR)%Qp-nQ+G=X!{`F|8VP8nyX|pi@}N`>C;)`I#k3>eP6ayYDNw_kHqVWxLx@@O}WmK3xy(vq0^2y4}Tk+@p^GG7n-~-@%{=#JgaTGU-rc1f_CVs!B=63r+&?oCh1`s^ja;X{>esv_{B5zTb&IZ(x{8dHTscX?GfRfu+?C|goNX3eHz9EQ{DZm?@cj)=sV||jq&kcd6`{p1dA`}t(oih6Y**MaO!)2P!16Kg87%iX09jp@6`QrAdRa^;xHfLM(pG3e9r-HmgBPMM1Hl%_lHQJQZ9VmzoPBZbHt4|xr&zOnF}2@m4l(AbBKp~vhJBI$_CzYipvmbpD5gX;JrFpjw07J(x>7?9AZDHyaE@sV$6c3S?C0mQ!9198NM?q9U6&V>m}Udht#>0(^yO|!WwHpzsVv{@^s890AjXFs<7eI*AHF4$iFtc3jPV)8pZA=Y}9BmVwsuR-KjLR>;rm9?zr=zL9lO%+072x|w)SualX0!9UP85u%!g`LTUM6&?yg)JDOFCc1>GGj*-C720mXu$+)05Pv&s^?EQZ)mJI*9K3$SZ29`g-3TXF~l6%c*QtXG_wyZ2%>fqenySmk`Eyn6`SINoIcz;TBS+*{qJ4ps=Ld4x`x>i{A;0R9e7o`d`fOnQ6`#Mq40(km%ONVUc+{#{ltSl6h{LGD(m9eW-pIP$Tf-%Y1DGk^Xh~(j9?@&f9?uX5;#|o>7Ed-~Ezth;Ar9glei@Z?CJ_C2jhEs)A?m3*g>(L^!;kylJZV-E`!{00@>ULP=98S_*@=GU!Cwi-!)-axdAWVn)gQ>ORyG)kUSU1=;N&Zk+K+JloO!o~=CLUo))EbCQ;=UxR%|@DSd-4~V=j|}I5ey7uemftXV;%-S0fG_Tk1j|-(vuwlhNCSILNXVWKj#5kj>E4H{wA1PtWZetnahd3!$g0E4CuP;(2O0Q9Q!BUQ+vH%vHppwKML4t3eK&(kS~Pb_4lU=MGWo?yMZJc5JtblEC+fsCPFU%Yl}F(^IWq@I4~b+)zk}Y2DN;jPaNKVG$0VLECR_dX9dQUH>*e5{SOIb9SLWQ43Ezy}>;SY9`+{FFlEVJMy&8?Hw)AAd)Lwx{0J$b}RL4!LHe{@WNnSz=F>>KR*?Gxxl+H4ru&tg&WV}b5wlMogX_p9(953hQndt=BJ?uK)`kLco@~z%^pk`vp1*xKJk5wXx90)QtBNFFaR;YJb{%s06~zBo;T{1Iek1$)xj!83_x1UJ8MWng*&GBBb?ur`ar}IpNTCZb?Lu7{;T?V{U_<%8_gxexY-C|3c3m^)p1GLD)Mit#<+Xd7_QZm*N;GI<}D0HyZ7RVk@G{SH?jHhsuEH(!?42+Qp@#bH(F9H-`VhODD9iICtN6{rg*x6wtJ>R07|ZwuAY_H)h`l;{6t(;d@bWwH?G8bloe3dG@kn^;6@NLGv_I8(MR_nrG8+DDj1e#@OPsl0{$ZuD)vFjd<2ijTXA`NeCT}aB)`2*7-P&HSq?zkYE^7+4DaOO%t{mD>6JGy9@XnEY+Z@2;)riCD-+2GoVo98VtGs~FzyEB3_sM(Z{I@Dwe^9!*LD!p<=dq;x2v~3_7#xmz56n`;-(57@>*$>DFt~p3d@g?@{%#ockLrufk)X9y)V@^#VdY+KIoL`D205&rohfd#9()!jijjK;$Vccrl*F8U@GiG>Hd+T#o&;9ccfncCD#6z!F|$&OS7;@_*mct#t3#oXvNoJs{#ysK3|jlo>mr^CiRQ4>t}R_HGD5JMnkCZZO<9&oe9kH-10ShvRW>7*ul@wOGog;_sfj`%}X_61tj$W4H~`{&+Rtyw>n&XlRpg;&VbfJ@8>yib*VZ$$lNQ^g;VxuWkCO@8W>-t4XU#6xyri6|e#cYrHq+8*rtf-6U?-{Q$#DK-5#1)~3(gKRZA8^e!Z-=Kucp1d3gohI18wZj@Ob;q0Zd@Dk8zT&l4O=;{>n%&6*jn?13XjGT;0`{mZ5Pe>zz+*AG%P4lg_t0))KK=Yq_c@1MxprZ?|-I0%V^C&_F_d;h?A);;LRdyqhO6nNaUG0!T9}p-28=iqah=uXxXpMkpKJr4KZNIV|�I;p>;?Urg)R@}W2t7N%!0ONa^*b`Tc{y5k|8;ZCghw=T0QPZnULjEwE=G(9Dc6-L2bn3uTz05!mWppW)IU)}k6mdvhI5z}%s|}i$#`(=$e?{Z%`HW3r;1*T=;1~z4H(~5(qN-p7@Rx3l*kg#}`t_Bu+3rOoxKmm(6U<5L+!B3@!zZJm_V)2-TC&I+|8BfMJIso|guc^M^O|tvdiGWC$cl&hDJwc3viOh3a)qA30EB_Xu)=G@;#CiF_^ceVLEI&J65%0fj&Ku_G;aDKfwJavpjj%uF$AfiCz3#@F$Xi6~lzHV0?g7=~q}kjI%ol|p8IZph{tz~n_gIhI!f}1b&;L2e5d^nnJm!86Mm{{E96Cp@Jp`6_?0#;t5$BcJ-bGa>)x+Ua_@*CMkKnw@&Ku3>VDbCiQX|c=q&}+bkFC*gk@Y7v9PfYU%6_^ni*F3QZZa|N#rr?8XKifWk~o-(J&`6z+TVHobNG-f@lE|+-PyAbydfx}~-I`s-9wTpjel0ubDQ_TzCk!2kPsMrFZR+W}O(g{SLzwf2rf^;*DQ*AVHWmg(A$%bMUr6WwEM4&Dw)J`p1ILoxa;-MC&Mo?U;=k&pHTzEbW^mt5I8uAyo8zEt<@^f(sp4PnAsfAqhS`ocsy$bR1%07VmP*50(n{SK$1dxJ|`f*~%@&O}NM?`Mt6123%z2mrW@~8)kZ*VkAzpO%g!}{5>yN%A>+c$WZHSi<9@;wWfFJ*4yO9|l+C%!v+$FUh06O_}(+{fy0=M_z|PsANifCW!|U`I=0JNQiW{)pGVj`>Xr%wM9|Uz%zS%v26$1?<9SE$$Ksq-YBo5Jz9?Z>e~^=ShKfr!0zj)hW7VqlxF{j@sO-@JIK@u?Mv1_?~_%rhVduj8$NzU9_Y#Cvqj*y2l(>MRoRw+*Awe%J{uO_NNwU@xg7bG#wwfHg^z<_cW#|S>KWu$PacJ=+aMMW&3Q8M)A!LXvRBTo@Rrw}({U?{s!+(@RKz!`|p{Z@iXEqyH?TKxfQC=-bOQ9M>OH^W#x5aIkZ1i7yrHgx<=?xj4AleN1GNXpjO>@vr>}UTt9t%XDG5a{=MILjX(=vJD+54fB8fYi#__vqF1JM`s`7E@DPijx`A4>oc<)QPF<^LZqb@F59s~!DtA4-L>Y0wVRnwPV;{X5sZUp4k@_nUOW4zmQV*0c3a3nkvIQ?ln2=nT!|GoMBk!YBtoK7!UkMV--pKr$ihpVr|xd4psVY4r-9}kWN?u|$C3$zWpnXE4F~~CV(~G+~7@83{oFSBHuL_7z5j%L~>RYAaA+8l%`%@5DSIE9s{x;k+(eUnG)BF^Mc$xyZ7sOVIGp$cPN(ggXLawPa@rMT>fLruIySA2t0nz3U{j_9}Z8mQ#CIR26n%lR~W~6KI_%a;|_z|6Zbz3%tzkXqBtNJBM<>^V?`L72QYu4VCl=F)*8vqhuhu5_^$4Mh_QslGZ%b(^U08;D{^I#&S6?%3=n$f4@iA3R?Mdr?eC9;`P{GGii%^t<4=guM8TFi#k3OW?=IGBBWLN^V@M;M<-X>y^;<96QaRT4f4jFHAkGxHv|JuuvU@#Zk$)4Jo?i|D??%5+)!~YWxRi?_ngufBjND*{g#P8qj>)-A_unjypMz@?I~(b7m+tg+HD$iagPSEsdJhSqmZ{0FU(YW@ht`#)5kZ|Cn6uP;4T!oBE^c!!kTL@dm!(+9mv6F{LYnqPA&93zDMjl2J;>`REe$*m&bW!jm`(J=V2_58;Dn3v5~TO@}A+KD>Mro}PvZVm0Fa5LJ+Y8KAg6c7ugL;fuuYCm`i?SxKuh4EDwto;}qmelNm!Vv{rjS)2Lo=%0=W?Dq+@NES3D>0gL8VFURXUxK@U~PY(vYGiA@J>X6T*cqP2dSQ8F`*<8A|x6v+lbk%g}t4R2mFlgnmAMMY%DvSDfS^l=%nl`=w?T%(Ad<0p1lIVxCp&RpWTb^3@53P%blkbiRye>ey*Y*w8998kK>0s=DT?pFy8<#Yld~64`ZD-#2o9%_yST)xnS{L(F#NWmV0YI#KYR@B&BFc)=`aV?Vln!A|C&WfdjJ6oIc~oi$Y$=J(ft1gD;v_Z%Ia?-LrRmzSF&U@Ho&>Gk6f~f6ORS8`mZPQ7<#Wg?2L{5&6{{RE$|GqRs!S+v!$X$9+3wKmS9B7i1BprO2;{{q@gZ1K`Q;2aDS}k%#cLh+1!784M-Yf>s{jB%M1u7MJ;bStyA4+1nVZBM-S#_B28DT^QIC2ZPlDXTIMndHEp+#|XFI$Ch754+w^Rv5=c)E~<)34kAY@uQL)IIaqvU;RFJgJ9&RX`)jANxz!-QyjuRFObuKw3B5+AicFrd4y|hc@`bcxSB0B9gvzy#wnBj0FPm-aq$2-k23|#(ey82#5yc5A9_9fBDAXFz7BCwJy4e_fP2jShL0}nC^4SXffVDQ6KncVHBiBRf*6qlk$xbQCAP#j0V%*^5s|jFm8?pM=wz*i-GHh8oeLi!?@30|H!!ld%g_dxNc~Sy<23nI#vv^qm$sK;Eh}(PCMWuGjB>ZB8|JVXeo2PT@)9SI5tIUA`~j3%aH&9qmZ@Ubb+LSRfE(txc1Nzg>*lsZ&BBpy#Ymu__&LX1_;?VZinibMQVx)OS{>R7QZ5)}6!*apWz84#nD#D0Ux7X_Efo>V&uq^;I#@G``+X!Q%hRcbUb)idSQY)kynyM7^|Lfd#N;i}YJzTwnC`>2Hhoa|dH;#}3(MoF{BQv(o3k=k*Es6|uh?IUWER<||s?y5W7AsRUJV$cF&0wabdnCiuHV-^o7Kdw5nrvRb|S|K3llP$bx}7MS9ym`Ad2aIPtxhyuqy8@6?XBhOJ|Js5qT7$Ed=R=maQ2|jZ>2vs!#->uvb2UIxEszt5|Zr%xWR`!#gd2YZ)UH$8AfyB!gbvX8^n#dpdM*&|;PzPIVc$4$3^&@mdRLcT;y+xa(q*z@qt0AA02-i$!@Jc<5`_H25$tMQ&tw(ff46n@Xr-1-ke3nJidq3y`X1lmnH6B`^1qTrTxmfjo^PaAPf5-O07fjc`IQ-2Sl{c_5}x*gTAFl`-HmwRX6@;oPqy`S#!9C=ZA`N{w@xiENpL4Os$E!v5GC;Sr;kl|%^O-2IkgPi^yZSv9VdMbe)UJRZ=k;BH~fNzc}$m(LuBm`GH847$Cxo*E7VE=&OBtG8TL^k9C-sp#4{C;m*(7;{kNu&_{UDUjMPJk>`0lEag$CRw+e1>juh`Uki8vn`asPPdBMs>Emk`PwNLhU^wvLZoaGA|KsY+zT&rd^Gr!H3a%-&`MO_24jG-icJq|}IB2bI?mys%=ha)cR=_hc5w!G9^ww-fzB+j3fl9^uWFXeZmK{gFVjr%bb8|Em%*);`R-E75^u6SUgwxBV4BBA9hWCGa||W$FM~&Sq;c7=MpFIh&T|4_ps+ycwSxQ_Ilq#BFJ^La}$t5i1q9FDzOlL+3o9!4m>ZJ>E{|>PEUm3385mzJCU!(ZLa9P;3R{TvD#Y~2a4~(*laU6e9d|*r1v`irKudC)^-2C|?W@@Pw1Bkw+wlgs=q*8Z(Z<@U?JpXj&nBu>B@-A(`%$x)B-iN{+PO0xQiXUdj^3Ud4i7^m<_F6!79P*Va%d0dxGXW;)eCT$4jQ5q&cU5_5-(={UQZnmkG4j>Pi<{ld`%+eff7c%R1WviY^tHkL;)9CavMT=XY~}tt-m8N4<>|Ncw^!as&nhq}VvojU0|Gr)=W0IV57{l`1!Tegr1*K1oNQYk*5^rbGe2Nr~Ta;=Y1@?cwjR;Nl`*aAMIDMDApmx7Xxbj99CgP-p4Gk3p3o#;o?K8FsWpD#Epd4{_F75c7#i3|w8-}gbdma@Ld3wRspOxPMZB2al9_2*CCD0~=Zfl5JaPt_&VS3Z#F<=3}_5+$}cGZOhK^ii<*!dbzvQqIm5Nk}+v_hTeTOGJR31sMR^jEZFe7|>e%JR2^snDEWbYamE)QPnH$lY{^nf*ol^-R<~USC>R%zNG*eO|JRUX5H7$@(L;;XMNqGPie32}Ygpu`l;zk-T)q5cN$ruGrkNW&`14L7R^{@8fGuTyO`MH9I$lF1_+^{6pVIuW&5G;UnkNgS5MVfUr)%72i+(6-h)icUmb|Am^|r6G7$9$ThAe15xyx4&*4sys9Pcf^=XGv`Chyp$_9qcZe!6V5BhNL+@qeC5Pg%(`!F5A+lTqc4?wc_{uI+X2ZHFJMIa}Jm;1N(l#}+;Xr)^+cOe%iGnwZ=2fB4$2@j+uHk>y2fIjrv$vH|aR0;~>2pe$ztZd1N)eTfhevEDsXzwu74LPUewdR8t!E3)zdwo`BC@<=#N$me{7L9*K64TID&qVd*6k0e@ItlZSz=kjzvG{()$}Bm@c3%s?j3yA|Gn>tj7y0Vx-HA5covCnVj`8_g!10rRn*YW*+dAZv$jqC}Pp32B)sfD1WAeyX&#ybL`TdIyb+WH}zwE*IUir$Y_N5U6c8@U=B=#YnIKSO*n|jd3(Hw|GQjxW_to?wjGHZ!q(h2LGRgNN?JCMXCgMFXp8u3{a?_l2-i~(X_uck0^J5h&rIwS!qbfi~2lEC>7aZ_^63{D1T$96%c9(ecqsNYCsCamT?So+M62i9K_7`@NqjUDY~FRN!Ew}ekD2}$TYO#0_|mLVUOO<+lf_Xd&irPC6}-@DgfIdgV2+4dA`M0IKK+AVA9Xe}U7L1+4agzR2>2z54`I1KbVdR-}0!rik8yTSVt*=nMQ}VhE)~Met5LAw<%!n@Y|OK5;OZQ!KAQkrIz7K`euCrio-$H+RUid8VtE~p?2u>d4$Iyjeo2F=X}9tmZsB-lw+ZdNw;=;2R%C3@nu-*JQ#3(XwMzTTwq_yI^1Y3kDGV&_w-^iwIxE<}EBxE_~=;~O>Zzt71(d2552NFvy-m$<6^Z@)m7c68J_hU%phAnFv3XXEj+_!jt;B&Wg4evQ6klsYlv`7UC?V;OLvYQLS`3)Fw|WvjJ}WCClqqv7X|s7H7A^F^jGp(TEJ*{N~VBSS)$<&Uu-cJHVho1em0ZsC$c%6nk?;S^gt4ssDuZ>(n&1RSNxU&CRj3)!S?f6^I4`sBD;qwXRq|7|&65^Rqim(yR3>v6qT9S_XprULJEvB^gO^}8PrzNm{zCpmU&C-Tn&b*|s>UOF7v^FE}w0(F|jyt6AFGax=vA)$zYy3dZSuKq_@pusqB=|>3a_3j&3>Go_0_%&1V%VE?n?8xl+B;o{8u6lwA>;A(Dy!*LLaFFkKD5zZWDSKj#+!Yf3Tlh*x99%wX>*>eDxW6D(FyPIhWU{}^zHyB2?B9jGLW4B;al$lV!~=DL6OL47ko_QX_)xFBYmqC>$9qrD@(M8IA{SZDuNul|V?uR+(Ph6~s81@GFiUYY8^-hT3lD*sM9*(0nvt)F_r@Pj&VW|>=`TALB44F-Jr+vLii6pa&%Q>lLk?M9T_(B3E0N4IKdFuScl;WY(8s45k|AApS;?Zu=o7f>S^E#Mcd78q^`tRd3HfT}K65*-yJ>K0Qj%m1#rK$~w^ult0YtyqZ?YIij?~ZT{Q8zouJcZ{#rU4|=K9TiRR)+i?fu5`#P@gUs?xrrnSn5VoulxgAM76=e6|#Rx%LKfBN3iNKc)duM>)J2~9~{Od#qIMYp@^QtWJRr9phlh)TKz{0&_2LrV!e09!Cw~d|*R)U#1-jgZ5QuYVx{6%OmJSxL4mw@wceJ&x@P>~mZ_f`xf_F&xi(*M)2nP8;V+9miKdBE%XZR0&Z81PPf$$RZ~%(oExSS)hAp>c|CxzRMdF2sANVoL}Z%nn^1ScLc0XUV1W<)mVOtp6It`^qFM{(w0r0j@BUIuAX;`6ukuu3bxp8SR(igdCBtw9SWJbZw(S`iSiL@e&*-v7EJ;_j^~-vOA+r={wxAiRM1pjZXIUo_PoJT2(EvlE1|mK;*;J;xR90se9Tf+@A@BIthdCD1D8IzIVEIN5FKG?h~8!c>i=6Or_0H3I@)NxU35i6h5E1fHuoN8oYHCWG5fOabEWvePEHD0JBWCcS1kT=gR)14$e?A$S#z+6S)leN|D$&ew7A$Xr>bvDIy2D(qDUQ;?Dpxb@9`#e8^WsAL9IRIt)yGAGYlpa*k8Mh0j~F7;s!7>Gwu`<*!VdbScIZ(d0jkh&U_ZsT-=oA5RE$TwSKOWHXCldyX6@ZkNP{+sYMlA4#02S=Ct7|x&Qj@NsQN*H7pB5G*fko}`W^2m&ot)momEO8E=o+zDqgaIcBe4lPk1ojoi9X$d&Op>}*QvRS`)5LM-0i5v6yM9#MPr8SLrhp{8CbGV33bvB>kkVOs9VvopG4=dz^lA^}ICXB4WSo_VWzLoBP~hgtEWV@79I`?I&4qhHhHt)PeJ#culue@H89L*Eaj#Oh$c5)#HbgWI14b#C_333)Bxc(>gaQ2LSJJmH*Kh`O16nc;%Nb(V!IZ(q};f=C6q7vX?{>Tt8a8)65O?SB1?FoR`Yd;7n_0m#8uF)%G8~zuR|bz~N1w&N@3HM-ly$&3iLpGw<3elOfvn#!vOo?wTG70ZrkD)16^k8Gl>cXaaBu40`X2-2E6L2rfC0TU(qCvvEyh9OW2f`tD^Z6`)Or2;e1jR!b3*8l;&83(l`h72((kJylk5l7W{C0K%v+B32TqZGXtz!V|2v*|o;S=3hndMQMql>ed69qK#*pf|0cn5z_cmaBe6Vi1N%8g!cy*_Ic>ht1?;0a;K=u_Kx@KN{eApl3CgBtENRI&xU$)(?p!7o_{HFqge8@bELm=+=B2R9&1)>xVlzu*JGgFNY%ZkNYato2K@**?dPvSiX$iFVgGX~dxEMS>2f#{2Snv$O}oW{Gu!<|W=!+91s&vs{olFvE@0i$wFy9>pK+;!-tqWI&ezx`py|Cs~@>K+K1pKJt~^)7PfW?df2C-FQrVBJ#|Ou>hA1?Q|gKyONSe%DG{#6A{4x`|_EWj41vO?)x*pmya`H4{(?Pai|l1hAzJLWL-*MDe|X9-uCYTeSz?6^jKHS4E)}_7wl0#QIV8Dd0v%XjV8An|pGI-vkQWm`3Y`j)Q9QlgaudcMvj=X=8B)I?1H^$(!Qch|RTs);IwN0P=#xzcK>$yb8ocGHq-VJr4f8JA#R9Jt<`SuSl)QS8^*5Y(>{rc50)QNpZ!eMlfQvd1ZLeZ0r$92}7W0bEQmgTW}`M`AEmz6fw%IyY@eQr>5lncveRbw$3Djer-MB~>VUuz8{U_w8%eyOWcVV7wv_7McfbhCJB&vSEfKE2-gSYpPy!IOG<&+VX4RVT&Jw}@g6`9qiK*9c6?{F80x&&(+Ghpbhub5ShDLZ@&Msy*ZrCSQez=O5erbiDJG>_ag_x^DP^%5RXCqH?dN)g)7VgG%@GlFN1fPz^m!cz+RyJ48efSz8FvhVfT&wc;v!!WkCTZRXGuTL@ejyXF9nNVxl|+p;ghH6k9_r9!F>9}Y#K=MUa0RFAzu;sw}*E!;E=-JoradkS0hul7`5v#pj7x?KKbb1(uizGk>{G89g*qo>Rk!gEe<0TX+a{s!rSxi%bd|U;Xx5pi=R?W!h@Jdp@bhOh)a{w5FiffEv6~+r=lePy_Vf*E`t3RM?|7$_^wyKdlVDXm`}@@wSRcMWESV*DGX=hx%Prmd3w??foy&h0T|k8p=aH|dp^@HN4Xa+LT()9Y}w{^D<1e03yvP@!@Qh8R-&d!L=u=NKX?^754mxn7xSw0cnW;z;e7gi7RR5MC>5T&Fb(7#D$HG{%1WglMZsl#wzLk$TOo4oG!hd!GMtVqXYbv$YVs`LlJu~h+EJ%EyfJ_s#CUxuP!SXE+wrI+w&6hSGiNKj%US1!Ol}MC-!_mZhU6)g#YS|c<2?nGQyvQ+_**jap~dfNuaYy!7_aTj`Lug@tViGQ=zfgX@cQ?9Ot2_lk?8Sqyb3y4l?|3oU1ck)0F))fN6d6>s5Em%avL?T?tXhgk$f&+-LyggpQSU6Do2Ta5tsUM{N{!;yon&-VuhfkCiTQlw;=1l}jDrf+7>(ux8hooj*44{`jnx&E7$cgI8DQsv3p0mn)7Tiic08Hm1T-6wFI4URJmni_cg+;j8Eco2?N9cRPmlJfHvVT+1c9KqaAVi*i-sPC*z6z+`5^`5Nfn490FvagRo&08Y1S=U{RPSF_poHJ+bj&k6(US(;vYs8C?~%s@hl3U#eVh)R{I6680+Gj(+oPT6ZFGqHO>>o*XfMU7L4r&w2PE0f@A_>m$@B@*d1LT~pw8x4^714a}Q`mT%?w?@R;3lx2QXW0A+A1a5LAi+J-DFS@kjA?ljF8yt*EGC?*eCUZAGaug8PY2a+@k3#Ss5ee6h?BZa2exTE>uVP3J-eT(<&-c$7Q$omXsAaeEb-d6j|F!J*M}=bqrOMLMcLPu4TLXUdm!q>_nnG%hl4R9h0hisUnzX#zPF1AgM(`K}&vUkEpY8D(#1@H3jNoHPM-qA#OMK?XcfwfnI*pW;`>uygVI&ig$+;|e&rpf0nlbYOiu6MCXYeHD~Z&+PbQ{ADd0+EP*zW=}x<>4g!k&#&0v^q$q_@*J-h(QkLr3_lP*{X%qs3i1_M_pT8IM18lw2i!lnX0321Xe7dLaOC3!&(8fj-naQ<`JSDrAk)Gh<^CPxyT|*LQu`Cr!C|?RW&I}97e_?WdsH()T;!9+&}E!Yq7VHM3nmbS{!A6riM|L1GuWVRDl0XsiQ@k$vN*J=jt#;;yWffUQsy&jl7h-R*=!$&VpwBc^)kzI6qNuQ_Zs~*s$gNuEJ7#)Grm)tPS9u7qKsGtdHWeLH8Q^@{I%C!j-@ILs2LEkbS*;$UdG+hLEougk2pPg+st~h24=D%K9L=KkmvIAo{o186jUe5Dmk!;(!yHULrjQ`AVX2$)!a9M6f$wJ;lcZ`HFVzkHyw!$)vwrsw?u4t!sJj%Q@VuqvsTmuXa2SPznF$33Zm6FH~L*{-+zgEjq`4DF}#k#*~$qzasobizlCfU9Hv4hO3aT4onO<`z9<76g?L9^j9KZsc6awU*aUfma*WuyFQ>FDQDZdFXqxIaJ(jFsAMbh)vDU%GZ`i{fX++iOOGL6bsdl_Tceo{?LA@MPGK1LZwSm5(|(^p)?GxpW4`6$v>vy3hfGkm*&jHa!UIGf6qhAOKuq@7`id3kn`+y;{`&>5K+-SexH0ChcG_y@y@-v3VFUTuF+Y*7j`zGwXko;G{L9q)DM>j0Ytx5IxLt`b)FnS-Xb9(@@WV-uOo2PMygmg<;W)RS?;7Ghq=AX(sg3nZDE&`o{nqVjOecNq?o38*SzDI3az!wm^fQ-#fSm9`Ehe~2fB{5Z*v{jWeBA{@t9^zCp`j{u&+iPpe|{I4FlH<`4aD>E62)J1psd?x&9O+hxME6$L?49@)z^%-Op6BfHwb{HaeDed$xE-YezOLoqP`6JXl5_{vEm25x(#2U8>Zr@$AefhH|3H(@>Qbr@bX^XbtTHI(asgv&WINRMd(6V-6D-uyFnPyT?XRcWRXD|9Xl^`ZHVUBQJg5#fv1<_mTY^H@H*QB?Erugr%Q`&}XZTIQ^vbf9ZA48(k0uT0_bf9B1UHh9_}5MvM}GIk;hXUp49q$LiJ{f0_&q(=PW!PDZ|}TsQoLd5Z?#se421b&#VRbf@QTT9E-cUrYJf?x;U`|Aa4WO(wiqomOR^hB{F%w6>oC$vdv!Szm(sta;|cYBnrj?b+}(l2Q-0YpcqoZ!PvPFZSJNO`EKk_1H$j*PbBKMv>viXx6z?AjU_q79red6ng^S889?^qvP3=Z*NW7{K_+N6O&nNifO>IvfhsI#!=Qj;*lZ2dFKfVReQ9@aGjR<0XpDSiD17^(=FBkgCJcGQF;B&NoZqWu$HCl4X7ZUA$X7&P`Sdx-aQ&>{&{AWJ@2X#n+&6{Mpx~_UwdF67e~7x=xkecvJnw#?GjJYoPWaK;kXbRp0AwfU|oT_PV2edTduO9Yn1+gSfAc<8o9qYIn3kvJY)8K8*xI(pSvm^lX&yHoevf%7;{A7$NFr<(xBnV(7dhd?qR7w2vs2-{<7xKgr^o|0_J({5+nx>?TPnM(#84j&yrv-EM~6G(+7TMZkq3xAAUac-&^9Q=4*87p)=+uta$pk+#H==<6iFWs~>+vX!Wphi*Qq0US_W{vzT=7tUMEsITn8lrT^RuJGkQSZC!s9MIur91p^GKa3A7!2A`v%U;*IAsNmN6tnZAk*|7X-aD;5lm=6>_O^9y#yl18HZVAALWiH{!+)7m>eAWjb1v`|Fu?Ptv9muVAC-H`>vR~41@__hMB6S?d}7yq27_VpBwI{?8W1(bd(EL%!F_L}yKj|bAgn6KvkM4$imf9P$>`0Fnrjrp-(>{Yv-J7$u8P@AfeD~|sZpB&7#1)_eRYmD=${$tYHl3RX%{j7E%_g>Pzv-(zWIA{e+DoC!y`6SP0Ml6u$_Y--zcVE;cOXEba)a%z0Xu)wtAAa{kK_P|gKkgNa;|w4gF0pA4WV6^{^#IFI3LiWT;cx(Q+J@DEL$_noz)5yO*3@y-2_LhnvJ4>dA{~_cp3wf4KB>u>@Wg78)xnDY_Pdy=#DtNl`Eq??$a|~a%<8zGXA43@bGHWGK)rLKaFk7J065rO8;);7Jy2nikhjzsGVd)Uh&*=xq287Ch4CP%cyDYu#qaCrvu&ndl#@Zg?Pb#=57dj@_l7N8MuYp4&%4W=Lw)OS+pf9`>7cUCaDQG0>PL7#Ade4jl4344odgMUThed@&t}mM%!sDaj%Nf6JIFkK7=42s{ZJ+y1dY(@Z>@58_(`F{>3LBh`zYL0otyvT0f1E=;BwX^Yt5=$bf@yR(#ysN#Wt+uIc{uOd!@7QYiI!-KTc15?jiKIZ~<>I~!3a)`2_&JjnHwN2$m~gkR70@=%ZrlPi4v8uML5{pF?BSO{uxXgY63S$~|fyQ-C*1fA;?8m;P)--!N>8KN{Gd>OY$qE6%swtP;9Hf^Ixf(gi<*K2-uz@AK)zIKX1uM9=s^)T4j;;*0THA=p5+q>$*yZmf8t!#BIDggDCyk}olSF+*An{tIGl)g?L8(0(8I{E?8j_mnV$~xfYvpTcw&cIxWYvl*KF^}>=8NI!?Df1J~$eVOmokr|8>SQNv$w?v8i?|Al+wI8+*rok6g+j#F}itt}7dLw%x&bCjCavhLXMnS56{FkU?+0sv)rqdsT#?oPv(MXoFD7oo5xR$(n#NiNhgqVh<%{30(6)+>BG9%Oq@5u7u53%1Lh>y%{l!Z=SN`2w#z>mENEz3pA|;w$3(v{GtU1q8~E>y3qE~8$y>fUw9nX)1CLw_uXuYIRl8ii_{h5pR&Y-lDBs-KzFDr1^xVa{Lr-Fx?l_ocInqXd7ek9y9=}Ub+w2M2l&m_wNln|^?hcp|KP`gO9G>57Q0Xv{d_q)XAu`7s+PKjHsSo-x3PR|Q@{nwfG)+;)~MgwYnZzDb_z@snI@B&iR(nfzIcHNX>iB+cJ$!Lf7jvgNo2sEhGM7gMvND_iZLs{OwR;`Yfp_&TH$lmu~MR5xPt*ipSQ&vd|zI+VmL53gavcQzHV-0Q~JNmi_V?o&xW~9K3kQY@OQ_)o%sfjy3oglB6S1f4tJ?BXNT#Ng4SmIJ7PG#h9=`iVLXZ;&oc4Z;+Y!b6r{B3_kRdL>1I{}aAHi;tZp^Hi?2c)fnjlw8rcI}v`KJ>D@ShxwLmQbr9AdC%dXl@PFqSK)5n!k1DTFQR0ufawRvUJ!n`tZ^HwK&eR0jilJHViPURm_Q-j^k9SdUQa~lm*Xz@V@vC>gMGY4;(|-AY%7Z)!c&87v3eX^}7xSET1`Ptb2yKbhx>^QZEOd6uc7MMyUfK>m+|gfI_qUNb*{|E?dNs)SETpVb%J(+CNWX9ww%0KsZ<+neSpac)_vY~Dj06PAL%Wt#rvwW_iU1mNer~@Tl?^;4vya>`-evHsYDPfSQuk*6#c;SazC7L)8zf$J&y2_hGRMq>sQ7z@O#}}W&J)mkN3M?n{@OZ1NDOXuzHpq6H3eO9hyzqKNTN*E`G5h8)D;wHi){Qe%<6i-q>$8&}#1XS{0%$rZuG8Rm=f1&z&EGhEQjII(Khd-AS@eg9@Kj}9fEunhb$za$+?`5?+kAH->XYz&|J!BPqL@icAo93PZKxCV+#Nz}=zP2A=8G8^2PH*Hp6~8u!>f5mc8{o|&ZU{G5Xs?yl-X;|xfZAszHbA*oGrp=fg4{=?3_2KQ5eldd^hA;aigHuwq{IB&Gufa9o=P~&-&=^qAc;<_Fj}-^!z5cF3hXB4^^qEZ56Bnsmo>F1=^P6E=iqe*1H~2K9S~>n=*9b6|;VLdm>Z)X6@MU!1`w^ii<>ble{|q3d~}epU$NGBO(8Mxd_LaecMQ?N}HQOdDHz2X%VFromvoWH=z_7n=A0^#b#O40aO@1{?&cj@2N~G`947Gyj?agCA~bd@ew}Y;oq?1&IvEj53q(OTo|4k=qxiN2H77isX?=h4cZS$O=fZ(YUfUuHn<$d!{4xAXq#kJ?pBT6+9d6{;hxMPu{DYzYAirb+9lkaFdg5>Z<2CVou@7R9&n4dhd|!4slhP8Y$AawG*h{j?$RRo>r1d|zv%$jq!&GOvCdMr<+d+Qp|wD77guV6#r6fz6(42?J{A++R$1j7|+XaQz=c=kqNpp-*t;s;dw8YCvksI^3u*YfLY;xbI!66)fbLLltqcjc>zW#S9eJA(N`gwGvIv3g&IjaZHrSvnMbH}CQ9v5!yx4XR~2j6o|wbD$=8G%dh%uQ#*Kt}x2)xs1XY~mjq4!K`gs~E?x`u#^u<`gav`;(lvbN?MbW%(Sl1zB9!ezy6c*#p#Pj2#jj-X0ICJDvvw??!H9*X)wBd65Lye~r{l$;gu}^S>D~2sUPNBe)`$)1vpS^?1abczpO{+zB7F%57OzYxEfhyS*_Yq9NuiVXzL2x>N?$ta)%3N#>b(EIZ$_i<4qRY$gB#?ELdxwx4zizv0_0B&9nkEEma2xTyN)S1zM!%H?Cfp@)LOnSD*?-KeGL|&*Ej?+k>rFY>?P|w`iRDU%%uSJJo~eFXx1=--vhO_CSw`XZwWqhc7VeLOah>}o^uOZxbNv{P<%g5N!Yk1BrWB4dIU>wbG>ryC|LPY)$X5@d&YxkHWB}n`wS>}dm*^|$Va0%Y32Da&V;s++WrMy+X)Gw(`}MlcUDO$huhz8QVng&fDd$L8VgI=^Moy2@ZbTT7-gM;2uEibfq(nZMIm1?Mw2rO6QkjSRNKC$dpQ1e?H<)}k%{0}u|&i7DsoqBQ>@v;*i`VDJ?r;?4f0h}lRDS$b2_;FkotP48+9YA#laKmGQrm-WvcZiUpk33s%$EkRg|vy!a046Tdn>?(pEis<-}EzYS21@0i;7dIcAZKB%2PI}`cp(GL5W7InTrs3f(^8+;>y*heDPh8%b{t?k_`=L9fk!gFO$We($a-_}Df%|y>7OVNlIqeH~O|v!41fs9+sx7F`?%3L<)5?UoDtiRA_Mr5)QSB0&>jwuc{Lx@$^6VbE)acDD*aJswwNzz8SsSh&1;NGB5{52+a@dDmDdOQ&R=uU0a(?C6=b=-=(kM|r4IODrU2KDn&&h9_9@HqLrsZ@#p>O@?N<2|>vD*Qie{)p>(UItH&i>kPTf=#ndy)<$Wkq1c73xn>dNf&g~k&AW?`Ycmai3ep~;2x30;|ag_u*b>p>eujo#v5E`6y#mV%UNmA;(c7jiG^GgWW9qqyO9oZv_J7n_u%pRvEG79U6>%2GTpU*79LO3*QW1aL-@LS?!5+I7+uKh^T7N!L(04(|R+m*W91lH{`yT0mOc|ZpwcA^%pZ_=9{rV`h`l@_F#4wJi>m#b-bbbX>=CNzBR8oZH?=jAON(a8lSxQXp`^_9SQEn&&XydcYl(pJ|(&Nj?nX-ka{4hnJL&B{I6qib;dyr1n8<`WLAOm{dTM9E)Swrza#HIfT8amqe5=W+Z*UrrZ=EO=;WIlR^o<9Pkuyx`}hS-=SXdDy!h^+nOD!-Ln8Vdlhn+x2NuC|5$_~iflhM)WYcrz8_&Nd542byjo5cNunrEy(}c+a$angVL^tJE0Q$RYmAS`wd$rUTLc&_)(HByN|mQP~$d2$(iqUa|qlKToEG|KbTIOuoFpQcNA=II%7mx|cMG@q`O?ao^{7QT7=b3F_BPI-Ug?O+BlZX=2uw@&b1k^);9i&^D^$gThpMv`3qT;~Ac3#DO(ywqLPrOV>|u8p+MM~5;||E76CX^mzUM90k7I{pH6Vx9ehco^yT{;Un}b1U8hJL63pELuBYKYu!M)cDDpj`MPp;SP7v&Z^=6?sv?`Ndv-{=q4RG>bjfZiL*cHaB^Kx-->z2EiU691Fh~ep>%T0*WzQyMRpffb>$?mL8eIR=7Afi8$Mz?Esf`$?-8T;v=P)rM>ahiJj8{T-gTu4ls>=Ta{@Xa%VdEA?R@91ji}$&jFmQg9|%2jKYK|k;dpdc*gx-n6a%?K?6#a)6po5$YY+@e0^ZN7C+HmN4`+?7s;Q?zb4kWAw`rKay1XZ$#bYm>%)jm4hMZGSH~;I<4kpNL84GswMxChFk#k^!V(g^+n=z=T2d{l_)0G1=z9m>S&{5aWyQc5Udk+i^sXWt?jk;aWxX;@uSwPfZM4m^T{L|?N_nWVVl;ctd6s>RgnhL!53R9&LHPFoV+vJrZWSG{TxRlQ78Isz4*j{qmNj>WKL3iJKr5SyniDb?&e!mAEET4`Ck3-w2u+*`ktu|Uu%f^h`gfY3^gwBUUMH$T8%p4BfMjb3y1u^g#Va>`jZX%Z`MEbCHq+)Q$b!Tdw<|Uipv=w_SqEeM7~-%@OYn;Y9eg#whZV`k#Ew*K%Cg*toysR5|LOJ)fWY^nnXRAF9M))QSDALO0V%e}1vESXV>zmHsm&6A}eWi@)B-x|D{QwdGq^F`-Q-K4c^U`Koe)<4p%qHrWq!!Y||yn^POUq>QscPw;xQ?P`qIg#T%G69-DJD{BqQU|iVKBAqcD#)Vzee`qPcM7|31xgM#%G7C=LeSf{!0pqy+LDdoAJ6SMcwBekvjmxT)ZNu~0cO~HPuGg86TdFOtH6QCk=o8Z!yBD&6+>e-q=Vdk6$lsI1hB*_j-)*^p=antN3(P(ouu9o7I)UQ5*tNPvrb(9zJe*p|lEd-O`21F2@^>y=o8A#L@{-bDtk+CMA~g%X)O1FF3c~nE^dGd7&j#LOn0Dn~pV_Xz>qoQ{AbkQBVx74%0SM>PfP6nTLJqkYkn>sg1fA>;n<$OkOYED~oWKNSflDDd96VR;GaPO1Fo+k~=VMnq1~LrUE#*=I)~>2Dq2RXi_Z+^#oM|MtgxhkQl$gBeQ)(mx;<`HJIwCMBpN6M`+&yoOHV{6F#STYA-oMb<^U^+dkvbJ!>oc%Kb#DqRi+|689L(xypHJ7!$Lfi16I*0)pYV2Qf%o3UI-VFVZph2i*@1+Nn+)y;w?&7L18Ct`dj>UFa5;K7KOAklBBK=A(GXDA@s3D(pIPo1l!Mo49RxD{aaT~{T%xk!`X*~zzN-BidtC5RtHB6ISxPr$O@3La}DEqZ1dsWcZ@Z!#UR+s(3R@B4Y8?RMe;PI7dUf8S|$R}hzXL1CY52;y*<0R4{q3`4W`nv4EaS}e-vv|LEa{MciqsYD_@#!R|?RkPaaah`$OxQwzoH6pu6@~aVg8~-mCnG@Z^Se&(nh-w+w7s65+d$!{59*?iUh;8a?zRN~h4RQtUSA!OK0f2Z4khK(dB&*wemr#bV_X*L%UbD9@pa@qUQ9ZJ$@B6&jN>8e9&2Mszk=7>kfVt6P4G(o>-*7#y3J&bPx(b@p#IaXyjTZ$Mlfts`sl_?&^RqRT;Hh5qfR6Q{NI?rHLQ)&Bl7BZ=rH?b;T3}$s7J|aq`z-s!hF+$dnT7rH$9n4Yrf1T`*&NWqP|M1)2rYH2Ws}tTI)>lNicnX9oUUJh8^#*o(m)yZDxa{7bKVKhpW1_KBwEtg!1`FgO@_kt?`tNl-f%;X`%k$reB>}@}kL94*kMj|FcqBP)IEf}^!_?7jD}1LiXLlBy{uVobeIe@Py8iM^()Z^60P+>lw`t!=CfQGre*igzc`f70AtN>;-eVHzrT(iW%p;pVc(NEHykhy2I`xg&pnz01^3##8!0|B#C{)T-3++<@U+NAOXSA2C)dJQUnZ=muysFj6wm8h{7~gX3l_*Y3|iW&;dv2#Hk)|yl*rRwqxdg{OAd{V)pCI7%h&e+&r5;_hIJRX@ayL3&#$i`U)e=@I#2V=f*U6;ZZ=Wx9zW7F|UnToCRb`X;bKek*FE5vNEH5<3fm%+0_&pKszvC^p-g<8@n+6+GH+q}s<9Ur|R#?AUMTeV)8;?Ibisx1Oaps@qF$SD!F5H`=hI|$5rI&23#fDzXBEBOmye=YB3|qLoIGrr>wje1R3@XogmY1PE*uVS0jiou@-cq+KOAX^Y*$3{ZBR{2hVHxfcl#8Am07IG1+OX1h31vNqdb3%vqo>{doc>kW!~wJ3!0tWB=X1?2Y69k?-{=b({mAx)Xag>f$(we1-UXE<_xbu`U`$z3JF|=i#C(C@XNgVHHl<$9>USH0n?`Y}Pu(pE?OSL^JON``*MHD6(oe@ZAk{avef5>2JR_dE{P#lN!uuWPZ4JKJry;zE+{?j|>0~b7Q|Xj-Tu!yPOHByvNp|L)?GI+b-(V6!&J6`-Ub``j{*}7@eKM<^bXI)H;MZ;X|Fyd*0U1HK?cy#&L#CUKcw1R2GB|IrZ35`07SufyvVK*-+MG7I~V&R}aNB^H03W2LBl=^y5oW|7!ykPx4adBE0_z|D51GDWpH!MhagMK6h|3{jWb*7V;IjPgsCK_CHMxMsD$Ql3w1-&jy(j?~L~=K4_lWT#*e#f6<|7$Svf$pj8Zz@pd*P&&I>9>nD@`=KlftioEVK)5v}OVKS6DD`J91{_Zb$eIIqQ|Enqs$p5a3Jd-}O?N`S)Htda@5#+$d@my$k3l?9ByHDr*Nh<)yoy;(r`(MoJX-TkEar*G-mu)58+;O$}5$vW@FkxG}NC={U?m1!-YF9LT38jMZH{XPs)y}EZDa3xOl+>)Cr%c6DP7EXLM2fMvAXE`TjEyO1>{VxQu*7ax*&~h}T6YHRLGLf3PbBS{A(++eqohcjVU>){~7Hr2lPgI`Rzp`|n`DAP?i1EIi(=!#*I~jSZJAe&#+;#^Z_g2Ei*FaGrPJ+xB48iFN3K>s;6!N{_jCn8H^LPsc6kSx~Lu_4(9p)Dx|p=LK11lfR2;8!6*i<$mJuSTL+gJf2m>kGyp8i|7NloH!Uw5$fBdf;#y;S55)aPjMM?6zN})mrm|8%BSo@ym6Ji`nx>?rhd3rQBj9nWVq~w_>{+)5ZpgyKCIU(YsP`=b63K04Xj7{9IqfHIP;QATk_?UAC{at4c5PcUP=3pE=d34$Y37cG)uHNm9iA7_=jCuS2Z99YnxEEVyk4Y{UY66qg~~s1qI&z0LyA?pX&JotQ_0HtY;P?b|K72Ks~wMK1M5=W^G`=`{5FG0Su-Vbfao`FvJ~SWw`6)26y`wLF?FM+dw5<$*rFOnH90is?1JML$Z>i*7@h;k-#k>+f1pm(3o6acgfGYysC8v`^J6fK=`RRX5jsHyj$pSEzKijRQuasOyPf0EIlzIlexD`xSK|1;xPCbIY@AE_VE9q$@QHpgk*~90Pm#uh9CaKg(MQnsQZ}6T(p7M-L!D;6`L*EQ9C&*FN>Pz6a>$sW%#zVhIbf4AHHB7y`lVFw@6{k*5$i4|L(;)3SWV;bA>^y;Q8h1DF_TysxwplFc`*M`D@dWF|c#k06D%k1oah8ku6d)Ncl4H;Q5W>9RTe-HJgCQ9E|cw~b@(d8c^+Q=uw`^xr^UFAYZ-Be7^aI1Pf-cyccQI;W($Z#^`1Va=_|p)kinVzV*_~Z5~T>xv*1F`})|CABaEEpS3gpVHSUGvY{Z>7d=Y66JL_X0Ids*d6m-<7kJ~-QEtJ6?Gtsgqh}+2>HCnJl4v+wYFd}A@CxrG7|;w3_z8E+S+f_mg2UAPf((r>D=fXHhXE7fD3Q*;!O08@9;U}V|`XZ?D_cl>Vce;Y}M44Fgrg_QlS>k>M~?_#qc`o<4sO%CE@eM2tsyY9S~RoxwpxRj68>{;qeX#d42b2yIp^!NIAL|V^-`jMzsHF?xgT9J43?q7?Bl-#@B7pxG!)_O-*Rwx0kcN{F{?L<7y1%}r7rN9r-?~J+XsJryF%<{q)WI$3|u-%+d)J5d{#gW-Gcy-fOIiMWz&DkmrGP~$78aw=|<{aYPFW&FbaLt0-!|mx|+Yu*uF4)R|MpZ3lojBqUvCgk`DibO-eh$ogi~35^f78cCiOhfMQnq3}(!qi1ZEJODAd?S+#X4AzMAmZ{n9{-Jo9!lt@2EpW_gQw{H^>6AKJJD+=Cv`p(3q7X1N=8z1b9VYzIGU#%h3D6fY9qJ0-XIQ^UJK-O$w5kV1L2O$X6Bf-Hy`C(4{L`u*%?6^BrrrVw=_zaKUv6Wr&~+On%KE;mcbYMEjhxW@ho)4hOkHH1bx2-VQxh*jo1tznFd^tF^F)-U|O(x^i|@VZ@;iS=61iAQ_VfB)}3kDLvYfByKO9^>Nsz7fyyLhWkP&NG@S+`en!@6^5(DCcL6yT&pWqn`rFHfb8d$OZ{swuIpoJYOkjf&lv^pqY;-;hn%T4rVr`SVQHJ8&aDBA%P;f7OHo2cNv_Fc`cd|IXzp9*F4AW}efWmr4^H^`E2))Dcb~%q&DwOKlazBnJ89MGibqT!&q=KRnM>?6`Gm!}~A4byW?^9pH@E<8PkrG}sXq4_+tkbM^5X%3=(}P0I75pFCm#v3yjGrS!F#+(~p#K9K(6{9Z<{6r%dU;Oa4^zXF!kzI&IE3`vg#jkaow9(^zo2_^-hEU5G!kJFr~o<5m7V^q-A*UvWzZF76CZ0@|-?vE`Kg%+)L1*bT91pyQsYS#O5=zVxZ$k~I4lXI+!5C8M;frq%MihlVH#~3)XYwx2?caZ<)cj0oE6B9sbT4MR@kEpLs)>NNeHaC?&zp3>h>Z_3L6UM{aGJud#^TNFG`YKPyQl(DP!2Iv-0hbSmSE)zH4nLuTwttbX`DWBVKW8dPo_U`IE_zPpd0~jht`jh^Y+^wF=L>C~rHH>!KIQx;kqJkv11h$DM4a^V)zc^L=UJmddqq&UsOO%)KSLo3)P{Y+ntD)Q{joaLcm72j+_jNVm|27RirnwBxseQc$sfXmoKasDM}KDdSEhpkOMmtlrC+a;rqWm@N`rZj_&ErHAUQMv_@iP3!ZR@70mAv8x>gHoJ@#_iP}16IpSpfoVN@e7FTPI8BtzO&WCCv)(d1k-Ozl*cb5wtSY$=~uG2(aLnk60ce3)u7@?zf4PJ1U{fat@To-VN`_g_SfpMl4asTUcN4GDEfE^WGlbl>oFMTO>Il90i79N)iEVD{Sz4X|!f^#l85gfKGxE7R&uP4vl948R#g&E<;|AgS{4}{wt+GtMvu759Ex7!R~Px=WM5YG$A+^p;u^APuuHq`5!nFSjX#TT}|LcR1ruE6({6a(^`d^2?!h?Bmc#iI;3BA}u5>Hy+zUO%3_><;lel-)t|+JJa;a=?mEF&Z=vhgzS}M}6gBWUpzcMF$P~*Tn1%sIP9Eoi$pllLgbsh4C=v>&iLD#*&sXAZl>m+&VAxQ9L|htTaRTpL2~V$&@*3ryNRZA2MOh;JleLFJitc&LaXMo-;l@Q7xPFQHPun?Ca)DW`l9K(y=5r%!3M2uk~Cnvw@uR>@*AW;4bI%xEw(a^i7O<*+Q99Pjh>%E2@?W8{yacCv4PLANR-Cn)=aTYq)*;dWyc%+je@A1f33+QY(t`BT$Es^&)lo#Jcs}{swOW)FDS~y5gL_CgK?>B^$uK}nh7U#24BCf#JJQVtan@dqybah|M*&pzS<}7a#y=j7OYvJq&zT;aqV50cH3w<13of-UDCLKas8%maA=btbX4Fnc@1ymPxc$!=^}9dFPY91Uz$P9i1*`BEdE?wzgEP3w0Ak1E@6Y`y7)R|XzQ28Rx2f=b^z&wxqDGqbBsDzcx@lbiBdV#SbWOr6z$|GF#?vp0Ve^9k{{);V3iI~d?L-n3ehGT)Y1u4RsHWI|%)S@#SLtC1>K&Pb1b=t%kPQLue!;C%{G@7*@>Y(k$uy#>Zl1DLVJ(Tpm`u}+ke#dz@2#h+};bfQD2esCT1I_K=_ou3I$5IPc^x*ZXvM)lqiv=!E-)!%dK>Z`vm{go}FB&QiORmnnjrxkTU-ouN;D7ILD0S?7{l6p?W<}&?1{tBg>O8keD0NmQkh*EY4ZQvv3BgnCH)-H<{dY**U&NpO^d@yN2q$;8U~Q_et%Ksu#o!In$YFsdGT5|#L2mp^}|f4uS^e^;E#A=xwZd#4h!l#`{s`ZBmVX0w=1h7t^ntNDLKTSTU$?xDWLOxDa#fjPTnWMUBr4hCN?~4E=6CN<(8^;GT_t45-F}Q;$xm`+#GH)VXAk1#k)aDz1BOHaK8@=%xcya&U}YBSx0f69tqE{nDkGRK%K)s#|pU$)tyc+%Un<|k#jvoZY4pYc}17KAHIG`!`%h*W~akF$yJWm9r5+td9xnawPeC*;kJ_t*5d11R7WO0J#sGyi>hEqiq7LDoZ|!6Pxxd1o>?fRjJ7FYOkp(JS1nA}zKc&*lP@$HWEC|ZCO;VXc>FcKpjh#5ohUcqnMN`WV&xrAJ-ZF&)os?3LA=u><)Z`@2xt&W#Ckvr{h4mq(t;b8d=M>af6J`=iMZ8W7+8ro8*c5OM#L{nO6KpPWB(Ac4*I-CF#X;uGc8zE4Y$17sc9epAZ+kN&+*t?pzX_hrQ&;Qe-L+BLV|ZRtSv(cb!k`s(Z5OLd~kG&pAEaov-m&u{Oa`nxTQ4sEIxZ&fxT&*9hpwFd}YksSAR^St@Uhn!PB_YVWa8}-}PJVrbvXU9x|9wt0CpKH-;hdfFB*_F$JX${*S#8Y$&IbU+bhRyfQuHA_Ggwz}IU)gZ9$vUe3D&j+nq-P52B*MT3#aZjRQD2e$%!kWT`F+hhDE*j4eG#1@R+;cN`e;zU59$-LKlk1r8oY~iGTlq@TZk$v=IAs6CPm!K;5BX<&y!~B~n+*D+HWkVPsIQzg#0xG7Wq^jJK-u_9)K_G_^R=Xbnax{)BViO>_w;<#%NKN591(SUk_hS_>)_2@E;0-_eAx29I!b*Mx&E=D$2c~#2p?6zSi;X&^zGyst!V_Hhe(S}Ke9%dY&II}p$RwX%JntBC(JpX;uPZV_y|J;if2c&<=a#z$#q%T%XeKH8s?q2zP0$)%1i#aVM^dzB|-yKF=$STWvB9Yh5|Mj0ZX$M~C`2M}TC(U#y>1{Z9e=)wE@4GRR0XJIDbnG8SU1YaLEavAtCPWz(X4O2R=q0X8+?k)ufBdpi5I0yNZ*!#RpLJ90Axht()X;I?w{!?Qop)l^3)ENp9;_B0`kMvh?{9W1>X1)UI^CBDGT})|)%B4W)FJyz9&MQMnF*t|2~zUYFt2T1&)!{rhsEy~OV!1Ey+(ZFo&@jh18u6YK8MTP|{suaeJ83j}~>R$$(h5kn?d~m17>%_?_`5bP*RcFGqi&9mG6nDV-X2IgShUJGMLwrJRFI`u*Zj9r0Y*-lA%nb2W*#N3=~5#No^;4|f4(!*7~>-SB)hI>!3u|g>;tl>Lj;}JHYZ*(z?bb`a3BW1mlL(A>hE4KK{#{A?Z{S)>)CNt_M{RPJZ9N-$x!qm>CaXi$OevO_%+816#j+ou3@qq=$bx$a@$JeA8y~?J|mw4-@d5Lbbf?*>8#g94$HXw_4u=`nBPfVMUT&bFAZH~{vyg$KjnXSqX4uqaqAHMYz;u^ndcEE%*m=Y5x8h0P>H^-DqappdmU?rY^?Igvgi;Q=QEFG5Z6})+#(&xDJq=ijyR2C@R`g1|Z5_yK4b1J9TGQjTA7o#~^$nzEp+{yi&-XF(Pv_B*M;X!!5`)w8&Ez+U=I)gl=4wQdrCDsc+Jl}=6QFIIGr|?0Z1FcNMkA2>V@7i+Nzo&o$tCH;^1s)+D_H3aOM=u%DoxHZEwW7Xae|T+U&Pj(K6DAlX3VL-I&uD&)&d|%QZFK`bN-brQDjOQY5;h;w2?O;LZ;_yXvi%_?W_Kbg8qQHg&=A*eAD0NK-Rd+gFZDvEx0$bPiR>Vs?#(rETzV}$p{9s!t)F+ERP0HvANC48;b`Bl+*QN_;2Odi0pF4-YNB$P|^N%~)Wd1V;;RWg|>9eL&nDTTWWWn_L(fGbr>Xzd&=~>Wy{*B4O1^B*hou}eAwlknSFlF_w^N5rFr8nL&`93OlTMEbGepJF?i-~hjvEkC9oJ%xg#A8>NKiQ(dfzcjceD54byQdH*uH%q4JIF-v$>z5uU1W8I4gEy7I?=-RC}qT&Z#uNFxSwU0h+yi%uLF;-mP)_j9y{<~wB#rpvVnFFx;K?61QD3=x>dac{o(Odxw^Y>}L>;x@W@1K)Wg6JX9oyN{iMX_(-uI6;Gx_zIALLQbO!_0WZRdVMPp<9z>$eHc`<$-D1>5i*(;w2Y01F$nfvJ=v}Cb0=TnAmWXG9Xm``!y~z%ID{%;p=;Eh2|;6F@f~Wig=HD$yuHIQq-RXyDMKxw3i~zpAWZ!4Oa8NYhFx7eDcw!m0!PQ!40q0b5|{~-aEG1Q^rS_35VA@oIYxab?$Pz_SrwQU+An&p-#C>E8(be>$kfApNA{^MC-f58KCy5LK3D%XK8f8Unhi8h+49O;me`UaZy^4<^uV-x{7q$GGNcRkr(ivcT!$>y3BhFkkzcoPM%+8ykA3N8Sy#KpoPXCQ=eOg9DzrJM~Rz7#F$Du_@vFQ_mcP{A*2Gp1PWHq3TDl@KSB$zcgj760?B|Ztp7QjlM!WlPz%8cyl&nx#XG{n`=`-d{sZ(l6kMUEjXMx&_!dab^xe`%fOQMY#Y>2PF;88OXd1|eG6BgjefxO$I&sv@!z9y5YCMLiIaz1U_F^aw_G%i~j$%WjPtK{p%Fpry-Sog#UXT$0a8OhPBh{qW|`BK%E301ewOB#)1T*DV%#Eb>g`TYe~H{kttROHr9jlL}4w!g6MIg4=}O5V8Md<7Fizs0PvxJEg57F~AjrvVH0-_n{RUWoi{mm2glHQA6$YjH5Xfc#0_uQ$eqD;EAr4LZnksBz;i;BjD4&+csl6hHIjXR3`iZQ_EK<|BJ!Thu2(N)G9l?{oQmAF_3bllzJr#WSE`h1~Jia(KTn(Up0@B}f$5G_J?CJgWQ70H6(k5!S^b+!)6sdl2ynqSrXN@%BTjDoe>ld4&sUaDKQ$Zm0NGEaqMr(6Us2W=rM`V|bUbu>Cg@}c{2ULY^gFzGBENeH9ZvLqZFtQ@{xY_%>lc=00pCyhD(aIr7tWsBJDXTPwkRE)V}X2#$9qMJI_n?bzfXuC>2-|pm1V<5VKvhk9>|mQ>$m*GhG|=(jGSr_U-30%v^}1~pNG{Yi~5AY><{o)<3dL7qH0Z7#QFVwZvX6?mzSWv;``}rPKUv(~unpP%=p-9FT%+!^*&;six`fVxH5|B_S=J~WgZRMvNp04IK8xJPI&MYrKPTs-uvqc@epnGM>MPP#<@9*UKmAiTQC~^uxh!65kO`-peh(a>=rr>D+DMHK&Ef*4>_3P{RYX`!BEI*Le!(wy_Mpxo=jjN~VDitEf+_n>g&mx^rHU-D>}vSFxB>BZ+EV3;qQrfEK3rI`AMrr(51j3Ujw0)_0;b`)*oxwHYk4O)kVvmvQTsz=dKjfYju6T&Ni5hoJ<5|Fj(EUI(Vx=ZY;aCfebXF@c(pdyvv?r~R&HCmq=9mMa=))kDF%q>=IxF|eMPoWPMev?&+i#?Q0L5d(|*K|OoQfquZ7(xb?*<|w`7-bGa>l-D%%4-h?71$cfINV^c(KO>#Y5DRaEp{7T-@&hN9CZNyO`hEMUSPftk}K)+0{N5o=Lk!Sak8i5_Xhqh{Z^u|l|H`wvA&DbpR_l@fXX*#u@UrH<=W%A4f^O$@M3un^RYM}0-s`IPrEf$YzonSlC=^x3cLX7T;;EO(>6%6#+d;K_$<{#G-yH#zX^wYJQ?opI-&IU)j?58Yk%om^PIKMZ&$OdN*ku;Bwlyfw}y*lsoc+eWQcflZKpM2d^a11YZdf|?`zAIV|DCqj!W-iv?RgrB`^tEAxLzj%eI19j?(Ux0$pQb#gThc?>U~4ZA6(vbnNh3-ZL5->{lq>_0dEAJ(KhLjr}=%zuaBw$p6r{eAz3iT#(OQ@o~X##3dT11)4tMf)4ZSPhAf3C;JPSX4w#z^mL?Fk1|(_;Bl<_pXX5~#jlb)|6X{H2JSD%Nl~}Uf{eAFEo6gHU){6xezLiS0lcG%1C5ma)6<(aoJb||R#5G;D{ieASD%HI=dd^%PW1=&eQZPiJy%a9cK>0+USSt~k!#4G?CX}Q;y}ap2i4yDkmqEl1HWE+6MCs>!S0$#s6zsOs%p;u%Y_BUE?(F|nJ@N8_~`@Dli5&gwaxX-IO0M!-L0+rGvU2q^!4XE@pq)pVA(5eqr<&Frm;?&k-y}JgPY`gv-tBy&mIb1z*F>_L3~>B7<=^=$Ah+q~nb0qOz1Khj7Vkm+aFtbh4;>XP-xCl=D+M(79T(<_vH&I~DyG(uO9zel+$)F;Br-8#$9GT`(5_eXOn{#v}L^l!CIOdx$Y5{@DtpNWB)mwQ=IEL&>qDvo?yHm@F4d&Y*dbJ?~RV-T;d6kB^Kl>>I`cg*hpjrjAo786_zxghx6jC;lmb&LC}7I10f!rxwDk(>m?`99{8Q~3T@1`qzXzP+P418S@VmjqGf&*ofg_xw0S1BTC^@OAU?eJ6i?_V8>$7OdWRW2@9_#NQ`WNNiikgxQ`2+;_hCzHM7)pF3;Lf{LC6I_>WfC(lE*%-L{0Pd{@Vpl;d6*|D`!nF9hB%$XfwhQ!7Oq76uVORp_|EcnzlmH&OPN$o+&oUKS{LA3bJI@x4?#@XA@6(39zlwL0cyAbxX^Z$+;b3rt$)*f&t-yu5bY@NGbq4Nb9{+(r_j0y^L2>lUf}5%!72)FLK~23&*Oktt-Gi|0mUb({+ETz?%02PLVQqP@%`CWCIM;Bu|)`V5#P6PWjfz)WRex)FLOrhF0G`2hhtFG$w1UU3rXXaK{}B0PFI}3*WaA_>#+{;{N0eIW;Ba(p19(haFZsD32v*kMw;vp=f2JtT*_v_oXx(PlKO~`PZJV&dyWm9u01xtlo9`Syv6b0CJsCkR;FuAN4zP(__e_p6Ntx$DK`i8mAs5>r8)5&Deigb_&68!)mfUTn$9c^?0On;@Z%xWAuq0~-Q^MM&|=%YS9<$VhfKZD@pi{eE=&_StNB$6^R(6^HdJ|h?(EdYyl^ikeA320*|2(T@YA&+nD6F|?3HW};qjmUDHPxGbA#e*TLyS=JHsL>V~mmqkL+};-kk&W)kaU+)9C-bldYHlS-WrZ^z2VGdd2Hi??KZX2!YYhQw&K!NlS$bizp>!mhgTSvcK~B#7blzFr`&uK*W&ukal=-~-H`ywNG5P+^y;?qfUH};+eOLyqeAB1BXsB!xUJE;oicZcoWm5yfGd}I(aYi}`ii*Uw2AxQa#!=u1;rSbSxjEi(v@s@;`B?#?*qmaUu*c`j}8ZVTc4XPr1S}vxtS(BljTCC*#c0mrs%`9Q<)lXxUkbrA}}QcdAi0#7kQo~baH)}eW?uQ_uF^s&s&P|AmfVWTW2QX^%gR|qZfJbS5IlPur%gV&bXdZZ8i=36YlTsa>x6P^f~`vibEeLzMa@WpRa0iK1+H;TT}nL8)IN=Rx#q^FVAjBfNo9k6oQ*S!uC86Lz3@(i2lYvAdDOE@+p~ex`+55j-`V2Fqjt*#>`00r`-1YzOKX@bKlE7p0#NXWeMgyS$PGa;ldS_npP}CF@)EIj}*~c8k@-5yZ=jIc6i)9I)SEH0822#ovIb*0y*F7f$5ea6U+DC{<>%c#n+&IJpBDVUKz&tGd-C<}k_`CvHNLx(Qh#-Dd-s|Bgw8%p2&2cB@cOe3XlCF4m<0{XuQSyb;`NVv{d~6JAQKE19TB95A^!fvg1V$@EYSAb>J{FC`0Vn!x7W+r;LxhkHa4B&bH01|59=%r-@m$B8*!t_pa1@G=7Rg|pJ)E=qUf$6-EyhP+3+`iov;2u#B=-u(`M8r0I>`XDZ7CBYL(My&9HSEjNee+x{~70Q03fm-E=AqdX-aOR}LYbxYF=*lwcN=U7xdPH|1Qf$OfxzOKRxGc7gvOl)^)fQ9FI3WGc9#Z_K$o}@F%Tr*9yp5Ia57b@x!SNr0W@Z98zdhOr_0qt?rw4y2(7~_0bjw$N#BW)NO}zdp3&{0u@fpO4+e$>qlnKAf6jjBKBTm+Ji=QF#{^0WBb(DRuy}ntGo)S8WtZNFkp`1VJpSL3YN2;rii?#s8M?(ETR)sXNK8m04$4>=ug@_vIL|ZmouN=Jh{0r)cW*gnn8Is87>w_MD34ZoLMb}7%{&oA>kiur=?Z@eNG$aTQuCG`J3H~ycfTu?K;KJR%0{lC|fb3`OBut2`PYU+Y*7+0RkA|b6ZHbiYRtba<;jfoxOb~?{Euw`TZQB@<1YnIQ$mb!;rc>ZU2d+l?Ki(c~1#4sfri1c&v{50e*C*p4Wn^?DaY@PeSVlwh4eTFZ5;eqe#tNl{lh)b7DJTm)84sa$&G#q6k|NSST8#_Mb@aM|i+JSjQlx9>XyfYVSZ-*@Hru5ODtymRU9LWUh#^U>*6fv$2!Ko3ei9C|At7)N#3&yosE@6%BVh$XBnDU2Zh&qJj?BXzUB^UN2?~%`;^lzU0!!&p=oegIzGmQr*e(YqQuMMG>6tr#D?DIzc9{T$ZatNKU!(`j@uJx3C9s}j=J~BBly(d5F$2Y`hNM6|)o{|IVa>cTykrdx@&PwNwDY@`w-qL5Q=3;)lCc4FX2eD3BH@V^5P&CH%`F&t=DxsrR-n(z3{TkyEoS}W>q&*w95g$atON>kVy+~hw1c&cqrY?s3$+_N7!ntr+w(MrpT;xeUXRZ?Kg%1)@_b&G%?tAg~t*O#H=t^`mdz^>-N&la*TRgD-qH*U9rCwdTo~6jq%YlYv{);|Q>cE{2{POjn`h38#-@p}>Yr4w?D&{6JZy6omq&Sz6(xTQrkY^Xmpaidu;@~;-pIV{{m=qTwM%T!yC|FWybrte$0@T~5^8&*8>w0iT~AUr)A;_V*1oxGOfw>f&bOL7|z7#B^{R#i~=Pc@lc+s=cN@AZyFti-(k^wEd8t;G81cc^vDp9I7cd`sJob7^qC#Ms!i193&F0$aEIumMxl)F&(czDeR1-iw7H$LIzC)xrnd(^s!`i7zea_Z|I9EQu^%P*L4X7abYoQTA}7S#I0=&KmFXC4N+q6rwKkq+)29FMzVX3$ZL9*B`o+I`eRY>FbN@*zin#b=9g7#E&tTZVqnYz~lMFQAa5{>Z-}D$~y&I{+x~=SHug&YphlGXT!Sqz-N0X^Jtj#!l4Wi9^9)uGwPH@@i8FJv&@tE^HW;RpuXbI^{&i-YiWIK;eDv1$p5ciPXA}#gdqAeoQ!x^zF(FBMMWRe`rS~^upAXSUfyKF$ceu__Dsa@UrX8?F^vr?nuqd(DY}UCp&KHe|2k*SkMI6K*^hF+o9imh1rsB^n;}0De|GJ9=@ddY&kt#zV>gEQ-flOO?(l3F3zc2rI{|gnYvJo}KHW`#6}qce%B(`1zpv$<2BclA;5*b;q|a)(G&B3*_3`P+wWy`(rB2<3f;~<;Ac!s6$Rq78VnwWy6{1gjE7Ln6JCylp0KectFm5TD1!Enx6XM?&y^{uwAgFW#WJG6(Y=|Ie#j$a(bflxr~N3-Y;UO?>Vx0|%B)(4_zOd0NEFUtUDdgP4MY%KIqiIAlGWE|Evby1$r}7}qX$qtAik9N6?t!T9uEjEk&eSwO6>M8m|a$8|BTgRZi_=Zt1U&0)5`TocAc_H(U&z~j#atEA|wA6xJ0_ypuYhmEl=H0_1Pc=C(?byNTvvy%zgPq@ULS48pu*?3!hz{zINpDu3sP-hj_k+nBT_`^J&!vpMzTd(F*NMH(Jj(aN$!-M8$vI%Usdw6vgUJ8KX_>#doE(_-CVY1v#Si@EG1FrnTDd^ZLz_XV13xC6BGbgnh3~^dd0dLmQmBZihUc6-2)-dIx>24oucWR!AK-M{lE3pcioM}SLWu7GoXL!i=e7}D5I-Cw)HTA6NYe`Rj*%>bbp;14A>65BT>WfA7hPL%pV4=w6;!7E_2kH^#)s_84V@#=gksD|R8DO@Z4|tz>y%d@w{k`4y$UUG`_IUn37lpT8uEZ+Q-)!a)%B$ms+e>xOUw~%w*&5vh8me5#eJmoxY%%kp#$42707dCJxxef7UN_+jA-tj>8^^}XM(x_W*EPL!-a5x7HPsFSb-bwM>yrCNYq$mT57S9`2NI-qHQ2Z)A)S3>YkI}QcsIR=#S4(IfV!$qgk{TOIeb-yxyMocnSaA5`GFe$l9ecmN*oWR!HY~bYDt3&9IL$;fV`UwOKPR_q2=Q05Z*|^(%mo2W|1XDDqb?%r*&;Kt`RmpgPsGV{pJ59g+|6?=7`TG?K6a09>^B}XZjn5ED-ZFBjVksdd8zQ$X8z3@N7PpZmyTZBEJy=C;)nK*GViZzNw-n%<}AKXQCBbG720oWE-Nv?y?x()AJH&}}dFJB~7Z{e6bJqQ$^c!~n-23TvHf(Tlyw)U$dWr1Yndr>p`x+%oMZDQaK5Fzw5;%Jv@jW>aasGK|NCv;I>~+b%c%$xccHGnuSvvHK=$i>r`u^mI2br2Q1BQxhA|jnpM}3a$yVzXC1p7ZeX5T5g$bNkDNG{obVtM%8`7p%KvKH-HY{G#Lkt$zLoJZVlH@(QtkPF*F3qw1D5hs1M1f;TIL9mmi)j`DlzhusSSf34kFD-oY91$mdq&ZwJzb;N98ugWpw2QKMRW|fLHE}M8M;(%7b6{WHT^^AAQe27-A^VK_<8t7PWrWOzuXsL4&S#?U%!P}U>Jc5QP=}B{ax#Ot{JGVSH(_2NeU>H8_!F19N8dkiz)asLUp?DY)7>JU4Mjl45xYSKj$1vosfqL{bELEGgg1o}#$2`dsLBZZ>+c2zjp1oAIV{S01d0J6T!rno?J0Ff-V{HV?G^u%*RLQ2NxegD!v6$Oq$h^BuaTVtx#}XI`%TgT>dq6O1vgqk8&Y>q0o-`dPA4J{jXuE`7N}r)`W5mg_mjQtbAhaXnUjkAFDugq$+0U(F~>@cPLCw(Ybcu>$0uAoF%%z^ZH@QF@U;SX+K-}>7-6(f~JRtp11k_OvoSoB@KPey&TywPlDqlr>!j9^*mnolgQT`pCzBu}^mCmK->B6V6mp>e%gssz-$XUFYkdZqa%x*f=FD7f$X1lK}GkWpyJmo@V{}Y(TH-68ND|W^hFfz4i2J-Zalm*c>Xvj}AIrdqTyR>c)~>q+aUVaIW2%d3{C>KMSkzZ_ymh=8#P_=Mnb3}q>!`1u?htjaDrCY#Ri;NjrS8iJj4SWCv*E__X9qKEx&x`bPuIc^!yWap`zego0)s}b;S}S{~2zMbqNm5|0ur&+(`W5C3Z$teZ^v+@26ClW`RIfZOR;3)GbeaGcSD7XM%XllTUMPQD24Jt31Pd&*J-;6b0bxiwoE?!g?Ioc`MxZ@hQaf14HgQx^O}6=|M*`iXJ2V#UgF8`EwYZDc5;qa6L>ynTR*=r>cS%WxmhtE!r9{c#s#;>hWz4;`~0!B{}f>e5FVG9rS0I6{SJ5-I@y{&4d6eMI92oY4`B8O?ePI?jWLZ0rRy#%pN)+l@Iro)3$cbMIG|=;>$6wmVBrmx$1Jw8T$wMf7TShY(M+40A?NbQ{~>lJaX*vqrk2?h0xxie0p(%^uwiLSa>s@LqZ@Y>068a6;Q(b`On&T0Ol$#+9{qSHb~XJ!{8Ph8#-Hi}IKF(z#&}Bo&-VPf>XQQnuz%)p+VTj@FBX%sV#xJHzJr0`7Ez3AT~PGYt@CoAa7Di20TYai^wD3XJRPjcIk4rsspZafQ_Uag6Km<#p?-@8$E?%ln3~uFP9OYkv8X0vM29ER|Y^{1+XQe9+@r07DJUr)t8HzqVa>x?x5Egf5abuU5zWBEP#_XlH!^h%O(Hu`I=PJzIA)+UpS)hMKr)4Hq!3-**CAz?cVPLq|GwnlY|yXVo#G*c>=er7}g-2KkfsM=B#1J}=bQET;IolK+(>)<0xle|-k>|GMmbFxN02L_8I|ZO&1Ax(J08(3203&9YC7P<$jNSYLB_qg?>{9lk${ejr{NF28oxp#uJVNwHAMzKSDggwYDXjT6BY7oyY!xgOz_F*%S`clbao4}V8j#uN5)cV~m^(JvlT2QaRTcUcc=?(;xOvRj>;XZ0`MQ`cqd^CJiHm2ayX`y&7I(GD%9pNMr(z>YyVH{`j$xy?bXBoB@*Ub*eda?1JO%ePVo-SR=oOz3bxJK|zR2|hE2^1v)h4@+WnG$l3x(^m1Qj-%IhE8aS9R=|BOLDL?1#v_d`bl4Cmgu{j%LCEpy@Vc#zboM~G`5b&N|<%mWow>E}zeP|w)5damU(c}KV|&pQ`daBF3FaUX{MYr%G|GaeVY%A(Y2F)Q0lKFURXYbP-mykR^12$KGx?${awu*aO>hym`=*dt20maxU4=9I<>}$oj53JE~&4rY8S0X-qL_Ef!_<&5_P_Ta531+R-@-ISobmU)ZK`=be}3*WKg8LE_vQ^I&>`!HnFU;TkJu64u0Q_ODJ{hwYS8r$0YOMhN$S!Wy(I7TXnn9{A)zMNOZq_vl($Qp+}9}nKX#<6g048AWrs+KE9Rp&s=Y7)K~8lmwsy)V#1u@=0UytsM97E=ekd7VFUMG*bNKH9K*vp83H~ITnKo*CwiDt2W7Kn+khD>8#YIO`|xDV|DFR1mGI!?B_%!cjfj)$$we7C;B#c{qOBVcf0c3ZypmHce3|`h&%0HKzcIU%@NNA6^Hcj5Z`AeFQ|Wuxodfr$bTuue%*T1x@#p+$u{^kSN%(sJWj@aLi`%V|=jKD-CHV?we)D}cW3A?_zkny=p9_O+&|v^38&&w;_LuB(z|=-+OnKRmxCJ{MvS-nezT1>>5pvZSEAfLK?$*ro_`Fs`RQ;dX5q`S3-{-S7Yjgq(`5Ti8~%^JYAygrmA&hiDsy8`E$lk{8zW%sjGT84u9XKr+-G#Grs&4_z-JR3wDQ6E_kfSyX8c~JDeoH}o>Ty&Kk-G%{tr2ywa>BOpMJ(d)K{B=7H(0?DF9*jPz3`@U#I$-vt@6-6oBH{R|ZEZ`7v_2!L3BaLNNB>o-L-FTUlLrHT|MRA&~RHMJ7ym#^&YIdEu-l~>PEyx++ETS&|W5Py<*TM7B^`Rb%GJueS(8FSx=QT#=x?4Dk<8j51F!X2YgB@!!Pn#XE3jn;z!P(z_Ez?Nke4`@-9qJ>`g#{pT4)Tu{$8(BBb=`fA5=7m;xykC4w9u?CEbSf(`YB-W*GI;X{MqxjFy+cD?Fd67IgbZy3~COyiWLHqrEqZ0{zxMKG!>*dI^D6uX0+|zt;S=6(;X&CXf&mZ^{=oaw%F(v58b9gLezFJrTw1`;^Z`Z`UAEdKPH}ydQtZKez>P+#Kx@_w-a$uwYEC``6MCpUG2wGq1*HKQhh7?}ePhs_v4_-yiN=OgUd>3x4bR&4cQ(Ev$jv$g}HP&TCV{Td}57mcxttQqH+fF5W-KXpy)}9G3>(7U~w%?u%QsxGhH!2#kw-kWc)pPoqRfyNBOW1u5FMx8TxFxJbs1w3|8s-XB6#(grOb;>vwLvSGYw^}eT+eZo(VJ%R%E=74p5hvX!R4z%;X)?yTy3uN0Kn=+SKP{lAl^$hXcTWoSRCKGWJU3o*8}c0sq|a0Il~hMgMHR80dLXna_>K}@M~5LH_rs0{M+B3nxZFnks)vIpkCg*{ZstBJOHsFYZ`i!%8|laNzON(t45hxkE%mHNd>*JysMacffVkC*Km&7&eCX)86gx7CxbBr5=~IdOLHk2z(i&ydISZ1uj4#+wz&~eMOF8covsqib^?eq94)q3k)K|w_Gc~RsV!?8wMn}0}ynf4Md(;(vkxwVp)1L2h=%aADT~XE*uCgkeU-h=__nd)tZr<2b(7x`tl+U@vxA#r`xv?>q?`h#}6p=T}4V@^1dS|uCclWK=ubYTEC&cTnzXhR>gNT2ybs_F+*^q;=yLo(kiYnsoe3-2Vh;?PLkfgu~RlJTs<%QXoT5@4k&||NcixBUzEuL^GHV-UiUr(u}_%_@~yJ5I=O+JwOd9%e3*I2G5Ztqn9kKf$Osy-C?A1+eX($Fx!5CRSwI6IF={fA2%SACz6TL`W6NuJZvP@nJuOJtrey9P_X&_Di|iFv$6;7+n#$~BN{5{i&8!*e(C_dI#{+CM%vcK_zVPF+U>!^xIgia?`+JF|El=J&$o`lfyti~jllFPIY28(-$U$O?W6cS_{>k~zhgJlSg?yK{Qfnm&w+yg#HbU*q@NzEDm1@Adm~J^ehtTm#bA++{iPC+C`XtSjQzE8hKsdhB%Y)VX3Oi=gfMppm3W=Koy(_{}09FE1*Dx+V1K{7tqWih!(xbNhc(U3ol}UDr+#kra_oM3iPj#$=_W3}wtv38g3vqJ$_y=FIbO%wy#YBB>}tp->2w3{jCXWJsm&+^6@k&iDTDyuWAt?&sL|b??2_wfA1@S_Mq!cy#)dzq|;%RrPZgvmj5F+D>CBZ7+h0E352uE$^(;xRsQ>g~SWr)rs;+;IFZV7~)Grn;uEO_v>hZBHDys-o)Tjes_K;!ziO=l@oj9)u{WzCH6nN+P^TcMRbD_dokAkcc3Y@qs@bF9!{JI05gihLB-HGdEUHi4<50*s`BtN=jsXUH{I|Qak`%B~uUa_%0mtt(D7q&ikOJSUF%C^7(_kE{SAhQh-}!Knko6!@KgB=>7P+QWQ2RKqt?A?>Y>kPfpxRbWl0lNA+SEQ~*~$Be1(^NO#2#nXi#O>C?(ar_H6ueCDfr1PAoS6z2C<2aXp=5v*@D1xgrrQ;k-Je;UEjAEtlPaD{_-1Wrq997IJ?+hiwDXskP4ubf1LpW+GS>{n-v_nNnDF*Ed^bhQRlmgUY+V;R%vADRU*axFbbMWsHeJBnU(s?hx!h$2__&X0YtqT9%DgvGQeGgCdpuPEvtKv>6GLhD7T)Q867ol$)oJMB!$9bQGc5acTSKHYs5WS@BuQgNsW6s@AXKId6AbwfbYUAa|e|DWb)%=}4A2!|FuXz}l?jJ9>v{8B~kkEMl?F*)UI<_D9D^rE@LGVT0Buh2^J~?OAtc718d{_0WoxRA^Pse)e@-VkM(5uECqxuEyeq!vB73@V&Q=t+%rGos5$nRN7-_H{KLct01ym5;%V3XxdmqV3&8I13zer!@SKX!i&(VzHXI%b^2s(t`>&(z3BEn_eGrScvi2pkueiSV%Z9Z@u%PkbO($Qp6FfGzw1~mq9t0py6aU*F)+t8@70OusHm3g0Y1%JVk0j97i`vom_HJkwuQZnXJ4S})PZ`1Bi1sDEjcvs{DIlV5EcE;Y+708Tl;o_*K;#`5y9dnK<@pwWDifeUqwcn(q3O^$yZ5ciKpqMOu5Z43L~i{stu0+Y0-XY#0!JnG>X(1pA!|6XFZ3kMAx8z}1>Cy}4nkj@;7v!KDPr&hDtT^I+0-tR0}pGt#+{j?lfBE}K*psan9oix~!eU)QS5&22WKAnE$#l>JRwEV@>M2s)|!PUW4qH!p{{_Ape!XoAq4LbH6Wh)W7w-JQWh_x&2OuVjOo*&DS`UMFsZVs}6l`#XgLiEw11D$wq^IE{lCly?Bo2w#xCD#UUCbr}KU!BA6vKM?M{OSHMe0SB0FN4U3cX_#tc_mQcnqFJ3mIU$>vwn^K$3OqahlNlFjL4sSu#W}{m)L!oalrA{UD%QOK8OZ#?}swK$uRX>Tq+XF|C9!ekC^ig7eMTW%B;|4Xc$Qy^3NH08cjRHi!$K3~UUVV5{HrmTgh4Z5$DdSY+jh(E5F~6=;K_fart;rU7BeDOH?x6xbT(i7BfaA=6?NzvO8x0tGGs5X}&nszLCi7jSLG&B#&j*<9Nu?#W%&W|!!G+=jM-)yo<(aRwa^~-#uNRAv^eLwL1vQ%=?^GTX0gVF|dDIv7(Ea~H&G8~<(M~I-28@?CzH-+UtrJ~UmD}wSeX_10CBHlQcQzXG4gvhru#c0ukOU*B2ZLNHQc@j$M3!R^jj-!G6-_*{urEr_!E6^i#aGDxvO-(_FUg^`o3HD=Te6>3M9#M2i_}Zs$-3h+fpGyg{rHrEH(Z(PNE-cz84j8>ZXF<$uaS()5{DhTBtziro66V%A@o7{zp=X288Y%*DmA6=ofm&&m2zL)0Ph&>!-+Nj`Fg)_+#AYTPSEB!P*jh5wZ_*&!3gYi5H|;)K+d}vACdnb`N6i>Y7F&KN-~fo_LX#BA;14ydjfgfDF@r9iLofIyc)Z)%}L!Bz?dCW7%|&Gun;TtPY56qOXgets=RRXeSa$4Wy|+=-+(INBifgKZ$&osPJ1ULBhQp?FN4Nac=beAkj}@MIG7~yKD*ms#pLFeTeY?um2!Iz6~|V-yD#)u)N!3`Hs#TdnlZVl~%}?2>-%oMuz)FDrS$F`Y)#z+-`5|Cxcy4-gp>O-@qJdWaa+D^!+mL{ceZzXrHuxXh3~LVbpUO*`YltN9Cg@FBOy?Tc_JwqMa{k2JTr<8M@hpMrePj#BES~kizH}W69??XD9TLwl1cETG=vz*0`WKdt$+Wa$O-6Zdd-w-{FSmKZ1+SDj!pzL3onxyTHE~#}8kz-0&!$28n7-oJUMBPu?VORmd^!VpwJ}Ew{rB`AK=b=2c;gkoT>j#Zq|L4eH8EzUBWv*3*SrW?Yp=-E-E80rS~zu7op>(N2W6L9|CVg&i%g6k}{uhRT_*q-0ITj#W?}+wl{Ai@=uhzcT`_dlq~!wQ$$N>!jna7kORWFy`BX@08agN|hv!=F${h_!^zTd5I}gpr??ULj)hp6~(7iquioDUkynir}{(a@Ae^nQ@;&;i*JOIBI6~pgd!|0lK$h!zVt{Br|s1#B2+OV{p<|bdyz%kg2(haZG$8WY^eb`v?TLaBP8!9K11C?JN8>m(wJ!d2@-7CVAIKC_9u%uZnfI>JVi=hU>Nw5RC;Hs`7e)sC#c<@1wVa?Y#@X7D_C_1J--u4)bI%>X^|D39{Pe0P6d>xcc6`NowS9ESh_MqD%oUvWaRwv)jC*$$8W4J%?>`}LB=+aiPBbX7e0^hn50kFQE5X~fbe>NSZ~CiCaGVP}R~ZJcE(S|)Bhl^)O!ci>f&#W%7BlK7k1az!z^3r2yEU>HcC~oSn_=n`Jx_S)8cHSoyYHCTcYG!Cg!MmWB1`=<7OcdAPMCQ@_QKxQK_?F4SV!elUZx?joBisOHCn#a9$83po|s|uZG!|}X(_-@^T778@PuCO}w3+?%vI3Ki}r2^Z{6?;UUGW9KzU7hvn3zgBADxRs2Hii40*Vq9X<9>wl9qn}im-z+K>3mo@#-*A`muxukSHba5G#K9GmLtw|A3FBBRB?rPF*G+so{<$mo^zxyw{n|tF{DeY{?TXRU0;7)2rIo(1XCANMYc=e-@SZrwZM!Q8HoJQ@7(zNP2a+7mK#x^OG&z+?+My(f6&#v_LIKeZMPr&z@+1PEVf78@fsC4%N}MbSD?MnQDGJLFctEzyQh2-V#?Q|kF#8h21@*S+oWun`WQNhj@d-gKu^zG(V0o_>tYY=(|An-)n9ct)-v_w`Dwdt?^4cUhTh291;~pw6nt?rw7Clt4~n+;G5vm^$&GE1jYSZ0e69OhPJCW((+Iy8l?;P-zIu0fpqoN`a&E^^13un^x3VLfdO{Ky8K0Qw(COwMz$2}GZ=iY`rekSGQ<4k=Lt@@k1*^2(@uD?Kj#j4hF&+B&)xMxDjiP_K|#zf%}_H4pcrouOBJj0#@SyMr9|Ay33)xMj7nBVJE52AZAklfkEw{ilNi41n>fuH8eScE(f{t)oPE&3JykpOIyCV}_-Lsa&Hav}$d%%EB7wj$FI3I_qwbu&>_&ThZ)+I1{CIpMC`AXqJD@A{mb$h+V@?hkvTCKskExzGL1CYyF^-Pl|I`o*(d!QVgfF=glD2#8>(&&2PS=Ipl=Ld||{iUy+ZO;V`yoL%T?5-CI`7Ni^8lfJ|_&DpgIEMBGc#Q~uwH#vN9&c5T(!!sjB32@%?>7J+VXfIi;q_Z+S5o`lq$_A}RJC)2kzRAcQh`uyCpZv!gyVd*0L|@&#dX3SSJWCPpg-u=OTj$)r353psldb>U^8so31{4cBzYm87D+Maud>BRX$Fz-RyHsI-3Q-1B}Sha0!Kg##n+<{a|#GwZZ9cqx$}+-5A0wIN{cc`@#shLD(OXcl8TxW??}-1AdWNqnlxv0&Xdb2;sZfJ85jHf5QjbKO_U{80dQvNz~%4NO!{wT`hv^(Lt$wQIqjDl-unj@^?c!%42O{?Z4Sj@xbLukQug1NV>blC&3AP@|yd7;DJN6x_dfKMxUi-xdR^if3!~yW+fB6hI5P<{b-)=Va6s|Kj=iV1#3E%iTE0BE8j7F+kjidzY2wUX1g-`=iL)^MCNYT*B?g(Ep6gK^y`t5)P+%212HRSEODS?sue*HEE@zdgG==`U^fsz|)o(mD~roPjTP~trxr;1w=ifCLlf{G*i)Aozbv7?!eH(Da41ZYVDCLLb1?t&wBaCw}_8?a`Ix&9dYnOF>R?#AL0{|a5v)MhZ~ToFYxFQQ~&Woqki}7_M1S|KPhJ*|9`kzH*o8nAn1v2S{v?%IN1037nkbX0_{bW`T3%_?`GO`svAYh{M>R$O4UkaQJvrTcXVbaoEsb%v&}R0h=3dJTP)a96V>;M+ViSK#L{a>T(O>5Wl!~{L95?@D_>M#%F{6B#Li%!}8D=cyO=eu!bPw^KRnR@?BA}aA$vsq~SQ?aHjRnq5wI6crNC$Y>P1R|MHi9zp3Iuuv{wmnDu#;3WD+aV0b9na>1GUA~0X4~$Jif~5VjRRA@%E9RGD_s{y!qvUv@?%#Khadsc+2S2h(ErWpYGyOyK-6oWFpmZ;G0Qi94e>moKY91c!Q(OT_|?x5kza@dp<`@r9t$2W8+Cl1Ar5+zjj!k3aE8otr;h!swZeI_V23@6xF0BOJ#e+S++^-dt9zI4sPp&G&R0K9(9Vl%as370?YS7`M|c;1`BOTUnnwOF%q#D`BmD)h^@w}5TLR7v@JM|{K__%hsu5-0zQ^W_isOe{7TvSiJg>wG>n^!ksqA6JZI<4_#{wvCl=hNYTa8okarQh;zv$A$US*`W2rduF4CWU%j^#(!u0IIVSX>)=DFAYLJav8kvAi;EDE|O;;AX7h?~M{2l6kK7>IaT@vLAS@&xhPHaS*-IDlW_;=Cu2UlI47Ysm3H!ZQ9V&MUOnOa{&p0H2xNxGp>Jfys;oKcTP++K!!Srp`y0FOOZDV>@hIA@R3Zt6-r{e7pN4V(s?C-5|J`?G>b$lCVZaqaXTd_8{r<#Zb4GerSpld_K?Y6fxG01L`rCvg6%|Plcs*3V$yA@_OMwrq`gV4a#2EFLG%%q$c_P`ulUI{#DQo>Dc%vwsORcbz&r*)g2%F{q~Ybe}8Eby!&xV-SG7BIlFe_58k0B60A`dzJJc>#GHL&ps6{RRT@<6RJqizg5&4zU7(tB%9oMnz}|&%E!E_t_QvzKU`0zw!}D$4b9Uk$uDmW1l5GXj1l=(1XUc6GyC@tBPqtY-H<7{f6K};#1DU3H$d$J_`C-U)&c5bO(nBN8B$(WLd)prq>XFZpr+rX-G}$sq0x_E#zI?`LC-TPS4&40LPjeTZKTvomo7#Wgf)fij^nLJ0e@^rxf0_{qr~NnlHvfP;p|bDogUjR?@S;eYDy>7FAQrzQIb~NoLr)`K81W?X|22*$GWzK>`yn3~PHsMAE1L`|VvBxF?nj&#k_^gx9;N_aO4CrI0iJh#>OJpH;UK~De)UXsU*uz6&HXQ=6G^bs?WxDwhxlDoLukfb#Q}`GK`tMrI#8lcAvEk?|FT@`D!`Kw`4r`TQSCQ&S#MBKR+j>_MS$bkn`!inSOQ>T)47p&tMAjgxne(#YO8<7Cm7ysO)Y%ZhW?>LGQVVUZ#eWBZ0K=i@&iAF9_*3iivl{_KRz7BxWFS-U27T?155b(e&0Tdae+9`ou$QrFz=Mv43mBf(YM+$HUUWINEKW*7$2$Yyk1DFCc)Ha?x|%y$RDB(tc}YrNCwey7Ow-Dh+FY{)(Vc<`4zvVc@NU&t5i#LgQ&KHK`-$KZAbHthvk+0oOG>|BM)5JgtgZtyk?C1w{SF>=WcyD@bRz>lDR6t?j!OQWDOS4(cb_OIh@NpWvM(RxdFwB%156+_z1D(r0Q%xpfhrgtakIL&J$cl5bhhI*a%)?whrfp}$G|t!qE-YvfOP)X8|IKyy^GXHzfEtBVGk#f73%8U0)3_aJV${p@#SW5d8ub994IDpP+<*Jn}cZzJGdSrYGs-Aw(;ckMadITZz)+Af5v-a#D1S~NLL=)5RWq^LmoGR6xD+n~&|cjCZdVX4@e5S%B(z2lp`3Gifj|Etn3I8WM-i)XDYNrc*#qaAG55TC}1XZ4*d$&kKiIaz5h;Pt>syrf0~<37g{<7sXCqOB}0(ZIDK-?Mca;_ycIQO9N3Sm;ncxFGun;vlh1sM7Cw9LUl)kV*4!y_}x;dfgooKp?H1vrY%+$+pfu-{sMXK=uoICsBvc&VV6eaaQ_IViC?dR=calv=FY;-ZiE5cNT!-6@Q|iq1Odf5P3%%EmJzK-oj>SV4XI-17oCW9u`oPw?PdRfYqJjUp>3l~fewF(%sa@_`EO4xHUKG0)aUgW?XGY_I@P9^|kXJ~GN%h#!`JRwbQO$D)#DVaKY+i{#vkB-9woIQQ0Dh&X5sgsaC1#{+Nqnvj{5h{MwPW0LZR5sg!1A%VdyiQNMY3LNsJ&4gq}c;UI63XbN^T5S43E*($~Y9{&lU7%#okGs=W%Nm>9-=u1GfWqLsD#Cig8#fCU;uJ@sp>=IpOC@=`=vlNkDzQC@hCM8q92fmD#uxI%N}z~@JOEU%Thkf0>7J5eeL?Yt|l@6Fqh24xw4`#VkX?+WwTY-#RI1FcZ!g*6g3b9RBQe(`VT)Bo|YF|e+hQf;cWVmcyUe|%AGfK*z}T+FlO~_={A6q9)7`lq@j&Q9Q{C`fi|C)dOq$LcOU2RKMM+h$>k*3(L*{iP*XMrpqtM@@9Fpc8%zVr%t6rnRVERzQ13q8Kvo{x4R`@C}g$}~ow>m7ISy9Dzc8~&_x3!YhipKaGge@N8NOzw(=S{*tfPUzo$C@84%o{9mYPuC9x^z%eNIA_s#Sh+*@m)``&yX4mS?!o8&cb>K$c|!18yLsR3lOg%qgRdpyh}-FjR+BW5REECvK5^t%j6NT9zO<(3qFs2p-`sdaZ}8{L43VJvQt-wlr*VGz4XA`%bxnh&=KPozE5!NrvWgdDBVk}|^vS?04E;lQXF$XS)+k7NyvR2<9Q`4Yf1p+s1Mk-^^om}E`%RvNqf>q|@o}^z0DL7tp3a9O$tC>YTrZQTtHv%Yi+dG%4|eDuj$O24N!;xB9DoS3;ky!?+MnHS5Yu#SuAV7f$_9s&8&5SVl3la;;lRSL)|m4+h>o(L&Hewxgt}XC!;)v-S%iF0*{x3S6d*)N21?M*`K6;ecL&3{`7184s5-a0&3$I+mo62XP9?R7*|^=YL9r3ZFTuZs^MS_mvhwo*Xc)R6w59b;7G|<)%KP&M7*W>x6xB1`OM1t3m-e(d_^(;NsorNhze>1w&6X`S9!|^lovq%4{A!2K=xdH+i7?^yF_~{4&Xe9dmYSEpCczpN*3cgr7$1pn;b!zdp0ESYKk4rFQD0OlT>ZxS>->D2Kb>LMPR=__0v_pw`)Ff`PyC3^ALF+qMxG&s1?`OgbB+RMP3bjpNf=L0`*>!Do``{0p~9Y8GKj;*CwhA)w#R`S-GNFm<#`fv6MMhJGxBZJG7$%&9>2zw9#7dX|DK{D4h%j#l=QDooCSHsvtt%5E($4dSuR8LtQXD`25+`a1xB2d!F5EZX+vWwB;edynU}f<=g-y;GewW?{nO7pvHZ7;VMFX+T6^%|udkJMvtUxR%xcqp0RT*($@EA%Q5a%LW=ONFWm)lztqLctPer`N*;3eWfv-9oruFk8rPuvcoL)UwzMevjmo+-&3n=*aEVR`+aeK%gr>D*R!D`y{MZl5+i{){;iYK}38szuvV?y!onPI0wEuW43AP$M+}_=XI21_vmx=C*VcakC+akY8IzVY2$J^^V&_8cY3W!(@sQO<*9IS{Bygn87(f_k8+{mxy(Km9AOGwZaPVPMN3~?azN}hO2ZJDcR60Fm^k?zWk_jI~{%JWJ;rhv4&j`A^+!-zwdl5}}EeZCog_^By~c8#N%`Y9f1z^A$I{mVGC%Q_Z_323B4c$=WJMk3}@5$7fy1L+{qAH%6$1Q859K-4K5=_Z!qo?`NknWaX|D-KWc_?d__uZpk75H7+*Z_HLcKX&Q9#VLXW4w%DRBdt*h{yioV@xs!tY#=HK#;l*v)aZt1>xV=^e<5~>ohWya@MBw#*Gr@HT`4u0XcwXj9VbqDZY{a+^kH3GQEh7P;gKl-*d(KXrU)&odLEH0{fvQ^(XWy4+z6#w4oD4_8HrG#O;(1GzWNmVKM=C={TF3@*n_~O%M6;3vs=Z;{A8+8fA5s6jp3awSFP=ViWftdQw_PoF&Wd#KT9~MEkcN0RTxC~xOizbROHO&3Fy&vpp1fNqUla+pv(1XntXJYS@p`fw#&{sv|SBq*Yv-t8-;flvV;oUpP6NtL$>J$?E+`5$Yvn}$3<;RBChw7z4+T>x?QCGx`=v&hR@)Gq3dY-awfr$gesx82Ou$NgE$a};nv#S$EFhC`!ln%FM|+=RrL=BtuvC~wcSOTnnQ?#slzi{N`BhJX>dbjMKg@46HTAuN>xF2CE_j9n#J(Yc$)7B~WY!blv=2V|Zj4tE~7=GUJj!K7>O7_OIYb>cp*!sebK%yY{2*G$8ss%LM%YJhXXI@sOQZCAMuY->ga9mhO;bd=kK|D}+t*3%)P04p)6k1fp;JzH^M_$)b29!oJrc#W07hHpfDC($>kE%F^1z{N9kMieM>+ec|*EhH1ekUWpdgCjaq(xtkMBdTI2|TAVQj5R#+dU0xGK`<_&Ek0!`CPfGie)-@T!|6O2tt0fWSL^lphyO6eknLm<$ye@{L<`j=c5eZSu!bA6N5Y|d&!vFmHnBpL_5y@!Jy-uooDY?zM^V+{QdnaxLyMN8}Ye=`(hzgbT7x<<>=4Z-T8LQnk6#&Q3@(xykn<1vprBvfr;ahzx}llw*zt864Z=HAeMA+)fqnI1AL=xKaUxwfkdk5j@Cnn=kCH;4yP^Yz^~M?@a0eBQRQo21}^=S4ppv7UiOuE-xtRF;2w`(23+T&*eXvTkK*J>I4a7M3DZFx5v{IxKTG8CrwE+xA^Osqu{Zf{O>4`Yh1$B|Ua0fvlQ!fMOf^Jv(uSD{fIK@cj1vlIR!c{|SF?txJNV2NwCeiZS6s-{+=mN&|l7J@1ZqAivsT6xn_IJDorLEL;3x6V5Bg0aGWt_;hG_Grm1Y5pg@e!O;5S<_!4!^YvbnP{fVsZ=qV00VQ9T{%sONe)ZSQm#uat7UnNW(@riz|LKz$ykY!$0x0%a#%tX{960YAHj2MUf=ofNW*>2;dfsxSQQ!9|;KZ}&!_XhxcVAn6X+X-11Wu%zoqp>PAIFbg&urGE!JSRb<|mU7pDL?aPOtZA@M>Pye0y!gCwvKyb*5)J@CxudZrF(Yfyd?)=flMr5N~^MzN!t*tGc{o>-j+$ARtI7GbzITPG6!kN?{kqFgyhKDV+(&y~%Y1fClpV8;-isE0bOmz*!e08V$rI`A?pOV}W2Nm+o$z88f!FPDw@vFLs!)%iG?-qLe?P3398P!+9^(>hnxG)j5~_^3K+!gTV5Iwx?Zio^0Q6f$~Br1C}>-%%>bhe26}CcSjT9#tIKM86G^p(m8yjFT*|=Jn4ksem#EotBVgMZFrdiy82H`+S8f(P|OPqUq#=)f975CFiR5o)y>=|snSIxFuPOo;^Pj)p*d`HJ@@W35ZZoBlE({iFseHv8Abnl4IJlrWJj2IrdE%e@qhP}m;b||N!>bl-*Rud-?lQhH&odb`~RMg+VH>kSr{|-JZ%Thw=EvAu;t=G)2W6FbI%j^8sz6muu(9&Ws!m1oSn#*4!A;s?9%+Ns+%zn>d$-C)2t%t485rvSMgj+Zu_DxVjU5BxfjeV=j@+;<&Dm`X2QwogNph)kdNK22y3l2&4Tq_FO;vaqkXr?P;VDcHW0k2&;sq;J#n_z^0R@YPfQfF8@(vZ+P5W#!JjKD@$cSvUv##zAP&xDI)wk&g*<`ikLh_R89u&~dRMRKJ!gNHT>REAgapO1J+U*JG43}}%_qL_rbF(n3eiV)ct5yoo{0M)`Z{9Nuax5X)uxt&0e+)Q_$E;zm0XSISLcsYB}_JCfoH*`UdjRFU4J&SOtW`oL4IP;?=OgNI>LGG@rqEN9f>q3Z}#L(gM@bD8$Wp)kV1m^$bv~IdCQKB=P~GOvYn-CWxknCC5?_&r&Dr%v=BI9GT(yl}F5{N^UCsyGs|%tJ#UXYm2kwe2@LvKAR;(fMnN0USCU5mdBt_F0^`~-O==UD>57r9oN@w&l`qGR3U+Dnnc#28}6j!X~`=XBc@Z4W{&W<+|LNC7?`BjblN-jv>A-W+GCN(t*eFgV_m%;=jVev`?6-hT7r`gS@mdJy|7ii9|{U*~Y#Y>@_I-{rPkU5oL;dx1sSlcVWC%3-;Yxd`{0G&S46*=a^q|m_;SR6a}na!XMD!GZ7>A}S>=~46vg;bPT^Yk_ZA5Vyjr+$q(f^JKfVEJ2|1=qaJZkOEgK9)60Mqc9&DPhY^P!>ZJ>?FcV~ks`V`oV%#M9PiYipGWsw4`HcINwY2^t2|Kf(f~w|r;|}6O@L=1DEO2!yJyej4_z=9XQa+o}|9WK};?woFc9BF&Dm;%+j=8miDX-gdX?S1{39@9XMSQA|R}gvfb+u_gl&w#iGM(EDZ^&$+@6(C;#atPTr#j(RC6&xGprK@EVXZF4Q=(2Ph%J**M`oOcb(HjQEILHWgx|qj>=z}`pAh-Uw>M^ih-RD6;2S&#wkaPlIh&gWioxF9UQFj#5#q9iWrEqz`0%FAY)-`7^ClUl3-%l&!NTKv(qVo2-1Dk^zj|dirh%}IneeYJ{O$?y@$u%)#d5>*kPvNSEI54d0h1?xt?MLmHe;J8^NWm`MkQTVKdfDjkUHTaFmSL3Ngkm8CVEQKzFNf;eoIbBJoal)<<+R8>bDdbsV4?YJ`GpxUc$g*cVUe5>5jED$`*aZxN2aUk+cR(oYZz@9YQht}vj#rELPHB&@)&(dytkpfkuO@XWVN3S^&iPO7sn^f7~H^C~;k58n{o4HobX^acZ*Rf_Tv$ARLRq5ZyK!DV=&rDtV7Ee?KX&vVK9-sfOUf<21>Z&(DMCB+gB!@AW9r$>*q51xTV!&zL30ajwq{i9(2xgfJ~-5_MGRzCDmPdP$4<*uW=LdD1pkqhvvKGgF@u_d&>Gu_tZDHdDi{SXY?_QTZH_o=3TMR)r$qN{kxK;)|fZq?BP5(b1nlC4{>_!IDvk0TEr|g?pr1heJ~a!pg&aH-gNbjQa1Q^Dg=A$qTeIVJ;DrgpeTGT$GYQ)Pv_rxXCyUpL8pJ1qofh>d0C^~z{isZx3b-2MSmktVCaH9%7e7B`_sQ_@f@aoe0%+{aXyqSEl}_6N8E_=np1D`!G;i6)z^Q{AOj&Yh%=4DjsVrwpKVV@f5^yNGR}dRquWZQVsV}f6$-S=ZO?_TGU2Zr-eY_u_Sdf`b0Jpwr~s7-A1y7+(%0uQ`usXa;XEPI9!$D(VeEy1q5=!z!|tjU=i{9R8LWSNEz_9z1GOmU#gcpoPD`>|aUSs@@(Y^-^Z(^FS>gS1MoK^a*hw@LcdM51j16hp(m~ziJw7?%i=J9}d4R?_>2ud}dp&e35F&hu3;GOWUs?zan&V{Hih;db8(WA+I3%0bMN4f~#CZH4^cN1A`AmW<&J%l>rr_n15JdQGDj~(Huq|OY#@Qfyf(F;s58K1^AFx5Z}YQG#BI!>^5F=9@h)e25^mT9#{}Us1u08YyWtU)s1-|zqJ13w=|q5L>|~(&3qvG((pMVzgnbl=NkLneE9hG!9q1l^fQ#im4D3sWJ0ssw5)l2I{sb0mXVNlIu9pr+f&1IFZ^8frmRn9Hk?X1Vx)f*acD^xSas7X2j08(DsxpZ>9j~*K6{WW7dlmx+UrLV2S)#)?A(9)S_X)N&VX50zg!+e7k&Lp#DSQ%%P4se5_^t!!6oEZzQr<^Z6xzyy1Q8CtqS@RBJc5MP(Bdp6f9!MuMSI^iOAkB0yCj$1O89=zC=IkPh&-l`5<^KeeQYP*>%^(WyoM0Jg%r*i#W{R8>?7wiOi^j=v(#w`KLey8HjZ(YmWHPXQg`aQVNXZ)aWSApzeBKu=RnWlN2E9Z4mmk6!|BSXGyE3Fz#ntd(m%PcW}93W!>r}G0!iM{HSoO@y#aFKEz?3N<-`|78>}ZDqX*`0&!R#&3)#;`yvRu!==7{4E09tpZ$D>O!(#ijwKyzY%<6Q{oxLFX#N#aFmdpK!xRZME;RWVpb&k$+Pm>MQR2>N|hdiwtkh>i>#XMLY31W;@7?ed3P$h{M|ZzimGHI1DN`@OtcIhn$oVJHb;oSX1D;C|9#6T?lLF(;ch*b(Wzw-6eWmy01Qm$yW~qsNw>>_skc^|x&ll=5Qnydw{2~03Ifcf^ZwWNQ`EyYG$>Sp~#h_{XG=Z`Z=TA|8^w6UDWH=mix1Mwc^&w;Xhh+Wr$w26^zSxTPyI;L44f4p)aaZ;I{?CXHyXN@34NEADeuA$e(O#?FK&`n>fimAad*U{uoj7kdWc#NxTu1&7AG*K#)obXRL}lc~*{)#H3tbj`V@jI_)47i=?ai2U)ag9o25&L!9m+jD$kb1e@UwA0ih;;?^V^B@r{mjd(kFH@SZaw-78RiWq*swqp_@4wB)lCjeDOiM{mQ(lefQ`%WU!P!JcRZeH|;-c6QclkmuY|9DzvxO`5ZfxKmnp(vFRJct#;`=5tnsTxUlQqCPh!Qd$aiP1k_XE9eul*uo&%c&kyhE2&BQs2`j@Bu8144+(Ye(8Syu=3~`INy(K5f?jD?c*8&Te`ct23GlV;f$Z%${${P7G)X7w)Z@k)$l3|Q<&%uiy(atj2oOkUZ8S?B3{|q;weMx7*Es0GO_}zVV(ElFV#s5rR`bb}=1P|XIiT3`4`SD+X3RgXD>#RDCcB1cw>vt;bYW>`rD~fhvKfC!M4cLO7#y@_7c;+f*3~anp4Cekzyb^b!ouFar&+h>--<5CvhZ~)@=uWAq(Z4UDli{q6dYijWy~-A%zi)!ud-10IXx~O!@lF3R85aE&x63p{JJA9Ss6Wy_VF-j(QgN+z?I~%Al4M^eszyyp0d%vY~XfT%wDt)&GUaS^PcX1-e#t+lteqxkD1a{{7-lK6ZYSs)3h|UB_;p-fG66C{YBC|GVJpoV@tk;`kb2WBR@Dz$>7uWH1;P2?Gg`O$$Hb{j_OJgNuEx$i|wvmlCqip9cdTL*;ugOAJGr!0{wj_*B`m1A&q?oU3^}97Z^|(eZWf%@p+;z-POgkfB)`^&l9@hn}=xs;!ZT$r9|9<9?;h*QAe;P9e;=5tA^W3Amw{b4c9Gv{$xjFg-uEk=$%@3W85}@Osr)mJllrGxq_pkS8wxqB3)9H=ZvN0~$y}0$*zktlx&j!6h{&20_^mfx9G6cltI9=L;@#3ibi5>IJDPV89re9GT`RDQ1+H3spQ{bn!0B_hvjHgOJ1b7z^65$hSEnd;8AcqJq4axInlt@~b~OhVl7@MUd?!+FE)X{k(OSci_39BAC_6-o5n;;y@jADkg6ugD9W$3jxdYx!)(=^OFY|bX2#;);~oY)}4GPNNJ+a|IDg8Av|a&E7TnLN}mr#iw=IS-i!EHCQY9n3a7vyz4d!8lp+orWg4~HSg2r_;;P(`i8v7b1?F9$Lj4J)l=Hg~hw{61z6YkMu-oYJ%xEC;>H$i#vKE~`6Mfu%o0M36aTy(O=g@k{Fvk6P3i-8!|o^ip!+x9i09@^@$oK~x{|2{1$o7PW-IfRl)W+8^%7g&@lzmbhC-tjG4V{l3k@}X6nODW%*Bx%?FTtlIX_%L1%tPK2G3N}=jdxwm-&>+J3#m9|Iby5V5Yu?d7)bG%`*h;2*v7v*#?)61rF}b#ASrNwfQZ}7S)%;|z+p(-_*$K20`>Q-Ue;$}0TU*D4c0R8`QT=CR*zYHD*d+t;$;uFE@RXwf5r-|L(Qf(n?dG$$Dd7CQC*n*j;v@Na>koM)DtOc0@%aF@4@3guB{Cl>QE^?4ckFu@-{gHgLa|5ZFVe8!2$uJvBdnA5-6FW21<)lT>gM+P1H=6!FR4aMp1VKaJtfIoSWR)AvW;4X(YQ$Ej^C*1oDteGjEpDsyo?Ee1kfOJo`1c0JXx$EvA_k$(cB7_W(ZtZXqdBX6hX5AvM<}TC;o)lzbZ@rg-x4V4};)@Vh8Z71#|CNH}I;M|1MCQfB%$j($cs&i_VuAw}n?(51P5*T=-)X3vX)`ui0r6SOrkk4`Wx%;jE$e&|%I)mr?7A-&EF7J5b`zz8ILW(~(B{Lgg6TSSfhaf7FHakyDxSxK@fSl*4ssFUIcK6?uj1^%u-sVVur-LAM?_3n!kxpP$2l+AyA<(jW4~D6{7yl>l+2pVBJ*h6zpStw?MlO{_Gu5TMa_P7Om4D)lYi2`Y3*(LrD5Z|d6^U26NdmYm{z`tkJ+61Fzx8h`r;pSHEnCGpkf%Ain)JvIp@58Ok5@+?rTIECVWT@|A2~|zxwQoG9l-@w(iIfMuhe`g5r8=9KV|1c!`G5M;c|(H&ry4^C$gOe%cXaZR+k|@7Q&B3B{4w4Zuvuy7m@q<7S2NHvBU=|a}XCyayrv`m=Cqrj@~=84skLEswzVOK_@n6-gQNMYUBC8g_S(`CVT$H-5At^q#mqr6a_qn?(;_-Lkh(>JL2+-7{#OLpW(KL<`y>w2B)kqouZ3=%g&#ZjAxcJ&~P|edZ>t>Hho)XLtG;dBE|M;+&Xc!5BE{8PfVLc!Ju`kb5DrOhb@}8S-HTAf|rJ6<+V{LhZD=!cO2sE2$h7R``bkG4>?0+ydn(;gZD}{E)bbhb3*Rhc~2U=@7V>m*PVzyy%A<-yr!}nj-b)d*6=MKbXmYnd@1zd$&*yp8^s~uA8u+FzxSL-xlPPX3n81H`{s8)Nh3YTtvM_@>Ck;P{O&W)2ARVp0BfhbOZ&$d~Fuxpc-UY@rTn#B+rV{M4WlE>D0IxG;EO@Q!+LL<Cx^H?DEG`|?-u(BX4U!p$+Km21V9R#Sq?A444!ptdQe*m*JhzHH|s!)offYcc{G@=}?uWZVJIbd`e6&(RAp>IP29FYiV4XGT>mB38!r0YyYvc-WpDdD@b2LDM4?~VcuO4ZL^~EF~=ClL_*6}O8elJJ;UU}%pnlaWC95q*T_;CVp`j4N$`vwJ}KB^0HjSwFbT%_eSfQIPtgIDh=K>4i7DCl^&lNR>-b+<=3ELvnKAwcmF>fT+xqPXdz6qTWZF*KF_z;S7G>?jhMS|@e7u`e)pA()q&cfq-U4}M|BOY^RWW?HCQ&#=aTxBOk*+e{9)l?usC0V4KUvh{WR8-t9R+t+?zwsSJ?imW1G2|&Napzew6+sUrx911Ga``XL`kmbpEIj%PqI#_+LA1Imr`vyNQB!u#uG3TNk|+z21qqRfZ18Q%r0NPT*yedS}FegYu%kSV&Oa9#eGzY~He7aa6b;odl)uUaasPX2D%;~|sIdyaT_Q5yIr+k)X^V6@yESC=_IfRm`OaMl;Q{X$Vc)aOzfhi;HZNjtUuNOgxS*#6w~;Ts9oVW@8N~->yXHk63vqq-j(~3lw*)X|>6rVqDYyF8-#f8**QQn;*r+p1LNW3^zu_x`>Nq=>JeRlM5Le&y!$I~I1)C;rb#Q1wJZXiI)=p0Egv>vwJwXilOyG!vza&o4z`k6z?a>g#r?=iW%bvhM?TGsd+lC`fDfuLQDrKPG&X57!BKR-AriAXhEOg2w7;ch6d|;>PCAV9AVV#au{r~Q#YC(EQVDrAW0#F(|w>16^;$*(bh-#iNUQ?}({3_q6R=#W&1**onPm|3NZ+hN%hB-q)WtDWy+1-efJc=g+X;6!H(6P9NxKsW@F%8bnZA&UXeCHkFq^|O`8Uv)SaILh+9On-{J1gEW!Z}>8jB&0_cShZd)*GCin=)YKFCWAwEUfdLeUlG!67`pgUqd|RdEu{7B?2IQ?ms+2oXm@T#p#_0H}&;j%|!f8#Ge_?+3!;a-@Ooyda%V~l8(+x3c8-XzhvPo(toDS=F8LJ|HZkKFpfj=G5lTs!xNDwRH~Hdj(tqSLyh*z`-9N`K>DgEsxv^^amh@@xMzHovzdD&1MX_74QgYMN0B~g6T29=8FwJw<`wcN^53s|v%tRaO&_C=asRg(WgR^$C?NjJu!VS@leqAPXbP^W`|sWK3gr;wrKokM*y(-OSy4j+Z9c52YA5nZT2K6Sqzwaab5_%XJQBA^xw|mWjdtcTVxI^DJ=Yne`Y`jE`%4uC}G;@S(=z{nD7*D2G_{t7m-dDX_2@Y7!$7=MCejEY-P63G*%c4MAMTWYsdy7D_nhQT+zWXSKGgPPH`+FK@2PsK6^LH;pjE5VVgO7uO=V!N$hUDVIubPh`PWlLKc|`+hqvJ6O`O*!&{YPw7aJcpUfrga1-M`q5soMEw4?Y0I^pX)u;u66ZM(aY4HI)}fre^SNK=zRJ5OHCZyk);@V2k59N?2#NxlF`AskF{J#fy$0Zf~3YeOW0Dmni)YV2gNt)}CtyuAE)3d%de=s0d%;en5tW+`tRl&WZTz#^}9P+LFt{t-8@4+!iCQJityiDT&`3XW^sVg!`Bg2T{&ekZR!AkAUsYN33%_U5Ls_qsB9?fcgH?tY}{>r{-1L`-llkoR_*^>^dF&%_SP~5zD%)<4Y*$N!$A3vB@p1Y)yv%5bYUIbKq#?e~!EC>3c5gnz?$?OR`L*g6*fSt2m-{y6BjO*A?Q-ZE#KL@s3sbWj5hv~J?v-%oF!vr*x1hgHIRE!8Ul{l7XhfXEg@3dQgy;O}*NAHzc3c!CN5N)~bosnz$Pdr?5Ar{@kpjO5j^{p$#D#ah^GT4%py1gPIittLIjGsGOM}rnhqy2i{}_q)m?m=i$VYr&bu{AJsus@(p2xuWdnf4`g^0hLG0@;hBLh;cE%Npwk&msKwqrs|IxFmVx_txU!a0L!{N6rzH*roPd2emG=S$`&Uj2$VYajWwY%c|ARvquJx}zQ>b79>cQ82|-F!7)}o^K@1lp{{VkFlQucUp_oDR4iNSJJ|Hf|)~6FA#gA^Ck^v_qSL&+(x}X`mNiEGoYPerd>ZA^(KiUPus>oa;w?GIm#7~8*T;zD8{*l9Z+Wk>JBwesk^S`{5VD!W6GnST|bee&azhbuU6zM}!KPxC%3^J*(b*ETq^qM*Xx~k|+oEOL*nU0~DA(Y3tDvnPasuuI$m>R}{PtkM!(WjrgK*mse+Vc3;uiK=Z0EB6TZokB7h6O+$BS=l4pHJj2EZ8ts0ZK6+tNSy2~(@)?`k=%}@b5%!a5)j=LUE{y)UEt7#ZKf&UmC(sWQI%}x58^;^hM{Hm6i$$Kfniu8&@e>P!7I^k+JcfMxgTxOAiQq$mYRuE_p~$aD{Aqe91vBp^PI_5z%KHQ7Cu7S0zCS3|sfk+{G3ej0Y(J6`_z7RraC?P3$_Xh@Z8dpUhP;^nTfXSZ);fXod}jzFGZ#4YrwWnlEJTJzCY@cklr0@s6CAbH|hKagj7Y@0EDyDlHL5AVM6y$N~d;I9gc4QlzIIlf?~>?!PbNAjpYaqsWi{J>3z{-Pc)SQ#)!f_uIWq#>sOagyisQiFR>CAYWxitx|5!_JK-cAxXGvuXZPh#McUyg00lhKuG?-c7oAweNHPY*@KB+m`|TuByF}qWu6lyLF%>3#Ofo^}9s!4}&L}M!ZO2p?dBnr|4|lKeFW^v(LKoLD-il8}|>%11vWYfIwFEkHi&`zDBuPkFC5ZVI7~$MAYN`Ee{S!$)ezL^;fekB6E#Rt!C`mJer0>@!MPKGDZAL(x()2IXg&=`(Ty*h$lVS5?ue62HEr}XQTBHKcF}_?C}8xOp=S3DY?i8EVp&*S*o+(*{?hOvJJ|O^bgVJ?41i9AI1tYP(C+G-p*3u?B5T@n#taS5GQ`Rl2`$BdEDQut%3Y%`hoVxx|=CDZOqS9-h@0yS|GpTnScVLx5*1Xi}>HJ7XJ2lF^uEGw{GX>PY{{Q{8Y()R1gjC-M(qIi6Oo_DDum_c8+ftT2&<#pkI#6Z}16c;6%m1C6Tcx=k@KG9dQ#`2z|Efs;@cX+7T;e$2PEFyh+Qt>8pr5|L{hh%i{~@aV+16{OZqs+20?E1Q0!@dE)YWC^s^%O^)NwWS&C*t0ME7uMe-B%h?O#&%T?(UPheoY!xvY9MfAjYMw{Dbo8T78Xh!U**g01eUbdSEqVj5%h%H|ha>7g!x7Ky4j$yZj{(x(TFeLWWfigO*XghjV|z1h>1xDD9ohU}EDRhuaXW7!;)`N8mgiLQh4oyn4alS31?t{f(i@c~T+*)qZ7Z!Yy9<8`>81dFpx4VNs@WJF0<5LxlIPpJsbqRp<53V?ZxWT{L^F^wZaPHd-9pq6ena^4c-6@#dzx~$q)rc2oi#c7)pAn0&#K+q0KR97J4P@TMmu$q_XLf%$&!d6NuWK5BJgUom#fkWZ4BQ$QeBN>y;*E0ucxRg!pgtxH_c(`m_jXx1Q<7g7G164=hlt-VU4QaGmJf>tjo-M_6nPh$^C@O>sQ{)*6nj2Ahy3c-!r61@ex@M#qK>5GXyiq83w8wgPoRO3mUzE+5}xy)&U6MG@Z-MMF{3vnn#h;P@8BF7NEy(JD(n{_{AUsa1xHG|?+cJ8OxRPk=|nUG;U^u7l4qiR-1%W_Pu>6)hI`$(q#1*C2c$2MBBzgXot=MENm!pE>27r9wgex}d|FTu9F08c1@kI(bQ~Y#QtC%eay{CIPio0D7+pcZwL$YG<|v@v-@y@iGi@5I!*9n)nV`O7B%1DM1<>$jM}vaqa+FW|$IAFTZr}2+UsIhl5Bbsudhhy`v;OL`q7!Y@Qn{>tj_YdL!_vf=<{&&oVibmuK&B649S4Aw?+IBC|Hbwb-|0(zERUjW^^$(d_I$&K!w1dvs+GzstsyOvaMPv?Isb^Nx$7htVPvZ(5k-Wk0fkVCxr@`F)^Vj9&D2F`1pTmakq=7sBCu@Zv-j&_IWhD1}k7?`}@=YE2(wIq`Oqxs>INR#1GjcV`t!AWV?ei=KNd1T5VwBqqnKAMyHY{j;J#eX80_8^D_rYx}oT;`O{NOn5pPXk0^v=ib>TfSw;}GZwwTJi}AlFCY8MQXpG4Vzca$t9|Pqq_vktO3*;+42p&vE14druXicX>bB?=sMXI4Mjje0p?kbl95W(tPCXqa?$1>)wBFL+y)(?I5^w~iCxlT+)T{=COMclR$V)-|Dg2G5t6m~6lR>BCpWL%e-gj^~&RP9GU&Y}DO?_*MSZyr~;mcv1LE+*J~BcON57b2UDYe-E8Od2SwcPrUgLA70MfHR!V>;u?uz(Vvf8Hied^L@RBZdaY?}i~h^UnO$$1l^6w>u@qOC%3-xlB$@{wN0K4_I}r$qM<;fhnnhMt2$5zTDB}_C#ENVyd5Bm@Q}5ck91j*@Zk)?DvTYbCmf&7h7$2eTZ`2c6?-k(LX+zu9Vh%um#sA-p;1!S&@`J)0u*e*GKZ#Rw92ReOsiseg3K>KToz6@u@QQUTK{Dn`%0F*6$|7jnAvj58FpWVaE8_kT%4{E_{4?rjv$sFUH+7>Op+bT=urs5K4Y~L9&Y1HJBDjy(xxuUZ^P#`~G`HP7$V*)u&OhsE;=^OV^M>g^5WgEm4cji23S@rK?0k`Yv(l0I|K@N!dH*n}@5;#2{NJuVVRw{!zJFe6o6HuevoKsX-L#g1&)(W48IFjz%BGs=ucSfTH1nvu2ye`z9^Sc>M+0ZJ(x+*}$GfP%k#J;${dE;Y@)!p>#VtELn1wBm*DSfIguIUAQP&o*u)NT9(C(FpUnp;~>X*$2GWWhD3h{`i2|M_o1#oE7`ts`Mh%-#>#V2yT&oRgr@k<-GFZFb!VDp#E5$BI0-hR|{t5qr|hoKUe9^{JT4fc~oKX+|6z>IelI@kd6w=HlZJ92U$a|PAdFWoXhb=9CT|SiQcVG8j_W4aq26C^rhC+K1`R~tn#7~t|8nDewt5r|q%Lsd2NAw>?6c~OA2iVEAvsC)C?DcCj$6xsunxEq`Syidv%jj4eCE7S+M0KfCusVWn96ecHzi<|YwQw~4}0vk*3S-(hgj>kA50R-qYK*p(Dnwux4yeTWF9g1HHU8&0I9f;f3k&Q;UB@w>g~pFDVO?5gZF3``#V(Od4KNMFZT=~(@82Bw;&O;0|9Jlw}ly5Zzb7V;Z4qux5B+(>*{b0l9_Z}O@O_fJdZf%hYd_)zdI@6&c0l#j5EG(iBuxee=)XWk#ykfD)D!QeShZ@+ayeXVw~X{GNl8lF6{IJa1YXBuV=X`i)=2IFFzJ5IGIA3@Hp>t>|2!EQ*Qg!<}yP2(fla#%pK?aEdxN4u%X2!PDH7`qJdjEz@~Rislv=bpXwCVP>-k#9=QC>^3ebKr=_57Ushv@X-1`m2<)>pSxYCfyZ@cNZuA+Gs?B^W*3{ybFk1$dj_`%?w+$oXS7Z;0abQTLG2rJ5pqtoeS>jajVly_T4aIN1+_#reH?Cex5FO&xq!we%NX7$`LWnusqw_2|Z3BMJ=*UjFKD41q?3zyT4G3bp*;g7<_ZS`#gJc-y!~o17LH#0sZb;m-z53&%X3+{utM!l?g7LXp3>jy^Nw(J4wjs~EWP373$Br2hlO@nMo*bIt+nWui}&uG78zXEmPlygNBI20ffzoUi>$aUSvnaz1)(WP0DPcH{{jPaYZgyc|;WqTv>K4XSf8)huC!yPAu>fR(NTLp+AbusoMLK74qRdMVLQ!Dn28B$4Nezk34TzmxFyBNne0B#sUz|LEUkrZ@m$>vG|P?Wc^-AH7`KDKLHeTmFCefzsBQz{V~-0R#9g>49?KPIZcwUMdG=6_R~MLb3EkI;LqzmAzvbSZem**$ZF*dj#7-@l@ImbaPKPv!&k@dYfC}CP13HGbNWcQA8b%QlfTNBx5)D0)|?e{2jw8&CgH5ibbjxAs~+T0pk8(@Odb_H#nlH>ZtK5h3A^ThRu>i=NG#`T&1z9ZrMGY2Xk4`)a-x;zVDZvt@+$X&;C@^Hy~K_)8xdxSagMewhH}M*Nc+`~J%-dxdg)ZvJQRHv>LIp4#&J1&eYc?TK!P3*fG*gUf@hxZg-V!}MPQAp1pDWM7fK*0wh&`1SgV4Brp=%;lV(fYa?1I9}beBi|PBSh>5m-`H{I(pdXd`}Ghfc3Hy{8iaOI5Aw#jmRlZ9<@i<4#m2Xro}=8z`*?xlSHd~2VYt3&cg^7@PZm0gBU*z*{B?_0fB%s@mD|r^KLRe@MtKr@HA}8HuPitny*dNdB^I5;3$RBa?zI&-Lz4G61weNFXzMaW@n9SLOGP9N@F2eN>0)v0ltY$&|&E!h2afshr*Ii;dh7VG0FCTtuML7%S|49mf*lks5$V{uk*7WVr)I5pfPrz7`$Z`zA^uI~soK!VERcSC`kIK7@6)fH73L?G8;I0>bOzWAso@Lf5>A_o>&d*)Y_U|KJ$MOledGX}yhHjF+&ufkhaQ6bEz9Nh2Gbz!`4(R-&Iezbf%rz{QTLMu(BP-vmLo5N*H`ncoT?f?!|9sLinE }(>s*5pD7fZ`r$r0gcjb^Ogbp}ELFD=MhfV_+Ru61GI<+V{8*StjBul(l&&82*Je`8VY&>hITNIZ16qW~to8~Ct%9P%!bk2_}+E$ok)(2j8^GUugo3k{do)-JJ?M?OI2ME*{rd-E0L@SLC4tkA41lLGOIeppZVi-nQeC-cTA&l<8l-@D24o$xr^ajs}t!b3z&U()Xa{#v>RS^2R2HIZs7>C+y=ijC(HRoYqCT$tUy}KitQ_yVJ8@oR>hJK=h5Eh3TEUdLMbh@RdO;!va{C5g0#Q2~a-5{%%9~|H06LCN_U*I2$_S^`9ox@1(A08fWh)SjHcEDl#X6$Zd22-CJL<8}%CbT_Vk$!=E(TijJY&d``SSpd84+vdSHUkA%88VhLq7RziuTqWb7+`&?c|&KAk^<tPXki~z_65p~^nq#I)a&2qHyZiUZ`+9S4L=x=mRVD=XD!Ne;kc4}j!`U>Us9*^yiuN{Z{0vMJ`kRz>5OtC&+p+#L2nKM^}_t!58Qk0&j~OAdC>>W+o>M=S*UI6KHnxXZ~Ct1Otl%nhw7T}n_X5Y|B{yY_?9sOSiR8CqH71rnY_1#<5EF5U)LVvp+4LJKlT^}{|4FLnYiDGRX?GTUgb{;BuhlV;ju4I7emH+d(BXt;I-tx_f$a6@4E|oL}_S{J}(Uiya#D0G4+^cueexRIVizK&3PT)gh^TOF~S%?!mDrA^IXwR}y$Vis0v0s`k_Yju|*7a!LM}y_>V>T^Wh!=LQ75mvi!_nb0;x6SQKA$~4{Ba}$f`?v@d_E#h;yVLou;4ywk#SrD;@uyPD_Zuj(Av5;FZ3_sIYv~(=|(9BN(EbI<+I;?LjKj7L5e6E$cpJAi>_H+0=CMEd?|YIGerdV>M+^?${j|B3VoJX$Ch%kitjdopjGj6^=R&PVO`cXK{W*&mksO%Hijwf)CcPHP09KeGAalplyca=*EdHKRdg_^c0h33#42iD?crI7Nfnol}=`MC$U$eAXGuCw0YT<_zdHY>RMujyxet{`$&tih(aGmvcPMAdl(^nz~j@i-r60BZgax%+KBNGhO%JO%}3rKfbtd0R1q3chB8oKAjJTHNXAvo_MGafAnd-S71IL`ddAXda(UqAMXE7yn0BW0ESt#7`!yZKH)>AO~0f%gNC0g5*22g#B+P~{8zsp9-!fp)V-R3T;v1cUpizOD!BKz=FeA2$HeCQY&+zm4g=bb^lpIG)`wXY`)$9vA~kZ(f0PwHZh3}?n{N8Yj+qdmg0wp&iPx#|hbMui73l<6oCr+_OxfOhAo4Ni03j@}yNOF`%f9AXIP;9b+4;BX(@r-Zb{vrBTRapQePIXrLfAYy+;B#`}nucltkT{IIBj(qwcXODKFpw7dTMkkGH~%eo4K3`q+$DCd?>d$3rPB%pH0&NXNjEeK^?sqg{LZK9jBxI)=10`~7v*m}(u`wZdDG|aS_PD6+_bXc66!4U$m}fUO+>jJesgidt@|we33R?#IvVBXZNB}=^zD2IvawIhuSGkBBX=wbcLgIQP9ec^}O=KAGOS@zKe>sK<$&5PFv58?B)$#z~0Op@b`?9F|~&^_WZ;@+FNU)0=}rI6ir?d0%rq%F|(Dsp{_`EYR=1o$5CS@xaVmMv^HkkUU4hHj%j-?$3+9ZR0~~v$pP>JtF+`UGy<}fdEd7aFy|PM7fn3wyj<|Jr%a?{23-W1mDx#xX>9_vnaTJXSZL4I`W^*w#v^QjqKg$-CvRCki3myel&C(Y~^v)fga(shG+`Qr><;>aj6|w859122wu-&^?`{P(3`HZR^C{IW~C`CK)K}Y80^gZhkzw}e#0zFp%hbAZN+!l{=u4ou~YUjdKNOBwVtN0P}`EWaJ*Oqe>$Y;rJG7#w(XFKY`q0UAMoZtWP6&LAO?Bny?Ic6CRP2PLi_G^gyW{(}E&e_EzKK52*&Ip;muyH1LZbR92Es?s6qhVvcI-fI;H*Wuw4ZCsuorU6*xfct&0`4j|J0h+>Wujt$5g!KSH~p8ac#&Ih?yTVw-v;`)@BPFkj!vm?%TjnEY7|8vRMaV^1+{%$?+?d@Z*Qh9!H$?>pR8qE7EVR@EPKla~E`uAbC4aG6s7MLLN1)+{O0$F9!1S7i5~*Af8`TKO!uZ1p}`Uf4c4lp=K~alQaP-%)#-=7#)=^vQfBOG9h%W4ps+MCRSYRC<;REzHxFqR~%6;u?pa{O8{oi}5(#uITDFx(samG(PXLBhCjQeuuf27-5{H%{{ztebmoC>J4K!J?lFoV2KsZ0eQGPM(JzHfAOQg=y%$AL9zPV3O?K@-*@ayAz5R6q(O*=)*u&ECIt^t0Pti!^fh2yRIF#v)g9M{~pLebV``3&K0vqO60zx5MPkL$?!Ms_sPkS{pr6TT1SCfoMsalVYJ_JM0M-23<`f9>3d^N`oI-w68H{)YnJsMF$>`N&&#tzGN?#GZzdiIeUPU5B{&r#*@u&uC#^@s}cYgm6xY2?Hxml>GRy5amhyhh6zhZ$FUBC^sjWZ>FQXSs3dle^coj%1xL*HtD}QUuE>mjcIYSOYGqb>sg+;;eI1=!Bsy5K+=&e?nSwg-@#rK5I<9%NM084U!-%-T{xG%2knJJ7bon#txJPXbkgMKcM&hGe%6u@$L)VjanQ69iC=TuaP0_2=tt#?@W74P^ZO6J$pA-xat`{UoQ3DZQdStpZ0$h)Oy(>;mE!mI-*7`Yb7D@uRm}(Du8k@}Ig{u8>a#$&uNF-}-1laFfW<-zNTKF%vX?2O=J&9Xe~15(~K-+th3T@uQX#!&*vNNL)5`(8>OY+vhz0A(qaEdvlAAc4Z;oCg1ZWcU}qO0%7MkbzS+?>dP%iKD%Yr@_j0=G~mrh`*~J5u!JR0Run1u{*CJPW;Sr?-{UJ$h$pRq|UeP<-=8X&apuHstzeYob+w?4(1E{TIBa2Z)^=a@w?!t0J_un|EA|4&m{51u(v!2W1q!ux{tgx>q5L`@fZq9*R(7j_yzHk{P2~j0Tk$`Z$0ie40&(+sK$F8RouCETjtB_r6N4}-?0Q8?tOn=BB?+11md~6ZW0H-a6G)##7*uC;$%)qD|enJ|K53K{W9d|ZDP#A^@~}MRk*tMWG>>QzVWLrAI>URv@G0-{GYtHk7f#l_TAjkB7I15wH`l?<_YukzBJ->j3jU9PpRMmnbR&0cpcrG*{Yrf6qp`9JvaF>;%AoYbOt`nKRA%l?WC{vt^erNx~blZ2aorZr!F~x*LMDoNR*N6Yx{oor9lp32C?ir4sOZrFeHl{%P^60Xyfq&4NQQlggD^+)E>+?cD+wSc7EMg(_F+SIOQ)q=gNTQ9_6PmeUX>mfBcPlGM$AL-#2u-njzoY8k42{PMbT=6RLiyi1^>6CfgO=?V&(!{;92rJ*fAeyVCm=R?*;EDF0aRG|vCJu|umefu&(JT)EUEi+t(3&LC#h7zT{Z-la@;M85R9f5_|LSO)A0TTNGoh4!r<)g-OSbbWdZ4X50zWKVUXzsSHlX-4Q>H!Rp{6x3+$d}$pZq<+zyOMj&qC;KYMYrP&hN9ca2Ye$oDV*8x5O8e1ovH^^!I+u@r_X~(I=UHIMC$DyULeA+@8eYJq^+6v|ZhP!?7_J5OYO@l!*^`PWitcjB?Hep>Ng)SP{(>4D4mQv(}-Dr<&_f)&y?(+dzK^54BdHdevAqq=+dr?NEhTw6^(ng?fJ=vHSL`asc%Gh=Kc`%@m~Zm$t77vYAn`kkbd2*t10kM-gVkbq>j?n<-~)yBnnbAu8D`fM?PcZ)bOZ?v!@#LA87vzM|^%v_wTLyXpmV`QD-y-aT4cy%GrH}Mtcj+zCxa}P)ph9`4I*(v&WcOZb3Pd{6KF57FgabwV+=pPvWN-@SBC>MsG?6`6E7Xy8O&T`Ft?xIcr?rj&dHKzrkkb8v!KmfA2baC*maT5_>2?9{`sUGdcAdj6P`SFBUJrANxx+iy8BR@Q6`l!lvE(LFEt{qJfse_m`JaLM~S&mQEPjj7Thd7zTdxo?37cE@-`rSIj6S94dngr4CK<3}~o0}2;_hw^ywhRNLPVtc+;v~NOkYS*B6#q$44B|$G2OFJySr}5KccSV6;#*wb&WT#f@yR5;xyME3{SBB`BpAL`07q_^r(a!(e$IGZ!JZ6=zl*q-{O6aMjtp!XGBRzo67ss`jxJ)i)mZ3%rS+%J4aALqy}okl9}6-m;{zP+kf-JBu5D?T6u>X(l<^j`kw;Z0-Iwil=Ydy*rOSu}ypGYPxM9JmJXrDO0TnOe7k&P-8Xx{M?{^E6@LY$b+Nlq0>#u5Z@*Fc!B3g3f4NNeVi;($K=(cr8qm7g5#0@=A65N_`L-qha`4V@Wf3_X2%G;AIYc5;r9KY0pPJN{Z=v@Ns`U-^60ucRFmH2pA7!$wK}koVO=U3;Rj_6@>PE?#iab3tJ*+(0%UWnQG6hTkm<;w{QJ&wUaJM?C+(Qu|GvT?*s&X2Z0STqK;L>{9x|twx46}A+5b4SZ~dz)W`e?gd?0za3K{6n?Ekm6NVAp?Gu8T+H{{_yB>9VS<0-hsTWK7&3;ndWUbY=w7tQIZz{OFAbCKte@ybC%X^>iW%jf(!#7R1<_eEORKhVM(`A>R=aiAnH@N?Q^)fZVPXLVD9uj@Fy?A*FoDSSBMh1)75I&xW%8}K5Z@<#a+f8x?dy>&?%ztFCkYVzf{@;cZh?BgvNJ|Q)G%vPZJOy#`JNPBl+aEXy`SzdG0aXj^XfTssnaX&gpKYSMXVkO~8f@0B`lB`;@r}m6kw3?_RXlWB^Qw6ASstu)8qf0U5ug0({pP)5+xa*U49pVugT04}S8MroE?S+cSeTwJq9dvCDE37NIGY@f+SM6oUhi?-@PWhik{Ey71xOdA^K<@ReW33{22rDfv2B+7gfajX9yc1H$)40bQ@OLT4Lzcc6lr$Fcl)Pt4##21_P+u`7#TfBRnlA=7Xi_kQ3|QZR_~|#l=CXGwP%<%kd+ZA0FQ=|4e{Vs9!z8m`0~-*Z>f{(aRg8gM-{XF}*&xr9^tkS3`GFDk+X<^c{O_wDIbVuc__Ohm^@Fp>he;o**AJ3`@T}tBxW0K}@viTdDKKJc!xVuwu5S)KR8-WG0tTvYTsLe%{Mq%4Gj=DiN=G&OKxK;ps;m$MY|Mv?~`y@nO8*Z7D$@bs%iHL6<4@a0L!iQE?a+&U<>*_50Nwx4G|Gh2q&C;k+%B`I*vL3{FQ2664JF3fs#bM>#;d*p29!KtgUfyU{G`~9|!XyEkV>>Rr@n>_G-#+%NX+Sm}}d#VBI^xnf1{0z&no%#juKmE$j58F9=d|&n56(>ddkdJhE^=pO_11kmQr2{{R%rSZQ++=YZ58%dZ%pcS-U?BfO>x4nn?mk>NkNh>$8<&}Z{wTNTG0kiDve3LFx@M2t&c5|6oSK%L&ll!NYDI1DTTk}MyI}$#b=!iP&3)@hUy@51JXk0>&3(+T&^~;&-vdVp6$+FS+iYdk5g)g-+Foiu1vz)TWz6RxU!o4@t_%K2!QyE3bz>b+zeg`n@_+44!#$qI!@%3fmxO&MI{xc(e&~OGxvB+=_=j{<&U1Q4i(|y$d-~Q_E%9~Ry}Y-N(9HeFKj+G42TUKqhlX(XBL?oieYnv7*2)KxpJj7?ci;8nBS)pG9^~Gm*X~c$Opq5z9N(3pa2a}HgUtVUjRM9Ehvg`yx#$0`4b2I9i{uF3y>FI(hG9*=7xe9~zsj`CZ)?3(l9op0H?^WX3C~XX#sb+6R{(kG;UM?!-FbWvZ0%oaw;cDaRQk5g3uZj9_2=z_1=_*_W*Tlp*>Nc?=jCFHS(7rwfGS)2!9P2EH8TOtqnG<8KkJYUYGoV5?Mk=ni(<$gy-N3@o!t}JuuMszr4lE5@#fMeXi+f&c;pbYn^*4{&n*!g`(uex(M?U%Hp{lRQQ;x^Wo=WKP;Tk?Y)@eP>`$F$Id8qB;_Rc>V^PnlxV;X0L^_CzHLy7n0Zw>2{L4kYFvqk)brOEk&q{C8RfcW4sDnW>Q>p28(SK)!({RgkLE+DS1>FZt@!~@dTzcmwa68CNW#p~UN?IQKL)wcuw_)%c7i9Ob7h`f&Uw<%EgukP|B#(&Q>RcUMF&@k?bUd7Ru76wZJ+bczKsFY90!@+i*C@0e(t4Avvk({I}0`WjEAT*Gh4V5+nrsy+&F(qHaQB*(AD$kon$i}=?oO&*%#dBDAPdP_C%`t*mBbt_KtpnATMRIteB^1Qa5Od3k{%0V3Cv-bVd%S>-jFxy{idcb+)X_CA4jQnCl!|mX}OHGc*i=0f$rYetRV6y7q9I>^?e=3@+6cglG_%3tw;oVCj{j{?JWxMVr!B*djwO1_h`ad>g&!4a$86x{DSoXVxIEk;MmL!9Z-^C%@3{56$7AWrgT2kKG1b5hdqKId!PG*#j3>&otC$JShtxwknx-|pjh=DOq{w_n;K{WAwwZOQTF^n380X{BYzXJU2=(yUdIVA$ET$Ey~J_%pv$6&S@P!9MkX8ucfL2bQNgq>fF7-Gy5&oEGtOs>YsA7?_m|B!7zk7xCKo;DM&gzFkK@DdC{uM4zstMeYa%an$qt-efsbz6Xwq!{(}^s?lU@4O_vZ*@@h85pf6K_K4Snltx)h&#?&Iv2ygAF?@=-50sr%lX^??T;dG6L)bCDN?&l$N$WdQ||ubQO>Bw)NUUPZs+Adl+hfzs$-N}lv~%@2JV+V1qLOj?EVBs|a}gYK;tJCE_Z3AKNsRh$^mNKkoH+KBQL@=OI**k8rW0r^s^p7;HdG8WuSp3chnjD9?#ua`gI0~u4V^u)7o{h4R_4;2>hpd0Kb1^!5ZxwW=z=p4zEpvU4&-^?2J)dvOgZmwecE6EAJWFqk#n@CHOtdqX8Ird;R*QmT;wh)kPe9y7{JZnEp3h1~jOq#$7&djd;JPf*VJQX!vUGy1}#q^WSoa#d=7u_Yg7Db8Q3{Sa}lzu#ik?@9rMvI_C(?Z_Jwtt!@Cm*ENf?eBkxc>SkWrrS6>PWj*bFIPhmf5)hwx?IB99VY(~pbVZ!ZHU8P354ul}JqziNe!?eHUtPLhnG9jvF+jy3Z|ukzr#m+^1%!G1F^I>8h&u>Wx&7?KtSgR1Jl=44qE#5DU!2o!v|dL1+`iG*s=9bk{Ha#A`!VA8mwvvxH=F{?p;AlaJO6J!VZnGB;<{G!EVn{`9XS_t%jw>}d>_&8x97$rlV!Z#z7~^`(N9SFxm>%>!Y8)MOn>M9qw37#san53UdSv-r9u(XC=^LzH5dy;87dk~B{GI4Qxj=GQE3nwOy`_^22`X$At54^ND`UK6iMl~_wl{f`Q1Nmuip2$`|PvM-p})S*0ToGWBF4}B3(@Bz&suGaeW%{LzC(w48G7|KcC@}@B-vHMgm_Z#41Ueeg-f$a-blgB)Nje&sKPfU(u9KgUFs`;qe#nI<)&XyW;feP`+Z%i0LcjpVC5)+BDN4Jwc&k@?^aJSJij=F1Hv^78AEi&&>NIsxn?cIj=b7spFy;x&%Kce~P{%dj6V-s`+yB<~$u-2^WL;iQ9-^I-tC)m)t3ei%ZFWe1mXRNSYO`QDMg2Olk!Tv70{j=bxWSDD4~OQmc`D|Hsm`4B0`?tW`Kb;V~27bPoK4-n&s8z1ng+fdav^v?_ZAm!A(CC+&%^Qjy!ol%Um~FU1Y+xd^csyX*_XvA?iK1cd$Tx*;Doo|KDmEO(8zbiT5eqe+8!&GP$pD_!&C95B)+0f8EMtMhLi7X`>QThq{qlSJR6*cJ5~NU;I3&110`S+mSl+Y{_Y@ZP(DA)c(jb_L>KiT~1plkI)CUk8|>Ysfb{cPNNq^ZoYc=%PAUvO%}hr-%bENGh<{n$|w{cn^`(rjRj<)L@uIp(&zOX+vx*l_Cj>PQnFovE!z)9`TSz^|sPjn`KoFZZzhmbfVkng#Av{qDoxW!`d`2RjciU_e`Yb>ErraZV4P`K?icfXwK=OC{5h&w073Z2dg(aUKiB95`q?h82-$Rn{N1OzpWf=@hWwS!eShZ|7Q~X%JijRNGpWxLMK-b_h+J?BXsAD%9u9dM&f!4epN|#QSCM}?U#hfAJPXo8ro5^U#_KFuY;M+0>W!&+is#QxLfuGCBLYU`zMhJ=-O1wzlgwFP;Hp9Z)dzT96!HbV52gQ*`}&i&Q?`|DLatq`tfVxV$?X%dK^b}5`Ag4*uQTC8k!bMIQPh)rMn$j9UBiOXYu%zZeje2a7j{1#iYmlK1$D9rY?sXhTVc`=8TZy@*C_C9cWHUSM)@8qM{$Ya9vawow5&PiL5dmoYc@uQIm@xojGh3cUWeC)Si{hD|dc&yv*M7%&AGN@z-?rgZzw6MkO2Kwt1qp$+iFUH^`5Y8|;pSELc7J%Ik%PAbWohhgr;y0`}_+$`5K}NsxuC=;1<*^w7HDBXqBO{?_DQ0P<3`AKB4}J4M@4@6PgL%G_^$ZPvG^RR5=&s3esSQkkC=TI^@(jDKn7$@hZt7d>Jl-|+Ee8r}`u7MiCHDkZqXu8t?OQ#vFCGB}{JqUEBwr{=dB;#-Z&@Xb_G%`)w)e8L3$|y?cwu`G2F0RzVyJv$*BzN-?^h@C?#T-Ug-P9&d~B_lJx~4ZFr_fTqi1Na=h@#-x9NC4OKxwrOawYSE*AK6q#8M?8aHW?cA(}J$z0TFHj-D*d=w$T>BbY0xGKE=6(7=-N2&9UFPaCpFGk(<)w$Vb(k3P>n0)(FTNV1jDF48=nJfs+ewV5A75#P70=5kN8lVBCyIoiZ#(Az|!aShU;q$Q$JC$72OH`fZr6G*5zgPUXjyDAP;5-gg8y(V(ez<;o{MPf164Co;uxq{dPNPehS4ib6iOJK);+=M&pKZ1Ex4gk`bog~gT4eqo)S28mLa!KOI$;OuC4-F8%ev0we6@0B2T_80iHfJX(@Tuy_u1k(=H?v@_*rliI+7juN-Sw~SrKd0Eho_GhAOsJGam#HWHfs?bV#m&i9ZC{$eIEaXS-_4uBULk+oKC^lFgaTEP%^BQ&keLqcuvhw6W_juGlb+wPGpOWus*L%Nfv#+B549;xIiCoNpml>I!XOE-)q~eaGr3v8H0}IA@IezlRaJ@}{;0Jjt@krD^IaM_gEe1?zd9?7WRyEq6s-L4jz=S8NHEEiwkyH6a?oY<*W4KBoS6uDoWRSv!M8BNQyS~WhTP2iTUy})+zh^dR|3-cC%}gNu&9_X*I5K>5{wn0vODeukNuz=L`|Z10j-vj|c=OIiAe;`%qc(dOzCiscZ}Z@*Y#`%*aZ|`2tUi$Q%7}oN-UV?zA?Qz|X?#0*xs`y;QO^oiXdqwvsE)Ip)F)JboQyfhYll87XzU;B_rZS%`A;_kD|IV2*s{xijqbzGWl4Mt^Szw`>XX&v`!}Os%eXbhpm=>IP2GQ;}`^5vfYO49S_V||E{k*jL@g&ink0Qobpzr-PLD6^J7eS(0$Ql}?wyocN*g-`XzN>YEi8CJh&LtcF&ub2=dpYwS6<|q5{KEtk_6noXjf~t?Ad!`$sP8(tPRnh;Z!$mEn6URzWcOCy0{=58Y28j00aeMRvIpzPVG|7ae*PIU9zC^zNtK;t0DKu{XKC^eoThyLU^BknX1Rq;Q^G}{Ui%0=$m4BqJ`&(nNRUOZTsrkfiCIP!AZkjcdCl4r(B_^2his0ru{8q>F<&+LvU3NSZZ2FkFO){v{s*?3zy+1*I-^M1felOHxddsHEj@YKd<)lUTe4UUNelBH{e@ll8N;S>PFCnM=sLmHMK;_%A0pSYdVx5J#Q5!RX>g%;e0d-yHpL!Qd6&j2P#fT4|MSgPfqm!2u>5wr$;?a*;sQ0`US?%E%GvLuOx9kIT$Ty9&j=EbCK=V9XboVprx>M`DdRNRG>!&b-Cy%Cg>W$y(d@P9mnBXtQQ@2NHP~`RkMj9M*5}rVxfqIYLC-9uEl@5cdy$}0Ckb6d(8acj62hGAW@1sVLfAP@e`xcS`TmLD=24xIz2rpXuW1kpEHD_}Lxgho}Zq^mK0B36+`nxt;O{&m45m0EZRMdb%mdC+Gf{8NVTuTZiY^Ce&k{6C!dy7?F0k89G0lCts$nP9;4skks>gO)LtPQRi$Y1-*R}1759hX!z`ndWQ0YcoY(l-1%Ixd>ZPOghJUlsCH-4@rn`ZP$1)t%_+h4<;$pI-jaOSa%2Pf_5+L1MGrW?g?#+paYK~tW4W1SL{Bfk-eVo^+dFr&p(&54(A6W^1T=%(sQ=A!N{;L`Pt@}*|bw+yc6_p5B$UJa#b&}KgcuFtDBoo~HadWFZKLw~HU@i<|4od9}D}$&vf5=yzH^dpIxo869pcPv)%rg8GVE-|`-V+wZ=*4)xV7)m!YO%>&)0g4kNCyuKv)gM18S!;8SZHDZAGL-~mgOw0s5*V~%GH9UD1eRJO$WMo2L;E&W^Yvfe^jDkB2!kGDCk>#jcs652=Yw6tjOOX!9tLhV@0<;)FZu5*}gppJA5@#zDz>QC-#BAf@2RYFYv9v`=sitn9pZ({do0nP#->d_~ghRy9`)h;t^7;v#i+*`HZKR!*WAuuzZHOTbm2=s-&v^gC2CS*An)-?t}cuxxP}r!wkq!5PTGW9{IC#3+=Ah60l}N%Ib(}6u?R-s?(&KGxQMn*aunz(Fv<}c(9v!C>c8fHL6Z)LN%80sP_zO<+}1F{NlONY-#-r1}@dtY`YY_Iw2q__<^)ldBG6&j3IuH6424!Mxy(!lQtbU39t@Y{NXC%;3uS#Meq1HKynIlJvFPdwhaobK2bwN=K10bukWO$&?2~tg*GnB=Ikh}e#Ba2a2^cf82{xD91H&2USCkWzosJeTJC21hjd-LkgFywZzdbL8k(?Lw^yU>lPsIS&Imz*gU&4B8~F0;a)A)ihKwpV08z}amlq7(3bB(L=;{vw};)Ga2OQC4_A)VlkjfCf~b?F+w=bK}1!FhFdNR=j!z>YUDr{n5R;1h=2>t1qY@_9m|ty)c9PzB1Xa2aHe;9FW?wDd18nR}Zl4@cP{~nzPhI)8LljkFB@a$f;ARnnkl?w*-b8u0#=W@vO3FJ*vsKxD`9HK<#PkG?BuaVB8@%azj_hfudDA3d2M)pQ>yy?;U*KiA`RD0`Y&Dx9_XKB<+CT)%xocv3+scV9`@#rwHn7iGE7G7YGHkJ*jLgKi`%wfCgKUAH5Vy|?i`g&dwI{iCIWvA~z6zDU$vgRE}Oq4OC)^;62dgZH0T^5I@kd?t4v5%rHJ-=QbBJ)gA0HnpvzFM0aD%`Dxe7-hSkZuJwCoG>3AkQW;MVyy0Qh28l0H23gSp-yrhmi%7+;m_9p@g@VRF2K7pO!$~9c)b0f)i~$Y(a>hW-zl<7Zam#Q&ei6cnpO?5U~y#Ei6sJC#(8o`c$C&_Hk8k774S^N^Te8#g&FOvOgOm7(r#}V#(hPfnChCoj|MkSt?BmeM_qJb(y6tFHR)g&p5|&Jf&M7!96WY90}6+)Z;r4={lo6?%hC`gfa-&kl8U<2R(XEv#CQS@Qia}@yN!?ceSWgCMUx3rlujDU>Y`rN)!%+Y>kAWN+kWfIji8^9>dz98%7UxU$&F1E`n9NkhaP7GH}7!$f9Hu61`3q|XE#sDgz72Ve)V5Nog-7VX-M;FCQxxJTboeNID9&DqVyyU_F7cT7t%mpymQu8{yp@uJl2!wFS>hj_qJ{J3`jC7o0Hmwem~0ZWT8WF>tLTbgF3cz_EI6EcLccBE$CcnkK=cq?=m||{_a#?+G9aDKJT^Ru}_vPn67tf=l+>^4$J3soL^=co7?wuwJqM~YClO4%Y7LT`a|36V`pEd_1{v*$D~+SWv7@!Om(9fS=}Qkqd!;g9WCvf54My`_yDP=wfFTKJ0r0NanzhQx5OWr@pJE-gOH3TN?${p*+pzs&Z4QJHfN!Hkr0a{m2fBw>hoXTT4C7B6Syv*NfXG^3gyhTp=sZJEqpli_HrSKDS6=7Q#uAsvl>p&M7QJy^6LW>~Ji3Iq64|vSkf&AeXXId6PfYZaf@1k3fPtZ$V_wq0kx@&KK|Ckd#&Z#`K2fJ9Xk|Xh4)gf6>WuHxIf?1q_>DQckk2gFDy=ZffSd*FwXVU)AAT_pJ|K|^?blaGoMj;A<~es}g30DTGyR5;XUl?(H(tz3*T8|<(H1-`<4M_*ePGZ~e`r6+%dR^4YfJHBqdaa%#r}~#%63m2~A-P>wEb()x{(lF4Wpe8#`3j)!ns`Us$9F0n+;ZYy5d+8_2d3Xi+rfY-4x2yq@#H~t?^!m@aOf%w`H^k(&3C&oT1M@YTRgC31mRtIt@8r$T6mS)9ohyq~pVA~Ve|r^2jNVn=85_z9_aa)w44ESpti63@Z=w2eD%tK5+W3!K|L-})j0_E@)Vk>ZI@o2DS@dW?K8ex)s10a-k8bPmgh8{O!TB3Pwy6<2;dXx89c-bfC_`YJ_(Dk2e|Egl!jZ9i+pGlTPt#8g0hMQ~7LFBmeVn?Ede(ufiap>4ucbX#y6{jH?z&wH&_=RX0^ZkqH_c-Bs%|%*Od!8?y)a5oMXX*HEZ|go-i37PtBiIj%=ujO1iP{lll1gj3A}{p6(3rsuryZbVj|@A9HzNcXB4YZOYE>xq^P7!JYT!$GFqr;Jy+IgL2eMzq>*^w;PeV%c=W^hcfD=5nboD{&!KjwbFb1`Y99hCeddy!J=E-`Z^!R=ik1&xbAr)6aL&aJpPt}pKDPWv$H&x1%nB5rcD#T`=|0cZr@A?YmVuDZH>J71Pr&epB9utaJa?Z46!J5e@hCBJu4@T`f?sum_x@pg8e{s}5b4Ki!bVvQK57syIcZvIViz(=5fNK7SEpnyEwFQb?oP{zWGi{0JND=a4vG$&xE|PEEyhUpmIlHs*tVcf$Vm2&G`85YWSG<)G%~W7;^H%!3kq;i%G3nAHfc<^0Sj;eTfmTIpM}8)}aCm(7+#A$g9i77oXH2%e>{g`#)jwp1HS#x`)Ne?ar2&=C4erRlAFbZi=ARBSIh7OgBapj4AH4Kzc?N7K*js&wCtpBvk&pbw$(fMQ?x-3!5%m?7FX}2n14m;y)*cV!i<)k={a8YWym`MqiSnVo5{cxTcRS7iU$5W-f%nMe?Jh)53@1R!&-9&*0P3Q{1_z%kaALyy9VNqj8K{4TUaKyi9G(jH=C#smo}x}$)}SmnQ7nzC&*OQnGeKKn-Ld;=V7)zLqk=ths_&z>eLA@3o9S!6L{8=POi(4~fwOa+)U5Dxsr<%D=}a&aT@o6}lfU2_@nDt10vgEk8S{B|BOg36RHSr(4xf*PoT!Yqgy_!*1d5O5|^aAD9#o_?}=eL^Q*-G|@gwsnFj>bINk_>PJjrvlaI;nFkYLvz$t&8SI*B|n!48(QJ#MqZt2DsUtXgylq5{2E0rB(f!c-^z5zEIOW{RfYFM)z=P_&H$=ktLX>ST~r;Fr_;&(hyrJhqY~dv6UD%HV?IX*o8rA?k`84C%>HZ^oQUXFSoXMRJx-IV(v^0~55sslgQd57SQvatJLzDZ{9&+BL(4Z#|pJAA1?VW9(fKObIaSJAJe0+lzWsE+qT_36l7p9UQ}TKyxRBd6*%NQtL|gZs(gcz?W4edS|6Y=5PL3j4^J1D1H7L4EB^d2*l5a5OYhbwu4VZS9RS89QkZVH7wem&H@h`CdCarH#&={{#1;U#Mu{q)N8^Jvb>fBJi{v?`O`v<9TI+TOMsc?X8`xaUcE;Bx)s=A>Z5Y;~AZGA6mC_CNy~R^y4EZ+Ej~FuxqK6tXz!unHN}nbqZe^#J&zOF_?_^>0e#x^Y~pFTp3kK(^Eu!Mb$eHuS^GnRiab2`QZI?_f3B@z%N{Tl?P9~j_T|^)0Q~X!2PL0`*Io7S0(O`ZV{mbNLCzQ<+Kw0T~rDi&;&6LMTyjrN~cc)-zqCmX`gcYgZmgU=y#ZggvaJ?2j<#C#>b$w_AB*ErBtz!sPljq~TDMC)jSFak=C2^mZ@ML%A6%oVLP@_iTjk>RW8z*DF0uUlD;Dif4k2M^!i$qx-^EOcFdmdTC(`8f~m{O9>%)89i(u8u7&{QrGqCit>IKyF=}*(&@USKMwqXZDu`&BgpN(~scuK*ckyy21u3tjr}4^K|wp#Fu%m<$%e3`mq`Zp7)OG=k;f-FSdai)?Yf6r4exYH~}i1-u~~7VBB5u-WyLU$?r?`?R25xd9nJ#EzX8Zn2@?PlBHUJ_F2{A{&4wa@^_>q8?4Ae`%rbqPKmI98410illkG)}oe!RYapaAf8yz@GTHonyEOTI8&r)aYC2**i0H>h*MD4Pf^CQW6n7rGvBE!{o;iaB{d`?1PKVHLR6O2-yDV;>+|_Hbf1KmPMr~UYHf*?a&q1#WpC9U+0jORpFbR2LU-*r`rC`!o1*(t#*yi3J7ptZn6I3d(3A^fyCnL^O>-1f7F3H7m-uvMw#UI?U`Y+dDAN7Nv8zP1UTHy4%+SSJ{=cFHVanuzPr#zN4rt~4s~LW%^MNe-;nB?^H7Zg8dZY~ITf@U^}Hs|${Nc@JB;?dW(eVO4N87)5Keu;9Erp1uI`vO*t$t#|^g6rtjva?ult-3;R_etc8ppF=u2P~k@0mL+sSE%+WZ}DXVOYLAvQZd>s=f*~#SDQExELRqD-h{`VVRqV1o3bF!VVU_vE3_xKK7fBV*FVtu9PLKESC35zP}C>BoJq!dhM%vxSbk3?pg19BZR;iEovqDYuSJ+JbJDXftHY3&f8O4`G>i$it)mlP?ngebVs~_qI140XUH%$vLVm609`g{v0%=2&hWRSUsl4W$l~7;;|nW=Z^s&xZ3y`(?koVZWF}MLG86uMC)0v7v543|{AjO3}@O#sqAz*!5=aTjUACvbSo|2#7hR5?vyX*P;3)y_REg`>TfdA*cFz<)<(~L99~I`yKMh?oYA|Hn3pXpQdBFM%b6R_V%*J?fh)my?Q3|N)d9;=9XZY4mOB1sQAp;f&H5QXuk-m9Oc0KZgz?Pgp6^%=lMRH4<^|#@9*Ft^(^G+Z)eon{bszT*1G{o@7!RR8CT)jWM4_%EM!A0pr|Q+>m&tGF(l$R8NAb!0-whg1t0ZPXQ%-)U(D6TaT4TR)P4x`N7UcDH1K5*3)zjk+T3!@=;7dKS08@QN;6Pj7tuv3chqHh5pFa*?`-`;>i$d{57o=K%kt##i_6;J&Xbk}f9H%Ye)86)xRqMg5><)S2pPM8Hf%y$?bB$iupReowhcfKPgs`iMB{3hq4fj~J_q-i`Br@5aA*Ydx8uTY5#tI~DDdFV(>Q-p+(BH|Dg%tI$5jI66-Lr0!Z>P#v!ugSvvsw@(ZXxKR*7b>gCS?>U=xN824qB{BuueH8Wtty<@`e61WbQTl&ZetRsLEP=CtE0`&vcZ|f}ieOV9PZ!HhNbufEriHEuX6P_w9+G-n!_Tkop4PuVvq1)p6c%I!ZocV_d!7pd4trNlLipnF%i2Ywb@l&YJm$>~n*SDGtt99u{HHG+`Q1!1Qf3vys^WY2A6%j*ncH7H2+ef760+zlxk?WL$>l#(JV)0c1DEzeme1BeyIo+cVRr?S`egW4%!4&(H>#fIdr=m*zVX93Xt%S)#MzZJ)>wV-N_>7i$&E*)%l~wUG3ruULqJlb4hL*SW}GQFgwGEZxAtcK*gUp>EAC(31qN@~OE7?{Gxy3K*QpzuBSLpAB|u5K=Rnt7t1OAMEQFo#(e8@eCVcjy`&1t$}vqo;MuiaN`pe(ovU6&GD3z3d{m3&qMJ&K0j34#rr4*>@Sjd^5s(UIA64K%SJaj@_SAGnQP~b{NV+kmuo`^;HwK2o@I>u%gR%6`Mu=+v7pPPU>fp>G&u!fr?+SU52_PW9`-Yv;rpFO_3{A^F{8m?d0{IFc$pLNl+TeLoRk@TU`q|Ur}*xa+6WFaP?IXhg&aN#|8Bj*AMd~i`(DobT0B6>U&nC+^56eJ0I>l5qNznKmGDX25i~?qVz&Pa>@^RM}PnkFUfVnfS>z!qt&%}e&l==GIYWH3UZr}lY5^2B)EUC7(w2&U-QeFXeJycUmVYasG~Bjni>2wVS$m5@}7`Bvgr0;;XFq5tDaiQfaNX~~oMIwWTW>a#I^^bidWBmP>Z`KS(o%78_E=nTG}bdz?9iXk&L(wN_Ct-wxu~zGvc2_77~DF0Umu}Pc-m1MCU&W~dXMRwxDyc&?VvSpW^E_h$DqhKYP}*0zGh8*w8I_kGrK9=qwEz6mL!y01Z3fJLiu^@$#t2kncsVbWoO}j(X2%eS&~fXnci^Zu?*UciVGA^U~=Q!F8xFMe7iGr{*4X`3a85$Yw`H~sBP@_A1t8e?~CfFuc$hr_D|VxQTu}3hzr_h{rPpVt7sh9RsG#I%pC1gR<<&^vzZQ5Jd3+NPaiI-?{dW0x%_59-BJIQpiBf#;jt-n2QO~2p^HX}^%L9|g`F@{5^)@F4^d0v}o4OVGm6tDCC8rW#Ce-Xwg^LA!gj7;uo>xLxPbOS61E*5nQ{fa?EdnTWh!N4$0D00E;*;^(d6>HkaBhdlp-oZkv|U6MG0oT_7)dzJ|k(jWNr??f)TZ=T1@^(<(Zr(QF6CGx7Ni&Ku1-&Z&KXSEd{a;`sDi38iI7dY=f`!^XpY;I0fu*-swX9w%lcHr-FziZ%xl^q?vGY68y{-B>~^JihJS)+8w`ZuxWxftrA4|g_#vm}tHUxJuHTh@6gj1{yUFiMmAmuj8Lt?tSaf*9mVa>p_w%nua%0N>Z4syLxWCVGguLc*9qM--0$g62isi^)0;|>3nsR<#4Tok+d_MbgjuMUO#6#CkY^`hkjju*xF9^uu|5L7skFaz_Vu9#LY#k8O*kM>nIsqWTCllk+zBoah$nD^0yY_Ot~oII)kmugVSemG{+s(WmoCJM>%26)B?sYUz>teA=#T(1)R~9=mzs7PQtG_;KjKnRK#7dONOzVn!;5)|oJ1`q#I=4u#@6xcXnf`zzlWpnN@}b^kfE&-&MoLiDy0;F?&pAjF5qK2Ez>o{tHL-Y9oCS{Lm@^}SuVggN&2*8kSW3WMDpZRQRSnLz$;z0o>6eR8*$Xv%J3!GoZnH@$9ne(GhcvvgpH1vv?a3Wv6!zOvZxBzrrH4OgOmS#))w9jN+rCvMRp@TSDD%wb&Ds5(}AS2E!5Z8fW3`8@uXxlZ51TNuE+FF(4d8|_2o?e4WEps(BEMEOs&kI0t%+gjv4Q8VVP$DB{76XJ|YyHbD&fzz#m*Cn8RmdiZQ`(D8Wy~K$>2bIu&weorLJi$XO$Z!1H>*#~}f%2DGtFeI=k?<|$IO;2hzjeyS6FBhm-L|j}UDQ`m_vh>vK0yb^scweKS-9?pG_;o&%w<4mulVc_^2puxKAOU=V8Cse?>iS9L_LthX6OZx`(mnI@6Y>aH#NOw)1}GpOVtzj^Z@Pl_MBmrA~|0@eJw8Qau@AJ)m4sdWJqzD_T6Tht!j0#R@s|@cCJK>^Mz`I&bnxGpnD9_St<&t3zWq9jMn-dJ?Yh@!Nl_eDseF@s8KeYn9?Ue)rVtMK9P4?)g`AB=WC0-<;*w6Tq!sVt`z=apEnxJOX}wG7Grz8tvwHqyA(f`F)pfeYthfPqbUxwwv$DyO{9zgvsf=0kqpfPUc8kCJPLyjp8%3TjZ7der4y_P&P^J;;D_Ouc-Kk4bdEMrX^K>Ka20(rBBJ1zG~CKOxWh###PDV{O`w#%UZQ`NU=M(-%|#;#}#e4dlwn7=>8g&`#;b=RDQaJCb=G|*ckco=%|4Et1UC>1ni#IsLMEwe8S2onWNOG$N&&TGEw1vIoaPu@}(@|fk=c-Ds7ojhyP^azu>@6NmIdrtqy2w<8GL=8oR?}2=2pBohvVNQYN!AE%z<1druieD^W5`S-?u$1r$P9+P|=(m)K}E`$1V>#MC9kjEiFRMT?dsIP_!&BHm?@>S-E)!TZb7?x=YdTT|4sOLHgRVC^>S#CFzOiznTPj{uQ9=9Y5M{hTjX(dS&u(^vEXCQcGUnn@{O72jAkEVgIc=b1}RC@GhOwj8wQvha9JgC*YXf@s^9T1Ga6)1iyjPFgV%W``!+SAi3UQ!TML3ikZWBp+OwP7Uzm){-My6OTrzjpq+d4n43H@5pY=@MqK(LJD1XA5Sn-}_@zG^Z^pZstZRX3G!T?!cQN9>w^Hu~&TEdr*$X5x=DN;g^u_``?lpbmaHvF;*s>pkf&)ZSUuN)`fK;)5U_lGy2-F|2Ntg`(~w$p(T&LQfpoIJ^eVEVW_bo~amTAmDef1QkC`4^$1J%bbhbPYM`brDYT`nBp4-!)@-ir3rF>}1xe~AWEy~7W7sB@_JvlC0{khZZ(nRts`3BED5k#5^Oy|8+lyf){%im0;qaI?#jrcK25WkeU=FaQzquEkwD(=q_42gh6QSA9}a4EqWwer0)I@|#D->KMGybu|9F#u)q2@b6<-c~DA_oA|1gf1UYrsWVod|J7_ssRmr?&DT#~uw-9dw@=^jej_mPhfjj89a(LpHg!G(!=$WI-0X=J%DU?01~Z(9}5_}0-5sl^1h&(!5EH)`M%zxG#(vA&3jMP#`H##GxFFjDR)j^p9)Uu#up@Ta0)0!H}1W|ujk|0?^T#+tBfCY%gCCZZyUI*N)@UwM}WRtv;-Sr#Ct;`3aJ+2HW&+3@8A)K{|9f%6piD&Hym`EkKCg8eI+0i1twtxUmMs(j7P1F_EtQ#i}>M`NV=QTotcTr!poD@khEMP)+Ppvbp0d>VSjB#(VEsvAAB9j}DUSGcNHz#C6bKTI|^Qi{!j?;Mn}d12~^kb=&HfF(Br6v`g4@Z-&JZx>WxXKGc9z{KGbo2dIJ;Yp6cA9a{>J}X}_K*eGg{=Q-h)Oou|GWb)HzD#|A3iLAW3Laa6*R>x$&QV1?xFm^Wp(t|gi7HQnz+hX?wZD@#<6Q}fZ^=?vIpY1hnjL;au|ANVf!4aplPEDwo7yY1NdWx2=}0+RhNrV{q{lRtWKHvAl`kUy`7oRbA#2W>x+~NA>uL+MTdS>KXsQ4U0>l5-+K-}rHdu+N7?iN!i|5^1K_0&-)lXKB&IZcAJCCOi8okP7fS=W8~Ss}?+eZ`tv_%b-#(>eq~aAFo;4+`j(vdqK;ng>%jX%O**0tBY!Gr$x19K-mE?ZG#hR|L1UZ#wUXn|I2g_)UKTq5{x$J1|w;}b0a(hBrDca2={MT`Y=r`^RoAGO(cmRgduG#^iBMJ;zf!X|QjeM^K+Sa>~9Bo{3oO_M?kVgJZphM>#y_dQ^Se&31I4>KeGBsx>@e$xwCH3^3EAk?RMn1oAw%RTgHT@TWywpCOrD>>ZyQy^8NjAu4;;d8gi9_d1)QNkqE&PxPQ3cm_edVD3@ju4VDR8GjyK~ylTd#QH-bsBhQ;H6GLf`UBn~>-Boaoo6ro+h-k0ZDIMy?w1Nb=hQ2FU)La(=Q5>K2DtTV;!#30Naqo6@6=e3o5NFI$+&jng}^9XVBRsJD#Cjc->7LA^x9lkI)N0;;Zq;(g?lKXm8|8y3%ave2Uhud^~rMl9-5Ccup3^~GJtS5^ObK01d67w;X>Ts9l^&jHD!NfVyY;AeepSkxxuS}OKuqJrsAX8WpWGLQf2PNVfI7Y7Cmd|YR1Rf1e<<^9-6D+mbo?DPb`o4i8Q9%I@+ScU)^b8>ZKxljYfqS7JIn;(;wzhdW}?30&?|jQ$$7iyZqIFdS&TcHRb(=_nZx4xRf3PA|0+bY@XY=M8l1kgBBYeZ4->cBN5_d=j|Q(tw#S;FPAE;VYZ}R+!H#WlN8t(`hI|v{w!PrdQAZQg(~bUDXQLJE(=t8c)>a_`sw;i8rnaMfsQOUW$H@J{tu?*zc4j&VyN>}&%^+)^cpWqd?^(GTq%!8wXzoO2ZaEO1>yv;0#>;193aXLOfjP+V7z4C166TCW1AHwJ4#ZIfNmxeS5aXUItXpQTByyAsJK5u9sVbwEjT?MZDLDg5MtoNh?6^DL*CGvG$o066*koxL(yMgR!v>R3La$+BYTW8xkm&a}o-EWEc5^!umWvp!p`e9TX;)^FuV8Wt{2Ty*bquqQaP3suG%LGP8=8T}7Xt%bE7N=$VS#Va@Pcrfq+J{=7rkk_DT_fnKb}PoW$2yWv_*5EXW_q42;_2sp{ZQdh*$o;{buUV8BG;==S-E629jNauy$|_m-(-hFeRQy+9E=N*bMzfYPv;!lcQ_srbl1^8I~w(Y-EF7ws8#Ok{c{`F;62b%KR;(4Jm5Lvo7)S@2XjZejKxeBPYauN&*av<92w;CM=^(*tM<@9?ND^>`bOkZ7wiZB{G&lmh|AsmJbLL$nrY9R2Xr`X8>=Uoh@5;a?9X3hfXiLeg$n|B&RehivHV~}z}u~stupJ7e`+Y1da8*4pSI^F_j%4|T^kH$Bwu9$_2)bu9s6fiW9Cxw`#Lli^CxXX9w%{NQRhiEyxYOQV>%t}NyRt*y_yN~U(QBtT!6ZT@>}klOM@S}vVFDlk-LxB+QjD4ps0_2WCBm#pSuTRlDsb+I(4^N&z^_89ON-l05QN;;oESWpaN0H2s;(4CGXuy46nzxZW0VEJqaiCv9uR(?^*QvT?%bwcp9({A@-^zVTibh-|igeYy#Gd-evkpyOFiyCw2}y~_ms*w{Jc{>WbzsX7mN(%{K4*50}c$oG5i*s)uI4)+r5H%4ai_`x;dGQ(s|QVV+hcwRG4&zC*Sb>)mo|AO-$IImM1S|jXWemV#Z`G7MP#@GCUB4`l@G|@7)>O*xWk6fkim}>-x=F2|}50C_qzZ(PiYH*UfoGZn>do@`xLfHj6oEa5S3kXF{<)`gB!GN09f7^!MA^#k*`27|e0^V2%8k_2(o(W~U*QJy0ocfHM_CZVW?t={2^6c}ZYsL7vxz{Q$<}b^H6Dyo5oh5nno`0v-%SV~;dQj2p;clMu%EfuF&pXgSS>*ZjDNm5s?ag_!ozz_-cbA>)T7sXO|Gu^Gh2U6!(jGc;$+y-mEs_NMNj?47!UX+SO&=m-Bk~A<$FsB;|BxGfZ|~@fVS;Dci9G!esISCJRwNW(XF*%xz)6P&)K}a(>?>(wdFA5hzvB2VQ+Hz10ETk|r!B+vF~mL3-`apamj9)W=R2Kp{4C>-bZ$NK6|+%aar4T^eKA$XwC@A1k2i+j$z5JV>X4dq;?3Tuueg6)AB+E2FUNILi?w*^B{_2aJ>?%1F^ch5YZt3K@1Zf_*WKX8fp-{p^!T&BZz8!ao7YM^keo+&KIr>o{g%+zOdz-2fphXuUs3g^=7q7idDFok@tkz4b?l*_woIV<+f0hT4iAKh0rS4QR%urQV(Ff|XKpM%q1fD`$BcLX^u%HD(avB>F~BD0bSRQ((NYP1g(_MG&U2~_;=x!>r=J76UEaD>6)<~85psh=z)bX2-3I};@C4$jjx!F6h*{ptVX>deEbYNP&-N|8hwq-Y|^*esP+ND-n*8PXuhP#GgKr9={nlro)j3}-$^5}`<@LZrb|ibg6?qVc!)dEU3R-`_t^*Ymkt`|PvM-uL?6_r31#($~@FK;5+K@p|_#?@Q_(=sNR&1GR6Mfrh%s7wsNoW*_6i%;RUHqCzol%l7`Poo&big$4WMeeyAGwaUvA90^@*xrrV7hT?0HDevLHy7J#X@=FHBP12(4$+}ennCo?(;beo))y~{y^(#gMz?o*eviv5-hkPD_TZRAigRVn;r5AeYfp$0>=GwUKI(859wbaq$(>6rPCR`xbY24J1e{1t#kCx>@fz379uQxEBgYg=(?0)gU<$KTGIa0{UdQJLSK6uV{^oUu8@nkO8eIR<707fP))bCq@@g(2R@e)E<@YqmU_dCW-?tLN8eOL&$Wd6R-_Qbfofr$lc))VhyWAHfJw;ACKN2Rki_l&ACvVRxK|Z%KDL-cnF5K`vSsuHZqjnT&+H5$+FGb6(>Xr7O8`%fCIrP$_6^I@m2@44g#Yz%sQq8wCF)DUFJVEZ-hxMawxQ0cP&od3&T=+f`=(Lt?16l8{ivPv3gUUNd=_F5Md25-l135ZTk;r%Q0Hvq-^DsFX=)MkNAlk~%6iwHqxByZdC*l#t6DvXyvwq%Pf?jK>gS#?5A{sLFE`oY20nZndYd)fo^n2M^SMiL-2cWai>s)w$h>&5N+|L*%IQHKe0hP9ffox_y^5bu8I9LbEcm(oP7e#h7NjgXRYa-77i!qbxwGL3(@|k@KXMEAN6!vR5%Wi-AL;>ms9U-edbgQXabWy9S@W*r$VuP-)I2U&eSY;j;}P=pgJM%#ZxiqJ)XZmXt5LW7829VtXX3qHBe#qGvKTozKKSkz!1NtoO#Qc@ZkalC{q8YeA&|$2UyMP0(&nvm&u8}HiI*p>#)j#Pv@p=LqEL-1?J+~cs`)M1wU>aMrucuu=*&k%~-HO=G0fYNmMjC2(KPofA0}3>`5W4j0Vp}G1a^D#i5%VdpzX?*5y7x=fR}$0=_%P9Fe$1V*sH1LV)q7nTB>>-$nC>&5kXPIur!*)|=&R{J6Fo<>|8eqMM(ZgykbNn;pQ28XxVft&;0GHdOCIp|j^H?-e0*wTVkqao{~wK<^gRrc=R#n^R5^3X{F>}XZ&ApFmr1IP%V?;t4yHM5eMr2&Wc_&h3e;DxX5IMepw0*KJSaN}>)SJ4)+?oC5xQEhfT42&_0{onj#>UX0*G{ZTIxsf`z4QQRy+{Ex+2dP^SrUX{m-?JO&1*55WU+}AVWDXPYf4XJO~})c<JuhssZEW!8~*gZ~+S@7Tb&j6*qo!qAm=kOuJD$qAS0QFU<)w+-}Qvsa+xubWo7iInG`15m|AptCUSfIN{2iNfi-_$DX_2Q=PV|i@gjbE!j(Ga;K?KPw?=7{`Nio-D9`95;F>e9f0Bk9{++9*0f{?`#T_mf-@rcVF;E*JIH!dJeDjBPwH9QC1IKOEyTU&VU)bYfmiu8SIIV0_5+qNsd6Jjt1PVM-$EE3f+-w*0XpbO_6S%|RYMCz&PZX}e|#VaV8ne>8yNOZ;S-)EY51d|4k<(nVQUA?uC|0@(2OUNmoNEav?K)uyxmh;!i3R=@LolzQyhjXE!~GX8tc!%UHT`ZjFVup{Odb`zq50x@nYmLACYzJv#w(-!`{at7D0$aS=#>3qm8no_aw5XNmlM(GDl$cO!pXFoVG5ud9YxAWIbJtTnKdtH0m4r6?#4U9WH+DHi5&71XC`Qh`Ew>b9Ju38q5eTLO@Fkh3t=nP;(xc#xg(Z`XCFL_b^w2lo2#ByKVFhM>$xqjwxHx3NVKi$(IiCpq3!}+Be7j9iyePCH2#xr){!TqMuJXn~g@bLP5jHf|hg4BX>d|;^xCuR*}-I~EJx6<@nK3HAt_zVLWw>29#C+KU&xa`NbC-I!4{4G-ze)#Cb?Vkk6h-!|@)k`GMH^w&)W$mh`y9}F5VfG%@?kDgHEYh*Z9DvCnT>+cAHM&!jAWe3u3F`@3T%hyNyk&j+|=p|E?1%EbV8*jLPyk+4JTNzStU$qQ38jwxiGJ$o3IUi4Wj8cZ_T%W&&t~5}%!CbME6yII_;;OVAO80BArq_(685yUAz!#m4;)qo9W?1euJU(G#IHTXdu?_6#T`n0`!sE6H?S7Kt%nXdBOh`7>P*D+t#ZWpym_oJ&4A)_W##-vB1)ePuImSFx})K?74$7_Tp0!aDUvmk?m`ijOepKG7Sg389wiJ#gjJ`8h|Rm=&UoNDX0qg@F(*-yNR7@wPt4=Z|>ia-T0R;e%Px&zZN+QTof1K2a_LAbodUIN|!0V#<^lhr=w0Qsf0L>&3igXP$iFXeSF&-woPiZ$Q2yoyB?Pz=lt~cUI1e#eBz6xYT{_6C3Wztvqq=I>x8yNP$&s5}`BI-d0)_V0KSSh|iU@^koMgzKM=ub(|+Md-}kdN<#2S@`^DkD>q0srjG&GIjWzFfvW&$e$9xWVJa7r_ZClYG1NRB61}Q+7(o9{FK8yW#P5G^O8ygPb9`o=(iUej`eGm8(>!^;w#=V9C?xt-pYSI-Bj-xj5^rzrE9>#t_aPZK~n>ve-xEXIed&nW!Mg!A1|=G_d;*EbZ1z<9F2ysz!~;Xve395OCqhMw&$7JB%CYyL;d*4@B!U=~&-BtF2mEwtx>WQ?naQ0so%te-x7|fTyKXq65!R>H`hVU3U&)LQQj&j_YvNKWpMV9@0Ik116SX{wpEH1k9mkm>C+=9?5X;$iKbp8f8B*PDw#JfCF{W{!`qfP@j-}bq`$O0@)v1KNk7M<+kKSWNd>g`K2VbAC;X!57_F`HY>MO+)V-CHE8JqK3LfZbf4DI7Hu{#6KDm2l{7?Vr;Fy1ZPxkRGWfQ-%%Jf|J!f{)%$=|}#kOfA^%&sP}FyA#V|6?*n$b#m$86lS%F+P&tw0)YFu|e^8<-6KujE@#E!85OC1Amv!3{MWmM{?5SwIRVAAkWt-I$?YmrRCEaHgH9KX4gGM{UGwAU&i~-A4#6#Th88cJVuodZ3!P%t^I{M)5wu-ExgBv(Gu6p+SO5Kx=kvX!^vhsQ{Xwrxgn?rKAP?Ek(43y6<59Z`BThm2aW$+{u0K5mw|cDYNjJ6>%=<7utj|hx(qRHqJJ{k|M`oq!}Tk&zmC`r4wSsve(g2Izg^@vsKpie$(+57b!ajd@*<|I^I-q=IHu%mj1Q?-(g>YNJ{QSLaevVBO?=CTc0L@>dzLcxJ*D5)xrdFaN156ALF@u~~nv@k(8MrC;8Oyt%x;dc5)7Mw_Um^_bCXSMtBF72)c7G%18b(4FHaVyB(?ES)>4Zjr}*c-W{6zQ)4(;vZ!-jZsfkHdJN58X1|30yd2{CUy#GBkPU(48zh1e7(Y;U*h_gsUVUAbDbR+`BD@o|ur&uhwEi$d-?f_Wr@RZ7=<0b@m+_rad`#?ARvcq>g=C$AP#D6(z@fDE0p(GyNyNqD;@4&H(7GZySouAW%GoN_L}Y3}p79u{7mQ5$!dLD!utvTUal=Y9Vt&|+UL5>Lrlq_{z3XzwLT7BqC5EBZ6iZ;)`j$F~{dUg8`rf8lL!$-brxzEOd1Qx{A9Mf3OLVlL%^xoNw4HK_R7@N|ON94IYG1BC~t2JYje_lbpY3<9t`NTNpTo;wm9EW`SwEo321U%UC$*}rq5c0H!DU4@#`HfIyw*?Tc}u>>AJt<1SAVX6`X{gS%nf@66YiE&Up}pioYW^~%ULk3ln757g+_~j!P&JO@Ov|OzWxaNYx!b}4wS*J#oR`Ss)8C8Ts2Z!k%32Z=4KYY+B{8=7|TSiX!?1TJ5?A24sgdQ_h-^6*rL+&SOx_d`66A1Y@OdF!Cr(M%DmkMOT-?dgLDU>?-$^JH9tv9fN9XInm`#N&zL6w6aHgTXU!edv%Qq(PE-F9m#7ZxhHhw>g%*0nsBOp(;&!=ojomAM%dKhmj#KCHG}SQ(PL)O;;opFEe;G(QjYBC0GTA}ITnnFl(Z!tx-O`4D6%zFs?D8@+D)kO$+oyA7o*#LvA-i;G)zhzV^y{buUP$e&laY>*zsg80rc=FF*hKV;w1nH4M;<ajAa<`NG29vT)hu25-FAN-XuKOrG^O}6kmpSlqv$~TUi2=&I_jz%LKvQ4z-CTavE4jeAGlqhpca^x4I&?!-5@;Q2Os#m#Hs|E{C;NLM~+m@n$L-ge-`KOSfo(lysq2q(s_^@8QtKaNPhExpA1^R{RG{0w=_8uIC%e|Zp1^mt2i!GHY$6Qlm|8DSI7bn%2_``*&^R;VZY6;*zkxzpi%-Ywy#d6>uFU*5g1=MV!f%Ty1JgrPoMlDk~LJSiK>yW4M7)nb01^_}y?Y&Zu>1Q~iaM=)-wby<9$t9f8NdZy7BiZ7F{P3bc0vxF`^;xv}4@PBpn<@+2MaCi|lZw$s$l1LP9wD{m+QLgm;E5@zEdE4}T7X=X7uAn+J@V`2$YwbqQS3Lt0^Wny`kNI_zkYDirzEWpD9pnPidYc+Y1h+$R@6~voNENyGr1ridva5C2JR2`R?i=K?M}=K?%#MM>5TmBlG7`_J_&$4ha^rpf6=QSlIwdaA9{bAuG0BL@n@?$y=;mT9V~ShB`+F6-9q|7neSl$ea2p!JZaQL8Yzp$Tp)hmPxA`rf26ECS&_!0#P@ZueK5{;4f1g+FP>}X6Zw6Nt9`v4)>+jwnsQGP-*?WaK>xfz=!`Xt|8Tor^t)%ycSH2$_JH-;X@rC@P6C}|1!rr(_z=oRqdlLXZ_;`VkhQDIWs^}^@N?{L*zjt*XG~9m>yDE8BX@sy$_KJtmw11dOpklJ#1?hMD_*VAgseOeF08OT{188vt^e4ri_n>*|BU^1iqEIjgX41^ali?5JHlU3>ank^KJaZ3ADHTc=dD~ZkIz&!8ToTX08Urt-l=_!=iromrJ{xu^C8Y*1>>R(`fZlR?kiG0PKUI;Zkz5E;(anVo)W0}GeA<#@ZwGl{M@1b16i}LWkVUQDpD>F`ArGwZ?PjeFk@lWNbfR=&e6T4-WZ<;P5u_01(d!sX_7LDRi4E7TybEEX&~x~)umgK%`R{tFH-%h(E`*J5ej%dW~r_|4jyScSi(6S*ZEG2TrM!ZiW^+?&d-*Oxp-Z(?Lv6u>b>ZXG3Q?#OKSCMM`Pq8%FhyT+7QKs9B);!Hh08^E#^Snx_ubFgKfmUH{GIK-!X^|M-_Mp~h1mIvCe&X0DlldO&v3?!kp##Q40eLgC74)B~hXf*tYxN}gJG`N?L~1J+yii2DxZK)9o2+N6ybx5YJ%k$cbQLEcpPd%kKIH|6-q6F)sza9Q)D8;#O0PiNbof{sKEkmq0ynq%C|p1gb~B%bG?z}SJl8>p`|pVzFG+$MnYe=fNTwqd`;AbPo{O|cLRIPDojD^LI9r0>{iLT|L%IjLTpgZX{w?JJ{7_A%gwi>9vB8Pr!~eLxD4f3NJ`r*-!!=J8{#yjAyz=lMu!_Sh+tkpGp^*%3_WEB%8ehj^6!M^V{*UoV_vfy3JuIzgrwPn8wF4ljPlfhN1AH?A8oo}_QvT|GY7&Uvj~unFV&VO*EX`^y5+ex-sV#`DztXti%s@?rJJ*Jp3yQD2e!I@fLK;JB<&zI7Ywt9?3oZKroJV06!>Tx7Z~jZ;K-YDe*k_-%jdtRYrdIOR%H~Jr4o{8pFR`MtyZr@6pf;ItxnU^qucg`T>#Wj_3X2i0Vw7Ju&{Z|Hok&jFk>-Nef#;X)v-8)N=pLj5Kv;>z0?5@H&E^^3&qS`a3%X8t={NZekcc`P}9IaoZx$q&m@7Xx#yU5vfWt!6O1wi&yV5J~0vkV=&9hwhgJiUjV{ZV(h5kf}Bf)4KL=0-w_zIvJOcT~@k0ntHPCvqpEJ}Iq;_&E}qE%Ke#(xmu>zT)nlLd*wQV;>lQ+Jt;L%g}Z(BM*S)`+nL{)ISTH-+Io>V?kagPom@!a+j=ed5^|(f%GYfzKz^F$Ct0P|G&O?jc<`lTjcnSe=UFw{)___6SMyDlV@74zdfE0^5-k>FVV{ScR%A2kIA00q{Aj&eN{6>U-5#I-v(MSfL!m1XhB{@zkNw~A{#{S%{0_SW!886<=*B1cY)gI-u;w*g?EqBOq23}7@Zds-9)~gc<^UlWI^%CXP5U)LEZAcpmk@$dydF|Zy{x!C;Za%4X`SA0?a7R%T>Z`(sN#j}^=#U^ayljA?uTI}z=#fU~LgS+jRoWDvt9iQa`)Wh7!E4o0tsx%rQ3Z;tm$nk)bL9HGrRXbS_;26ypS~&|i#qDMN|{AvFCVsi3Ej|f7rCwB{lQ=ZAuz*&(l)rEzKYgJFnRHW2D_Flu9+aj{57Q#p2j_;13lZ(VpK8es8jV~(|W|S!8=>3ee-7239|Ala*7>t!0||GUjGoT!|YjGDS7sDE;KWfeJ3A9eRcD}d!cI?6ME98SE^Ux`jus|c7j4Z8(c<;W!B1}zH0ACNqaYy2d@0Q!5XiKe|+CYtNEm_6nS24t4!EGPCwGT^x_mD=)B$H@K_=E-}il)e4g%5N&~XLy>2GvebVP8p_~reW0cR)o?zaOm$!b&?`Ob+hXHek2Qcps1?{``VOtKg*2jiaQv3l#y8T-&400y+{(ggTv;5}#=VcocT_)AbTU?{;V3JIgViJOuMNW7FTnubXlp-GA79;4bQ@C1JY}$fg9ps-p_=i$DSNMI|KRM8|yD8tsvfC(~CpN%Q4Q|w*5A5tl@#p52G3ldyMmoKMqSte=yP~yp3|+Vfv_E{T=21^$*%Jg!;-ypC?p!?z`%!@ql}tRF9nWXu|fM5#{{Bz%{vE5{ocE>tMb2vuwq5FdY?G*^moPmn$a|{8|>EYG(nw1))lWkPluXI*5&1kk&}K|j4B44SpBuLQ-!kMM+p7LD|3K657aUaxpScHnvGv`A?VwehffDk=aBuX#Qrkjc*UfNij?)MkX6y+KJVuM^V(iF&2ozGJ&Qj*K$Z`FE7fKX<)MyBH8>v=byfh3MRptRUBbVwOv*pDdwM<;M3q|W#UdyBSj~^1!HMG@_lGII^!H1)KNUYihiQX8#+q-Dlll5q83T?Q`mxO^=ljNV4E_@6<$%TorMCY0$cugt)JlBFg+*$K@77pS`rv%nC1*Ftgx*)nmEw;fcir{obP$7CsW=_`%BsyAumK*1dq1#v(fRd3M!)4M%av>!T;(tprs-m{ys9ZYcgbb%Hyfc(=#zT%q2#QayOR4IjWzHfbT`qq?ZJUArYw&PX-a#4R2CjspA3ERV+fI4ci*fy_u-9qR(#c6Hcf!xn<^`?iXX%Hvg+Uqv~ufu&3eP2A94wmv=U+23b_eVN%PdG@y$@TvYt%F#IFy-d*7nUMnqb9^73Q^EV$Y(FnTqaYXLgjy-@DE$PLcgDqsUtmH<+H8UL0n{fE%U1@!Dr7_0o;a1a3aC%ube!@<6&|RLPq|ZHirkM7?317Kf%HAnp!7l39bT&LzD5Y&u6`{Ge2)BK(Ef3=(`hh0Rz7;6G~Q20C2wc%6*{aqa&@xGMdakZX8Ud8`|?!2pQF@wox3Tv^ws1Xh;k=Jh!*7Hij5f>8M$yu{p%0=7)ssL7a1jKS0;R@I~ZtXhWC@bVe6XdhuI=OpHDKVugHGZOU9{!4e=h9(S*!S$AN`NBYu<(RI5L5JUzeGq9=Nm1JlQ9l4Rd@BSbzM2`-62hVGH!1av|0%RQEtb#6O<;TG(`g$%itRA`jp1sIN$W+m!SGH{VcNotT_WW(?&)M)IcS`nORpf=^V!xdT;6caJaG&G=jPu0LEBU^&1u);ceEQ4}l=Z+JH(yVT6+*&Qiw>nI5*Pl-fRw=c^QwQP78+|XHe7WwDukC(=J{`Wq2&7}CIj=gBPH--u1IWPeS&pYh&+c7?Pm<>whRo`ZopQ^N%>%_fv#u$1;QH0C8P{z$ZxFzr&u65!$K&rs_SJH_EriMT>mDt3LN4eExucMlMcR;?HBxj@Zr%ZRP9Y6)SJ2*^{ek*q&Z;B(?~i7HQkHb+{9fegi9Y+(@DyENjqK0HiNhUnX9km{yNk^F#&daX+4X(iM-O-bXnZP=L$A%q~)qWD~q&zpS^6Q*sn{uks7VSp_q#&QxQurX6_3xD@_kq=iA-?!dR>Cnhwr%JrPr;Zh!`F;)8ub#i#Z`h|HfWy;|CL6p%{_UF6MX?Ma{Lpmfw#-Fc(b@FZ`(tVrXg~ZE|7tQ`pIrA?C7^-pd+8gkN0GNz*8cuOd|y)cE}-6jLA6!OCsFFaXPIB`DNkgJ{N!)mqx4@6-1cjt8V|Y;%W+PvrT8+1RJ5)f;DhYQLCKeS$nz$zQhH=3gvGX!k4=9fFK{=q>(0%BlvDmz_PKaJ_hzlXmUoK=8){iTCMx*3zp9OVhl%HztatUyKu*?iW_oAC{vhplr8;EnWiIn~I?eK^{5Cb+Lp?Y>IUS7d(~18X*r@1Nx;)F-kBLzdZ=bD?fC^F-SvnI3AS@Eu{F1=GxXRj;y1>eTzfC?@{{ic-3_TpB%%0yC-^{d|i+Cx!rR``Lv_ipu8sJ$l!bA9;6|bLN0tvTdlQ?a-WB`Z!*a0&x6skPEOfij`#DnyUn_292>gim@O7Rk)NGWm=d~;D>`TWDT7k4J}qTR-F`k4DYYg&UyS@LZ+b?Dfpv{81#+kdOn&YxzwMe0(xgy)kLxYk_PuAn>gI~hDHj%D-Y5O^R_QQ-Em5F2Ga1kK`DojPx$I#BuP>r}dm8Gi=3k3AYi@GE-bwZPy-yMUc=+6@i?lBCp|hcEU{6-~KTe(_F0L1VH<3tYHKOjy?dp$srNH?5o=LR=$?o%LH=&|8F$brK^54oprK?4IeM7i7$MGagJDhD_GNs2l*#z?8|JCljoPNNeY1MGub?dabB|JbKZ4(A#AN@Gy2Pr|7p%LO!%7#Pb;*p)67s`g~`>%`z#~!#FkY3_Y@sP_HF-~L5IowTZc2R8KmJQ^SW8g&tQKD0ZT2auU&xHu8@6o<5yQP!`>^)fd?PZr-k-f@X??s9_urdo+_nQ*5sZM94z>X1V#9~xU~(%`x6YoqOj$eA}%yH=&pA$WXmRq8e5#BEEyCGyI`o!uVA;mGMZHFK1R?>oBchvW`d^ch9R?qzUcrX)I%U1^S*{GMY9~DoC(4fKX@Y-`mmB>lmshdoPb5e^gwR9q1Y`0;1{<>^OHnU*y<#a(8DNY0t^eGDJS}MACEq-rC~w|(r>u`1HV>>{^RK*Q3E9rutwZ1NoG=*-2Nf(BbOh6)&E>LVnT1Z{;;3;`d!)vuP8>ceGG?U&f$LF4Wo?=P}%o%b!*B*Wb^C#Z^(QqXfwJ4GBLkeaeQ5Ly}G#zoH*I>2I4J#)Ac6`<(N%QAb^K3HR3}=0_7MIzFAUqnyhNw&#yKAr$SewfiC8#yPcXoJb*W2el)kI&sc%FC&T)WBB%JUA<_QA;ciM@I_XRGxrYlGv0wI@N>ldT*2$VLE#!k*{_&_y4#-JAd4*pB$aY>SrJaEMZ{LQPGwZUzrTvh5i4oq9f90GRuAVgb+R4#cbdRDBCuL;&SJC0_Go$#e)_6bVoLhm?Te4x%MTL(BuaL{^^q#VW&{qp?U2bYThMzlo52uYI%>=TZE@3?CC{bVFrEK`_zsY;}BE`=tyMgxOBo}Nf&7PD~*0spG^cQ}7IC{l!Rf;=uvL59SO90yrXC+VNAg2W+6-;=V35Fm0pI%&zdSHh6$Mp{sX+XS=KAL%`2PP9j*)5t5`SYg^f4Gf$An9`RkNw1RV4D0uu(}!Zz7FSfrJr~%kp6J*KcK$iMCmFl8~5LNhiMf5Ppy_KZ`SCuK~r}mJvagP2P10cT9!m|;b_B|=I7f{cWt>Q>uhI`QrL{83sgXS_t{x(1BF`hSCcSgVTV8hJ(KC`Ys)T?CMua!@@P|q@8z4pR5+jKhon#173B>I-V+#1wf%tFZ<#jOHxo9cQjH+5J8L3GDi#7kA53FLfNmrIFr_t1UbWi~uWX2*nSBA-#Jl;JRg2QO|1dd;Qi+ow_AOj{rE!R+c3o9=VSNqv(uNeBl|)GZ36tSe5b4!6~e%!H|>TgAt!qP{9Dv`^gMm<4@zR?b`4fO^Sc$KECVo9SRGec+}05#*}-%vHT)v*DQT_gWiSJQqpYS6q_Lg@Li78n1CsU)^e6yyemcCXn-t&D)Ug4>M5+C}IP7zV@dia>u34tM^&)VD_W7rKa~$M}=BG$z^@x!xRIapq)+emy4L8;j>BzAIAD63}hp3eigen`*ZlBc=CdI}KX+waV7$>lPL5yCTzH^f)@DeSP#&#qufZT7AR1axJEG5KQliXlX{itT*=acp{HhWX-iY_<_=gF{mUyn|Pito3DN8D}j1xUCRkEqfJaWVjjr(N?GrkmDQviS;>a_`+L8C)Wg5;(o(zsWe*Q3RUK*uDeGV#9Bj->Bm^SgzZ`4i@s3!geDqD)*X=Y(S4e>lX)W)3?^UV6kxs$YH|2AZa`V3CaL|zfu#J*@n=&K6zF`Q?}f2w?YdRHnNY$YE{+A5%4TDR9ayL@ymyp~O^@!d?>H+(Nl*}0YpWId7P8RRR72}uK?H|z`Cjb0TazjkWPNB$ZftjI|eKhs00lmGVV{IOm>&xL4D@v6winKOr?ugHE0P7ZVkJ!F&qwFbGShvdyW6SHBDU5k1XWqmB@^w9_V{^r27gMFLIf|38)(OdaZg9&6G7@sEOYW9v+;iuT(|Gdg2N|~}BXKOIaU;KaiS?r?tWd6MWiE)+TFhbAcp6SBT2~p6)*hZ68T7Hh2n=jHTb#fht?%88_5#A@6x*X_s(xUJ*FO}Lsgk`x5ibR*0POc2<6Aj6YOPhvsU`E*~Kg|=A^K?Ch?6P)W*C>_0{HF*!$P-aIpvKrI33{I&qu%pd&t<^R+zUA3u3W(Xh%#02hZlq>`hMlfHig%9(IRA;rqR8}o9BMAL-`zbuf>JgFl;6Zxp73yTl^rUBX4I?xF9RpI>3(^uj_gan9fVL?a;z_T2x;>=+Ko1qYW-BU&g|CYNrg-!j`eY^zwwoX0E8CCXMJY(lWUaajy5plpu^V=ynu+jpB>y@d}4f$JVnMVf-5c2)MkLX7LDlUh61M4Us4E`@a=5n4ymHQtpnq@0bNfO{>Gyc$9T2yN`R1eWbxm^;3as$D>b|<)X3c#uhRlo=%UF--kNthOF#RTxpJ|{yFRx>ZOO$GP{y~<-w9^H&>sg>;s;hzLl?Xhz)PveF*yv!HeUlyl31kdyVMf!#D13muO&<&kHa*Q@kjXF&9P>&j*t>Y|v{X2nCq{ECn>4;xk>FEywRt5jeD*`K7X1@+Gt4Y4Zwcs3Xs)yKDmBTq7$;Mt|l0~?o<7L!aVK39P(?%3yiSgmkHb?SWNW0X8Tbj=V#O)zBm%to$z`;jyEa|TpicB;2Ii#p`PTKAA1i!8X_efq^U7s`5+SMG}wuV_H_5sd)kWWDsr4F(L2t@CW3hCKDWyRl_`j%Zy`rytMpg@qNkRTJ|CnWRwd&vnSjb4L-mY*9boyLrfU7mMFk*~kO_ibbk#<0(ENUr!dt5AeaRIKtC};wLuO`uE9>#X{KkwZrIpDE1}H8(BCa_B{jiCbfBIr&D~r7~!+7ZOwxG_05MTbCK&Fk$rmQJqWxQ^kj9E2Pyrvt0uF(8a5H%cTK)(z)$2y9;N@z9puB~i_Xd+zmd276?2zgA_TIZ$(Rwme&pkw6?IaX;2|}V5$com@9)X;@(~BJM7}ZSGmw+(0D2=dQ6I(_ir-XP@6V%RwG5czWl;NR6s4cwomC?itvL{5yQ|$}DWz}D$iB}ERVK`>a^J1I2RYd%U~L*3j%jZ4^*@Qc%5CuPt3^C8YWVs0T`KY|(#56xmwb>^2%TJzjlBKT8v`?CAUu*R-^cZl0H;Ea&$-;s{cKOQh)V#OoZ6wXAFpR7FS47M%}Vub!&Z3M-I%X-?_B@5OQ)HT(8K4KH65>GK#;!$+jaOM~AUtS9IWxfp^HYG>)Zr|KW=IL!FaDom1bCb>Ri_U>@4@SnJ`t6)ELd&nQld@SuO!k%Zm%XCdP@GDU&2JL(9*B{^#cRmKYg-!Ev3Hz{cTIa$Y;oR|S*-|sy~F~6rv>{)&HcP6}Cm*2bF7W1{Kprg6@Dh*a2dMS)qh3iqtVBXh!lmWid1Nk=daKBIW;hwFZ19E`u_m!=UdZ}<>bYD9!59XZ`_WK1#{NsO<#eU_FWy5H$riADu#dG^KH)-2agQ!W~7Zth(WzHVY#15XJ;mmeZ^(6Q7<*GTzl`(DH<%eGM1lvgmUiBS53l`ct0n9Tu67gih7AzykYsVQ#m3%+}?@0$a#*zXqBgV&{Ou$N1dBVSG9m>bw+z^8(Y@5w5tql7Nb@jjKAz`A~K+3rKAm)NsXd!l@4pjTY7GMIz9D8_Ks0rI?|vuaRe%xBay?avRJNhT8Wqs;WYv8#})N6HpQj^x3zPxVKJuTlEfq>RYQMzcYB;uXgglyj+?Wtshfgx+wHd2M3fit%^oN#j;^@L_sQ{(bdw%6cHj&Frs&5ZVv9o9uatoa}S695Uchr{D6Hm#BYs$c=Jj-OL2CKZ)y6ieIi(^Dhl|8d&^M5B=Ut(Jc&}>9>jRt9;?!?@MmD9~U`M&2DZwp`VSbXwIKeuaf&{(!}_j)FS1&B@%tT$n(iQ#ccSp>37LxZTx%ke99;f9<2FtRoj~4cM*4NLzPfc0E(X+6c4>eeS1PxZH=|D5XgCq4(0F3bL;aBGhqEd60}it&hi@7c@uABit>U{5=FOo|2W>@L4($Z^?$$-d5iR;@6yEce7bu?=FA-A;zLb&-NgJz<#5#L1HI^*`hDk*he_H@cz#Ug{O>|Mr&%2uKKo1?8)PJ(cFZ}CoLr|qpTvXR=_`Bp`ywAVQ)=nBSpv{?`_9U6MXn)yVm;(2gva@_FHUpA&sFw+v8d8K0~S2V8#w2P`eaK{wB4k;nUL_9lQz$V;*a|AarMbS8kic{H>e$^^rybUwo&(Ez{N#|54guDKC7bw{iAQ>z_ZWMelcOl?+6Yy*6TANq_*m0X(Z|&@|4jEV|E{w%ZQQHaj!ZbV$@|WZK;*@p_fIs((|~!oV6rs>`Gp<9#*5A{Aj`OGqZmbZk-o`Z6**9>(06<4PvoRujqOS%JZQG6*QWH-$$Xk#+4zhN6^#82#>gtTe77<5Dd2u0cksxi1Dk{*Ka=Xk$j7T6`V$|U0qJ8hOO9!yUaDDNaORnK7TA>3wS`dDudcOC&z>(J-ruDg%Li{Gzx29y@vn3S9Q|lw79fqfg^|&|DdIs6Ftz>S&s!spRy{s_j2;u*Q(t+NpG8jkg|-pzZ}p@nRk=4PIxTUw!+RSZe9Eu0xZHr8?0*^bi4QwY>J_pcBIhTb?`)kTg!+UeC&}Ab&(FQKK+5KJ28fr>T;uat3sHVwtGVUC?=z`)?~y)`1x=%4c3zakzwb1z`2Jji4u=n0Z0b&|`;adu62_CZ9Jt9%k-xE>(l_u?Ypv^eCJglzS^VZ9C(kX@?AdVhePf8nSL8~a>-v0ea^Z5u=_7kpP%mjMkg4m4;=_US)=OeFkynS?-WTKuAl_U+yFBy%`eGTYq{FjkYRqYSF~8@V9K5WimI?N~XCsFw_2*gZq|>epWQppHgAH-rNjBYg?#dB5j9u#`cETFhmrmEb?=4@N12awB*Z<5xz0}5iIJP%A??3+{2h>00^Y%rK4Oab@k8(6oFFjeISF|pM3t=aGKbRMV{Nod>mE2m6@kQrT8tm}z3r%$N(=Q3&uPM{P@QydBB_@|>U7_5aso8UypbBvkOi(umz&#OqyAiX((;#K4|UX?F|ESM`Z-|BKNpZFz<5fe`t)nv%mXjqq)%1}sDA=gI<6&I6Yp<}W9xyp80YO7Q%`<=!-aNwmf%S_atdm_z-t5>zM%bPA-}&{|fo2&pnTpxTQhOUcJy$N~oih-!6aosW}5oa^808JEM-WIQv7@DL)H(O5F}ruqo?HT?;q&KcT~Pm7lx%exWWR>-SpL+CwF%2T7&v(i`liX&p|ZJC(mj{^)C~cr~G~A}6`D8Oq@2lKtsFE*C<`S*v6v$~q*u{#>G+2I?d7w~Y>=E)sOEfz5>(u<)pGf`>kGceywIPU%@-zJC8lT`A=HF0B{zAJUJO^Coh||vUkO%J{CuaIPPvi@#n1KBAiZ-vU_u1enA#?xsNy>GCAAMb!$b;>ca(+&c$lXJJG1e;zpvEy$W8o##QDnW>aWf&zv#`;bAVf}{qck&11EWuKEy^kVkvsR~-ko$W1Aff6Jh^Wla`HU#C{`8_X~4JX2=d%lRoYM5=#Vd^r}a4)^$fXw{oW==REOprgZ!~yZgz_}6CV331h2Y4=^NPJE_avszU4ip32Kx+I1xUk7p>0oVB*G#vd5{&jpH~6GbRgQ$Wi_mFBPw!>ZO$R$wUa|*L%KPy@Y&lhhtPsY#JEYgKL3%*1zk_A%xhwo(xFI{9?kV_tv}}fQFZ3wQ2p=!FSJ^s4K0>PWJyv~;+7>Ug^(puqLLJ8u~e4q3L*P8hB0Q0EtSerDHW1J$sV#)Qk0bRn=|k4r~CZ+r|WuL=Q=azoN->y*S$P%E0WJ=z}8l^**}0*OTH@hp57(@@uj={aM>xkvsib{r>848W3?f-3Q1Q-JXB=LJOVaS1B?R^~uN@2OoPYCYVznzIB#G{*qma`_ocnLyU$<7ae^}nViXtHLQSYWn{fxGg3gT1gK=`}AC)N4Sh*~7m6p;x**Pqe(PviLqrWV&28fO8~FJ3{avpQRIIN8S_8;%}{x~IGcbrJJw(W2RIG$7{P4Kt7vc@tJS9pX|JdA}v;D4@(+EGf=}@vNTM=vAnT{4MOC-o4C%s4Ew@YO5eWKVErYzf&Q{mnKIVxhPY;`J6XfZ=Nkl#kxP;z6FFT2GC!!8&byEhM@vC)EjKH|lypx;b53}{gX!dA^)l>g}d_kG0tH>WJ5d9X>>rqGT^cmrix1~W}6{DZUgF1(pXS%wB4xIX8l3v;$Lt|PvGC?Nq_Uv;}$cf(*y^{r2>kq7~ia{N9p8eu3Oe%!AHlKd9KE?C*lvrlA_dSd|N%L{vQ0=5bs{fQrpMB`Rz1^mGp4>Bfa&FJr`uXHO4FMC>Z*r2B=8JlZAisRC`GZXSom=zNMl|4^n;#t6P0~>XR!V2M^WfIbLiGa$$TvkPZAyK}gb}afVS;7I9Y&Qu2RIkN=4R`J<|*X7r8%D5UkhRL*XC=KllZwA4~3{I{Kar##}j9V8TkDPKmXBBDKMn#Pv2yZdTH$HU>d(x2E0(CcyF3QeM0!NRqmw#vHpi9A>XxiV|*=x3cFVQme^{5I!An$_}xN18uZ-k)+-Re<1JTie&xoO2U<_sOQ}CmFA@HmGuoL@>^raBnGcVjnZvh2ovk;dTBVu}kopUV`F(?Piy%v?Y-&yh^3S(;>*HjK;f;#uwP4a*OTr%V+{+YD+b1bTe}_8c5#QA{ch_YAebGx@^>XBOugfS*ZMNRf)`wYCpH=RQ>t;aa|m8i6*`I=G{zC(pa~otqA#md1~{*RM5BSIF@LgYpV)*{ur=GGGb>LR>ile$cDez81AV5e7b;~_Hd*-@L8DKVZLSq4GuA&<=yvEB0GPb0Xhui)T^6YljcVYiF}lzGT~6O91&njZy`EGY3GOU}Tv1a!$&;wB*xR46UlT=eu4}!<$N`cbGyhh!H6#@-|D60%M2b@__wQA)@Xh#d{dz{44_LKX>YWb-W=`$P(^x^8N2BqhWbR!m5dD1lq3EG({DM}yw*9~XM^kU!&&*85gNhl|?0^P=7%C;Hwaotdy(eSE3b81m$S5TCu1EC}Nsoai4%o+ZvtyTB@hXX1Ps6FsE*`Byo^J0BIny3WY9FO|sE(;9q}_|hPd*OMpxFzTqwdzt%;?qxu3{~Xrc=g7x{en0J}Q#gIQxyqq&lGOR1vao$@reWRWQMxDEMnbw^i$Y&sY$-@&Y3h`Oa^>gTTBHB9Jl-aI=(3HiRk`%gY3u{eI?NhDr5;xVA-Q3$T@B3^edMt-JsFl9qP5pdzO4_Y@5#|P{e7<0r2fIpFLhS>(P1=5b*;n<)J0Q|U7l_4VQ~CT^GIJT%=@2zs~eUO(bNzJdLZ@B!OC``agflK-l`hv%7Nda0n*^QmRwrT@jFy0v`RC%EUI0e%t?B*4UY)M&f+9X|GcNq*s?rkC^m|8c^%*7O4vPKpITxL<`jhv?@LwW4wS#_u$sF52tqAw}(^!(dR(r<)qciT9GP9h1`^bf*#dx^BmyKMz@u7l-Qyf0GKfc;+H+UIoV0qcM9sBW!*?7O~|$0=YXvWga|fx3mrZ>@Vyg)5hZRD+hF&hZ?)XLHDc1`{(4PCm3iUBryGJwEx94!#DJ7q=}#K6L2V*>5pSXgolRUU~vK<@K2BZh-c1_WJv7nNS2b3-yeR=d-^@im9A=6F)W~zxR3j8Gg2&JR^Ul`NAjEMSLF$qSg!K!EF9Ni&EYqAGy)z`?->Ry;=_*drc!J=5m$pEP&wkLtpeP@%+LWCpWHnQ3!;ujK&+}H7Q3wakmsf>4VTgwUhY$zqW2sSD%vtI~&FqE;@=j$deX#{mn(yFQO+nV6@tx39Z&CK{Qk89Ul-_nEdtFOnjVe%$b+~gt*Tb0z$v+b@Uw?dhqz}wwH_Nyhwa1Xew4c*7c#qQS1M0|pbvRYdKpjQQIZf**gvAG#xqc)b)6IX}n7uzbbTT6KEoqMAZO>k+;Mo)~$kCxS&?x_SN_gdGLx~JnJ?E42w-)4GY85}43@PyUWnIh|59*e{#9Nm;Zc>5p^C*!={^-tf-R11-J@efm#>{}^bJd`y!irJ66W!cWp=7mhS6K9valEk?jE^_N^EP$)h+IPMgqK?X5x>F{mvJl*-Wft#TkH?G5OU;%K>qly_r1+js691&Re%a>ZMc=E4k)-(UWM3hTA`yOu>GXD=_ujM;y`MBmfwyU5p6>aB4Yrh}aVU-Z3t%J!hNeh!{e)%qWo!LckJLDceC%0RkAFN1bePj~&$J`YNlmJCJoMlE!A%V09`k}bFC8d?r=EYs2b@XqEB3n2XP5?TIjlP~6m`_)iEGPhKV?ADtamHDNPg`0u^E*aA1ItTTzhwte79mmcx3pq!GOl{5r{*+uv6@cff)_bJ~`>%eujLHtZr3L9vvR9;90q(7x@HB`=IGG11`QSvC8g3-g8^>iOyCQ5dBZxRmg=ew=Lq4D}=!x*PrBuBbRwPH&<1Rt*>ILudmfd{{FxtzHM14@ZwK%uh@+L>5y)YucoYR27K9ExS}T%<57<6jpeUI3M6#I1h01X{dc^cVtu~gA1ZvfFpIM0Eb5|W+tyi99yI89-Mo@l7Wtr3Xo>qE9ctFyzb^d;xvsK+Qn@}8hXvW@Y-azknr@+<*&GY}zVD=R^1Ram$d5CwKb?Jw2IX$13BsQ-9(81E*WUU+bRhcj9gOk#a*^kuFHSST@oCZbPxAP=$Iqm+rIfNDNIYe)?J?9*0)lmo`|S&1V8(+L7klyhJEhmiuGvupPDDeXAL_;zro}1M!O774Lb7m|5^{d*p=w^0zG%h-5_D&ijG-hnQD7Tup_jch%1>mLOlNeqUlI`|oGX+smo)G~`5_XOJ%s)H+v+$~Pj<(`~g`cAdTd?LQFat$?3P^mo<0XMwQcy+*Y{yd8CknYakfjpw;VZK1f6H>H!u8(eDZjE^4=}UP`bCqL538Mx}A`|eAqJ`=3hxY{8$_L)L->O&MPUfam_lFL!`J9QMa_SgbLxRUj-x@kmucT3r{>k1JQv~+oPW#&)uXhv~5WqbSwQnD?C8*UsX+;n?%e}aDRB^fh>M*L5bvF>J$q`&dbi%y+YDm3UcR9g%rYE@trrTzasxGpSs}V=^`L}E1M6az9ROw-=velVSbBxxF^Pi#Hh5V>mAY|vRnW8Qqr8D4yj~D%R&mr&*$_OJf83aT$4wI`ntM0K6yOe{%oJY?SnKpe|N09m&EU{`q}k-Q630It;HJ;)zC`Tk|CPa&)dd$#i05{Ylpj<~bnv9zW$Tq`IdiTqM?Q0m4wv8M?uqY1zTR#u?};lDPAu@wl>O%$->qdGFkvoP#^UseA1_B9_)2*D9`^b>*J|l*g)}@5Q4g1@Uj$EnDto(KME>~svA*6dDKP#pmG{I$)K{-I#+-VwIs*t_ijbcqUsEOZfG$T0=q2~I+exEt=}TjcKqD2b{UdybwUN8cT0DG+z5Y^kcZq#5BJ~O0h`l$_LI>jc59%UsiQsd8qsaspo7h%mdDKxFDi+BN7g!vBdkQ!5ys~!tV;Y4JI={KTo?LIg>R8=N_WFD5W4Ham8_3Hx$MIDSviE~tBGw%>q&a{Idp-u8%7B9h@?PbTd^m}G%+DkWSm@n(b^%B}oSB#XZP@xs_t)o-#z#oHi?yT2nXRwdRJs*5x{>@DjQ<22yF~}}^6&{MC*SONC!4_iPK|P)7y&yevtq%76=A*$QK%enUe4mo!u0N%q>4&z7TZIqazVt#N)f2+KPw=W8Qx`S92Ls4)$ex=tE6?XgWqRY{={;{@&c&&s*^36Nb-|^BNS{|RtVF+b7ns!`E>1KKd9E*DNxtIZ!~!b^MLDLbX`%olmUO*U&dZMkGkcE*kr)wY6`rx-#6g)-TxoIU(7pOO)ML9tLy1JoyZ4Nd2cej*y|BdkYs8EFMyoz87yS$NuqA;)-e)i3-j_O`hR*u0YCTmjm@?K0!)xnVZJxgMO~y35H!7hF$>tQ#r@?8=;v_HH(vD8`vOqg@T*aRG@s~#fMf2S`-MRCXDif@>hn!Kx4w@~hNATaQm&+WDs%RW@ZyXNpzxWmUt*42XWzMB$DJsgIZ98&kcS6PtT;AE1)*uZmj+8n`MAJydrDks;1M^%%2GofytMU2C3`<$yu5ixFc5j-6<*IK875@3-})jsjy&+<)=>M6EErs}cbkeg)`JoLb?!Wcoce@uKCB-j>U()!7Q&kKbD0rY$QP`2Tlr{PGV~yd-HZW{P{kgS4kQ9ZM{VPyX^gb?Hk9R1-!`Zj&NP-Z=pgKvun2k5Av?6K7G$)G@z%eElFHPs@H0?{LSd2L*2Z0ea5?y%gLPb-MoPbGlPw@E#gT2S9Ox~(j9C)Sw>@=_>7#pexTh%;J^9Z>ASIh?3{}FPOo=`@TYS4sU!orQ-;cP`RZgiNe{TMX^wH86|$pyI@8i2S-q@ly#{jXv{zt<76sz3ZEkp~jQO~i+qv{<^;C{8+(CIfo_L?c9sVyK%cY7ud2r0+Mh_jrLk@p)GC=-hGTB&Jg$XgHFF${G!1HtdV_)xzc(;97fp~o3<~a@H{DmA}P$^QsVd&hytN7U0`;o!mdi;V^SN14je1~B&Se|N{pG@i>d~f9+@$ybO5OZS7NWKkk1=*jdPXWrEUZasb87(S%L{63l%;4NcB{Nzs>FqEGS42>P(A79yO5{XU<&+k5YN1vajIz**}A=b}tG!b$u5vARpFPJH0oDeZ3KPTl8mOoJZrtZQCfW3{XEYT5)$NsqZgq`Ju*x6o}iQ_Ha9?o{Ifvn?P@+!kUcG!e?uczxAE#R&PlIBCcs9j=ZY={bSQdbRhb5y5?g%ig<5+OpD6!$+ULgQF9cYex-X|^lz-=0Wkzq6Z!ds9S4wQMvXHB*L{637DFlIIL-U<{kgsIKrdg?^z$}+JQu^wsb9OzQvn^{Yd;cpF{`-^-@`($QE1iP>^O@Ot8u^K};SZ-jQb8~}>D*=yY2WR{IA{o1XMIS4)Z*3`oh%F3Vp?s*hqw?NCX{=lC%u)uUeen#Nr_&!zxUTw5i@{7_%Dgrn`{S^W^NjK|xtH&_wrsStHS=W#9{>X|AV3GJeW3|LTlQY3H-@*{DtHpG3Vz^5fk+r`b0*LgmvP*|A_VG=JMdG1I4RD0frS$k5w~h!n0!ua?U)D3k>iUI$6`+g1Sg~M`YI{%Y1k}IjT?=f}HTH{m93@UXklDR_jUqjB>2Ck%onkYM7ko-Guio-(*3fWlS=sKG6Lz>YvY!ZO6R_(_u#V)UTcb|9@Qkimy-R77DBh^o)FMkNm?&l_}wC?EPTEt~`q{w@`kjA)BKd-fcC41l0vO*$3>J93v6?!epuCFKr^QvtPTCu3F2p{{*&q;84C}GSc4E0Z+azdqwZ8{M1VV-s1@vQrOm#ybeK+%iFH4=i{`51TM*HcvB-u|(NmsIbx?af3_?&};N^sl89o`1Ido>EsaIt;$mUad3>^_9<&GtGQj47j_{Z}=c-K90uHHfpg#J}4fH@6o!B`s&<9&*$IXv*1tqBcEs7r22dpvEbt>g`D?c4XMx0_sABHohOqxasGXqNxoj`5noL{r@@w5h3$H61dhOFm4Pko-dBt{2=lVQ}gS{GTAdT$!Ngsh`jBx91_vd1NlTQWiL~0Qx32{b}t)UL|v)NqBo9aOUE=qrUp`xA%(S$|UI8IJm2TRA==m_^tg+dKwUZGb7c=H#}?$FnE{={JCmbIa$a#b%A(Up}&BMRg8bjDC4z18ELmVBGw*DzbDaeC(R;IEtKztFN_Tz1dIF8p3*x}Uyc3ElUl=<1Sbc6)4!7PZc@rEYW6qM!0&=><&0Y7&c8nS?z)=^XAGOqmE1&bHI-AiOp6LBRUX#Dq&(n8{g1itt8&0v@A5GV7IMMaY2K0S=etohX--Bt@*OKz?yt3Cz#PwQ39+w{H%qELTD>nHl>SQoar%y&Q~$}n-Zx9r;_s63gDVbtJEgMUSBG~+=4>I==M(c&d^M7wdj4%6X&2NXqZRBQ;Jq{mUEM$O`#ACqofcl^PcmUcsMmuD2U2}hr0W$UT`DkpR!vmf{Qq_GuPSoj*XNH_lO`m;tgiy2bt~yG@3F;89zE1c-EHGXyNno+D!66PYcr|eF#chHrfxpi7X^iTYWl!l6@#4a63aj(=o7?VOziL>-y>3(7zKxoo%5L&0?TbZo`&UQ&K=O+Z#3e}5*l`)%o8-;CUNOSCugkvAoqjFngBz~2L^M|5u?KNlgd#1f(d1W$f*|2OxrTdT}mklR*`0sV>bk2ak}PWTiU$>f8@oqnlSBRo&-56M%0Z7fcGsgDeDr=NS(6ch_NKA-8+==XJ?f8G^aNCs=7;C>G398*D!ij~pnAY`(;^RzIj4(gd&o5w=-`kNE`X8tnLeB`or`vey%$jo$hPUJ;CFHGEF>7yJlVQ(0&j-bx*kWyItYX+U;>y<=`o0)GoA$LrK0eOxmE`E(bZX|eC{K6Cyf;YzLwVI&53O#Uob})m*sVB@{h{qFtQWqB$!h=ZXx3^!Tjy3BObnBf;295EK{BeFfU#&g=*Wg_1|pv5Bql+@`>6t^0V2WN9^kpFCsraozU{4HV=~Nf|05!qG*7lYdCP>)5SvP}}5AFC!tyrwg0&Y#M2nk>0XD)xgQsT;iGVOYR!?x*^QpZDHx3tM|zQ#9({8p@O3sUt*B_3<&Wo)JEtmOv>+EYX_T9uBl$D9sgE(DrSjmAnv2bNE$T5MuCZ!16K=8^-81&1?s8maq$E(94=S~3JU3>d?ke78cIxrE0$6*EyWqzioYN=6yjmo6B>|34J(M@Rin?h0RQ#W13sX7!?#E2b)48nLAUrsd0p96(+p|ddyR`Xt2K*edIQ@Xv#7TbXHHVZN8nR*c3Qvh|0mxU+_KSNYo(mVXHrn0Yi=Ru>owRMwgWvltl2nhQ9&>j-nvkT-gpX0lJwdlnkMRwS3JUb+!w;{C8t)aTy95FoTGk&a04}AcHyp#!N8-NqNL}@U1faYMN!-?o`p086S92FD1;Rt?Yno3XC)N?3`V4rKu{+C(l)n?@u@K-l%>v@RJF*mc-KQ~;)R)=t{rHkUCMw7;megN;u#WwEtx4N<{yg%Bm2;Q9w#$Qnz!=qn4&=o8(QV3v@_jQW?pveo@={y6Sd)(h3)U#7wsay_RnWIB2`>P{cULvf9Y@{eH?RHf@8)>WH5#8ZAn7Q=?`Z+_qbzv#)aq^TH0Jxd_Fj$u(VPv(pHPNeNZhG%#A8A;7v^58y)%zAS4da5>2`!i9{dRkoh@ffs;3$=EiyUD1Wq4q9CC*espc*j7Vyke@nH5L@0nLV-JVkbA^xKKPH#lrC45JtC894L_U=Egpx=hNMJIY>p!#YGaOP}~>eXY!f-Gp&8601x(5o|R7yVlKwjCbl+0A}mZPc1x_yzfkM9y&UDF`?h#yx*${8(L!0N|=bENuUAt9O0Dtb&4dRv|FON7}R;rNz{N0LCgQPgmwF7F|%y%h3_~6FdAwMc$sL1TgfTywz_ouXx6F$opr?S9WLGN4nD$<ABe(h^6m-Zg7dqyKhgohzK0QBC-iG~r4HaW|kIecX@7DVIw&Cz`S0=o!igXTniFzsiarK87F%~pb+Wz28M$W~*>8wC}0W{sN8*)F6+&jx6!IhTC@sl~X5!dB8>>p6zqBNLJ)b_a`k6eOJW5UTklQWmIX(93pO$mZo)mfbSYW`u=ImCOGXH^amb7^dfk*^+}m2Pn;7l_Ar-WB=$^!$LV^LY^E_@H`+G;+e{VW$O?Gj~|98TArTANl8RJ_yF?*Ts^2SqXjVai)NiceC4uT*}|=v}ke?jLdQhz(WS(ee5lrP8Ct&&`Cyg%l|J19C^MdXvwa-z+ncaWHT2A6$i8B4UQf!$vHzSi=2oPG-kU)22odBFiaeW@c_?6QP&G*Ti~47yebl(&dMaG7pV1T0fc)*9Y1^X~Iba^Lw65(lWGs@K>Xne4W7iw%_|LZ@EAL2n0;Ze+oq&`a&gKLNgw^$CWxG<1hZ>iB5Olv<@W0Zz(=*i^D$uIN_V)Yo7tP6rZ~os~}&=UHr!3B?SUD{QNy@A)d!+Y3AGa>$BlovCLBS-`Ef6bU%MQ?-Y$w?@`x@dW`V-Z}g=@kN4$(TOt1c_!(dOYcH%B;A+}v*>)7;U0b}SI%iKaVKTsPK+_!ahL^5NYj?Y_AfR0@VU-TXwPZ|_>KD1)fD}_ZdF`{P$F`Sz?9AJe40}qKIvsk3=c$Vqw*R{_1NPSU&vv+ueEzXjE~j%SFu#0Sdb$-kQ9m&%mJMdrL(<7fc>dsDwr{=MX&|<2Y1T+3sUNU=)Zg+t9a1xl1S*wCaWnmM*;mgqz?Zk!G4UblE@Ho}Dv=N2xuKc|k7K-x|L@T3;_EEXin@QsU>52tqVFTEB@WK*dw!xn0OMM6gFmiYlqPX}6s;7H$7~#y^lC}x^c|>@;$yMLp7lxwQQ-Ryk=Y6hkVmgEeB&XM4V8x|+ROGJzwy#`;TI3~^NrIk?IHCEuGT#7zcG`}@v8??AL7u(-V+5^86armrFym#`8V0P(Uh(1>x~dFcz+S~)qeI1sh`CHV*X_7GSpW@K6I5|9K>7byuZdo{UfV*z(UeF30ywX{?=I{*K_#%g)b!?o`mRTHm^p0VC4+A1s)X8pj030hf6QgjLFD7|g!^~@|2nSCDGb=7W7bn3f;vi$wf6U>UHRaZt)P?Qg?y>A(O63b3;JI>*f_N#zuq99W_>vhYIjYqX&~v76MS1FJ)Dw2wM>LNyaM%1$k=Hv?!zFzf(#|m2yB7Y+M`D-y>HguO~J<&Bn{%3KG-wtmY3_N|lPKU&=&QEdiE}%oZ!;sE^4aq5#Z!u7|}()GcS(3zt|h1&IFLTMXnJ+YsSwsF+YY*5!&i%1>)*>eOW#l=T{2I-!o7s9Vs?r^8C--!pHy@jUtMymj*v84zx|z3^@e&V|%*S8?Ok%?E2gNygSfhOy|ejz^mXA6S@Q!B(3e;h(i_$-adWrIEUs_JrOB21I|sb$q`k*P(_E3LJ2AGuw0@c_pt+$r7DxaA=mOyXZ~wc?hG4xdqa|Vf6>Ao^=?Hs&U$pclib#{2Ke~%epa7I@EH)YlbTWnp#5a%_31RmD3FZd-(F?{iifBNz7c%SDx|6H2mo&W>yPkCFD@^pk>-}2rR2o6@hN-wGASddv&W6z7^Nz5mKUI(ubD(nr=`hr2w)e?P%!lTm46C`ihXI8D!KM><|0y>4gX*K)67$po8a!75RA7rkPVU)F)ClaUv*K`C;h)JHqyANmV_zX+po{N*l?d?9>Fv((?X(c#*bEv#FlzRO-w)$yb93}A0FW+pF3e$_$Rn_9|*x#rG4407?lm2Dil6qs~PWXrJyqF9h=88Tod2-<&cdXHu(A3L-Wj&v@=W65e_8+$XY^wtWN4!yAQL9;>v%Tpc-m<*(@Ol4#oTw-Gwvz#rcoT(*>!_~+L1mQXvKjoo7nGh;ytRi7x_L-9`oL>>7ckO>{;6(C?B-p}t}-%dD5yEO;MVHu)p~^;PY$zOmsSu~6r=K6X(Z^2_T2=X_q41osRw6*P7re`p-MM8Gp0x_4~+bXy6z&j`=&8W#$5O$CL12tghq^e}4)cQ#B|NXy8sCd~mC615OIN(0+zonIG8{tTyA{VL^;pu@5%8;J*|sH2+r=oIA>4EW_Ory)BNb<{>Z-`C6Mv)3bmapPJR@OP7kV{b#?n|yq2QQ0PVSk4)&q(z9xb36B$A~ZCAIFfd5>9zA!QPKa@YCvSrSLq&+{cK+G;m4C{MzJ(eA$LjFYT*z$kQ*F9r6l!-_Oif#%>H)@VcU`VH@hDA^Sh+_XP8yXxT1H1|7Ll#5hICg9S4~?s+*1Vf>2l9Z(331){I(`zY#=FMY2amX{{NdM!28$1LPZR!e%ER;5FbVe3;X%<<*F@8MBZ$t+g8SYzFE&6i-_Dqo>dr5S;Kz5JGZYo`MLu+v9DM+5DSZo$2O(ulj2nRTFW}86QOOYa`?g;s&k)@rBZ22(%&F6HwPnET)@R)!W2l$*9Lo0JKFI|6O1>usb;yJ0if2z-u{i6s3mtiSen7y=v^Y3;T-SJ4UvmRr)GbymO$nfd?Y-CCzVx~8d|ri0$v2*v6K)K{N&XO2}_xEZ=QLgY!q2n|5fSzDnpiu99U#hdTw_0~$l9mk58Gp4AMH^XhgueH}S*9|zd$FA=xsCh4oT4sMV03s?|4;if7+j`w*(Fm>s#vUtdIhkk0_qU${n)6&iBs#(=N^3nmcteXfZlU$V#zMp4=MkRNtB#&b3Dj{1Eo-6?Ufj52L`I)E$riUPIkwvT)&X-YNF|eL8PZP%0@7rrD>sW-AR6+GUGxZA5)F^7%&Js1_ZFc~Fnd{QvPc$~wKGvl!5kT2SE8?Lt?LAkTSAX|h~MXVx2$KJDh-tC?weN`ttJnKsiljA4T*ogXSM*ig2^MCSTvMo(weH7{+iv5$t8e=hF{X@F2^&oPhZtu|EM7Wx$TQ2b)^NbJI*QQCgr2%D)qiH}Ja$^2OpdtkI%v+64s>L|jmRe}A!g5$X+2}Q`|9~$X9^07d2|FBgzX^!OF8P~R*h>igw|8~d>^-O-Y@6E`c39zDZ+s7@u$fLiQ4zG$!1EOx-WQa6ZvG%qm&k_pgm3P06AnB_e=dvAn%Bf(deCLCb44$XKuYc}WS+;(5&X{cXKtA8^z&BS|5ZBArh(DK7+C(p`>?GdsZWsbJ)TGavp+irxI0mw>^a!*Mk6W>xEAn9q+}w$8S}t|Yas;|Qhc=Uc_SAo>|5(pMuo!$dt_KH$a}MstGlIXAa@}0;dc^$x4E9Hnf-hAo9ouk=Y#yj&SHT#Vhk|dQPcc14*3wT(vO9Wyr=pR$mQQ1nOH6pLlKzVHCl#eWOwJF!T&8sP#zODSLERVfP)E(&SnA>^N#pqZuQ`O=#ydSPZyOzqX&QHDO5%CuddQr7D9GObF0S!AKZtrs(AKysDV+%glIltUcaZ1jd<@ke&xd;sMMm?lAt&;r*WSm%);}3a3pe9>?RtEpwC2nt_ix(A4-OA>h|}QW$46ef1pmjowe)tlPj<1_Bf_WXQZ4E$B2Vu$nFm2)>%CmVQ7`$98zqSaFu{FEc-H~ayu}AK_K#;a=fkFFkw5uK^Bfrs%@$L?;^0%8p{^{+FWu6tdZ=k2309gL3G#;_e{W-{#`={G=~1b-%XT5Z-|)53-H!rCws?32{lWEp<%e3{!9gnM9Zl4`lSPVO870l`kYN9wVR2o;cGOoL7q3Oitfa&9o|rv1d+jnOylGQg%JF20F0@5Z%lB3G@F0jayftWkJvzJt#W^jUUr%yhFiTxCb^&-vPHXXj68J+;|@*P#GU!Y#vUYKY1Vn!+~bUE<%M-uV_bq)Nbk1}AcL}_R($w!o^tKgoI1uJK^E3|wj&EM(j+!!U5&G9Ah@J8;Fa{S??RW!K6)1B`12k+0e(qF^B#&RLZ+d$i?f@OqoXl?^+5d6G{ck%KTn2yO=4jD>hq-~-6a7zU>y2UY4bA&sfvauC+te~z5GLHXN5Mka`z(4TF^OY;9rx?!oUNrkc%1u%XD`Rw!$eTvs|z~b_iL&iPGcbwf4^*tsRGL>atUpS5W>er}(_H2_p$S!{%tUn8NRBOD8MpPXGnz=tnmLwqWPd@2N708FNC^_+OQmC)q9=_eM)A~AG+vcrQqJsLQQp>@s(fMe@d4@_Voq*wSt<~Dp-yk)_7_$^+mM?H%bXWq*Kj~i^qU=Hzkgrq={yN=M_zNZ`0}lU9Pqh&*P$^TdAP}&cgr(#p?i>$I^BJm%^g8|KCYI3m%YR8WSxi}3wp?0nYkLuz7qSWocNeI9r?)*QB7RgIk1|mS{+$HlL6ljbOpaQM{dyWFtkf7AI_c9J6vpuyy|?i+8(y=!&?S2K_Pjw^kZe@MBItxN(I6nSN=8XC4u8+-5xh{fc^MoJIzsFeGj;6@SrFc%>GJT7aBlabWL)G`s|~5oVgVzLXbb@9U2{d$AGcrGRv;0BY(c!{zL83eE6lCCVllA&VTHeaXx;@D;Cz<6tCUVMVhl*Q)VPmo(OK-npz5B$dgYO)X6VRhrl)Cze-5!yNJxbS=_5BU~+Us(vOs9lzL+%cRPj(-pX>CVs^;w1nzw~U6TU~n&cuiCs9XDJil))UYZL>lb65dO~v~!5_?=V+CC3h0RiQ5hRD;lvzlJlGeC69IpcYxd5f3CvNZ0^&WBl*{OddKA{Wuw+^G3B4i0`Q{~2bB>lZQqLZc%IvID+feln93hk24^_H8sBUN3Qxl8ME2?fbW_MmJn3aMI(&UccqYdGam`N>)<;n^%&8>wcY{&l=X-93bjC87ojKnm|Mk{;%;3Zg42nrU3|1#(XR-BF`=!Yv+49I`M=r#~f1<*Wuklj`0Xv1vnk#Pg;br7S)`nv*!H{JD23hm()^U5@vM@Zq^$kPDZd1akL?BX_eNr4%UVaq^Xqg7N-5|0AGha)kkpmnpdqOpx-S#d7KBW>l1P3Iua>wtQ0cIJ%@u)nd8l*pJA2OM@-d*Xctl*DhI(e!PuH;uU~+tkAqeZt59L0ZAFO{J?(R17S6f1gFIDIJCk)0z$E`0WUC;6So-=4I&ipLZ2rZ4W9Agu3Y@_Ph%pHRDj_U9}(-xl~`nIh__teN*`B}wN15l6ISk>(68S}iHLC>MHO+GuF(!8nzl_AA==`*g^xd@1ELiu%gCO5@03Sq2bwf5)z1d}%QIu!AOh-(>gQ*K=?hby3I5*wkycqCxAiTX!6tl&70lrPX{k9)7AFD|lgveB0sicK6Mxuw&>|$~y_@!6!d{kK)MiK2S8IOx#QMcVgYL%FRs$uZ`8DkQ<)oCRypk$BL=2ttEobbOiN}$&VZEVh)*{^}^~Ua`xqK}SX0au?+E)er%%yN)(>SjmiK+KE#5rMom@Oh<@B?A^D1n;)GM9MP~|3aCdy`c2ug)_+WC%?x3czPZ7G`(u~^2T-inwClH4BG^7-5d2*Mhy8%n+Cy(U#ajS6|Up!D4!FC3)#>28_&Z{N0C1^ckDW;NCl$5^Czi~uW*Yy_0f?WfISJy);Cah8B|_eX>6PeM8DvsCCHclt{o8?r^B^j4~cs@sG|~hOxyotUoSD&sBR~6ql^%}E5S_I?kT>*;Wz3lBA-C)E}B`}W}demGY_;V#}!^`IHucj9uu^0Zd>SJK==oxbt!yAQGT)zw*nqPciK^|eQT+I^wJfz94WcPk>Fah7}5h#mtDJ^14r{LcrBt$%72^JQF^@SwNto`5xSx4cqi#)^3GRV+C0W(xH{T&dC5!NFvZ&pztq=ST8IzrxoiXORKy?E?3}H`D_%GycZ@N~ge48Ic#W_9H*o@J8WH75n#Wow9yKDc(1tZbYRp2V~eU)Vz6=O&{?7oQ_)~=&H(qDyg+*l?RchM67*eZ^nec3(|H<{dj-mt{3pEx|0AzJ&sc|>Z{=2PxD*VQbGE%^5_wBSI=>C{^RDqJv3SvDL}*ns@I|Jk}?!zg$!hXrj*b!KVQ^W#GI85?JUTG^rtalsIRVDl|QPt$_Cojy&A!jsIMr+hm1OuXyEbMDdod9j8olz{w_!PVJ-wQUB9pJL_K48*XdjN$~?Fndg0@WaMUxq#P-%6)n~x5)%ibXU&6T16#eTf{`4qlxT{~Q{S?n{T_&6`>(CAOwBhJQ=RxFxL$?dY=B2<1qA@rXbr%ta*DlV0M`b~x%Np_f*t#k=NlIry_|lA%8}0D>6j5fsHr|sBLLwiR-&uj*XQIFE+^lsp_!-JQ7(a;m>eY-+uF2=QFdpobra{Lz)d^i?0jITj;47Q3-q93w)Wu=T?A>Mz_;D+7e$h#i{#i?%qP~oT(AzI6`AK!`C!7>#-FzAcM0^5fBbUBtttXz84AVDFQeDN66S|giEdzY)Yc6ZMA`cw$=5G|tf{=hKvg-y&aV>3uofmdw!&TYO{3E3PL0Q3bVI9ge5VfrNIwpjANhn7)-l;Jc460)dxJW)-7VL#rK_w5yMU77dZ9^SZVEgX0x-A1tKfnHZ;W6@iUqr-y8%J{H9o%(59m3y};CL`P4s=!T23(kpeDqy5|9-b*@M$_&P)O2CM84^Pe+JCzuzQtDs+%JG$69!^VAhEgqXCj0JK?uY<{kTbdwaIcIY){|iPRmG+_ixQ89nvOG>#zeFRNJara2eHkIf3=W02~vufl!JLkt*;tT5EsfcZg{x_R%e3`YV~T$yk82zAtzquXN^*Tn%vZtEZ44ahahO>bzYCWGbE1ER5aQ7_poka>JQIs^XB{@grp0DVDSWV&2*gtOqrws|fU!pKLB7Y|CYf6s5$z2!eaig#JE7bpoe8Wa?EUz$-z(nTf<8mn4z;nungVF6N|Ro|6)S*;uMpjt;nE42`L+B~C$4t5MsCI%JdBY*ly!E4U5C=g&jXc>~eI{0!sSI)T`Aig^+vSuZ6fAQwR1uIiH{X}tb7hkQC1vJg5`;UZ?r!4-k?SoA=%&L|?FgFWz6fuXMM}r3At_rd)a>&bEcY0oAKi|Kz{AVOqp^oY`S=(d9-WL;dtKS?)Za7wRGsuDg*W(V(E)hfSam)AR7T)X7ZqT|))Ed_>!hi3RXFNFEyq3oz)deZh-?{pCq`(m?<*!<9B;WN&qi_5EW`L-;)4Gx$lz+T~Pp!MeG7HXX(Ij^GBG2Iu&MrEY4f{SFTR{;-zPgCozEYb8wUol}VFupk;riT3FZSQBkI(jVKTMEs$#2WhT%E^>M-9&;>8>w1Hk%9>Ks8q!^1YAGCBpFXI`iu>5dKgpEawBRYb?Gz{uiYQkagBQ&V+!Am5k})YBW91q&yYvIR=;em*cygWTY3xcAK}?L4VZuvuo$i0}>?bcI#(n5X0Y6xLhd6ZJHww^%oL;#IbeA?b|ljcaie2Tj}d|g>Q-D__0rs`sN(XM4w#bOM)T2&zDjoQ6~^{;ZHnIgXP}^uj+qCJ&-3*Cb~2?6JB-Sx^>zZdDOytx877_0WqI>DIM>d<+P8DLFWIX>bv7|e!u^fXlPI>qb)*ckR<7db}5n7PLz?fmG<6y&wI6~C|N0@5K<`;Mbl0c4YTk4y5GM~=k@c?`{DV%T(9eO?)$#Z^E%f#&r<|l?j64)I1slRkbTl-R05a%n=M*Nc~;enqFxv?{qG0IPoAH<&^|q{^1_PM=wfDJr}tu8;7^Bp-42KwFP8SqZ7l?4bH%kw@1lLqaDGa=%|-(nU&DMqA;gLM%kvX-i2hU&{KOXRb~w;*jznD%_UXJ=>y&c-;&UxRTeBaC9{fxQp=ErCst(BEWcFny2Bfrli>5=qoR~(!4iStN+kP5+d{F~3<_k<8y{+I?IdP0h}{&bzi37s9H4r`(8S22U{$j797-kXXfGVPFBD(csVyzBDSH4?hwG;lLH;9Y(k?*|Kb6H;cF=LD8s>~iE+gkGG;uOj$sRDU`-1mjmRi6+gb!%JW>lQ8slVILo1^V=OhFG_)%`Qko*F@E)Gi~ai1=`xm{B>xn~i->+1U%2A_tFvnhnZ^A%{(Yl=N@ewDd8>ram4=9fCnec1e`>D8^|i>mp5@gwr*RenZ)^Y8%pBxhvMV)sJ;$hUkbO)O;KkXCZ9_zHPyI}~$_goanby``ZIFIz!FC7H@c=wB4M4YHk>l!Em`-YSYt0xgZkag?D2fq@Q&iMmU-<(5xLXYcpmx3|%`!b7Y#ASY6nRv|nd>xW*a?Nc+eC0@wzJq-X{GNByPTdiCl=I&og+=nIES;#u50OX7UcJfL%%9DQ8x-jve(Ysx!`0jZ$a6kzq%eee><_LF4lZn?LNfQX%3uNF?nh0XgXSTpbE=K(tlwIEw!IVms&K=7ChO_+qDE^b`GcAoIZXB{dtYPJ{&nBq8n|vRQ59djSN#)bQD&h&;;4H@eF26BP=48F%up;XR!L7eClbA|bRZkWF-s)rP(YW4%lIiC`k%QNv~&vwLJ%M2`bwU&bH6;tJh??`c~sl;%uuVr8*B9v>Bk9b;rQJ%|K0$5bt9+5am>c{u|BTW8IgE(rQlL<*r=>(%_{OYkBRy}y30V!W=%B}EEXdyI){AP1(q|M?H(r&+$MQLz8=v;y0&i~>4n!ju+wR2Z7V57@(PrWv@bKbq!@UpK(K*TSTkCF1&^_(8Foh^YQ{2>W%co0{^^=Jd@I#e1%SRrE(oOlh#z!}`d3FSI97R~)9zfEW+Wk}ae>D|NM4KGClEiA_WNj_?Zo){w#9*6q6^JuxTpkn@TM5gx$V<)3uR#EIq3$FOd&iG7q^Y9Yg`I2G4tzD-b8nDUai6;1_&|+Cb7_@K|6K-R{T$LSO0*sUPCKLDldHu40&2$Msf))X$Nq)24csfUrBJM|$i}QilkC&fE`w%*2SKm^A$U6}Hfc6m=8!@hHr$Mrvu#4C##Cwn49%aNaKsE;!^^o*h34MTzONwEc@rL`~Nb$Ww&-jeb9wi`Tzo9ILAMtAafF|#vQrI03yZfpq+K14Ke^prq-5vC@-6TDbf^6F@-pY|68l>~F#`l7I!?d^4-gMnb5MM{pngi8&+%Afm?#k{X@%Q8n-r=jm6RRq7wmG>TQ!+00#{(||wtNpI>C!9mxMcnrZD>BbhK}Xu&%tc-lzkpNAj4u@Kx%NL#S%Yyfu^nsg?er4URbemQ$jrAoG2@?ss!5q#;h|SZc3jz&?rBTqoNQFIN}oVKDbK?!Mp4hxu@w#}h?6b_kb%f>OrE_ok%#M~l?cdpDOtXD^SPN+RO7{l&L9riH>p-SP#m79qbns2<~9)0PN?u8+)6*q=LdK*JpUcxAw;6v?Ma&^mbU?wmX5ua|mO)VsuHK+(iCj-!**d;{mcCpvbH7r(zx(X*Kl!sb!AsujFo5k8gk_yXUgX1WS7O>;1VkO)$shQ+?AzZtAuCY=3G>2tsHGt8&peooY$=6{vObkAq&zx-OfhesjnU9CARTwW3is`r7MaD%*QS7R?fT>+=h1&X{cJM$Jv9@&V$4HLf751hR==^LJb3n8Jobw@;+&l4gf8b%!2C`rqw5yl_w6~E<2_7e{(f5(47%0O&I>PRI;+|+;Cahop6({JrwyO!vg+4GaM6O}z8R@6jUQR)o&1C`Ue)bnn$2PT6SYM^Qj5`$Le#XLa1}E0VL$JmwvzYnl2dnm$FOzLf1&&9>mOHkizq|K-_a&2#EFk(&(cDS#mfWR(KP2RX-r(DhvKP^A^=!v(4UI5)NR#yPg%fDE+t)s}-G5F4UP30>NeV^#^SNVS#2t)T+U!097X#O`4yG?ba+x#cOhae;v<_n%=XY2thkDd59Xnr`MT`Kyg9|J{lBA|bnl#<>*AnL0#^lV4cC(Rd~KbYWur{%6y|S1_ChU2&+>dI8{3^+$x%EO=E|f8L!x3k+&q?jvp}OcoAo!6eNnbtZ%HpIq1ymSYdouTM8A(UIA?bO#J{<+ap2e%~u9s9Z$pXE-8rgx;?z6b)i)kZ~(LC4_uGyIT0`ufQ+IJd!44}Y^lfI^=m$0r-?zXrD0hnSa4D3{2hCT7bbs-f-SWM-cw$Puk`NTb>AcfGF|u1t#C))wJ0vs@O^bA@R@yEobmzJ)8yyFwmB>ho~Jp8pU%a2S4*{A@M|jyY?AMZ%yY)|5a)Fk)`im#4FK~T3@~GMkfBOG~M#Ax}>Psyh5s$t9s_)SKWZ+O+ZTBu2@wF17&+YeQLOT!dA^&wazxvScL7H|RTw?dT_EH%6m2P5R55tfG%wu+!&|2hI`#fYb6;{!pr_p+K|0?8HAHTF|pS(^7BbUGpzpfz8{#-LkmcIyydf7-#uu1+A?faj~xnanCh8flsyn`-&aNL#|nOhH7n$1SXArYC=JtL(~hOC`pF)8$A;;+mT1<-+cNY4l<$Y*9zW7K^$LNlGtFv^ndmfx=SL2a6F-Rzr>ir>PNgs0mtW9NSAx9p~0!l&0>>QI6h?V;o4vIbkNY|U!+RnWBJe7&+S@V1VsOtcaIT&bfUIkTBVp(ZxT2k-^Q0G#wSN%#4FC(}ZTQ^|)tk9wH`y}5mgN^3Aq^|-#FTv09y?wjte$=!zhO7X@Xhrgfmfc0Nvj5}%YEs<4;WBz^}{U1GzMjkcwX^5(DkOuvATgE0x`ENe0A`6Lp^g!poKl+X$E_t+RUV}XI95J-}eQxBf7jtn1KC|aLyAc{06j~KuX6BZ!#+v9H`FbNn^fGYU6zs$9W!q0JCcxJJ(EAWbZavOgw=NS8jMkpx5?p%E$X{mFjo@wUKpI6LB4b;=F>AaU0TBAioXu#r$YtTOdj+U4{K`}*U?JlAT>~G+t7uTt#(&+~8SSR9r(R{rawgAAZyT@aL%XG4PjC(2Qv};4^g?@%;P;d0^ZLiKnAK;^h7?~d3V*!TC^(j->#mTE{2_`@WOqtn3WP|U=uyl?{t&k)T1$RmCS2k$v%j5>_966_WDn$mV6WcG9Fi^*aSl?}{Lk)Z8cBMsyeZq$t*LP8+|8ACq%*CB%;|9XxnZlL55$>QR$uw2uSgLoT77LdH%$`ScEhkj-B*R-qM2hsSR;%dVG`t{p(gf))zorsp{wTRl!AYX2sFieMiwggdUph*<#S2a_9NfO45&Ac=25P>n2_6Fy{MgqiLx`Aa8N~uwFuf!2mBan~W|}9@M)Qukc%=CqQ6Kz#``*@}rNIgjr4hwCT#qyx{qb_MY^dL_<;`t_>q!;6bm35BJ{bLe_iwEjuIKe9wU2MpDG;xfa!9-jc@%N)?#$#N7c}oG_6H)5BJy7L`q6>Vd%L#)dCslLmJ~%Q12%mh&SCdNoC=7xN!JhsQl=^PynXnE_`jgj={JAU79W1h1(9;!#0Ig)f66dgP-1lfa}1zv&A16ZBmM=!pnmWCj)S?#Pa-$ZS>8S;9&}dqzgWHL|L@ma&yxm{p~59wXOQQ34(mB8vSq{1y1}x{Z-{4nSa-SEA|K>VX)XR5c?Z~fqIuQ5CPX!QvC_VVjvYNrF|6Mdi;$zR7D}QWo1(nYF-REb}e>qvv-!|xkvGfB!=pufEw|uBOI*}CzI6)!lkuKc&;Vx%75IVf#-YyM@}j^+cGXR=oGZsY^@v>iORnkdk{p8d#Q3fkX9YGkpYDRaNFqWQ)OBF=s@XInUx4xK+jI>~D`38a3JbssatWfuED#+RLM?3ds@*E7F#zjaZOAe4Vpq)ZL>d3mG0ldBgc1Cjs5cMSLWi{62C59Ve-+sP5Zx1>IR>ihPl2nXf>(I0?!0(rs~qfL6QJ_XQmfz9Bu6{#LDy=L(86!Y^v8r^FDic}Y%k+I#+g9dj`vGblJ^(P|wO|G~}hf5Mu6{~mn~cm{MHDDti_UrStLDeEgRq8dr!v#p-b9Hia%^rvWhxNO#vpI6gfYLevs(*JuyX*DnD&?O%0{OS_gt?lQUgrWBgkoi05`E3X3zSYcHUV2vq*j8#U0BPhE4|HQU&Zi~9dgwV(OzM{xmNzwHw!}$AtSA^cR!Qo+MC3Vp>c_&$)|gUmf$~}W^liUtt|7Zz_w$y3sP||GBHrOY$mA6-=x6*%eRga=y*KtelMmZ7%k&%i&<=n4{XWgvOM%CN`A4^t^cGr|?s>KI4i#)A^J|qQ5Kjv8SC^hghpCp7IaZcvA3{(6hZF;(-H)1DRib?e-SFK@i{O=eb`C=bae;Hxpb9Z}aFRK7*0=P3_jmo8T9#_(9^{3A6O%B+7GQkotpB_6HswTCf4WjdjPr8(D|l+L2BX&__F9kgvTnJKOyyQU5RoC5PikzL@f4q7fntF;2;QD77oCjrT+7^~bM9a&*s3q7(i}ouD_bWuS2hdEHclle?#4W*l!IoYZ*23x;9RJJWkc%h{Bv9nT>Lek0$zh|b+j!Q&#|8TygM+L3TJgJ(l=EiZ^@NdoJO0Xf#Y?y!mrDbSL7cH_7Y%zzC^z8!$8D&J-#e(sriO-gZioJW5hxO+!HS4}Kjcei7xlHw;TraU}V)l-3$Z>xtmQHL`klm(OL?DG$6AijUmY30LKc@TMelG9fo@fU*QJ0iI#P#fBveb?rHc)#Yw&!QvyDO9LiapcPJbENeg-&45wFAY@Vzg&^ZN4#@mebXg51{@dr8>i)G_MphyuNwG=}Cm3y#XKF1;s?j2B%Ibw-C;qbyozYhkc!o6fpncsKt{!3cQMoZWz3v!dXmN@7lPl*2-Yj`v^kJV4)z!36*#C?4~pNmo8Ph*C}mo!q{;*PN+&zR>&uc6n;b_Wn2sOi@hCF%u?4a?WbA#S>FbNNqY255&a-ga~j;@rYw)(h941|N?V>ppEqJ?#}IXl=R^A#mYv$DUioG_+6SQ}bm%<5_i@8$=M_NeB)~rh&QfLQj_z*__AE<;2v5IiiHF%QeftTQm{x@4o!rZKoGY7q?y?_y3o^5odV6hr`;fDUTJRasTgrQTxnkV-mFfp4oEa3GVYZ?mJfZ38e#}D`UM3apxp`oyxFm@H%rz^^P~%^HQ=bm$z3wgen*n+Yh1L$_L|H+`TC9(sn@B*%tAes~9T#e^4PiM5XoE7gAkkm5}u#rr(|CqDN>w@zLX4v4n!=eKeEZZ-tTqWGgy84;+@cL#v!VV9mjK6{V_QT(Qbqv=~__$GY6yikAFb>Jei;EAa;cUV+JYj$AQ$ZSwSSCL52nyGCvKZDv?(l;S;^_)rJmRpRj*vl_$l=Zm&8y?8<;uWkyPlH_&d50V!ZY}|hMh9q+B^=`sXo7h81@J^^R}8_&NzrZxkL3-iEwOX+@nz6!UyrxhCl)w;I}~(e8Nvi@q%AIaS`YPaW;EJaji#g=-!>QP}s5@lK`5$$6cKVqPsNQ24T=#N^hXrH-Uk_MYD(!rcIvOZrDaU%a@;yeQitZq#xg`j3M~lyVQeT)m1M?PfUo8OHu0bZNM1DftZ+Xq9!l~9f8>v*}CzrFj{o>Biz;)kgnpY>rNp7xGv%Pkk4!_#xO<0W}KUw{4_x86h7!aJozQD8-d58_sC_d;csJ;n-nQ{T}rfjbmPr&sMd7P156i8lY%g*VCJm-=cXWO5HG*GhJByYH%#9J~R^(-x>gZ?c+z2lO|LrOkgp4)Yw!Ro`}*May5?L%wQJJ>3fJTO{#w*UQGf2gD%g0*<+q|CY$4$hudlJ`A^SL&F_fc-noaOnM#NI!lJq>&tlyik;fHwodFklp4n4KeUME&tfudjoPo~i@B{WLnExZjbg1Rsp&(|t^_?FnUns#x-1WnB0+i3`bN+W0aW~`O7VC;MFib4=?YM;a{O9xKs*h&FnT(XTo4z4#0z!5}srf+Y$~bSrye7kDPK|T96xhHvU9!moasLX#_~!LASo}fA$E^nO(oOcqM49_l?;7#)i(e2Ac<`-Tmw8^wn?9i%EQ4{Ud!BLfr<2bBq4O%#gnpTb-yOWq{C$=V-q-L)Jc)XQ)3ZMTh&n|s4a6gj9o|*b(g3F3wj7&}JdF}>sTzJT8)&(IgJoW0K2rTmqR_kWe5g1*k+<&(;u8WgOWD&YK=kto$U^?Mc)JCsfE*2WMVQx(1tR`_%QbG*AUY7|^{!Kh-!DD+MWuuR0<~c~zgi$p==}|BaEI+u?b$V=$Onjf!=~;qsChV$Dnim7np~mnaQ0FnY`1z{#pQuGq1SxtOB#GNmlwLaf;Kykp>&dATue5EzFEH0_7(Cgq8?^TaXt_ieE#W(E45!yxKu!aedbP55v2YvgsyU^JdJgK$}dCe|B@F`TFrdl>R^wm0s!x6CYo*2i`0^HBvot;P1ElGl#f$Mf9N+Ld0(G~qWG94aDP>*#}(cev_${Ts~zr#(4<6p~~<1tn+)(b+oftfsdLjlV1}3I6};jKX^~gdEKW*gJ#W*QI4ekFF#7+KQW@{Kt>hU?f|&_{**D|MBc2fO#x7av^d{h$2eigg>Au6y%Zqy=C#(NJtM>{+9;+p*qKn_*k6VAB%Qte*AUR8Z3u7uS4`_F=vzSIKD_d_Tg5oj5{qd`jU%maNFQ+V-1k@LWO_}zjxR&#PkB?&-tMB~RRJ70N&Npr=Pi6t-?jilh|oVoF;$WDA=1BcSP3afAxL+nrtFJCxpHw!J@yfesMoTenr%ouS-k^=GR%|nh@6U$@MgdXANh=`p^HWlI)O2dDlI3sp`oGZYJ$`mxa7#pW2r-Pp?wo?`!oFyu}#LX{(PkTxCcD;ye*?3;D@dKySd$ayopb+T?1ts81R&~xo^1KwI{R6A`0IGmVA_`gNq(mg}cH~1D=Son;2&fT3B#?gj6>M{SAfV>d}YL9Q+-AL+}w{z>Zu$Rnp-&T#U_XQ1copbii=Z|uvv-$+F+afr{%UYpPS>SP$T$4om7BZ_3WA>$$ICpkc}o47zJK-oMrC5*2Ynz-tsCvhwa@&k3Wb8@kxU0?{Y4>9My37V?pj1bef*OISzF{Mp6?_C`8kt;Xb>*fj=V@w?^g{Ee+Ce`JJ&ZOzasiN4VC180RQBwWATWKX?HC%Xea=Q_?>?xx{#+amPkFVk*9*~N58Woq;5@)s*?P+4Vd*@bE#xOa%PirsE^AoQC6x`_RWpEdAA)m558+Q~UJcQ94)^-TWN43g=m(8Gml4WeyxHRe5qj25}|Zhvt^91u)%z#qj1boM(f_N_LI8RCwL_T>SF_#Qg%6NDnjjXYYx%$|wGj^6*2JeDM89ho-0IwLPPV8~3h_DibV%)`We15Bm@&^1#-=@BtBOHxF$R{dMPJw%r2Rks#(HRoza~&Hg}>9;%v3g4B}o;tO|4`kB1Tj~YKu2cF~cJ8ZHLKko7^{Dwgej2Zr|(?5p%ij(;Q14adKy6DBRAyOU=D_-%D0z`kUdH;|nREHW^db`uW?1)y&^M{BVzWu^A(@X~ATQb`j8OK83hQpXqe@34c)C7x(=|Y02z*2>ois-%&vPe@l{X`T8`Y-BupSz}v#3?Y0i_WA#fOaZ6_a{m{$p`+Cve1@V7>`}|Z6IDD!cc@%~?b^UuYG3NW$c^z*&B#%5ce6>yctJf5mlpDJ-)QLPn+4X|dDjOO+WM6e=K``Q77n(nGSJL5IOn=}7WyDKQZ}`{R!GOM!^X*$m^<~4|z7c0u1cRtujN2GL@&rO3>i$R!RMA~aZ`UCoAoj<*>rz;Gs)D3GGFEZHo-KJ9z-ZjLMDio@gtW-;!OMzaJiYXUtvJuoS5W$2hi`27;ct0#XN`1tSmEPi$%Xr)Q=4wj$rj~HJPpB>(?X_m$ud?0?|)Q^j*v>uI|RzD0M0gN_-xyIb4eC=b2VXk-d=x;hFuFI8Q{A&nP=`%fMe#!PdcbEiCa*!3oCTDx<}x8>X$Fz8CqVz(krt}%$ps*%XzuZ(?=ARKJ!N}c*X)zf_X57ZLY9A4pdE<3nZ~?u*x$AJp1Tn~_d@H5;QHr@(6{G^me^sOzi6??x#M@!VD*j0Rf0yyqn>ay-VoW64T|dmZ{_om^25VyK4og;L-6OArTQd&&O#5FI~+$Tz?-)Cpluc6DG+L0G){&3Wt2_BUl9*IIr?GBkPhd^HCAM=An_300bdSp21tf~-ZO2Cxcj(_km5f#*!$?@%3dyvBQ4-P^!m|U=DCTXeD9ejj_(%?3Ou2c0PMl74Dk-cV?59M1v2-MTA`8K`^9Oq^X$JW;IrUd7OSsE*g?dJdk=UC*k}=UkW`7D)^@s@9+sieCr26{(L5{p7;BrySy9XMkhPFM?cZQ`Hajj4OOSa@-PXFPD5t?}ZxgSd{CMeDtzsjPUyw;MRm!;6yksn;_>Fk0&|I|Ij$r-Q*CMlKNdLPDW9{_Y=PWzp4z@M!P;&Uy45UnW2DD1xW8_a#8g1MMrOZ;&r}@Qh!!yPnF*x5>^${ExFql3qwyex6?x{Wal7v~Lx`^dCj7=6$3-wsAQZm48M-!#UmfvNnvTop|FK^Y3{Qd_8z7HD(E}U%}MOHh4)o{5bi!q;MPZrEk6GuBWZehTFjpHi-*al7aq4actIyQgrRYyhd^}bRTNJVCpaa*UKPArZA|s(t+g)R(SB3Vk)W5cJTp}Kf9pyqh>u~)#Sv1RKf~gQGx{IN61@ps;yMD(PJ7j{$lw|h51k58M`t;m8l?!Yo-eU>dk%v6)Zhum+s1Rx-*T@LnCGjHW_ts_uNqoy+0QxR3m#CQhK8rMNYmgY=OGclKExf=`%Hx0=x{-{T40cr2RmV;pk$rN05dsCv~3!xPwv|%1Bah`!?l%ecYdD1b#}1ncVBxJ4lWAE<5rP$#m#m_nD=HRf@to3o@8BoE^*K2;GG6GR>Gy}Uyw)j7D!cDJ;{Q-HEs(1exyDr(k?f)-pzwm16mS3W28E%;1u>$849rUOGrA3e_U3oZ@5SWLZ3{JlpnQpsBy%cn+~izi1&yqyNOIbQ)RIF5^6~xuh_UW;r;h#ZjkJ-|LfUET+e28Gyf8=P*`&@yd!uWeq_Ml76+Q+^s=vDiAt1mrfu~=&?wb(tzkQGZTwAs~=1+9d116h@8(r{PV*BAdU1Y>&#_^X$AaO+?*sdDbkJX~qnMh^EQ^ItT>Zz^q#%Cf?vMI+3MoMJdoO9kIN19$6_ZK984w}Gx$@6z9N!l;dPwzb4lDnmc^L6Go|}gi<`uxmZtsF6y@EPlekBICzXl40z((Q0zlQxWeB`y!V*nhf9i<@oi|5&y5hPC7g)d2qGY6LBJcF~2?=7{yjbCv^}f(n;3H=EH!ki+vU^;#G?u9yqat0-rA3U4Q#A@-(>(59H4<&u>akrRI4@BEI6MfmFqL8W4H?-dZGH_gCOj*R}+(K9X5#J%f2uMe8faxR<8_r`_o(GYa09b*U=eu$#$%{MzwD+etiR^h4l{cQDFZ1S8}-iYgvWMe--4xi^k08K|ze$xCAur>g1%r?WYOLH?(1#Fo_%Khd8rL6&*W{akuta0Gdj4U^XSZ!7|yo2z|oeR1*!S|1ADwcndUN%{Z;|1iHF2fE2uBE|zqeOnSLJ1U;1z{ShbGe)7vqb39SzrS6Y3FDk|+wzYfkJ`s{_=iMtp~7gos9+h!Z9;!#s9Dt&fd9PX_h}@(#3{Ayhtp;#pc*T>;QJWzlPzIuRpec1aK@*6X*TIzY5y+cA3JL3P;I!+1#fdtF{?iO7IYfE=@*Ls;%kAq{ZT1Fn*XH>l-*BBoJ!F)1II!wM4v^}+lJbn|*b|{@PnV0eBuSrh<#1?%R2noEcuhZULEd6@Z&3BEdlsmAoa!L>E_?xM*~ZD-INt&^ACqWt#aw+sGn$`!|Sxi)2rfuxc_&^$N58@DxCK6rozOAH;Ff8k++1)UiS4qoe4I%@##rPhzmEt3;xr&ES;{>LBwOES{sjZ6oTonen-3v@|kOaM~l`hp#srAM8_0y=5bQf){n_I9!*>=BlRg;<#uOj`DHo?@z>uoB;~8$eYHe=z|I+ZpI>Np`hw5hEM1`#Wf%-BJttDXV?u|gP$CwT-&L;6BlVRd`ZA{MNMY$tn4dsgb&sL@O-2Um`_pj=`AnJO)rFhNa#(uis;?1$did$PX6E@v>d5F}x1Wfw$-J*1TT20=QC%lVw@SM})@q{+ja647%Y*p%>hy0dR&g%d4xr}%M)Kw<(4v(dh$7RM8PKiQoq;1wsoL8Kh<&4>Aa=(ST}P1VVB^i;&#S6lrO;G@HaL&5{aUWiK)j#T#~+;F+Fd*mhZ6WUYprVZ{vK-rsAIH7WWc0H%g`WCJG6b+JwlC>XP(2pNaDF0*Tn+zfm%^y2s5vTc{w0&HY4sYdy)0z_z*ZMs0m?JA2iWI-P-Va1vo_bR@K`b9Qyi|O)+TnA0)qUQ=h3~~`WVq}!FpslB4Kv8Ea(31C@BI)2_u{@ynv(L{2_2_k{uod&Ueup=xO{fJ=!E`g!_j0o)3Ir_vL%im_!bhyVD8&D7o;r)ZNzI0ykGceXM=6Ii!DtIaYEPV{qUjLB?k{80kN%Mw&Jo9dkpWL1ntje!K|jvwpLMwigbLa}E7+6jsgG_NKO`9qe0_IocL*X6B>FD6K28FYhiX-kBp#UJMNjnklLnmW*AvE)F`gs(O}R1SZx+0^a@;veMII6rvUIQFgFLWuzV|PL)MqV@qLg|@i~^$^zb{?}Y5;I~gD?qw>W-3jJo68N8C*R|ICfNlr9U9Xi1aleoe_^;ed_!6saP-d%%vD)ZyPwPNzp)HvE-`O=~x);s0h$AtkTv(m=`tW2P`ghg1kbb4n0^lpQn=a+W^>DB$d(z~`v?|7!>CZhh?1u1r(%Q&vBsUcWK9>7pmwZM$r{8QFTeLbEipRaeQkyaEbaZh44!_cLuv75q7e+lzcIoef2#C`bq3sbWQuT|${Kdja{1vPwCgozX(HN9&Ol41!XOcdeDg?BKi|Q$8$WeS(qOu5?WP6+jN4qSzPcu$Bn##d1w{DdHPA)K)81=E6DsBQ>{HBCja%9t#jNE`(dtGz}43n4s5aOo_pw}^$CH3OIOb|Md1uygpw(UU3QZ@GM}$axYzrdL<~Dg$0jdKtQnA)m2QEvk$7z&tO{S-xoJ5lkyk1-Lxs{gOWIa9Bc6XFGAvP(4usy}!D7VYkI0_m7(4+60ZkV_d?)3x|D|S^cn870*eH9NHS!QbpSFoF1_nmUUw6^akDu~l{A$ff266S$rYH9hXC4QxH@r=UrTdoWO}F4YL|!`Qi)`SJ*jj$64#)F}-Y7Zem=95l?$SN;5Z9VNK4Nb~fuEtl@2$@uUYL}BP5K%Y)Z`}Hk7*!&rrp{<~ct#a9*Xlw#NYAgG!0p_uJoPUtS)4FTS`n{O@X>!1C$EhmuGQyd=f(B2-s?gZ{0cZx=dlcV$YZMZRrk<5AneEe7kS9Xr~6DI=2GCz))}vlrMUi!*?yN*vZ?UI!c)AK57)^$&-|l7_()y+l}m_+@5t8KsLp_GVPl;;gNK93aIy)#EWKOJcpH!G?4*B+ue8G$U}I&8n0ei@ZY~bOX@!&xj2m$-dq5Ob95Ag9)l^0#tCnnfaS{81d43{dQYpXu$m0N8Tp&m%kyJC7kk{4!Q56{6xDEf0?cI{`C|C!q%#sYfvHO&8Fv;zUB0X8uttE77|)_Xorf`?wW3Ujs~U#jy+T@rR89U?_uwtDl>W^tC?YO>*F>(t(%I>ZThbwNH5eQUq%LBCJvRP0Wm0FA4xr>X_ld9E&r{{fRO}0OA{V#;9L<@StV0f|kL(flWx0`ECW2Ng8VEEW|w#1vHcuvD3>OHYESV#z_9mhC{4s(0h7nAj09@-@03a@47vt{MM1Ad&cJnv@XyKhxSn&4HRk#rAwa~BwUTiDFKg7~G9u!j_u65(1Pz=gKJ&ET+$E{NI)>dt-a`DIe`I9BZstbdBTtH-5c^?OF61>yU8;6Re135H&IQ(mKy05mbi`ke2&AR%rb64TaVh7!$Y;(uNy-P+(tz<>ZC+Ui;@=u~X!TCffrz`0koulX?`3|n4JZE7bvc9cvwn}Cf?y?c0ijaJL!$lJS4VKf!elz<$KW#LEv)xElmh3+I*bQ-kUy|~&pjEeeZJigah9F`~VcF77poQLJ7nfsV$>JpCqZ}GWA-(QbY6yT~H=ZLAqbrSQM^iYAdf1JVbDbf$R+$HFs%g(p?uOf~o{A-QvNnowZw{mv;_9qWxThfD|RF(d2=fld`@vP5pVGOH&cFh=$57}?qyev5xrrxOPj{+x2<6F3pkI8c2MVU&3p(bD^&GAiR0H-=YM^#LV*>`Wv-RP@uMrQt#YPNL3@q#!TNTzTYtfO6N>>F#3T%lmjobA=+2xvmIPXUwhv~ckY7#uJ#qV3mIlOq+9V(HEBAsb1^uopxOq)RX~#I$ml1mJxzF=}cJ1uhz6Y59oVd}ryO`_0UehMKitjZ%dG`BrTomy{ikswLVPDj7Pp&RBO}avzQBEGFDEhGp)s7_v7cvOPm42&@#WZ7BM(C@<`W6W%azM954!TVWS?@m7-z={%kEdos!00QBw}oo?jW1ObQP1VA+@>_+V8(txlSO%4aH_&d72e~Nra=DE!`{{Qy~#D1=E=9<&i@L_UD)lecv?&^GFQ*Wv%g0vkaOY-($f5sMFaPzAa!_0a2gbiJ&{~9azK4Bw;@a3L5Mr!$x(RNqNnDH_IhiZnQ2z3TAfqa)Ihf%sEg`$?XW6pcKZFh4f*zPa7d3zZ9N#;7KE}#5253o<|o*KymNuF$&-l1xIF@Wnosu>Gqneu12UPZqU%u>r;oYR)|!JP*|C-XDxwZ)&?(fsYn^$cP@8%~={oyQb^_LKK`|MV3@V4S$P_zwF0&Hs8i(k6kcD5x|Rhh>YTP)Yq9+|f;gd&aRS=L&R5v?q5jAESabQRA~>q?v^_Wh+ad2uCXI99`5og?#8TuqA%HM+#yuJ-+ui`pLSqKN-m3IA!K5iXQS3t1)TZQko9mxA-v`n#gtjz1`D3{W(xKWwG#nHu}lDT+P%%s8mdymA*wkBY7~Axrqxeh7TTMcp+cSaHAho|565`%#s>GBJx<-Ii=fZy#NMi9f7`V^beIR)(k%%W0(4Ft2SX<-OGPp;Dmq}rHC4;ATF}$Yu}g;!&n&H?7UBL>5Vd>$#IhV!zovrMXb``lgr3VdR_#7k~VQMknS4k8aqrN0AV{iYFQpk-Ca_A{zVq7e#85vDBZej?~9eJ0mMEHyq5)3+pKK0dK^ca0T9sBX|q0#8Di>Rd_3|#x-~w-i~YW4qS)hxE}As37o_Yco%NOyYU{p7w^MOct38&2k=3B2p`5r@KJmWAIB%~Nqh>Q#%J(Zd=8(-7w|=V317xna0|YQui@+X2EK`J;oJBQzKieS`}hHVh#%p{_z8ZBpW)~D1%8QN;n(;Lev9AX_xJ<;h(F=a_zV7uzv1ur2mXnF;XhDI0|XQR000O8001EXJzjciMF0Q*ga7~l7623gZ(?(0a&}>KX>V?GUvO_}ZgehgaCrd$5CDV#00000002b*00000005ip7wQ`j$;eQ~P_3SlTAW;@Zl$1Z6KbfgqoAIaUsO_*m=~X4l#&V(cT3DEP6dh=XCxM+0{I%6ItsN46ag*N0AV{@6aWAK2mk;8Api)Ii=j>c004*p000jF6aZ;$VP|D>b7^{Ib1rUhc>w?r0Ehqp0000008Rh^000000GsR=>KhQr$WX>mt)7xvoLr=CrJ!z;X`-&9pq`drR8o|f7oT60k_r-cOUx-w1&SAEBo?Fs`5J~g3Pzeb3bhJk1Fi;f28Ip%3=9BJO9KQH000080000X0Kgd(FI4~l0FVFx01^Nc0ApcnZ(?d?V{~74VRCRTZg6=401yC>0000000010000000001+>=)`A5Xs0;#!#)El3JWxq;934Zj)xAuA`uymS0p-l$aNvUzCyx5_e0?DNY577iT0EqyqUGMmm~03bhIp050{jF7I>>`0sE2u{};F!qFZ8P)h>@6aWAK2mk;8ApjH||D;0z004mi0018V6aZvzUvF@9X>DnGWnXD-baH8Kb7^C9Ut@1_WiD=Tc>w?r0D%Ai0000007C!(000000GsR=>KhQr$WX>mt)7xvoLr=CrJ!DuWT>vApq`drR8o|f7oT60k_r-cOUx-w1&SAEBo?Fs`5Kx!3bhIp0WJmrP)h>@6aWAK2mk;8Apn9c_|roG004mi001Tc6aZvzUvF@9X>DnGWnXD-baH8Kb7^C9Uu0=>bZ>HWX>V?GE^csn0RRvHfdBvi00000LjV8(00000o9q|r8xYCJP{vTLo|0OeT%>NLpk9+?sIH@+o|a!!Qk0k%pI?-c3KDlq%qdO*}(?b9N0D%Ai02%-k0Az1pZ*X*JZE1RCUuAf7a%paJX=8IPZg6=401yCy000000000(000000001+>=)`A5Xs0;#!#)El3JWxq;934UXx^~uA`uymS0p-l$aNvUzCyx5_e0?DNY577iT0EqyqUGnmP)#3KRh@MgUMt0|XQR000O8001EXf-U&dLjV8(fdBvi7623gWN%+@aCB*HX?kT}W^!R|WpgfWaCrd$5CDMy00000002V(00000005ip7wQ`j$;eQ~P_3SlTAW;@Zl$1JlVqr_qoAIaUsO_*m=~X4l#&V(cT3DEP6dh=XCxM+0{I%6ItsN46ag+q08mQ<1QY-O00;m803iT^E%?(z0001i0000U02BaZZ(nb4bZKpAdSzc@VQg<=YGq?|Uw2`0a4v3ec>w?r0D%Ai0000007C!(000000GsR=>KhQr$WX>mt)7xvoLr=CrJ!DuWT>vApq`drR8o|f7oT60k_r-cOUx-w1&SAEBo?Fs`5Kx!3bhIp0WL-WP)h>@6aWAK2mk;8Api_qfO$&*004*p0015U6aZskY-wV0VRUJ4ZeMR=YGq?|UvqF_V`*+@E^csn0RRvHhyVZp00000O8@`>00000o9q|r8xYCJP{vTLo|0OeT%>NLpl*|9p{}E#o|a!!Qk0k%pI?-c3KDlq%qdO*}(?b9N0D%Ai03HAo0Az1pVQ_G4d0%gJbZlv5a$j;~YGq?|X>V>WZg6=401yCy000000000(000000001+>=)`A5Xs0;#!#)El3JWxq;934UXx^~uA`uymS0p-l$aNvUzCyx5_e0?DNY577iT0EqyqUGnmP)#3KRh@MgUMt0|XQR000O8001EXF>zM+MgRZ+hyVZp9sm>oZ(?(0a&~28UvO!7Wo%z{ZewL~bYW?3ba^graCrd$5CDh(00000002e+00000005ip7wQ`j$;eQ~P_3SlTAW;@Zl$1ZlV+i=qoAIaUsO_*m=~X4l#&V(cT3DEP6dh=XCxM+0{I%6ItsN46ag*<2yg%ZP)h>@6aWAK2mk;8Apn9c_|roG004mi000{R6aZvzUtw@?Yw?r0D%Ai0000007C!(000000GsR=>KhQr$WX>mt)7xvoLr=CrJ!DuWT>vApq`drR8o|f7oT60k_r-cOUx-w1&SAEBo?Fs`5Kx!3bhIp0WL-WP)h>@6aWAK2mk;8ApjH||D;0z004mi000XB6aaQ*a$;|DWiD=Tc>w?r0D%Ai0000007C!(000000GsR=>KhQr$WX>mt)7xvoLr=CrJ!DuWT>vApq`drR8o|f7oT60k_r-cOUx-w1&SAEBo?Fs`5Kx!3bhIp0WJmrP)h*<6ay3h000O8001EX>IWHfnH~TDASM6+4gdfE0000000000fB^si003!jbaH8Kb7^C9E^csnP)h*<6ay3h000O8001EXT51v|MgRZ+fB*mh82|tP0000000000fC1Sa003opbaH8Kb7^C9UvhL`W^!+Ba%E;NZg6=}O928D0~7!N00;m803iUp(R|OwApihiBLDys00000000000001h0csxr0A_MwZDn&`a&%vGZ*pa3E^csnP)h*<6ay3h000O8001EXJzjciMF0Q*ga7~l3IG5A0000000000fB|(u003}rX>N3LE^csnP)h*<6ay3h000O8001EX8}eu#aZm&RK+pyN761SM0000000000fC2VF003`db7gXNVRUJ4ZgXE^Z((v|E^csnP)h*<6ay3h000O8001EXap$=wxB&nFI0*m%EdT%j0000000000fB~S*WpZ|5bZKvHb6;?8X>N2bZg6=}O928D0~7!N00;m803iT9UV3Xq0001l0000j00000000000001h0aKL(0BLSyX=7z`UvO_}ZggK`VQpz{baH8Kb7^C9Ut?iyWq5RQX>N0AV{Vrpe$bYFL2a&RtgaCuNm0Rj{Q6aWAK2mk;8ApjH||D;0z004mi0018V0000000000004ji2$%!_WN%+@aCB*HX?kT}X>N3KX>N0AV{>0)Z*pZWZg6=}O928D0~7!N00;m803iT^E%?(z0001i0000c00000000000001h0i2iw0Az1pZ*X*JZE1RCUukZ1a%paJX=8I=WNCABZ*p{LZ*FrgZg6=}O928D0~7!N00;m803iT^E%?(z0001i0000Q00000000000001h0XLZh0Az1pZ*X*JZE1RCUuAf7a%paJX=8IPZg6=}O928D0~7!N00;m803iT^E%?(z0001i0000M00000000000001h0mhjG0Az1pZ*X*JZE1RCUuJS)ZDn&VZg6=}O928D0~7!N00;m803iT^E%?(z0001i0000U00000000000001h0a2O+0Az1pZ*X*JZE1RCUt?ixZ(?d?V{~74VRCRTZg6=}O928D0~7!N00;m803iSjT!48?0001p0000U00000000000001h0pywl0ApcnX<~9=bZKvHUvFY+Wn*+-b8ul}X>MmOZg6=}O928D0~7!N00;m803iT^E%?(z0001i0000U00000000000001h0e_nW0Az1pVQ_G4d0%gJbZlv5a$j;~YGq?|X>V>WZg6=}O928D0~7!N00;m803iS|aaQ+60001p0000U00000000000001h0TP@90B>S*WpZ|9WM6P;cx7x~b#7y2a&%#7ZghDrZg6=}O928D0~7!N00;m803iT^E%?(z0001i0000R00000000000001h0jQh=0Az1pVQ_G4d0%p6XLW30a%p;DbZKvHE^csnP)h*<6ay3h000O8001EX6dnJhLjV8(fdBvi3jhEB0000000000fB`t21ORqra$;|DWiD=Tc~DCQ1^@s602Kfg0MP{i0Jxn50000', } mrcal-2.4.1/doc/data/figueroa-overpass-looking-S/splined-1.scale0.35.cahvor000066400000000000000000000006131456301662300261750ustar00rootroot00000000000000Dimensions = 6016 4016 Model = CAHV = perspective, linear C = 2.1261078702 0.0858522242 0.0347777812 A = 0.0234070514 -0.0033110290 0.9997205345 H = 776.9442742876 -23.5724035228 3000.2140409137 V = 59.7166619167 714.0243294724 1958.8057109503 Hs = 706.6353735 Hc = 3017.639608 Vs = 720.6420364 Vc = 1957.291928 # this is hard-coded Theta = -1.5707963267948966 (-90.0 deg) mrcal-2.4.1/doc/data/figueroa-overpass-looking-S/splined-1.scale0.6.cahvor000066400000000000000000000006131456301662300261130ustar00rootroot00000000000000Dimensions = 6016 4016 Model = CAHV = perspective, linear C = 2.1261078702 0.0858522242 0.0347777812 A = 0.0234070514 -0.0033110290 0.9997205345 H = 1281.4515805279 -33.2730544920 2988.3695831873 V = 69.6468255305 1228.6707434658 1960.2776956553 Hs = 1211.374926 Hc = 3017.639608 Vs = 1235.386348 Vc = 1957.291928 # this is hard-coded Theta = -1.5707963267948966 (-90.0 deg) mrcal-2.4.1/doc/diff-notransform.fig000066400000000000000000000017151456301662300173400ustar00rootroot00000000000000#FIG 3.2 Produced by xfig version 3.2.7b Portrait Center Metric Letter 100.00 Single -2 1200 2 0 32 #a0a0a0 6 360 1980 585 2205 4 0 8 50 -1 16 10 0.0000 5 120 90 495 2205 0\001 4 2 8 50 -1 16 14 0.0000 5 180 135 495 2115 q\001 -6 6 298 1732 1271 2831 2 3 0 5 1 7 60 -1 -1 18.000 0 0 7 0 0 5 658 1750 658 2809 316 2809 316 1750 658 1750 2 3 0 5 1 7 60 -1 -1 18.000 0 0 7 0 0 5 658 2017 1252 1750 1252 2809 658 2546 658 2017 -6 6 268 1702 1300 2860 2 3 0 2 2 7 50 -1 -1 12.000 0 0 7 0 0 5 655 1742 655 2821 308 2821 308 1742 655 1742 2 3 0 2 2 7 50 -1 -1 12.000 0 0 7 0 0 5 655 2011 1260 1742 1260 2821 655 2552 655 2011 -6 6 330 2553 555 2778 4 2 12 50 -1 16 14 0.0000 5 180 135 465 2688 q\001 4 0 12 50 -1 16 10 0.0000 5 120 90 465 2778 1\001 -6 2 1 0 1 12 7 30 -1 -1 0.000 0 0 7 0 1 2 1 1 1.00 75.00 120.00 467 2562 6535 1084 2 1 0 1 8 7 40 -1 -1 0.000 0 0 7 1 0 2 1 1 1.00 75.00 120.00 448 2302 6535 1084 4 0 0 50 -1 16 14 0.0000 5 180 135 6615 1170 p\001 mrcal-2.4.1/doc/diff-yestransform.fig000066400000000000000000000024751456301662300175300ustar00rootroot00000000000000#FIG 3.2 Produced by xfig version 3.2.7b Portrait Center Metric Letter 100.00 Single -2 1200 2 0 32 #a0a0a0 5 1 0 1 0 7 50 -1 -1 0.000 0 0 1 0 5639.000 1364.000 5688 1018 5985 1315 5688 1710 1 1 1.00 98.91 131.88 6 284 1597 1080 2495 2 3 0 5 1 7 60 -1 -1 18.000 0 0 7 0 0 5 579 1612 579 2478 300 2478 300 1612 579 1612 2 3 0 5 1 7 60 -1 -1 18.000 0 0 7 0 0 5 579 1829 1065 1612 1065 2478 579 2262 579 1829 -6 6 365 3350 590 3575 4 0 12 50 -1 16 10 0.0000 5 120 90 500 3575 1\001 4 2 12 50 -1 16 14 0.0000 5 180 135 500 3485 q\001 -6 6 225 2671 1214 3759 2 3 0 2 2 7 50 -1 -1 12.000 0 0 7 0 0 5 577 2748 656 3625 372 3649 295 2772 577 2748 2 3 0 2 2 7 50 -1 -1 12.000 0 0 7 0 0 5 599 2968 1071 2704 1148 3583 636 3405 599 2968 -6 6 317 1790 542 2015 4 2 8 50 -1 16 14 0.0000 5 180 135 452 1925 q\001 4 0 8 50 -1 16 10 0.0000 5 120 90 452 2015 0\001 -6 6 5407 942 5632 1167 4 0 8 50 -1 16 10 0.0000 5 120 90 5542 1167 0\001 4 2 8 50 -1 16 14 0.0000 5 180 135 5542 1077 p\001 -6 6 5421 1641 5646 1866 4 2 12 50 -1 16 14 0.0000 5 180 135 5556 1776 p\001 4 0 12 50 -1 16 10 0.0000 5 120 90 5556 1866 1\001 -6 2 1 0 1 8 7 40 -1 -1 0.000 0 0 7 1 0 2 1 1 1.00 75.00 120.00 407 2062 5385 1067 2 1 0 1 12 7 30 -1 -1 0.000 0 0 7 0 1 2 1 1 1.00 75.00 120.00 478 3330 5321 1792 4 0 0 50 -1 16 14 0.0000 5 180 1080 6023 1391 Transform\001 mrcal-2.4.1/doc/differencing.org000066400000000000000000000715541456301662300165370ustar00rootroot00000000000000#+TITLE: Model differencing #+OPTIONS: toc:t * Intrinsics differences mrcal provides the [[file:mrcal-show-projection-diff.html][=mrcal-show-projection-diff=]] tool to compute and display projection differences between several models (implemented using [[file:mrcal-python-api-reference.html#-show_projection_diff][=mrcal.show_projection_diff()=]] and [[file:mrcal-python-api-reference.html#-projection_diff][=mrcal.projection_diff()=]]). This has numerous applications. For instance: - evaluating the manufacturing variation of different lenses - quantifying intrinsics drift due to mechanical or thermal stresses - testing different solution methods - underlying a cross-validation scheme ** What is meant by a "difference"? We want to compare different representations of the same lens, so we're /not/ interested in extrinsics. At a very high level, to evaluate the projection difference at a pixel coordinate $\vec q_0$ in camera 0 we need to: 1. Unproject $\vec q_0$ to a fixed point $\vec p$ using lens 0 2. Project $\vec p$ back to pixel coords $\vec q_1$ using lens 1 3. Report the reprojection difference $\vec q_1 - \vec q_0$ [[file:figures/diff-notransform.svg]] This simple definition is conceptually sound, but isn't applicable in practice. In the [[file:tour-differencing.org][tour of mrcal]] we calibrated the same lens using the same data, but with two different lens models. The models are describing the same lens, so we would expect a low difference. However, the simple algorithm above produces a difference that is non-sensically high. As a heat map: #+begin_src sh mrcal-show-projection-diff \ --intrinsics-only \ --cbmax 15 \ --unset key \ opencv8.cameramodel \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export # THIS IS GENERATED IN tour-differencing.org #+end_src [[file:external/figures/diff/diff-radius0-heatmap-splined-opencv8.png]] And as a vector field: #+begin_src sh mrcal-show-projection-diff \ --intrinsics-only \ --vectorfield \ --vectorscale 5 \ --gridn 30 20 \ --cbmax 15 \ --unset key \ opencv8.cameramodel \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export # THIS IS GENERATED IN tour-differencing.org #+end_src [[file:external/figures/diff/diff-radius0-vectorfield-splined-opencv8.svg]] The reported differences are in pixels. The issue is similar to the one encountered by the [[file:uncertainty.org::#propagating-through-projection][projection uncertainty]] routine: each calibration produces noisy estimates of all the intrinsics and all the coordinate transformations: [[file:figures/uncertainty.svg]] The above plots projected the same $\vec p$ in the camera coordinate system, but that coordinate system shifts with each model computation. So in the /fixed/ coordinate system attached to the camera housing, we weren't in fact projecting the same point. There exists some transformation between the camera coordinate system from the solution and the coordinate system defined by the physical camera housing. It is important to note that *this implied transformation is built-in to the intrinsics*. Even if we're not explicitly optimizing the camera pose, this implied transformation is still something that exists and moves around in response to noise. The above vector field suggests that we need to pitch one of the cameras. We can automate this by adding a critical missing step to the procedure above between steps 1 and 2: - Transform $\vec p$ from the coordinate system of one camera to the coordinate system of the other camera [[file:figures/diff-yestransform.svg]] We don't know anything about the physical coordinate system of either camera, so we do the best we can: we compute a fit. The "right" transformation will transform $\vec p$ in such a way that the reported mismatches in $\vec q$ will be small. Previously we passed =--intrinsics-only= to bypass this fit. Let's omit that option to get the the diff that we expect: #+begin_src sh mrcal-show-projection-diff \ --unset key \ opencv8.cameramodel \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export # THIS IS GENERATED IN tour-differencing.org #+end_src [[file:external/figures/diff/diff-splined-opencv8.png]] ** Implied transformation details :PROPERTIES: :CUSTOM_ID: implied-transformation :END: As with [[file:uncertainty.org::#effect-of-range][projection uncertainty]], the difference computations are not invariant to range. So we always compute "the projection difference when looking out to $r$ meters" for some possibly-infinite $r$. The procedure we implement is: 1. Regularly sample the two imagers, to get two corresponding sets of pixel coordinates $\left\{\vec q_{0_i}\right\}$ and $\left\{\vec q_{1_i}\right\}$ 2. Unproject the camera-0 pixel coordinates to a set of points $\left\{\vec p_{0_i}\right\}$ in the camera-0 coordinate system. The range is given with =--distance=. [[file:mrcal-python-api-reference.html#-sample_imager_unproject][=mrcal.sample_imager_unproject()=]] function does this exactly 3. Unproject the camera-1 pixel coordiantes to a set of normalized unit observation vectors $\left\{\vec v_{1_i}\right\}$ in the camera-1 coordinate system. These correspond to $\left\{\vec p_{0_i}\right\}$, except they're unit vectors instead of points in space. 4. Compute the implied transformation $\left(R,t\right)$ as the one to maximize \[ \sum_i w_i \vec v_{1_i}^T \frac{R \vec p_{0_i} + t}{\left|R \vec p_{0_i} + t\right|} \] where $\left\{w_i\right\}$ is a set of [[#fit-weighting][weights]]. As with main calibration optimization, this one is unconstrained, using the [[file:conventions.org::#pose-representation][=rt= transformation representation]]. The inner product above is $\cos \theta$ where $\theta$ is the angle between the two observation vectors in the camera-1 coord system. When looking out to infinity the $t$ becomes insignificant, and we do a rotation-only optimization. This is the logic behind [[file:mrcal-python-api-reference.html#-implied_Rt10__from_unprojections][=mrcal.implied_Rt10__from_unprojections()=]] and [[file:mrcal-python-api-reference.html#-projection_diff][=mrcal.projection_diff()=]]. *** Which transform is "right"? We just described a differencing method that computes an implied transformation given a range $r$. This will produce a different result for each $r$, but in reality, there's only a single /true/ transformation, and the solutions at different ranges are different estimates of it. If we just need to compare two different representations of the same lens, then we don't care about the implied transformation itself. The correct thing to do here would be to set $r$ to the intended working distance of the system: for me this is generally infinity. Looking at a single $r$, these implied-transformation fits will always overfit a little bit, but from experience, this doesn't affect the resulting model-difference output. However, in some applications ([[#extrinsics-diff][extrinsics differencing]] for instance), we /do/ want the true implied transform. And when we look at this computed transform more deeply, we see that with some $r$ we get a result that is clearly wrong. For instance: #+begin_example $ mrcal-show-projection-diff \ --no-uncertainties \ --unset key \ --distance 1000 \ opencv8.cameramodel \ splined.cameramodel Transformation cam1 <-- cam0: rotation: 0.316 degrees, translation: [-2.67878241 -0.832383 1.8063095 ] m ## WARNING: fitted camera moved by 3.336m. This is probably aphysically high, and something is wrong. Pass both a high and a low --distance? #+end_example More on =--no-uncertainties= later; it's here to speed things up, and isn't important. We asked for a diff at 1000m out, and the solver said that the optimal transform moves the camera coordinate system back by 1.8m and to the right by 2.7m. This is looking at the same data as before: comparing two solves from the [[file:tour-differencing.org][tour of mrcal]]. Nothing moved. The camera coordinate system could have shifted inside the camera housing a tiny bit, but the solved shifts are huge, and clearly aren't inside the housing anymore. This needs a deeper investigation on how to do it "properly", but for practical use I have a working solution: solve using points at two ranges at the same time, a near range and a far range: #+begin_example $ mrcal-show-projection-diff \ --no-uncertainties \ --unset key \ --distance 1,1000 \ opencv8.cameramodel \ splined.cameramodel Transformation cam1 <-- cam0: rotation: 0.316 degrees, translation: [2.90213542e-05 2.59871714e-06 1.73397909e-03] m #+end_example Much better. This is analogous to the multiple ranges-to-the camera we need when we compute a [[file:recipes.org::#surveyed-calibration][surveyed calibration]] and the multiple ranges we get when we [[file:tour-choreography.org::#tilt][tilt the chessboard during calibration]]. *** Selection of fitting data :PROPERTIES: :CUSTOM_ID: fitting-data-selection :END: When we use a fit to compute the implied transformation, we minimize the reprojection error. We hope that the main contributions to this error come from geometric misalignment. If this was the case, minimizing this reprojection error would produce the correct implied $\left(R,t\right)$. Applying this transformation would correct the misalignment, leaving a very small residual. It is possible to have other error contributions though, which would break this method of finding the implied $\left(R,t\right)$. This is common when intrinsics differences are significant; let's demonstrate that. We just saw a difference result from the [[file:tour-differencing.org][tour of mrcal]], showing that the two models are similar but not identical. Once again: #+begin_src sh mrcal-show-projection-diff \ --unset key \ opencv8.cameramodel \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export # THIS IS GENERATED IN tour-differencing.org #+end_src [[file:external/figures/diff/diff-splined-opencv8.png]] This uses the default data-selection behavior of [[file:mrcal-show-projection-diff.html][=mrcal-show-projection-diff=]]: - [[#fit-weighting][uncertainties are used to weight the sampled points]] - points are sampled from the /whole/ imager (without uncertainties the default behavior is to use a limited region in the center instead) What if we used all the data in the imager, but weighed them all equally? #+begin_src sh mrcal-show-projection-diff \ --unset key \ --no-uncertainties \ --radius 1e6 \ --cbmax 50 \ opencv8.cameramodel \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ mrcal-show-projection-diff \ --unset key \ --no-uncertainties \ --radius 1e6 \ --cbmax 50 \ $D/{opencv8,splined}.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/diff/diff-splined-opencv8--all-data.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' #+end_src [[file:external/figures/diff/diff-splined-opencv8--all-data.png]] Note the completely different color-bar scaling: this difference is huge! The reason this doesn't work is that projections of the two models don't just differ due to an implied transformation: there's also a significant difference in intrinsics. This difference is small near the center, and huge in the corners, so even the optimal $\left(R,t\right)$ fits badly. We can solve this problem by either - [[#fit-weighting][Giving the bad points low weights during the solve]] by using the default behavior, without =--no-uncertainties=. This is described in the next section - Excluding the bad points entirely by passing a =--radius= Let's demonstrate the effect of =--radius=. I re-ran the calibration from the [[file:tour.org][tour of mrcal]] using [[file:lensmodels.org::#lensmodel-opencv][=LENSMODEL_OPENCV4=]]. This model fits the wide lens even worse than the [[file:lensmodels.org::#lensmodel-opencv][=LENSMODEL_OPENCV8=]] fits we studied, and is not expected to work at all. But it is very good for this demo. If we run this solve, the [[file:formulation.org::#outlier-rejection][outlier rejection]] logic kicks in, and makes the solve converge despite the model not fitting the data well. The resulting model is available [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/opencv4.cameramodel][here]]. Using an insufficient model like this isn't a good way to run calibrations: the outlier rejection will throw away the clearly-ill-fitting measurements, but marginal measurements will make it through, which will slightly poison the result. I'm only doing this for this demo. If you really do want to use an insufficient model, and you really do care only about points near the center, you should use the [[file:mrcal-cull-corners.html][=mrcal-cull-corners=]] tool to throw away the data you don't care about, prior to calibrating. Let's compute the diff between the narrow-only =LENSMODEL_OPENCV4= lens model and the mostly-good-everywhere =LENSMODEL_OPENCV8= model, using an expanding radius of points. We expect this to work well when using a small radius, and we expect the difference to degrade as we use more and more data away from the center. #+begin_src sh # This is a zsh loop for r (200 600 800 1000) { mrcal-show-projection-diff \ --no-uncertainties \ --distance 1 \ --radius $r \ --cbmax 15 \ --unset key \ --extratitle "radius $r" \ opencv[48].cameramodel } #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ for r (200 600 800 1000) { ~/projects/mrcal/mrcal-show-projection-diff \ --no-uncertainties \ --distance 1 \ --radius $r \ --cbmax 15 \ --unset key \ --extratitle "radius $r" \ $D/opencv[48].cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/diff/diff-radius$r-opencv4-opencv8.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' } #+end_src [[file:external/figures/diff/diff-radius200-opencv4-opencv8.png]] [[file:external/figures/diff/diff-radius600-opencv4-opencv8.png]] [[file:external/figures/diff/diff-radius800-opencv4-opencv8.png]] [[file:external/figures/diff/diff-radius1000-opencv4-opencv8.png]] All of these radii are equally "right", and there's a trade-off in picking one. The models agree very well in a small region at the center, but they can also agree decently well in a much larger region, if we are willing to accept a higher level of error in the middle. For the purposes of computing the implied transform you don't need a lot of data, so I generally use a small region in the center, where I have reasonable confidence that the intrinsics match. For a camera like this one =--radius 500= is usually plenty. *** Fit weighting :PROPERTIES: :CUSTOM_ID: fit-weighting :END: Clearly the =LENSMODEL_OPENCV4= solve does agree with the =LENSMODEL_OPENCV8= solve well, but /only/ in the center of the imager. The issue from a tooling standpoint is that in order for the tool to tell us that, *we* needed to tell the tool to only look at the center. That is unideal. The issue we observed is that some regions of the imager have unreliable behavior, which poisons the fit. But we know where the fit is reliable: in the areas where the [[file:uncertainty.org][projection uncertainty]] is low. So we can weigh the fit by the inverse of the projection uncertainty, and we will then favor the "good" regions. Without requiring the user to specify the good-projection region. This works, but with a big caveat. As described on the [[file:uncertainty.org][projection uncertainty]] page, lean models report overly-optimistic uncertainties. Thus when used as weights for the fit, areas that actually are unreliable will be weighted too highly, and will still poison the fit. We see that here, when comparing the =LENSMODEL_OPENCV4= and =LENSMODEL_OPENCV8= results. The above plots show that the =LENSMODEL_OPENCV4= result is only reliable within a few 100s of pixels around the center. However, =LENSMODEL_OPENCV4= is a very lean model, so its uncertainty at 1m out (near the sweet spot, where the chessboards were) looks /far/ better than that: #+begin_src sh mrcal-show-projection-uncertainty \ --distance 1 \ --unset key \ opencv4.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ ~/projects/mrcal/mrcal-show-projection-uncertainty \ --distance 1 \ --unset key \ $D/opencv4.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/uncertainty/uncertainty-opencv4-1m.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' #+end_src [[file:external/figures/uncertainty/uncertainty-opencv4-1m.png]] And the diff using that uncertainty as a weight /without/ specifying a radius looks poor: #+begin_src sh mrcal-show-projection-diff \ --distance 1 \ --unset key \ opencv[48].cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ ~/projects/mrcal/mrcal-show-projection-diff \ --distance 1 \ --unset key \ $D/opencv[48].cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/diff/diff-weighted-opencv4-opencv8.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' #+end_src [[file:external/figures/diff/diff-weighted-opencv4-opencv8.png]] Where this technique /does/ work well is when using [[file:splined-models.org][splined models]], which produce realistic uncertainty estimates. To demonstrate, let's produce a splined-model calibration that is only reliable in a particular region of the imager. We do this by culling the [[file:tour.org][tour of mrcal]] calibration data to throw out all points outside of a circle at the center, calibrate off /that/ data, and run a diff on /those/ results: #+begin_src sh < corners.vnl \ mrcal-cull-corners --imagersize 6000 3376 --cull-rad-off-center 1500 \ > /tmp/raw.vnl && vnl-join --vnl-sort - -j filename /tmp/raw.vnl \ <(< /tmp/raw.vnl vnl-filter -p filename --has level | vnl-uniq -c | vnl-filter 'count > 20' -p filename ) \ > corners-rad1500.vnl mrcal-calibrate-cameras \ --corners-cache corners-rad1500.vnl \ --lensmodel LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=30_Ny=18_fov_x_deg=150 \ --focal 1900 \ --object-spacing 58.8e-3 \ --object-width-n 14 \ '*.JPG' mrcal-show-projection-uncertainty \ --distance 1 \ --unset key \ splined-rad1500.cameramodel mrcal-show-projection-diff \ --distance 1 \ --unset key \ splined{,-rad1500}.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ < $D/corners.vnl \ mrcal-cull-corners --imagersize 6000 3376 --cull-rad-off-center 1500 \ > /tmp/raw.vnl && vnl-join --vnl-sort - -j filename /tmp/raw.vnl \ <(< /tmp/raw.vnl vnl-filter -p filename --has level | vnl-uniq -c | vnl-filter 'count > 20' -p filename ) \ > $D/corners-rad1500.vnl ~/projects/mrcal/mrcal-calibrate-cameras \ --corners-cache $D/corners-rad1500.vnl \ --lensmodel LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=30_Ny=18_fov_x_deg=150 \ --imagersize 6000 3376 \ --focal 1900 \ --object-spacing 58.8e-3 \ --object-width-n 14 \ --out /tmp \ '*.JPG' mv /tmp/camera-0.cameramodel $D/splined-rad1500.cameramodel ~/projects/mrcal/mrcal-show-projection-uncertainty \ --distance 1 \ --unset key \ $D/splined-rad1500.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/uncertainty/uncertainty-splined-rad1500-1m.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' ~/projects/mrcal/mrcal-show-projection-diff \ --distance 1 \ --unset key \ $D/splined{,-rad1500}.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/diff/diff-weighted-splined-rad1500.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' #+end_src The cut-down corners are [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/corners-rad1500.vnl][here]] and the resulting model is [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/splined-rad1500.cameramodel][here]]. The uncertainty of this model looks like this: [[file:external/figures/uncertainty/uncertainty-splined-rad1500-1m.png]] and the diff like this: [[file:external/figures/diff/diff-weighted-splined-rad1500.png]] This is yet another reason to use only splined models for real-world lens modeling. We just demonstrated that projection uncertainties provide a working method for selecting the points used to fit the implied transformation. From a practical standpoint, there's a downside: computing uncertainties makes the differencing method much slower. So while the uncertainty-aware method is available in [[file:mrcal-show-projection-diff.html][=mrcal-show-projection-diff=]], most of the time I run something like =mrcal-show-projection-diff --no-uncertainties --radius 500=. This falls back on simply using the points in a 500-pixel-radius circle at the center. This computes much faster, and with good-coverage-low-error calibrations usually produces a very similar result. If something looks odd, I will run the uncertainty-aware diff to debug. But my usual default is =--no-uncertainties=. * Extrinsics differences :PROPERTIES: :CUSTOM_ID: extrinsics-diff :END: The above technique can be used to quantify intrinsics differences between two representations of the same lens. This is useful, for instance, to detect any intrinsics calibration drift over time. This doesn't tell us anything about extrinsics drift, however. It's possible to have a multi-camera system composed of very stable lenses mounted on a not-rigid-enough mount. Any mechanical stress wouldn't affect the intrinsics, but the extrinsics /would/ shift. And we want a method to quantify this shift . I haven't needed to do this very often, so the technique I'm using isn't mature yet. The extrinsics diff computation is implemented in the [[https://github.com/dkogan/mrcal/blob/master/analyses/extrinsics-stability.py][=extrinsics-stability.py= tool]]. This isn't stable yet, and only exists in the mrcal sources for now. But I used it several times, and it appears to work well. In this description I will consider 2-camera systems, but the approach is general for any number of cameras. Let's say we have two calibrations (0 and 1) of a stereo pair ($\mathrm{left}$ and $\mathrm{right}$ cameras). Between the calibrations the system was stressed (shaked, flipped, heated, etc), and we want to know if the camera geometry shifted as a result. The obvious technique is to compare the transformation $T_{0\mathrm{left},0\mathrm{right}}$ and $T_{1\mathrm{left},1\mathrm{right}}$. Each of these is available directly in the two calibrations, and we can compute the difference $T_{0\mathrm{right},1\mathrm{right}} = T_{0\mathrm{right},0\mathrm{left}} T_{1\mathrm{left},1\mathrm{right}}$. This is the transform between the right cameras in the two calibrations if we line up the two left cameras. This approach sounds good, but it is incomplete because it ignores the transformation implied by the different intrinsics, as described above. So lining up the two left cameras does not line up their projection behavior. And comparing the poses of the right cameras does not compare their projection behavior. We just talked about how to compute the implied transforms ${T^\mathrm{implied}_{0\mathrm{left},1\mathrm{left}}}$ and $T^\mathrm{implied}_{0\mathrm{right},1\mathrm{right}}$. So the final transformation describing the shift of the right camera is \[ T^\mathrm{implied}_{1\mathrm{right},0\mathrm{right}} T_{0\mathrm{right},0\mathrm{left}} T^\mathrm{implied}_{0\mathrm{left},1\mathrm{left}} T_{1\mathrm{left},1\mathrm{right}} \] The [[https://github.com/dkogan/mrcal/blob/master/analyses/extrinsics-stability.py][=extrinsics-stability.py= tool]] implements this logic. To compute the implied transformations we want the "true" transform, not a transform at any particular range, so we use a near and a far range. I tried this out in practice on a physical camera pair. I had calibrations before and after a lot of mechanical jostling happened. And for each calibration I had an odd and even set for [[file:tour-cross-validation.org][cross-validation]], which reported very low intrinsics differences: the intrinsics were "correct". I evaluated the extrinsics stability, looking at the odd calibrations: #+begin_example $ ~/projects/mrcal/analyses/extrinsics-stability.py \ BEFORE/camera-0-odd-SPLINED.cameramodel \ BEFORE/camera-1-odd-SPLINED.cameramodel \ AFTER/camera-0-odd-SPLINED.cameramodel \ AFTER/camera-1-odd-SPLINED.cameramodel translation: 0.04mm in the direction [0.13 0.06 0.99] rotation: 0.01deg around the axis [ 0.93 0.32 -0.18] #+end_example So it claims that the right camera shifted by 0.04mm and yawed by 0.01deg. This sounds low-enough to be noise, but what /is/ the noise level? The tool also reports the camera resolution for comparison against the reported rotation: #+begin_example Camera 0 has a resolution of 0.056 degrees per pixel at the center Camera 1 has a resolution of 0.057 degrees per pixel at the center Camera 2 has a resolution of 0.056 degrees per pixel at the center Camera 3 has a resolution of 0.057 degrees per pixel at the center #+end_example So this rotation is far smaller than one pixel. What if we look at the allegedly-identical "even" calibration: #+begin_example $ ~/projects/mrcal/analyses/extrinsics-stability.py \ BEFORE/camera-0-even-SPLINED.cameramodel \ BEFORE/camera-1-even-SPLINED.cameramodel \ AFTER/camera-0-even-SPLINED.cameramodel \ AFTER/camera-1-even-SPLINED.cameramodel translation: 0.07mm in the direction [ 0.63 -0.73 0.25] rotation: 0.00deg around the axis [ 0.55 -0.32 0.77] #+end_example That's similarly close to 0. What if instead of comparing before/after we compare odd/even before and then odd/even after? odd/even happened at the same time, so there was no actual shift, and the result will be at the noise floor. #+begin_example $ ~/projects/mrcal/analyses/extrinsics-stability.py \ BEFORE/camera-0-odd-SPLINED.cameramodel \ BEFORE/camera-1-odd-SPLINED.cameramodel \ BEFORE/camera-0-even-SPLINED.cameramodel \ BEFORE/camera-1-even-SPLINED.cameramodel translation: 0.07mm in the direction [0.09 0.76 0.64] rotation: 0.00deg around the axis [ 0.77 -0.1 -0.63] $ ~/projects/mrcal/analyses/extrinsics-stability.py \ AFTER/camera-0-odd-SPLINED.cameramodel \ AFTER/camera-1-odd-SPLINED.cameramodel \ AFTER/camera-0-even-SPLINED.cameramodel \ AFTER/camera-1-even-SPLINED.cameramodel translation: 0.05mm in the direction [9.69e-01 8.13e-04 2.46e-01] rotation: 0.00deg around the axis [-0.43 -0.78 0.44] #+end_example So with these calibrations we have strong evidence that no extrinsics drift has occurred. More testing and development of this method are planned, and this tool will be further documented and released. mrcal-2.4.1/doc/examples/000077500000000000000000000000001456301662300152055ustar00rootroot00000000000000mrcal-2.4.1/doc/examples/dense-stereo-demo/000077500000000000000000000000001456301662300205245ustar00rootroot00000000000000mrcal-2.4.1/doc/examples/dense-stereo-demo/dense-stereo-demo.cc000066400000000000000000000266511456301662300243640ustar00rootroot00000000000000// Sample dense stereo pipeline, implemented using the C mrcal API. This is a // C++ source file because the remapping and disparity search come from OpenCV, // which is a C++ library. The mrcal calls are C functions // // On a Debian machine you can build like this: // g++ \ // -I/usr/include/opencv4 \ // -fpermissive \ // dense-stereo-demo.cc \ // -lopencv_core \ // -lopencv_calib3d \ // -lopencv_imgproc \ // -lmrcal \ // -o dense-stereo-demo // // The -fpermissive is required for the C++ compiler to accept C99 code. // // Note: this sample code does not bother to deallocate any memory. #include #include #include #include #include extern "C" { #include "mrcal.h" } static cv::Mat remap(const float* map, const mrcal_image_uint8_t* image, const int remapped_width, const int remapped_height) { cv::Mat cv_image(image->height, image->width, CV_8UC1, image->data, image->stride); cv::Mat cv_remapped(remapped_height, remapped_width, CV_8UC1); cv::Mat cv_map(remapped_height, remapped_width, CV_32FC2, (void*)map); cv::remap( cv_image, cv_remapped, cv_map, cv::Mat(), cv::INTER_LINEAR ); return cv_remapped; } int main(int argc, char* argv[]) { // https://mrcal.secretsauce.net/external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/0.cameramodel // https://mrcal.secretsauce.net/external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/1.cameramodel const char* model_filenames[] = { "/tmp/0.cameramodel", "/tmp/1.cameramodel" }; // https://mrcal.secretsauce.net/external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/0.jpg // https://mrcal.secretsauce.net/external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/1.jpg const char* image_filenames[] = { "/tmp/0.jpg", "/tmp/1.jpg", }; // Hard-coded rectified field-of-view and center-of-view parameters mrcal_point2_t azel_fov_deg = {170., 60.}; mrcal_point2_t azel0_deg = {}; const int disparity_min = 0; const int disparity_max = 256; // hard-coded scale used by OpenCV SGBM const int disparity_scale = 16; // Use the same resolution in the rectified image as in the input image double pixels_per_deg_az = -1.; double pixels_per_deg_el = -1.; mrcal_cameramodel_t* models[2]; mrcal_image_uint8_t images[2]; //// Read the models from disk for(int i=0; i<2; i++) { models[i] = mrcal_read_cameramodel_file(model_filenames[i]); if(models[i] == NULL) { fprintf(stderr, "Error loading model '%s'\n", model_filenames[i]); return 1; } if(!mrcal_image_uint8_load(&images[i], image_filenames[i])) { fprintf(stderr, "Error loading image '%s'\n", image_filenames[i]); return 1; } } //// Compute the rectified system mrcal_cameramodel_LENSMODEL_LATLON_t model_rectified0 = { .lensmodel = { .type = MRCAL_LENSMODEL_LATLON } }; double baseline; if(!mrcal_rectified_system(// output model_rectified0.imagersize, model_rectified0.intrinsics, model_rectified0.rt_cam_ref, &baseline, // input, output &pixels_per_deg_az, &pixels_per_deg_el, &azel_fov_deg, &azel0_deg, // input &models[0]->lensmodel, models[0]->intrinsics, models[0]->rt_cam_ref, models[1]->rt_cam_ref, model_rectified0.lensmodel.type, // autodetect nothing false,false,false,false)) { fprintf(stderr, "Error calling mrcal_rectified_system()\n"); return 1; } //// Compute the rectification maps const int rectified_width = model_rectified0.imagersize[0]; const int rectified_height = model_rectified0.imagersize[1]; float* rectification_maps = (float*)aligned_alloc(0x10, rectified_width* rectified_height* 2*2*sizeof(float)); if(rectification_maps == NULL) { fprintf(stderr, "Error calling malloc()\n"); return 1; } if(!mrcal_rectification_maps(// output rectification_maps, // input &models[0]->lensmodel, models [0]->intrinsics, models [0]->rt_cam_ref, &models[1]->lensmodel, models [1]->intrinsics, models [1]->rt_cam_ref, model_rectified0.lensmodel.type, model_rectified0.intrinsics, model_rectified0.imagersize, model_rectified0.rt_cam_ref) ) { fprintf(stderr, "Error calling mrcal_rectification_maps()\n"); return 1; } //// Use the rectification maps to compute the rectified images cv::Mat cv_left_rect = remap(&rectification_maps[0], &images[0], rectified_width, rectified_height); cv::Mat cv_right_rect = remap(&rectification_maps[rectified_width* rectified_height* 2], &images[1], rectified_width, rectified_height); //// Write the rectified images to disk mrcal_image_uint8_save("/tmp/rect-left.png", &(mrcal_image_uint8_t) { .width = rectified_width, .height = rectified_height, .stride = rectified_width, .data = (uint8_t*)cv_left_rect.data }); fprintf(stderr, "Wrote '/tmp/rect-left.png'\n"); mrcal_image_uint8_save("/tmp/rect-right.png", &(mrcal_image_uint8_t) { .width = rectified_width, .height = rectified_height, .stride = rectified_width, .data = (uint8_t*)cv_right_rect.data }); fprintf(stderr, "Wrote '/tmp/rect-right.png'\n"); //// Disparity search cv::Mat cv_disparity; cv::Ptr sgbm = cv::StereoSGBM::create(disparity_min, disparity_max-disparity_min, 3, 600, 2400, 1, 0, 5, 100, 2); sgbm->compute(cv_left_rect, cv_right_rect, cv_disparity); mrcal_image_uint16_t image_disparity = { .width = rectified_width, .height = rectified_height, .stride = rectified_width*2, .data = (uint16_t*)cv_disparity.data }; mrcal_image_bgr_t image_color_disparity = { .width = rectified_width, .height = rectified_height, .stride = (int)(rectified_width*sizeof(mrcal_bgr_t)), .data = (mrcal_bgr_t*)malloc(rectified_height* rectified_width*sizeof(mrcal_bgr_t)) }; if(image_color_disparity.data == NULL) { fprintf(stderr, "Error: malloc() failed\n"); return 1; } if(!mrcal_apply_color_map_uint16(&image_color_disparity, &image_disparity, // no auto range false,false, // auto function true, disparity_min*disparity_scale, disparity_max*disparity_scale, // ignored functions 0,0,0)) { fprintf(stderr, "Error: mrcal_apply_color_map_uint16() failed\n"); return 1; } mrcal_image_bgr_save("/tmp/disparity.png", &image_color_disparity); fprintf(stderr, "Wrote '/tmp/disparity.png'\n"); //// Convert disparities to ranges mrcal_image_double_t image_range = { .width = rectified_width, .height = rectified_height, .stride = (int)(rectified_width*sizeof(double)), .data = (double*)aligned_alloc(0x10, rectified_height* rectified_width*sizeof(double)) }; if(image_range.data == NULL) { fprintf(stderr, "Error: malloc() failed\n"); return 1; } if(!mrcal_stereo_range_dense(&image_range, &image_disparity, disparity_scale, disparity_min * disparity_scale, disparity_max * disparity_scale, model_rectified0.lensmodel.type, model_rectified0.intrinsics, baseline)) { fprintf(stderr, "Error: mrcal_stereo_range_dense() failed\n"); return 1; } mrcal_image_bgr_t image_color_range = { .width = rectified_width, .height = rectified_height, .stride = (int)(rectified_width*sizeof(mrcal_bgr_t)), .data = (mrcal_bgr_t*)malloc(rectified_height* rectified_width*sizeof(mrcal_bgr_t)) }; if(image_color_range.data == NULL) { fprintf(stderr, "Error: malloc() failed\n"); return 1; } const double range_min = 0; const double range_max = 1000; if(!mrcal_apply_color_map_double(&image_color_range, &image_range, // no auto range false,false, // auto function true, range_min, range_max, // ignored functions 0,0,0)) { fprintf(stderr, "Error: mrcal_apply_color_map_double() failed\n"); return 1; } mrcal_image_bgr_save("/tmp/range.png", &image_color_range); fprintf(stderr, "Wrote '/tmp/range.png'\n"); return 0; } mrcal-2.4.1/doc/formulation.org000066400000000000000000000762161456301662300164530ustar00rootroot00000000000000#+TITLE: Optimization problem formulation #+OPTIONS: toc:t * Overview mrcal contains a solver used to compute the [[file:lensmodels.org][lens models]] and/or geometry. This is accessible via either - =mrcal_optimize()= routine in the [[file:c-api.org][C API]] - [[file:mrcal-python-api-reference.html#-optimize][=mrcal.optimize()=]] routine in the [[file:python-api.org][Python API]] These are the main call in the [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras=]] tool (to calibrate cameras) and [[file:mrcal-convert-lensmodel.html][=mrcal-convert-lensmodel=]] tool (to fit a different lens model into an existing model). The optimization routines are more general than what these tools provide, and can solve other problems, such as structure-from-motion. Note that the APIs for handling discrete points are still unstable, so the SFM functionality remains lightly-documented for now. The solver moves around the /state/ vector $\vec b$, which contains all the geometry and all the lens models. For any hypothesis $\vec b$, the solver can predict the pixel coordinates where the hypothetical cameras would observe their hypothetical world. The differences between these predicted pixel observations and the actual pixel observations we gathered from looking at chessboards are stored in a /measurement/ vector $\vec x$. The solver then tries to find the set of geometry and lens parameters to best explain the observed pixel coordinates, so it seeks the $\vec b$ to minimize the cost function $E \equiv \left \Vert \vec x \left(\vec b\right)\right \Vert ^2$. The optimization library interfaces with mrcal by invoking a callback function for each hypothesis $\vec b$ to test. This callback function computes $\vec x$ and the local gradients $J \equiv \frac{\partial \vec x}{\partial \vec b}$ (large and sparse). For analysis, this callback function is available by itself via - =mrcal_optimizer_callback()= routine in the [[file:c-api.org][C API]] - [[file:mrcal-python-api-reference.html#-optimizer_callback][=mrcal.optimizer_callback()=]] routine in the [[file:python-api.org][Python API]] * World geometry :PROPERTIES: :CUSTOM_ID: world-geometry :END: There are 3 different coordinate systems in the optimization: - *frame* coordinate system: the local coordinate system of the chessboard. The chessboard is assumed mostly flat, with the grid of points lying in the $xy$ plane. The origin is at one of the corners. - *reference* coordinate system: the "world" coordinate system in the optimization problem. This coordinate system is the common system that ties everything together. Each chessboard pose is represented as a transformation between the local chessboard frame and the reference frame. And each camera pose is represented as the transformation between the local camera frame and the reference frame. Note that this coordinate system doesn't necessarily have any physical meaning. - *camera* coordinate system: the local coordinate system of each camera. The $x$ and $y$ axes are aligned with pixel coordinates in an image: $x$ is to the right and $y$ is down. $z$ is then forward to complete the right-handed system of coordinates. So the data flow to project a particular chessboard corner which sits at $\vec p_\mathrm{frame}$ in the local chessboard coordinate system is: \[ \vec q \xleftarrow{\mathrm{intrinsics}} \vec p_\mathrm{camera} \xleftarrow{T_\mathrm{cr}} \vec p_\mathrm{reference} \xleftarrow{T_\mathrm{rf}} \vec p_\mathrm{frame} \] where the intrinsics and the transformations $T_\mathrm{cr}$ and $T_\mathrm{rf}$ are all elements of the state vector. ** Geometric free variables If too many transformations are left as free variables for the optimizer to find, the system will be under-determined, and the optimization routine will fail: complaining about a "not positive definite" (singular in this case) Hessian. Example: we have 1 stationary camera observing 10 chessboards. We want to be able to uniquely represent the transformation between each chessboard and the camera, for a total of 10 transformations. If we optimize a camera pose $T_\mathrm{cr}$ camera and 10 separate chessboard poses $T_\mathrm{rf}$ for each chessboard, we will have 11 transformations in the optimization vector. Since 11 > 10, we have more variables in the optimization vector than are needed to uniquely describe the world. So the system is under-determined, and the optimization will fail. In a vanilla calibration problem such as this, we would address this by fixing the reference coordinate system to one of the camera or chessboard frames. The mrcal convention is to fix the reference coordinate system to camera 0, setting $T_\mathrm{cr}$ to the identity transformation. In the above example, this would reduce the number of transformations being optimized from 11 to 10, which resolves the issue. Any other method of making the optimization variables unique is valid also. For instance, the chessboard poses might be known. In that case we don't need to optimize any $T_\mathrm{rf}$, and solving for the $T_\mathrm{cr}$ is enough. ** The physical meaning of the /reference/ coordinate system The reference coordinate system is a single coordinate system common to the whole optimization problem that all the objects in the world can use to localize themselves. It does /not/ have /any/ physical meaning beyond that. In particular, the reference coordinate system is /not/ attached to any fixed object in the world. Thus noise in the chessboard observations would shift the reference coordinate system, just as it would shift the camera and chessboard coordinate systems. The [[file:uncertainty.org][projection uncertainty]] documentation talks about this in depth. * Calibration object :PROPERTIES: :CUSTOM_ID: calibration-object :END: This is called a "chessboard" or just "board" in some parts of the code. The optimization code refers to the chessboard pose array as "frames". When running a camera calibration, we use observations of a known-geometry object. At this time mrcal expects this object to be a planar regular grid of observable points, possibly with a small amount of [[#board-deformation][deformation]]. Usually this object is a chessboard-like grid of black and white squares, where the observed points are at the corner of each square. Detections of these corners serve as the input features to mrcal. mrcal is a purely geometrical toolkit, and this vision problem must be [[file:how-to-calibrate.org::#corner-detector][handled by another library]]. ** Board deformation :PROPERTIES: :CUSTOM_ID: board-deformation :END: The calibration object is assumed to be nominally planar. However, large calibration boards used for calibration of wide lenses are never flat: temperature and humidity effects deform the board strongly-enough to affect the calibration. mrcal currently supports a simple 2-parameter deformation model. This model uses two axis-aligned parabolic factors. Let the chessboard grid span $[-1,1]$ along the $x$ and $y$ axes. Then I define the non-planar deformation as $z \equiv k_x (1 - x^2) + k_y (1 - y^2)$ with $k_x$ and $k_y$ being the two deformation factors being optimized by the solver. If the board were flat, $k_x$ and $k_y$ would be 0, and thus we would have $z=0$ everywhere. The deflection at the edges is 0, and is strongest at the center. Empirically, this appears to work well: I get better-fitting solves, and less systematic error. And the optimal deformation factors $k_x$, $k_y$ are consistent between different calibrations. Clearly, this does not work for especially strong or asymmetric deflections. There's a richer 5-parameter deformation model in a not-yet-released branch that appears to work even for asymmetric deflections. This needs more testing, and has not yet been released. Talk to Dima if you want to play with it. * Lens behavior :PROPERTIES: :CUSTOM_ID: lens-behavior :END: The fundamental operation to map a point in the camera coordinate system to a pixel where that point would be observed by the camera is called /projection/. mrcal supports [[file:lensmodels.org][multiple methods]] to model the behavior of different lenses. Of particular note is that at this time, mrcal assumes that all projections are /central/: all rays of light are assumed to intersect at a single point (the origin of the camera coordinate system). So $k \vec v$ projects to the same $\vec q$ for any $k$. This is very convenient, mostly true, and almost every camera library assumes this. This assumption breaks down when projecting observations /very/ close to the lens, with "close" being judged relative to the physical size of the lens. Extreme close-ups exhibit /non-central/ behavior: [[file:figures/noncentral.svg]] While [[file:tour-choreography.org::#choreography-distance][extreme close-ups are very good for calibration quality]], the working distance is usually past the range where non-central effects are observable. So it is recommended to avoid the non-central regime by keeping the chessboard far-enough out to make the central model work well. [[File:tour-cross-validation.org][Cross-validation]] can be used to verify whether noncentral effects are present. That said, support for /non-central/ lenses is coming in a future release of mrcal, which will allow us to model the noncentral behavior. * Optimization details The mrcal solver is an optimization routine based on sparse nonlinear least squares. The optimization loop is implemented in [[https://www.github.com/dkogan/libdogleg][=libdogleg=]], which at its core uses the [[https://people.engr.tamu.edu/davis/suitesparse.html][CHOLMOD solver]] to compute the [[https://en.wikipedia.org/wiki/Cholesky_decomposition][Cholesky factorization]], to then efficiently solve the linear system $J^T J \vec a = \vec b$ where the jacobian matrix $J$ is large and sparse. The optimization problem is posed without constraints. This is achieved by using [[https://en.wikipedia.org/wiki/Axis%E2%80%93angle_representation#Rotation_vector][Rodrigues vectors]] to represent rotations. A different rotation representation, such as one using unit quaternions or rotation matrices would require constraints: not all sets of 4 numbers are a unit quaternion, and not all sets of 9 numbers are a valid rotation matrix. The optimization algorithm is iterative, so it isn't guaranteed to converge to the global optimum. Thus it is imperative to pass a good *seed* (an initial estimate of the solution) to the optimization routines. The [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras=]] tool achieves this by 1. Computing an initial estimate directly using geometry and some simplifying assumptions. These geometric seeding routines are available standalone: - [[file:mrcal-python-api-reference.html#-estimate_monocular_calobject_poses_Rt_tocam][=mrcal.estimate_monocular_calobject_poses_Rt_tocam()=]]: Estimate camera-referenced poses of the calibration object from monocular views - [[file:mrcal-python-api-reference.html#-estimate_joint_frame_poses][=mrcal.estimate_joint_frame_poses()=]]: Estimate world-referenced poses of the calibration object - [[file:mrcal-python-api-reference.html#-seed_stereographic][=mrcal.seed_stereographic()=]]: Compute an optimization seed for a camera calibration 2. Refining that estimate with a sequences of optimization problems that allow more and more of the parameters to vary. The final problem is the /full/ problem where all the variables are free to move. The set of variables we're optimizing can be selected with the [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_problem_selections_t=]] structure passed to [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_optimize()=]] in C (or the =do_optimize_...= arguments to [[file:mrcal-python-api-reference.html#-optimize][=mrcal.optimize()=]] in Python). * State vector $\vec b$ :PROPERTIES: :CUSTOM_ID: state-vector :END: The state vector $\vec b$ is controlled by the optimization algorithm as it searches for the optimal solution. This vector may contain - *intrinsics*: the lens parameters of all the cameras in the optimization problem - *extrinsics*: the poses of all the cameras in the optimization problem. These are specified as unconstrained =rt= transformations from some arbitrary "reference". coordinate system, to the camera coordinate system. These are represented by $T_\mathrm{cr}$ in the flow diagram above - *frames*: the poses of all the chessboards in the optimization problem. These are specified as unconstrained =rt= transformations from the local chessboard coordinate system to some arbitrary "reference" coordinate system. These are represented by $T_\mathrm{rf}$ in the flow diagram above - *points*: the location in the reference coordinate system of any discrete points being observed. A vanilla "calibration" problem wouldn't have any of these, but an SFM problem would have many - *calibration-object warp*: the [[#board-deformation][deformation of the calibration object]] An optimization problem could contain /all/ those things, but it usually only contains a subset, depending on the specific problem being solved. Common problems are: - A vanilla calibration problem. We have stationary cameras observing a moving chessboard. $\vec b$ contains intrinsics and extrinsics and frames and the calibration-object warp - Structure-from-motion. We have moving cameras observing a stationary world. $\vec b$ contains extrinsics and points. - An intrinsics-fitting problem such as what [[file:mrcal-convert-lensmodel.html][=mrcal-convert-lensmodel=]] solves. $\vec b$ contains intrinsics and points Any other combination is possible. ** State vector layout When analyzing the behavior of the optimizer it is often useful to pick out particular elements of the full optimization vector $\vec b$. mrcal provides a number of functions to report the index and size of the block of $\vec b$ that contains specific data. In C: - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_state_index_intrinsics()=]]: Return the index in the optimization vector of the intrinsics of camera i - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_state_index_extrinsics()=]]: Return the index in the optimization vector of the extrinsics of camera i - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_state_index_frames()=]]: Return the index in the optimization vector of the pose of frame i - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_state_index_points()=]]: Return the index in the optimization vector of the position of point i - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_state_index_calobject_warp()=]]: Return the index in the optimization vector of the calibration object warp - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_num_states_intrinsics()=]]: Get the number of intrinsics parameters in the optimization vector - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_num_states_extrinsics()=]]: Get the number of extrinsics parameters in the optimization vector - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_num_states_frames()=]]: Get the number of calibration object pose parameters in the optimization vector - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_num_states_points()=]]: Get the number of point-position parameters in the optimization vector - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_num_states_calobject_warp()=]]: Get the number of parameters in the optimization vector for the board warp - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_num_states()=]]: Get the full length of the optimization vector And in Python: - [[file:mrcal-python-api-reference.html#-state_index_intrinsics][=mrcal.state_index_intrinsics()=]]: Return the index in the optimization vector of the intrinsics of camera i - [[file:mrcal-python-api-reference.html#-state_index_extrinsics][=mrcal.state_index_extrinsics()=]]: Return the index in the optimization vector of the extrinsics of camera i - [[file:mrcal-python-api-reference.html#-state_index_frames][=mrcal.state_index_frames()=]]: Return the index in the optimization vector of the pose of frame i - [[file:mrcal-python-api-reference.html#-state_index_points][=mrcal.state_index_points()=]]: Return the index in the optimization vector of the position of point i - [[file:mrcal-python-api-reference.html#-state_index_calobject_warp][=mrcal.state_index_calobject_warp()=]]: Return the index in the optimization vector of the calibration object warp - [[file:mrcal-python-api-reference.html#-num_states_intrinsics][=mrcal.num_states_intrinsics()=]]: Get the number of intrinsics parameters in the optimization vector - [[file:mrcal-python-api-reference.html#-num_states_extrinsics][=mrcal.num_states_extrinsics()=]]: Get the number of extrinsics parameters in the optimization vector - [[file:mrcal-python-api-reference.html#-num_states_frames][=mrcal.num_states_frames()=]]: Get the number of calibration object pose parameters in the optimization vector - [[file:mrcal-python-api-reference.html#-num_states_points][=mrcal.num_states_points()=]]: Get the number of point-position parameters in the optimization vector - [[file:mrcal-python-api-reference.html#-num_states_calobject_warp][=mrcal.num_states_calobject_warp()=]]: Get the number of parameters in the optimization vector for the board warp - [[file:mrcal-python-api-reference.html#-num_states][=mrcal.num_states()=]]: Get the full length of the optimization vector If plotting a whole vector of state, it is helpful to annotate the plot to make it clear which variables correspond to each block of state. mrcal provides a helper function to help with this: - [[file:mrcal-python-api-reference.html#-plotoptions_state_boundaries][=mrcal.plotoptions_state_boundaries()=]]: Return the =set= plot options for gnuplotlib to show the state boundaries ** State vector scaling :PROPERTIES: :CUSTOM_ID: state-packing :END: The nonlinear least squares-solving library used by mrcal is [[https://www.github.com/dkogan/libdogleg][=libdogleg=]], which implements [[https://en.wikipedia.org/wiki/Powell's_dog_leg_method][Powell's dogleg method]]. This is a trust-region algorithm that represents the trust region as a ball in state space. I.e. the radius of this trust region is the same in every direction. And /that/ means that the optimization will work best when each state variable in $\vec b$ affects the cost function $E$ evenly. Example of what we don't want: camera positions measured in km, while the chessboard positions are measured in mm, with both sets of these very different numbers stored in $\vec b$. Clearly getting identical behavior from each variable is impossible, but we can scale the elements of $\vec b$ to keep things more or less even. mrcal applies this scaling, and the =libdogleg= optimization library never sees the full state vector $\vec b$, but the scaled vector $\vec b_\mathrm{packed}$. Similarly, it never sees the full jacobian $J \equiv \frac{\partial \vec x}{\partial \vec b}$, but rather $J_\mathrm{packed} \equiv \frac{\partial \vec x}{\partial \vec b_\mathrm{packed}}$. This means that the optimization callback functions report packed state. These are - =mrcal_optimizer_callback()= routine in the [[file:c-api.org][C API]] - [[file:mrcal-python-api-reference.html#-optimizer_callback][=mrcal.optimizer_callback()=]] routine in the [[file:python-api.org][Python API]] To pack or unpack an array of state, mrcal provides some routines. In C: - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_pack_solver_state_vector()=]]: Scales a state vector to the packed, unitless form used by the optimizer - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_unpack_solver_state_vector()=]]: Scales a state vector from the packed, unitless form used by the optimizer And in Python: - [[file:mrcal-python-api-reference.html#-pack_state][=mrcal.pack_state()=]]: Scales a state vector to the packed, unitless form used by the optimizer - [[file:mrcal-python-api-reference.html#-unpack_state][=mrcal.unpack_state()=]]: Scales a state vector from the packed, unitless form used by the optimizer * Measurement vector $\vec x$ Given a hypothesis state vector $\vec b$ mrcal computes a vector of errors, or /measurements/ $\vec x$. The optimization algorithm searches the space of hypotheses $\vec b$, trying to minimize $E \equiv \left \Vert \vec x \right \Vert^2$. We know where each point was observed in reality, and we know where the state vector $\vec b$ predicts each one would have been observed. So we can construct a vector of errors $\vec q_\mathrm{err} \equiv \vec q_\mathrm{predicted}\left( \vec b \right) - \vec q_\mathrm{ref}$. From the [[#noise-model][noise analysis]] we derive a matrix of weights $W$ to construct \[ \vec x_\mathrm{observations} \equiv W q_\mathrm{err} = W \left( \vec q_\mathrm{predicted}\left( \vec b \right) - \vec q_\mathrm{ref} \right) \] This is the bulk of the measurement vector. ** Regularization :PROPERTIES: :CUSTOM_ID: Regularization :END: In addition to $\vec x_\mathrm{observations}$, the measurement vector contains [[https://en.wikipedia.org/wiki/Regularization_(mathematics)][/regularization/]] terms. These are mostly-insignificant terms that are meant to improve the convergence of the solver. They are also aphysical, and cause a bias in the solution, so mrcal is careful to keep these small-enough to not break anything noticeably. The behavior of these terms is likely to change in the future, so I don't document these in detail; please consult the sources. Currently the logic is at the end of the [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.c][=optimizer_callback()=]] function in =mrcal.c=. It is possible to control whether a solve does/does not include regularization terms with the =do_apply_regularization= bit in [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_problem_selections_t=]] or the =do_apply_regularization= key in the call to [[file:mrcal-python-api-reference.html#-optimize][=mrcal.optimize()=]]. ** Measurement vector layout When analyzing the behavior of the optimizer it is often useful to pick out particular elements of the full measurement vector $\vec x$. mrcal provides a number of functions to report the index and size of the block of $\vec x$ that contains specific data. In C: - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_measurement_index_boards()=]]: Return the measurement index of the start of a given board observation - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_measurement_index_points()=]]: Return the measurement index of the start of a given point observation - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_measurement_index_regularization()=]]: Return the index of the start of the regularization measurements - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_num_measurements_boards()=]]: Return how many measurements we have from calibration object observations - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_num_measurements_points()=]]: Return how many measurements we have from point observations - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_num_measurements_regularization()=]]: Return how many measurements we have from regularization - [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_measurements()=]]: Return how many measurements we have in the full optimization problem And in Python: - [[file:mrcal-python-api-reference.html#-measurement_index_boards][=mrcal.measurement_index_boards()=]]: Return the measurement index of the start of a given board observation - [[file:mrcal-python-api-reference.html#-measurement_index_points][=mrcal.measurement_index_points()=]]: Return the measurement index of the start of a given point observation - [[file:mrcal-python-api-reference.html#-measurement_index_regularization][=mrcal.measurement_index_regularization()=]]: Return the index of the start of the regularization measurements - [[file:mrcal-python-api-reference.html#-num_measurements_boards][=mrcal.num_measurements_boards()=]]: Return how many measurements we have from calibration object observations - [[file:mrcal-python-api-reference.html#-num_measurements_points][=mrcal.num_measurements_points()=]]: Return how many measurements we have from point observations - [[file:mrcal-python-api-reference.html#-num_measurements_regularization][=mrcal.num_measurements_regularization()=]]: Return how many measurements we have from regularization - [[file:mrcal-python-api-reference.html#-num_measurements][=mrcal.num_measurements()=]]: Return how many measurements we have in the full optimization problem If plotting a whole vector of measurements, it is helpful to annotate the plot to make it clear which values correspond to each block of measurements. mrcal provides a helper function to help with this: - [[file:mrcal-python-api-reference.html#-plotoptions_measurement_boundaries][=mrcal.plotoptions_measurement_boundaries()=]]: Return the =set= plot options for gnuplotlib to show the measurement boundaries * Noise modeling :PROPERTIES: :CUSTOM_ID: noise-model :END: The [[file:uncertainty.org][projection uncertainty routine]] is used to gauge the effects of sampling error on the solve. This is done by modelling the noise in the input pixel observations, and propagating it through the solve. This assumes that model errors are insignificant. If the model errors /were/ significant, then - the computed projection uncertainty would underestimate the expected errors: the non-negligible model errors would be ignored - the computed calibration would be biased: the residuals $\vec x$ would be heteroscedastic, so the computed optimum would /not/ be a maximum-likelihood estimate of the true calibration ** Noise on the inputs :PROPERTIES: :CUSTOM_ID: noise-model-inputs :END: I solve the calibration problem using [[https://en.wikipedia.org/wiki/Ordinary_least_squares][Ordinary Least Squares]], minimizing the discrepancies between pixel observations and their predictions. The pixel observations $\vec q_\mathrm{ref}$ are noisy, and I assume that they are zero-mean, independent and normally-distributed. In particular, I treat the 2 values in each observation ($x$ and $y$) as two independent measurements. I have no proof that the noise truly meets all those criteria, but empirical evidence suggests that these are all reasonable assumptions. And they simplify lots of analyses that we want to do. In order to propagate the input noise, we need to quantify it: for the $i$ -th observed point, what is $\mathrm{Var}\left(\vec q_{\mathrm{ref}_i}\right)$? Chessboard corner detectors often make it easy to infer the /relative/ accuracy levels between the different corners, as opposed to an /absolute/ noise level for each one. Thus the implementation splits the observed noise into two parts: - The baseline standard deviation of the noise $\sigma$. This is one value that applies to /all/ the observations - The scale $s_i$ applied to that baseline. These are different for each observed corner The [[https://github.com/dkogan/mrgingham/][=mrgingham=]] corner detector, in particular, reports the resolution used in detecting each corner as a decimation level: level-0 is "full-resolution", level-1 is "half-resolution" and so on. From that decimation level we get the relative scale \[ s_i \equiv 2^{\mathrm{level}} \] and we can define the 2x2 variance for each observed corner \[ \mathrm{Var}\left( \vec q_{\mathrm{ref}_i} \right) = s_i^2 \sigma^2 I \] and the variance for all the pixel observations \[\mathrm{Var}\left(\vec q_\mathrm{ref}\right) = \mathrm{diag}\left(s_i^2\right) \sigma^2 \] The remaining piece is to compute $\sigma$, but this is hard to measure directly. There's an [[https://github.com/dkogan/mrgingham/blob/master/mrgingham-observe-pixel-uncertainty][attempt]] in mrgingham, but it doesn't obviously work well. Thus the current method is to estimate $\sigma$ from the solve residuals: \[\sigma = \sqrt{\mathrm{Var}\left( \vec x^*_\mathrm{observations} \right)}\] where $\vec x^*$ is the measurement vector at the optimum. If all the assumptions are satisfied and we have enough data, then the input noise is the only source of error, and the only thing that affects the optimal $\vec x$, and this way of evaluating $\sigma$ is reasonable. If we have too little data, we're going to be overfitting, and the $\sigma$ computed using the above method will be too low. The current thought is that this will be hard to do with chessboards and even a half-hearted calibration will always have enough data. So mrcal currently doesn't try to catch this case. This might be added in the future. ** Noise in the measurement vector $\vec x$ :PROPERTIES: :CUSTOM_ID: noise-in-measurement-vector :END: We know where each point was observed in reality, and we know where the state vector $\vec b$ predicts each one would have been observed. So we can construct a vector of errors $\vec q_\mathrm{err} \equiv \vec q_\mathrm{predicted}\left( \vec b \right) - \vec q_\mathrm{ref}$. For the purposes of optimization we want to weight the errors of uncertain observations less than confident ones, and to do that we can use the same $s_i$ scale factor we computed earlier. For point $i$ I define the weight \[w_i \equiv \frac{1}{s_i} \] Let's construct a diagonal matrix of all these weights: $W \equiv \mathrm{diag}\left( \vec w \right)$. Then the measurement vector is \[ \vec x_\mathrm{observations} \equiv W q_\mathrm{err} = W \left( \vec q_\mathrm{predicted}\left( \vec b \right) - \vec q_\mathrm{ref} \right) \] If we assume that the model fits the data and that we have enough data to not overfit (both reasonable assumptions), then \[\mathrm{Var}\left( \vec x_\mathrm{observations} \right) = W \mathrm{Var}\left( \vec q_\mathrm{ref} \right) W^T = \sigma^2 I \] where $\sigma$ is the input noise we're propagating. Furthermore, $\vec x_\mathrm{observations}$ is homoscedastic: each element as the same variance. I make two more (reasonable) assumptions: - The rest of the measurement vector $\vec x$ ([[#Regularization][regularization]]) is insignificant - I consider the linear problem at the local linearization of my nonlinear system And then I can make a larger statement: the optimal parameter vector we compute from the least-squares optimization is the maximum-likelihood estimate of the true solution. * Outlier rejection :PROPERTIES: :CUSTOM_ID: outlier-rejection :END: Some of the input may not fit the model due to errors in the input data (chessboard corner mis-detections or motion blur for instance) or due to the model not being able to represent reality (insufficiently-flexible lens model or [[#board-deformation][board deformation model]] for instance). Either of these would violate the [[#noise-model][noise model]], which could bias the resulting estimate. Finding and detecting such points would eliminate such a bias. Currently mrcal employs a very simple outlier-rejection scheme. More or less, all measurements that have $x_i$ beyond some $k$ standard deviations above 0 are thrown out as outliers. See [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.c][=markOutliers()=]] for details. This scheme is effective in handling small numbers of obvious outliers. Any subtle outliers will get through, and will poison the solve. So it is imperative that the input data is as clean as possible. More sophisticated methods are under development. mrcal-2.4.1/doc/how-to-calibrate.org000066400000000000000000002216321456301662300172470ustar00rootroot00000000000000#+TITLE: How to run a calibration #+OPTIONS: toc:t Calibrating cameras is one of the main applications of mrcal, so I describe this process in some detail here. * Capturing images ** Calibration object We need to get images of a [[file:formulation.org::#calibration-object][calibration object]], a board containing an observable grid of points. mrcal doesn't care where these observations come from: any tool that can produce a table of corner observations can be utilized. Currently the recommended method is to use a classical /chessboard/ target, and to employ the [[https://github.com/dkogan/mrgingham][mrgingham]] detector. The mrgingham documentation has a [[https://github.com/dkogan/mrgingham/raw/master/chessboard.14x14.pdf][.pdf of a chessboard pattern]] that works well. See the [[file:recipes.org::#non-mrgingham-detector][recipes]] to use a non-mrgingham detector and/or a non-chessboard object. *** Chessboard shape :PROPERTIES: :CUSTOM_ID: chessboard-shape :END: The pattern should be printed and mounted onto a /rigid/ and /flat/ surface to produce the calibration object. The [[file:formulation.org][optimization problem]] assumes the board shape to be constant over all the calibration images, and any instability in the board shape breaks that assumption. Depending on the resolution of the camera and the amount of calibration accuracy required, even a slightly floppy chessboard can break things. Don't take this for granted. A method for quantifying this effect appears [[#residuals-chessboard-shape][below]]. Similarly, the optimization problem assumes that the calibration object is mostly flat. Some amount of deformation is inevitable, so mrcal /does/ support a simple [[file:formulation.org::#board-deformation][non-planar board]] model, with the board shape being computed as part of the calibration solve. In my experience, if you try to make sure the board is flat, this model is enough to fix most of the unavoidable small deflections. If care isn't taken to ensure the board is flat, the current simple deformation model is often insufficient to fully model the shape. Don't take this for granted either. A method for quantifying this effect appears [[#residuals-chessboard-shape][below]] as well. I usually use a square chessboard roughly 1m per side to calibrate my fisheye lenses. Such a large chessboard often has issues with its shape. To mitigate these, my chessboard is backed by about 1 inch of aluminum honeycomb. This is expensive, but works well to stabilize the shape. The previous board I was using is backed with the same amount of /foam/ instead. This is significantly cheaper, and still pretty good, but noticeably less flat and less rigid. This foam-backed board does warp with variations in temperature and humidity, but this drift is slow, and the shape is /usually/ stable long-enough for a chessboard dance. If you can make one, the aluminum honeycomb-backed boards are strongly recommended. *** Chessboard size :PROPERTIES: :CUSTOM_ID: chessboard-size :END: There's a tradeoff to consider between large and small chessboards. According to the [[file:tour-choreography.org::#choreography-distance][dance study]], we want close-ups that fill the imager, so we're choosing between small chessboards placed near the camera and large chessboards placed away from the camera. - Small chessboards placed close to the camera produce two issues: 1. the chessboard would appear out of focus. This is OK up to a point (out-of-focus blur is mostly isotropic, and this noise averages out nicely), but extreme out-of-focus images should probably be avoided 2. Extreme close-ups exhibit [[file:formulation.org::#lens-behavior][noncentral projection behavior]]: observation rays don't all intersect at the same point. Today's mrcal cannot model this behavior, so extreme close-ups should be avoided to allow the central-only models to fit. The [[file:tour-cross-validation.org][cross-validation page]] shows how to detect errors caused by noncentral projection - Large chessboards are better, but are difficult to manufacture, to keep them flat and stiff, and to move them around. Currently I use a 1m x 1m square board, which seems to be near the limit of what is reasonable. For wide lenses especially, you want a larger chessboard. When calibrating an unfamiliar system I usually try running a calibration with whatever chessboard I already have, and then analyze the results to see if anything needs to be changed. It's also useful to rerun the [[file:tour-choreography.org][dance study]] for the specific geometry being calibrated. ** Image-capturing details Now that we have a calibration object, this object needs to be shown to the camera(s). It is important that the images contain clear features. Motion blur or exposure issues will all cause bias in the resulting calibration. If calibrating multiple cameras, mrcal will solve for all the intrinsics /and/ extrinsics. There is one strong requirement on the captured images in this case: the images must be synchronized across all the cameras. This allows mrcal to assume that if camera A and camera B observed a chessboard at time T, then this chessboard was at /exactly/ the same location when the two cameras saw it. Generally this means that either - The cameras are wired to respond to a physical trigger signal - The chessboard and cameras were physically fixed (on a tripod, say) at each time of capture Some capture systems have a "software" trigger mode, but this is usually too loose to produce usable results. A similar consideration exists when using cameras with a [[https://en.wikipedia.org/wiki/Rolling_shutter][rolling shutter]]. With such cameras it is imperative that everything remain stationary during image capture, even when only one camera is involved. See the [[#residuals-sync][residual analysis of synchronization errors]] and [[#residuals-rolling-shutter][of rolling shutter]] for details. ** Lens settings Lens intrinsics are usually very sensitive to any mechanical manipulation of the lens. It is thus strongly recommended to set up the lens it its final working configuration (focal length, focus distance, aperture), then to mechanically lock down the settings, and then to gather the calibration data. This often creates dancing challenges, described in the next section. If you /really/ need to change the lens settings after calibrating or if you're concerned about drifting lens mechanics influencing the calibration (you should be!), see the [[file:recipes.org::#lens-stability][recipes]] for a discussion. ** Dancing :PROPERTIES: :CUSTOM_ID: dancing :END: As shown in the [[file:tour-choreography.org][dance study]], the most useful observations to gather are - close-ups: the chessboard should fill the whole frame as much as possible. - oblique views: tilt the board forward/back and left/right. I generally tilt by ~ 45 degrees. At a certain point the corners become indistinct and the detector starts having trouble, but depending on the lens, that point could come with quite a bit of tilt. A less dense chessboard eases this also, at the cost of requiring more board observations to get the same number of points. - If calibrating multiple cameras, it is impossible to place a calibration object at a location where it's seen by all the cameras /and/ where it's a close-up for all the cameras. So you should get close-ups for each camera individually, and also get observations common to multiple cameras, that aren't necessarily close-ups. The former will serve to define your camera intrinsics, and the latter will serve to define your extrinsics (geometry). Get just far-enough out to create the joint views. If usable joint views are missing, the extrinsics will be undefined, and the solver will complain about a "not positive definite" (singular in this case) Hessian. A dataset composed primarily of tilted closeups produces good results. As described [[#chessboard-size][above]], you want a large chessboard placed as close to the camera as possible, before the out-of-focus and noncentral effects kick in. If the model will be used to look at far-away objects, care must be taken to produce a reliable calibration /at long ranges/, not just at the /short/ ranges where the chessboards were. The primary way to do that is to get close-up chessboard views. If the close-up range is very different from the working range (infinity, possibly), the close-up images could be very out-of-focus. The current thought is that the best thing to do is to get close-up images even if they're out of focus. The blurry images will have a high uncertainty in the corner observations (hopefully without bias), but the uncertainty improvement that comes from the near-range chessboard observations more than makes up for it. In these cases you usually need to get more observations than you normally would to bring down the uncertainties to an acceptable level. In challenging situations it's useful to re-run the [[file:tour-choreography.org][dance study]] for the specific use case to get a sense of what kind of observations are required and what kind of uncertainties can be expected. See the [[file:tour-choreography.org][dance study]] for detail. Another issue that could be caused by extreme close-ups is a [[file:formulation.org::#lens-behavior][noncentral projection behavior]]: observation rays don't all intersect at the same point. Today's mrcal cannot model this behavior, and the [[file:tour-cross-validation.org][cross-validation]] would show higher-than-expected errors. In this case it is recommended to gather calibration data from further out. It is better to have more chessboard data rather than less. mrgingham will throw away frames where no chessboard can be found, so it is perfectly reasonable to grab too many images with the expectation that they won't all end up being used in the computation. I usually aim for about 100 usable frames, but you may get away with fewer, depending on your specific scenario. The mrcal uncertainty feedback will tell you if you need more data. Naturally, intrinsics are accurate only in areas where chessboards were observed: chessboard observations on the left side of the image tell us little about lens behavior on the right side. Thus it is imperative to cover the whole field of view during the chessboard dance. It is often tricky to get good data at the edges and corners of the imager, so care must be taken. Some chessboard detectors (mrgingham in particular) only report complete chessboards. This makes it extra-challenging to obtain good data at the edges: a small motion that pushes one chessboard corner barely out of bounds causes the whole observation to be discarded. It is thus /very/ helpful to be able to see a live feed of the camera as the images are being captured. In either case, checking the coverage is a great thing to do. The usual way to do this is indirectly: [[file:tour-uncertainty.org][by visualizing the projection uncertainty]]. Or by [[#Visualization][visualizing the obtained chessboard detections]] directly. ** Image file-naming convention With monocular calibrations, there're no requirements on image filenames: use whatever you like. If calibrating multiple synchronized cameras, however, the image filenames need to indicate which camera captured each image and at which time. I generally use =frameFFF-cameraCCC.jpg=. Images with the same =FFF= are assumed to have been captured at the same instant in time, and =CCC= identifies the camera. Naming images in this way is sufficient to communicate these mappings to mrcal. * Detecting corners :PROPERTIES: :CUSTOM_ID: corner-detector :END: A number of tools are available to detect chessboard corners (OpenCV is commonly used, and different organizations have their own in-house versions). None of the available ones worked well for my use cases, so I had to write my own, and I recommend it for all corner detections: [[https://github.com/dkogan/mrgingham/][=mrgingham=]]. mrgingham is fast and is able to find chessboard corners subject to very un-pinhole-like projections. At this time it has two limitations that will be lifted eventually: - It more or less assumes a regular grid of N-by-N corners (i.e. N+1-by-N+1 squares) - It requires /all/ the corners to be observed in order to report the detections from an image. Incomplete chessboard observations aren't supported If these are unacceptable, any other detector may be used instead. See the [[file:recipes.org::#non-mrgingham-detector][recipes]]. ** Using mrgingham Once mrgingham is [[file:install.org][installed]] or built from [[https://github.com/dkogan/mrgingham][source]], it can be run by calling the =mrgingham= executable. The sample in the [[file:tour-initial-calibration.org][tour of mrcal]] processes [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/images][these images]] to produce [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/corners.vnl][these chessboard corners]] like this: #+begin_src sh mrgingham --jobs 4 --gridn 14 '*.JPG' > corners.vnl #+end_src mrgingham tries to handle a variety of lighting conditions, including varying illumination across the image, but the corners must exist in the image in some form. At this time mrgingham returns /only/ complete chessboard views: if even one corner of the chessboard couldn't be found, mrgingham will discard the entire image. Thus it takes care to get data at the edges and in the corners of the imager. A live preview of the captured images is essential. Another requirement due to the design of mrgingham is that the board should be held with a flat edge parallel to the camera xz plane (parallel to the ground, usually). mrgingham looks for vertical and horizontal sequences of corners, but if the board is rotated diagonally, then none of these sequences are clearly "horizontal" or "vertical". ** Choice of calibration object When given an image of a /chessboard/, the detector is directly observing the feature we actually care about: the corner. Another common calibration board style is a grid of circles, where the feature of interest is the center of each circle. When given an image of such a grid of circles, the detector either - detects the contour at the edge of each circle - finds the pixel blob comprising each circle observation and from either of these, the detector infers the circle center. This can work when looking at head-on images, but when given tilted images subjected to non-pinhole lens behaviors, getting accurate circle centers from outer contours or blobs is /hard/. The resulting inaccuracies in the detections of circle centers will introduce biases into the solve that aren't modeled by the [[file:uncertainty.org][projection uncertainty routine]], so chessboards are /strongly/ recommended in favor of circle grids. Some other calibration objects use [[https://april.eecs.umich.edu/software/apriltag][AprilTags]]. mrcal [[file:formulation.org::#noise-model][assumes independent noise]] on each point observation, so correlated sources of point observations are also not appropriate sources of data. Thus using individual corners of AprilTags will be un-ideal: their noise is correlated. Using the /center/ of an AprilTag would eliminate this correlated noise, but maybe would have a similar inaccuracy problem that a grid of circles would have. If using a possibly-problematic calibration object such as a grid of circles or AprilTags, double-check the detections by [[file:recipes.org::#reproject-to-chessboard][reprojecting to calibration-object space]] after a solve has completed. ** Visualization :PROPERTIES: :CUSTOM_ID: Visualization :END: Once we have a =corners.vnl= from some chessboard detector, we can visualize the coverage. From the [[file:tour-initial-calibration.org][tour of mrcal]]: #+begin_example $ < corners.vnl \ vnl-filter -p x,y | \ feedgnuplot --domain --square --set 'xrange [0:6000] noextend' --set 'yrange [3376:0] noextend' #+end_example [[file:external/figures/calibration/mrgingham-coverage.png]] Doing this is usually unnecessary since the [[file:tour-uncertainty.org][projection uncertainty reporting]] shows the coverage (and more!), but it's good to be able to do this for debugging. * Model choice :PROPERTIES: :CUSTOM_ID: model-choice :END: Before calibrating we need to choose the model for representing the lenses. Use [[file:splined-models.org][=LENSMODEL_SPLINED_STEREOGRAPHIC=]]. This model works very well, and is able to represent real-world lenses better than the parametric models (all the other ones). This is true even for long, near-pinhole lenses. Depending on the specific lens and the camera resolution this accuracy improvement may not be noteworthy. But even in those cases, the splined model is flexible enough to get truthful [[file:uncertainty.org][projection uncertainty estimates]], so it's /still/ worth using. Today I use other models only if I'm running quick experiments: splined models have many more parameters, so things are slower. [[file:splined-models.org][=LENSMODEL_SPLINED_STEREOGRAPHIC=]] has several [[file:splined-models.org::#splined-models-configuration-selection][configuration variables]] that need to be set. The full implications of these choices still need to be studied, but the results appear fairly insensitive to these. I generally choose =order=3= to select cubic splines. I generally choose a rich model with fairly dense spline spacing. For instance the splined model used in the [[file:tour-initial-calibration.org][tour of mrcal]] has =Nx=30_Ny=18=. This has 30 spline knots horizontally and 18 vertically. You generally want =Ny= / =Nx= to roughly match the aspect ratio of the imager. The =Nx=30_Ny=18= arrangement is probably denser than it needs to be, but it works OK. The cost of such a dense spline is a bit of extra computation time and more stringent requirements on calibration data to fully and densely cover the imager. The last configuration parameter is =fov_x_deg=: the horizontal field-of-view of the lens. The splined model is defined by /knots/ spread out across space, the arrangement of these knots defined by the =fov_x_deg= parameter. We want the region in space defined by the knots to roughly match the region visible to the lens. A too-large =fov_x_deg= would waste some knots by placing them beyond where the lens can see. And a too-small =fov_x_deg= would restrict the projection representation on the edge of the image. An initial estimate of =fov_x_deg= can be computed from the datasheet of the lens. Then a test calibration should be computed using that value, and the [[file:mrcal-show-splined-model-correction.html][=mrcal-show-splined-model-correction=]] tool can then be used to validate that =fov_x_deg= parameter. In the [[file:tour-initial-calibration.org][tour of mrcal]] we get something like this: #+begin_src sh mrcal-show-splined-model-correction \ --set 'cbrange [0:0.1]' \ --unset grid \ --set 'xrange [:] noextend' \ --set 'yrange [:] noextend reverse' \ --set 'key opaque box' \ splined.cameramodel #+end_src [[file:external/figures/splined-models/splined-magnitude.png]] This is about what we want. The valid-intrinsics region covers most of the spline-in-bounds region without going out-of-bounds anywhere. In the [[file:tour-initial-calibration.org][tour of mrcal]] we followed this procedure to end up with - =LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=30_Ny=18_fov_x_deg=150= Getting this perfect isn't important, so don't spent a ton of time working on it. See [[file:splined-models.org::#splined models field of view selection][the lensmodel documentation]] for more detail. * Computing the calibration :PROPERTIES: :CUSTOM_ID: calibration :END: We have data; we have a lens model; we're ready. Let's compute the calibration using the [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras=]] tool. The invocation should look something like this: #+begin_src sh mrcal-calibrate-cameras \ --corners-cache corners.vnl \ --lensmodel LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=30_Ny=18_fov_x_deg=150 \ --focal 1900 \ --object-spacing 0.0588 \ --object-width-n 14 \ '*.JPG' #+end_src - =--corners-cache corners.vnl= says that the chessboard corner coordinates live in a file called =corners.vnl=. This is the output of the [[#corner-detector][corner detector]]. If this argument is omitted, or a non-existent file is given, [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras=]] will run mrgingham, and write the results into the given path. Thus the same command would be used to both compute the corners initially, and to reuse the pre-computed corners in subsequent runs. As described above, the =corners.vnl= file can come from any chessboard detector. If it's a detector that produces a 4th column of /weights/ instead of a decimation level, pass in =--corners-cache-has-weights= - =--lensmodel= specifies which lens model we're using for /all/ the cameras. See [[#model-choice][the "Model choice" section above]]. Not being able to select different models for different cameras is a current limitation of mrcal. If some very different lenses are present in the same calibration, I use a densely-spaced (high =Nx=, =Ny=) splined model with the =fov_x_deg= of the widest lens in the set. This wastes knots in the too-wide areas of the narrow lenses, but if the spline was dense-enough, there're enough knots remaining to fit the narrower lenses. - =--focal 1900= provides the initial estimate for the camera focal lengths, in pixels. This doesn't need to be extremely precise, but do try to get this close if possible. The focal length value to pass to =--focal= ($f_\mathrm{pixels}$) can be derived using the [[file:lensmodels.org::#lensmodel-stereographic][stereographic model]] definition: \[ f_\mathrm{pixels} \approx \frac{\mathrm{imager\_width\_pixels}}{4 \tan \frac{\mathrm{field\_of\_view\_horizontal}}{4}} \] This expression is a good initial estimate for both long and wide lenses. Note that the manufacturer-specified "field of view" and "focal length" values are usually poorly-defined: the former is different in all directions, and the latter is meaningless in wide lenses that are nowhere near the pinhole model. With a longer lens, we can assume pinhole behavior to get \[ f_\mathrm{pixels} = f_\mathrm{mm} \frac{\mathrm{imager\_width\_pixels}}{\mathrm{imager\_width\_mm}} \] As with the =fov_x_deg= parameter described in [[#model-choice][the "Model choice" section above]], running a test calibration with a rough estimate, and then passing in the much-closer optimized value is a good strategy. The optimized focal length is the first two values of the =intrinsics= vector in the result. Those two values should be similar, and anything around there should work well for =--focal=. - =--object-spacing= is the distance between neighboring corners in the chessboard. Even spacing, identical in both directions is assumed - =--object-width-n= is the horizontal corner count of the calibration object. In the example invocation above there is no =--object-height-n=, so [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras=]] assumes a square chessboard After the options, [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras=]] takes globs describing the images. One glob per camera is expected, and in the above example /one/ glob was given: ='*.JPG'=. Thus this is a monocular solve. More cameras would imply more globs. For instance a 2-camera calibration might take arguments #+begin_example 'frame*-camera0.png' 'frame*-camera1.png' #+end_example Note that these are /globs/, not /filenames/. So they need to be quoted or escaped to prevent the shell from expanding them: hence ='*.JPG'= and not =*.JPG=. Finally, to compute [[#cross-validation][cross-validation diffs (see below)]] it's necessary to run several independent calibrations. I generally split the dataset into even/odd chunks, and calibrate them independently. With this =zsh= snippet, for instance: #+begin_src sh for oddeven (odd even) { cmd=(mrcal-calibrate-cameras \ --corners-cache corners.vnl \ --lensmodel LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=30_Ny=18_fov_x_deg=150 \ --focal 1900 \ --object-spacing 0.0588 \ --object-width-n 14) if [[ $oddeven = "even" ]] { globs=('frame*[02468]-camera'{0,1}'.png') } else { globs=('frame*[13579]-camera'{0,1}'.png') } cmd=($cmd $globs) $cmd for i (0 1) { mv camera-$i.cameramodel camera-$i-$oddeven.cameramodel } } #+end_src ** Troubleshooting broken solves Usually the solver converges, and produces a result. Then we [[#interpreting-results][look at the diagnostics to evaluate the quality of this result]] (next section). We can do that if the errors are small, and the optimization completed successfully. If the data issues are too large, however (pervasive sync errors, completely insufficient lens model, etc), the solver will have trouble. It could - Take a very long time to converge to /some/ solution - Produce tool many outliers, possibly incrementally, producing output such as this: #+begin_example mrcal.c(5413): Threw out some outliers. New count = 174/35280 (0.5%). Going again mrcal.c(5413): Threw out some outliers. New count = 252/35280 (0.7%). Going again mrcal.c(5413): Threw out some outliers. New count = 303/35280 (0.9%). Going again #+end_example This will slow down the solve dramatically. Unless the data is known to be funky, more than ~ 3% outliers should raise questions If the solver has trouble like this, it is usually helpful to turn off the outlier rejection by running =mrcal-calibrate-cameras --skip-outlier-rejection ....=, and then [[#residuals][examine the residuals as described below]]. Hopefully that would provide a hint about the issues. It also helps to simplify the problem, which is effective at isolating certain issues. For instance, a nonconverging multi-camera solve should be attempted monocularly, one camera at a time. If some cameras converge and some don't, that points to the issue. If individually the solves converge, but together they don't, there could be an issue with the [[#residuals-sync][camera synchronization]], or the chessboard corner indices aren't consistent. Similarly solving with a subset of images is often enlightening. Another common problem is getting messages like this: #+begin_example mrcal.c(3758): WARNING: Board observation 157 (icam_intrinsics=0, icam_extrinsics=-1, iframe=104) had almost all of its points thrown out as outliers: only 0/100 remain. CHOLMOD is about to complain about a non-positive-definite JtJ. Something is wrong with this observation mrcal.c(3758): WARNING: Board observation 158 (icam_intrinsics=1, icam_extrinsics=0, iframe=104) had almost all of its points thrown out as outliers: only 0/100 remain. CHOLMOD is about to complain about a non-positive-definite JtJ. Something is wrong with this observation mrcal.c(5412): Threw out some outliers (have a total of 861 now); going again libdogleg at dogleg.c:1115: CHOLMOD warning: libdogleg at dogleg.c:1115: not positive definite. libdogleg at dogleg.c:1115: file: ../Cholesky/t_cholmod_rowfac.c libdogleg at dogleg.c:1115: line: 430 libdogleg at dogleg.c:1115: #+end_example The complaint is about a singular Hessian matrix. Usually this happens if some variable in the optimization has no effect at all on the solution, and the optimizer thus doesn't know what to do with that variable. Usually heavy outlier rejection precedes this, and the missing data is causing the problem. Example: all chessboard observations for a given frame were thrown out; thus moving the chessboard pose at that time has no effect, and we get a singular Hessian. The diagnostic technique is the same: disable the outlier rejection and examine the residuals. * Interpreting the results :PROPERTIES: :CUSTOM_ID: interpreting-results :END: Once we have a calibration, we should evaluate how well it represents reality. The tour of mrcal shows a very detailed process: [[file:tour-initial-calibration.org::#opencv8-model-solving][a real-world fit using =LENSMODEL_OPENCV8=]] and [[file:tour-initial-calibration.org::#splined-model-solving][a real-world fit using =LENSMODEL_SPLINED_STEREOGRAPHIC_...=]]. The analysis sequence outlined there is too thorough for everyday use, but it's good to look through those pages to get a sense. A high-level process is - [[#uncertainty][Examine the projection uncertainty to make sure we have enough good data in the right places]] - [[#cross-validation][Examine the cross-validation diffs to confirm that the model fits and that the reported uncertainty is trustworthy]] - [[#residuals][If these diffs are too high, examine the residuals to find out why]] This is a /lot/, but you don't need to do all this every time. As noted in [[file:formulation.org::#noise-model][the noise model description]], we want homoscedastic noise in our observations of the chessboard corners. We will get that if and only if our models faithfully describe the world; so the available diagnostics serve to pinpoint areas where the models don't fit, so that those issues could be addressed. I now describe each step. ** Projection uncertainty :PROPERTIES: :CUSTOM_ID: uncertainty :END: As described in detail in [[file:uncertainty.org][the projection-uncertainty page]], the projection uncertainty computed by mrcal gauges the effect of sampling error. Since we /always/ have noise in our chessboard observations, it's important that the solution be insensitive to this noise. Otherwise a recalibration of the same system would produce very different results due to new chessboard observations containing new noise. Projection uncertainty can be visualized with the [[file:mrcal-show-projection-uncertainty.html][=mrcal-show-projection-uncertainty=]] tool. From the [[file:tour-uncertainty.org][tour of mrcal]]: #+begin_src sh mrcal-show-projection-uncertainty splined.cameramodel --cbmax 1 --unset key #+end_src #+begin_src sh :exports none :eval no-export # THIS IS GENERATED IN tour-uncertainty.org #+end_src [[file:external/figures/uncertainty/uncertainty-splined.png]] This is projection uncertainty at infinity, which is what I'm usually interested in. If we care /only/ about the performance at some particular distance, that can be requested with =mrcal-show-projection-uncertainty --distance ...=. That uncertainty will usually be better than the uncertainty at infinity. Making sure things work at infinity will make things work at other ranges also. The projection uncertainty measures the quality of the chessboard dance. If the [[#dancing][guidelines noted above]] were followed, you'll get good uncertainties. If the uncertainty is poor in some region, you need more chessboard observations in that area. To improve it everywhere, follow the guidelines: more observations, more closeups, more tilt. The projection uncertainties will be overly-optimistic if model errors are present or if a too-lean lens model is selected. So we now look at the cross-validation diffs to confirm that no model errors are present. If we can confirm that, the projection uncertainties can be used as the authoritative gauge of the quality of our calibration. Since the uncertainties are largely a function of the chessboard dance, I usually don't bother looking at them if I'm recalibrating a system that I have calibrated before, with a similar dance. Since the system and the dance didn't change, neither would the uncertainty. ** Cross-validation diffs :PROPERTIES: :CUSTOM_ID: cross-validation :END: If we have an acceptable projection uncertainty, we need to decide if it's a good gauge of calibration quality: if we have model errors or not. A good way to do that is to compute a cross-validation: we calibrate the camera system twice with independent input data, and we compare the resulting projections. If the models fit, then we only have sampling error affecting the solves, and the resulting differences will be in-line with what the uncertainties predict: $\mathrm{difference} \approx \mathrm{uncertainty}_0 + \mathrm{uncertainty}_1$. Otherwise, we have an extra source of error not present in the uncertainty estimates, which would cause the cross-validation diffs to be significantly higher. That would suggest a deeper look is necessary. To get the data, we can do two separate dances, or we can split the dataset into odd/even images, as described [[#calibration][above]]. Note: if the chessboard is moved very slowly, the even and odd datasets will be very qualitatively similar, and it's possible to get a low cross-validation diff even in the presence of model errors: the two samples of the model error distribution would be similar to each other. This usually doesn't happen, but keep in mind that it /could/, so you should move at a reasonable speed to make the odd/even datasets non-identical. In the [[file:tour-cross-validation.org][tour of mrcal]] we computed a cross-validation, and discovered that there indeed exists a model error. The cross-validation diff looked like this: #+begin_src sh mrcal-show-projection-diff \ --cbmax 2 \ --unset key \ 2-f22-infinity.splined.cameramodel \ 3-f22-infinity.splined.cameramodel #+end_src [[file:external/figures/cross-validation/diff-cross-validation-splined.png]] And the two uncertainties looked roughly like this: [[file:external/figures/uncertainty/uncertainty-splined.png]] The diff is more than roughly 2x the uncertainty, so something wasn't fitting: the lens had a non-negligible noncentral behavior at the chessboard distance, which wasn't fixable with today's mrcal. So we could either - Accept the results as is, using the diffs as a guideline to how trustworthy the solves are - Gather more calibration images from further out, minimizing the unmodeled noncentral effect Cross-validation diffs are usually /very/ effective at detecting issues, and I usually compute these every time I calibrate a lens. In my experience, these are the single most important diagnostic output. While these are very good at /detecting/ issues, they're less good at pinpointing the root cause. To do that usually requires thinking about the [[#residuals][solve residuals (next section)]]. ** Residuals :PROPERTIES: :CUSTOM_ID: residuals :END: We usually have a /lot/ of images and a /lot/ of residuals. Usually I only look at the residuals if - I'm calibrating an unfamiliar system - I don't trust something about the way the data was collected; if I have little faith in the camera time-sync for instance - Something unknown is causing issues (we're seeing too-high cross-validation diffs), and we need to debug The residuals in the whole problem can be visualized with the [[file:mrcal-show-residuals.html][=mrcal-show-residuals=]] tool. And the residuals of specific chessboard observations can be visualized with the [[file:mrcal-show-residuals-board-observation.html][=mrcal-show-residuals-board-observation=]] tool. Once again. As noted in [[file:formulation.org::#noise-model][the noise model description]], we want homoscedastic noise in our observations of the chessboard corners. So the residuals should all be independent and should all have the same dispersion: each residual vector should look random, and unrelated to any other residual vector. There should be no discernible patterns to the residuals. If model errors are present, the residuals will /not/ appear random, and /will/ exhibit patterns. And we will then see those patterns in the residual plots. The single most useful invocation to run is #+begin_example mrcal-show-residuals-board-observation \ --from-worst \ --vectorscale 100 \ solved.cameramodel \ 0-5 #+end_example This displays the residuals of a few worst-fitting images, with the error vectors scaled up 100x for legibility (the "100" often needs to be adjusted for each specific case). The most significant issues usually show up in these few worst-fitting chessboard observations. The residual plots are interactive, so it's useful to then zoom in on the worst fitting points (easily identifiable by the color) in the worst-fitting observations to make sure the observed chessboard corners we're fitting to are in the right place. If something was wrong with the chessboard corner detection, a zoomed-in residual image would tell us this. Next the residual plots should be examined for patterns. Let's look at some common issues, and the characteristic residual patterns they produce. For most of the below I'm going to show the usual calibration residuals we would expect to see if we had some particular kind of issue. We do this by simulating /perfect/ calibration data, corrupting it with the kind of problem we're demonstrating, recalibrating, and visualizing the result. Below I do this in Python using the [[file:mrcal-python-api-reference.html#-make_perfect_observations][=mrcal.make_perfect_observations()=]] function. These could equivalently have been made using the [[https://www.github.com/dkogan/mrcal/blob/master/analyses/mrcal-reoptimize][=mrcal-reoptimize=]] tool: #+begin_example $ mrcal/analyses/mrcal-reoptimize \ --explore \ --perfect \ splined.cameramodel ... Have REPL looking at perfect data. Add flaw, reoptimize, visualize here. #+end_example This technique is powerful and is useful for more than just making plots for this documentation. We can also use it to quantify the errors that would result from problems that we suspect exist. We can compare those to the [[file:tour-cross-validation.org][cross-validation errors]] that we observe to get a hint about what is causing the problem. For instance, you might have a system where you're not confident that your chessboard is flat or that your lens model fits or that your camera sync works right. You probably see high [[file:tour-cross-validation.org][cross-validation diffs]], but don't have a sense of which factor is most responsible for the issues. We can simulate this, to see if the suspected issues would cause errors as high as what is observed. Let's say you placed a straight edge across your chessboard, and you see a deflection at the center of ~ 3mm. mrcal doesn't assume a flat chessboard, but its deformation model is simple, and even in this case it can be off by 1mm. Let's hypothesize that the board deflection is 0.5mm horizontally and 0.5mm vertically, in the other direction. We can then use the [[https://www.github.com/dkogan/mrcal/blob/master/analyses/mrcal-reoptimize][=mrcal-reoptimize= tool]] to quantify the resulting error, and we can compare the simulated cross-validation diff to the one we observe. We might discover that the expected chessboard deformation produces cross-validation errors that are smaller than what we observe. In that case, we should keep looking. But if we see the simulated cross-validation diff of the same order of magnitude that we observe, then we know it's time to fix the chessboard. *** Poorly-fitting lens model We saw this in [[file:tour-initial-calibration.org::#opencv8-solve-diagnostics][the tour of mrcal]]: we tried to calibrate a very wide lens with =LENSMODEL_OPENCV8=, and it showed clear signs of the model not fitting. Read that page to get a sense of what that looks like in the various diagnostics. Broadly speaking, lens modeling errors increase as you move towards the edges of the imager, so we would see higher errors at the edges. This often looks similar to an [[#residuals-chessboard-shape][unmodeled deformation in the chessboard shape]]. *** Errors in the chessboard detector What if the chessboard detector gets a small number of corners localized incorrectly? If the shift is large, those corner observations will be thrown out as outliers, and will not affect the solve. But if they're small, they may cause a bias in the solution. What does that look like? Let's simulate it. We - take the =LENSMODEL_SPLINED_STEREOGRAPHIC= solve from [[file:tour-initial-calibration.org][the tour of mrcal]] - produce perfect observations at the computed optimal geometry - add perfect independent gaussian noise to the observations This data now follows [[file:formulation.org::#noise-model][the noise model]] perfectly. Then I add the flaw: I bump all the observed corners on the chessboard diagonal in observation 10 to the right by 0.8 pixels, and I look at the residuals. This requires a bit of code: #+begin_src python #!/usr/bin/python3 import sys import mrcal import numpy as np import numpysane as nps def add_imperfection(optimization_inputs): for i in range(14): optimization_inputs['observations_board'][10,i,i,0] += 0.8 model = mrcal.cameramodel('splined.cameramodel') optimization_inputs = model.optimization_inputs() mrcal.make_perfect_observations(optimization_inputs) add_imperfection(optimization_inputs) mrcal.optimize(**optimization_inputs) mrcal.show_residuals_board_observation(optimization_inputs, 10, vectorscale = 200, circlescale = 0.5, title = "Effect of corner detection error at the center", paths = optimization_inputs['imagepaths']) #+end_src #+begin_src python :exports none :eval no-export #!/usr/bin/python3 import sys import mrcal import numpy as np import numpysane as nps def add_imperfection(optimization_inputs): for i in range(14): optimization_inputs['observations_board'][10,i,i,0] += 0.8 model = mrcal.cameramodel('/home/dima/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/splined.cameramodel') optimization_inputs = model.optimization_inputs() mrcal.make_perfect_observations(optimization_inputs) add_imperfection(optimization_inputs) mrcal.optimize(**optimization_inputs) mrcal.show_residuals_board_observation(optimization_inputs, 10, vectorscale = 200, circlescale = 0.5, hardcopy = "~/projects/mrcal-doc-external/figures/residuals/chessboard-detection-errors.png", title = "Effect of corner detection error at the center", terminal = 'pngcairo size 1024,550 transparent noenhanced crop font ",12"', paths = optimization_inputs['imagepaths']) mrcal.show_residuals_board_observation(optimization_inputs, 10, vectorscale = 200, circlescale = 0.5, hardcopy = "~/projects/mrcal-doc-external/figures/residuals/chessboard-detection-errors.pdf", title = "Effect of corner detection error at the center", terminal = 'pdf size 8in,6in noenhanced solid color font ",16"', paths = optimization_inputs['imagepaths']) import os os.system("pdfcrop ~/projects/mrcal-doc-external/figures/residuals/chessboard-detection-errors.pdf") #+end_src With a model on disk, the same could be produced with #+begin_src sh mrcal-show-residuals-board-observation \ --vectorscale 200 \ --circlescale 0.5 \ --title "Effect of corner detection error at the center" \ splined.cameramodel \ 10 #+end_src [[file:external/figures/residuals/chessboard-detection-errors.png]] Here we see the residuals on the top-left/bottom-right diagonal be consistently larger than the others, and we see them point in a consistent non-random direction. This isn't easily noticeable without knowing what to look for. /But/ the usual method of zooming in to the worst-few points will make the error in the detected corners visibly apparent. *** Rolling shutter :PROPERTIES: :CUSTOM_ID: residuals-rolling-shutter :END: Many cameras employ a [[https://en.wikipedia.org/wiki/Rolling_shutter][rolling shutter]]: the images aren't captured all at once, but are built up over time, capturing different parts of the image at different times. If the scene or the camera are moving, this would produce images that violate mrcal's view of the world: that at an instant in time I can describe the /full/ chessboard pose and its observed corners. mrcal does not model rolling shutter effects, so non-static calibration images would cause problems. Today the only way to calibrate rolling-shutter cameras with mrcal is to make sure the cameras and the chessboard are stationary during each image capture. How do we make sure that no rolling-shutter effects ended up in our data? We look at the residuals. Prior to the dataset used in [[file:tour-initial-calibration.org][the tour of mrcal]] I captured images that used the "silent mode" of the Sony Alpha 7 III camera. I didn't realize that this mode implied a rolling shutter, so [[file:external/2022-10-17--dtla-overpass--samyang--alpha7][that dataset]] wasn't useful to demo anything other than the rolling shutter residuals. Looking at the worst few observations: #+begin_src sh mrcal-show-residuals-board-observation \ --from-worst \ --vectorscale 20 \ --circlescale 0.5 \ splined.cameramodel \ 0-3 #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-10-17--dtla-overpass--samyang--alpha7/2-f22-infinity/ for i (`seq 0 3`) { mrcal-show-residuals-board-observation \ --from-worst \ --vectorscale 40 \ --circlescale 0.5 \ --title "Residuals from a rolling shutter camera" \ --hardcopy "~/projects/mrcal-doc-external/figures/residuals/rolling-shutter-$i.png" \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' \ $D/splined.cameramodel \ $i mrcal-show-residuals-board-observation \ --from-worst \ --vectorscale 40 \ --circlescale 0.25 \ --title "Residuals from a rolling shutter camera" \ --hardcopy "~/projects/mrcal-doc-external/figures/residuals/rolling-shutter-$i.svg" \ --terminal 'svg size 800,400 noenhanced solid dynamic font ",14"' \ $D/splined.cameramodel \ $i mrcal-show-residuals-board-observation \ --from-worst \ --vectorscale 40 \ --circlescale 0.25 \ --title "Residuals from a rolling shutter camera" \ --hardcopy "~/projects/mrcal-doc-external/figures/residuals/rolling-shutter-$i.pdf" \ --terminal 'pdf size 8in,6in noenhanced solid color font ",16"' \ $D/splined.cameramodel \ $i pdfcrop ~/projects/mrcal-doc-external/figures/residuals/rolling-shutter-$i.pdf } #+end_src [[file:external/figures/residuals/rolling-shutter-0.svg]] [[file:external/figures/residuals/rolling-shutter-2.svg]] [[file:external/figures/residuals/rolling-shutter-3.svg]] I'm omitting the 2nd image because it qualitatively looks very similar to the first. Note the patterns. Clearly something is happening, but it varies from image to image, and a warped chessboard isn't likely to explain it. In addition to that, the magnitude of all the errors is dramatically higher than before: the vectors are scaled up 5x less than those in [[file:tour-initial-calibration.org][the tour of mrcal]]. *** Synchronization :PROPERTIES: :CUSTOM_ID: residuals-sync :END: What if we're calibrating a multi-camera system, and the image synchronization is broken? You should have a hardware sync: a physical trigger wire connected to each camera, with a pulse on that line telling each camera to begin the image capture. If this is missing or doesn't work properly, then a similar issue occurs as with a [[#residuals-rolling-shutter][rolling-shutter]]: images captured at allegedly a particular instant in time haven't actually been captured completely at /that/ time. This can be confirmed by recalibrating monocularly, to see if individually the solves converge. And as expected, this can be readily seen in the residuals. A time sync problem means that synced images A and B were supposed to capture a chessboard at some pose $T$. But since the sync was broken, the chessboard moved, so the chessboard was really at two different poses: $T_\mathrm{A}$ and $T_\mathrm{B}$. mrcal was told that there was no motion, so it ends up solving for some compromise transform $T_\mathrm{mid}$ that splits the difference. So the residuals for image A would point from the observation at $T_\mathrm{A}$ towards the observation at the compromise pose $T_\mathrm{mid}$. And the residuals for image B would point in the opposite direction: from the observation at $T_\mathrm{B}$ towards the observation at the compromise pose $T_\mathrm{mid}$. Let's demo this with a little code. I grab the monocular solve from [[file:tour-initial-calibration.org][the tour of mrcal]], add a second camera with perfect observations and noise, and add the flaw: one of the chessboard observations was erroneously reported for two images in a row. This happened in only one camera of the pair, so a time-sync error resulted. This is a simulation, but as with everything else on this page, I've seen such problems in real life. The incorrect observation is observation 40, frame 20, camera 0. #+begin_src python #!/usr/bin/python3 import sys import mrcal import numpy as np import numpysane as nps def binocular_from_monocular(optimization_inputs): # Assuming monocular calibration. Add second identical camera to the right # of the first optimization_inputs['intrinsics'] = \ nps.glue( optimization_inputs['intrinsics'], optimization_inputs['intrinsics'], axis = -2 ) optimization_inputs['imagersizes'] = \ nps.glue( optimization_inputs['imagersizes'], optimization_inputs['imagersizes'], axis = -2 ) optimization_inputs['extrinsics_rt_fromref'] = np.array(((0,0,0, -0.1,0,0),), dtype=float) i = optimization_inputs['indices_frame_camintrinsics_camextrinsics'] optimization_inputs['indices_frame_camintrinsics_camextrinsics'] = \ np.ascontiguousarray( \ nps.clump(nps.xchg(nps.cat(i, i + np.array((0,1,1),dtype=np.int32)), 0, 1), n=2)) # optimization_inputs['observations_board'] needs to have the right shape # and the right weights. So I just duplicate it optimization_inputs['observations_board'] = \ np.ascontiguousarray( \ nps.clump(nps.xchg(nps.cat(optimization_inputs['observations_board'], optimization_inputs['observations_board']), 0,1), n=2)) del optimization_inputs['imagepaths'] def add_imperfection(optimization_inputs): iobservation = 40 iframe,icam_intrinsics,icam_extrinsics = \ optimization_inputs['indices_frame_camintrinsics_camextrinsics'][iobservation] print(f"observation {iobservation} iframe {iframe} icam_intrinsics {icam_intrinsics} is stuck to the previous observation") optimization_inputs ['observations_board'][iobservation, ...] = \ optimization_inputs['observations_board'][iobservation-2,...] model = mrcal.cameramodel('splined.cameramodel') optimization_inputs = model.optimization_inputs() binocular_from_monocular(optimization_inputs) mrcal.make_perfect_observations(optimization_inputs) add_imperfection(optimization_inputs) optimization_inputs['do_apply_outlier_rejection'] = False mrcal.optimize(**optimization_inputs) mrcal.cameramodel(optimization_inputs = optimization_inputs, icam_intrinsics = 0).write('/tmp/sync-error.cameramodel') for i in range(2): mrcal.show_residuals_board_observation(optimization_inputs, i, from_worst = True, vectorscale = 2, circlescale = 0.5) #+end_src #+begin_src python :exports none :eval no-export #!/usr/bin/python3 import sys import os import os.path import mrcal import numpy as np import numpysane as nps def binocular_from_monocular(optimization_inputs): # Assuming monocular calibration. Add second identical camera to the right # of the first optimization_inputs['intrinsics'] = \ nps.glue( optimization_inputs['intrinsics'], optimization_inputs['intrinsics'], axis = -2 ) optimization_inputs['imagersizes'] = \ nps.glue( optimization_inputs['imagersizes'], optimization_inputs['imagersizes'], axis = -2 ) optimization_inputs['extrinsics_rt_fromref'] = np.array(((0,0,0, -0.1,0,0),), dtype=float) i = optimization_inputs['indices_frame_camintrinsics_camextrinsics'] optimization_inputs['indices_frame_camintrinsics_camextrinsics'] = \ np.ascontiguousarray( \ nps.clump(nps.xchg(nps.cat(i, i + np.array((0,1,1),dtype=np.int32)), 0, 1), n=2)) # optimization_inputs['observations_board'] needs to have the right shape # and the right weights. So I just duplicate it optimization_inputs['observations_board'] = \ np.ascontiguousarray( \ nps.clump(nps.xchg(nps.cat(optimization_inputs['observations_board'], optimization_inputs['observations_board']), 0,1), n=2)) del optimization_inputs['imagepaths'] def add_imperfection(optimization_inputs): iobservation = 40 iframe,icam_intrinsics,icam_extrinsics = \ optimization_inputs['indices_frame_camintrinsics_camextrinsics'][iobservation] print(f"observation {iobservation} iframe {iframe} icam_intrinsics {icam_intrinsics} is stuck to the previous observation") optimization_inputs ['observations_board'][iobservation, ...] = \ optimization_inputs['observations_board'][iobservation-2,...] model = mrcal.cameramodel('/home/dima/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/splined.cameramodel') optimization_inputs = model.optimization_inputs() binocular_from_monocular(optimization_inputs) mrcal.make_perfect_observations(optimization_inputs) add_imperfection(optimization_inputs) optimization_inputs['do_apply_outlier_rejection'] = False mrcal.optimize(**optimization_inputs) mrcal.cameramodel(optimization_inputs = optimization_inputs, icam_intrinsics = 0).write('/tmp/sync-error.cameramodel') for i in range(2): mrcal.show_residuals_board_observation(optimization_inputs, i, from_worst = True, vectorscale = 2, circlescale = 0.5, title = "Residuals from a broken camera sync", hardcopy = f"~/projects/mrcal-doc-external/figures/residuals/sync-errors-{i}.png", terminal = 'pngcairo size 1024,550 transparent noenhanced crop font ",12"') mrcal.show_residuals_board_observation(optimization_inputs, i, from_worst = True, vectorscale = 2, circlescale = 0.25, title = "Residuals from a broken camera sync", hardcopy = f"~/projects/mrcal-doc-external/figures/residuals/sync-errors-{i}.svg", terminal = 'svg size 800,400 noenhanced solid dynamic font ",14"') mrcal.show_residuals_board_observation(optimization_inputs, i, from_worst = True, vectorscale = 2, circlescale = 0.25, title = "Residuals from a broken camera sync", hardcopy = f"~/projects/mrcal-doc-external/figures/residuals/sync-errors-{i}.pdf", terminal = 'pdf size 8in,6in noenhanced solid color font ",16"') os.system(os.path.expanduser(f"pdfcrop ~/projects/mrcal-doc-external/figures/residuals/sync-errors-{i}.pdf")) #+end_src [[file:external/figures/residuals/sync-errors-0.svg]] [[file:external/figures/residuals/sync-errors-1.svg]] We're plotting the two worst-residual observations, and we clearly see the tell-tale sign of a time-sync error. As before, we can make these plots from the commandline: #+begin_src sh mrcal-show-residuals-board-observation \ --from-worst \ --vectorscale 2 \ --circlescale 0.5 \ /tmp/sync-error.cameramodel \ --explore \ 0-1 #+end_src Here we passed =--explore= to drop into a REPL to investigate further, which gives us another clear indication that we have a time-sync error. The tool reports some useful diagnostics at the top of the REPL: #+begin_example The first 10 worst-fitting observations (i_observations_sorted_from_worst[:10]) [41, 40, 97, 94, 95, 38, 99, 96, 98, 39] The corresponding 10 (iframe, icamintrinsics, icamextrinsics) tuples (indices_frame_camintrinsics_camextrinsics[i_observations_sorted_from_worst[:10] ]): [[20 1 0] [20 0 -1] [48 1 0] [47 0 -1] [47 1 0] [19 0 -1] [49 1 0] [48 0 -1] [49 0 -1] [19 1 0]] #+end_example Since a time-sync error affects multiple images at the same time, we should see multiple chessboard observations from the same frame (instant in time) in the high-residuals list, and we clearly see that above. We corrupted frame 20 camera 0, so it's no longer syncronized with frame 20 camera 1. We expect both of those observations to fit badly, and we do see that: the [[file:mrcal-show-residuals-board-observation.html][=mrcal-show-residuals-board-observation=]] tool says that the worst residual is from frame 20 camera 1 and the second-worst is frame 20 camera 0. High errors in multiple cameras in the same frame like this are another tell-tale sign of sync errors. We can also query the errors themselves in the REPL: #+begin_example In [1]: err_per_observation[i_observations_sorted_from_worst][:10] Out[1]: array([965407.29301702, 864665.95442895, 11840.10373732, 7762.88344105, 7759.5509593 , 7618.23632488, 7190.35449443, 6621.34798572, 6499.23173619, 6039.45522539]) #+end_example So the two frame-20 sum-of-squares residuals are on the order of $900,000 \mathrm{pixels}^2$, and the next worst one is ~ 100 times smaller. *** Chessboard shape :PROPERTIES: :CUSTOM_ID: residuals-chessboard-shape :END: Since flat chessboards don't exist, mrcal doesn't assume that the observed chessboard is flat. Today it uses [[file:formulation.org::#board-deformation][a simple parabolic model]]. It /does/ assume the board shape is constant throughout the whole calibration sequence. So let's run more simulations to test two scenarios: 1. The chessboard is slightly non-flat, but in a way not modeled by the solver 2. The chessboard shape changes slightly over the course of the chessboard dance **** Unmodeled chessboard shape As before, we rerun the scenario from [[file:tour-initial-calibration.org][the tour of mrcal]] with perfect observations and perfect, but with a flaw: I use the very slightly parabolic chessboard, but tell mrcal to assume the chessboard is flat. The script is very similar: #+begin_src python #!/usr/bin/python3 import sys import mrcal import numpy as np import numpysane as nps def add_imperfection(optimization_inputs): H,W = optimization_inputs['observations_board'].shape[1:3] s = optimization_inputs['calibration_object_spacing'] print(f"Chessboard dimensions are {s*(W-1)}m x {s*(H-1)}m") print(f"Chessboard deflection at the center is {optimization_inputs['calobject_warp'][0]*1000:.1f}mm , {optimization_inputs['calobject_warp'][1]*1000:.1f}mm in the x,y direction") optimization_inputs['calobject_warp'] *= 0. optimization_inputs['do_optimize_calobject_warp'] = False model = mrcal.cameramodel('splined.cameramodel') optimization_inputs = model.optimization_inputs() optimization_inputs['calobject_warp'] = np.array((1e-3, -0.5e-3)) mrcal.make_perfect_observations(optimization_inputs) add_imperfection(optimization_inputs) mrcal.optimize(**optimization_inputs) mrcal.show_residuals_board_observation(optimization_inputs, 0, from_worst = True, vectorscale = 200, circlescale = 0.5) #+end_src #+begin_src python :exports none :eval no-export #!/usr/bin/python3 import sys import os import os.path import mrcal import numpy as np import numpysane as nps def add_imperfection(optimization_inputs): H,W = optimization_inputs['observations_board'].shape[1:3] s = optimization_inputs['calibration_object_spacing'] print(f"Chessboard dimensions are {s*(W-1)}m x {s*(H-1)}m") print(f"Chessboard deflection at the center is {optimization_inputs['calobject_warp'][0]*1000:.1f}mm , {optimization_inputs['calobject_warp'][1]*1000:.1f}mm in the x,y direction") optimization_inputs['calobject_warp'] *= 0. optimization_inputs['do_optimize_calobject_warp'] = False model = mrcal.cameramodel('/home/dima/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/splined.cameramodel') optimization_inputs = model.optimization_inputs() optimization_inputs['calobject_warp'] = np.array((1e-3, -0.5e-3)) mrcal.make_perfect_observations(optimization_inputs) add_imperfection(optimization_inputs) mrcal.optimize(**optimization_inputs) mrcal.cameramodel(optimization_inputs = optimization_inputs, icam_intrinsics = 0).write('/tmp/unmodeled-chessboard-shape.cameramodel') mrcal.show_residuals_board_observation(optimization_inputs, 0, from_worst = True, vectorscale = 200, circlescale = 0.5, title = "Residuals from a static chessboard shape error", hardcopy = f"~/projects/mrcal-doc-external/figures/residuals/unmodeled-chessboard-shape.png", terminal = 'pngcairo size 1024,550 transparent noenhanced crop font ",12"') mrcal.show_residuals_board_observation(optimization_inputs, 0, from_worst = True, vectorscale = 200, circlescale = 0.25, title = "Residuals from a static chessboard shape error", hardcopy = f"~/projects/mrcal-doc-external/figures/residuals/unmodeled-chessboard-shape.svg", terminal = 'svg size 800,400 noenhanced solid dynamic font ",14"') mrcal.show_residuals_board_observation(optimization_inputs, 0, from_worst = True, vectorscale = 200, circlescale = 0.25, title = "Residuals from a static chessboard shape error", hardcopy = f"~/projects/mrcal-doc-external/figures/residuals/unmodeled-chessboard-shape.pdf", terminal = 'pdf size 8in,6in noenhanced solid color font ",16"') os.system(os.path.expanduser(f"pdfcrop ~/projects/mrcal-doc-external/figures/residuals/unmodeled-chessboard-shape.pdf")) #+end_src It says: #+begin_example Chessboard dimensions are 0.7644m x 0.7644m Chessboard deflection at the center is 1.0mm , -0.5mm in the x,y direction #+end_example And the worst residual image looks like this: [[file:external/figures/residuals/unmodeled-chessboard-shape.svg]] It usually looks similar to the residuals from a poorly-modeled lens (chessboard edges tend to be observed at the edges of the lens). In /this/ solve the residuals all look low-ish at the center, much bigger at the edges, and consistent at the edges. **** Unstable chessboard shape What if the chessboard flexes a little bit? I redo my solve using a small parabolic deflection at the first half of the sequence and twice as much deformation during the second half. #+begin_src python #!/usr/bin/python3 import sys import mrcal import numpy as np import numpysane as nps def add_imperfection(optimization_inputs, observed_pixel_uncertainty): Nobservations = len(optimization_inputs['observations_board']) observations_half = np.array(optimization_inputs['observations_board'][:Nobservations//2,...]) optimization_inputs['calobject_warp'] *= 2. mrcal.make_perfect_observations(optimization_inputs, observed_pixel_uncertainty = observed_pixel_uncertainty) optimization_inputs['observations_board'][:Nobservations//2,...] = observations_half H,W = optimization_inputs['observations_board'].shape[1:3] s = optimization_inputs['calibration_object_spacing'] print(f"Chessboard dimensions are {s*(W-1)}m x {s*(H-1)}m") print(f"Chessboard deflection at the center (second half of dataset) is {optimization_inputs['calobject_warp'][0]*1000:.2f}mm , {optimization_inputs['calobject_warp'][1]*1000:.2f}mm in the x,y direction") print(f"Chessboard deflection at the center at the first half of the dataset is half of that") model = mrcal.cameramodel('splined.cameramodel') optimization_inputs = model.optimization_inputs() observed_pixel_uncertainty = np.std(mrcal.residuals_board(optimization_inputs).ravel()) optimization_inputs['calobject_warp'] = np.array((1e-3, -0.5e-3)) mrcal.make_perfect_observations(optimization_inputs, observed_pixel_uncertainty = observed_pixel_uncertainty) add_imperfection(optimization_inputs, observed_pixel_uncertainty) mrcal.optimize(**optimization_inputs) print(f"Optimized chessboard deflection at the center is {optimization_inputs['calobject_warp'][0]*1000:.2f}mm , {optimization_inputs['calobject_warp'][1]*1000:.2f}mm in the x,y direction") mrcal.cameramodel(optimization_inputs = optimization_inputs, icam_intrinsics = 0).write('/tmp/unstable-chessboard-shape.cameramodel') mrcal.show_residuals_board_observation(optimization_inputs, 0, from_worst = True, vectorscale = 200, circlescale = 0.5) #+end_src #+begin_src python :exports none :eval no-export #!/usr/bin/python3 import sys import os import os.path import mrcal import numpy as np import numpysane as nps def add_imperfection(optimization_inputs, observed_pixel_uncertainty): Nobservations = len(optimization_inputs['observations_board']) observations_half = np.array(optimization_inputs['observations_board'][:Nobservations//2,...]) optimization_inputs['calobject_warp'] *= 2. mrcal.make_perfect_observations(optimization_inputs, observed_pixel_uncertainty = observed_pixel_uncertainty) optimization_inputs['observations_board'][:Nobservations//2,...] = observations_half H,W = optimization_inputs['observations_board'].shape[1:3] s = optimization_inputs['calibration_object_spacing'] print(f"Chessboard dimensions are {s*(W-1)}m x {s*(H-1)}m") print(f"Chessboard deflection at the center (second half of dataset) is {optimization_inputs['calobject_warp'][0]*1000:.2f}mm , {optimization_inputs['calobject_warp'][1]*1000:.2f}mm in the x,y direction") print(f"Chessboard deflection at the center at the first half of the dataset is half of that") model = mrcal.cameramodel('/home/dima/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/splined.cameramodel') optimization_inputs = model.optimization_inputs() observed_pixel_uncertainty = np.std(mrcal.residuals_board(optimization_inputs).ravel()) optimization_inputs['calobject_warp'] = np.array((1e-3, -0.5e-3)) mrcal.make_perfect_observations(optimization_inputs, observed_pixel_uncertainty = observed_pixel_uncertainty) add_imperfection(optimization_inputs, observed_pixel_uncertainty) mrcal.optimize(**optimization_inputs) print(f"Optimized chessboard deflection at the center is {optimization_inputs['calobject_warp'][0]*1000:.2f}mm , {optimization_inputs['calobject_warp'][1]*1000:.2f}mm in the x,y direction") mrcal.cameramodel(optimization_inputs = optimization_inputs, icam_intrinsics = 0).write('/tmp/unstable-chessboard-shape.cameramodel') mrcal.show_residuals_board_observation(optimization_inputs, 0, from_worst = True, vectorscale = 200, circlescale = 0.5, title = "Residuals from a dynamic chessboard shape error", hardcopy = f"~/projects/mrcal-doc-external/figures/residuals/unstable-chessboard-shape.png", terminal = 'pngcairo size 1024,550 transparent noenhanced crop font ",12"') mrcal.show_residuals_board_observation(optimization_inputs, 0, from_worst = True, vectorscale = 200, circlescale = 0.25, title = "Residuals from a dynamic chessboard shape error", hardcopy = f"~/projects/mrcal-doc-external/figures/residuals/unstable-chessboard-shape.svg", terminal = 'svg size 800,400 noenhanced solid dynamic font ",14"') mrcal.show_residuals_board_observation(optimization_inputs, 0, from_worst = True, vectorscale = 200, circlescale = 0.25, title = "Residuals from a dynamic chessboard shape error", hardcopy = f"~/projects/mrcal-doc-external/figures/residuals/unstable-chessboard-shape.pdf", terminal = 'pdf size 8in,6in noenhanced solid color font ",16"') os.system(os.path.expanduser(f"pdfcrop ~/projects/mrcal-doc-external/figures/residuals/unstable-chessboard-shape.pdf")) #+end_src It says: #+begin_example Chessboard dimensions are 0.7644m x 0.7644m Chessboard deflection at the center (second half of dataset) is 2.00mm , -1.00mm in the x,y direction Chessboard deflection at the center at the first half of the dataset is half of that Optimized chessboard deflection at the center is 1.66mm , -0.79mm in the x,y direction #+end_example [[file:external/figures/residuals/unstable-chessboard-shape.svg]] It looks a bit like the unmodeled chessboard residuals above, but smaller, and more subtle. But lest you think that these small and subtle residuals imply that this doesn't affect the solution, here's the resulting difference in projection: #+begin_src sh mrcal-show-projection-diff \ --no-uncertainties \ --radius 500 \ --unset key \ /tmp/unstable-chessboard-shape.cameramodel \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export mrcal-show-projection-diff \ --no-uncertainties \ --radius 500 \ --unset key \ /tmp/unstable-chessboard-shape.cameramodel \ ~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/splined.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/residuals/unstable-chessboard-shape-diff.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' #+end_src [[file:external/figures/residuals/unstable-chessboard-shape-diff.png]] So [[#chessboard-shape][take care to make your chessboard rigid]]. I can think of better visualizations to more clearly identify these kinds of issues, so this might improve in the future. For both of these chessboard deformation cases it's helpful to look at more than just 1 or 2 worst-case residuals. Look at the worst 10. In both cases the most tilted chessboard observations usually show very consistent residual vectors along the far edge of the chessboard. mrcal-2.4.1/doc/index.org000066400000000000000000000101151456301662300152050ustar00rootroot00000000000000#+title: mrcal - camera calibrations and more! mrcal is a toolkit that provides improved methods for making and using camera models (calibration, tracking, mapping, photogrammetry, etc). It was originally built at NASA/JPL to generate the high-accuracy calibrations demanded by long-range stereo, so it provides facilities to calibrate cameras, thoroughly analyze the accuracy of the result, and to propagate and report uncertainties. * Why mrcal? Because all other tools are terrible if you care about accuracy. They make basic questions like "how much data should I gather for a calibration?" and "how good is this calibration I just computed?" and "how different are these two models?" unanswerable. The previous state-of-the-art was good-enough for low-resolution cameras and long-focal-length lenses and low-range stereo. But today, the existing tools are often insufficient. This toolkit allows the user to confidently produce calibrations that are as good as possible. It provides lots of visualization capabilities to evaluate various properties of a model solution. And it provides powerful analysis methods, such as model differencing and quantification of projection and triangulation uncertainty. To fit the real-world lens behavior mrcal loosens many assumptions common in other toolkits: the calibration chessboard isn't assumed to be flat, lenses aren't assumed to follow simple parametric models, rectified stereo isn't done with a pinhole model, and so on. mrcal consists of - a C library for core functionality - a Python library for higher-level functions - pre-made commandline tools to handle common tasks * Documentation index ** Overview, background - [[file:tour.org][The tour of mrcal]]: if this is your first exposure to mrcal, start here. This goes over the high-level capabilities of the toolkit, to give a good sense of what mrcal can do that's different and better than other tools. - [[file:conventions.org][Terminology and conventions]] ** Details about the internals - [[file:formulation.org][Problem formulation]]: at the core of a calibration routine is an optimization problem. The details are important to interpret the results - [[file:lensmodels.org][Lens models supported by mrcal]] - [[file:splined-models.org][Splined-stereographic lens model]]: this very rich lens model is available for high-fidelity modeling of projection and quantification of uncertainty. It is the recommended model, and is novel in mrcal, so it's described in detail here. - [[file:cameramodels.org][Camera model representation in memory and on disk]] - [[file:differencing.org][Projection differencing]]: mrcal can compute the projection difference between several models. This is useful to evaluate calibration quality and lens stability and a multitude of other things. - [[File:uncertainty.org][Projection uncertainties]]: mrcal can compute the projection uncertainty of a calibration. This quantifies the effect of sampling error, and is an excellent gauge of the quality of a model. - [[file:stereo.org][Dense stereo processing]] - [[file:triangulation.org][Triangulation]] ** Practical guides - [[file:how-to-calibrate.org][How to calibrate a camera system: practical details]] - [[file:recipes.org][Recipes: various scenarios that need special attention]] ** Toolkit usage - [[file:install.org][Installation, build instructions]] - [[file:commandline-tools.org][Command-line tools]] - [[file:python-api.org][The Python API]] - [[file:c-api.org][The C API]] ** [[file:versions.org][Releases: a version history, release notes, and the planned roadmap]] * Citing To cite this work in a publication, use this bibtex stanza: #+begin_example @misc{mrcal, author = "Dima Kogan", title = "mrcal", howpublished = "\url{http://mrcal.secretsauce.net}", } #+end_example * Dev communication For now let's use the [[https://github.com/dkogan/mrcal/issues][github issue tracker]] for bug reporting and for communication in general. At some point I will probably set up a mailing list as well. * Author Dima Kogan == * License and copyright These are listed on [[file:copyrights.org][their own page]]. mrcal-2.4.1/doc/install.org000066400000000000000000000201071456301662300155460ustar00rootroot00000000000000#+title: Building or installing I provide packages for a number of distros. If possible, please use these instead of building from source. If you're interested in packages for a not-yet-supported distro, please contribute! You can email me for help. * Installing from packages :PROPERTIES: :CUSTOM_ID: installing-from-packages :END: mrcal is included in recent versions of Debian and Ubuntu. So if you're running at least Debian 12 (bookworm) or Ubuntu 22.04 (jammy), you can install with a single command. For instance the commandline tools and the C development library and the Python library can be installed with #+begin_src sh apt install mrcal libmrcal-dev python3-mrcal #+end_src For older distros or if you want to get the latest release of mrcal, you can use the mrcal APT repository. I currently distribute packages for - Debian/buster (10) - Debian/bullseye (11) - Debian/bookworm (12) - Debian/sid (bleeding-edge) - Ubuntu/bionic (18.04 LTS) - Ubuntu/focal (20.04 LTS) - Ubuntu/jammy (22.04 LTS) =amd64= and =arm64= architectures only (except Debian/buster and Ubuntu/bionic, which are =amd64-only=). To use these, add to your =/etc/apt/sources.list=: #+begin_example deb [trusted=yes] http://mrcal.secretsauce.net/packages/DISTRO/public/ DISTRO main #+end_example where =DISTRO= is one of - =buster= - =bulleye= - =bookworm= - =bionic= - =focal= - =jammy= Then, =apt update && apt install mrcal=. The chessboard corner finder, while not strictly required, is needed if you're doing chessboard-based calibrations. =apt install mrgingham= * Building from source If you cannot use the packages for whatever reason, you must build from source. This isn't /difficult/, but requires you to obtain all the dependencies. They're listed in the =Build-Depends= section of the [[https://salsa.debian.org/science-team/mrcal/-/blob/master/debian/control][debian package definition]]. Most of these are available in most distros. Things that may not be: - [[https://www.github.com/dkogan/mrbuild][=mrbuild=]]: the build system. If you can't get it from the package manager, just run =make=, and follow the printed message to get a local copy of =mrbuild=. - [[https://github.com/dkogan/libdogleg/][=libdogleg-dev=]]: the optimization library. You need at least version 0.15.3. - [[https://github.com/dkogan/vnlog/][=vnlog=]]: the toolkit to manipulate textual tables. You only /need/ this for the test suite. There's nothing to build. Simply downloading the sources and pointing the =PATH= there is sufficient. - [[https://github.com/dkogan/numpysane/][=python3-numpysane=]]: The make-numpy-reasonable library. You absolutely need at least version 0.35. Available in the usual places Python libraries live. This is a python-only library. Simply downloading the sources and pointing the =PYTHONPATH= there is sufficient. - [[https://github.com/dkogan/gnuplotlib/][=python3-gnuplotlib=]]: The plotting library used in all the visualizations. You need at least version 0.38. Available in the usual places Python libraries live. This is a python-only library. Simply downloading the sources and pointing the =PYTHONPATH= there is sufficient. - [[https://github.com/dkogan/mrgingham/][=mrgingham=]]: the chessboard corner finder. This isn't strictly a requirement - any corner finder can be used. If you want to use this one (and you can't use the packages), you need to build it. - [[https://re2c.org/][=re2c=]]: parser-generator for the C code to parse =.cameramodel= files. At least version 2 is required. - [[https://github.com/yaml/pyyaml][=python3-yaml=]]: yaml parser used for the OpenCV, Kalibr model reading - [[https://pyfltk.sourceforge.io/][=python3-fltk=]]: Python bindings for the [[https://www.fltk.org/][FLTK]] GUI toolkit. Optional. Used only in the visualizer in the [[file:mrcal-stereo.html][=mrcal-stereo=]] tool. - [[https://github.com/dkogan/GL_image_display][=python3-gl-image-display=]]: an image widget for FLTK. Optional. Used only in the visualizer in the [[file:mrcal-stereo.html][=mrcal-stereo=]] tool. - [[https://freeimage.sourceforge.io/][=libfreeimage-dev=]]: an image reading/writing library. Most distros have this available. - [[https://www.cvlibs.net/software/libelas/][=libelas-dev=]]: the ELAS stereo matcher. Used as an option in the [[file:mrcal-stereo.html][=mrcal-stereo=]] tool. Optional. Once these are all downloaded and built (where needed), we can talk about building mrcal. The build-time executables (=re2c=) must be found in the =PATH=, the Python libraries in =PYTHONPATH=, and the C headers and libraries must be findable via the flags in =CFLAGS= and =LDFLAGS= respectively. Anything that hasn't been installed to a standard location must be pointed to via the environment. So to build: #+begin_src sh export PATH=$PATH:extra_path_to_executables export PYTHONPATH=extra_path_to_python_libraries CFLAGS=-Iextra_path_to_c_headers LDFLAGS="-Lextra_path_to_libraries -Wl,-rpath=extra_path_to_libraries" make #+end_src If everything has been installed to a standard location, you just run =make= without any of the extra stuff. The build should then complete successfully, and the test suite should pass: #+begin_src sh make test-nosampling #+end_src If stuff doesn't work, feel free to bug me. * code :noexport: Need to install =ca-certificates= in all the chroots so that I can talk to the https://mrcal APT server #+begin_src sh for distro (buster bullseye bookworm sid bionic focal jammy) { sudo schroot -c source:${distro}-amd64 -- sh -c 'apt update && apt -y upgrade && apt -y install ca-certificates' } #+end_src If that's already installed, still bring all the chroots up-to-date: #+begin_src sh for distro (buster bullseye bookworm sid bionic focal jammy) { sudo schroot -c source:${distro}-amd64 -- sh -c 'apt update && apt -y upgrade' } #+end_src To native-build (amd64) any dependency or mrcal itself: #+begin_src sh for distro (buster bullseye bookworm sid bionic focal jammy) { perl -a -p -i -e 'if($. == 1) { $F[1] =~ s/-([0-9]+).*\)/-$1'$distro'1)/; $F[2] = "'$distro';"; $_ = join(" ",@F) . "\n"; }' debian/changelog; DEB_BUILD_OPTIONS=nocheck \ sbuild \ --no-apt-update \ --no-apt-upgrade \ --host=amd64 \ --arch-any \ --arch-all \ --source \ -c ${distro}-amd64 \ --anything-failed-commands '%s' \ --extra-repository="deb [trusted=yes] http://mrcal.secretsauce.net/packages/$distro/public/ $distro main" dput -u digitalocean_mrcal_$distro ../*${distro}*.changes(om[1]) } #+end_src To cross-build for arm64: #+begin_src sh for distro (bullseye bookworm sid) { perl -a -p -i -e 'if($. == 1) { $F[1] =~ s/-([0-9]+).*\)/-$1'$distro'1)/; $F[2] = "'$distro';"; $_ = join(" ",@F) . "\n"; }' debian/changelog; DEB_BUILD_OPTIONS=nocheck \ sbuild \ --host=arm64 \ --arch-any \ --no-arch-all \ --no-source \ --profiles=nocheck,cross \ -c ${distro}-amd64 \ --anything-failed-commands '%s' \ --extra-repository="deb [trusted=yes] http://mrcal.secretsauce.net/packages/$distro/public/ $distro main" dput -u digitalocean_mrcal_$distro ../*${distro}*.changes(om[1]) } for distro (focal jammy) { perl -a -p -i -e 'if($. == 1) { $F[1] =~ s/-([0-9]+).*\)/-$1'$distro'1)/; $F[2] = "'$distro';"; $_ = join(" ",@F) . "\n"; }' debian/changelog; DEB_BUILD_OPTIONS=nocheck \ sbuild \ --no-apt-update --no-apt-upgrade \ --host=arm64 \ --arch-any \ --no-arch-all \ --no-source \ --profiles=nocheck,cross \ -c ${distro}-amd64 \ --anything-failed-commands '%s' \ --extra-repository="deb [trusted=yes] http://mrcal.secretsauce.net/packages/$distro/public/ $distro main" dput -u digitalocean_mrcal_$distro ../*${distro}*.changes(om[1]) } #+end_src The ubuntu repos were done differently above because for some idiotic reason ubuntu puts the non-amd64 packages into a different domain. So I have to manually add the right sources, and I have to explicitly tell sbuild to not try to "apt update", because it would try to use the same repos with the different arch, and it would fail mrcal-2.4.1/doc/lensmodels.org000066400000000000000000000416231456301662300162530ustar00rootroot00000000000000#+TITLE: mrcal lens models #+OPTIONS: toc:t mrcal supports a wide range of projection models. Some are intended to represent physical lenses, while others are idealized, useful for processing. /All/ are referred to as /lens/ models in the code and in the documentation. The representation details and projection behaviors are described here. * Representation :PROPERTIES: :CUSTOM_ID: representation :END: A =mrcal= /lens/ model represents a lens independent of its pose in space. A lens model is fully specified by - A model /family/ (or /type/). This is something like =LENSMODEL_PINHOLE= or =LENSMODEL_SPLINED_STEREOGRAPHIC= - /Configuration/ parameters. This is a set of key/value pairs, which is required only by some model families. These values are /not/ subject to optimization, and may affect how many optimization parameters are needed. - Optimization parameters. These are the parameters that the optimization routine controls as it runs Each model family also has some /metadata/ key/value pairs associated with it. These are inherent properties of a model family, and are not settable. At the time of this writing there are 3 metadata keys: - =has_core=: True if the first 4 optimization values are the "core": $f_x$, $f_y$, $c_x$, $c_y$. As of mrcal 2.3 this is True for all models. - =can_project_behind_camera=: True if this model is able to project vectors from behind the camera. If it cannot, then [[file:mrcal-python-api-reference.html#-unproject][=mrcal.unproject()=]] will never report =z= < 0. As of mrcal 2.3 this is True only for models based on a stereographic projection, for instance [[#splined-stereographic-lens-model][=LENSMODEL_SPLINED_STEREOGRAPHIC=]]. It is False for models based on a pinhole projection, for instance =LENSMODEL_OPENCV...= and =LENSMODEL_CAHVOR...=. - =has_gradients=: True if this model has gradients implemented. As of mrcal 2.3 all models have this. - =noncentral=: True if [[file:formulation.org::#lens-behavior][projection is /not/ invariant to scaling; i.e. if every observation ray does /not/ intersect at the same point]]. As of mrcal 2.3 only [[#lensmodel-cahvore][=LENSMODEL_CAHVORE=]] does this. In Python, the models are identified with a string =LENSMODEL_XXX= where the =XXX= selects the specific model family and the configuration, if needed. A sample model string with a configuration: =LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=30_Ny=20_fov_x_deg=170=. The configuration is the pairs =order=3=, =Nx=30= and so on. At this time, model families that accept a configuration /require/ it to be specified fully, although optional configuration keys will be added soon. Today, calling Python functions with =LENSMODEL_SPLINED_STEREOGRAPHIC= or =LENSMODEL_SPLINED_STEREOGRAPHIC_order=3= will fail due to an incomplete configuration. The [[file:mrcal-python-api-reference.html#-lensmodel_metadata_and_config][=mrcal.lensmodel_metadata_and_config()=]] function returns a dict containing the metadata and configuration for a particular model string. In C, the model family is selected with the [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h#mrcal_lensmodel_type_t][=mrcal_lensmodel_type_t=]] enum. The elements are the same as the Python model names, but with =MRCAL_= prepended. So the sample model from above has type =MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC=. In C the [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h##mrcal_lensmodel_t][=mrcal_lensmodel_t=]] structure contains the type /and/ configuration. This structure is thus an analogue the the model strings, as Python sees them. So a number of C functions accepting [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h##mrcal_lensmodel_t][=mrcal_lensmodel_t=]] arguments are analogous to Python functions taking model strings. For instance, the number of parameters needed to fully describe a given model can be obtained by calling [[file:mrcal-python-api-reference.html#-lensmodel_num_params][=mrcal.lensmodel_num_params()=]] in Python or [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h#mrcal_lensmodel_num_params][=mrcal_lensmodel_num_params()=]] in C. Given a [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h##mrcal_lensmodel_t][=mrcal_lensmodel_t lensmodel=]] structure of type =XXX= (i.e. if =lensmodel.type= is =MRCAL_LENSMODEL_XXX=) then the configuration is available in =lensmodel.LENSMODEL_XXX__config=, which has type =mrcal_LENSMODEL_XXX__config_t=. The metadata is requestable by calling this function: #+begin_src c mrcal_lensmodel_metadata_t mrcal_lensmodel_metadata( const mrcal_lensmodel_t* lensmodel ); #+end_src * Intrinsics core :PROPERTIES: :CUSTOM_ID: core :END: Most models contain an "intrinsics core". These are 4 values that appear at the start of the parameter vector: - $f_x$: the focal length in the horizontal direction, in pixels - $f_y$: the focal length in the vertical direction, in pixels - $c_x$: the horizontal projection center, in pixels - $c_y$: the vertical projection center, in pixels At this time all models contain a core. * Models Currently all models except [[#lensmodel-cahvore][=LENSMODEL_CAHVORE=]] represent a /central/ projection: all observation rays intersect at a single point (the camera origin). So $k \vec v$ projects to the same $\vec q$ for all $k$. This isn't strictly true for real-world lenses, so [[file:formulation.org::#lens-behavior][non-central projections]] will be supported in a future release of mrcal. ** =LENSMODEL_PINHOLE= :PROPERTIES: :CUSTOM_ID: lensmodel-pinhole :END: This is the basic "pinhole" model with 4 parameters: the core. Projection of a point $\vec p$ is defined as \[\vec q = \left[ \begin{aligned} f_x \frac{p_x}{p_z} + c_x \\ f_y \frac{p_y}{p_z} + c_y \end{aligned} \right] \] This model is defined only in front of the camera, and projects to infinity as we approach 90 degrees off the optical axis ($p_z \rightarrow 0$). Straight lines in space remain straight under this projection, and observations of the same plane by two pinhole cameras define a [[https://en.wikipedia.org/wiki/Homography][homography]]. This model can be used for [[file:stereo.org][stereo rectification]], although it only works well with long lenses. Longer lenses tend to have roughly pinhole behavior, but no real-world lens follows this projection, so this exists for data processing only. ** =LENSMODEL_STEREOGRAPHIC= :PROPERTIES: :CUSTOM_ID: lensmodel-stereographic :END: This is another trivial model that exists for data processing, and not to represent real lenses. Like the pinhole model, this has just the 4 core parameters. To define the projection of a point $\vec p$, let's define the angle off the optical axis: \[ \theta \equiv \tan^{-1} \frac{\left| \vec p_{xy} \right|}{p_z} \] then \[ \vec u \equiv \frac{\vec p_{xy}}{\left| \vec p_{xy} \right|} 2 \tan\frac{\theta}{2} \] and \[\vec q = \left[ \begin{aligned} f_x u_x + c_x \\ f_y u_y + c_y \end{aligned} \right] \] This model is able to project behind the camera, and has a single singularity: directly opposite the optical axis. mrcal refers to $\vec u$ as the /normalized/ stereographic projection; we get the projection $\vec q = \vec u$ when $f_x = f_y = 1$ and $c_x = c_y = 0$ Note that the pinhole model can be defined in the same way, except the pinhole model has $\vec u \equiv \frac{\vec p_{xy}} {\left| \vec p_{xy} \right|} \tan \theta$. And we can thus see that for long lenses the pinhole model and the stereographic model function similarly: $\tan \theta \approx 2 \tan \frac{\theta}{2}$ as $\theta \rightarrow 0$ ** =LENSMODEL_LONLAT= :PROPERTIES: :CUSTOM_ID: lensmodel-lonlat :END: This is a standard [[https://en.wikipedia.org/wiki/Equirectangular_projection][equirectangular projection]]. It's a trivial model useful not for representing lenses, but for describing the projection function of wide panoramic images. This works just like latitude an longitude on a globe, with a linear angular map on latitude and longitude. The 4 intrinsics core parameters are used to linearly map latitude, longitude to pixel coordinates. The full projection expression to map a camera-coordinate point $\vec p$ to an image pixel $\vec q$: \[ \vec q = \left[ \begin{aligned} f_x \, \mathrm{lon} + c_x \\ f_y \, \mathrm{lat} + c_y \end{aligned} \right] = \left[ \begin{aligned} f_x \tan^{-1}\left(\frac{p_x}{p_z}\right) + c_x \\ f_y \sin^{-1}\left(\frac{p_y}{\left|\vec p\right|}\right) + c_y \end{aligned} \right] \] So $f_x$ and $f_y$ specify the angular resolution, in pixels/radian. For normal lens models the optical axis is at $\vec p = \left[ \begin{aligned} 0 \\ 0 \\ 1 \end{aligned} \right]$, and projects to roughly the center of the image, roughly at $\vec q = \left[ \begin{aligned} c_x \\ c_y \end{aligned} \right]$. /This/ model has $\mathrm{lon} = \mathrm{lat} = 0$ at the optical axis, which produces the same, usual $\vec q$. However, this projection doesn't represent a lens and there is no "camera" or an "optical axis". The view may be centered anywhere, so $c_x$ and $c_y$ could be anything, even negative. The special case of $f_x = f_y = 1$ and $c_x = c_y = 0$ (the default values in [[file:mrcal-python-api-reference.html#-project_lonlat][=mrcal.project_lonlat()=]]) produces a /normalized/ equirectangular projection: \[ \vec q_\mathrm{normalized} = \left[ \begin{aligned} \mathrm{lon} \\\mathrm{lat} \end{aligned} \right] \] This projection has a singularity at the poles, approached as $x \rightarrow 0$ and $z \rightarrow 0$. ** =LENSMODEL_LATLON= :PROPERTIES: :CUSTOM_ID: lensmodel-latlon :END: This is a "transverse equirectangular projection". It works just like [[#lensmodel-lonlat][=LENSMODEL_LONLAT=]], but rotated 90 degrees. So instead of a globe oriented as usual with a vertical North-South axis, this projection has a horizontal North-South axis. The projected $x$ coordinate corresponds to the latitude, and the projected $y$ coordinate corresponds to the longitude. As with [[#lensmodel-lonlat][=LENSMODEL_LONLAT=]], lenses do not follow this model. It is useful as the core of a [[file:stereo.org][rectified view used in stereo processing]]. The full projection expression to map a camera-coordinate point $\vec p$ to an image pixel $\vec q$: \[ \vec q = \left[ \begin{aligned} f_x \, \mathrm{lat} + c_x \\ f_y \, \mathrm{lon} + c_y \end{aligned} \right] = \left[ \begin{aligned} f_x \sin^{-1}\left(\frac{p_x}{\left|\vec p\right|}\right) + c_x \\ f_y \tan^{-1}\left(\frac{p_y}{p_z}\right) + c_y \end{aligned} \right] \] As with [[#lensmodel-lonlat][=LENSMODEL_LONLAT=]], $f_x$ and $f_y$ specify the angular resolution, in pixels/radian. And $c_x$ and $c_y$ specify the projection at the optical axis $\vec p = \left[ \begin{aligned} 0 \\ 0 \\ 1 \end{aligned} \right]$. The special case of $f_x = f_y = 1$ and $c_x = c_y = 0$ (the default values in [[file:mrcal-python-api-reference.html#-project_latlon][=mrcal.project_latlon()=]]) produces a /normalized/ transverse equirectangular projection: \[ \vec q_\mathrm{normalized} = \left[ \begin{aligned} \mathrm{lat} \\\mathrm{lon} \end{aligned} \right] \] This projection has a singularity at the poles, approached as $y \rightarrow 0$ and $z \rightarrow 0$. ** =LENSMODEL_OPENCV4=, =LENSMODEL_OPENCV5=, =LENSMODEL_OPENCV8=, =LENSMODEL_OPENCV12= :PROPERTIES: :CUSTOM_ID: lensmodel-opencv :END: These are simple parametric models that have the given number of "distortion" parameters in addition to the 4 core parameters. The projection behavior is described in the [[https://docs.opencv.org/4.5.0/d9/d0c/group__calib3d.html#details][OpenCV documentation]]. These do a reasonable job in representing real-world lenses, /and/ they're compatible with many other tools. The projection function is \begin{align*} \vec P &\equiv \frac{\vec p_{xy}}{p_z} \\ r &\equiv \left|\vec P\right| \\ \vec P_\mathrm{radial} &\equiv \frac{ 1 + k_0 r^2 + k_1 r^4 + k_4 r^6}{ 1 + k_5 r^2 + k_6 r^4 + k_7 r^6} \vec P \\ \vec P_\mathrm{tangential} &\equiv \left[ \begin{aligned} 2 k_2 P_0 P_1 &+ k_3 \left(r^2 + 2 P_0^2 \right) \\ 2 k_3 P_0 P_1 &+ k_2 \left(r^2 + 2 P_1^2 \right) \end{aligned}\right] \\ \vec P_\mathrm{thinprism} &\equiv \left[ \begin{aligned} k_8 r^2 + k_9 r^4 \\ k_{10} r^2 + k_{11} r^4 \end{aligned}\right] \\ \vec q &= \vec f_{xy} \left( \vec P_\mathrm{radial} + \vec P_\mathrm{tangential} + \vec P_\mathrm{thinprism} \right) + \vec c_{xy} \end{align*} The parameters are $k_i$. For any N-parameter OpenCV model the higher-order terms $k_i$ for $i \geq N$ are all 0. So the tangential distortion terms exist for all the models, but the thin-prism terms exist only for =LENSMODEL_OPENCV12=. The radial distortion is a polynomial in =LENSMODEL_OPENCV4= and =LENSMODEL_OPENCV5=, but a rational for the higher-order models. Practically-speaking =LENSMODEL_OPENCV8= works decently well for wide lenses. For non-fisheye lenses, =LENSMODEL_OPENCV4= and =LENSMODEL_OPENCV5= work ok. I'm sure scenarios where =LENSMODEL_OPENCV12= is beneficial exist, but I haven't come across them. ** =LENSMODEL_CAHVOR= :PROPERTIES: :CUSTOM_ID: cahvor-lens-model :END: mrcal supports =LENSMODEL_CAHVOR=, a lens model used in a number of tools at JPL. The =LENSMODEL_CAHVOR= model has 5 "distortion" parameters in addition to the 4 core parameters. This support exists only for compatibility, and there's no reason to use it otherwise. This model is described in: [[https://trs.jpl.nasa.gov/bitstream/handle/2014/20686/98-1739.pdf][Gennery, D.B. 2001. Least-squares camera calibration including lens distortion and automatic editing of calibration points. In Calibration and Orientation of Cameras in Computer Vision, A. Gruen and T.S. Huang (Eds.), Springer-Verlag, pp. 123–136]] ** =LENSMODEL_CAHVORE_...= :PROPERTIES: :CUSTOM_ID: lensmodel-cahvore :END: This is an extended flavor of =LENSMODEL_CAHVOR= to support wider lenses. The =LENSMODEL_CAHVORE= model has 8 "distortion" parameters in addition to the 4 core parameters. As with =LENSMODEL_CAHVOR= this support exists only for compatibility, and there's no reason to use it otherwise. CAHVORE is a [[file:formulation.org::#lens-behavior][noncentral projection]], so more infrastructure is required to make =unproject()= do something reasonable in all cases. Thus projection uncertainty and differencing don't work for this model, and throw an error. *** Configuration =LENSMODEL_CAHVORE= models have a single configuration parameter: =linearity=. - =linearity= = 0 is a "fisheye" CAHVORE model. This is referred to as =CAHVORE2= in JPL tools - =linearity= = 1 is a "perspective" CAHVORE model. This is referred to as =CAHVORE1= in JPL tools - Any other =linearity= is a "general" CAHVORE model. This is referred to as =CAHVORE3= in JPL tools *** Some notes - The last 3 intrinsic parameters of =LENSMODEL_CAHVORE= are the $\vec E$ vector. If these are 0, this becomes a central projection, and [[file:mrcal-python-api-reference.html#-unproject][=mrcal.unproject()=]] is able to work normally. If you want to compute differences you need [[file:mrcal-python-api-reference.html#-unproject][=mrcal.unproject()=]], so you must "centralize" the model by setting =intrinsics[-3:] = 0=. This ignores any noncentral effects, which could be significant close to the lens. Doing this also invalidates the uncertainty logic. More general noncentral projection logic will be added in a future release of mrcal, and this situation may improve then - A =LENSMODEL_CAHVORE= projection with $\vec E = 0$ and =linearity= = 1 is equivalent to a =LENSMODEL_CAHVOR= projection This model is described in: [[https://link.springer.com/article/10.1007/s11263-006-5168-1][Gennery, D.B. Generalized Camera Calibration Including Fish-Eye Lenses. Int J Comput Vision 68, 239–266 (2006)]] ** =LENSMODEL_SPLINED_STEREOGRAPHIC_...= :PROPERTIES: :CUSTOM_ID: splined-stereographic-lens-model :END: This is a stereographic model with correction factors. It is mrcal's attempt to model real-world lens behavior with more fidelity than the usual parametric models make possible. To compute a projection using this model, we first compute the normalized stereographic projection $\vec u$ as in the [[#lensmodel-stereographic][=LENSMODEL_STEREOGRAPHIC=]] definition above: \[ \theta \equiv \tan^{-1} \frac{\left| \vec p_{xy} \right|}{p_z} \] \[ \vec u \equiv \frac{\vec p_{xy}}{\left| \vec p_{xy} \right|} 2 \tan\frac{\theta}{2} \] Then we use $\vec u$ to look-up a $\Delta \vec u$ using two separate splined surfaces: \[ \Delta \vec u \equiv \left[ \begin{aligned} \Delta u_x \left( \vec u \right) \\ \Delta u_y \left( \vec u \right) \end{aligned} \right] \] and we then define the rest of the projection function: \[\vec q = \left[ \begin{aligned} f_x \left( u_x + \Delta u_x \right) + c_x \\ f_y \left( u_y + \Delta u_y \right) + c_y \end{aligned} \right] \] The $\Delta \vec u$ are the off-stereographic terms. If $\Delta \vec u = 0$, we get a plain stereographic projection. Much more detail about this model is available on the [[file:splined-models.org][splined models page]]. *** Configuration There are several configuration parameters described on the [[file:splined-models.org::#splined-models-configuration-selection][splined models page]]. mrcal-2.4.1/doc/mrcal-docs-publish.el000066400000000000000000000025121456301662300174010ustar00rootroot00000000000000(setq org-publish-project-alist `(("orgfiles" :base-directory "." :base-extension "org" :publishing-directory "./out" :publishing-function org-html-publish-to-html :section-numbers nil :with-toc nil :with-sub-superscript nil :html-postamble nil :with-author "Dima Kogan" :with-email "dima@secretsauce.net" :html-head-include-default-style nil :html-head ,(concat "" "") :html-preamble ,(with-temp-buffer (insert-file-contents "mrcal-preamble-GENERATED.html") (buffer-string)) :html-mathjax-options ((path "external/MathJax-master/es5/tex-chtml.js") (scale "100") (align "center") (font "TeX") (linebreaks "false") (autonumber "AMS") (indent "0em") (multlinewidth "85%") (tagindent ".8em") (tagside "right"))))) mrcal-2.4.1/doc/mrcal-preamble-TEMPLATE.html000066400000000000000000000007541456301662300203570ustar00rootroot00000000000000


      mrcal-2.4.1/doc/mrcal.css000066400000000000000000000016011456301662300151750ustar00rootroot00000000000000/* This background color is hardcoded in the docs in a few places. Do a "git grep" if changing it */ body {background-color: #e8dfd0;} pre {border: 1px solid black; box-shadow: 3px 3px 3px #606060;} pre.example {background-color: #303030; color: #e5e5e5; max-width 700px} .org-svg {width: 90%; min-width: 500px; max-width: 900px;} pre.src { background-color: #303030; color: #e5e5e5; position: relative; overflow: auto; } /* Style for the nav bar at the top. Adapted from */ /* o-blog.css */ .supernav_title { font-size: 30px; font-weight: bolder; } .supernav_list { vertical-align: middle; top: 0; list-style: none outside none; white-space: normal; overflow: hidden; } .supernav_list li { display: inline-block; } .supernav_list li + li:before { content: " / "; padding: 0 10px; } img { max-width: 100%; } mrcal-2.4.1/doc/news-2.0.org000066400000000000000000000263731456301662300153640ustar00rootroot00000000000000#+TITLE: mrcal 2.0 release notes #+OPTIONS: toc:nil * New in mrcal 2.0 Lots and lots of under-the-hood improvements and bug fixes. Most notable ones listed here ** High level significant improvements - Reworked the [[file:stereo.org][dense stereo processing]]. This is now documented, with nice APIs. Rectified models can be represented in a [[file:cameramodels.org][=.cameramodel=]] file, and saved to disk. - Added [[file:triangulation.org][sparse triangulation routines]]. Uncertainty can be propagated through these routines to gauge the effects of calibration-time and observation-time noise. - [[file:lensmodels.org::#splined-stereographic-lens-model][=LENSMODEL_SPLINED_STEREOGRAPHIC=]] models have been thoroughly tested, and are ready for prime time. Solver now applies anisotropic regularization to reduce curl in the correction vector field, so the solved models now act mostly radially. The [[file:mrcal-show-splined-model-correction.html][=mrcal-show-splined-model-correction=]] tool extended, and produces clearer plots. These models work well. Use them. - The =observed_pixel_uncertainty= is now estimated from the optimized residuals instead of being specified explicitly. The reported uncertainties should now be correct in absolute, not just relative terms - [[file:mrcal-python-api-reference.html#-unproject][=mrcal.unproject()=]] can report gradients - Calibration residuals can be visualized from the stored cameramodel, not just from [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras --explore=]]. Added new tools - [[file:mrcal-show-residuals-board-observation.html][=mrcal-show-residuals-board-observation=]] - [[file:mrcal-show-residuals.html][=mrcal-show-residuals=]] and new Python API functions - [[file:mrcal-python-api-reference.html#-show_residuals_board_observation][=mrcal.show_residuals_board_observation()=]] - [[file:mrcal-python-api-reference.html#-show_residuals_histogram][=mrcal.show_residuals_histogram()=]] - [[file:mrcal-python-api-reference.html#-show_residuals_vectorfield][=mrcal.show_residuals_vectorfield()=]] - [[file:mrcal-python-api-reference.html#-show_residuals_magnitudes][=mrcal.show_residuals_magnitudes()=]] - [[file:mrcal-python-api-reference.html#-show_residuals_directions][=mrcal.show_residuals_directions()=]] - [[file:mrcal-python-api-reference.html#-show_residuals_regional][=mrcal.show_residuals_regional()=]] - [[file:cameramodels.org][=.cameramodel=]] files can be read/written from C - Added simple projection/unprojection functions to the Python and C APIs: - [[file:mrcal-python-api-reference.html#-project_pinhole][=mrcal.project_pinhole()=]] - [[file:mrcal-python-api-reference.html#-unproject_pinhole][=mrcal.unproject_pinhole()=]] - [[file:mrcal-python-api-reference.html#-project_latlon][=mrcal.project_latlon()=]] - [[file:mrcal-python-api-reference.html#-unproject_latlon][=mrcal.unproject_latlon()=]] - [[file:mrcal-python-api-reference.html#-project_lonlat][=mrcal.project_lonlat()=]] - [[file:mrcal-python-api-reference.html#-unproject_lonlat][=mrcal.unproject_lonlat()=]] This is added to the existing functions - [[file:mrcal-python-api-reference.html#-project_stereographic][=mrcal.project_stereographic()=]] - [[file:mrcal-python-api-reference.html#-unproject_stereographic][=mrcal.unproject_stereographic()=]] - Added [[file:lensmodels.org::#lensmodel-latlon][=LENSMODEL_LATLON=]] and [[file:lensmodels.org::#lensmodel-lonlat][=LENSMODEL_LONLAT=]] models to represent epipolar-aligned and panoramic images respectively ** Lower-level improvements for user convenience and/or internal machinery - All Python =poseutils= functions can now work in-place - Added [[file:mrcal-python-api-reference.html#-invert_R][=mrcal.invert_R()=]] function - [[file:mrcal-python-api-reference.html#-transform_point_Rt][=mrcal.transform_point_Rt()=]] and [[file:mrcal-python-api-reference.html#-rotate_point_R][=mrcal.rotate_point_R()=]] can take an =inverted= argument - [[file:mrcal-python-api-reference.html#-project_stereographic][=mrcal.project_stereographic()=]] and [[file:mrcal-python-api-reference.html#-unproject_stereographic][=mrcal.unproject_stereographic()=]] and the others now use [[https://github.com/dkogan/numpysane/blob/master/README-pywrap.org][=numpysane_pywrap=]], so full broadcasting and in-place output are available - Added [[file:mrcal-python-api-reference.html#-num_states][=mrcal.num_states()=]], [[file:mrcal-python-api-reference.html#-num_intrinsics_optimization_params][=mrcal.num_intrinsics_optimization_params()=]] - New [[file:lensmodels.org::#representation][lensmodel metadata property]]: =has_gradients=. Currently only [[file:lensmodels.org::#lensmodel-cahvore][=LENSMODEL_CAHVORE=]] has this at =False= - [[file:mrcal-python-api-reference.html#-transform_image][=mrcal.transform_image()=]] supports more of the opencv api, like inplace output - [[file:mrcal-reproject-image.html][=mrcal-reproject-image=]] tool has new =--distance= argument - =mrcal-show-....= visualization tools (and =mrcal.show_...()= functions) have new =--title= (and =title=) argument. These replace the default title instead of extending the default, which =--extratitle= does - [[file:mrcal-python-api-reference.html#-projection_uncertainty][=mrcal.projection_uncertainty()=]] function can take =observed_pixel_uncertainty= argument, to override the value inferred from the residuals at the optimum - The visualization functions can plot observations with dots instead of points: - [[file:mrcal-python-api-reference.html#-show_projection_diff][=mrcal.show_projection_diff()=]] - [[file:mrcal-python-api-reference.html#-show_projection_uncertainty][=mrcal.show_projection_uncertainty()=]] - [[file:mrcal-python-api-reference.html#-show_splined_model_correction][=mrcal.show_splined_model_correction()=]] - Added [[file:mrcal-python-api-reference.html#-fitted_gaussian_equation][=mrcal.fitted_gaussian_equation()=]] * Migration notes 1.0 -> 2.0 mrcal is being actively developed, and some improvements change the interfaces in incompatible ways, requiring small amounts of work to port older code. I try to avoid breaking changes, but sometimes doing this is necessary. The C API is mostly unstable. If you use the mrcal C library, read this section carefully. The Python API and the commandline tools are mostly stable, but some things did change, so please still read this section. - The =observed_pixel_uncertainty= is now estimated from the optimized residuals instead of being specified explicitly. =mrcal_optimize()= and =mrcal_optimizer_callback()= in the C API don't have this argument anymore. The Python analogues [[file:mrcal-python-api-reference.html#-optimize][=mrcal.optimize()=]] and [[file:mrcal-python-api-reference.html#-optimizer_callback][=mrcal.optimizer_callback()=]] still accept the argument (to keep old [[file:cameramodels.org][=.cameramodel=]] files working), but this argument is now ignored - =seed_pinhole()= function reworked and renamed to [[file:mrcal-python-api-reference.html#-seed_stereographic][=mrcal.seed_stereographic()=]] - [[file:mrcal-python-api-reference.html#-transform_image][=mrcal.transform_image()=]] API extended. Calls are backwards-compatible, but the defaults have changed - =show_splined_model_surface()= function renamed to [[file:mrcal-python-api-reference.html#-show_splined_model_correction][=mrcal.show_splined_model_correction()=]]. Similarly, The =mrcal-show-splined-model-surface= tool renamed to [[file:mrcal-show-splined-model-correction.html][=mrcal-show-splined-model-correction=]]. New function and tool can display the data in new ways (the correction vector field and correction magnitude), and the defaults have changed - [[file:mrcal-show-distortion-off-pinhole.html][=mrcal-show-distortion-off-pinhole=]] cmdline tool: =--scale= argument renamed to =--vectorscale= for consistency - [[file:mrcal-python-api-reference.html#-show_distortion_off_pinhole][=mrcal.show_distortion_off_pinhole()=]]: radial functionality split into [[file:mrcal-python-api-reference.html#-show_distortion_off_pinhole_radial][=mrcal.show_distortion_off_pinhole_radial()=]] - =mrcal.show_projection_uncertainty_xydist()= was removed. It wasn't useful - [[file:lensmodels.org::#lensmodel-cahvore][=LENSMODEL_CAHVORE=]] lens models: =linearity= is a configuration parameter, /not/ an optimization parameter. All existing [[file:cameramodels.org][=.cameramodel=]] files containing [[file:lensmodels.org::#lensmodel-cahvore][=LENSMODEL_CAHVORE=]] models must be ported. I doubt there's a single one of those out there. - =mrcal.hypothesis_corner_positions()= renamed to [[file:mrcal-python-api-reference.html#-hypothesis_board_corner_positions][=mrcal.hypothesis_board_corner_positions()=]] and the API was updated in a breaking way - =mrcal.lensmodel_metadata()= renamed to [[file:mrcal-python-api-reference.html#-lensmodel_metadata_and_config][=mrcal.lensmodel_metadata_and_config()=]] - All the existing stereo processing functions were redone. Calls to - =mrcal.stereo_rectify_prepare()= - =mrcal.stereo_unproject()= - =mrcal.stereo_range()= - =mrcal.stereo_range()= must be ported. See the [[file:python-api.org::#python-api-stereo][documentation]] for the new functions. - - =mrcal_transform_point_Rt()= and =mrcal_rotate_point_R()= C functions now take an =inverted= argument. This is an API, ABI break - [[file:mrcal-python-api-reference.html#-synthesize_board_observations][=mrcal.synthesize_board_observations()=]] returns =Rt_ref_boardref=, not =Rt_cam0_boardref=. The API didn't change, but the meaning of the output did - =mrcal_project_...()= and =mrcal_unproject_...()= functions now take =const double* fxycxy= instead of 4 discrete =double= values - Similarly, the =mrcal.project_...()= and =mrcal.unproject_...()= functions now take an =fxycxy= array instead of 4 discrete values - =mrcal_state_index_THING()= and =mrcal_num_states_THING()= (and their Python flavors) return <0 and 0 respectively in C (and None and 0 respectively in Python) in case the THING isn't actually being optimized - [[file:mrcal-show-geometry.html][=mrcal-show-geometry=]] tool: =--scale-axes= argument renamed to =--axis-scale= - [[file:mrcal-show-valid-intrinsics-region.html][=mrcal-show-valid-intrinsics-region=]] tool: =--writeimage= renamed to =--write-image= - [[file:mrcal-python-api-reference.html#-apply_color_map][=mrcal.apply_color_map()=]] uses BGR, not RGB - [[file:mrcal-python-api-reference.html#-image_transformation_map][=mrcal.image_transformation_map()=]]: API extended in non-backwards-compatible way - Some tools, functions have more consistent, better arguments at the expense of breaking the API: - [[file:mrcal-python-api-reference.html#-show_projection_diff][=mrcal.show_projection_diff()=]] - [[file:mrcal-show-projection-diff.html][=mrcal-show-projection-diff=]] - [[file:mrcal-python-api-reference.html#-projection_diff][=mrcal.projection_diff()=]] - [[file:mrcal-graft-models.html][=mrcal-graft-models=]] - [[file:mrcal-show-geometry.html][=mrcal-show-geometry=]] tool: default is flipped, so =--hide-boards= option was removed and a =--show-calobjects= option added - [[file:mrcal-python-api-reference.html#-synthesize_board_observations][=mrcal.synthesize_board_observations()=]] uses different strings for the =which= argument: =_= -> =-= mrcal-2.4.1/doc/news-2.1.org000066400000000000000000000017311456301662300153540ustar00rootroot00000000000000#+TITLE: mrcal 2.1 release notes #+OPTIONS: toc:nil * New in mrcal 2.1 This is a /very/ minor release, made primarily to facilitate the push to Debian. Updates: - Lots of minor documentation improvements. These appear on [[http://mrcal.secretsauce.net][the website]] - Visualization functions use more legible colors to display the valid-intrinsics region - Python library imports =cv2= only where necessary, which dramatically speeds up all the tools where =cv2= isn't used - [[file:mrcal-python-api-reference.html#-r_from_R][=mrcal.r_from_R()=]] works better with small rotations. Near-identity rotations now report correspondingly-small =r=, rather than 0 * Migration notes 2.0 -> 2.1 This is a /very/ minor release, and is 99.9% compatible. The only incompatible update: - [[file:mrcal-python-api-reference.html#-annotate_image__valid_intrinsics_region][=mrcal.annotate_image__valid_intrinsics_region()=]] draws in green by default for consistency with other functions mrcal-2.4.1/doc/news-2.2.org000066400000000000000000000247211456301662300153610ustar00rootroot00000000000000#+TITLE: mrcal 2.2 release notes #+OPTIONS: toc:nil * New in mrcal 2.2 This is a mostly-maintenance release. I'm using these tools myself a /lot/, and I'm developing some [[file:roadmap.org][exciting (and not-yet-ready) new features]]. In the process, I'm cleaning things up and making infrastructural improvements. This release is a collection of many such improvements: there are a lot of medium-size fixes, but nothing huge. Exciting new features in future releases. In the nearest term, I need some sort of "recipes" documentation section and an extension of the [[file:tour.org][tour of mrcal]] with better calibration data. This is coming. Soon. ** Stereo processing - The [[file:mrcal-stereo.html][=mrcal-stereo=]] tool includes an interactive, graphical visualizer, accessed with =mrcal-stereo --viz stereo=. This allows the user to quickly assess the quality of the stereo result, the ranges, epipolar misalignment, and sensitivity to errors. Requires [[https://pyfltk.sourceforge.io/][pyfltk]] and [[https://github.com/dkogan/GL_image_display][GL_image_display]] - Since the [[file:mrcal-stereo.html][=mrcal-stereo=]] tool now has multiple visualizers, the =--show-geometry= option has been renamed to =--viz geometry= - The [[file:mrcal-stereo.html][=mrcal-stereo=]] tool can write out a point cloud in the [[https://en.wikipedia.org/wiki/PLY_(file_format)][=.ply= format]] if invoked with the =--write-point-cloud= option - The [[file:mrcal-stereo.html][=mrcal-stereo=]] tool can use the [[https://www.cvlibs.net/software/libelas/][libelas stereo matcher]] instead of the default [[https://docs.opencv.org/4.x/d2/d85/classcv_1_1StereoSGBM.html][SGBM matcher in OpenCV]] if invoked with =--stereo-matcher ELAS=. Requires [[https://www.cvlibs.net/software/libelas/][libelas]]. - The [[file:mrcal-python-api-reference.html#-stereo_range][=mrcal.stereo_range()=]] function can accept scalar disparities - Added [[file:mrcal-python-api-reference.html#-stereo_unproject][=mrcal.stereo_unproject()=]] function to compute 3D points directly, instead of explicitly calling [[file:mrcal-python-api-reference.html#-stereo_range][=mrcal.stereo_range()=]] first - The [[file:mrcal-python-api-reference.html#-rectified_system][=mrcal.rectified_system()=]] function returns an additional dict of metadata if invoked with =return_metadata = True=. This is useful to determine the computed stereo resolution and field-of-view parameters ** [[https://www.github.com/dkogan/mrcal/blob/master/poseutils.py][=poseutils=]] - The =pq= transform representation was replaced with the [[file:conventions.org::#pose-representation][=qt= representation]], which is analogous to the [[file:conventions.org::#pose-representation][=rt= representation]]. Consequently the =mrcal.pq_from_Rt()=, =mrcal.Rt_from_pq()= functions have been replaced with [[file:mrcal-python-api-reference.html#-qt_from_Rt][=mrcal.qt_from_Rt()=]], [[file:mrcal-python-api-reference.html#-Rt_from_qt][=mrcal.Rt_from_qt()=]] functions. These are available only in the Python layer. - [[file:mrcal-python-api-reference.html#-quat_from_R][=mrcal.quat_from_R()=]] and [[file:mrcal-python-api-reference.html#-R_from_quat][=mrcal.R_from_quat()=]] are now implemented in C, broadcast fully, and support in-place output. Like the rest of the [[https://www.github.com/dkogan/mrcal/blob/master/poseutils.py][=poseutils=]]. These are available only in the Python layer. - Added [[file:mrcal-python-api-reference.html#-compose_r][=mrcal.compose_r()=]] function for direct composition of [[https://en.wikipedia.org/wiki/Axis%E2%80%93angle_representation#Rotation_vector][Rodrigues rotations]], /without/ transforming to a rotation matrix first. This is available in both the Python and C layers - Added [[file:mrcal-python-api-reference.html#-skew_symmetric][=mrcal.skew_symmetric()=]] function for a matrix-multiplication-based cross-product. This is available only in the Python layer ** The [[file:mrcal-convert-lensmodel.html][=mrcal-convert-lensmodel=]] tool improvements This tool received lots of usability and robustment improvements: - The =--viz= output plot can be controlled and written to disk by passing =--set=, =--unset=, =--hardcopy=, etc. Same as with the [[file:mrcal-show-projection-diff.html][=mrcal-show-projection-diff=]] tool and others. - The output model is written to a file on disk instead of to stdout. This is incompatible with previously behavior, but is much nicer. We're now less likely to produce an unwanted spew onto the console - =--radius= and =--where= work even without =--sampled=: they cut down on the observations being fitted - We can pass multiple values in =--distance=. This is critically important for =--sampled= solves: using a near and far distance together stabilizes the fitted translation. Prior to this =--sampled= solves often ended up unusable due to an aphysical translation. - =--distance= is used even without =--sampled=: this controls the diff visualization produced with =--viz= - Non-sampled solves are now run using incremental stages, just like in the [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras=]] tool. This makes the non-sampled operation of this tool much more robust - Non-sampled solves can be limited to just the camera in question by passing =--monotonic= ** Other - Most functions in the Python API now accept non-essential arguments as keywords only. Most common usages should remain functional, but code that used too many positional arguments in calls will need to be ported. This will increase the readability of that code, and this change makes it easier to maintain API compatibility in the future - The [[file:conventions.org::#symbols-optimization][variable convention used for the optimization state]] changed to $\vec b$ from $\vec p$. Previously, $\vec p$ was used to denote both optimization state and points in space, with this ambiguity being clear from context. However, too many times we'd see a situation where this /wasn't/ clear from context. Renaming this clears up the ambiguity. This isn't a functional change, but affects lots of documentation, comments and variable names. - Added [[file:mrcal-python-api-reference.html#-load_image][=mrcal.load_image()=]] and [[file:mrcal-python-api-reference.html#-save_image][=mrcal.save_image()=]] functions to both the Python and C APIs. These aren't special in any way, but are convenient, and allow us to avoid OpenCV, which is slow and massive. Requires [[https://freeimage.sourceforge.io/][libfreeimage]] - The [[file:mrcal-python-api-reference.html#-mrcal-triangulate][=mrcal.mrcal-triangulate()=]] tool now has a =--clahe= option to apply equalization to the input images prior to processing - The [[file:mrcal-python-api-reference.html#-ref_calibration_object][=mrcal.ref_calibration_object()=]] function can accept different spacings in the horizontal and vertical directions - The [[file:mrcal-python-api-reference.html#-ref_calibration_object][=mrcal.ref_calibration_object()=]] function can broadcast over =object_spacing= and =calobject_warp= - The code can be cross-built, if invoked from the Debian build tools (=DEB_HOST_MULTIARCH= and the compiler and linker environment variables set) - The [[file:mrcal-python-api-reference.html#-compute_chessboard_corners][=mrcal.compute_chessboard_corners()=]] function API was cleaned up. Many arguments have different names, and most of them are only accepted as keywords. The =weight_column_kind= argument must be one of ='level'= or ='weight'= or =None=. - The =mrcal-to-cameramodel= tool was renamed to [[file:mrcal-from-cahvor.html][=mrcal-from-cahvor=]] to make it easier to support future format converters. - The [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras=]] tool now reports its "RMS error" as the RMS error of the measurement vector. Each pixel observation produces 2 measurement values: the error in $x$ and $y$. Prior to this release I reported the RMS error treating such a pair as /one/ value: $\sqrt{\frac{\left\Vert \vec x \right\Vert^2}{\frac{N_\mathrm{measurement}}{2}}}$. This was in conflict with other parts of the code, so now I report this as two separate values: $\sqrt{\frac{\left\Vert \vec x \right\Vert^2}{N_\mathrm{measurement}}}$. So now the reported RMS error is just $\mathrm{Var} \left( \vec x \right)$ - [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras=]] and [[file:mrcal-python-api-reference.html#-seed_stereographic][=mrcal.seed_stereographic()=]] can accept multiple estimates for focal length: one estimate per camera. Useful in seeding calibration problems containing multiple disparate cameras - The [[file:mrcal-show-geometry.html][=mrcal-show-geometry=]] tool and the [[file:mrcal-python-api-reference.html#-show_geometry][=mrcal.show_geometry()=]] function can now display the calibration objects observed by /all/ cameras during a calibration (previous behavior) /or/ they can dispaly the objects observed by just the given camera. The default behavior is unchanged. * Migration notes 2.1 -> 2.2 The vast majority of existing usage remains the same, but some updates described above will require a code change: - Most of the Python API functions now use keyword-only arguments for the non-essential arguments. Any calls that used too many positional arguments will need to be clarified with keywords - =mrcal.pq_from_Rt()= calls must be replaced with [[file:mrcal-python-api-reference.html#-qt_from_Rt][=mrcal.qt_from_Rt()=]], and the caller must use the [[file:conventions.org::#pose-representation][=qt= transform representation]] - =mrcal.Rt_from_pq()= calls must be replaced with [[file:mrcal-python-api-reference.html#-Rt_from_qt][=mrcal.Rt_from_qt()=]], and the caller must use the [[file:conventions.org::#pose-representation][=qt= transform representation]] - =mrcal-stereo --show-geometry= is now invoked as =mrcal-stereo --viz geometry= - The =mrcal-to-cameramodel= tool was renamed to [[file:mrcal-from-cahvor.html][=mrcal-from-cahvor=]] - A C header was renamed: =basic_geometry.h= -> [[https://www.github.com/dkogan/mrcal/blob/master/basic-geometry.h][=basic-geometry.h=]], requiring an =#include= update - The [[file:mrcal-python-api-reference.html#-compute_chessboard_corners][=mrcal.compute_chessboard_corners()=]] function API was changed. If you're using this, please see the documentation - The [[file:mrcal-convert-lensmodel.html][=mrcal-convert-lensmodel=]] tool writes the output model to a file on disk, not to stdout as it has previously. New usage will need to be adjusted mrcal-2.4.1/doc/news-2.3.org000066400000000000000000000162201456301662300153550ustar00rootroot00000000000000#+TITLE: mrcal 2.3 release notes #+OPTIONS: toc:nil * New in mrcal 2.3 This is once again a mostly-maintenance release. Many medium-important but significant improvements and fixes are present here. The big update in this release is extended documentation, especially practical notes in the [[file:how-to-calibrate.org][how-to-calibrate page]] and the [[file:recipes.org][recipes]]. Exciting new features are coming. ** Improved discrete point support Calibrations are still implemented primarily off chessboard observations, but support for discrete points is being added bit by bit: - Added [[file:mrcal-python-api-reference.html#-residuals_point][=mrcal.residuals_point()=]], an analogue to [[file:mrcal-python-api-reference.html#-residuals_chessboard][=mrcal.residuals_chessboard()=]] - The [[file:mrcal-python-api-reference.html#-show_residuals_vectorfield][=mrcal.show_residuals_...()=]] functions now display residuals from chessboard /and/ point observations - [[file:mrcal-python-api-reference.html#-show_geometry][=mrcal.show_geometry()=]] and [[file:mrcal-show-geometry.html][=mrcal-show-geometry=]] and [[file:mrcal-show-projection-uncertainty.html][=mrcal-show-... --observations=]] can display calibration-time points - Projection uncertainty can be computed with calibrations from point observations /if/ the points were fixed ** Full CAHVORE support CAHVORE models now have gradients implemented, so all the normal functionality now works with these models. We can solve for a CAHVORE model. This model is noncentral, so unprojection only works if $E = 0$: when this model behaves centrally ** C API - =mrcal_image_..._crop()= is now =static inline=. This fixes linker errors on some compilers - =mrcal_cameramodel_t= now has =double intrinsics[0]= instead of =double intrinsics[]=. This allows =#include = to work inside C++ code - =mrcal_cameramodel_t= has a size unknown at compile time, so it cannot be allocated on the stack. To resolve this we now have [[https://github.com/dkogan/mrcal/blob/88e4c1df1c8cf535516719c5d4257ef49c9df1da/mrcal-types.h#L338][=mrcal_cameramodel_LENSMODEL_XXXX_t= structures]] for models that have known-at-compile-time size. These can be allocated on the stack, so they are easier to use - Dense stereo processing in C is now possible. [[https://github.com/dkogan/mrcal/blob/88e4c1df1c8cf535516719c5d4257ef49c9df1da/stereo.h][=stereo.h=]] contains: - =mrcal_rectified_resolution()= - =mrcal_rectified_system()= - =mrcal_rectification_maps()= ** [[file:mrcal-stereo.html][=mrcal-stereo=]] - [[file:mrcal-stereo.html][=mrcal-stereo=]] writes out a binary disparity image as a 16-bpp =.png= file. This allows lossless post-processing of the stereo result - [[file:mrcal-stereo.html][=mrcal-stereo --viz stereo=]] displays both the rectified and input coordinates under the mouse cursor - [[file:mrcal-stereo.html][=mrcal-stereo=]] can process multiple images in parallel - bug fix: [[file:mrcal-stereo.html][=mrcal-stereo=]] respects =--axis-scale= - bug fix: [[file:mrcal-stereo.html][=mrcal-stereo=]] can once again process multiple files with a single invocation ** Generic visualization updates - [[file:mrcal-python-api-reference.html#-show_projection_diff][=mrcal.show_projection_diff()=]] and [[file:mrcal-show-projection-diff.html][=mrcal-show-projection-diff=]] handle =nan= values better: no confused plots or ugly warnings on the console - [[file:mrcal-python-api-reference.html#-show_projection_diff][=mrcal.show_projection_diff()=]] and [[file:mrcal-show-projection-diff.html][=mrcal-show-projection-diff=]] can plot vectorfields with multiple distances - [[file:mrcal-python-api-reference.html#-show_projection_uncertainty_vs_distance][=mrcal.show_projection_uncertainty_vs_distance()=]] now has =distance_min=, =distance_max=, =observed_pixel_uncertainty= arguments to better control the plot. The defaults autodetect the values, so the default behavior does not change - [[file:mrcal-python-api-reference.html#-show_residuals_board_observation][=mrcal.show_residuals_board_observation()=]] and [[file:mrcal-show-residuals-board-observation.html][=mrcal-show-residuals-board-observation=]] reports =iobservation_from_worst= in its title. This makes it simple to regenerate specific plots, even if they were displayed out of order - [[file:mrcal-show-residuals-board-observation.html][=mrcal-show-residuals-board-observation=]] has =--from-glob= ** Image I/O - [[file:mrcal-python-api-reference.html#-save_image][=mrcal.save_image()=]] can write 16-bit-per-pixel grayscale images properly. This requires a more recent =libfreeimage= than is available on some OSs. The tests make sure it works. ** Calibration seed bug fix [[file:mrcal-python-api-reference.html#-estimate_monocular_calobject_poses_Rt_tocam][=mrcal.estimate_monocular_calobject_poses_Rt_tocam()=]] ignores invalid input points. This makes calibrating with incomplete chessboard observations work properly ** Generic API updates - Commandline tools now print errors to standard error instead of throwing exceptions - [[file:mrcal-python-api-reference.html#-rectified_resolution][=mrcal.rectified_resolution()=]] has been split from [[file:mrcal-python-api-reference.html#-rectified_system][=mrcal.rectified_system()=]] - [[file:mrcal-python-api-reference.html#-optimize][=mrcal.optimize()=]] and [[file:mrcal-python-api-reference.html#-optimizer_callback][=mrcal.optimizer_callback()=]]: all arguments are keyword-only, most arguments are optional - [[file:mrcal-python-api-reference.html#-measurement_index_boards][=mrcal.measurement_index_...()=]] all return <0 if those particular measurements aren't present - Added [[file:mrcal-python-api-reference.html#-make_perfect_observations][=mrcal.make_perfect_observations()=]] to produce perfect observations with perfect noise. Very useful for error analysis - [[file:mrcal-python-api-reference.html#-ref_calibration_object][=mrcal.ref_calibration_object()=]] can return the position of /any/ point on the chessboard, /not/ just the chessboard corners - [[file:mrcal-convert-lensmodel.html][=mrcal-convert-lensmodel=]] has =--cbmax= - [[file:mrcal-python-api-reference.html#-residuals_chessboard][=mrcal.residuals_chessboard()=]] argument rename: =i_cam= $\rightarrow$ =icam_intrinsics= for consistency. The old argument is still accepted for backwards compatibility - [[file:mrcal-python-api-reference.html#-residuals_chessboard][=mrcal.residuals_chessboard()=]]() has a new =return_observations= argument The default =return_observations=False= produces the original behavior. =if return_observations:= we return =residuals,observations= - [[file:mrcal-python-api-reference.html#-residuals_chessboard][=mrcal.residuals_chessboard()=]] returns size-0 arrays if no observations are present - [[file:mrcal-python-api-reference.html#-show_geometry][=mrcal.show_geometry()=]] has smarter logic when given > 2 cameras: the =axis_scale= has a reasonable default size * Migration notes 2.2 -> 2.3 The [[https://github.com/dkogan/mrcal/blob/88e4c1df1c8cf535516719c5d4257ef49c9df1da/mrcal.h#L671][mrcal_measurement_index_regularization()]] C function has an extended prototype. To migrate, pass the extra requested arguments. mrcal-2.4.1/doc/news-2.4.org000066400000000000000000000133021456301662300153540ustar00rootroot00000000000000#+TITLE: mrcal 2.4 release notes #+OPTIONS: toc:nil * New in mrcal 2.4 This is yet another mostly-maintenance release. A number of bugs are fixed, and a number of new features have been added. The biggest new features: - mrcal can be built with clang. Try it out like this: =CC=clang CXX=clang++ make=. This opens up some portability improvements, such as making it easier to run on Windows. - Full dense stereo pipeline in C. ** General fixes - All the tools use =/usr/bin/env= in the =#!= line. People who live life on hard mode now have it slightly easier - Tools to support more file formats: - [[file:mrcal-from-kalibr.html][=mrcal-from-kalibr=]] - [[file:mrcal-to-kalibr.html][=mrcal-to-kalibr=]] - [[file:mrcal-from-ros.html][=mrcal-from-ros=]] These are experimental. /Please/ let me know if these are or aren't useful - [[file:mrcal-stereo.html][=mrcal-stereo=]], [[file:mrcal-python-api-reference.html#-stereo_range][=mrcal.stereo_range()=]] work properly if =disparity_min>0= - The [[file:mrcal-stereo.html][=mrcal-stereo=]] GUI displays the pixel coordinates for /both/ cameras, not just the one under the cursor ** Build - mrcal builds with clang - The sources do not use =_GNU_SOURCE=: mrcal does not depend on glibc - The sources support the updated CHOLMOD APIs in the recent distros ** Python API - The Procrustes fit functions ([[file:mrcal-python-api-reference.html#-align_procrustes_vectors_R01][=mrcal.align_procrustes_vectors_R01()=]], [[file:mrcal-python-api-reference.html#-align_procrustes_vectors_Rt01][=mrcal.align_procrustes_vectors_Rt01()=]]) detect and report errors in the input data - [[file:mrcal-python-api-reference.html#-show_projection_diff][=mrcal.show_projection_diff()=]] has similar contour-generating options as what [[file:mrcal-python-api-reference.html#-show_projection_uncertainty][=mrcal.show_projection_uncertainty()=]] has - renamed =mrcal.residuals_chessboard()= to [[file:mrcal-python-api-reference.html#-residuals_board][=mrcal.residuals_board()=]]. Both names are available for backwards compatibility - =mrcal.show_residuals_...()= functions and =mrcal-show-residuals-...= tools now /all/ have =cbmax= and =--cbmax= options respectively to set the upper bound for the mapping in the heat map display - Added [[file:mrcal-python-api-reference.html#CHOLMOD_factorization-rcond][=mrcal.CHOLMOD_factorization.rcond()=]] as an interface to =cholmod_rcond()= - [[file:mrcal-python-api-reference.html#-worst_direction_stdev][=mrcal.worst_direction_stdev()=]] works with NxN arrays, not just 2x2 - [[file:mrcal-python-api-reference.html#-ref_calibration_object][=mrcal.ref_calibration_object()=]] has a new =optimization_inputs= argument. This provides a convenient shorthand to get the object used in a particular calibration - Added [[file:mrcal-python-api-reference.html#-R_aligned_to_vector][=mrcal.R_aligned_to_vector()=]] to produce a non-unique rotation to map a given vector to [0,0,1] - Added [[file:mrcal-python-api-reference.html#-sorted_eig][=mrcal.sorted_eig()=]] to compute an eigenvalue decomposition with /sorted/ eigenvalues - Added [[file:mrcal-python-api-reference.html#-write_point_cloud_as_ply][=mrcal.write_point_cloud_as_ply()=]] to write a point cloud as a =.ply= file - [[file:mrcal-python-api-reference.html#-apply_color_map][=mrcal.apply_color_map()=]] supports /all/ gnuplot rgbformulae, above the 7,5,15 default - [[file:mrcal-python-api-reference.html#-stereo_range][=mrcal.stereo_range()=]] has more optional arguments: - =disparity_max= to set the upper valid-disparity bound - =disparity_scaled_min=, =disparity_scaled_max= to act on the raw disparity data produced by the stereo matcher ** C API - Better error handling: lensmodel-parsing functions return an error code instead of asserting, if given invalid input. Affected functions: - =mrcal_lensmodel_name_unconfigured()= - =mrcal_lensmodel_name()= - =mrcal_lensmodel_type_from_name()= - =mrcal_lensmodel_from_name()= - More image types supported. We now have: - =mrcal_image_int8_t= - =mrcal_image_uint8_t= - =mrcal_image_int16_t= - =mrcal_image_uint16_t= - =mrcal_image_int32_t= - =mrcal_image_uint32_t= - =mrcal_image_int64_t= - =mrcal_image_uint64_t= - =mrcal_image_float_t= - =mrcal_image_double_t= - =mrcal_image_bgr_t= - Renamed the =bgr_t= type to =mrcal_bgr_t=. For namespacing. - =mrcal_rectification_maps()= supports =LENSMODEL_LATLON= /and/ =LENSMODEL_PINHOLE= rectification - The remaining pieces for a [[file:c-api.org::#dense-stereo-in-c][full dense-stereo pipeline in C]] were implemented. The new functions are - =mrcal_stereo_range_sparse()= to convert a set of disparity values to ranges - =mrcal_stereo_range_dense()= to convert a disparity /image/ to a range /image/ - =mrcal_apply_color_map()= to convert a disparity or range image to a heat map for human consumption A [[https://github.com/dkogan/mrcal/blob/master/doc/examples/dense-stereo-demo/dense-stereo-demo.cc][dense-stereo-in-C sample]] is provided. * Migration notes 2.3 -> 2.4 - C API/ABI breaking change: these functions now take an extra =int Nobservations_board= argument: - =mrcal_pack_solver_state_vector()= - =mrcal_unpack_solver_state_vector()= - C API breaking change: =bgr_t= structure renamed to =mrcal_bgr_t= - Python API: a function was renamed: =mrcal.residuals_chessboard()= -> [[file:mrcal-python-api-reference.html#-residuals_board][=mrcal.residuals_board()=]]. Both names are available for backwards compatibility, but moving to the new name is recommended. - Python [[file:mrcal-python-api-reference.html#-apply_color_map][=mrcal.apply_color_map()=]] function: =a_min=, =a_max= arguments now /must/ be passed in as kwargs, and not as positionals. mrcal-2.4.1/doc/noncentral.fig000066400000000000000000000040701456301662300162220ustar00rootroot00000000000000#FIG 3.2 Produced by xfig version 3.2.8b Portrait Center Metric Letter 100.00 Single -2 1200 2 0 32 #a0a0a0 6 -242 -2713 -85 -2568 5 1 0 2 2 7 40 -1 -1 0.000 1 0 0 0 -198.500 -2640.500 -121 -2698 -102 -2640 -121 -2583 2 2 0 2 2 7 40 -1 -1 12.000 0 0 -1 0 0 5 -189 -2583 -227 -2583 -227 -2698 -189 -2698 -189 -2583 2 1 0 2 2 7 40 -1 -1 0.000 0 1 7 0 0 4 -121 -2583 -189 -2611 -189 -2669 -121 -2698 -6 6 -180 -3555 2430 -3150 4 0 0 50 -1 16 12 0.0000 4 195 2580 -180 -3195 all intersect at the same point\001 4 0 0 50 -1 16 12 0.0000 4 195 2190 -180 -3375 Far-away rays effectively\001 -6 6 -195 -1365 1006 -255 5 1 0 2 2 7 40 -1 -1 0.000 1 0 0 0 90.000 -810.000 810 -1350 990 -810 810 -270 2 2 0 2 2 7 40 -1 -1 12.000 0 0 -1 0 0 5 180 -270 -180 -270 -180 -1350 180 -1350 180 -270 2 1 0 2 2 7 40 -1 -1 0.000 0 1 7 0 0 4 810 -271 180 -540 180 -1080 810 -1350 -6 6 -45 -1170 810 -810 6 300 -1005 480 -900 4 2 1 45 -1 32 10 0.0000 4 105 105 405 -900 D\001 4 0 1 45 -1 16 10 0.0000 4 90 75 405 -900 z\001 -6 2 1 0 2 1 7 45 -1 -1 8.000 0 0 -1 0 0 2 765 -1125 765 -855 2 1 0 2 1 7 45 -1 -1 0.000 0 0 -1 1 1 2 1 1 1.00 60.00 120.00 1 1 1.00 60.00 120.00 0 -1035 765 -1035 2 1 0 2 1 7 45 -1 -1 8.000 0 0 -1 0 0 2 0 -1125 0 -855 -6 6 -180 -1845 2430 -1440 4 0 0 50 -1 16 12 0.0000 4 195 2580 -180 -1485 all intersect at the same point\001 4 0 0 50 -1 16 12 0.0000 4 195 1935 -180 -1665 Close-up rays do NOT\001 -6 2 1 0 1 0 7 50 -1 -1 12.000 0 0 -1 0 0 2 -213 -2641 4590 -2250 2 1 0 1 0 7 50 -1 -1 12.000 0 0 -1 0 0 2 -213 -2641 4590 -3060 2 1 0 1 0 7 50 -1 -1 12.000 0 0 -1 0 0 2 -213 -2641 4500 -3420 2 1 0 1 0 7 50 -1 -1 0.000 0 0 -1 0 0 2 -213 -2641 4635 -2641 2 1 0 1 0 7 50 -1 -1 12.000 0 0 -1 0 0 2 -213 -2641 4500 -1890 2 1 0 3 0 7 50 -1 -1 12.000 0 0 -1 0 0 2 0 -810 2160 -810 2 1 0 1 0 7 60 -1 -1 0.000 0 0 -1 0 0 2 630 -810 2160 360 2 1 0 1 0 7 60 -1 -1 0.000 0 0 -1 0 0 2 2160 45 450 -810 2 1 0 1 0 7 60 -1 -1 0.000 0 0 -1 0 0 2 2160 -225 225 -810 2 1 0 1 0 7 60 -1 -1 0.000 0 0 -1 0 0 2 2160 -540 90 -810 2 1 0 1 0 7 60 -1 -1 0.000 0 0 -1 0 0 2 2115 720 765 -810 mrcal-2.4.1/doc/observation-usefulness.fig000066400000000000000000000047261456301662300206140ustar00rootroot00000000000000#FIG 3.2 Produced by xfig version 3.2.8b Portrait Center Metric Letter 100.00 Single -2 1200 2 0 32 #a0a0a0 6 2025 1621 2520 2250 2 3 0 1 0 7 50 -1 -1 0.000 0 0 -1 0 0 5 2205 1779 2520 1621 2520 2250 2205 2092 2205 1779 2 3 0 1 0 7 50 -1 -1 0.000 0 0 -1 0 0 5 2205 1621 2205 2250 2025 2250 2025 1621 2205 1621 -6 6 7785 855 7875 3105 2 3 0 1 0 0 50 -1 20 0.000 0 0 -1 0 0 5 7785 855 7785 1305 7875 1305 7875 855 7785 855 2 3 0 1 32 32 50 -1 20 0.000 0 0 7 0 0 5 7785 1305 7785 1755 7875 1755 7875 1305 7785 1305 2 3 0 1 0 0 50 -1 20 0.000 0 0 -1 0 0 5 7785 1755 7785 2205 7875 2205 7875 1755 7785 1755 2 3 0 1 32 32 50 -1 20 0.000 0 0 7 0 0 5 7785 2205 7785 2655 7875 2655 7875 2205 7785 2205 2 3 0 1 0 0 50 -1 20 0.000 0 0 -1 0 0 5 7785 2655 7785 3105 7875 3105 7875 2655 7785 2655 -6 6 3510 1620 5220 3285 2 3 0 1 0 0 50 -1 20 0.000 0 0 -1 0 0 5 5130 1620 4812 1938 4875 2002 5194 1684 5130 1620 2 3 0 1 32 32 50 -1 20 0.000 0 0 7 0 0 5 4812 1938 4494 2256 4557 2320 4875 2002 4812 1938 2 3 0 1 0 0 50 -1 20 0.000 0 0 -1 0 0 5 4494 2256 4175 2575 4239 2638 4557 2320 4494 2256 2 3 0 1 32 32 50 -1 20 0.000 0 0 7 0 0 5 4175 2575 3857 2893 3921 2956 4239 2638 4175 2575 2 3 0 1 0 0 50 -1 20 0.000 0 0 -1 0 0 5 3857 2893 3539 3211 3603 3275 3921 2956 3857 2893 -6 6 3960 270 4770 2520 6 3960 270 4050 2520 2 3 0 1 0 0 50 -1 20 0.000 0 0 -1 0 0 5 3960 270 3960 720 4050 720 4050 270 3960 270 2 3 0 1 32 32 50 -1 20 0.000 0 0 7 0 0 5 3960 720 3960 1170 4050 1170 4050 720 3960 720 2 3 0 1 0 0 50 -1 20 0.000 0 0 -1 0 0 5 3960 1170 3960 1620 4050 1620 4050 1170 3960 1170 2 3 0 1 32 32 50 -1 20 0.000 0 0 7 0 0 5 3960 1620 3960 2070 4050 2070 4050 1620 3960 1620 2 3 0 1 0 0 50 -1 20 0.000 0 0 -1 0 0 5 3960 2070 3960 2520 4050 2520 4050 2070 3960 2070 -6 4 0 0 50 -1 16 14 0.0000 5 180 600 4140 810 Good\001 -6 6 2672 1440 3656 2424 6 2672 1440 3656 2424 2 3 0 1 0 0 50 -1 20 0.000 0 0 -1 0 0 5 3618 1440 3429 1629 3466 1667 3656 1478 3618 1440 2 3 0 1 32 32 50 -1 20 0.000 0 0 7 0 0 5 3429 1629 3240 1818 3277 1856 3466 1667 3429 1629 2 3 0 1 0 0 50 -1 20 0.000 0 0 -1 0 0 5 3240 1818 3050 2008 3088 2045 3277 1856 3240 1818 2 3 0 1 32 32 50 -1 20 0.000 0 0 7 0 0 5 3050 2008 2861 2197 2899 2234 3088 2045 3050 2008 2 3 0 1 0 0 50 -1 20 0.000 0 0 -1 0 0 5 2861 2197 2672 2386 2710 2424 2899 2234 2861 2197 -6 4 0 12 50 -1 16 14 0.0000 5 180 480 2970 2385 Best\001 -6 4 0 4 50 -1 16 14 0.0000 5 180 435 7920 2025 Bad\001 4 0 12 50 -1 16 14 0.0000 5 180 480 4365 2745 Best\001 mrcal-2.4.1/doc/org.css000066400000000000000000000045351456301662300146770ustar00rootroot00000000000000.title { text-align: center; margin-bottom: .2em; } .subtitle { text-align: center; font-size: medium; font-weight: bold; margin-top:0; } .todo { font-family: monospace; color: red; } .done { font-family: monospace; color: green; } .priority { font-family: monospace; color: orange; } .tag { background-color: #eee; font-family: monospace; padding: 2px; font-size: 80%; font-weight: normal; } .timestamp { color: #bebebe; } .timestamp-kwd { color: #5f9ea0; } .org-right { margin-left: auto; margin-right: 0px; text-align: right; } .org-left { margin-left: 0px; margin-right: auto; text-align: left; } .org-center { margin-left: auto; margin-right: auto; text-align: center; } .underline { text-decoration: underline; } #postamble p, #preamble p { font-size: 90%; margin: .2em; } p.verse { margin-left: 3%; } pre { border: 1px solid #ccc; box-shadow: 3px 3px 3px #eee; padding: 8pt; font-family: monospace; overflow: auto; margin: 1.2em; } pre.src { position: relative; overflow: visible; padding-top: 1.2em; } table { border-collapse:collapse; } caption.t-above { caption-side: top; } caption.t-bottom { caption-side: bottom; } td, th { vertical-align:top; } th.org-right { text-align: center; } th.org-left { text-align: center; } th.org-center { text-align: center; } td.org-right { text-align: right; } td.org-left { text-align: left; } td.org-center { text-align: center; } dt { font-weight: bold; } .footpara { display: inline; } .footdef { margin-bottom: 1em; } .figure { padding: 1em; } .figure p { text-align: center; } .equation-container { display: table; text-align: center; width: 100%; } .equation { vertical-align: middle; } .equation-label { display: table-cell; text-align: right; vertical-align: middle; } .inlinetask { padding: 10px; border: 2px solid gray; margin: 10px; background: #ffffcc; } #org-div-home-and-up { text-align: right; font-size: 70%; white-space: nowrap; } textarea { overflow-x: auto; } .linenr { font-size: smaller } .code-highlighted { background-color: #ffff00; } .org-info-js_info-navigation { border-style: none; } #org-info-js_console-label { font-size: 10px; font-weight: bold; white-space: nowrap; } .org-info-js_search-highlight { background-color: #ffff00; color: #000000; font-weight: bold; } .org-svg { width: 90%; } mrcal-2.4.1/doc/projection-scale-invariance.fig000066400000000000000000000015151456301662300214360ustar00rootroot00000000000000#FIG 3.2 Produced by xfig version 3.2.7b Portrait Center Metric Letter 100.00 Single -2 1200 2 0 32 #a0a0a0 6 259 1456 745 2006 2 3 0 1 0 7 50 -1 -1 0.000 0 0 7 0 0 5 436 1456 436 2006 259 2006 259 1456 436 1456 2 3 0 1 0 7 50 -1 -1 0.000 0 0 7 0 0 5 436 1594 745 1456 745 2006 436 1869 436 1594 -6 6 2250 1575 5175 2250 4 0 0 40 -1 16 14 0.0000 5 225 2685 2250 1800 But the uncertainty of that\001 4 0 0 40 -1 16 14 0.0000 5 225 2925 2250 2025 projection varies with range\001 -6 1 3 0 1 0 0 40 -1 20 0.000 1 0.0000 1952 1503 39 39 1952 1503 1972 1537 1 3 0 1 0 0 40 -1 20 0.000 1 0.0000 6236 874 39 39 6236 874 6256 908 1 3 0 1 0 0 40 -1 20 0.000 1 0.0000 4091 1187 39 39 4091 1187 4111 1221 2 1 0 3 0 7 50 -1 -1 8.000 0 0 7 0 0 2 327 1742 6241 873 4 2 0 50 -1 16 14 0.0000 4 225 3900 5175 900 Each point projects to the same pixel\001 mrcal-2.4.1/doc/pydoc.py000077500000000000000000003300251456301662300150650ustar00rootroot00000000000000#! /usr/bin/python3.8 """COPY OF pydoc.py FROM THE PYTHON UPSTREAM This is /usr/lib/python3.8/pydoc.py from the libpython3.8-stdlib package version 3.8.4-1 on Debian License: PYTHON SOFTWARE FOUNDATION LICENSE VERSION 2 -------------------------------------------- 1. This LICENSE AGREEMENT is between the Python Software Foundation ("PSF"), and the Individual or Organization ("Licensee") accessing and otherwise using this software ("Python") in source or binary form and its associated documentation. 2. Subject to the terms and conditions of this License Agreement, PSF hereby grants Licensee a nonexclusive, royalty-free, world-wide license to reproduce, analyze, test, perform and/or display publicly, prepare derivative works, distribute, and otherwise use Python alone or in any derivative version, provided, however, that PSF's License Agreement and PSF's notice of copyright, i.e., "Copyright (c) 2001, 2002, 2003, 2004, 2005, 2006, 2007, 2008, 2009, 2010, 2011, 2012, 2013, 2014 Python Software Foundation; All Rights Reserved" are retained in Python alone or in any derivative version prepared by Licensee. 3. In the event Licensee prepares a derivative work that is based on or incorporates Python or any part thereof, and wants to make the derivative work available to others as provided herein, then Licensee hereby agrees to include in any such work a brief summary of the changes made to Python. 4. PSF is making Python available to Licensee on an "AS IS" basis. PSF MAKES NO REPRESENTATIONS OR WARRANTIES, EXPRESS OR IMPLIED. BY WAY OF EXAMPLE, BUT NOT LIMITATION, PSF MAKES NO AND DISCLAIMS ANY REPRESENTATION OR WARRANTY OF MERCHANTABILITY OR FITNESS FOR ANY PARTICULAR PURPOSE OR THAT THE USE OF PYTHON WILL NOT INFRINGE ANY THIRD PARTY RIGHTS. 5. PSF SHALL NOT BE LIABLE TO LICENSEE OR ANY OTHER USERS OF PYTHON FOR ANY INCIDENTAL, SPECIAL, OR CONSEQUENTIAL DAMAGES OR LOSS AS A RESULT OF MODIFYING, DISTRIBUTING, OR OTHERWISE USING PYTHON, OR ANY DERIVATIVE THEREOF, EVEN IF ADVISED OF THE POSSIBILITY THEREOF. 6. This License Agreement will automatically terminate upon a material breach of its terms and conditions. 7. Nothing in this License Agreement shall be deemed to create any relationship of agency, partnership, or joint venture between PSF and Licensee. This License Agreement does not grant permission to use PSF trademarks or trade name in a trademark sense to endorse or promote products or services of Licensee, or any third party. 8. By copying, installing or otherwise using Python, Licensee agrees to be bound by the terms and conditions of this License Agreement. I needed to make minor changes to this tool to produce reference HTML documentation for mrcal. The modifications are in the mrcal version control. Broadly: - removed the "index" links at the top-right - remoded the "modules" section. This was mostly telling the reader about all the modules that the module being documented imports, which is irrelevant - I don't list any "package contents". Those just list the submodules, which I don't want to do - set all the submodule links (mrcal.submodule.function) to work as if it was mrcal.function. That's how the api looks to the user - pydoc output to stdout: for easier integration into the Makefile - I don't document builtins - Added links to external projects I use (gp,nps,np,cv2) - Using my css style and my preamble - I don't swallow failures due to a broken import Generate Python documentation in HTML or text for interactive use. At the Python interactive prompt, calling help(thing) on a Python object documents the object, and calling help() starts up an interactive help session. Or, at the shell command line outside of Python: Run "pydoc " to show documentation on something. may be the name of a function, module, package, or a dotted reference to a class or function within a module or module in a package. If the argument contains a path segment delimiter (e.g. slash on Unix, backslash on Windows) it is treated as the path to a Python source file. Run "pydoc -k " to search for a keyword in the synopsis lines of all available modules. Run "pydoc -n " to start an HTTP server with the given hostname (default: localhost) on the local machine. Run "pydoc -p " to start an HTTP server on the given port on the local machine. Port number 0 can be used to get an arbitrary unused port. Run "pydoc -b" to start an HTTP server on an arbitrary unused port and open a Web browser to interactively browse documentation. Combine with the -n and -p options to control the hostname and port used. Run "pydoc -w " to write out the HTML documentation for a module to a file named ".html". Module docs for core modules are assumed to be in /usr/share/doc/pythonX.Y/html/library if the pythonX.Y-doc package is installed or in https://docs.python.org/X.Y/library/ This can be overridden by setting the PYTHONDOCS environment variable to a different URL or to a local directory containing the Library Reference Manual pages. """ __all__ = ['help'] __author__ = "Ka-Ping Yee " __date__ = "26 February 2001" __credits__ = """Guido van Rossum, for an excellent programming language. Tommy Burnette, the original creator of manpy. Paul Prescod, for all his work on onlinehelp. Richard Chamberlain, for the first implementation of textdoc. """ # Known bugs that can't be fixed here: # - synopsis() cannot be prevented from clobbering existing # loaded modules. # - If the __file__ attribute on a module is a relative path and # the current directory is changed with os.chdir(), an incorrect # path will be displayed. import builtins import importlib._bootstrap import importlib._bootstrap_external import importlib.machinery import importlib.util import inspect import io import os import pkgutil import platform import re import sys import sysconfig import time import tokenize import urllib.parse import warnings from collections import deque from reprlib import Repr from traceback import format_exception_only extranames = \ dict( gp = "https://www.github.com/dkogan/gnuplotlib", gnuplotlib = "https://www.github.com/dkogan/gnuplotlib", nps = "https://www.github.com/dkogan/numpysane", numpysane = "https://www.github.com/dkogan/numpysane", vnlog = "https://www.github.com/dkogan/vnlog", np = "https://numpy.org/doc/stable/reference/index.html", numpy = "https://numpy.org/doc/stable/reference/index.html", scipy = "https://docs.scipy.org/doc/scipy/reference/index.html", cv2 = "https://docs.opencv.org/master/") # --------------------------------------------------------- common routines def pathdirs(): """Convert sys.path into a list of absolute, existing, unique paths.""" dirs = [] normdirs = [] for dir in sys.path: dir = os.path.abspath(dir or '.') normdir = os.path.normcase(dir) if normdir not in normdirs and os.path.isdir(dir): dirs.append(dir) normdirs.append(normdir) return dirs def getdoc(object): """Get the doc string or comments for an object.""" result = inspect.getdoc(object) or inspect.getcomments(object) return result and re.sub('^ *\n', '', result.rstrip()) or '' def splitdoc(doc): """Split a doc string into a synopsis line (if any) and the rest.""" lines = doc.strip().split('\n') if len(lines) == 1: return lines[0], '' elif len(lines) >= 2 and not lines[1].rstrip(): return lines[0], '\n'.join(lines[2:]) return '', '\n'.join(lines) def classname(object, modname): """Get a class name and qualify it with a module name if necessary.""" name = object.__name__ if object.__module__ != modname: name = object.__module__ + '.' + name return name def isdata(object): """Check if an object is of a type that probably means it's data.""" return not (inspect.ismodule(object) or inspect.isclass(object) or inspect.isroutine(object) or inspect.isframe(object) or inspect.istraceback(object) or inspect.iscode(object)) def replace(text, *pairs): """Do a series of global replacements on a string.""" while pairs: text = pairs[1].join(text.split(pairs[0])) pairs = pairs[2:] return text def cram(text, maxlen): """Omit part of a string if needed to make it fit in a maximum length.""" if len(text) > maxlen: pre = max(0, (maxlen-3)//2) post = max(0, maxlen-3-pre) return text[:pre] + '...' + text[len(text)-post:] return text _re_stripid = re.compile(r' at 0x[0-9a-f]{6,16}(>+)$', re.IGNORECASE) def stripid(text): """Remove the hexadecimal id from a Python object representation.""" # The behaviour of %p is implementation-dependent in terms of case. return _re_stripid.sub(r'\1', text) def _is_bound_method(fn): """ Returns True if fn is a bound method, regardless of whether fn was implemented in Python or in C. """ if inspect.ismethod(fn): return True if inspect.isbuiltin(fn): self = getattr(fn, '__self__', None) return not (inspect.ismodule(self) or (self is None)) return False def allmethods(cl): methods = {} for key, value in inspect.getmembers(cl, inspect.isroutine): methods[key] = 1 for base in cl.__bases__: methods.update(allmethods(base)) # all your base are belong to us for key in methods.keys(): methods[key] = getattr(cl, key) return methods def _split_list(s, predicate): """Split sequence s via predicate, and return pair ([true], [false]). The return value is a 2-tuple of lists, ([x for x in s if predicate(x)], [x for x in s if not predicate(x)]) """ yes = [] no = [] for x in s: if predicate(x): yes.append(x) else: no.append(x) return yes, no def visiblename(name, all=None, obj=None): """Decide whether to show documentation on a variable.""" # Certain special names are redundant or internal. # XXX Remove __initializing__? if name in {'__author__', '__builtins__', '__cached__', '__credits__', '__date__', '__doc__', '__file__', '__spec__', '__loader__', '__module__', '__name__', '__package__', '__path__', '__qualname__', '__slots__', '__version__'}: return 0 # Private names are hidden, but special names are displayed. if name.startswith('__') and name.endswith('__'): return 1 # Namedtuples have public fields and methods with a single leading underscore if name.startswith('_') and hasattr(obj, '_fields'): return True if all is not None: # only document that which the programmer exported in __all__ return name in all else: return not name.startswith('_') def classify_class_attrs(object): """Wrap inspect.classify_class_attrs, with fixup for data descriptors.""" results = [] for (name, kind, cls, value) in inspect.classify_class_attrs(object): if inspect.isdatadescriptor(value): kind = 'data descriptor' if isinstance(value, property) and value.fset is None: kind = 'readonly property' results.append((name, kind, cls, value)) return results def sort_attributes(attrs, object): 'Sort the attrs list in-place by _fields and then alphabetically by name' # This allows data descriptors to be ordered according # to a _fields attribute if present. fields = getattr(object, '_fields', []) try: field_order = {name : i-len(fields) for (i, name) in enumerate(fields)} except TypeError: field_order = {} keyfunc = lambda attr: (field_order.get(attr[0], 0), attr[0]) attrs.sort(key=keyfunc) # ----------------------------------------------------- module manipulation def ispackage(path): """Guess whether a path refers to a package directory.""" if os.path.isdir(path): for ext in ('.py', '.pyc'): if os.path.isfile(os.path.join(path, '__init__' + ext)): return True return False def source_synopsis(file): line = file.readline() while line[:1] == '#' or not line.strip(): line = file.readline() if not line: break line = line.strip() if line[:4] == 'r"""': line = line[1:] if line[:3] == '"""': line = line[3:] if line[-1:] == '\\': line = line[:-1] while not line.strip(): line = file.readline() if not line: break result = line.split('"""')[0].strip() else: result = None return result def synopsis(filename, cache={}): """Get the one-line summary out of a module file.""" mtime = os.stat(filename).st_mtime lastupdate, result = cache.get(filename, (None, None)) if lastupdate is None or lastupdate < mtime: # Look for binary suffixes first, falling back to source. if filename.endswith(tuple(importlib.machinery.BYTECODE_SUFFIXES)): loader_cls = importlib.machinery.SourcelessFileLoader elif filename.endswith(tuple(importlib.machinery.EXTENSION_SUFFIXES)): loader_cls = importlib.machinery.ExtensionFileLoader else: loader_cls = None # Now handle the choice. if loader_cls is None: # Must be a source file. try: file = tokenize.open(filename) except OSError: # module can't be opened, so skip it return None # text modules can be directly examined with file: result = source_synopsis(file) else: # Must be a binary module, which has to be imported. loader = loader_cls('__temp__', filename) # XXX We probably don't need to pass in the loader here. spec = importlib.util.spec_from_file_location('__temp__', filename, loader=loader) try: module = importlib._bootstrap._load(spec) except: return None del sys.modules['__temp__'] result = module.__doc__.splitlines()[0] if module.__doc__ else None # Cache the result. cache[filename] = (mtime, result) return result def importfile(path): """Import a Python source file or compiled file given its path.""" magic = importlib.util.MAGIC_NUMBER with open(path, 'rb') as file: is_bytecode = magic == file.read(len(magic)) filename = os.path.basename(path) name, ext = os.path.splitext(filename) if is_bytecode: loader = importlib._bootstrap_external.SourcelessFileLoader(name, path) else: loader = importlib._bootstrap_external.SourceFileLoader(name, path) # XXX We probably don't need to pass in the loader here. spec = importlib.util.spec_from_file_location(name, path, loader=loader) return importlib._bootstrap._load(spec) def safeimport(path, forceload=0, cache={}): """Import a module; handle errors; return None if the module isn't found. If the module *is* found but an exception occurs, it's wrapped in an ErrorDuringImport exception and reraised. Unlike __import__, if a package path is specified, the module at the end of the path is returned, not the package at the beginning. If the optional 'forceload' argument is 1, we reload the module from disk (unless it's a dynamic extension).""" try: # If forceload is 1 and the module has been previously loaded from # disk, we always have to reload the module. Checking the file's # mtime isn't good enough (e.g. the module could contain a class # that inherits from another module that has changed). if forceload and path in sys.modules: if path not in sys.builtin_module_names: # Remove the module from sys.modules and re-import to try # and avoid problems with partially loaded modules. # Also remove any submodules because they won't appear # in the newly loaded module's namespace if they're already # in sys.modules. subs = [m for m in sys.modules if m.startswith(path + '.')] for key in [path] + subs: # Prevent garbage collection. cache[key] = sys.modules[key] del sys.modules[key] module = __import__(path) except: # Did the error occur before or after the module was found? (exc, value, tb) = info = sys.exc_info() if path in sys.modules: # An error occurred while executing the imported module. raise ErrorDuringImport(sys.modules[path].__file__, info) elif exc is SyntaxError: # A SyntaxError occurred before we could execute the module. raise ErrorDuringImport(value.filename, info) elif issubclass(exc, ImportError) and value.name == path: # No such module in the path. return None else: # Some other error occurred during the importing process. raise ErrorDuringImport(path, sys.exc_info()) for part in path.split('.')[1:]: try: module = getattr(module, part) except AttributeError: return None return module # ---------------------------------------------------- formatter base class class Doc: PYTHONDOCS = os.environ.get("PYTHONDOCS", "https://docs.python.org/%d.%d/library" % sys.version_info[:2]) def document(self, object, name=None, *args): """Generate documentation for an object.""" args = (object, name) + args # 'try' clause is to attempt to handle the possibility that inspect # identifies something in a way that pydoc itself has issues handling; # think 'super' and how it is a descriptor (which raises the exception # by lacking a __name__ attribute) and an instance. try: if inspect.ismodule(object): return self.docmodule(*args) if inspect.isclass(object): return self.docclass(*args) if inspect.isroutine(object): return self.docroutine(*args) except AttributeError: pass if inspect.isdatadescriptor(object): return self.docdata(*args) return self.docother(*args) def fail(self, object, name=None, *args): """Raise an exception for unimplemented types.""" message = "don't know how to document object%s of type %s" % ( name and ' ' + repr(name), type(object).__name__) raise TypeError(message) docmodule = docclass = docroutine = docother = docproperty = docdata = fail def getdocloc(self, object, basedir=sysconfig.get_path('stdlib')): """Return the location of module docs or None""" try: file = inspect.getabsfile(object) except TypeError: file = '(built-in)' docloc = os.environ.get("PYTHONDOCS", self.PYTHONDOCS) basedir = os.path.normcase(basedir) if (isinstance(object, type(os)) and (object.__name__ in ('errno', 'exceptions', 'gc', 'imp', 'marshal', 'posix', 'signal', 'sys', '_thread', 'zipimport') or (file.startswith(basedir) and not file.startswith(os.path.join(basedir, 'dist-packages')) and not file.startswith(os.path.join(basedir, 'site-packages')))) and object.__name__ not in ('xml.etree', 'test.pydoc_mod')): if docloc.startswith(("http://", "https://")): docloc = "%s/%s" % (docloc.rstrip("/"), object.__name__.lower()) else: docloc = os.path.join(docloc, object.__name__.lower() + ".html") else: docloc = None return docloc # -------------------------------------------- HTML documentation generator class HTMLRepr(Repr): """Class for safely making an HTML representation of a Python object.""" def __init__(self): Repr.__init__(self) self.maxlist = self.maxtuple = 20 self.maxdict = 10 self.maxstring = self.maxother = 100 def escape(self, text): return replace(text, '&', '&', '<', '<', '>', '>') def repr(self, object): return Repr.repr(self, object) def repr1(self, x, level): if hasattr(type(x), '__name__'): methodname = 'repr_' + '_'.join(type(x).__name__.split()) if hasattr(self, methodname): return getattr(self, methodname)(x, level) return self.escape(cram(stripid(repr(x)), self.maxother)) def repr_string(self, x, level): test = cram(x, self.maxstring) testrepr = repr(test) if '\\' in test and '\\' not in replace(testrepr, r'\\', ''): # Backslashes are only literal in the string and are never # needed to make any special characters, so show a raw string. return 'r' + testrepr[0] + self.escape(test) + testrepr[0] return re.sub(r'((\\[\\abfnrtv\'"]|\\[0-9]..|\\x..|\\u....)+)', r'\1', self.escape(testrepr)) repr_str = repr_string def repr_instance(self, x, level): try: return self.escape(cram(stripid(repr(x)), self.maxstring)) except: return self.escape('<%s instance>' % x.__class__.__name__) repr_unicode = repr_string class HTMLDoc(Doc): """Formatter class for HTML documentation.""" # ------------------------------------------- HTML formatting utilities _repr_instance = HTMLRepr() repr = _repr_instance.repr escape = _repr_instance.escape def page(self, title, contents): """Format an HTML page.""" with open("doc/mrcal-preamble-GENERATED.html", "r") as f: preamble = f.read() return '''\ Python: %s %s %s ''' % (title, preamble, contents) def heading(self, title, fgcol, bgcol, extras=''): """Format a page heading.""" return '''
       
       
      %s
      %s
      ''' % (bgcol, fgcol, title, fgcol, extras or ' ') def section(self, title, fgcol, bgcol, contents, width=6, prelude='', marginalia=None, gap=' '): """Format a section with a heading.""" if marginalia is None: marginalia = '' + ' ' * width + '' result = '''

      ''' % (bgcol, fgcol, title) if prelude: result = result + ''' ''' % (bgcol, marginalia, prelude, gap) else: result = result + ''' ''' % (bgcol, marginalia, gap) return result + '\n
       
      %s
      %s %s
      %s
      %s%s%s
      ' % contents def bigsection(self, title, *args): """Format a section with a big heading.""" title = '%s' % title return self.section(title, *args) def preformat(self, text): """Format literal preformatted text.""" text = self.escape(text.expandtabs()) return replace(text, '\n\n', '\n \n', '\n\n', '\n \n', ' ', ' ', '\n', '
      \n') def multicolumn(self, list, format, cols=4): """Format a list of items into a multi-column list.""" result = '' rows = (len(list)+cols-1)//cols for col in range(cols): result = result + '' % (100//cols) for i in range(rows*col, rows*col+rows): if i < len(list): result = result + format(list[i]) + '
      \n' result = result + '' return '%s
      ' % result def grey(self, text): return '%s' % text def namelink(self, name, *dicts): """Make a link for an identifier, given name-to-URL mappings.""" for dict in dicts: if name in dict: if re.match('builtins\.', dict[name]): return name return '%s' % (dict[name], name) return name def classlink(self, object, modname): """Make a link for a class.""" name, module = object.__name__, sys.modules.get(object.__module__) if hasattr(module, name) and getattr(module, name) is object and not re.match('builtins\.',classname(object, modname)): def strip_submodule(m): s = "[a-zA-Z0-9_]+" return re.sub(rf"({s})\.{s}\.({s})", r"\1.\2", m) return '%s' % ( name, strip_submodule(classname(object, modname))) return classname(object, modname) def modulelink(self, object): """Make a link for a module.""" return '%s' % (object.__name__, object.__name__) def modpkglink(self, modpkginfo): """Make a link for a module or package to display in an index.""" name, path, ispackage, shadowed = modpkginfo if shadowed: return self.grey(name) if path: url = '%s.%s.html' % (path, name) else: url = '%s.html' % name if ispackage: text = '%s (package)' % name else: text = name return '%s' % (url, text) def filelink(self, url, path): """Make a link to source file.""" return '%s' % (url, path) def markup(self, text, escape=None, funcs={}, classes={}, methods={}): """Mark up some plain text, given a context of symbols to look for. Each context dictionary maps object names to anchor names.""" escape = escape or self.escape results = [] here = 0 pattern = re.compile(r'\b((http|ftp)://\S+[\w/]|' r'RFC[- ]?(\d+)|' r'PEP[- ]?(\d+)|' r'(self\.)?(\w+))') while True: match = pattern.search(text, here) if not match: break start, end = match.span() results.append(escape(text[here:start])) all, scheme, rfc, pep, selfdot, name = match.groups() if scheme: url = escape(all).replace('"', '"') results.append('%s' % (url, url)) elif rfc: url = 'http://www.rfc-editor.org/rfc/rfc%d.txt' % int(rfc) results.append('%s' % (url, escape(all))) elif pep: url = 'http://www.python.org/dev/peps/pep-%04d/' % int(pep) results.append('%s' % (url, escape(all))) elif selfdot: # Create a link for methods like 'self.method(...)' # and use for attributes like 'self.attr' if text[end:end+1] == '(': results.append('self.' + self.namelink(name, methods, extranames)) else: results.append('self.%s' % name) elif text[end:end+1] == '(': results.append(self.namelink(name, methods, funcs, classes, extranames)) else: results.append(self.namelink(name, classes, extranames)) here = end results.append(escape(text[here:])) return ''.join(results) # ---------------------------------------------- type-specific routines def formattree(self, tree, modname, parent=None): """Produce HTML for a class tree as given by inspect.getclasstree().""" result = '' for entry in tree: if type(entry) is type(()): c, bases = entry result = result + '

      ' result = result + self.classlink(c, modname) if bases and bases != (parent,): parents = [] for base in bases: parents.append(self.classlink(base, modname)) result = result + '(' + ', '.join(parents) + ')' result = result + '\n
      ' elif type(entry) is type([]): result = result + '
      \n%s
      \n' % self.formattree( entry, modname, c) return '
      \n%s
      \n' % result def docmodule(self, object, name=None, mod=None, *ignored): """Produce HTML documentation for a module object.""" name = object.__name__ # ignore the passed-in name try: all = object.__all__ except AttributeError: all = None parts = name.split('.') links = [] for i in range(len(parts)-1): links.append( '%s' % ('.'.join(parts[:i+1]), parts[i])) linkedname = '.'.join(links + parts[-1:]) head = '%s' % linkedname try: path = inspect.getabsfile(object) url = urllib.parse.quote(path) filelink = self.filelink(url, path) except TypeError: filelink = '(built-in)' info = [] if hasattr(object, '__version__'): version = str(object.__version__) if version[:11] == '$' + 'Revision: ' and version[-1:] == '$': version = version[11:-1].strip() info.append('version %s' % self.escape(version)) if hasattr(object, '__date__'): info.append(self.escape(str(object.__date__))) if info: head = head + ' (%s)' % ', '.join(info) docloc = self.getdocloc(object) if docloc is not None: docloc = '
      Module Reference' % locals() else: docloc = '' result = self.heading( head, '#ffffff', '#7799ee') modules = None classes, cdict = [], {} for key, value in inspect.getmembers(object, inspect.isclass): # if __all__ exists, believe it. Otherwise use old heuristic. if True: if visiblename(key, all, object): classes.append((key, value)) cdict[key] = cdict[value] = '#' + key for key, value in classes: for base in value.__bases__: if base == builtins.object: continue key, modname = base.__name__, base.__module__ module = sys.modules.get(modname) if modname != name and module and hasattr(module, key): if getattr(module, key) is base: if not key in cdict: cdict[key] = cdict[base] = modname + '.html#' + key funcs, fdict = [], {} for key, value in inspect.getmembers(object, inspect.isroutine): # if __all__ exists, believe it. Otherwise use old heuristic. if True: if visiblename(key, all, object): funcs.append((key, value)) fdict[key] = '#-' + key if inspect.isfunction(value): fdict[value] = fdict[key] data = [] for key, value in inspect.getmembers(object, isdata): if visiblename(key, all, object): data.append((key, value)) doc = self.markup(getdoc(object), self.preformat, fdict, cdict) doc = doc and '%s' % doc result = result + '

      %s

      \n' % doc if modules: contents = self.multicolumn( modules, lambda t: self.modulelink(t[1])) result = result + self.bigsection( 'Modules', '#ffffff', '#aa55cc', contents) if classes: classlist = [value for (key, value) in classes] contents = [ self.formattree(inspect.getclasstree(classlist, 1), name)] for key, value in classes: contents.append(self.document(value, key, name, fdict, cdict)) result = result + self.bigsection( 'Classes', '#ffffff', '#ee77aa', ' '.join(contents)) if funcs: contents = [] for key, value in funcs: contents.append(self.document(value, key, name, fdict, cdict)) result = result + self.bigsection( 'Functions', '#ffffff', '#eeaa77', ' '.join(contents)) if data: contents = [] for key, value in data: contents.append(self.document(value, key)) result = result + self.bigsection( 'Data', '#ffffff', '#55aa55', '
      \n'.join(contents)) if hasattr(object, '__author__'): contents = self.markup(str(object.__author__), self.preformat) result = result + self.bigsection( 'Author', '#ffffff', '#7799ee', contents) if hasattr(object, '__credits__'): contents = self.markup(str(object.__credits__), self.preformat) result = result + self.bigsection( 'Credits', '#ffffff', '#7799ee', contents) return result def docclass(self, object, name=None, mod=None, funcs={}, classes={}, *ignored): """Produce HTML documentation for a class object.""" realname = object.__name__ name = name or realname bases = object.__bases__ contents = [] push = contents.append # Cute little class to pump out a horizontal rule between sections. class HorizontalRule: def __init__(self): self.needone = 0 def maybe(self): if self.needone: push('
      \n') self.needone = 1 hr = HorizontalRule() # List the mro, if non-trivial. mro = deque(inspect.getmro(object)) if len(mro) > 2: hr.maybe() push('
      Method resolution order:
      \n') for base in mro: push('
      %s
      \n' % self.classlink(base, object.__module__)) push('
      \n') def spill(msg, attrs, predicate): ok, attrs = _split_list(attrs, predicate) if ok: hr.maybe() push(msg) for name, kind, homecls, value in ok: try: value = getattr(object, name) except Exception: # Some descriptors may meet a failure in their __get__. # (bug #1785) push(self.docdata(value, name, mod)) else: push(self.document(value, name, mod, funcs, classes, mdict, object)) push('\n') return attrs def spilldescriptors(msg, attrs, predicate): ok, attrs = _split_list(attrs, predicate) if ok: hr.maybe() push(msg) for name, kind, homecls, value in ok: push(self.docdata(value, name, mod)) return attrs def spilldata(msg, attrs, predicate): ok, attrs = _split_list(attrs, predicate) if ok: hr.maybe() push(msg) for name, kind, homecls, value in ok: base = self.docother(getattr(object, name), name, mod) if callable(value) or inspect.isdatadescriptor(value): doc = getattr(value, "__doc__", None) else: doc = None if doc is None: push('
      %s
      \n' % base) else: doc = self.markup(getdoc(value), self.preformat, funcs, classes, mdict) doc = '
      %s' % doc push('
      %s%s
      \n' % (base, doc)) push('\n') return attrs attrs = [(name, kind, cls, value) for name, kind, cls, value in classify_class_attrs(object) if visiblename(name, obj=object)] mdict = {} for key, kind, homecls, value in attrs: mdict[key] = anchor = '#' + name + '-' + key try: value = getattr(object, name) except Exception: # Some descriptors may meet a failure in their __get__. # (bug #1785) pass try: # The value may not be hashable (e.g., a data attr with # a dict or list value). mdict[value] = anchor except TypeError: pass while attrs: if mro: thisclass = mro.popleft() else: thisclass = attrs[0][2] attrs, inherited = _split_list(attrs, lambda t: t[2] is thisclass) if object is not builtins.object and thisclass is builtins.object: attrs = inherited continue elif thisclass is object: tag = 'defined here' else: tag = 'inherited from %s' % self.classlink(thisclass, object.__module__) tag += ':
      \n' sort_attributes(attrs, object) # Pump out the attrs, segregated by kind. attrs = spill('Methods %s' % tag, attrs, lambda t: t[1] == 'method') attrs = spill('Class methods %s' % tag, attrs, lambda t: t[1] == 'class method') attrs = spill('Static methods %s' % tag, attrs, lambda t: t[1] == 'static method') attrs = spilldescriptors("Readonly properties %s" % tag, attrs, lambda t: t[1] == 'readonly property') attrs = spilldescriptors('Data descriptors %s' % tag, attrs, lambda t: t[1] == 'data descriptor') attrs = spilldata('Data and other attributes %s' % tag, attrs, lambda t: t[1] == 'data') assert attrs == [] attrs = inherited contents = ''.join(contents) if name == realname: title = 'class %s' % ( name, realname) else: title = '%s = class %s' % ( name, name, realname) if bases: parents = [] for base in bases: parents.append(self.classlink(base, object.__module__)) title = title + '(%s)' % ', '.join(parents) decl = '' try: signature = inspect.signature(object) except (ValueError, TypeError): signature = None if signature: argspec = str(signature) if argspec and argspec != '()': decl = name + self.escape(argspec) + '\n\n' doc = getdoc(object) if decl: doc = decl + (doc or '') doc = self.markup(doc, self.preformat, funcs, classes, mdict) doc = doc and '%s
       
      ' % doc return self.section(title, '#000000', '#ffc8d8', contents, 3, doc) def formatvalue(self, object): """Format an argument default value as text.""" return self.grey('=' + self.repr(object)) def docroutine(self, object, name=None, mod=None, funcs={}, classes={}, methods={}, cl=None): """Produce HTML documentation for a function or method object.""" realname = object.__name__ name = name or realname anchor = (cl and cl.__name__ or '') + '-' + name note = '' skipdocs = 0 if _is_bound_method(object): imclass = object.__self__.__class__ if cl: if imclass is not cl: note = ' from ' + self.classlink(imclass, mod) else: if object.__self__ is not None: note = ' method of %s instance' % self.classlink( object.__self__.__class__, mod) else: note = ' unbound %s method' % self.classlink(imclass,mod) if (inspect.iscoroutinefunction(object) or inspect.isasyncgenfunction(object)): asyncqualifier = 'async ' else: asyncqualifier = '' if name == realname: title = '%s' % (anchor, realname) else: if cl and inspect.getattr_static(cl, realname, []) is object: reallink = '%s' % ( cl.__name__ + '-' + realname, realname) skipdocs = 1 else: reallink = realname title = '%s = %s' % ( anchor, name, reallink) argspec = None if inspect.isroutine(object): try: signature = inspect.signature(object) except (ValueError, TypeError): signature = None if signature: argspec = str(signature) if realname == '': title = '%s lambda ' % name # XXX lambda's won't usually have func_annotations['return'] # since the syntax doesn't support but it is possible. # So removing parentheses isn't truly safe. argspec = argspec[1:-1] # remove parentheses if not argspec: argspec = '(...)' decl = asyncqualifier + title + self.escape(argspec) + (note and self.grey('%s' % note)) if skipdocs: return '
      %s
      \n' % decl else: doc = self.markup( getdoc(object), self.preformat, funcs, classes, methods) doc = doc and '
      %s
      ' % doc return '
      %s
      %s
      \n' % (decl, doc) def docdata(self, object, name=None, mod=None, cl=None): """Produce html documentation for a data descriptor.""" results = [] push = results.append if name: push('
      %s
      \n' % name) doc = self.markup(getdoc(object), self.preformat) if doc: push('
      %s
      \n' % doc) push('
      \n') return ''.join(results) docproperty = docdata def docother(self, object, name=None, mod=None, *ignored): """Produce HTML documentation for a data object.""" lhs = name and '%s = ' % name or '' return lhs + self.repr(object) def index(self, dir, shadowed=None): """Generate an HTML index for a directory of modules.""" modpkgs = [] if shadowed is None: shadowed = {} for importer, name, ispkg in pkgutil.iter_modules([dir]): if any((0xD800 <= ord(ch) <= 0xDFFF) for ch in name): # ignore a module if its name contains a surrogate character continue modpkgs.append((name, '', ispkg, name in shadowed)) shadowed[name] = 1 modpkgs.sort() contents = self.multicolumn(modpkgs, self.modpkglink) return self.bigsection(dir, '#ffffff', '#ee77aa', contents) # -------------------------------------------- text documentation generator class TextRepr(Repr): """Class for safely making a text representation of a Python object.""" def __init__(self): Repr.__init__(self) self.maxlist = self.maxtuple = 20 self.maxdict = 10 self.maxstring = self.maxother = 100 def repr1(self, x, level): if hasattr(type(x), '__name__'): methodname = 'repr_' + '_'.join(type(x).__name__.split()) if hasattr(self, methodname): return getattr(self, methodname)(x, level) return cram(stripid(repr(x)), self.maxother) def repr_string(self, x, level): test = cram(x, self.maxstring) testrepr = repr(test) if '\\' in test and '\\' not in replace(testrepr, r'\\', ''): # Backslashes are only literal in the string and are never # needed to make any special characters, so show a raw string. return 'r' + testrepr[0] + test + testrepr[0] return testrepr repr_str = repr_string def repr_instance(self, x, level): try: return cram(stripid(repr(x)), self.maxstring) except: return '<%s instance>' % x.__class__.__name__ class TextDoc(Doc): """Formatter class for text documentation.""" # ------------------------------------------- text formatting utilities _repr_instance = TextRepr() repr = _repr_instance.repr def bold(self, text): """Format a string in bold by overstriking.""" return ''.join(ch + '\b' + ch for ch in text) def indent(self, text, prefix=' '): """Indent text by prepending a given prefix to each line.""" if not text: return '' lines = [prefix + line for line in text.split('\n')] if lines: lines[-1] = lines[-1].rstrip() return '\n'.join(lines) def section(self, title, contents): """Format a section with a given heading.""" clean_contents = self.indent(contents).rstrip() return self.bold(title) + '\n' + clean_contents + '\n\n' # ---------------------------------------------- type-specific routines def formattree(self, tree, modname, parent=None, prefix=''): """Render in text a class tree as returned by inspect.getclasstree().""" result = '' for entry in tree: if type(entry) is type(()): c, bases = entry result = result + prefix + classname(c, modname) if bases and bases != (parent,): parents = (classname(c, modname) for c in bases) result = result + '(%s)' % ', '.join(parents) result = result + '\n' elif type(entry) is type([]): result = result + self.formattree( entry, modname, c, prefix + ' ') return result def docmodule(self, object, name=None, mod=None): """Produce text documentation for a given module object.""" name = object.__name__ # ignore the passed-in name synop, desc = splitdoc(getdoc(object)) result = self.section('NAME', name + (synop and ' - ' + synop)) all = getattr(object, '__all__', None) docloc = self.getdocloc(object) if docloc is not None: result = result + self.section('MODULE REFERENCE', docloc + """ The following documentation is automatically generated from the Python source files. It may be incomplete, incorrect or include features that are considered implementation detail and may vary between Python implementations. When in doubt, consult the module reference at the location listed above. """) if desc: result = result + self.section('DESCRIPTION', desc) classes = [] for key, value in inspect.getmembers(object, inspect.isclass): # if __all__ exists, believe it. Otherwise use old heuristic. if True: if visiblename(key, all, object): classes.append((key, value)) funcs = [] for key, value in inspect.getmembers(object, inspect.isroutine): # if __all__ exists, believe it. Otherwise use old heuristic. if True: if visiblename(key, all, object): funcs.append((key, value)) data = [] for key, value in inspect.getmembers(object, isdata): if visiblename(key, all, object): data.append((key, value)) modpkgs = [] modpkgs_names = set() if hasattr(object, '__path__'): for importer, modname, ispkg in pkgutil.iter_modules(object.__path__): modpkgs_names.add(modname) if ispkg: modpkgs.append(modname + ' (package)') else: modpkgs.append(modname) modpkgs.sort() result = result + self.section( 'PACKAGE CONTENTS', '\n'.join(modpkgs)) # Detect submodules as sometimes created by C extensions submodules = [] for key, value in inspect.getmembers(object, inspect.ismodule): if value.__name__.startswith(name + '.') and key not in modpkgs_names: submodules.append(key) if submodules: submodules.sort() result = result + self.section( 'SUBMODULES', '\n'.join(submodules)) if classes: classlist = [value for key, value in classes] contents = [self.formattree( inspect.getclasstree(classlist, 1), name)] for key, value in classes: contents.append(self.document(value, key, name)) result = result + self.section('CLASSES', '\n'.join(contents)) if funcs: contents = [] for key, value in funcs: contents.append(self.document(value, key, name)) result = result + self.section('FUNCTIONS', '\n'.join(contents)) if data: contents = [] for key, value in data: contents.append(self.docother(value, key, name, maxlen=70)) result = result + self.section('DATA', '\n'.join(contents)) if hasattr(object, '__version__'): version = str(object.__version__) if version[:11] == '$' + 'Revision: ' and version[-1:] == '$': version = version[11:-1].strip() result = result + self.section('VERSION', version) if hasattr(object, '__date__'): result = result + self.section('DATE', str(object.__date__)) if hasattr(object, '__author__'): result = result + self.section('AUTHOR', str(object.__author__)) if hasattr(object, '__credits__'): result = result + self.section('CREDITS', str(object.__credits__)) try: file = inspect.getabsfile(object) except TypeError: file = '(built-in)' result = result + self.section('FILE', file) return result def docclass(self, object, name=None, mod=None, *ignored): """Produce text documentation for a given class object.""" realname = object.__name__ name = name or realname bases = object.__bases__ def makename(c, m=object.__module__): return classname(c, m) if name == realname: title = 'class ' + self.bold(realname) else: title = self.bold(name) + ' = class ' + realname if bases: parents = map(makename, bases) title = title + '(%s)' % ', '.join(parents) contents = [] push = contents.append try: signature = inspect.signature(object) except (ValueError, TypeError): signature = None if signature: argspec = str(signature) if argspec and argspec != '()': push(name + argspec + '\n') doc = getdoc(object) if doc: push(doc + '\n') # List the mro, if non-trivial. mro = deque(inspect.getmro(object)) if len(mro) > 2: push("Method resolution order:") for base in mro: push(' ' + makename(base)) push('') # List the built-in subclasses, if any: subclasses = sorted( (str(cls.__name__) for cls in type.__subclasses__(object) if not cls.__name__.startswith("_") and cls.__module__ == "builtins"), key=str.lower ) no_of_subclasses = len(subclasses) MAX_SUBCLASSES_TO_DISPLAY = 4 if subclasses: push("Built-in subclasses:") for subclassname in subclasses[:MAX_SUBCLASSES_TO_DISPLAY]: push(' ' + subclassname) if no_of_subclasses > MAX_SUBCLASSES_TO_DISPLAY: push(' ... and ' + str(no_of_subclasses - MAX_SUBCLASSES_TO_DISPLAY) + ' other subclasses') push('') # Cute little class to pump out a horizontal rule between sections. class HorizontalRule: def __init__(self): self.needone = 0 def maybe(self): if self.needone: push('-' * 70) self.needone = 1 hr = HorizontalRule() def spill(msg, attrs, predicate): ok, attrs = _split_list(attrs, predicate) if ok: hr.maybe() push(msg) for name, kind, homecls, value in ok: try: value = getattr(object, name) except Exception: # Some descriptors may meet a failure in their __get__. # (bug #1785) push(self.docdata(value, name, mod)) else: push(self.document(value, name, mod, object)) return attrs def spilldescriptors(msg, attrs, predicate): ok, attrs = _split_list(attrs, predicate) if ok: hr.maybe() push(msg) for name, kind, homecls, value in ok: push(self.docdata(value, name, mod)) return attrs def spilldata(msg, attrs, predicate): ok, attrs = _split_list(attrs, predicate) if ok: hr.maybe() push(msg) for name, kind, homecls, value in ok: if callable(value) or inspect.isdatadescriptor(value): doc = getdoc(value) else: doc = None try: obj = getattr(object, name) except AttributeError: obj = homecls.__dict__[name] push(self.docother(obj, name, mod, maxlen=70, doc=doc) + '\n') return attrs attrs = [(name, kind, cls, value) for name, kind, cls, value in classify_class_attrs(object) if visiblename(name, obj=object)] while attrs: if mro: thisclass = mro.popleft() else: thisclass = attrs[0][2] attrs, inherited = _split_list(attrs, lambda t: t[2] is thisclass) if object is not builtins.object and thisclass is builtins.object: attrs = inherited continue elif thisclass is object: tag = "defined here" else: tag = "inherited from %s" % classname(thisclass, object.__module__) sort_attributes(attrs, object) # Pump out the attrs, segregated by kind. attrs = spill("Methods %s:\n" % tag, attrs, lambda t: t[1] == 'method') attrs = spill("Class methods %s:\n" % tag, attrs, lambda t: t[1] == 'class method') attrs = spill("Static methods %s:\n" % tag, attrs, lambda t: t[1] == 'static method') attrs = spilldescriptors("Readonly properties %s:\n" % tag, attrs, lambda t: t[1] == 'readonly property') attrs = spilldescriptors("Data descriptors %s:\n" % tag, attrs, lambda t: t[1] == 'data descriptor') attrs = spilldata("Data and other attributes %s:\n" % tag, attrs, lambda t: t[1] == 'data') assert attrs == [] attrs = inherited contents = '\n'.join(contents) if not contents: return title + '\n' return title + '\n' + self.indent(contents.rstrip(), ' | ') + '\n' def formatvalue(self, object): """Format an argument default value as text.""" return '=' + self.repr(object) def docroutine(self, object, name=None, mod=None, cl=None): """Produce text documentation for a function or method object.""" realname = object.__name__ name = name or realname note = '' skipdocs = 0 if _is_bound_method(object): imclass = object.__self__.__class__ if cl: if imclass is not cl: note = ' from ' + classname(imclass, mod) else: if object.__self__ is not None: note = ' method of %s instance' % classname( object.__self__.__class__, mod) else: note = ' unbound %s method' % classname(imclass,mod) if (inspect.iscoroutinefunction(object) or inspect.isasyncgenfunction(object)): asyncqualifier = 'async ' else: asyncqualifier = '' if name == realname: title = self.bold(realname) else: if cl and inspect.getattr_static(cl, realname, []) is object: skipdocs = 1 title = self.bold(name) + ' = ' + realname argspec = None if inspect.isroutine(object): try: signature = inspect.signature(object) except (ValueError, TypeError): signature = None if signature: argspec = str(signature) if realname == '': title = self.bold(name) + ' lambda ' # XXX lambda's won't usually have func_annotations['return'] # since the syntax doesn't support but it is possible. # So removing parentheses isn't truly safe. argspec = argspec[1:-1] # remove parentheses if not argspec: argspec = '(...)' decl = asyncqualifier + title + argspec + note if skipdocs: return decl + '\n' else: doc = getdoc(object) or '' return decl + '\n' + (doc and self.indent(doc).rstrip() + '\n') def docdata(self, object, name=None, mod=None, cl=None): """Produce text documentation for a data descriptor.""" results = [] push = results.append if name: push(self.bold(name)) push('\n') doc = getdoc(object) or '' if doc: push(self.indent(doc)) push('\n') return ''.join(results) docproperty = docdata def docother(self, object, name=None, mod=None, parent=None, maxlen=None, doc=None): """Produce text documentation for a data object.""" repr = self.repr(object) if maxlen: line = (name and name + ' = ' or '') + repr chop = maxlen - len(line) if chop < 0: repr = repr[:chop] + '...' line = (name and self.bold(name) + ' = ' or '') + repr if doc is not None: line += '\n' + self.indent(str(doc)) return line class _PlainTextDoc(TextDoc): """Subclass of TextDoc which overrides string styling""" def bold(self, text): return text # --------------------------------------------------------- user interfaces def pager(text): """The first time this is called, determine what kind of pager to use.""" global pager pager = getpager() pager(text) def getpager(): """Decide what method to use for paging through text.""" if not hasattr(sys.stdin, "isatty"): return plainpager if not hasattr(sys.stdout, "isatty"): return plainpager if not sys.stdin.isatty() or not sys.stdout.isatty(): return plainpager use_pager = os.environ.get('MANPAGER') or os.environ.get('PAGER') if use_pager: if sys.platform == 'win32': # pipes completely broken in Windows return lambda text: tempfilepager(plain(text), use_pager) elif os.environ.get('TERM') in ('dumb', 'emacs'): return lambda text: pipepager(plain(text), use_pager) else: return lambda text: pipepager(text, use_pager) if os.environ.get('TERM') in ('dumb', 'emacs'): return plainpager if sys.platform == 'win32': return lambda text: tempfilepager(plain(text), 'more <') if hasattr(os, 'system') and os.system('(pager) 2>/dev/null') == 0: return lambda text: pipepager(text, 'pager') if hasattr(os, 'system') and os.system('(less) 2>/dev/null') == 0: return lambda text: pipepager(text, 'less') import tempfile (fd, filename) = tempfile.mkstemp() os.close(fd) try: if hasattr(os, 'system') and os.system('more "%s"' % filename) == 0: return lambda text: pipepager(text, 'more') else: return ttypager finally: os.unlink(filename) def plain(text): """Remove boldface formatting from text.""" return re.sub('.\b', '', text) def pipepager(text, cmd): """Page through text by feeding it to another program.""" import subprocess proc = subprocess.Popen(cmd, shell=True, stdin=subprocess.PIPE) try: with io.TextIOWrapper(proc.stdin, errors='backslashreplace') as pipe: try: pipe.write(text) except KeyboardInterrupt: # We've hereby abandoned whatever text hasn't been written, # but the pager is still in control of the terminal. pass except OSError: pass # Ignore broken pipes caused by quitting the pager program. while True: try: proc.wait() break except KeyboardInterrupt: # Ignore ctl-c like the pager itself does. Otherwise the pager is # left running and the terminal is in raw mode and unusable. pass def tempfilepager(text, cmd): """Page through text by invoking a program on a temporary file.""" import tempfile filename = tempfile.mktemp() with open(filename, 'w', errors='backslashreplace') as file: file.write(text) try: os.system(cmd + ' "' + filename + '"') finally: os.unlink(filename) def _escape_stdout(text): # Escape non-encodable characters to avoid encoding errors later encoding = getattr(sys.stdout, 'encoding', None) or 'utf-8' return text.encode(encoding, 'backslashreplace').decode(encoding) def ttypager(text): """Page through text on a text terminal.""" lines = plain(_escape_stdout(text)).split('\n') try: import tty fd = sys.stdin.fileno() old = tty.tcgetattr(fd) tty.setcbreak(fd) getchar = lambda: sys.stdin.read(1) except (ImportError, AttributeError, io.UnsupportedOperation): tty = None getchar = lambda: sys.stdin.readline()[:-1][:1] try: try: h = int(os.environ.get('LINES', 0)) except ValueError: h = 0 if h <= 1: h = 25 r = inc = h - 1 sys.stdout.write('\n'.join(lines[:inc]) + '\n') while lines[r:]: sys.stdout.write('-- more --') sys.stdout.flush() c = getchar() if c in ('q', 'Q'): sys.stdout.write('\r \r') break elif c in ('\r', '\n'): sys.stdout.write('\r \r' + lines[r] + '\n') r = r + 1 continue if c in ('b', 'B', '\x1b'): r = r - inc - inc if r < 0: r = 0 sys.stdout.write('\n' + '\n'.join(lines[r:r+inc]) + '\n') r = r + inc finally: if tty: tty.tcsetattr(fd, tty.TCSAFLUSH, old) def plainpager(text): """Simply print unformatted text. This is the ultimate fallback.""" sys.stdout.write(plain(_escape_stdout(text))) def describe(thing): """Produce a short description of the given thing.""" if inspect.ismodule(thing): if thing.__name__ in sys.builtin_module_names: return 'built-in module ' + thing.__name__ if hasattr(thing, '__path__'): return 'package ' + thing.__name__ else: return 'module ' + thing.__name__ if inspect.isbuiltin(thing): return 'built-in function ' + thing.__name__ if inspect.isgetsetdescriptor(thing): return 'getset descriptor %s.%s.%s' % ( thing.__objclass__.__module__, thing.__objclass__.__name__, thing.__name__) if inspect.ismemberdescriptor(thing): return 'member descriptor %s.%s.%s' % ( thing.__objclass__.__module__, thing.__objclass__.__name__, thing.__name__) if inspect.isclass(thing): return 'class ' + thing.__name__ if inspect.isfunction(thing): return 'function ' + thing.__name__ if inspect.ismethod(thing): return 'method ' + thing.__name__ return type(thing).__name__ def locate(path, forceload=0): """Locate an object by name or dotted path, importing as necessary.""" parts = [part for part in path.split('.') if part] module, n = None, 0 while n < len(parts): nextmodule = safeimport('.'.join(parts[:n+1]), forceload) if nextmodule: module, n = nextmodule, n + 1 else: break if module: object = module else: object = builtins for part in parts[n:]: try: object = getattr(object, part) except AttributeError: return None return object # --------------------------------------- interactive interpreter interface text = TextDoc() plaintext = _PlainTextDoc() html = HTMLDoc() def resolve(thing, forceload=0): """Given an object or a path to an object, get the object and its name.""" if isinstance(thing, str): object = locate(thing, forceload) if object is None: raise ImportError('''\ No Python documentation found for %r. Use help() to get the interactive help utility. Use help(str) for help on the str class.''' % thing) return object, thing else: name = getattr(thing, '__name__', None) return thing, name if isinstance(name, str) else None def render_doc(thing, title='Python Library Documentation: %s', forceload=0, renderer=None): """Render text documentation, given an object or a path to an object.""" if renderer is None: renderer = text object, name = resolve(thing, forceload) desc = describe(object) module = inspect.getmodule(object) if name and '.' in name: desc += ' in ' + name[:name.rfind('.')] elif module and module is not object: desc += ' in module ' + module.__name__ if not (inspect.ismodule(object) or inspect.isclass(object) or inspect.isroutine(object) or inspect.isdatadescriptor(object)): # If the passed object is a piece of data or an instance, # document its available methods instead of its value. object = type(object) desc += ' object' return title % desc + '\n\n' + renderer.document(object, name) def doc(thing, title='Python Library Documentation: %s', forceload=0, output=None): """Display text documentation, given an object or a path to an object.""" if output is None: pager(render_doc(thing, title, forceload)) else: output.write(render_doc(thing, title, forceload, plaintext)) def writedoc(thing, forceload=0): """Write HTML documentation to a file in the current directory.""" object, name = resolve(thing, forceload) page = html.page(describe(object), html.document(object, name)) sys.stdout.write(page) def writedocs(dir, pkgpath='', done=None): """Write out HTML documentation for all modules in a directory tree.""" if done is None: done = {} for importer, modname, ispkg in pkgutil.walk_packages([dir], pkgpath): writedoc(modname) return class Helper: # These dictionaries map a topic name to either an alias, or a tuple # (label, seealso-items). The "label" is the label of the corresponding # section in the .rst file under Doc/ and an index into the dictionary # in pydoc_data/topics.py. # # CAUTION: if you change one of these dictionaries, be sure to adapt the # list of needed labels in Doc/tools/extensions/pyspecific.py and # regenerate the pydoc_data/topics.py file by running # make pydoc-topics # in Doc/ and copying the output file into the Lib/ directory. keywords = { 'False': '', 'None': '', 'True': '', 'and': 'BOOLEAN', 'as': 'with', 'assert': ('assert', ''), 'async': ('async', ''), 'await': ('await', ''), 'break': ('break', 'while for'), 'class': ('class', 'CLASSES SPECIALMETHODS'), 'continue': ('continue', 'while for'), 'def': ('function', ''), 'del': ('del', 'BASICMETHODS'), 'elif': 'if', 'else': ('else', 'while for'), 'except': 'try', 'finally': 'try', 'for': ('for', 'break continue while'), 'from': 'import', 'global': ('global', 'nonlocal NAMESPACES'), 'if': ('if', 'TRUTHVALUE'), 'import': ('import', 'MODULES'), 'in': ('in', 'SEQUENCEMETHODS'), 'is': 'COMPARISON', 'lambda': ('lambda', 'FUNCTIONS'), 'nonlocal': ('nonlocal', 'global NAMESPACES'), 'not': 'BOOLEAN', 'or': 'BOOLEAN', 'pass': ('pass', ''), 'raise': ('raise', 'EXCEPTIONS'), 'return': ('return', 'FUNCTIONS'), 'try': ('try', 'EXCEPTIONS'), 'while': ('while', 'break continue if TRUTHVALUE'), 'with': ('with', 'CONTEXTMANAGERS EXCEPTIONS yield'), 'yield': ('yield', ''), } # Either add symbols to this dictionary or to the symbols dictionary # directly: Whichever is easier. They are merged later. _strprefixes = [p + q for p in ('b', 'f', 'r', 'u') for q in ("'", '"')] _symbols_inverse = { 'STRINGS' : ("'", "'''", '"', '"""', *_strprefixes), 'OPERATORS' : ('+', '-', '*', '**', '/', '//', '%', '<<', '>>', '&', '|', '^', '~', '<', '>', '<=', '>=', '==', '!=', '<>'), 'COMPARISON' : ('<', '>', '<=', '>=', '==', '!=', '<>'), 'UNARY' : ('-', '~'), 'AUGMENTEDASSIGNMENT' : ('+=', '-=', '*=', '/=', '%=', '&=', '|=', '^=', '<<=', '>>=', '**=', '//='), 'BITWISE' : ('<<', '>>', '&', '|', '^', '~'), 'COMPLEX' : ('j', 'J') } symbols = { '%': 'OPERATORS FORMATTING', '**': 'POWER', ',': 'TUPLES LISTS FUNCTIONS', '.': 'ATTRIBUTES FLOAT MODULES OBJECTS', '...': 'ELLIPSIS', ':': 'SLICINGS DICTIONARYLITERALS', '@': 'def class', '\\': 'STRINGS', '_': 'PRIVATENAMES', '__': 'PRIVATENAMES SPECIALMETHODS', '`': 'BACKQUOTES', '(': 'TUPLES FUNCTIONS CALLS', ')': 'TUPLES FUNCTIONS CALLS', '[': 'LISTS SUBSCRIPTS SLICINGS', ']': 'LISTS SUBSCRIPTS SLICINGS' } for topic, symbols_ in _symbols_inverse.items(): for symbol in symbols_: topics = symbols.get(symbol, topic) if topic not in topics: topics = topics + ' ' + topic symbols[symbol] = topics topics = { 'TYPES': ('types', 'STRINGS UNICODE NUMBERS SEQUENCES MAPPINGS ' 'FUNCTIONS CLASSES MODULES FILES inspect'), 'STRINGS': ('strings', 'str UNICODE SEQUENCES STRINGMETHODS ' 'FORMATTING TYPES'), 'STRINGMETHODS': ('string-methods', 'STRINGS FORMATTING'), 'FORMATTING': ('formatstrings', 'OPERATORS'), 'UNICODE': ('strings', 'encodings unicode SEQUENCES STRINGMETHODS ' 'FORMATTING TYPES'), 'NUMBERS': ('numbers', 'INTEGER FLOAT COMPLEX TYPES'), 'INTEGER': ('integers', 'int range'), 'FLOAT': ('floating', 'float math'), 'COMPLEX': ('imaginary', 'complex cmath'), 'SEQUENCES': ('typesseq', 'STRINGMETHODS FORMATTING range LISTS'), 'MAPPINGS': 'DICTIONARIES', 'FUNCTIONS': ('typesfunctions', 'def TYPES'), 'METHODS': ('typesmethods', 'class def CLASSES TYPES'), 'CODEOBJECTS': ('bltin-code-objects', 'compile FUNCTIONS TYPES'), 'TYPEOBJECTS': ('bltin-type-objects', 'types TYPES'), 'FRAMEOBJECTS': 'TYPES', 'TRACEBACKS': 'TYPES', 'NONE': ('bltin-null-object', ''), 'ELLIPSIS': ('bltin-ellipsis-object', 'SLICINGS'), 'SPECIALATTRIBUTES': ('specialattrs', ''), 'CLASSES': ('types', 'class SPECIALMETHODS PRIVATENAMES'), 'MODULES': ('typesmodules', 'import'), 'PACKAGES': 'import', 'EXPRESSIONS': ('operator-summary', 'lambda or and not in is BOOLEAN ' 'COMPARISON BITWISE SHIFTING BINARY FORMATTING POWER ' 'UNARY ATTRIBUTES SUBSCRIPTS SLICINGS CALLS TUPLES ' 'LISTS DICTIONARIES'), 'OPERATORS': 'EXPRESSIONS', 'PRECEDENCE': 'EXPRESSIONS', 'OBJECTS': ('objects', 'TYPES'), 'SPECIALMETHODS': ('specialnames', 'BASICMETHODS ATTRIBUTEMETHODS ' 'CALLABLEMETHODS SEQUENCEMETHODS MAPPINGMETHODS ' 'NUMBERMETHODS CLASSES'), 'BASICMETHODS': ('customization', 'hash repr str SPECIALMETHODS'), 'ATTRIBUTEMETHODS': ('attribute-access', 'ATTRIBUTES SPECIALMETHODS'), 'CALLABLEMETHODS': ('callable-types', 'CALLS SPECIALMETHODS'), 'SEQUENCEMETHODS': ('sequence-types', 'SEQUENCES SEQUENCEMETHODS ' 'SPECIALMETHODS'), 'MAPPINGMETHODS': ('sequence-types', 'MAPPINGS SPECIALMETHODS'), 'NUMBERMETHODS': ('numeric-types', 'NUMBERS AUGMENTEDASSIGNMENT ' 'SPECIALMETHODS'), 'EXECUTION': ('execmodel', 'NAMESPACES DYNAMICFEATURES EXCEPTIONS'), 'NAMESPACES': ('naming', 'global nonlocal ASSIGNMENT DELETION DYNAMICFEATURES'), 'DYNAMICFEATURES': ('dynamic-features', ''), 'SCOPING': 'NAMESPACES', 'FRAMES': 'NAMESPACES', 'EXCEPTIONS': ('exceptions', 'try except finally raise'), 'CONVERSIONS': ('conversions', ''), 'IDENTIFIERS': ('identifiers', 'keywords SPECIALIDENTIFIERS'), 'SPECIALIDENTIFIERS': ('id-classes', ''), 'PRIVATENAMES': ('atom-identifiers', ''), 'LITERALS': ('atom-literals', 'STRINGS NUMBERS TUPLELITERALS ' 'LISTLITERALS DICTIONARYLITERALS'), 'TUPLES': 'SEQUENCES', 'TUPLELITERALS': ('exprlists', 'TUPLES LITERALS'), 'LISTS': ('typesseq-mutable', 'LISTLITERALS'), 'LISTLITERALS': ('lists', 'LISTS LITERALS'), 'DICTIONARIES': ('typesmapping', 'DICTIONARYLITERALS'), 'DICTIONARYLITERALS': ('dict', 'DICTIONARIES LITERALS'), 'ATTRIBUTES': ('attribute-references', 'getattr hasattr setattr ATTRIBUTEMETHODS'), 'SUBSCRIPTS': ('subscriptions', 'SEQUENCEMETHODS'), 'SLICINGS': ('slicings', 'SEQUENCEMETHODS'), 'CALLS': ('calls', 'EXPRESSIONS'), 'POWER': ('power', 'EXPRESSIONS'), 'UNARY': ('unary', 'EXPRESSIONS'), 'BINARY': ('binary', 'EXPRESSIONS'), 'SHIFTING': ('shifting', 'EXPRESSIONS'), 'BITWISE': ('bitwise', 'EXPRESSIONS'), 'COMPARISON': ('comparisons', 'EXPRESSIONS BASICMETHODS'), 'BOOLEAN': ('booleans', 'EXPRESSIONS TRUTHVALUE'), 'ASSERTION': 'assert', 'ASSIGNMENT': ('assignment', 'AUGMENTEDASSIGNMENT'), 'AUGMENTEDASSIGNMENT': ('augassign', 'NUMBERMETHODS'), 'DELETION': 'del', 'RETURNING': 'return', 'IMPORTING': 'import', 'CONDITIONAL': 'if', 'LOOPING': ('compound', 'for while break continue'), 'TRUTHVALUE': ('truth', 'if while and or not BASICMETHODS'), 'DEBUGGING': ('debugger', 'pdb'), 'CONTEXTMANAGERS': ('context-managers', 'with'), } def __init__(self, input=None, output=None): self._input = input self._output = output @property def input(self): return self._input or sys.stdin @property def output(self): return self._output or sys.stdout def __repr__(self): if inspect.stack()[1][3] == '?': self() return '' return '<%s.%s instance>' % (self.__class__.__module__, self.__class__.__qualname__) _GoInteractive = object() def __call__(self, request=_GoInteractive): if request is not self._GoInteractive: self.help(request) else: self.intro() self.interact() self.output.write(''' You are now leaving help and returning to the Python interpreter. If you want to ask for help on a particular object directly from the interpreter, you can type "help(object)". Executing "help('string')" has the same effect as typing a particular string at the help> prompt. ''') def interact(self): self.output.write('\n') while True: try: request = self.getline('help> ') if not request: break except (KeyboardInterrupt, EOFError): break request = request.strip() # Make sure significant trailing quoting marks of literals don't # get deleted while cleaning input if (len(request) > 2 and request[0] == request[-1] in ("'", '"') and request[0] not in request[1:-1]): request = request[1:-1] if request.lower() in ('q', 'quit'): break if request == 'help': self.intro() else: self.help(request) def getline(self, prompt): """Read one line, using input() when appropriate.""" if self.input is sys.stdin: return input(prompt) else: self.output.write(prompt) self.output.flush() return self.input.readline() def help(self, request): if type(request) is type(''): request = request.strip() if request == 'keywords': self.listkeywords() elif request == 'symbols': self.listsymbols() elif request == 'topics': self.listtopics() elif request == 'modules': self.listmodules() elif request[:8] == 'modules ': self.listmodules(request.split()[1]) elif request in self.symbols: self.showsymbol(request) elif request in ['True', 'False', 'None']: # special case these keywords since they are objects too doc(eval(request), 'Help on %s:') elif request in self.keywords: self.showtopic(request) elif request in self.topics: self.showtopic(request) elif request: doc(request, 'Help on %s:', output=self._output) else: doc(str, 'Help on %s:', output=self._output) elif isinstance(request, Helper): self() else: doc(request, 'Help on %s:', output=self._output) self.output.write('\n') def intro(self): self.output.write(''' Welcome to Python {0}'s help utility! If this is your first time using Python, you should definitely check out the tutorial on the Internet at https://docs.python.org/{0}/tutorial/. Enter the name of any module, keyword, or topic to get help on writing Python programs and using Python modules. To quit this help utility and return to the interpreter, just type "quit". To get a list of available modules, keywords, symbols, or topics, type "modules", "keywords", "symbols", or "topics". Each module also comes with a one-line summary of what it does; to list the modules whose name or summary contain a given string such as "spam", type "modules spam". '''.format('%d.%d' % sys.version_info[:2])) def list(self, items, columns=4, width=80): items = list(sorted(items)) colw = width // columns rows = (len(items) + columns - 1) // columns for row in range(rows): for col in range(columns): i = col * rows + row if i < len(items): self.output.write(items[i]) if col < columns - 1: self.output.write(' ' + ' ' * (colw - 1 - len(items[i]))) self.output.write('\n') def listkeywords(self): self.output.write(''' Here is a list of the Python keywords. Enter any keyword to get more help. ''') self.list(self.keywords.keys()) def listsymbols(self): self.output.write(''' Here is a list of the punctuation symbols which Python assigns special meaning to. Enter any symbol to get more help. ''') self.list(self.symbols.keys()) def listtopics(self): self.output.write(''' Here is a list of available topics. Enter any topic name to get more help. ''') self.list(self.topics.keys()) def showtopic(self, topic, more_xrefs=''): try: import pydoc_data.topics except ImportError: self.output.write(''' Sorry, topic and keyword documentation is not available because the module "pydoc_data.topics" could not be found. ''') return target = self.topics.get(topic, self.keywords.get(topic)) if not target: self.output.write('no documentation found for %s\n' % repr(topic)) return if type(target) is type(''): return self.showtopic(target, more_xrefs) label, xrefs = target try: doc = pydoc_data.topics.topics[label] except KeyError: self.output.write('no documentation found for %s\n' % repr(topic)) return doc = doc.strip() + '\n' if more_xrefs: xrefs = (xrefs or '') + ' ' + more_xrefs if xrefs: import textwrap text = 'Related help topics: ' + ', '.join(xrefs.split()) + '\n' wrapped_text = textwrap.wrap(text, 72) doc += '\n%s\n' % '\n'.join(wrapped_text) pager(doc) def _gettopic(self, topic, more_xrefs=''): """Return unbuffered tuple of (topic, xrefs). If an error occurs here, the exception is caught and displayed by the url handler. This function duplicates the showtopic method but returns its result directly so it can be formatted for display in an html page. """ try: import pydoc_data.topics except ImportError: return(''' Sorry, topic and keyword documentation is not available because the module "pydoc_data.topics" could not be found. ''' , '') target = self.topics.get(topic, self.keywords.get(topic)) if not target: raise ValueError('could not find topic') if isinstance(target, str): return self._gettopic(target, more_xrefs) label, xrefs = target doc = pydoc_data.topics.topics[label] if more_xrefs: xrefs = (xrefs or '') + ' ' + more_xrefs return doc, xrefs def showsymbol(self, symbol): target = self.symbols[symbol] topic, _, xrefs = target.partition(' ') self.showtopic(topic, xrefs) def listmodules(self, key=''): if key: self.output.write(''' Here is a list of modules whose name or summary contains '{}'. If there are any, enter a module name to get more help. '''.format(key)) apropos(key) else: self.output.write(''' Please wait a moment while I gather a list of all available modules... ''') modules = {} def callback(path, modname, desc, modules=modules): if modname and modname[-9:] == '.__init__': modname = modname[:-9] + ' (package)' if modname.find('.') < 0: modules[modname] = 1 def onerror(modname): callback(None, modname, None) ModuleScanner().run(callback, onerror=onerror) self.list(modules.keys()) self.output.write(''' Enter any module name to get more help. Or, type "modules spam" to search for modules whose name or summary contain the string "spam". ''') help = Helper() class ModuleScanner: """An interruptible scanner that searches module synopses.""" def run(self, callback, key=None, completer=None, onerror=None): if key: key = key.lower() self.quit = False seen = {} for modname in sys.builtin_module_names: if modname != '__main__': seen[modname] = 1 if key is None: callback(None, modname, '') else: name = __import__(modname).__doc__ or '' desc = name.split('\n')[0] name = modname + ' - ' + desc if name.lower().find(key) >= 0: callback(None, modname, desc) for importer, modname, ispkg in pkgutil.walk_packages(onerror=onerror): if self.quit: break if key is None: callback(None, modname, '') else: try: spec = pkgutil._get_spec(importer, modname) except SyntaxError: # raised by tests for bad coding cookies or BOM continue loader = spec.loader if hasattr(loader, 'get_source'): try: source = loader.get_source(modname) except Exception: if onerror: onerror(modname) continue desc = source_synopsis(io.StringIO(source)) or '' if hasattr(loader, 'get_filename'): path = loader.get_filename(modname) else: path = None else: try: module = importlib._bootstrap._load(spec) except ImportError: if onerror: onerror(modname) continue desc = module.__doc__.splitlines()[0] if module.__doc__ else '' path = getattr(module,'__file__',None) name = modname + ' - ' + desc if name.lower().find(key) >= 0: callback(path, modname, desc) if completer: completer() def apropos(key): """Print all the one-line module summaries that contain a substring.""" def callback(path, modname, desc): if modname[-9:] == '.__init__': modname = modname[:-9] + ' (package)' print(modname, desc and '- ' + desc) def onerror(modname): pass with warnings.catch_warnings(): warnings.filterwarnings('ignore') # ignore problems during import ModuleScanner().run(callback, key, onerror=onerror) # --------------------------------------- enhanced Web browser interface def _start_server(urlhandler, hostname, port): """Start an HTTP server thread on a specific port. Start an HTML/text server thread, so HTML or text documents can be browsed dynamically and interactively with a Web browser. Example use: >>> import time >>> import pydoc Define a URL handler. To determine what the client is asking for, check the URL and content_type. Then get or generate some text or HTML code and return it. >>> def my_url_handler(url, content_type): ... text = 'the URL sent was: (%s, %s)' % (url, content_type) ... return text Start server thread on port 0. If you use port 0, the server will pick a random port number. You can then use serverthread.port to get the port number. >>> port = 0 >>> serverthread = pydoc._start_server(my_url_handler, port) Check that the server is really started. If it is, open browser and get first page. Use serverthread.url as the starting page. >>> if serverthread.serving: ... import webbrowser The next two lines are commented out so a browser doesn't open if doctest is run on this module. #... webbrowser.open(serverthread.url) #True Let the server do its thing. We just need to monitor its status. Use time.sleep so the loop doesn't hog the CPU. >>> starttime = time.monotonic() >>> timeout = 1 #seconds This is a short timeout for testing purposes. >>> while serverthread.serving: ... time.sleep(.01) ... if serverthread.serving and time.monotonic() - starttime > timeout: ... serverthread.stop() ... break Print any errors that may have occurred. >>> print(serverthread.error) None """ import http.server import email.message import select import threading class DocHandler(http.server.BaseHTTPRequestHandler): def do_GET(self): """Process a request from an HTML browser. The URL received is in self.path. Get an HTML page from self.urlhandler and send it. """ if self.path.endswith('.css'): content_type = 'text/css' else: content_type = 'text/html' self.send_response(200) self.send_header('Content-Type', '%s; charset=UTF-8' % content_type) self.end_headers() self.wfile.write(self.urlhandler( self.path, content_type).encode('utf-8')) def log_message(self, *args): # Don't log messages. pass class DocServer(http.server.HTTPServer): def __init__(self, host, port, callback): self.host = host self.address = (self.host, port) self.callback = callback self.base.__init__(self, self.address, self.handler) self.quit = False def serve_until_quit(self): while not self.quit: rd, wr, ex = select.select([self.socket.fileno()], [], [], 1) if rd: self.handle_request() self.server_close() def server_activate(self): self.base.server_activate(self) if self.callback: self.callback(self) class ServerThread(threading.Thread): def __init__(self, urlhandler, host, port): self.urlhandler = urlhandler self.host = host self.port = int(port) threading.Thread.__init__(self) self.serving = False self.error = None def run(self): """Start the server.""" try: DocServer.base = http.server.HTTPServer DocServer.handler = DocHandler DocHandler.MessageClass = email.message.Message DocHandler.urlhandler = staticmethod(self.urlhandler) docsvr = DocServer(self.host, self.port, self.ready) self.docserver = docsvr docsvr.serve_until_quit() except Exception as e: self.error = e def ready(self, server): self.serving = True self.host = server.host self.port = server.server_port self.url = 'http://%s:%d/' % (self.host, self.port) def stop(self): """Stop the server and this thread nicely""" self.docserver.quit = True self.join() # explicitly break a reference cycle: DocServer.callback # has indirectly a reference to ServerThread. self.docserver = None self.serving = False self.url = None thread = ServerThread(urlhandler, hostname, port) thread.start() # Wait until thread.serving is True to make sure we are # really up before returning. while not thread.error and not thread.serving: time.sleep(.01) return thread def _url_handler(url, content_type="text/html"): """The pydoc url handler for use with the pydoc server. If the content_type is 'text/css', the _pydoc.css style sheet is read and returned if it exits. If the content_type is 'text/html', then the result of get_html_page(url) is returned. """ class _HTMLDoc(HTMLDoc): def page(self, title, contents): """Format an HTML page.""" css_path = "pydoc_data/_pydoc.css" css_link = ( '' % css_path) return '''\ Pydoc: %s %s%s
      %s
      ''' % (title, css_link, html_navbar(), contents) def filelink(self, url, path): return '%s' % (url, path) html = _HTMLDoc() def html_navbar(): version = html.escape("%s [%s, %s]" % (platform.python_version(), platform.python_build()[0], platform.python_compiler())) return """
      Python %s
      %s
      """ % (version, html.escape(platform.platform(terse=True))) def html_index(): """Module Index page.""" def bltinlink(name): return '%s' % (name, name) heading = html.heading( 'Index of Modules', '#ffffff', '#7799ee') names = [name for name in sys.builtin_module_names if name != '__main__'] contents = html.multicolumn(names, bltinlink) contents = [heading, '

      ' + html.bigsection( 'Built-in Modules', '#ffffff', '#ee77aa', contents)] seen = {} for dir in sys.path: contents.append(html.index(dir, seen)) contents.append( '

      pydoc by Ka-Ping Yee' '<ping@lfw.org>') return 'Index of Modules', ''.join(contents) def html_search(key): """Search results page.""" # scan for modules search_result = [] def callback(path, modname, desc): if modname[-9:] == '.__init__': modname = modname[:-9] + ' (package)' search_result.append((modname, desc and '- ' + desc)) with warnings.catch_warnings(): warnings.filterwarnings('ignore') # ignore problems during import def onerror(modname): pass ModuleScanner().run(callback, key, onerror=onerror) # format page def bltinlink(name): return '%s' % (name, name) results = [] heading = html.heading( 'Search Results', '#ffffff', '#7799ee') for name, desc in search_result: results.append(bltinlink(name) + desc) contents = heading + html.bigsection( 'key = %s' % key, '#ffffff', '#ee77aa', '
      '.join(results)) return 'Search Results', contents def html_getfile(path): """Get and display a source file listing safely.""" path = urllib.parse.unquote(path) with tokenize.open(path) as fp: lines = html.escape(fp.read()) body = '

      %s
      ' % lines heading = html.heading( 'File Listing', '#ffffff', '#7799ee') contents = heading + html.bigsection( 'File: %s' % path, '#ffffff', '#ee77aa', body) return 'getfile %s' % path, contents def html_topics(): """Index of topic texts available.""" def bltinlink(name): return '%s' % (name, name) heading = html.heading( 'INDEX', '#ffffff', '#7799ee') names = sorted(Helper.topics.keys()) contents = html.multicolumn(names, bltinlink) contents = heading + html.bigsection( 'Topics', '#ffffff', '#ee77aa', contents) return 'Topics', contents def html_keywords(): """Index of keywords.""" heading = html.heading( 'INDEX', '#ffffff', '#7799ee') names = sorted(Helper.keywords.keys()) def bltinlink(name): return '%s' % (name, name) contents = html.multicolumn(names, bltinlink) contents = heading + html.bigsection( 'Keywords', '#ffffff', '#ee77aa', contents) return 'Keywords', contents def html_topicpage(topic): """Topic or keyword help page.""" buf = io.StringIO() htmlhelp = Helper(buf, buf) contents, xrefs = htmlhelp._gettopic(topic) if topic in htmlhelp.keywords: title = 'KEYWORD' else: title = 'TOPIC' heading = html.heading( '%s' % title, '#ffffff', '#7799ee') contents = '
      %s
      ' % html.markup(contents) contents = html.bigsection(topic , '#ffffff','#ee77aa', contents) if xrefs: xrefs = sorted(xrefs.split()) def bltinlink(name): return '%s' % (name, name) xrefs = html.multicolumn(xrefs, bltinlink) xrefs = html.section('Related help topics: ', '#ffffff', '#ee77aa', xrefs) return ('%s %s' % (title, topic), ''.join((heading, contents, xrefs))) def html_getobj(url): obj = locate(url, forceload=1) if obj is None and url != 'None': raise ValueError('could not find object') title = describe(obj) content = html.document(obj, url) return title, content def html_error(url, exc): heading = html.heading( 'Error', '#ffffff', '#7799ee') contents = '
      '.join(html.escape(line) for line in format_exception_only(type(exc), exc)) contents = heading + html.bigsection(url, '#ffffff', '#bb0000', contents) return "Error - %s" % url, contents def get_html_page(url): """Generate an HTML page for url.""" complete_url = url if url.endswith('.html'): url = url[:-5] try: if url in ("", "index"): title, content = html_index() elif url == "topics": title, content = html_topics() elif url == "keywords": title, content = html_keywords() elif '=' in url: op, _, url = url.partition('=') if op == "search?key": title, content = html_search(url) elif op == "getfile?key": title, content = html_getfile(url) elif op == "topic?key": # try topics first, then objects. try: title, content = html_topicpage(url) except ValueError: title, content = html_getobj(url) elif op == "get?key": # try objects first, then topics. if url in ("", "index"): title, content = html_index() else: try: title, content = html_getobj(url) except ValueError: title, content = html_topicpage(url) else: raise ValueError('bad pydoc url') else: title, content = html_getobj(url) except Exception as exc: # Catch any errors and display them in an error page. title, content = html_error(complete_url, exc) return html.page(title, content) if url.startswith('/'): url = url[1:] if content_type == 'text/css': path_here = os.path.dirname(os.path.realpath(__file__)) css_path = os.path.join(path_here, url) with open(css_path) as fp: return ''.join(fp.readlines()) elif content_type == 'text/html': return get_html_page(url) # Errors outside the url handler are caught by the server. raise TypeError('unknown content type %r for url %s' % (content_type, url)) def browse(port=0, *, open_browser=True, hostname='localhost'): """Start the enhanced pydoc Web server and open a Web browser. Use port '0' to start the server on an arbitrary port. Set open_browser to False to suppress opening a browser. """ import webbrowser serverthread = _start_server(_url_handler, hostname, port) if serverthread.error: print(serverthread.error) return if serverthread.serving: server_help_msg = 'Server commands: [b]rowser, [q]uit' if open_browser: webbrowser.open(serverthread.url) try: print('Server ready at', serverthread.url) print(server_help_msg) while serverthread.serving: cmd = input('server> ') cmd = cmd.lower() if cmd == 'q': break elif cmd == 'b': webbrowser.open(serverthread.url) else: print(server_help_msg) except (KeyboardInterrupt, EOFError): print() finally: if serverthread.serving: serverthread.stop() print('Server stopped') # -------------------------------------------------- command-line interface def ispath(x): return isinstance(x, str) and x.find(os.sep) >= 0 def _get_revised_path(given_path, argv0): """Ensures current directory is on returned path, and argv0 directory is not Exception: argv0 dir is left alone if it's also pydoc's directory. Returns a new path entry list, or None if no adjustment is needed. """ # Scripts may get the current directory in their path by default if they're # run with the -m switch, or directly from the current directory. # The interactive prompt also allows imports from the current directory. # Accordingly, if the current directory is already present, don't make # any changes to the given_path if '' in given_path or os.curdir in given_path or os.getcwd() in given_path: return None # Otherwise, add the current directory to the given path, and remove the # script directory (as long as the latter isn't also pydoc's directory. stdlib_dir = os.path.dirname(__file__) script_dir = os.path.dirname(argv0) revised_path = given_path.copy() if script_dir in given_path and not os.path.samefile(script_dir, stdlib_dir): revised_path.remove(script_dir) revised_path.insert(0, os.getcwd()) return revised_path # Note: the tests only cover _get_revised_path, not _adjust_cli_path itself def _adjust_cli_sys_path(): """Ensures current directory is on sys.path, and __main__ directory is not. Exception: __main__ dir is left alone if it's also pydoc's directory. """ revised_path = _get_revised_path(sys.path, sys.argv[0]) if revised_path is not None: sys.path[:] = revised_path def cli(): """Command-line interface (looks at sys.argv to decide what to do).""" import getopt class BadUsage(Exception): pass _adjust_cli_sys_path() try: opts, args = getopt.getopt(sys.argv[1:], 'bk:n:p:w') writing = False start_server = False open_browser = False port = 0 hostname = 'localhost' for opt, val in opts: if opt == '-b': start_server = True open_browser = True if opt == '-k': apropos(val) return if opt == '-p': start_server = True port = val if opt == '-w': writing = True if opt == '-n': start_server = True hostname = val if start_server: browse(port, hostname=hostname, open_browser=open_browser) return if not args: raise BadUsage for arg in args: if ispath(arg) and not os.path.exists(arg): print('file %r does not exist' % arg, file=sys.stderr) break if ispath(arg) and os.path.isfile(arg): arg = importfile(arg) if writing: if ispath(arg) and os.path.isdir(arg): writedocs(arg) else: writedoc(arg) else: help.help(arg) except (getopt.error, BadUsage): cmd = os.path.splitext(os.path.basename(sys.argv[0]))[0] print("""pydoc - the Python documentation tool {cmd} ... Show text documentation on something. may be the name of a Python keyword, topic, function, module, or package, or a dotted reference to a class or function within a module or module in a package. If contains a '{sep}', it is used as the path to a Python source file to document. If name is 'keywords', 'topics', or 'modules', a listing of these things is displayed. {cmd} -k Search for a keyword in the synopsis lines of all available modules. {cmd} -n Start an HTTP server with the given hostname (default: localhost). {cmd} -p Start an HTTP server on the given port on the local machine. Port number 0 can be used to get an arbitrary unused port. {cmd} -b Start an HTTP server on an arbitrary unused port and open a Web browser to interactively browse documentation. This option can be used in combination with -n and/or -p. {cmd} -w ... Write out the HTML documentation for a module to a file in the current directory. If contains a '{sep}', it is treated as a filename; if it names a directory, documentation is written for all the contents. """.format(cmd=cmd, sep=os.sep)) if __name__ == '__main__': cli() mrcal-2.4.1/doc/python-api.org000066400000000000000000000637051456301662300162030ustar00rootroot00000000000000#+TITLE: mrcal Python API #+OPTIONS: toc:t A Python API is available to go beyond what the [[file:commandline-tools.org][pre-made commandline tools]] can do. These tools themselves are written using the Python API, so their sources are are a good guide. All the Python functions have complete docstrings, so the =pydoc3= tool is effective at displaying the relevant documentation. For convenience, all the docstrings have been extracted and formatted into the [[file:mrcal-python-api-reference.html][Python API reference]]. The available functions, by category: * Geometry ** Primitives Functions to manipulate [[file:conventions.org::#pose-representation][rotations and poses]]. - [[file:mrcal-python-api-reference.html#-identity_R][=mrcal.identity_R()=]]: Return an identity rotation matrix - [[file:mrcal-python-api-reference.html#-identity_r][=mrcal.identity_r()=]]: Return an identity Rodrigues rotation - [[file:mrcal-python-api-reference.html#-identity_Rt][=mrcal.identity_Rt()=]]: Return an identity Rt transformation - [[file:mrcal-python-api-reference.html#-identity_rt][=mrcal.identity_rt()=]]: Return an identity rt transformation - [[file:mrcal-python-api-reference.html#-r_from_R][=mrcal.r_from_R()=]]: Compute a Rodrigues vector from a rotation matrix - [[file:mrcal-python-api-reference.html#-R_from_r][=mrcal.R_from_r()=]]: Compute a rotation matrix from a Rodrigues vector - [[file:mrcal-python-api-reference.html#-rt_from_Rt][=mrcal.rt_from_Rt()=]]: Compute an rt transformation from a Rt transformation - [[file:mrcal-python-api-reference.html#-Rt_from_rt][=mrcal.Rt_from_rt()=]]: Compute an Rt transformation from a rt transformation - [[file:mrcal-python-api-reference.html#-invert_R][=mrcal.invert_R()=]]: Invert an (3,3) matrix rotation. This is a transpose - [[file:mrcal-python-api-reference.html#-invert_Rt][=mrcal.invert_Rt()=]]: Invert an Rt transformation - [[file:mrcal-python-api-reference.html#-invert_rt][=mrcal.invert_rt()=]]: Invert an rt transformation - [[file:mrcal-python-api-reference.html#-compose_r][=mrcal.compose_r()=]]: Compose Rodrigues rotations - [[file:mrcal-python-api-reference.html#-compose_Rt][=mrcal.compose_Rt()=]]: Compose Rt transformations - [[file:mrcal-python-api-reference.html#-compose_rt][=mrcal.compose_rt()=]]: Compose rt transformations - [[file:mrcal-python-api-reference.html#-rotate_point_r][=mrcal.rotate_point_r()=]]: Rotate point(s) using a Rodrigues vector - [[file:mrcal-python-api-reference.html#-rotate_point_R][=mrcal.rotate_point_R()=]]: Rotate point(s) using a rotation matrix - [[file:mrcal-python-api-reference.html#-transform_point_rt][=mrcal.transform_point_rt()=]]: Transform point(s) using an rt transformation - [[file:mrcal-python-api-reference.html#-transform_point_Rt][=mrcal.transform_point_Rt()=]]: Transform point(s) using an Rt transformation - [[file:mrcal-python-api-reference.html#-R_from_quat][=mrcal.R_from_quat()=]]: Convert a rotation defined as a unit quaternion rotation to a rotation matrix - [[file:mrcal-python-api-reference.html#-quat_from_R][=mrcal.quat_from_R()=]]: Convert a rotation defined as a rotation matrix to a unit quaternion - [[file:mrcal-python-api-reference.html#-Rt_from_qt][=mrcal.Rt_from_qt()=]]: Compute an Rt transformation from a qt transformation - [[file:mrcal-python-api-reference.html#-qt_from_Rt][=mrcal.qt_from_Rt()=]]: Compute a qt transformation from an Rt transformation ** Alignment - [[file:mrcal-python-api-reference.html#-align_procrustes_points_Rt01][=mrcal.align_procrustes_points_Rt01()=]]: Compute a rigid transformation to align two point clouds - [[file:mrcal-python-api-reference.html#-align_procrustes_vectors_R01][=mrcal.align_procrustes_vectors_R01()=]]: Compute a rotation to align two sets of direction vectors - [[file:mrcal-python-api-reference.html#-R_aligned_to_vector][=mrcal.R_aligned_to_vector()=]]: Compute a non-unique rotation to map a given vector to [0,0,1] * Lens models Routines for manipulating [[file:lensmodels.org][lens models]]. - [[file:mrcal-python-api-reference.html#-supported_lensmodels][=mrcal.supported_lensmodels()=]]: Returns a tuple of strings for the various lens models we support - [[file:mrcal-python-api-reference.html#-lensmodel_num_params][=mrcal.lensmodel_num_params()=]]: Get the number of lens parameters for a particular model type - [[file:mrcal-python-api-reference.html#-lensmodel_metadata_and_config][=mrcal.lensmodel_metadata_and_config()=]]: Returns [[file:lensmodels.org::#representation][meta-information about a model]] - [[file:mrcal-python-api-reference.html#-knots_for_splined_models][=mrcal.knots_for_splined_models()=]]: Return a tuple of locations of x and y spline knots * Projections - [[file:mrcal-python-api-reference.html#-project][=mrcal.project()=]]: Projects a set of 3D camera-frame points to the imager - [[file:mrcal-python-api-reference.html#-unproject][=mrcal.unproject()=]]: Unprojects pixel coordinates to observation vectors - [[file:mrcal-python-api-reference.html#-project_pinhole][=mrcal.project_pinhole()=]]: Projects a set of 3D camera-frame points using a pinhole model - [[file:mrcal-python-api-reference.html#-unproject_pinhole][=mrcal.unproject_pinhole()=]]: Unprojects a set of 2D pixel coordinates using a pinhole model - [[file:mrcal-python-api-reference.html#-project_stereographic][=mrcal.project_stereographic()=]]: Projects a set of 3D camera-frame points using a stereographic map - [[file:mrcal-python-api-reference.html#-unproject_stereographic][=mrcal.unproject_stereographic()=]]: Unprojects a set of 2D pixel coordinates using a stereographic map - [[file:mrcal-python-api-reference.html#-project_latlon][=mrcal.project_latlon()=]]: Projects a set of 3D camera-frame points using a transverse equirectangular projection (used primarily for wide-angle stereo) - [[file:mrcal-python-api-reference.html#-unproject_latlon][=mrcal.unproject_latlon()=]]: Unprojects a set of 2D pixel coordinates using a transverse equirectangular projection (used primarily for wide-angle stereo) - [[file:mrcal-python-api-reference.html#-project_lonlat][=mrcal.project_lonlat()=]]: Projects a set of 3D camera-frame points using an equirectangular projection (useful for representing 360-degree panoramas) - [[file:mrcal-python-api-reference.html#-unproject_lonlat][=mrcal.unproject_lonlat()=]]: Unprojects a set of 2D pixel coordinates using an equirectangular projection (useful for representing 360-degree panoramas) * Visualization ** Driver routines These are all backends for the corresponding [[file:commandline-tools.org][commandline tools]]. - [[file:mrcal-python-api-reference.html#-show_geometry][=mrcal.show_geometry()=]]: Visualize the world represented by some number of cameras and chessboards and points. For instance, result of a calibration run. - [[file:mrcal-python-api-reference.html#-show_projection_diff][=mrcal.show_projection_diff()=]]: Visualize the difference in projection between N models - [[file:mrcal-python-api-reference.html#-show_projection_uncertainty][=mrcal.show_projection_uncertainty()=]]: Visualize the uncertainty in camera projection - [[file:mrcal-python-api-reference.html#-show_projection_uncertainty_vs_distance][=mrcal.show_projection_uncertainty_vs_distance()=]]: Visualize the uncertainty in camera projection along one observation ray - [[file:mrcal-python-api-reference.html#-show_distortion_off_pinhole][=mrcal.show_distortion_off_pinhole()=]]: Visualize a lens's deviation from a pinhole projection: examine the difference across the imager - [[file:mrcal-python-api-reference.html#-show_distortion_off_pinhole_radial][=mrcal.show_distortion_off_pinhole_radial()=]]: Visualize a lens's deviation from a pinhole projection: examine the radial distortion curve - [[file:mrcal-python-api-reference.html#-show_valid_intrinsics_region][=mrcal.show_valid_intrinsics_region()=]]: Visualize a model's valid-intrinsics region - [[file:mrcal-python-api-reference.html#-show_splined_model_correction][=mrcal.show_splined_model_correction()=]]: Visualize the projections corrections represented by a splined model - [[file:mrcal-python-api-reference.html#-show_residuals_board_observation][=mrcal.show_residuals_board_observation()=]]: Visualize calibration residuals for a single observation - [[file:mrcal-python-api-reference.html#-show_residuals_histogram][=mrcal.show_residuals_histogram()=]]: Visualize the distribution of the optimized residuals - [[file:mrcal-python-api-reference.html#-show_residuals_vectorfield][=mrcal.show_residuals_vectorfield()=]]: Visualize the optimized residuals as a vector field - [[file:mrcal-python-api-reference.html#-show_residuals_magnitudes][=mrcal.show_residuals_magnitudes()=]]: Visualize the optimized residual magnitudes as color-coded points - [[file:mrcal-python-api-reference.html#-show_residuals_directions][=mrcal.show_residuals_directions()=]]: Visualize the optimized residual directions as color-coded points - [[file:mrcal-python-api-reference.html#-show_residuals_regional][=mrcal.show_residuals_regional()=]]: Visualize the optimized residuals, broken up by region ** Utilities - [[file:mrcal-python-api-reference.html#-annotate_image__valid_intrinsics_region][=mrcal.annotate_image__valid_intrinsics_region()=]]: Annotate an image with a model's valid-intrinsics region - [[file:mrcal-python-api-reference.html#-imagergrid_using][=mrcal.imagergrid_using()=]]: Get a 'using' gnuplotlib expression for imager colormap plots - [[file:mrcal-python-api-reference.html#-fitted_gaussian_equation][=mrcal.fitted_gaussian_equation()=]]: Get an 'equation' gnuplotlib expression for a gaussian curve fitting some data - [[file:mrcal-python-api-reference.html#-sample_imager][=mrcal.sample_imager()=]]: Returns regularly-sampled, gridded pixels coordinates across the imager - [[file:mrcal-python-api-reference.html#-sample_imager_unproject][=mrcal.sample_imager_unproject()=]]: Reports 3D observation vectors that regularly sample the imager - [[file:mrcal-python-api-reference.html#-plotoptions_state_boundaries][=mrcal.plotoptions_state_boundaries()=]]: Return the 'set' plot options for gnuplotlib to show the state boundaries - [[file:mrcal-python-api-reference.html#-plotoptions_measurement_boundaries][=mrcal.plotoptions_measurement_boundaries()=]]: Return the 'set' plot options for gnuplotlib to show the measurement boundaries - [[file:mrcal-python-api-reference.html#-apply_color_map][=mrcal.apply_color_map()=]]: Color-code an array - [[file:mrcal-python-api-reference.html#-write_point_cloud_as_ply][=mrcal.write_point_cloud_as_ply()=]]: Write a point cloud to a .ply file * Calibration helpers These are used by routines implementing a [[file:formulation.org][camera calibration]] system. Most users will run the [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras=]] tool instead of calling these. - [[file:mrcal-python-api-reference.html#-compute_chessboard_corners][=mrcal.compute_chessboard_corners()=]]: Compute or read the chessboard observations, and return them in a usable form - [[file:mrcal-python-api-reference.html#-estimate_monocular_calobject_poses_Rt_tocam][=mrcal.estimate_monocular_calobject_poses_Rt_tocam()=]]: Estimate camera-referenced poses of the calibration object from monocular views - [[file:mrcal-python-api-reference.html#-estimate_joint_frame_poses][=mrcal.estimate_joint_frame_poses()=]]: Estimate world-referenced poses of the calibration object - [[file:mrcal-python-api-reference.html#-seed_stereographic][=mrcal.seed_stereographic()=]]: Compute an optimization seed for a camera calibration * Image transforms - [[file:mrcal-python-api-reference.html#-scale_focal__best_pinhole_fit][=mrcal.scale_focal__best_pinhole_fit()=]]: Compute the optimal focal-length scale for reprojection to a pinhole lens - [[file:mrcal-python-api-reference.html#-pinhole_model_for_reprojection][=mrcal.pinhole_model_for_reprojection()=]]: Generate a pinhole model suitable for reprojecting an image - [[file:mrcal-python-api-reference.html#-image_transformation_map][=mrcal.image_transformation_map()=]]: Compute a reprojection map between two models - [[file:mrcal-python-api-reference.html#-transform_image][=mrcal.transform_image()=]]: Transforms a given image using a given map * Model analysis - [[file:mrcal-python-api-reference.html#-implied_Rt10__from_unprojections][=mrcal.implied_Rt10__from_unprojections()=]]: Compute the implied-by-the-intrinsics transformation to fit two cameras' projections - [[file:mrcal-python-api-reference.html#-worst_direction_stdev][=mrcal.worst_direction_stdev()=]]: Compute the worst-direction standard deviation from a 2x2 covariance matrix - [[file:mrcal-python-api-reference.html#-projection_uncertainty][=mrcal.projection_uncertainty()=]]: Compute the [[file:uncertainty.org][projection uncertainty]] of a camera-referenced point - [[file:mrcal-python-api-reference.html#-projection_diff][=mrcal.projection_diff()=]]: Compute the [[file:differencing.org][difference in projection]] between N models - [[file:mrcal-python-api-reference.html#-is_within_valid_intrinsics_region][=mrcal.is_within_valid_intrinsics_region()=]]: Which of the pixel coordinates fall within the valid-intrinsics region? * Stereo, triangulation, feature-matching :PROPERTIES: :CUSTOM_ID: python-api-stereo :END: - [[file:mrcal-python-api-reference.html#-rectified_system][=mrcal.rectified_system()=]]: Generate rectified stereo models, which we can use to rectify images for stereo matching - [[file:mrcal-python-api-reference.html#-rectified_resolution][=mrcal.rectified_resolution()=]]: Compute the resolution to be used for the rectified system. Usually this is called by [[file:mrcal-python-api-reference.html#-rectified_system][=mrcal.rectified_system()=]], but it's available standalone as well - [[file:mrcal-python-api-reference.html#-rectification_maps][=mrcal.rectification_maps()=]]: Construct pixel mappings to transform captured images into rectified images - [[file:mrcal-python-api-reference.html#-stereo_range][=mrcal.stereo_range()=]]: Compute ranges from observed disparities - [[file:mrcal-python-api-reference.html#-stereo_unproject][=mrcal.stereo_unproject()=]]: Compute a point cloud from observed disparities - [[file:mrcal-python-api-reference.html#-match_feature][=mrcal.match_feature()=]]: Find a pixel correspondence in a pair of images - [[file:mrcal-python-api-reference.html#-triangulate][=mrcal.triangulate()=]]: Triangulate N points with uncertainty propagation. This is a higher-level function than the other =mrcal.triangulate_...()= routines - [[file:mrcal-python-api-reference.html#-triangulate_geometric][=mrcal.triangulate_geometric()=]]: Simple geometric triangulation - [[file:mrcal-python-api-reference.html#-triangulate_lindstrom][=mrcal.triangulate_lindstrom()=]]: Triangulation minimizing the 2-norm of pinhole reprojection errors - [[file:mrcal-python-api-reference.html#-triangulate_leecivera_l1][=mrcal.triangulate_leecivera_l1()=]]: Triangulation minimizing the L1-norm of angle differences - [[file:mrcal-python-api-reference.html#-triangulate_leecivera_linf][=mrcal.triangulate_leecivera_linf()=]]: Triangulation minimizing the infinity-norm of angle differences - [[file:mrcal-python-api-reference.html#-triangulate_leecivera_mid2][=mrcal.triangulate_leecivera_mid2()=]]: Triangulation using Lee and Civera's alternative midpoint method. Recommended. - [[file:mrcal-python-api-reference.html#-triangulate_leecivera_wmid2][=mrcal.triangulate_leecivera_wmid2()=]]: Triangulation using Lee and Civera's inverse-depth-weighted alternative midpoint method. Recommended in favor of [[file:mrcal-python-api-reference.html#-triangulate_leecivera_mid2][=mrcal.triangulate_leecivera_mid2()=]] if we're looking at objects very close to either camera. * Synthetic data - [[file:mrcal-python-api-reference.html#-ref_calibration_object][=mrcal.ref_calibration_object()=]]: Return the geometry of the calibration object - [[file:mrcal-python-api-reference.html#-synthesize_board_observations][=mrcal.synthesize_board_observations()=]]: Produce synthetic chessboard observations - [[file:mrcal-python-api-reference.html#-make_perfect_observations][=mrcal.make_perfect_observations()=]]: Write perfect observations with perfect noise into the optimization_inputs * CHOLMOD interface The mrcal solver is an optimization routine based on sparse nonlinear least squares. The optimization loop is implemented in [[https://www.github.com/dkogan/libdogleg][=libdogleg=]], which uses the [[https://people.engr.tamu.edu/davis/suitesparse.html][CHOLMOD solver]] to compute the [[https://en.wikipedia.org/wiki/Cholesky_decomposition][Cholesky factorization]]. With a Cholesky factorization we can efficiently solve the linear system $J^T J \vec a = \vec b$ where the jacobian matrix $J$ is large and sparse. CHOLMOD is a C routine, and mrcal provides a Python interface. This is used internally for the [[file:uncertainty.org][projection uncertainty]] computations, and is convenient for general analysis. The sparse $J$ matrix is available from the optimizer via the [[file:mrcal-python-api-reference.html#-optimizer_callback][=mrcal.optimizer_callback()=]] function, as a [[https://docs.scipy.org/doc/scipy/reference/generated/scipy.sparse.csr_matrix.html][=scipy.sparse.csr_matrix=]] sparse array. The factorization can be computed by instantiating a [[file:mrcal-python-api-reference.html#CHOLMOD_factorization][=mrcal.CHOLMOD_factorization=]] class, and the linear system can then be solved by calling [[file:mrcal-python-api-reference.html#CHOLMOD_factorization-solve_xt_JtJ_bt][=mrcal.CHOLMOD_factorization.solve_xt_JtJ_bt()=]]. See these two docstrings for usage details and examples. * Layout of the measurement and state vectors Functions to interpret the contentes of the [[file:formulation.org][state and measurement vectors]]. - [[file:mrcal-python-api-reference.html#-state_index_intrinsics][=mrcal.state_index_intrinsics()=]]: Return the index in the optimization vector of the intrinsics of camera i - [[file:mrcal-python-api-reference.html#-state_index_extrinsics][=mrcal.state_index_extrinsics()=]]: Return the index in the optimization vector of the extrinsics of camera i - [[file:mrcal-python-api-reference.html#-state_index_frames][=mrcal.state_index_frames()=]]: Return the index in the optimization vector of the pose of frame i - [[file:mrcal-python-api-reference.html#-state_index_points][=mrcal.state_index_points()=]]: Return the index in the optimization vector of the position of point i - [[file:mrcal-python-api-reference.html#-state_index_calobject_warp][=mrcal.state_index_calobject_warp()=]]: Return the index in the optimization vector of the calibration object warp - [[file:mrcal-python-api-reference.html#-num_states_intrinsics][=mrcal.num_states_intrinsics()=]]: Get the number of intrinsics parameters in the optimization vector - [[file:mrcal-python-api-reference.html#-num_states_extrinsics][=mrcal.num_states_extrinsics()=]]: Get the number of extrinsics parameters in the optimization vector - [[file:mrcal-python-api-reference.html#-num_states_frames][=mrcal.num_states_frames()=]]: Get the number of calibration object pose parameters in the optimization vector - [[file:mrcal-python-api-reference.html#-num_states_points][=mrcal.num_states_points()=]]: Get the number of point-position parameters in the optimization vector - [[file:mrcal-python-api-reference.html#-num_states_calobject_warp][=mrcal.num_states_calobject_warp()=]]: Get the number of parameters in the optimization vector for the board warp - [[file:mrcal-python-api-reference.html#-num_intrinsics_optimization_params][=mrcal.num_intrinsics_optimization_params()=]]: Get the number of intrinsics parameters to describe /one/ camera - [[file:mrcal-python-api-reference.html#-measurement_index_boards][=mrcal.measurement_index_boards()=]]: Return the measurement index of the start of a given board observation - [[file:mrcal-python-api-reference.html#-measurement_index_points][=mrcal.measurement_index_points()=]]: Return the measurement index of the start of a given point observation - [[file:mrcal-python-api-reference.html#-measurement_index_regularization][=mrcal.measurement_index_regularization()=]]: Return the index of the start of the regularization measurements - [[file:mrcal-python-api-reference.html#-num_measurements_boards][=mrcal.num_measurements_boards()=]]: Return how many measurements we have from calibration object observations - [[file:mrcal-python-api-reference.html#-num_measurements_points][=mrcal.num_measurements_points()=]]: Return how many measurements we have from point observations - [[file:mrcal-python-api-reference.html#-num_measurements_regularization][=mrcal.num_measurements_regularization()=]]: Return how many measurements we have from regularization - [[file:mrcal-python-api-reference.html#-num_measurements][=mrcal.num_measurements()=]]: Return how many measurements we have in the full optimization problem - [[file:mrcal-python-api-reference.html#-num_states][=mrcal.num_states()=]]: Get the total number of parameters in the optimization vector * State packing The optimization routine works in the [[file:formulation.org::#state-packing][space of scaled parameters]], and several functions are available to pack/unpack the state vector $\vec b$. - [[file:mrcal-python-api-reference.html#-pack_state][=mrcal.pack_state()=]]: Scales a state vector to the packed, unitless form used by the optimizer - [[file:mrcal-python-api-reference.html#-unpack_state][=mrcal.unpack_state()=]]: Scales a state vector from the packed, unitless form used by the optimizer - [[file:mrcal-python-api-reference.html#-ingest_packed_state][=mrcal.ingest_packed_state()=]]: Read a given packed state into optimization_inputs * Optimization Direct interfaces to the [[file:formulation.org][mrcal optimizer]]. - [[file:mrcal-python-api-reference.html#-optimize][=mrcal.optimize()=]]: Invoke the calibration routine - [[file:mrcal-python-api-reference.html#-optimizer_callback][=mrcal.optimizer_callback()=]]: Call the optimization callback function * Camera model reading/writing The [[file:mrcal-python-api-reference.html#cameramodel][=mrcal.cameramodel=]] class provides functionality to read/write models from/to files on disk. Both the =.cameramodel= and =.cahvor= file formats are supported, choosing the proper one, depending on the given filename. When reading a pipe (no filename known), both formats are tried. If writing to a pipe, the =.cameramodel= format is chosen, unless =.cahvor= is requested via the arguments. The available methods: - [[file:mrcal-python-api-reference.html#cameramodel-__init__][=mrcal.cameramodel.__init__()=]]: Read a model from a file on disk, or construct from the data given in the arguments. - [[file:mrcal-python-api-reference.html#cameramodel-write][=mrcal.cameramodel.write()=]]: Write out this camera-model to a file - [[file:mrcal-python-api-reference.html#cameramodel-intrinsics][=mrcal.cameramodel.intrinsics()=]]: Get or set the intrinsics in this model - [[file:mrcal-python-api-reference.html#cameramodel-extrinsics_rt_toref][=mrcal.cameramodel.extrinsics_rt_toref()=]]: Get or set the extrinsics in this model - [[file:mrcal-python-api-reference.html#cameramodel-extrinsics_rt_fromref][=mrcal.cameramodel.extrinsics_rt_fromref()=]]: Get or set the extrinsics in this model - [[file:mrcal-python-api-reference.html#cameramodel-extrinsics_Rt_toref][=mrcal.cameramodel.extrinsics_Rt_toref()=]]: Get or set the extrinsics in this model - [[file:mrcal-python-api-reference.html#cameramodel-extrinsics_Rt_fromref][=mrcal.cameramodel.extrinsics_Rt_fromref()=]]: Get or set the extrinsics in this model - [[file:mrcal-python-api-reference.html#cameramodel-imagersize][=mrcal.cameramodel.imagersize()=]]: Get the imagersize in this model - [[file:mrcal-python-api-reference.html#cameramodel-valid_intrinsics_region][=mrcal.cameramodel.valid_intrinsics_region()=]]: Get or set the valid intrinsics region - [[file:mrcal-python-api-reference.html#cameramodel-optimization_inputs][=mrcal.cameramodel.optimization_inputs()=]]: Get the original optimization inputs. Used for uncertainty evaluation or other analysis - [[file:mrcal-python-api-reference.html#cameramodel-icam_intrinsics][=mrcal.cameramodel.icam_intrinsics()=]]: Get the camera index indentifying this camera at optimization time. Used in conjunction with [[file:mrcal-python-api-reference.html#cameramodel-optimization_inputs][=mrcal.cameramodel.optimization_inputs()=]] * Image reading/writing mrcal includes simple functions for reading/writing images. These aren't interesting, or better than any other functions you may have already. These exist because they're faster than loading the opencv module and to make life easy for those that don't already have other functions handy. - [[file:mrcal-python-api-reference.html#-load_image][=mrcal.load_image()=]]: load an image from a file on disk into a numpy array - [[file:mrcal-python-api-reference.html#-save_image][=mrcal.save_image()=]]: save an image in a numpy array to a file on disk * Miscellaneous utilities - [[file:mrcal-python-api-reference.html#-hypothesis_board_corner_positions][=mrcal.hypothesis_board_corner_positions()=]]: Reports the coordinates of chessboard points, as predicted by the optimization state - [[file:mrcal-python-api-reference.html#-polygon_difference][=mrcal.polygon_difference()=]]: Return the difference of two closed polygons - [[file:mrcal-python-api-reference.html#-mapping_file_framenocameraindex][=mrcal.mapping_file_framenocameraindex()=]]: Parse image filenames to get the frame numbers - [[file:mrcal-python-api-reference.html#-close_contour][=mrcal.close_contour()=]]: Close a polyline, if it isn't already closed - [[file:mrcal-python-api-reference.html#-apply_homography][=mrcal.apply_homography()=]]: Apply a homogeneous-coordinate homography to a set of 2D points - [[file:mrcal-python-api-reference.html#-corresponding_icam_extrinsics][=mrcal.corresponding_icam_extrinsics()=]]: Return the icam_extrinsics corresponding to a given icam_intrinsics - [[file:mrcal-python-api-reference.html#-residuals_board][=mrcal.residuals_board()=]]: Compute and return the chessboard residuals - [[file:mrcal-python-api-reference.html#-residuals_point][=mrcal.residuals_point()=]]: Compute and return the discrete point residuals - [[file:mrcal-python-api-reference.html#-sorted_eig][=mrcal.sorted_eig()=]]: Compute eigenvalues, eigenvectors; sorted results returned mrcal-2.4.1/doc/recipes.org000066400000000000000000001372561456301662300155500ustar00rootroot00000000000000#+TITLE: Recipes #+OPTIONS: toc:t * Using a non-mrgingham corner detector or a non-chessboard :PROPERTIES: :CUSTOM_ID: non-mrgingham-detector :END: While in my day-to-day work I use /chessboards/ and process images of them using the [[https://github.com/dkogan/mrgingham][mrgingham]] chessboard corner detector, this isn't a requirement. In fact, mrcal doesn't care at all where its detections come from. The only requirements on the calibration object are that - The calibration object is nominally planar; small amounts of [[file:formulation.org::#board-deformation][deformation]] are allowed - The object contains a /regular/ grid of points. Gaps are allowed, but the points that do exist must lie on this grid - The grid spacing is identical in the horizontal and vertical directions - Each point in the object is uniquely identifiable in each observation of the object It's /not/ required that all points are observed in every image of the object: partial observations of the board are supported by mrcal (mrgingham won't detect those, but mrcal has no problem ingesting incomplete views). And boards that don't contain a full grid are supported as well. For instance here's [[https://github.com/dkogan/mrcal/issues/4][a bug report]] where somebody used a calibration board with an unrelated fiducial in the middle. To use a grid detector other than mrgingham, we need to - produce a compatible =corners.vnl= file. This is a [[https://www.github.com/dkogan/vnlog][=vnlog=]] (text table) where each row describes a single corner detection - feed this file to [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras --corners-cache=]] A sample =corners.vnl= describing observations of a toy 2x2 chessboard: #+begin_example # filename x y weight frame0-cam0.jpg 10.2 12.5 1.0 frame0-cam0.jpg 21.2 15.1 1.0 frame0-cam0.jpg 9.4 19.5 0.5 frame0-cam0.jpg 21.3 23.6 1.0 frame0-cam1.jpg - - - frame1-cam0.jpg - - - frame1-cam1.jpg 30.1 39.6 0.25 frame1-cam1.jpg 45.8 38.5 1.0 frame1-cam1.jpg - - - frame1-cam1.jpg 42.5 47.4 1.0 #+end_example Whitespace added for clarity. Here we have 2 cameras and 2 frames. Only =frame0-cam0.jpg= and =frame1-cam1.jpg= have a chessboard detection, with one of the corners missing in =frame1-cam1.jpg=. The =corners.vnl= file contains 3 or 4 columns. The first 3 columns are: - =filename=: a path to the image on disk - =x=, =y=: pixel coordinates of a detected corner in the If a 4th column is present, it describes the detector's confidence in the detection of that particular corner. It may be either - =level=: the decimation level of the detected corner. If the detector needed to cut down the image resolution to find this corner, we report that resolution here. Level-0 means "full-resolution", level-1 means "half-resolution", level-2 means "quarter-resolution" and so on. A level of =-= or <0 means "skip this point"; this is how incomplete board observations are specified. This "decimation level" interpretation is the [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras=]] default. This column is reported by mrgingham - =weight=: how strongly to weight that corner. More confident detections take stronger weights. This should be inversely proportional to the standard deviation of the detected pixel coordinates. With decimation levels we have $\mathrm{weight} = 2^{-\mathrm{level}}$. As before, a weight of =-= or <0 means "skip this point"; this is how incomplete board observations are specified. Select this "weight" interpretation with =mrcal-calibrate-cameras --corners-cache-has-weights= If no 4th column is present, we assume an even weight of 1.0 for all the points. The whole chessboard is described by a sequence of these corner detections, listed in a /consistent/ grid order: the first row is traversed point-by-point in order, then the second row, and so on. Each chessboard image is represented by either /exactly/ $N_\mathrm{width} N_\mathrm{height}$ corner records or a single record #+begin_example FILENAME - - - #+end_example to represent images with no detected corners. An image with incomplete detections should /still/ contain $N_\mathrm{width} N_\mathrm{height}$ records in the same consistent order. The missing corners should be given with any =x=, =y=, but with $\mathrm{weight} \leq 0$ or =-=. The record could also be completely null: #+begin_example FILENAME - - - #+end_example The missing points are treated as outliers by the solver. Currently the diagnostics included these points as outliers as well, although that will likely change in the future. * Using mrgingham with rotated cameras :PROPERTIES: :CUSTOM_ID: calibrating-upside-down :END: The [[https://github.com/dkogan/mrgingham][mrgingham corner detector]] is the tool I use to detect corners in images of chessboards (although [[#non-mrgingham-detector][other methods are available]]). mrgingham looks for plain chessboards in the images, without any extra fiducials. It reports the corners in the top-most horizontal row in order from left to right. Then the next row down, and the next row, and so on. Here "top", "left" and "right" are the pixel coordinates in the image. The position of each corner in this list uniquely identifies the corner. So the corner in row $i$, col $j$ always appears at index $i N_\mathrm{width} + j$ in the list. This works well, as long as the "horizontal" and "vertical" directions in the image are consistent, which they usually are. However, if the camera orientation isn't identical across cameras or across time, issues can arise. Consider a 2-camera calibration where one camera is mounted rightside-up, but the other is mounted upside-down. Here the first corner reported in the left camera is the top-left corner in the chessboard, but the first corner reported in the right camera is the bottom-right corner in the chessboard. The first reported corner has index 0, so it must represent the same corner for all cameras, but here it does not. In the very common situation where the cameras are all mounted right-side-up or sideways or upside-down we can handle this situation by reordering the corners in a mrgingham corners list. This is done by the [[https://github.com/dkogan/mrgingham/mrgingham-rotate-corners][=mrgingham-rotate-corners= tool]]. The usage is simple: #+begin_src sh < corners.vnl \ mrgingham-rotate-corners [--gridn N] \ --90 REGEX_CAM_90deg \ --180 REGEX_CAM_180deg \ --270 REGEX_CAM_270deg \ [... more rotation selections ...] \ > corners-rotated.vnl #+end_src We pass in the =corners.vnl= set of detections. Filenames that were captured by a camera rotated by 90deg are selected by =REGEX_CAM_90deg= and so on. The result is a =corners-rotated.vnl= with reordered corners that meet the assumptions of the solver, and can be passed to [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras=]]. Another example: #+begin_src sh # camera A is rightside-up # camera B is mounted sideways # cameras C,D are upside-down mrgingham --gridn N \ 'frame*-cameraA.jpg' \ 'frame*-cameraB.jpg' \ 'frame*-cameraC.jpg' \ 'frame*-cameraD.jpg' | \ mrgingham-rotate-corners \ --gridn N \ --90 cameraB \ --180 'camera[CD]' \ > corners-rotated.vnl #+end_src * Chessboard-less calibration with surveyed chessboards :PROPERTIES: :CUSTOM_ID: surveyed-calibration :END: Usually cameras are calibrated by observing a moving calibration object with stationary cameras. This is not the only possible scheme, and mrcal supports others. A /surveyed/ calibration is one where the poses of the objects being observed are pre-determined (by surveying them, for instance). Then we get a simplified calibration problem: - Each point in space being observed has a fixed position. This is assumed to be known perfectly - The camera is stationary, with a non-fixed pose: we solve for it - Only monocular solves are necessary. Since the objects being observed are fixed, there is no interaction between the multiple cameras being calibrated, and a multi-camera surveyed calibration can be solved by computing several independent monocular calibrations. Furthermore, it doesn't matter if we're observing chessboards or discrete points or both: everything being observed has a known, fixed position. So when solving these problems we call =mrcal.optimize(...)= with - /Fixed/ =frames_rt_toref= and =points= arrays localizing the observed objects - =do_optimize_frames = False= to tell the optimization to fix them in space Calibrating in this way is uncommon, so the [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras= tool]] does not support this directly. But this kind of solve is readily available via the [[file:python-api.org][Python APIs]], as demonstrated by the [[https://www.github.com/dkogan/mrcal/blob/master/test/test-surveyed-calibration.py][=test/test-surveyed-calibration.py=]] script: #+begin_src sh test/test-surveyed-calibration.py \ --do-sample \ --make-documentation-plots '' #+end_src #+begin_src sh :exports none :eval no-export ## The below figures made like this D=../mrcal-doc-external/figures/surveyed-calibration/ mkdir -p $D test/test-surveyed-calibration.py \ --do-sample \ --make-documentation-plots $D #+end_src This script simulates 3 observed chessboards in front of the camera. A long lens is used with a lean lens model ([[file:lensmodels.org::#lensmodel-opencv][=LENSMODEL_OPENCV4=]]). We capture a single frame. The observed image looks like this: [[file:external/figures/surveyed-calibration/observations.svg]] Here we're looking at chessboards, but the observations are given to mrcal as discrete points for flexibility; we could use fixed chessboards identically. This setup is clearly violating the [[file:how-to-calibrate.org::#dancing][usual guidelines for capturing calibration data]]: we have a too-lean lens model, and we're not covering the imager with data. This is still useful to illustrate the processing, however. And this isn't far off from how somebody might capture data for a surveyed calibration. These kinds of solves usually work off far less data than the usual moving-chessboard calibrations, so they are more susceptible to [[file:uncertainty.org][sampling error causing high projection uncertainty]]. Fortunately, the techniques that we have for analyzing calibration quality ([[file:uncertainty.org][projection uncertainty quantification]] and [[file:tour-cross-validation.org][cross-validation differencing]]) are available here, so we can see how good or bad the results are. Note: today mrcal supports computing the uncertainty of a chessboard-less calibration /only/ if the points are fixed, as they are here; this will be implemented fully in the future. Similarly to the simulations in the [[file:tour-uncertainty.org][tour of mrcal]], we show that the predicted projection uncertainty matches what we get from sampling the input noise multiple times: [[file:external/figures/surveyed-calibration/var-q.svg]] We also looked at the effect of input noise on the extrinsics. The error in solved $z$ in camera coordinates: [[file:external/figures/surveyed-calibration/var-errz.svg]] Clearly the uncertainty propagation logic is working. Note: today's discrete point handling in mrcal has extra factors that generate this warning when computing an uncertainty: #+begin_example WARNING: I'm currently treating the point range normalization (penalty) terms as following the same noise model as other measurements. This will bias the uncertainty estimate #+end_example This is benign, and the related logic is likely to change in the future. The usual rule-of-thumb is to gather calibration data at multiple ranges because it is otherwise difficult to disentangle the effects of camera position from the effects of intrinsics. We can demonstrate this explicitly using the same test script: we solve the same calibration problem, with the range to the center chessboard varying. #+begin_src sh for z (4 5 8 9 9.5 10 10.5 11 15 20 30) { test/test-surveyed-calibration.py \ --only-report-uncertainty \ --range-board 10 \ --range-board-center $z 2>/dev/null } \ | vnl-filter -p z-center,stdev \ | feedgnuplot \ --domain \ --vnl \ --autolegend \ --y2 'stdev(errz)' \ --ymin 0 \ --y2min 0 \ --lines \ --points \ --xlabel 'Distance to the middle chessboard (m)' \ --ylabel 'Reprojection error (pixels)' \ --y2label 'Position error in z (m)' \ --legend 'stdev(q)' 'Standard deviation of reprojection at infinity' \ --legend 'stdev(errz)' 'Standard deviation of the error in z' \ --title 'Surveyed calibration: effect of camera range variability; 2 cameras at 10m, one variable' #+end_src #+begin_src sh :exports none :eval no-export for z (4 5 8 9 9.5 10 10.5 11 15 20 30) { test/test-surveyed-calibration.py \ --only-report-uncertainty \ --range-board 10 \ --range-board-center $z 2>/dev/null } \ | awk '/#/ && !legend {print; legend=1;} !/#/ {print}' \ | vnl-align \ | tee /tmp/surveyed-calibration-single.vnl D=~/projects/mrcal-doc-external/figures/surveyed-calibration mkdir -p $D < /tmp/surveyed-calibration-single.vnl \ vnl-filter -p z-center,stdev \ | feedgnuplot \ --domain \ --vnl \ --autolegend \ --y2 'stdev(errz)' \ --ymin 0 \ --y2min 0 \ --lines \ --points \ --xlabel 'Distance to the middle chessboard (m)' \ --ylabel 'Reprojection error (pixels)' \ --y2label 'Position error in z (m)' \ --legend 'stdev(q)' 'Standard deviation of reprojection at infinity' \ --legend 'stdev(errz)' 'Standard deviation of the error in z' \ --title 'Surveyed calibration: effect of camera range variability; 2 cameras at 10m, one variable' \ --hardcopy $D/moving-range-single.svg \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' > /dev/null #+end_src #+begin_src sh :exports none :eval no-export ## results: one observation # z-bulk z-center stdev(q) stdev(errz) 10.0 4.0 0.3537 0.0021 10.0 5.0 0.4851 0.0035 10.0 8.0 1.7751 0.0176 10.0 9.0 3.9342 0.0412 10.0 9.5 7.9519 0.0839 10.0 10.0 76.4639 0.6743 10.0 10.5 11.3296 0.1387 10.0 11.0 5.6793 0.0684 10.0 15.0 1.7219 0.0222 10.0 20.0 1.3979 0.0189 10.0 30.0 1.4779 0.0205 #+end_src [[file:external/figures/surveyed-calibration/moving-range-single.svg]] So when all 3 chessboards sit at 10m out, we get far worse uncertainties in both the projection behavior and position estimates defined by the calibration. When running the standard moving-chessboard calibration we have an [[file:tour-choreography.org::#tilt][analogous effect when we consider tilting the chessboard to the camera]]: chessboard tilt creates the variable ranges required for a well-defined solve. In our scenario here, the issue is high sampling error causing a high projection uncertainty. One way to mitigate this problem is by gathering more data. Even if everything is stationary, and we capture multiple images of the same stationary scene, we are still capturing multiple samples of the input noise. In theory. If we capture $N$ times more data, the expected uncertainty improvement is $\sqrt{N}$. Let's try it by passing the =--oversample 10= option: #+begin_src sh for z (4 5 8 9 9.5 10 10.5 11 15 20 30) { test/test-surveyed-calibration.py \ --oversample 10 \ --only-report-uncertainty \ --range-board 10 \ --range-board-center $z 2>/dev/null } \ | vnl-filter -p z-center,stdev \ | feedgnuplot \ --domain \ --vnl \ --autolegend \ --y2 'stdev(errz)' \ --ymin 0 \ --y2min 0 \ --lines \ --points \ --xlabel 'Distance to the middle chessboard (m)' \ --ylabel 'Reprojection error (pixels)' \ --y2label 'Position error in z (m)' \ --legend 'stdev(q)' 'Standard deviation of reprojection at infinity' \ --legend 'stdev(errz)' 'Standard deviation of the error in z' \ --title 'Surveyed calibration: effect of camera range variability; 2 cameras at 10m, one variable; 10x oversampling' #+end_src #+begin_src sh :exports none :eval no-export for z (4 5 8 9 9.5 10 10.5 11 15 20 30) { test/test-surveyed-calibration.py \ --oversample 10 \ --only-report-uncertainty \ --range-board 10 \ --range-board-center $z 2>/dev/null } \ | awk '/#/ && !legend {print; legend=1;} !/#/ {print}' \ | vnl-align \ | tee /tmp/surveyed-calibration-oversampled.vnl D=~/projects/mrcal-doc-external/figures/surveyed-calibration mkdir -p $D < /tmp/surveyed-calibration-oversampled.vnl \ vnl-filter -p z-center,stdev \ | feedgnuplot \ --domain \ --vnl \ --autolegend \ --y2 'stdev(errz)' \ --ymin 0 \ --y2min 0 \ --lines \ --points \ --xlabel 'Distance to the middle chessboard (m)' \ --ylabel 'Reprojection error (pixels)' \ --y2label 'Position error in z (m)' \ --legend 'stdev(q)' 'Standard deviation of reprojection at infinity' \ --legend 'stdev(errz)' 'Standard deviation of the error in z' \ --title 'Surveyed calibration: effect of camera range variability; 2 cameras at 10m, one variable; 10x oversampling' \ --hardcopy $D/moving-range-oversampled.svg \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' > /dev/null #+end_src #+begin_src sh :exports none :eval no-export ## results: 10 observations # z-bulk z-center stdev(q) stdev(errz) 10.0 4.0 0.1158 0.0006 10.0 5.0 0.1593 0.0011 10.0 8.0 0.5708 0.0055 10.0 9.0 1.2551 0.0128 10.0 9.5 2.5246 0.0259 10.0 10.0 24.5037 0.2080 10.0 10.5 3.6249 0.0442 10.0 11.0 1.8052 0.0215 10.0 15.0 0.5407 0.0069 10.0 20.0 0.4369 0.0059 10.0 30.0 0.4607 0.0064 #+end_src [[file:external/figures/surveyed-calibration/moving-range-oversampled.svg]] And it works as expected: we still see the spike, but all the uncertainties are roughly a factor or $\sqrt{10} = 3.2$ smaller. Note that this works if the input noise is truly gaussian and independent. Empirically, this is mostly true, but may not be 100% true. Techniques that rely heavily on this assumption, such as this one, may not work perfectly in the real world. Take these results with a grain of salt. * Stability of intrinsics :PROPERTIES: :CUSTOM_ID: lens-stability :END: When we calibrate a camera system, we're assuming that the physical properties of the system are fixed. If they weren't, then even a very accurate calibration isn't useful: the system may have changed by the time we actually use the computed calibration. We must try to stabilize all parts of the system prior to calibrating, and then we can check to see how well we did. In the [[file:tour.org][tour of mrcal]] we used a Samyang 12mm F2.8 fisheye lens. This is not a machine-vision lens; it's intended to be used by human photographers operating an SLR camera. As a result, it has moving parts. In particular, the human-operated focus ring engages an internal mechanism that physically moves the front lens element. Immobilizing the external focus ring does /not/ immobilize the internal mechanism, so any mechanical backlash shows up as an instability in intrinsics. From experience, I know that this lens is sensitive to mechanical motion, and we can clearly see this in the data. For the [[file:tour.org][tour of mrcal]] I gathered two independent sets of chessboard images one after another, without moving anything. This was used for [[file:tour-cross-validation.org][cross-validation]], and resulted in this diff: [[file:external/figures/cross-validation/diff-cross-validation-splined-noncentral.png]] Then I moved the camera and tripod over by 2m or so, and gathered more chessboard images. Comparing these with the previous set showed a clear shift in the intrinsics: #+begin_src sh :exports none :eval no-export mkdir -p ~/projects/mrcal-doc-external/figures/lens-stability/ D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/ function c { < $1 ~/projects/mrcal-noncentral/analyses/noncentral/centralize.py 3 } mrcal-show-projection-diff \ --no-uncertainties \ --radius 500 \ --cbmax 2 \ --unset key \ <(c $D/3-*/splined-noncentral.cameramodel) \ <(c $D/4-*/splined-noncentral.cameramodel) \ --hardcopy ~/projects/mrcal-doc-external/figures/lens-stability/diff-dance34-splined-noncentral.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' #+end_src [[file:external/figures/lens-stability/diff-dance34-splined-noncentral.png]] This was from just carefully moving the tripod. To be clear: this isn't a /bad/ lens, it's just not built with high-accuracy machine vision in mind. A lens intended for machine vision applications would do better. If we had to use /this/ lens, I would gather multiple sets of data before and after stressing the system (shaking, flipping, heating, etc). Then the resulting diffs would tell us how much to trust the calibration. * Stability of extrinsics Similarly to [[#lens-stability][the above discussion about the stability of lens intrinsics]], we sometimes want to consider the stability of the camera-camera geometric transformation in a multi-camera system. For instance, it's possible to have a multi-camera system composed of very stable lenses mounted on a not-rigid-enough mount. Any mechanical stresses wouldn't affect the intrinsics, but the extrinsics /would/ shift. Evaluation of this motion is described on the [[file:differencing.org::*Extrinsics differences][differencing page]]. * Converting lens models :PROPERTIES: :CUSTOM_ID: convert-lensmodel :END: It is often useful to convert a camera model utilizing one lens model to use another one. For instance when [[#interoperating-with-too-lean-model][using a calibration in an existing system that doesn't support the model we have]]. This is a common need, so a standalone tool is available for this task: [[file:mrcal-convert-lensmodel.html][=mrcal-convert-lensmodel=]]. Two modes are available: 1. If the given cameramodel file contains =optimization_inputs=, then we have all the data that was used to compute this model in the first place, and we can re-run the original optimization, using the new lens model. This is the default behavior, and is the preferred choice. However it can only work with models that were computed by mrcal originally. 2. We can sample a grid of points on the imager, unproject them to observation vectors in the camera coordinate system, and then fit a new camera model that reprojects these vectors as closely to the original pixel coordinates as possible. This can be applied to models that didn't come from mrcal. Select this mode by passing =--sampled=. Since camera models (lens parameters /and/ geometry) are computed off real pixel observations, the confidence of the projections varies greatly across the imager and across observation distances. The first method uses the original data, so it implicitly respects these uncertainties: uncertain areas in the original model will be uncertain in the new model as well. The second method, however, doesn't have this information: it doesn't know which parts of the imager and space are reliable, so the results suffer. As always, the [[file:differencing.org::#implied-transformation][intrinsics have some baked-in geometry information]]. Both methods optimize intrinsics /and/ extrinsics, and output cameramodels with updated versions of both. If =--sampled=: we can request that only the intrinsics be optimized by passing =--intrinsics-only=. Also, if =--sampled= and not =--intrinsics-only=: we fit the extrinsics off 3D points, not just observation directions. The distance from the camera to the points is set by =--distance=. This can take a comma-separated list of distances to use. It's /strongly/ recommended to ask for two different distances: - A "near" distance: where we expect the intrinsics to have the most accuracy. At the range of the chessboards, usually - A "far" distance: at "infinity". A few km is good usually. The reason for this is that =--sampled= solves at a single distance aren't sufficiently constrained, similar to the issues that result from a [[#surveyed-calibration][surveyed calibration]] of chessboards all at the same range. If we ask for a single far distance: =--distance 1000= for instance, we can easily get an extrinsics shift of 100m. This is aphysical: changing the intrinsics could shift the camera origin by a few mm, but not 100m. Conceptually we want to perform a rotation-only extrinsics solve, but this isn't yet implemented. Passing both a near and far distance appears to constrain the extrinsics well in practice. The computed extrinsics transform is printed on the console, with a warning if an aphysical shift was computed. Do pay attention to the console output. Some more tool-specific documentation are available in the documentation in [[file:mrcal-convert-lensmodel.html][=mrcal-convert-lensmodel=]]. * Interoperating with other tools Any application that uses camera models is composed of multiple steps, some of which would benefit from mrcal-specific logic. Specifically: 1. For successful long-range triangulation or stereo we need maximum precision in our lens models. mrcal supports [[file:splined-models.org][=LENSMODEL_SPLINED_STEREOGRAPHIC=]]: a rich model that fits real-world lenses better than the lean models used by other tools. This is great, but as of today, mrcal is the only library that knows how to use these models. 2. Furthermore, mrcal can use [[file:stereo.org::#stereo-rectification-models][=LENSMODEL_LATLON=]] to describe the rectified system instead of the more traditional [[file:stereo.org::#stereo-rectification-models][=LENSMODEL_PINHOLE= rectification function]]. This allows for nice stereo matching even with wide lenses, but once again: these rectified models and images can only be processed with mrcal. A common need is to use mrcal's improved methods in projects built around legacy stereo processing. This usually means selecting specific chunks of mrcal to utilize, and making sure they can function as part of the existing framework. Some relevant notes follow. ** Utilizing a too-lean production model :PROPERTIES: :CUSTOM_ID: interoperating-with-too-lean-model :END: You can create /very/ accurate models with [[file:splined-models.org][=LENSMODEL_SPLINED_STEREOGRAPHIC=]]: these have very low [[file:uncertainty.org][projection uncertainty]] and [[file:tour-cross-validation.org][cross-validation diffs]]. Even if these models are not supported in the production system, it is worth solving with them to serve as a ground truth. If we calibrated with [[file:splined-models.org][=LENSMODEL_SPLINED_STEREOGRAPHIC=]] to get a ground truth, we can recalibrate using the same data for whatever model is supported. A [[file:differencing.org][difference]] can be computed to estimate the projection errors we expect from this production lens model. There's a trade-off between how well the production model fits and how much data is included in the calibration: the fit is usually good near the center, with the errors [[file:differencing.org::#fitting-data-selection][increasing as we include more and more of the imager towards the corners]]. If we only care about a region in the center, we should cull the unneeded points with, for instance, the [[file:mrcal-cull-corners.html][=mrcal-cull-corners=]] tool. This would make the production model fit better in the area we care about. Keep in mind that these lens-model errors are correlated with each other when we look at observations across the imager. And these errors are present in each observation, so they're correlated across time as well. So these errors will /not/ average out, and they will produce a bias in whatever ultimately uses these observations. To be certain about how much error results from the production lens model alone, you can [[file:how-to-calibrate.org::#residuals][generate perfect data using the splined solve, and reoptimize it with the production model]]. This reports unambiguously the error due to the lens-model-fitting issues in isolation. ** Reprojecting to a lean production model It is possible to use a lean camera model /and/ get the full accuracy of [[file:splined-models.org][=LENSMODEL_SPLINED_STEREOGRAPHIC=]] if we spend a bit of computation time: 1. Calibrate with [[file:splined-models.org][=LENSMODEL_SPLINED_STEREOGRAPHIC=]] to get a high-fidelity result 2. Compute an acceptable production model that is close-ish to the ground truth. This doesn't need to be perfect 3. During operation of the system, reproject each captured image from the splined model to the production model using, for instance, the [[file:mrcal-reproject-image.html][=mrcal-reproject-image=]] tool. 4. Everything downstream of the image capture should be given the production model and the reprojected image The (production model, reprojected image) pair describes the same scene as the (splined model, captured image) pair. So we can use a simple production model /and/ get a high-quality calibration produced with the splined model. The downsides of doing this are the quantization errors that result from resampling the input image and the computation time. If we don't care about computation time at all, the production model can use a higher resolution than the original image, which would reduce the quantization errors. ** Using the [[file:stereo.org::#stereo-rectification-models][=LENSMODEL_LATLON= rectification model]] To utilize the wide-lens-friendly [[file:stereo.org::#stereo-rectification-models][=LENSMODEL_LATLON= rectification model]], mrcal must be involved in computing the rectified system and in converting disparity values to ranges. There's usually little reason for the application to use the rectified models and disparities for anything other than computing ranges, so swapping in the mrcal logic here usually isn't effortful. So the sequence would be: 1. mrcal computes the rectified system 2. Camera images reprojected to the rectified models. This could be done by any tool 3. Stereo matching to produce disparities. This could be done by any tool 4. mrcal converts disparities to ranges and to a point cloud 5. The point cloud is ingested the the system to continue processing * Visualizing post-solve chessboard observations :PROPERTIES: :CUSTOM_ID: reproject-to-chessboard :END: mrcal is primarily a geometric toolkit: after we [[file:how-to-calibrate.org::#corner-detector][detect the chessboard corners]], we never look at the chessboard images again, and do /everything/ with the detected corner coordinates. This assumes the chessboard detector works perfectly. At least for [[https://github.com/dkogan/mrgingham/][=mrgingham=]], this is a close-enough assumption; but it's nice to be able to double-check. To do that the mrcal sources include the [[https://www.github.com/dkogan/mrcal/blob/master/analyses/mrcal-reproject-to-chessboard][=mrcal-reproject-to-chessboard= tool]]; this is still experimental, so it's not included in a mrcal installation, and currently has to be invoked from source. This tool takes in completed calibration, and reprojects each chessboard image to a chessboard-referenced space: each resulting image shows just the chessboard, with each chessboard corner appearing at exactly the same pixel in each image. Example frame from the [[file:tour.org][tour of mrcal]]: #+begin_src sh analyses/mrcal-reproject-to-chessboard \ --image-path-prefix images \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export Dout=~/projects/mrcal-doc-external/figures/reprojected-to-chessboard mkdir -p $Dout D=/home/dima/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/3-f22-infinity/; analyses/mrcal-reproject-to-chessboard \ --image-path-prefix $D/images \ --outdir $Dout \ $D/splined.cameramodel ffmpeg \ -r 5 -f image2 -export_path_metadata 1 \ -pattern_type glob -i "$Dout/DSC*.JPG" \ -filter:v "drawtext=text='%{metadata\\:lavf.image2dec.source_basename}':fontcolor=yellow:fontsize=48" \ -y \ $Dout/reprojected-to-chessboard.mp4 #+end_src [[file:external/figures/reprojected-to-chessboard/DSC06155.JPG]] This is a sample frame from [[file:external/figures/reprojected-to-chessboard/reprojected-to-chessboard.mp4][the full animation]] of [[file:external/figures/reprojected-to-chessboard/][these images]]. The red circles indicate corner observations classified as outliers by the solver. Ideally every reprojected image should be very similar, with each chessboard corner randomly, and independently jumping around a tiny bit (by the amount reported in the [[file:tour-initial-calibration.org::#opencv8-solve-diagnostics][fit residuals]]). If the detector had any issues or an image was faulty in some way, this would be clearly seen by eyeballing the sequence of images. The whole image would shift; or a single non-outlier corner would jump. It's good to eyeball these animations as a final sanity check before accepting a calibration. For questionable calibration objects (such as grids of circles or AprilTags), checking this is /essential/ to discover biases in these implicit detectors. * Visualizing camera resolution :PROPERTIES: :CUSTOM_ID: visualizing-resolution :END: Ignoring [[file:formulation.org::#lens-behavior][noncentral effects]] very close to the lens, a camera model maps directions in space to pixel coordinates, with each pixel covering a solid angle of some size. As sensor resolutions increase, the pixels become finer, covering smaller solid angles. For various processing it is often useful to visualize this angular resolution of a camera. For instance to justify using geometric-only techniques, such as the [[file:triangulation.org][triangulation methods]]. mrcal provides the [[https://www.github.com/dkogan/mrcal/blob/master/analyses/mrcal-show-model-resolution.py][=analyses/mrcal-show-model-resolution.py=]] tool to do this. This tool isn't yet "released", so it is not yet part of the installed set, and must be run from the source tree. A sample visualization of the lens from the [[file:tour.org][tour of mrcal]]: #+begin_src sh analyses/mrcal-show-model-resolution.py \ --title "Mean angular resolution (deg/pixel) over the imager" \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/figures/resolution mkdir -p $D PYTHONPATH=$PWD \ analyses/mrcal-show-model-resolution.py \ --title "Mean angular resolution (deg/pixel) over the imager" \ --unset key \ --hardcopy $D/splined-resolution.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' \ mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/3-f22-infinity/splined.cameramodel #+end_src [[file:external/figures/resolution/splined-resolution.png]] So as we move outwards, each pixel covers less space. Note that at each pixel the projection behavior isn't necessarily isotropic: the resolution may be different if looking in different directions. The current implementation of the tool /does/ assume isotropic behavior, however, and it displays the mean resolution. * Estimating ranging errors caused by calibration errors Any particular application has requirements for how accurate the mapping and/or localization need to be. [[file:triangulation.org][Triangulation accuracy scales with the square of range]], so performance will be strongly scene-dependent. But we can use mrcal to quickly get a ballpark estimate of how well we can hope to do. Let's look back at the [[file:tour-initial-calibration.org][tour of mrcal]]. We saw that using [[file:lensmodels.org::#lensmodel-opencv][=LENSMODEL_OPENCV8=]] was insufficient, and resulted in these projection errors: #+begin_src sh mrcal-show-projection-diff \ --unset key \ opencv8.cameramodel \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export # THIS IS GENERATED IN tour-differencing.org #+end_src [[file:external/figures/diff/diff-splined-opencv8.png]] Let's say the lens model error is 0.5 pixels per camera (I'm looking at a rough median of the plots). So at worst, two cameras give us double that: 1.0 pixel error. At worst this applies to disparity directly, so let's assume that. Noise in stereo matching is usually on the order of 0.3 pixels, so we're going to have on the order of 1.0 + 0.3 = 1.3 pixels of disparity error. Let's see how significant this is. Let's once again go back to [[file:tour-stereo.org][tour of mrcal, this time to its stereo matching page]]. How would 1.3 pixels of disparity error affect that scene? Let's find out. We write a little bit of Python code to rerun the stereo processing, focusing on a section of the scene, for clarity. #+begin_src python #!/usr/bin/python3 import sys import os import numpy as np import numpysane as nps import mrcal import cv2 import gnuplotlib as gp model_filenames = [ f"{i}.cameramodel" for i in (0,1) ] image_filenames = [ f"{i}.jpg" for i in (0,1) ] az_fov_deg = 32.4 el_fov_deg = 24.9 az0_deg = -20.2 el0_deg = 6.6 pixels_per_deg = -1. rectification = 'LENSMODEL_LATLON' disparity_min,disparity_max = 0,150 range_image_min,range_image_max = 1,1000 disparity_error_expected = 1.3 models = [mrcal.cameramodel(modelfilename) for modelfilename in model_filenames] models_rectified = \ mrcal.rectified_system(models, az_fov_deg = az_fov_deg, el_fov_deg = el_fov_deg, az0_deg = az0_deg, el0_deg = el0_deg, pixels_per_deg_az = pixels_per_deg, pixels_per_deg_el = pixels_per_deg, rectification_model = rectification) rectification_maps = mrcal.rectification_maps(models, models_rectified) # This is a hard-coded property of the OpenCV StereoSGBM implementation disparity_scale = 16 # round to nearest multiple of disparity_scale. The OpenCV StereoSGBM # implementation requires this disparity_max = disparity_scale*round(disparity_max/disparity_scale) disparity_min = disparity_scale*int (disparity_min/disparity_scale) stereo_sgbm = \ cv2.StereoSGBM_create(minDisparity = disparity_min, numDisparities = disparity_max - disparity_min, blockSize = 5, P1 = 600, P2 = 2400, disp12MaxDiff = 1, uniquenessRatio = 5, speckleWindowSize = 100, speckleRange = 2 ) images = [mrcal.load_image(f, bits_per_pixel = 24, channels = 3) for f in image_filenames] images_rectified = [mrcal.transform_image(images[i], rectification_maps[i]) \ for i in range(2)] disparity = stereo_sgbm.compute(*images_rectified) ranges0 = mrcal.stereo_range( disparity, models_rectified, disparity_scale = disparity_scale) delta = 0.1 ranges1 = mrcal.stereo_range( disparity + delta*disparity_scale, models_rectified, disparity_scale = disparity_scale) drange_ddisparity = (ranges0-ranges1) / delta idx_valid = (disparity > 0) * (disparity < 30000) drange_ddisparity[~idx_valid] = 0 filename_plot = f"{Dout}/sensitivity.png" title = f"Expected range error assuming disparity error of {disparity_error_expected} pixels" gp.plot( drange_ddisparity * disparity_error_expected, square = True, _set = ('xrange noextend', 'yrange reverse noextend', 'logscale cb', 'cblabel "Expected range error (m)"', 'cbtics (.3, 1, 10, 100, 500)'), cbrange = [0.3,500], _with = 'image', tuplesize = 3, title = title) #+end_src #+begin_src python :exports none :eval no-export #!/usr/bin/python3 import sys import os import numpy as np import numpysane as nps import mrcal import cv2 import gnuplotlib as gp D = "/home/dima/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/stereo" Dout = "/home/dima/projects/mrcal-doc-external/figures/stereo-range-sensitivity" try: os.mkdir(Dout) except FileExistsError: pass model_filenames = [ f"{D}/{i}.cameramodel" for i in (0,1) ] image_filenames = [ f"{D}/{i}.jpg" for i in (0,1) ] find_crop_from_original = False if find_crop_from_original: az_fov_deg = 170 el_fov_deg = 95 az0_deg = -15 el0_deg = 10 else: az_fov_deg = 32.4 el_fov_deg = 24.9 az0_deg = -20.2 el0_deg = 6.6 pixels_per_deg = -1. rectification = 'LENSMODEL_LATLON' disparity_min,disparity_max = 0,150 range_image_min,range_image_max = 1,1000 disparity_error_expected = 1.3 models = [mrcal.cameramodel(modelfilename) for modelfilename in model_filenames] models_rectified = \ mrcal.rectified_system(models, az_fov_deg = az_fov_deg, el_fov_deg = el_fov_deg, az0_deg = az0_deg, el0_deg = el0_deg, pixels_per_deg_az = pixels_per_deg, pixels_per_deg_el = pixels_per_deg, rectification_model = rectification) if find_crop_from_original: q00 = np.array((2378,1157)) q11 = np.array((3592,2068)) fxy = models_rectified[0].intrinsics()[1][0:2] cxy = models_rectified[0].intrinsics()[1][2:4] azel0 = (q00 - cxy) / fxy azel1 = (q11 - cxy) / fxy print(f" az_fov_deg = {(azel1 - azel0)[0] * 180./np.pi:.1f}") print(f" el_fov_deg = {(azel1 - azel0)[1] * 180./np.pi:.1f}") print(f" az0_deg = {(azel1 + azel0)[0]/2 * 180./np.pi:.1f}") print(f" el0_deg = {(azel1 + azel0)[1]/2 * 180./np.pi:.1f}") sys.exit(0) rectification_maps = mrcal.rectification_maps(models, models_rectified) # This is a hard-coded property of the OpenCV StereoSGBM implementation disparity_scale = 16 # round to nearest multiple of disparity_scale. The OpenCV StereoSGBM # implementation requires this disparity_max = disparity_scale*round(disparity_max/disparity_scale) disparity_min = disparity_scale*int (disparity_min/disparity_scale) stereo_sgbm = \ cv2.StereoSGBM_create(minDisparity = disparity_min, numDisparities = disparity_max - disparity_min, blockSize = 5, P1 = 600, P2 = 2400, disp12MaxDiff = 1, uniquenessRatio = 5, speckleWindowSize = 100, speckleRange = 2 ) images = [mrcal.load_image(f, bits_per_pixel = 24, channels = 3) for f in image_filenames] images_rectified = [mrcal.transform_image(images[i], rectification_maps[i]) \ for i in range(2)] disparity = stereo_sgbm.compute(*images_rectified) disparity_colored = mrcal.apply_color_map(disparity, a_min = disparity_min*disparity_scale, a_max = disparity_max*disparity_scale) image_filenames_base = \ [os.path.splitext(os.path.split(f)[1])[0] for f in image_filenames] def write_output_one(func, filename): func(filename) print(f"Wrote '{filename}'") f,e = os.path.splitext(filename) filename_downsampled = f"{f}.downsampled{e}" os.system(f"convert {filename} -scale 50% {filename_downsampled}") print(f"Wrote '{filename_downsampled}'") write_output_one(lambda filename: mrcal.save_image(filename, images_rectified[0]), f"{Dout}/{image_filenames_base[0]}-rectified.png") write_output_one(lambda filename: mrcal.save_image(filename, images_rectified[1]), f"{Dout}/{image_filenames_base[1]}-rectified.png") write_output_one(lambda filename: mrcal.save_image(filename, disparity_colored), f"{Dout}/{image_filenames_base[0]}-disparity.png") ranges0 = mrcal.stereo_range( disparity, models_rectified, disparity_scale = disparity_scale) delta = 0.1 ranges1 = mrcal.stereo_range( disparity + delta*disparity_scale, models_rectified, disparity_scale = disparity_scale) drange_ddisparity = (ranges0-ranges1) / delta idx_valid = (disparity > 0) * (disparity < 30000) drange_ddisparity[~idx_valid] = 0 filename_plot = f"{Dout}/sensitivity.png" title = f"Expected range error assuming disparity error of {disparity_error_expected} pixels" gp.plot( drange_ddisparity * disparity_error_expected, square = True, _set = ('xrange noextend', 'yrange reverse noextend', 'logscale cb', 'cblabel "Expected range error (m)"', 'cbtics (.3, 1, 10, 100, 500)'), cbrange = [0.3,500], _with = 'image', tuplesize = 3, title = title, hardcopy = filename_plot, terminal = 'pngcairo size 1024,768 transparent noenhanced crop font ",12"') print(f"Wrote '{filename_plot}'") #+end_src The rectified images look like this: [[file:external/figures/stereo-range-sensitivity/0-rectified.png][file:external/figures/stereo-range-sensitivity/0-rectified.downsampled.png]] [[file:external/figures/stereo-range-sensitivity/1-rectified.png][file:external/figures/stereo-range-sensitivity/1-rectified.downsampled.png]] And the disparity image looks like this: [[file:external/figures/stereo-range-sensitivity/0-disparity.png][file:external/figures/stereo-range-sensitivity/0-disparity.downsampled.png]] And we compute the range sensitivity. And we plot it: file:external/figures/stereo-range-sensitivity/sensitivity.png Since [[file:triangulation.org][triangulation accuracy scales with the /square/ of range]], this is a log-scale plot; otherwise it would be illegible. As expected we see that the relatively-nearby tree has an expected range error of < 1m, while the furthest-away building has an expected range error that approaches 500m. Clearly these are rough estimates, but they allow us to quickly gauge the ranging capabilities of a system for a particular scene. mrcal-2.4.1/doc/rectification.fig000066400000000000000000000054171456301662300167100ustar00rootroot00000000000000#FIG 3.2 Produced by xfig version 3.2.7b Portrait Center Metric Letter 100.00 Single -2 1200 2 0 32 #a0a0a0 5 1 0 1 0 7 50 -1 -1 4.000 0 0 0 0 5347.539 2044.693 5522 1893 5567 1972 5578 2063 5 1 0 1 0 7 50 -1 -1 4.000 0 1 0 0 185.205 3941.516 584 3421 427 3332 225 3287 5 1 0 1 0 7 50 -1 -1 4.000 0 1 0 0 2509.990 3527.159 2715 3298 2625 3242 2524 3220 6 4617 1851 4979 2260 2 3 0 2 2 7 50 -1 -1 12.000 0 0 7 0 0 5 4750 1955 4975 1855 4975 2256 4750 2156 4750 1955 2 3 0 2 2 7 50 -1 -1 12.000 0 0 7 0 0 5 4750 1855 4750 2256 4621 2256 4621 1855 4750 1855 -6 6 4617 1851 4979 2260 2 3 0 5 1 7 60 -1 -1 18.000 0 0 7 0 0 5 4751 1858 4751 2252 4624 2252 4624 1858 4751 1858 2 3 0 5 1 7 60 -1 -1 18.000 0 0 7 0 0 5 4751 1957 4972 1858 4972 2252 4751 2154 4751 1957 -6 6 2315 3443 2720 3802 2 3 0 2 2 7 50 -1 -1 12.000 0 0 7 0 0 5 2318 3671 2716 3671 2716 3799 2318 3799 2318 3671 2 3 0 2 2 7 50 -1 -1 12.000 0 0 7 0 0 5 2418 3671 2318 3447 2716 3447 2617 3671 2418 3671 -6 6 11 3439 424 3806 2 3 0 5 1 7 60 -1 -1 18.000 0 0 7 0 0 5 18 3671 416 3671 416 3799 18 3799 18 3671 2 3 0 5 1 7 60 -1 -1 18.000 0 0 7 0 0 5 118 3671 18 3447 416 3447 317 3671 118 3671 -6 1 3 0 1 0 0 50 -1 20 0.000 1 0.0000 6936 1611 45 45 6936 1611 6981 1611 1 3 0 1 0 0 50 -1 20 0.000 1 0.0000 4033 276 45 45 4033 276 4078 276 2 1 0 3 0 7 50 -1 -1 8.000 0 0 7 0 0 2 4673 2063 6937 1610 2 1 0 1 0 7 50 -1 -1 4.000 0 0 7 1 0 2 1 1 1.00 45.28 71.69 4673 2063 4673 3251 2 1 0 1 0 7 50 -1 -1 4.000 0 0 7 1 0 2 1 1 1.00 45.28 71.69 4673 2063 6937 2063 2 1 0 1 0 7 50 -1 -1 4.000 0 0 7 1 0 2 1 1 1.00 44.87 71.04 225 3747 225 1504 2 1 0 1 0 7 50 -1 -1 4.000 0 0 7 1 0 2 1 1 1.00 44.87 71.04 225 3747 1010 3747 2 1 0 3 0 7 50 -1 -1 8.000 2 0 7 0 0 3 225 3747 4039 270 2524 3747 2 1 1 1 0 7 50 -1 -1 8.000 0 0 -1 0 0 2 225 3747 2524 3747 2 1 1 1 0 7 50 -1 -1 8.000 0 0 7 0 0 2 2524 3747 2524 1504 2 1 0 1 0 7 50 -1 -1 0.000 0 0 7 1 0 2 1 1 1.00 75.00 105.00 4770 810 4095 315 2 1 0 1 0 7 50 -1 -1 0.000 0 0 -1 1 0 2 1 1 1.00 75.00 105.00 6165 1080 6840 1530 4 0 0 50 -1 32 14 0.0000 4 210 120 5696 1988 f\001 4 0 0 50 -1 -1 14 0.0000 5 120 105 6840 2205 z\001 4 1 0 50 -1 16 14 0.0000 5 225 2670 6120 2835 Looking into the baseline\001 4 0 0 50 -1 -1 14 0.0000 5 165 120 4729 3251 y\001 4 2 0 50 -1 32 14 0.0000 5 165 120 2655 3150 q\001 4 0 0 50 -1 32 10 0.0000 5 105 75 2655 3195 1\001 4 1 0 50 -1 16 14 0.0000 5 180 915 1350 3960 baseline\001 4 0 0 50 -1 -1 14 0.0000 5 120 120 898 3691 x\001 4 2 0 50 -1 32 14 0.0000 5 165 120 430 3247 q\001 4 0 0 50 -1 32 10 0.0000 5 105 75 430 3292 0\001 4 0 0 50 -1 -1 12 0.0000 5 90 90 281 1616 z\001 4 1 0 50 -1 16 18 0.0000 5 270 1155 1350 4365 Top view\001 4 1 0 50 -1 16 18 0.0000 5 210 1215 6120 4365 Side view\001 4 1 0 50 -1 16 14 0.0000 4 225 1635 5445 1035 Observed point\001 mrcal-2.4.1/doc/roadmap.org000066400000000000000000000353731456301662300155360ustar00rootroot00000000000000#+TITLE: mrcal roadmap #+OPTIONS: toc:nil * New, big features being considered for a future release - Triangulation in the optimization loop. This will allow efficient SFM since the coordinates of each observed 3D point don't need to be explicitly optimized as part of the optimization vector. This should also allow calibrating extrinsics separately from intrinsics, while propagating all the sources of uncertainty through to the eventual triangulation. This is being developed in the [[https://github.com/dkogan/mrcal/tree/2022-06--triangulated-solve][=2022-06--triangulated-solve= branch]] - Non-central projection support. At this time, mrcal assumes that all projections are /central/: all rays of light are assumed to intersect at a single point (the origin of the camera coordinate system). So $k \vec v$ projects to the same $\vec q$ for any $k$. This is very convenient, but not completely realistic. Support for /non-central/ lenses will make possible more precise calibrations of all lenses, but especially wide ones. This is being developed in the [[https://github.com/dkogan/mrcal/tree/noncentral][=noncentral= branch]] - Improved projection uncertainty quantification. The [[file:uncertainty.org][current projection uncertainty method]], which functional, has some issues. A new approach in the [[https://github.com/dkogan/mrcal/tree/2022-04--cross-uncertainty][=2022-04--cross-uncertainty= branch]] aims to resolve them. The current projection uncertainty method works badly if given chessboards at multiple different ranges from the camera. This is due to the aphysical transform $T_{\mathrm{r}^+\mathrm{r}}$ computed as part of the [[file:uncertainty.org::#propagating-through-projection][uncertainty computation]]. We can clearly see this in the dance study: #+begin_src sh dance-study.py \ --scan num_far_constant_Nframes_near \ --range 2,10 \ --Ncameras 1 \ --Nframes-near 100 \ --observed-pixel-uncertainty 2 \ --ymax 2.5 \ --uncertainty-at-range-sampled-max 35 \ opencv8.cameramodel #+end_src This tells us that adding /any/ observations at 10m to the bulk set at 2m makes the projection uncertainty /worse/. One could expect no improvement from the far-off observations, but they shouldn't break anything. The issue is the averaging in 3D point space. Observation noise causes the far-off geometry to move much more than the nearby chessboards, and that far-off motion then dominates the average. We can also see it with the much larger ellipse we get when we add =--extra-observation-at= to #+begin_src sh test/test-projection-uncertainty.py \ --fixed cam0 \ --model opencv4 \ --show-distribution \ --range-to-boards 4 \ --extra-observation-at 40 \ --do-sample \ --explore #+end_src Some experimental fixes are implemented in [[https://www.github.com/dkogan/mrcal/blob/master/test/test-projection-uncertainty.py][=test/test-projection-uncertainty.py=]]. For instance: #+begin_src sh test/test-projection-uncertainty.py \ --fixed cam0 \ --model opencv4 \ --show-distribution \ --explore \ --do-sample \ --reproject-perturbed mean-frames-using-meanq-penalize-big-shifts #+end_src It is important to solve this to be able to clearly say if non-closeup observations are useful at all or not. There was quick a bit of thought and experimentation in this area, but no conclusive solutions yet. The solution being considered: solve for $T_{\mathrm{r}^+\mathrm{r}}$ directly. We have a solve that minimizes the reprojection error $\Sigma_i \left\Vert\vec q_i - \mathrm{project}\left(T_\mathrm{cr_i} T_\mathrm{rf_i} \vec p_{\mathrm{frame}_i}\right)\right\Vert^2$ and another one that looks at perturbed quantities $\left\Vert\vec q^+ - \mathrm{project}^+\left(T_{\mathrm{c}^+\mathrm{r}^+} T_{\mathrm{r}^+\mathrm{f}^+} \vec p_{\mathrm{frame}}\right)\right\Vert^2$. Can I cross these to find the $T_{\mathrm{r}^+\mathrm{r}}$ that minimizes $\left\Vert\vec q^+ - \mathrm{project}^+\left(T_{\mathrm{c}^+\mathrm{r}^+} T_{\mathrm{r}^+\mathrm{r}} T_\mathrm{rf} \vec p_{\mathrm{frame}}\right)\right\Vert^2$. A diagram: #+begin_example ORIGINAL SOLVE PERTURBED SOLVE point in point in chessboard chessboard frame frame | | | Trf | Tr+f+ v v point in point in ref frame <-- Trr+ --> ref frame | | | Tcr | Tc+r+ v v point in point in cam frame cam frame | | | project | project v v pixel pixel #+end_example Some experiments along those lines are implemented in =mrcal-show-projection-diff --same-dance= and in =test/test-projection-uncertainty.py --reproject-perturbed ...= When asked to compute the uncertainty of many pixels at once (such as what [[file:mrcal-show-projection-uncertainty.html][=mrcal-show-projection-uncertainty=]] tool does), mrcal currently computes a separate $T_{\mathrm{r}^+\mathrm{r}}$ for each pixel. But there exists only one $T_{\mathrm{r}^+\mathrm{r}}$, and this should be computed once for all pixels, and applied to all of them. Currently we are able to compute projection uncertainties only when given a vanilla calibration problem: stationary cameras are observing a moving chessboard. We should support more cases, for instance structure-from-motion coupled with intrinsics optimization. And computing uncertainty from a points-only chessboard-less solve should be possible - Richer board-shape model. Currently mrcal can solve for an axis-aligned paraboloid board shape. This is better than nothing, but experiments indicate that real-world board warping is more complex than that. A richer board-shape model will make mrcal less sensitive to imperfect chessboards, and will reduce that source of bias. This is being developed in the [[https://github.com/dkogan/mrcal/tree/richer-board-shape][=richer-board-shape= branch]], but this has the least priority of any ongoing work * Things that should be fixed, but that I'm not actively thinking about today ** Algorithmic *** Uncertainty quantification - The input noise should be characterized better. Currently we use the distribution from the optimal residuals. This feels right, but the empirical distribution isn't entirely gaussian. Why? There's an [[https://github.com/dkogan/mrgingham/blob/master/mrgingham-observe-pixel-uncertainty][attempt]] to quantify the input noise directly in mrgingham. Does it work? Does that estimate agree with what the residuals tell us? If not, which is right? If a better method is found, the =observed_pixel_uncertainty= should come back as something the user passes in. - Can I quantify heteroscedasticity to detect model errors? In the [[file:tour-initial-calibration.org][tour of mrcal]] the human observer can clearly see patterns in the residuals. Can these patterns be detected automatically to flag these issues, especially when they're small and not entirely obvious? Do I want a [[https://en.wikipedia.org/wiki/White_test]["white test"]]? - As desired, we currently report high uncertainties in imager regions with no chessboards. When using a splined model, the projection in those regions is controlled entirely by the regularization terms, so we report high uncertainties there only because of the moving extrinsics. This isn't a great thing to rely on, and could break if I have some kind of surveyed calibration (known chessboard and/or camera poses). *** Differencing Fitting of the implied transformation is key to computing a diff, and various details about how this is done could be improved. Currently mrcal computes this from a fit. The default behavior of [[file:mrcal-show-projection-diff.html][=mrcal-show-projection-diff=]] is to use the whole imager, using the uncertainties as weights. This has two problems: - If using a splined model, this is slow - If using a lean model, the overly-optimistic uncertainties you get from lean models tend to poison the fit, as seen in the [[file:differencing.org::#fit-weighting][documentation]]. *** Triangulation - Currently I have a routine to compute projection uncertainty. And a separate routine to compute triangulation uncertainty. It would be nice to have a generic monocular uncertainty routine that is applicable to those and more cases. Should I be computing the uncertainty of a stabilized, normalized stereographic projection of $\mathrm{unproject}\left(\vec q\right)$? Then I could do monocular tracking with uncertainties. Can I derive the existing uncertainty methods from that one? - As noted on the [[file:triangulation.org::#triangulation-problems-as-infinity][triangulation page]], some distributions become non-gaussian when looking at infinity. Is this a problem? When is it a problem? Should it be fixed? How? *** [[file:splined-models.org][Splined models]] - It's currently not clear how to choose the spline order (the =order= configuration parameter) and the spline density (the =Nx= and =Ny= parameters). There's some trade-off here: a quadratic spline needs denser knots. An initial study of the effects of spline spacings appears [[file:splined-models.org::#splined-models-uncertainty-wiggles][here]]. Can this be used to select the best spline configuration? We see that the uncertainty oscillates, with peaks at the knots. The causes and implications of this need to be understood better - The current regularization scheme is iffy. More or less mrcal is using simple L2 regularization. /Something/ is required to tell the solver what to do in regions of no data. The transition between "data" and "no-data" regions is currently aphysical, as described in the [[file:splined-models.org::#splined-non-monotonicity][documentation]]. Changing the regularization scheme to pull towards the mean, and not towards 0 /could/ possibly fix this. An [[https://github.com/dkogan/mrcal/commit/c8f9918023142d7ee463821661dc5bcc8f770b51][earlier attempt]] to do that was reverted because any planar splined surface would have "perfect" regularization, and that was breaking things (crazy focal lengths would be picked). But now that I'm locking down the intrinsics core when optimizing splined models, this isn't a problem anymore, so maybe that approach should be revisited. *** Outlier rejection - The current outlier-rejection scheme is simplistic. A smarter approach is available in [[https://github.com/dkogan/libdogleg/][=libdogleg=]] (Cook's D and Dima's variations on that). Bringing those in could be good - Outlier rejection is currently only enabled for chessboard observations. It should be enabled for discrete points as well *** Stereo - A pre-filter should be added to the [[file:mrcal-stereo.html][=mrcal-stereo=]] tool to enhance the edges prior to stereo matching. A patch to add an early, untested prototype: #+begin_src diff diff --git a/mrcal/stereo.py b/mrcal/stereo.py index 6ba3549..7a6eabc 100644 --- a/mrcal/stereo.py +++ b/mrcal/stereo.py @@ -1276,5 +1276,22 @@ data_tuples, plot_options. The plot can then be made with gp.plot(*data_tuples, q0[ 0,-1], q0[-1,-1] ) + image1 = image1.astype(np.float32) + image1 -= \ + cv2.boxFilter(image1, + ddepth = -1, + ksize = tuple(template_size1), + normalize = True, + borderType = cv2.BORDER_REPLICATE) + template_size0 = (round(np.max(q0[...,1]) - np.min(q0[...,1])), + round(np.max(q0[...,0]) - np.min(q0[...,0]))) + # I don't need to mean-0 the entire image0. Just the template will do + image0 = image0.astype(np.float32) + image0 -= \ + cv2.boxFilter(image0, + ddepth = -1, + ksize = template_size0, + normalize = True, + borderType = cv2.BORDER_REPLICATE) image0_template = mrcal.transform_image(image0, q0) #+end_src - Currently a stereo pair arranged axially (one camera in front of the other) cause mrcal to fail. But it could work: the rectified images are similar to a polar transform of the input. *** [[file:mrcal-python-api-reference.html#-estimate_monocular_calobject_poses_Rt_tocam][=mrcal.estimate_monocular_calobject_poses_Rt_tocam()=]] An early stage of a calibration run generates a rough estimate of the chessboard geometry. Internally this is currently assuming a pinhole model, which is wrong, and currently requires an [[https://github.com/dkogan/mrcal/commit/6d78379][ugly hack]]. This does appear to work fairly well, but it should be fixed ** Software *** Stereo - The [[file:mrcal-stereo.html][=mrcal-stereo=]] tool should be able to estimate the field of view automatically: the user should not be required to pass =--az-fov-deg= and =--el-fov-deg= *** Uncertainty - Currently [[file:mrcal-python-api-reference.html#-triangulate][=mrcal.triangulate()=]] broadcasts nicely, while [[file:mrcal-python-api-reference.html#-projection_uncertainty][=mrcal.projection_uncertainty()=]] does not. It would be nice if it did and if its API resembled that of [[file:mrcal-python-api-reference.html#-triangulate][=mrcal.triangulate()=]] *** Misc - [[file:mrcal-show-geometry.html][=mrcal-show-geometry=]] tool: the [[file:mrcal-stereo.html][=mrcal-stereo=]] tool produces a field-of-view visualization. This should be made available in the Python API and in the [[file:mrcal-show-geometry.html][=mrcal-show-geometry=]] tool - [[https://github.com/dkogan/mrcal/blob/master/analyses/dancing/dance-study.py][=dance-study.py=]]: if asked for chessboards that are too close, the tool goes into an infinite loop as it searches for chessboard poses that are fully visible by the camera. Something smarter than an infinite loop should happen - Warnings in [[https://github.com/dkogan/mrcal/blob/master/mrcal.c][=mrcal.c=]]: there are a number of warnings in [[https://github.com/dkogan/mrcal/blob/master/mrcal.c][=mrcal.c=]] tagged with =// WARNING= that should eventually be addressed. This has never been urgent-enough to deal with. But someday - viz tools should accept =--vectorfield= /and/ =--vector-field= mrcal-2.4.1/doc/splined-models.org000066400000000000000000000676511456301662300170360ustar00rootroot00000000000000#+TITLE: mrcal splined lens models #+OPTIONS: toc:t mrcal supports a family of rich lens models to - model real-world lens behavior with more fidelity than the usual parametric models make possible - produce reliable [[file:uncertainty.org][projection uncertainty]] estimates A summary of these models appears on the lens-model page: [[file:lensmodels.org::#splined-stereographic-lens-model][=LENSMODEL_SPLINED_STEREOGRAPHIC_...= models]], and we expand on it here. The current approach is one of many possible ways to define a rich projection function based on splined surfaces. Improved representations could be developed in the future. The idea of using a very rich representation to model lens behavior has been described in literature (for instance [[https://ieeexplore.ieee.org/abstract/document/8500466][here]] and [[https://arxiv.org/abs/1912.02908][here]]). However, *every paper I've seen models unprojection* (mapping pixels to observation vectors) instead of projection (observation vectors to pixels). The usual direction is projection, employed by every other lens model in every other toolkit, so following the papers would require rewriting lots of code specifically to support this one model. *mrcal's rich representation models projection*, so this new model fits into the same framework as all the other models, and all the higher-level logic (differencing, uncertainty quantification, etc) continues to work with no modifications. These models are now mature, and have been used extensively in many different applications. It is now my strong recommendation to use these in lieu of any other model. A common point of concern is computational performance, which is expected when switching from a model that has 12 parameters to a model that has 500 or more parameters. However, the implementation is built around B-splines, so the projection function has local support, and the projection of any given point uses only a few parameters. Some things involving these models are slower, and some aren't, but the difference is never dramatic. Try it. * Projection function The =LENSMODEL_SPLINED_STEREOGRAPHIC_...= model is a stereographic model with correction factors. To compute a projection using this model, we first compute the normalized stereographic projection $\vec u$ as in the [[file:lensmodels.org::#lensmodel-stereographic][=LENSMODEL_STEREOGRAPHIC=]] definition: \[ \theta \equiv \tan^{-1} \frac{\left| \vec p_{xy} \right|}{p_z} \] \[ \vec u \equiv \frac{\vec p_{xy}}{\left| \vec p_{xy} \right|} 2 \tan\frac{\theta}{2} \] Then we use $\vec u$ to look-up a $\Delta \vec u$ using two separate splined surfaces: \[ \Delta \vec u \equiv \left[ \begin{aligned} \Delta u_x \left( \vec u \right) \\ \Delta u_y \left( \vec u \right) \end{aligned} \right] \] and we then define the rest of the projection function: \[\vec q = \left[ \begin{aligned} f_x \left( u_x + \Delta u_x \right) + c_x \\ f_y \left( u_y + \Delta u_y \right) + c_y \end{aligned} \right] \] The $\Delta \vec u$ are the off-stereographic terms: if $\Delta \vec u = 0$, we get a plain stereographic projection. The surfaces $\Delta u_x$ and $\Delta u_y$ are defined as [[https://en.wikipedia.org/wiki/B-spline][B-splines]], parametrized by the values of the "knots" (control points). These knots are arranged in a fixed grid in the space of $\vec u$, with the grid density and extents set by the model configuration (i.e. not subject to optimization). The values at each knot are set in the intrinsics vector, and this controls the projection function. * B-spline details We're using B-splines primarily for their local support properties: moving a knot only affects the surface in the immediate neighborhood of that knot. This makes our jacobian sparse, which is critical for rapid convergence of the optimization problem. Conversely, at any $\vec u$, the sampled value of the spline depends /only/ on the knots in the immediate neighborhood of $\vec u$. A [[https://www.github.com/dkogan/mrcal/blob/master/analyses/splines/bsplines.py][script used in the development of the splined model]] shows this effect: [[file:external/figures/splined-models/cubic-spline-perturbations.svg]] We sampled a curve defined by two sets of cubic B-spline control points: they're the same except the one point in the center differs. We can see that the two spline-interpolated functions produce a different value only in the vicinity of the tweaked control point. And we can clearly see the radius of the effect: the sampled value of a cubic B-spline depends on the two control points on either side of the query point. A quadratic B-spline has a narrower effect: the sampled value depends on the nearest control point, and one neighboring control point on either side. This plot shows a 1-dimension splined /curve/, but we have splined /surfaces/. To sample a spline surface: 1. Arrange the control points in a grid 2. Sample each row independently as a separate 1-dimensional B-spline 3. Use these row samples as control points to sample the resulting column Processing columns first and then rows produces the same result. The [[https://www.github.com/dkogan/mrcal/blob/master/analyses/splines/bsplines.py][same dev script from above]] checks this. * Configuration :PROPERTIES: :CUSTOM_ID: splined-models-configuration-selection :END: The configuration selects the [[file:lensmodels.org::#splined-stereographic-lens-model][=LENSMODEL_SPLINED_STEREOGRAPHIC_...=]] model parameters that aren't subject to optimization. These define the high-level behavior of the spline. We have: - =order=: the degree of each 1D polynomial. This is either 2 (quadratic splines, C1 continuous) or 3 (cubic splines, C2 continuous). At this time, 3 (cubic splines) is recommended. I haven't yet done a thorough study on this, but empirical results tell me that quadratic splines are noticeably less flexible, and require a denser spline to fit as well as a comparable cubic spline. - =Nx= and =Ny=: The spline density. We have a =Nx= by =Ny= grid of evenly-spaced control points. The ratio of this spline grid should be selected to match the aspect ratio of the imager. Inside each spline patch we effectively have a lean parametric model. Choosing a too-sparse spline spacing will result in larger patches, which aren't able to fit real-world lenses. Choosing a denser spacing results in more parameters and a more flexible model at the cost of needing more data and slower computations. No data-driven method of choosing =Nx= or =Ny= is available at this time, but =Nx=30_Ny=20= appears to work well for some /very/ wide lenses I tested with; this is probably overkill. An initial study of the effects of different spacings appears [[#splined-models-uncertainty-wiggles][below]]. - =fov_x_deg=: The horizontal field of view, in degrees. Selects the region in the space of $\vec u$ where the spline is well-defined. =fov_y_deg= is not included in the configuration: it is assumed proportional with =Ny= and =Nx=. =fov_x_deg= is used to compute a =knots_per_u= quantity, and this is applied in both the horizontal and vertical directions. * Field-of-view selection :PROPERTIES: :CUSTOM_ID: splined-models-field-of-view-selection :END: The few knots around any given $\vec u$ define the value of the spline function there. These knots define "spline patch", a polynomial surface that fully represents the spline function in the neighborhood of $\vec u$. As the sample point $\vec u$ moves around, different spline patches, selected by a different set of knots are selected. With cubic splines, each spline patch is defined by the local 4x4 grid of knots (16 knots total). With quadratic splines, each spline is defined by a 3x3 grid. Since the knots are defined on a fixed grid, it is possible to try to sample the spline beyond the region where the knots are defined (beyond our declared field of view). In this case we use the nearest spline patch, which could sit far away from $\vec u$. So here we still use a 4x4 grid of knots to define the spline patch, but $\vec u$ no longer sits in the middle of these knots: because we're past the edge, and the preferred knots aren't available. This produces continuous projections everywhere, at the cost of reduced function flexibility at the edges: the effective edge patches could be much larger that the internal patches. We can control this by selecting a wide-enough =fov_x_deg= to cover the full field-of-view of the camera. We then wouldn't be querying the spline beyond the knots, since those regions in space are out-of-view of the lens. =fov_x_deg= should be large enough to cover the field of view, but not so wide to waste knots representing invisible space. It is recommended to estimate this from the datasheet of the lens, and then to run a test calibration. Running the [[file:mrcal-show-splined-model-correction.html][=mrcal-show-splined-model-correction=]] tool then compares the valid-intrinsics region (area with sufficient calibration data) against the bounds of the spline-in-bounds region, letting the user know if the field-of-view is too small. * Fidelity and uncertainties This splined model has many more parameters, and is far more flexible than the lean parametric models (all the other currently-supported lens models). This has several significant effects. These models are much more capable of representing the behavior of real-world lenses than the lean models: at a certain level of precision the parametric models are always wrong. The tour of mrcal shows [[file:tour-initial-calibration.org::#opencv8-model-solving][a real-world fit using =LENSMODEL_OPENCV8=]] and [[file:tour-initial-calibration.org::#splined-model-solving][a real-world fit using =LENSMODEL_SPLINED_STEREOGRAPHIC_...=]], where we can clearly see that the splined model fits the data better. The higher parameter counts do result in higher reported uncertainties (see the [[file:tour-uncertainty.org::#splined-model-uncertainties][tour of mrcal]] for examples). This is a good thing: the lean models report uncertainty estimates that are low, but do not match reality. While the higher uncertainty estimates from the splined models are truthful. This is because the [[file:uncertainty.org][uncertainty estimate algorithm]] constrains the lenses to the space that's representable by a given lens model, which is a constraint that only exists on paper. Since mrcal reports the covariance matrix of any projection operation, the uncertainty can be used to pass/fail a calibration /or/ the covariance can be propagated to whatever is using the model. It is thus recommended to use splined models even for long lenses, which do fit the pinhole model more or less. * Uncertainty wiggles :PROPERTIES: :CUSTOM_ID: splined-models-uncertainty-wiggles :END: In the [[file:tour-uncertainty.org::#tour-uncertainty-splined-model-uncertainties][the tour of mrcal]] we evaluated the projection uncertainty of a splined-model solve: #+begin_src sh mrcal-show-projection-uncertainty splined.cameramodel --cbmax 1 --unset key #+end_src #+begin_src sh :exports none :eval no-export # THIS WAS COMPUTED IN tour-uncertainty.org #+end_src [[file:external/figures/uncertainty/uncertainty-splined.png]] Note that the uncertainties from the splined model don't look smooth. Let's look into that now by evaluating the uncertainty across the imager at $y = \frac{\mathrm{height}}{2}$. To do this we need to write a bit of Python code: #+begin_src python #!/usr/bin/python3 import mrcal import numpy as np import numpysane as nps import gnuplotlib as gp from scipy.signal import argrelextrema m = mrcal.cameramodel('splined.cameramodel') W,H = m.imagersize() x = np.linspace(0, W-1, 1000) q = np.ascontiguousarray( \ nps.transpose( \ nps.cat(x, H/2*np.ones(x.shape)))) v = mrcal.unproject(q, *m.intrinsics()) s = mrcal.projection_uncertainty(v, m, atinfinity = True, what = 'worstdirection-stdev') print(repr(x[argrelextrema(s,np.greater)])) gp.plot(x, s, _with = 'lines', xrange = (0,W-1), yrange = (0,0.2), xlabel = 'x pixel', ylabel = 'Projection uncertainty (pixels)', title = 'Projection uncertainty at infinity, across the image at y=height/2') #+end_src #+begin_src python :exports none :eval no-export #!/usr/bin/python3 import sys sys.path[:0] = '/home/dima/projects/mrcal', import mrcal import numpy as np import numpysane as nps import gnuplotlib as gp from scipy.signal import argrelextrema m = mrcal.cameramodel('/home/dima/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/splined.cameramodel') W,H = m.imagersize() x = np.linspace(0, W-1, 1000) q = np.ascontiguousarray( \ nps.transpose( \ nps.cat(x, H/2*np.ones(x.shape)))) v = mrcal.unproject(q, *m.intrinsics()) s = mrcal.projection_uncertainty(v, m, atinfinity = True, what = 'worstdirection-stdev') print(repr(x[argrelextrema(s,np.greater)])) gp.plot(x, s, _with = 'lines', xrange = (0,W-1), yrange = (0,0.2), xlabel = 'x pixel', ylabel = 'Projection uncertainty (pixels)', title = 'Projection uncertainty at infinity, across the image at y=height/2', hardcopy = '/home/dima/projects/mrcal-doc-external/figures/uncertainty/uncertainty-splined-horizontal-scan.svg', terminal = 'svg size 800,600 noenhanced solid dynamic font ",14"', ) gp.plot(x, s, _with = 'lines', xrange = (2500, 3500), xlabel = 'x pixel', ylabel = 'Projection uncertainty (pixels)', title = 'Projection uncertainty at infinity, across the image at y=height/2', hardcopy = '/home/dima/projects/mrcal-doc-external/figures/uncertainty/uncertainty-splined-horizontal-scan-zoomed.svg', terminal = 'svg size 800,600 noenhanced solid dynamic font ",14"', ) #+end_src [[file:external/figures/uncertainty/uncertainty-splined-horizontal-scan.svg]] We can clearly see the non-monotonicity. This feels like it has something to do with our spline knot layout, so let's check that. The above script also reports the $x$ coordinates of the local maxima of the uncertainties: #+begin_example array([ 96.08008008, 378.31531532, 558.46546547, 2089.74174174, 2347.95695696, 2582.15215215, 2828.35735736, 3068.55755756, 3326.77277277, 3590.99299299, 5716.76476476, 5860.88488488]) #+end_example Let's look at the knot layout arbitrarily in the region near the center, marking the uncertainty maxima with red lines: #+begin_src sh mrcal-show-splined-model-correction \ --imager-domain \ --set 'xrange [2500:3400]' \ --set "yrange [$((3376/2+500 )):$((3376/2-500 ))]" \ --set 'arrow from 2582.2, graph 0 to 2582.2, graph 1 nohead lc "red" front' \ --set 'arrow from 2828.4, graph 0 to 2828.4, graph 1 nohead lc "red" front' \ --set 'arrow from 3068.6, graph 0 to 3068.6, graph 1 nohead lc "red" front' \ --set 'arrow from 3326.8, graph 0 to 3326.8, graph 1 nohead lc "red" front' \ --unset key \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ ~/projects/mrcal/mrcal-show-splined-model-correction \ --imager-domain \ --set 'xrange [2500:3400]' \ --set "yrange [$((3376/2+500 )):$((3376/2-500 ))]" \ --set 'arrow from 2582.2, graph 0 to 2582.2, graph 1 nohead lc "red" front' \ --set 'arrow from 2828.4, graph 0 to 2828.4, graph 1 nohead lc "red" front' \ --set 'arrow from 3068.6, graph 0 to 3068.6, graph 1 nohead lc "red" front' \ --set 'arrow from 3326.8, graph 0 to 3326.8, graph 1 nohead lc "red" front' \ --unset key \ $D/splined.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/uncertainty/splined-knots-zoomed.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' #+end_src [[file:external/figures/uncertainty/splined-knots-zoomed.png]] The uncertainty is highest near the knots, so adjusting the spline spacing would have an effect here. I haven't yet studied the effect of changing the spline spacing, but we can do a quick study here. Let's re-run the splined model optimization in the [[file:tour-uncertainty.org::#tour-uncertainty-splined-model-uncertainties][the tour of mrcal]], but using different spline spacings. And let's then reconstruct the uncertainty-across-center plot from above for each spacing. We re-run the solves using this =zsh= script: #+begin_src sh for Ny (4 6 8 10 15 20 25 30) { Nx=$((Ny*3/2)) mrcal-calibrate-cameras \ --corners-cache corners.vnl \ --lensmodel LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=${Nx}_Ny=${Ny}_fov_x_deg=150 \ --focal 1900 \ --object-spacing 58.8e-3 \ --object-width-n 14 \ --imagersize 6000 3376 \ '*.JPG' } #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ mkdir -p $D/splined-models-different-spacings/ for Ny (4 6 8 10 15 20 25 30) { Nx=$((Ny*3/2)) ~/projects/mrcal/mrcal-calibrate-cameras \ --corners-cache $D/corners.vnl \ --lensmodel LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=${Nx}_Ny=${Ny}_fov_x_deg=150 \ --focal 1900 \ --object-spacing 58.8e-3 \ --object-width-n 14 \ --out /tmp \ --imagersize 6000 3376 \ '*.JPG' mv /tmp/camera-0.cameramodel $D/splined-models-different-spacings/splined-Nx=${Nx}-Ny=${Ny}.cameramodel } #+end_src Results available [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/splined-models-different-spacings][here]]. And we write a bit of Python to make our plots: #+begin_src python #!/usr/bin/python3 import mrcal import numpy as np import numpysane as nps import gnuplotlib as gp import glob import re model_paths = np.array(glob.glob(f'splined-Nx=*.cameramodel')) Nx = np.array([int(re.sub('.*Nx=([0-9]+).*?$', '\\1', p)) \ for p in model_paths]) i = Nx.argsort() model_paths = model_paths[i] models = [mrcal.cameramodel(str(m)) for m in \ model_paths] W,H = models[0].imagersize() x = np.linspace(0, W-1, 1000) q = np.ascontiguousarray( \ nps.transpose( \ nps.cat(x, H/2*np.ones(x.shape)))) s = np.array([mrcal.projection_uncertainty(mrcal.unproject(q, *m.intrinsics()), m, atinfinity = True, what = 'worstdirection-stdev') \ for m in models]) legend = np.array([ re.sub('.*(Nx=[0-9]+)-(Ny=[0-9]+).*?$', '\\1 \\2', m) \ for m in model_paths ]) gp.plot(x, s, _with = 'lines', legend = legend, xrange = (0,W-1), yrange = (0,0.2), xlabel = 'x pixel', ylabel = 'Projection uncertainty (pixels)', title = 'Projection uncertainty at infinity, across the image at y=height/2', _set = 'key bottom right', wait = True) #+end_src #+begin_src python :exports none :eval no-export #!/usr/bin/python3 import sys sys.path[:0] = '/home/dima/projects/mrcal', import mrcal import numpy as np import numpysane as nps import gnuplotlib as gp import glob import re D='/home/dima/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/splined-models-different-spacings' model_paths = np.array(glob.glob(f'{D}/splined-Nx=*.cameramodel')) Nx = np.array([int(re.sub('.*Nx=([0-9]+).*?$', '\\1', p)) \ for p in model_paths]) i = Nx.argsort() model_paths = model_paths[i] models = [mrcal.cameramodel(str(m)) for m in \ model_paths] W,H = models[0].imagersize() x = np.linspace(0, W-1, 1000) q = np.ascontiguousarray( \ nps.transpose( \ nps.cat(x, H/2*np.ones(x.shape)))) if 1: s = np.array([mrcal.projection_uncertainty(mrcal.unproject(q, *m.intrinsics()), m, atinfinity = True, what = 'worstdirection-stdev') \ for m in models]) import pickle with open(f'{D}/uncertainties.pickle', 'wb') as f: pickle.dump(s, f) else: import pickle with open(f'{D}/uncertainties.pickle', 'rb') as f: s = pickle.load(f) legend = np.array([ re.sub('.*(Nx=[0-9]+)-(Ny=[0-9]+).*?$', '\\1 \\2', m) \ for m in model_paths ]) gp.plot(x, s, _with = 'lines', legend = legend, xrange = (0,W-1), yrange = (0,0.2), xlabel = 'x pixel', ylabel = 'Projection uncertainty (pixels)', title = 'Projection uncertainty at infinity, across the image at y=height/2', _set = 'key bottom right', hardcopy = '/home/dima/projects/mrcal-doc-external/figures/uncertainty/uncertainty-splined-horizontal-scan-different-spacings.svg', terminal = 'svg size 800,600 noenhanced solid dynamic font ",14"', ) #+end_src [[file:external/figures/uncertainty/uncertainty-splined-horizontal-scan-different-spacings.svg]] So we can see that as we pick a denser spline: - The uncertainty increases across the board. We already saw and noted this previously: lean models under-report the uncertainty - The frequency of the uncertainty wiggle increases. This makes sense: we just noted that the wiggles follow the spline knots. - The amplitude of the wiggle increases also. /This/ is interesting. It could be due to the fact that a richer spline is better able to squeeze between the gaps between the observed points. Or it could be because dense splines imply smaller spline patches, which means fewer observations are available in any given patch. Or it could be some fundamental property of B-spline-based optimization. This needs a deeper investigation * Optimization practicalities ** Core redundancy As can be seen in the projection function above, the splined stereographic model parameters contain splined correction factors $\Delta \vec u$ /and/ an intrinsics core $\left(f_x,f_y,c_x,c_y\right)$. The core variables are largely redundant with $\Delta \vec u$: for any perturbation in the core, we can achieve a /very/ similar change in projection behavior by bumping $\Delta \vec u$ in a specific way. As a result, if we allow the optimization algorithm to control all the variables, the system will be under-determined, and the optimization routine will fail: complaining about a "not positive definite" (singular in this case) Hessian. At best the Hessian will be slightly non-singular, but convergence will be slow. To resolve this, the recommended sequence for optimizing splined stereographic models is: 1. Fit the best =LENSMODEL_STEREOGRAPHIC= model to compute an estimate of the intrinsics core 2. Refine that solution with a full =LENSMODEL_SPLINED_STEREOGRAPHIC_...= model, using the core we just computed, and asking the optimizer to lock down those core values. This can be done by setting the =do_optimize_intrinsics_core= bit to 0 in the [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_problem_selections_t=]] structure passed to [[https://www.github.com/dkogan/mrcal/blob/master/mrcal.h][=mrcal_optimize()=]] in C (or passing =do_optimize_intrinsics_core=False= to [[file:mrcal-python-api-reference.html#-optimize][=mrcal.optimize()=]] in Python). This is what the [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras=]] tool does. ** Regularization :PROPERTIES: :CUSTOM_ID: splined-model-regularization :END: Another issue that comes up is the treatment of areas in the imager where no points were observed. By design, each parameter of the splined model controls projection from only a small area in space. So what happens to parameters controlling an area where no data was gathered? We have no data to suggest to the solver what values these parameters should take: they don't affect the cost function at all. Trying to optimize such a problem will result in a singular Hessian and complaints from the solver. We address this issue with regularization, to lightly pull all the $\Delta \vec u$ terms to 0. Another, related effect, is the interaction of extrinsics and intrinsics. Without special handling, splined stereographic solutions often produce a roll of the camera (rotation around the optical axis) to be compensated by a curl in the $\Delta \vec u$ vector field. This isn't wrong per se, but is an unintended effect that's nice to eliminate. It looks really strange when a motion in the $x$ direction in the camera coordinate system doesn't result in the projection moving in its $x$ direction. We use regularization to handle this effect as well. Instead of pulling all the values of $\Delta \vec u$ towards 0 evenly, we pull the $\Delta \vec u$ acting tangentially much more than those acting radially. This asymmetry serves to eliminate any unnecessary curl in $\Delta \vec u$. Regardless of direction, these regularization terms are /light/. The weights are chosen to be small-enough to not noticeably affect the optimization in its fitting of the data. This may be handled differently in the future. ** Uglyness at the edges :PROPERTIES: :CUSTOM_ID: splined-non-monotonicity :END: An unwelcome property of the projection function defined above, is that it allows aphysical, nonmonotonic behavior to be represented. For instance, let's look at the gradient in one particular direction. \begin{aligned} q_x &= f_x \left( u_x + \Delta u_x \right) + c_x \\ \frac{\mathrm{d}q_x}{\mathrm{d}u_x} &\propto 1 + \frac{\mathrm{d}\Delta u_x}{\mathrm{d}u_x} \end{aligned} We would expect $\frac{\mathrm{d}q_x}{\mathrm{d}u_x}$ to always be positive, but as we can see, here that depends on $\frac{\mathrm{d}\Delta u_x}{\mathrm{d}u_x}$, which could be /anything/ since $\Delta u_x$ is an arbitrary splined function. Most of the time we're fitting the spline into real data, so the real-world monotonic behavior will be represented. However, near the edges quite often no data is available, so the behavior is driven by [[#splined-model-regularization][regularization]], and we're very likely to hit this non-monotonic behavior there. This produces very alarming-looking spline surfaces, but it's not /really/ a problem: we get aphysical behavior in areas where we don't have data, so we have no expectations of reliable projections there. The [[file:mrcal-show-splined-model-correction.html][=mrcal-show-splined-model-correction= tool]] visualizes either the bounds of the valid-intrinsics region or the bounds of the imager. In many cases we have no calibration data near the imager edges, so the spline is determined by [[#splined-model-regularization][regularization]] in that area, and we get odd-looking knot layouts and imager contours. A better regularization scheme or (better yet) a better representation would address this. See [[file:tour-initial-calibration.org::#splined-model-solving][a tour of mrcal]] for examples. mrcal-2.4.1/doc/stereo.org000066400000000000000000000203171456301662300154040ustar00rootroot00000000000000#+TITLE: Dense stereo processing #+OPTIONS: toc:t * Overview The [[file:tour-stereo.org][tour of mrcal]] shows an example of dense stereo processing done with mrcal; details about that computation appear here. Given a pair of calibrated (both intrinsics and extrinsics) cameras, mrcal can perform stereo processing to produce a dense stereo map. This is relatively slow, and is often overkill for what is actually needed. But sometimes it is useful, and the resulting depth images look /really/ nice. On a high level, mrcal stereo processing is the usual [[https://en.wikipedia.org/wiki/Epipolar_geometry][epipolar geometry]] technique: 1. Ingest - Two camera models, each containing the intrinsics /and/ extrinsics (the relative pose between the two cameras) - A pair of images captured by these two cameras 2. Compute a "rectified" system: a pair of models where each corresponding row of pixels in the two cameras all represent observation rays that lie in the same /epipolar/ plane 3. Reproject the images to these rectified models to produce /rectified/ images 4. Perform "stereo matching". For each pixel in the left rectified image we try to find the corresponding pixel in the same row of the right rectified image. The difference in columns is written to a /disparity/ image. This is the most computationally-intensive part of the process. 5. Convert the /disparity/ image to a /range/ image using the geometry defined by the rectified system The epipolar constraint (all pixels in the same row in both rectified images represent the same plane in space) allows for one-dimensional stereo matching, which is a massive computational win over the two-dimensional matching that would be required with another formulation. The rectified coordinate system looks like this: [[file:figures/rectification.svg]] The code and documentatio refers to two angles: - $\theta$: the "azimuth"; the lateral angle inside the epipolar plane. Related directly to the $x$ pixel coordinate in the rectified images - $\phi$: the "elevation"; the tilt of the epipolar plane. Related directly to the $y$ pixel coordinate in the rectified images * Rectification models :PROPERTIES: :CUSTOM_ID: stereo-rectification-models :END: A rectified system satisfies the epipolar constraint (see above). mrcal supports two models that can have this property, selected with the =rectification_model= argument to [[file:mrcal-python-api-reference.html#-rectified_system][=mrcal.rectified_system()=]] or with the =--rectification= commandline argument to [[file:mrcal-stereo.html][=mrcal-stereo=]]. - [[file:lensmodels.org::#lensmodel-pinhole][=LENSMODEL_PINHOLE=]]: this is the traditional rectification model, used in most existing tools. It works decently well for small fields of view (as with a long lens), but fails with large fields of view (as with a wide lens). The issues stem from the uneven angular resolution across the image, which shoots out to $\infty \frac{\mathrm{pixels}}{\mathrm{deg}}$ as $\theta \rightarrow \pm 90^\circ$. This produces highly distorted rectified images, which affects stereo matching adversely, since areas of disparate resolution are being compared. This is supported by mrcal purely for compatibility with other tools; there's little reason to use this representation otherwise - [[file:lensmodels.org::#lensmodel-latlon][=LENSMODEL_LATLON=]]: this is a "transverse equirectangular projection". It is defined with even angle spacing in both directions, so $x - x_0 = k_x \theta$ and $y - y_0 = k_y \phi$ where $x$ and $y$ are pixel coordinates in the rectified images, $x_0$ and $y_0$ are the centers of projection of the rectified system and $k_x$ and $k_y$ are the angular resolution in the two directions. This is the recommended rectification model, and is the default in mrcal Let's demonstrate the two rectification models. In the [[file:tour-stereo.org][tour of mrcal]] we showed a dense stereo processing sequence. Let's re-rectify those same images and models with =LENSMODEL_PINHOLE= and =LENSMODEL_LATLON=. This is a demo, so I ask for the same pixels/angle resolution at the center of the image in both cases, and demonstrate how this affects the resolution at other parts of the image. #+begin_src sh for model (LENSMODEL_PINHOLE LENSMODEL_LATLON) { mrcal-stereo \ --az-fov-deg 160 \ --el-fov-deg 140 \ --pixels-per-deg -0.05 \ --rectification $model \ [01].cameramodel \ [01].jpg } #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/stereo Dout=~/projects/mrcal-doc-external/figures/stereo mkdir -p $Dout for model (LENSMODEL_PINHOLE LENSMODEL_LATLON) { $PYTHONPATH/mrcal-stereo \ --az-fov-deg 160 \ --el-fov-deg 140 \ --pixels-per-deg -0.05 \ --rectification $model \ --outdir /tmp \ --force \ $D/[01].cameramodel \ $D/[01].jpg mv /tmp/0-rectified.png $Dout/rectified-demo-lowres-${${model/LENSMODEL_/}:l}.png } #+end_src The left image rectified with =LENSMODEL_LATLON= (resolution at the center is 1/20 of the resolution of the original image): [[file:external/figures/stereo/rectified-demo-lowres-latlon.png]] The left image rectified with =LENSMODEL_PINHOLE= (resolution at the center is still 1/20 of the resolution of the original image): [[file:external/figures/stereo/rectified-demo-lowres-pinhole.png]] These are the actual, unscaled rectified images. Note the identical resolution at the center of the image. And note how =LENSMODEL_PINHOLE= rectification causes the image to expand dramatically as we approach the edges. Using =LENSMODEL_PINHOLE= with wide lenses like this introduces an unwinnable trade-off. If you choose the pixels/angle resolution to keep all your information at the center, you'll get a huge image, with low-information pixels at the edges. But if you want to reduce this expansion by lowering the resolution, you'll lose data at the center. Or you can cut off data at the edges. No matter what you do, you either lose information or you're stuck with a huge image. And even if this was all fine, with =LENSMODEL_PINHOLE= the stereo-matching algorithm has to match image patches with widely different resolutions. =LENSMODEL_LATLON= solves all these issues with no down sides, and is thus the recommended rectification function. * Interfaces Currently stereo processing is available via the [[file:mrcal-stereo.html][=mrcal-stereo=]] tool. This tool implements the usual stereo processing for a single frame. More complex usages are available via the Python APIs and the C functions in [[https://www.github.com/dkogan/mrcal/blob/master/stereo.h][=stereo.h=]]. A sequence of images captured with a stereo pair can be processed like this: 1. [[file:mrcal-python-api-reference.html#-rectified_system][=mrcal.rectified_system()=]] to construct the rectified system defined by the stereo pair 2. [[file:mrcal-python-api-reference.html#-rectification_maps][=mrcal.rectification_maps()=]] to construct the pixel mappings needed to transform captured images into rectified images. This is relatively slow, but it depends on the relative stereo geometry only, so this can be computed once, and applied to /all/ the subsequent images captured by the stereo pair 3. For each pair of captured images - [[file:mrcal-python-api-reference.html#-transform_image][=mrcal.transform_image()=]] to generate rectified images - stereo matching to compute disparities. mrcal does not provide its own method, and the [[file:mrcal-stereo.html][=mrcal-stereo=]] tool uses the [[https://docs.opencv.org/4.5.3/d2/d85/classcv_1_1StereoSGBM.html][OpenCV SGBM stereo matcher]]. Any stereo matcher can be used. The result is a /disparity/ image, where each pixel in the first rectified image is mapped to a corresponding pixel offset from the same feature in the second rectified image - [[file:mrcal-python-api-reference.html#-stereo_range][=mrcal.stereo_range()=]] to convert the disparities to ranges, which can then be used to produce a point cloud A demo of the process if shown in the [[file:tour-stereo.org][tour of mrcal]]. mrcal-2.4.1/doc/talk/000077500000000000000000000000001456301662300143225ustar00rootroot00000000000000mrcal-2.4.1/doc/talk/talk.org000066400000000000000000000453321456301662300157750ustar00rootroot00000000000000#+title: mrcal - camera calibrations and more! #+AUTHOR: Dima Kogan #+OPTIONS: toc:nil H:2 #+LATEX_CLASS_OPTIONS: [presentation] #+LaTeX_HEADER: \setbeamertemplate{navigation symbols}{} # I want clickable links to be blue and underlined, as is custom #+LaTeX_HEADER: \usepackage{letltxmacro} #+LaTeX_HEADER: \LetLtxMacro{\hreforiginal}{\href} #+LaTeX_HEADER: \renewcommand{\href}[2]{\hreforiginal{#1}{\color{blue}{\underline{#2}}}} #+LaTeX_HEADER: \renewcommand{\url}[1]{\href{#1}{\tt{#1}}} # I want a visible gap between paragraphs #+LaTeX_HEADER: \setlength{\parskip}{\smallskipamount} * Overview ** Where is all this? Documentation, installation instructions and everything else are available here: - http://mrcal.secretsauce.net/ This talk is a condensed version of the "tour of mrcal" page: - http://mrcal.secretsauce.net/tour.html Please see that page for a bit more detail, and for links to all the data and commands in the studies I'll discuss ** mrcal: calibrations and other stuff I couldn't find a set of tools to make my visual ranging work possible, so I wrote my own: - A set of C, Python libraries to work with - camera models - 3D geometry - images - Lots of analysis, tools available - Fancy lens models - Lots of visualization facilities - Many commandline tools available, so no coding required for many tasks ** Tour of mrcal I will go through the "tour of mrcal" page: - http://mrcal.secretsauce.net/tour.html We follow a real-world data flow, from chessboard observations to stereo processing. Images captured using - Nikon D750 full-frame SLR. 6000x4000 imager - /Very/ wide lens: Samyang 12mm F2.8 fisheye. 180deg field of view corner-corner - Just one camera * Corners ** Gathering corners This is a wide lens, so we have a large chessboard: - 10x10 point grid - 7.7cm between adjacent points Most observations take right in front of the lens, so depth of field is a concern. Thus - Images gathered outside - F22 ** Corner detections mrgingham corner detections look like this for an arbitrary image: #+ATTR_LATEX: :width \linewidth [[file:../external/figures/calibration/mrgingham-results.png]] * Calibrating opencv8 ** Let's run a calibration! This is a wide lens, so we need a lens model that can handle it. Let's use the 8-parameter OpenCV model: =LENSMODEL_OPENCV8= #+begin_example $ mrcal-calibrate-cameras --lensmodel LENSMODEL_OPENCV8 ... ... RMS reprojection error: 0.8 pixels Noutliers: 3 out of 18600 total points: 0.0% of the data calobject_warp = [-0.00103983 0.00052493] #+end_example Let's examine the solution. We want the errors in the solve to follow the mrcal noise model, and if they don't, we want to try to fix it. ** Noise model mrcal assumes that - The model (lens parameters, geometry, ...) accurately represents reality - All errors (differences between the observations of the chessboard and what the model predicts) come from observation noise - The errors are independent, gaussian and have the same variance everywhere If all those assumptions are true, then the results of the least-squares optimization (what the calibration routine is doing) are the maximum-likelihood solution. We will never satisfy all these assumptions, but we should try hard to do that. ** Does the solved geometry look right? #+ATTR_LATEX: :width 0.8\linewidth [[file:../external/figures/calibration/calibration-chessboards-geometry.pdf]] Yes. That's how I danced. ** =LENSMODEL_OPENCV8= residuals histogram What does the error distribution look like? #+ATTR_LATEX: :width 0.9\linewidth [[file:../external/figures/calibration/residuals-histogram-opencv8.pdf]] ** =LENSMODEL_OPENCV8= worst-observation residuals The worst-fitting observations are a great way to see common issues such as: - out-of focus images - images with motion blur - rolling shutter effects - synchronization errors - chessboard detector failures - insufficiently-rich models (of the lens or of the chessboard shape or anything else) Any of these would violate the assumptions of the noise model, so we want to fix them ** =LENSMODEL_OPENCV8=: the worst image #+ATTR_LATEX: :width \linewidth [[file:../external/figures/calibration/worst-opencv8.png]] ** =LENSMODEL_OPENCV8=: the 3rd-worst image #+ATTR_LATEX: :width \linewidth [[file:../external/figures/calibration/worst-incorner-opencv8.png]] ** =LENSMODEL_OPENCV8=: residual directions #+ATTR_LATEX: :width \linewidth [[file:../external/figures/calibration/directions-opencv8.pdf]] ** =LENSMODEL_OPENCV8=: conclusions The =LENSMODEL_OPENCV8= lens model does not fit our data in observable ways. These unmodeled errors are small, but cause big problems when doing precision work, for instance with long-range stereo. Let's fix it. * Calibrating splined models ** =LENSMODEL_SPLINED_STEREOGRAPHIC= definition - We need a more flexible lens model to represent our lens. - mrcal currently supports a /splined/ model that is configurable to be as rich as we like We compute a normalized /stereographic/ projection: \[ \vec u = \mathrm{project}_\mathrm{stereographic}\left(\vec p\right) \] This maps a 3D direction vector to a 2D point $\vec u$. This works behind the camera, so wide-angle lenses are supported well. ** =LENSMODEL_SPLINED_STEREOGRAPHIC= definition Then use $\vec u$ to look-up an adjustment factor $\Delta \vec u$ using two splined surfaces: one for each of the two elements of \[ \Delta \vec u \equiv \left[ \begin{aligned} \Delta u_x \left( \vec u \right) \\ \Delta u_y \left( \vec u \right) \end{aligned} \right] \] We can then define the rest of the projection function: \[\vec q = \left[ \begin{aligned} f_x \left( u_x + \Delta u_x \right) + c_x \\ f_y \left( u_y + \Delta u_y \right) + c_y \end{aligned} \right] \] ** Let's re-run the calibration Let's re-process the same calibration data using this splined model. We run the same command as before, but using the =LENSMODEL_SPLINED_STEREOGRAPHIC_= ... =order=3_Nx=30_Ny=20_fov_x_deg=170= model. This is one long string. #+begin_example $ mrcal-calibrate-cameras --lensmodel LENSMODEL_SPLINED_STEREOGRAPHIC_ ... ... order=3_Nx=30_Ny=20_fov_x_deg=170 ... ... RMS reprojection error: 0.6 pixels Noutliers: 0 out of 18600 total points: 0.0% of the data calobject_warp = [-0.00096895 0.00052931] #+end_example ** =LENSMODEL_SPLINED_STEREOGRAPHIC= residuals histogram This is promising. What does the histogram look like? #+ATTR_LATEX: :width 0.9\linewidth [[file:../external/figures/calibration/residuals-histogram-splined.pdf]] ** =LENSMODEL_SPLINED_STEREOGRAPHIC=: the worst image #+ATTR_LATEX: :width \linewidth [[file:../external/figures/calibration/worst-splined.png]] ** =LENSMODEL_SPLINED_STEREOGRAPHIC=: 3rd-worst image #+ATTR_LATEX: :width \linewidth [[file:../external/figures/calibration/worst-incorner-splined.png]] ** =LENSMODEL_SPLINED_STEREOGRAPHIC=: residual directions #+ATTR_LATEX: :width \linewidth [[file:../external/figures/calibration/directions-splined.png]] * Differencing ** Differencing We computed the calibration two different ways. How different are the two models? Let's compute the difference using an obvious algorithm: Given a pixel $\vec q_0$, - Unproject $\vec q_0$ to a fixed point $\vec p$ using lens 0 - Project $\vec p$ back to pixel coords $\vec q_1$ using lens 1 - Report the reprojection difference $\vec q_1 - \vec q_0$ #+ATTR_LATEX: :width 0.8\linewidth [[file:../figures/diff-notransform.pdf]] ** Differencing #+ATTR_LATEX: :width \linewidth [[file:../external/figures/diff/diff-radius0-heatmap-splined-opencv8.png]] ** Differencing #+ATTR_LATEX: :width \linewidth [[file:../external/figures/diff/diff-radius0-vectorfield-splined-opencv8.pdf]] ** Differencing So with a motion of the camera, we can make the errors disappear. The issue is that each calibration produces noisy estimates of all the intrinsics and all the coordinate transformations: [[file:../figures/uncertainty.pdf]] And the point $\vec p$ we were projecting wasn't truly fixed. ** Differencing We want to add a step: - Unproject $\vec q_0$ to a fixed point $\vec p_0$ using lens 0 - *Transform $\vec p_0$ from the coordinate system of one camera to the coordinate system of the other camera* - Project $\vec p_1$ back to pixel coords $\vec q_1$ using lens 1 - Report the reprojection difference $\vec q_1 - \vec q_0$ [[file:../figures/diff-yestransform.pdf]] ** Differencing #+ATTR_LATEX: :width \linewidth [[file:../external/figures/diff/diff-splined-opencv8.png]] ** Differencing /Much/ better. As expected, the two models agree relatively well in the center, and the error grows as we move towards the edges. This differencing method has numerous applications: - evaluating the manufacturing variation of different lenses - quantifying intrinsics drift due to mechanical or thermal stresses - testing different solution methods - underlying a cross-validation scheme ** Differencing A big question: - How much of the observed difference is random sampling error? To answer this (an other) questions, mrcal can quantify the projection uncertainty, so let's do that. * Uncertainty ** Uncertainty When we project a point $\vec p$ to a pixel $\vec q$, it would be /really/ nice to get an uncertainty estimate $\mathrm{Var} \left(\vec q\right)$. The we could - Propagate this uncertainty downstream to whatever uses the projection operation, for example to get the uncertainty of ranges from a triangulation - Evaluate how trustworthy a given calibration is, and to run studies about how to do better - Quantify overfitting effects - Quantify the baseline noise level for informed interpretation of model differences Since splined models can have 1000s of parameters (the one we just demoed has 1204), they are prone to overfitting, and it's critically important to gauge those effects. ** Uncertainty A grand summary of how we do this: 1. We are assuming a particular distribution of observation input noise $\mathrm{Var}\left( \vec q_\mathrm{ref} \right)$ 2. We propagate it through the optimization to get the variance of the optimization state $\mathrm{Var}(\vec b)$ 3. For any /fixed/ point, its projection $\vec q = \mathrm{project}\left( \mathrm{transform}\left( \vec p_\mathrm{fixed} \right)\right)$ depends on parameters of $\vec b$, whose variance we know. So \[ \mathrm{Var}\left( \vec q \right) = \frac{\partial \vec q}{\partial \vec b} \mathrm{Var}\left( \vec b \right) \frac{\partial \vec q}{\partial \vec b}^T \] ** Uncertainty simulation The mrcal test suite contains a simulation to validate the approach. - 4 cameras - Placed side by side + noise in pose - =LENSMODEL_OPENCV4= lens model - looking at 50 chessboard poses, with randomized pose ** Uncertainty simulation The geometry looks like this: #+ATTR_LATEX: :width \linewidth [[file:../external/figures/uncertainty/simulated-uncertainty-opencv4--simulated-geometry.pdf]] ** Uncertainty simulation Each camera sees this: #+ATTR_LATEX: :width \linewidth [[file:../external/figures/uncertainty/simulated-uncertainty-opencv4--simulated-observations.pdf]] The red *$\ast$* is a point we will examine. ** Uncertainty simulation #+ATTR_LATEX: :width \linewidth [[file:../external/figures/uncertainty/simulated-uncertainty-opencv4--distribution-onepoint.pdf]] ** Uncertainty simulation Let's look at the uncertainty everywhere in the imager #+ATTR_LATEX: :width \linewidth [[file:../external/figures/uncertainty/simulated-uncertainty-opencv4--uncertainty-wholeimage-noobservations.pdf]] This confirms the expectation: the sweet spot of low uncertainty follows the region where the chessboards were ** Uncertainty simulation - The worst-uncertainty-at-*$\ast$* camera claims an uncertainty of 0.8 pixels. That's pretty low. But we had no chessboard observations there; is this uncertainty realistic? _No_ - =LENSMODEL_OPENCV4= is stiff, so the projection doesn't move much due to noise. And we interpreted that as low uncertainty. But that comes from our choice of model, and /not/ from the data. So *Lean models always produce overly-optimistic uncertainty estimates* Solution: use splined models! They are very flexible, and don't have this issue. ** Uncertainty simulation Running the same simulation with a splined model, we see the /real/ projection uncertainty: #+ATTR_LATEX: :width \linewidth [[file:../external/figures/uncertainty/simulated-uncertainty-splined--uncertainty-wholeimage-noobservations.pdf]] So /only/ the first camera actually had usable projections. ** Uncertainty simulation Let's overlay the observations: #+ATTR_LATEX: :width \linewidth [[file:../external/figures/uncertainty/simulated-uncertainty-splined--uncertainty-wholeimage-observations.pdf]] ** Uncertainty from previous calibrations Computing the uncertainty map from the earlier =LENSMODEL_OPENCV8= calibration: #+ATTR_LATEX: :width \linewidth [[file:../external/figures/uncertainty/uncertainty-opencv8.pdf]] ** Uncertainty from previous calibrations And from the =LENSMODEL_SPLINED_STEREOGRAPHIC_...= calibration: #+ATTR_LATEX: :width \linewidth [[file:../external/figures/uncertainty/uncertainty-splined.pdf]] ** Uncertainty conclusion The splined model promises double the uncertainty that =LENSMODEL_OPENCV8= does. Conclusions: - We have a usable uncertainty-quantification method - It is over-optimistic when applied to lean models So splined models have a clear benefit even for long lenses, where the lean models are expected to fit * Ranging note ** Ranging note Let's revisit an important detail I glossed-over when talking about differencing and uncertainties. Both computations begin with $\vec p = \mathrm{unproject}\left( \vec q \right)$ But an unprojection is ambiguous in range, so *diffs and uncertainties are defined as a function of range* #+ATTR_LATEX: :width \linewidth [[file:../figures/projection-scale-invariance.pdf]] All the uncertainties reported so far, were at $\infty$ ** The uncertainty figure The uncertainty of our =LENSMODEL_OPENCV8= calibration at the center as a function of range: #+ATTR_LATEX: :width 0.8\linewidth [[file:../external/figures/uncertainty/uncertainty-vs-distance-at-center.pdf]] * Choreography ** Overview We have a good way to estimate uncertainties, so let's study what kind of chessboard dance is best. We - set up a simulated world with some baseline geometry - scan some parameter - calibrate - look at the uncertainty-vs-range plots as a function of that parameter This is output of a tool included in the mrcal tree. See the [[http://mrcal.secretsauce.net/tour.html][tour of mrcal]] page for the commands. ** How many chessboard observations should we get? #+ATTR_LATEX: :width \linewidth [[file:../external/figures/dance-study/dance-study-scan-Nframes.pdf]] ** How far should the chessboards be placed? #+ATTR_LATEX: :width \linewidth [[file:../external/figures/dance-study/dance-study-scan-range.pdf]] ** How much should we tilt the chessboards? #+ATTR_LATEX: :width \linewidth [[file:../external/figures/dance-study/dance-study-scan-tilt_radius.pdf]] ** How many cameras should be included in each calibration? #+ATTR_LATEX: :width \linewidth [[file:../external/figures/dance-study/dance-study-scan-Ncameras.pdf]] ** How dense should our chessboard be? #+ATTR_LATEX: :width \linewidth [[file:../external/figures/dance-study/dance-study-scan-object_width_n.pdf]] ** What should the chessboard corner spacing be? #+ATTR_LATEX: :width \linewidth [[file:../external/figures/dance-study/dance-study-scan-object_spacing.pdf]] ** Do we want tiny boards nearby or giant boards faraway? #+ATTR_LATEX: :width \linewidth [[file:../external/figures/dance-study/dance-study-scan-object_spacing-compensated-range.pdf]] ** Conclusions - More frames are good - Closeups are /extremely/ important - Tilted views are good - A smaller number of bigger calibration problems is good - More chessboard corners is good, as long as the detector can find them reliably - Tiny chessboards near the camera are better than giant far-off chessboards. As long as the camera can keep the chessboards /and/ the working objects in focus #+ATTR_LATEX: :width 0.7\linewidth [[file:../figures/observation-usefulness.pdf]] * Stereo ** Overview mrcal can do some basic stereo processing. At its core, it's the usual epipolar geometry process: 1. Ingest two camera models 2. Ingest images captured by these two cameras 3. Transform the images to construct "rectified" images 4. Perform "stereo matching" Each pair of corresponding rows in the rectified images represents a plane in space: #+ATTR_LATEX: :width 0.65\linewidth [[file:../figures/rectification.pdf]] ** Input images I used the lens I calibrated at the start to capture a pair of images in downtown Los Angeles. The left image: #+ATTR_LATEX: :width 0.75\linewidth [[file:../external/figures/stereo/0.downsampled.jpg]] We're on a catwalk between 2nd and 3rd, looking S over Figueroa St. ** Rectification I then used mrcal's rectification function to produce the rectified image. The left: #+ATTR_LATEX: :width 0.7\linewidth file:../external/figures/stereo/rectified0-splined.downsampled.jpg ** Disparity And the resulting disparity, as computed by the OpenCV matcher: #+ATTR_LATEX: :width 0.7\linewidth file:../external/figures/stereo/disparity-splined.downsampled.png ** JPLV What if we wanted to use JPLV stereo with splined models? We can use mrcal to remap to another projection and feed /that/ to jplv. For instance, let's - Remap to a pinhole model (with some arbitrary zoom factor) - Use jplv to compute the rectified image ** JPLV remapped-to-pinhole image Remapped to a pinhole image with mrcal #+ATTR_LATEX: :width 0.9\linewidth file:../external/figures/stereo/0-reprojected-scale0.35.downsampled.jpg ** JPLV rectified image Rectified with jplv #+ATTR_LATEX: :width 0.9\linewidth file:../external/figures/stereo/jplv-stereo-rect-left-scale0.35.downsampled.png ** JPLV stereo Disparity from OpenCV #+ATTR_LATEX: :width 0.9\linewidth file:../external/figures/stereo/disparity-jplv-scale0.35.downsampled.png ** Narrow virtual cameras Another way to do stereo processing of wide images using tools that aren't built for it is to - split the wide-angle stereo pair into a set of narrow-view stereo pairs This generates a skewed geometry, but mrcal can still use it just fine. Due to a bug, jplv cannot. ** Narrow virtual cameras #+ATTR_LATEX: :width 0.9\linewidth file:../external/figures/stereo/stereo-geometry-narrow.pdf ** Narrow virtual cameras One of the resulting resampled /pinhole/ images: #+ATTR_LATEX: :width 0.9\linewidth file:../external/figures/stereo/narrow-left.downsampled.jpg ** Narrow virtual cameras Rectified using mrcal #+ATTR_LATEX: :width 0.9\linewidth file:../external/figures/stereo/rectified0-narrow.downsampled.jpg ** Narrow virtual cameras Disparity from OpenCV #+ATTR_LATEX: :width 0.9\linewidth file:../external/figures/stereo/disparity-narrow.downsampled.png * Finally ** Conclusions - We have a toolkit that can do lots of cool stuff - There's much to do still, and there's a laundry list on the documentation page. ** Thanks! Questions? mrcal-2.4.1/doc/tour-choreography.org000066400000000000000000000400431456301662300175620ustar00rootroot00000000000000#+title: A tour of mrcal: optimal choreography #+OPTIONS: toc:t * Previous We just [[file:tour-effect-of-range.org][discussed the effect of range in differencing and uncertainty computations]]. * Optimal choreography Now that we know how to measure calibration quality and what to look for, we can run some studies to figure out what makes a good chessboard dance. These are all computed by the [[https://www.github.com/dkogan/mrcal/blob/master/analyses/dancing/dance-study.py][=analyses/dancing/dance-study.py=]] tool. It generates synthetic data, scans a parameter, and produces the uncertainty-vs-range curves at the imager center to visualize the effect of that parameter. I run all of these studies using the =LENSMODEL_OPENCV8= model. It computes faster than the splined model, and qualitatively produces similar results. ** How many chessboard observations should we get? #+begin_src sh dance-study.py \ --scan Nframes \ --Ncameras 1 \ --Nframes 20,200 \ --range 0.5 \ --observed-pixel-uncertainty 2 \ --ymax 1 \ opencv8.cameramodel #+end_src #+begin_src sh :exports none :eval no-export mkdir -p ~/projects/mrcal-doc-external/figures/dance-study D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity PYTHONPATH=~/projects/mrcal; \ export PYTHONPATH; \ $PYTHONPATH/analyses/dancing/dance-study.py \ --scan Nframes \ --Ncameras 1 \ --Nframes 20,200 \ --range 0.5 \ --observed-pixel-uncertainty 2 \ --ymax 1 \ $D/opencv8.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/dance-study/dance-study-scan-Nframes.svg \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' > /dev/null #+end_src [[file:external/figures/dance-study/dance-study-scan-Nframes.svg]] Here I'm running a monocular solve that looks at chessboards ~ 0.5m away, scanning the frame count from 20 to 200. The horizontal dashed lines in these plots is the uncertainty of the input noise observations: 2 pixels. We can usually do much better than that. The vertical dashed line is the mean distance where we observed the chessboards. Looks like the sweet spot is a bit past that. And it looks like more observations is always better, but we reach the point of diminishing returns at ~ 100 frames. ** How close should the chessboards be? :PROPERTIES: :CUSTOM_ID: choreography-distance :END: #+begin_src sh dance-study.py \ --scan range \ --Ncameras 1 \ --Nframes 100 \ --range 0.4,10 \ --observed-pixel-uncertainty 2 \ opencv8.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity PYTHONPATH=~/projects/mrcal; \ export PYTHONPATH; \ $PYTHONPATH/analyses/dancing/dance-study.py \ --scan range \ --Ncameras 1 \ --Nframes 100 \ --range 0.4,10 \ --observed-pixel-uncertainty 2 \ $D/opencv8.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/dance-study/dance-study-scan-range.svg \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' > /dev/null #+end_src [[file:external/figures/dance-study/dance-study-scan-range.svg]] This effect is /dramatic/: we want closeups. Anything else is a waste of time. Here we have two vertical dashed lines, indicating the minimum and maximum ranges I'm scanning. And we can see that the sweet spot moves further back as we move the chessboards back. ** Should the chessboards be shown head-on, or should they be tilted? :PROPERTIES: :CUSTOM_ID: tilt :END: #+begin_src sh dance-study.py \ --scan tilt_radius \ --tilt-radius 0,80 \ --Ncameras 1 \ --Nframes 100 \ --range 0.5 \ --observed-pixel-uncertainty 2 \ --ymax 2 \ --uncertainty-at-range-sampled-max 5 \ opencv8.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity PYTHONPATH=~/projects/mrcal; \ export PYTHONPATH; \ $PYTHONPATH/analyses/dancing/dance-study.py \ --scan tilt_radius \ --tilt-radius 0,80 \ --Ncameras 1 \ --Nframes 100 \ --range 0.5 \ --observed-pixel-uncertainty 2 \ --ymax 2 \ --uncertainty-at-range-sampled-max 5 \ $D/opencv8.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/dance-study/dance-study-scan-tilt_radius.svg \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' > /dev/null #+end_src [[file:external/figures/dance-study/dance-study-scan-tilt_radius.svg]] The head-on views (tilt = 0) produce quite poor results. And we get more and more confidence with more board tilt, with diminishing returns at about 45 degrees. We now know that we want closeups and we want tilted views. This makes intuitive sense: a tilted close-up view is the best-possible view for the solver to disambiguate focal length effects from the effects of chessboard range. The worst-possible observations for this are head-on far-away views. Given such observations, moving the board forward/backward and changing the focal length have a very similar effect on the observed pixels. Also this clearly tells us that /chessboards/ are the way to go, and a calibration object that contains a grid of circles will work badly. Circle grids work either by finding the centroid of each circle "blob" or by fitting a curve to the circle edge to infer the location of the center. A circle viewed from a tilted closeup will appear lopsided, so we have a choice of suffering a bias from imprecise circle detections or getting poor uncertainties from insufficient tilt. Extra effort can be expended to improve this situation to make circle grids usable, or chessboards can be used. ** How many cameras should observe the chessboard? Moving on. Often we want to calibrate multiple cameras, and if we only care about the intrinsics we are free to do one N-way calibration or N separate monocular calibrations or anything in-between. The former has more constraints, so presumably that would produce less uncertainty. How much? I'm processing the same calibration geometry, varying the number of cameras from 1 to 8. The cameras are all in the same physical location, so they're all seeing the same thing (modulo the noise), but the solves have different numbers of parameters and constraints. #+begin_src sh dance-study.py \ --scan Ncameras \ --Ncameras 1,8 \ --camera-spacing 0 \ --Nframes 100 \ --range 0.5 \ --ymax 0.4 \ --uncertainty-at-range-sampled-max 10 \ --observed-pixel-uncertainty 2 \ opencv8.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity PYTHONPATH=~/projects/mrcal; \ export PYTHONPATH; \ $PYTHONPATH/analyses/dancing/dance-study.py \ --scan Ncameras \ --Ncameras 1,8 \ --camera-spacing 0 \ --Nframes 100 \ --range 0.5 \ --ymax 0.4 \ --uncertainty-at-range-sampled-max 10 \ --observed-pixel-uncertainty 2 \ $D/opencv8.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/dance-study/dance-study-scan-Ncameras.svg \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' > /dev/null #+end_src [[file:external/figures/dance-study/dance-study-scan-Ncameras.svg]] Clearly there's a benefit to more cameras. After about 4, we hit diminishing returns. That's great. We now know how to dance given a particular chessboard. But what kind of chessboard do we want? mrcal assumes a chessboard being an evenly-spaced planar grid with any number of points and any spacing. ** How dense should the chessboard pattern be? Let's examine the point counts. We expect that adding more points to a chessboard of the same size would produce better results, since we would have strictly more data to work with. This expectation is correct: #+begin_src sh dance-study.py \ --scan object_width_n \ --range 2 \ --Ncameras 1 \ --Nframes 100 \ --object-width-n 5,30 \ --uncertainty-at-range-sampled-max 30 \ --observed-pixel-uncertainty 2 \ opencv8.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity PYTHONPATH=~/projects/mrcal; \ export PYTHONPATH; \ $PYTHONPATH/analyses/dancing/dance-study.py \ --scan object_width_n \ --range 2 \ --Ncameras 1 \ --Nframes 100 \ --object-width-n 5,30 \ --uncertainty-at-range-sampled-max 30 \ --observed-pixel-uncertainty 2 \ $D/opencv8.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/dance-study/dance-study-scan-object_width_n.svg \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' > /dev/null #+end_src [[file:external/figures/dance-study/dance-study-scan-object_width_n.svg]] Here we varied =object-width-n=, but also adjusted =object-spacing= to keep the chessboard size the same. ** How big should the chessboard be? What if we leave the point counts alone, but vary the spacing? As we increase the point spacing, the board grows in size, spanning more and more of the imager. We expect this would improve things: #+begin_src sh dance-study.py \ --scan object_spacing \ --range 2 \ --Ncameras 1 \ --Nframes 100 \ --object-spacing 0.04,0.20 \ --observed-pixel-uncertainty 2 \ opencv8.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity PYTHONPATH=~/projects/mrcal; \ export PYTHONPATH; \ $PYTHONPATH/analyses/dancing/dance-study.py \ --scan object_spacing \ --range 2 \ --Ncameras 1 \ --Nframes 100 \ --object-spacing 0.04,0.20 \ --observed-pixel-uncertainty 2 \ --hardcopy ~/projects/mrcal-doc-external/figures/dance-study/dance-study-scan-object_spacing.svg \ $D/opencv8.cameramodel \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' > /dev/null #+end_src [[file:external/figures/dance-study/dance-study-scan-object_spacing.svg]] And it does. At the same range, a bigger chessboard is better. Finally, what if we increase the spacing (and thus the board size), but also move the board back to compensate, so the apparent size of the chessboard stays the same? I.e. do we want a giant board far away or a tiny board really close in? #+begin_src sh dance-study.py \ --scan object_spacing \ --scan-object-spacing-compensate-range-from 0.04 \ --range 2 \ --Ncameras 1 \ --Nframes 100 \ --object-spacing 0.04,0.20 \ --ymax 20 \ --uncertainty-at-range-sampled-max 200 \ --observed-pixel-uncertainty 2 \ opencv8.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity PYTHONPATH=~/projects/mrcal; \ export PYTHONPATH; \ $PYTHONPATH/analyses/dancing/dance-study.py \ --scan object_spacing \ --scan-object-spacing-compensate-range-from 0.04 \ --range 2 \ --Ncameras 1 \ --Nframes 100 \ --object-spacing 0.04,0.20 \ --ymax 20 \ --uncertainty-at-range-sampled-max 200 \ --observed-pixel-uncertainty 2 \ --hardcopy ~/projects/mrcal-doc-external/figures/dance-study/dance-study-scan-object_spacing-compensated-range.svg \ $D/opencv8.cameramodel \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' > /dev/null #+end_src [[file:external/figures/dance-study/dance-study-scan-object_spacing-compensated-range.svg]] Looks like the optimal uncertainty is similar in all cases, but tracks the moving range. The uncertainty at infinity is roughly similar in all cases. This is expected: we care about the size of the chessboard relative to its distance from the camera, and that is constant here. Conclusions: - More frames are good - Closeups are /extremely/ important (up to some [[file:how-to-calibrate.org::#dancing][practical limits]]) - Tilted views are good - A smaller number of bigger calibration problems is good - More chessboard corners is good, as long as the detector can find them reliably [[file:figures/observation-usefulness.svg]] None of these are surprising, but it's good to see the effects directly from the data. And we now know /exactly/ how much value we get out of each additional observation or an extra little bit of board tilt or some extra chessboard corners. Before moving on, I should stress that the results presented here represent a particular scenario using a =LENSMODEL_OPENCV8= lens, and produce clear rules of thumb. For a /specific/ lens and geometry, rerun these studies for your use cases. * Next [[file:tour-stereo.org][We can now use the models for stereo processing]] mrcal-2.4.1/doc/tour-cross-validation.org000066400000000000000000000227761456301662300203660ustar00rootroot00000000000000#+title: A tour of mrcal: cross-validation #+OPTIONS: toc:nil * Previous We just [[file:tour-uncertainty.org][computed the projection uncertainties of the models]] * Cross-validation We now have a good method to evaluate the quality of a calibration: the [[file:uncertainty.org][projection uncertainty]]. Is that enough? If we run a calibration and see a low projection uncertainty, can we assume that the computed model is good, and use it moving forward? Once again, unfortunately, we cannot. A low projection uncertainty tells us that we're not sensitive to noise in the observed chessboard corners. However it says nothing about the effects of model errors. Anything that makes our model not fit produces a model error. These can be caused by any of (for instance) - out-of focus images - images with motion blur - [[https://en.wikipedia.org/wiki/Rolling_shutter][rolling shutter]] effects - camera synchronization errors - chessboard detector failures - insufficiently-rich models (of the lens or of the chessboard shape or anything else) If model errors were present, then - the computed projection uncertainty would underestimate the expected errors: the non-negligible model errors would be ignored - the computed calibration would be biased: the residuals $\vec x$ would be heteroscedastic, so the computed optimum would /not/ be a maximum-likelihood estimate of the true calibration (see the [[file:formulation.org::#noise-model][noise modeling page]]) By definition, model errors are unmodeled, so we cannot do anything with them analytically. Instead we try hard to force these errors to zero, so that we can ignore them. To do that, we need the ability to detect the presense of model errors. The [[file:tour-initial-calibration.org::#opencv8-solve-diagnostics][solve diagnostics we talked about earlier]] are a good start. An even more powerful technique is computing a /cross-validation diff/: - We gather not one, but two sets of chessboard observations - We compute two completely independent calibrations of these cameras using the two independent sets of observations - We use the [[file:mrcal-show-projection-diff.html][=mrcal-show-projection-diff=]] tool to compute the difference. The two separate calibrations sample the input noise /and/ the model noise. This is, in effect, an empirical measure of uncertainty. If we gathered lots and lots of calibration datasets (many more than just two), the resulting empirical distribution of projections would conclusively tell us about the calibration quality. Here we try to get away with just two empirical samples and the computed projection uncertainty to quantify the response to input noise. If the model noise is negligible, as we would like it to be, then the cross-validation diff contains sampling noise only, and the computed uncertainty becomes the authoritative gauge of calibration quality. In this case we would see a difference on the order of $\mathrm{difference} \approx \mathrm{uncertainty}_0 + \mathrm{uncertainty}_1$. It would be good to define this more rigorously, but in my experience, even this loose definition is sufficient, and this technique works quite well. For the Downtown LA dataset I /did/ gather more than one set of images, so let's compute the cross-validation diff using our data. We already saw evidence that =LENSMODEL_OPENCV8= doesn't fit well. What does its cross-validation diff look like? #+begin_src sh mrcal-show-projection-diff \ --cbmax 2 \ --unset key \ 2-f22-infinity.opencv8.cameramodel \ 3-f22-infinity.opencv8.cameramodel #+end_src #+begin_src sh :exports none :eval no-export mkdir -p ~/projects/mrcal-doc-external/figures/cross-validation/ D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/ mrcal-show-projection-diff \ --cbmax 2 \ --unset key \ $D/[23]-f22-infinity/opencv8.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/cross-validation/diff-cross-validation-opencv8.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' #+end_src [[file:external/figures/cross-validation/diff-cross-validation-opencv8.png]] A reminder, the computed dance-2 uncertainty (response to sampling error) looks like this: [[file:external/figures/uncertainty/uncertainty-opencv8.png]] The dance-3 uncertainty looks similar. So if we have low model errors, the cross-validation diff whould be within ~0.2 pixels in most of the image. Clearly this model does /far/ worse than that. So we can conclude that =LENSMODEL_OPENCV8= doesn't fit well. We expect the splined model to do better. Let's see. The cross-validation diff: #+begin_src sh mrcal-show-projection-diff \ --cbmax 2 \ --unset key \ 2-f22-infinity.splined.cameramodel \ 3-f22-infinity.splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export mkdir -p ~/projects/mrcal-doc-external/figures/cross-validation/ D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/ mrcal-show-projection-diff \ --cbmax 2 \ --unset key \ $D/[23]-f22-infinity/splined.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/cross-validation/diff-cross-validation-splined.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' #+end_src [[file:external/figures/cross-validation/diff-cross-validation-splined.png]] And the dance-2 uncertainty (from before): [[file:external/figures/uncertainty/uncertainty-splined.png]] Much better. It's an improvement over =LENSMODEL_OPENCV8=, but it's still noticeably not fitting. So we can explain ~0.2-0.4 pixels of the error away from the edges (twice the uncertainty), but the other 0.5-1.0 pixels of error (or more if considering the data at the edges) is unexplained. Thus any application that requires an accuracy of <1 pixel would have problems with this calibration. I know from past experience with this lens that the biggest problem here is caused by [[file:formulation.org::#lens-behavior][mrcal assuming a central projection in its models]]: it assumes that all rays intersect at a single point. This is an assumption made by more or less every calibration tool, and most of the time it's reasonable. However, this assumption breaks down when you have a physically large, wide-angle lens looking at objects /very/ close to the lens: exactly the case we have here. In most cases, you will never use the camera system to observe extreme closeups, so it /is/ reasonable to assume that the projection is central. But this assumption breaks down if you gather calibration images so close as to need the noncentral behavior. If the calibration images were gathered from too close, we would see a too-high cross-validation diff, as we have here. The recommended remedy is to gather new calibration data from further out, to minimize the noncentral effects. The /current/ calibration images were [[file:tour-choreography.org::#choreography-distance][gathered from very close-in]] to maximize the [[file:tour-uncertainty.org][projection uncertainty]]. So getting images from further out would produce a higher-uncertainty calibration, and we would need to capture a larger number of chessboard observations to compensate. Here I did not gather new calibration data, so we do the only thing we can: we model the noncentral behavior. [[https://github.com/dkogan/mrcal/tree/noncentral][A branch of mrcal]] contains an experimental and not-entirely-complete support for noncentral projections. I solved this calibration problem with that code, and the result does fit our data /much/ better. The cross-validation diff: #+begin_src sh :exports none :eval no-export mkdir -p ~/projects/mrcal-doc-external/figures/cross-validation/ D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/ function c { < $1 ~/projects/mrcal-noncentral/analyses/noncentral/centralize.py 3 } mrcal-show-projection-diff \ --no-uncertainties \ --radius 500 \ --cbmax 2 \ --unset key \ <(c $D/2-*/splined-noncentral.cameramodel) \ <(c $D/3-*/splined-noncentral.cameramodel) \ --hardcopy ~/projects/mrcal-doc-external/figures/cross-validation/diff-cross-validation-splined-noncentral.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' #+end_src [[file:external/figures/cross-validation/diff-cross-validation-splined-noncentral.png]] This still isn't perfect, but it's close. The noncentral projection support is not yet done. Talk to me if you need it. A more rigorous interpretation of these cross-validation results would be good, but a human interpretation is working well, so it's low-priority for me at the moment. * Next Now [[file:tour-effect-of-range.org][we discuss the effect of range in differencing and uncertainty computations]]. mrcal-2.4.1/doc/tour-differencing.org000066400000000000000000000172401456301662300175160ustar00rootroot00000000000000#+title: A tour of mrcal: differencing #+OPTIONS: toc:nil * Previous We just [[file:tour-initial-calibration.org][gathered calibration images and computed some calibrations]]. * Differencing An overview follows; see the [[file:differencing.org][differencing page]] for details. We just used the same chessboard observations to compute the intrinsics of a lens in two different ways: - Using a lean =LENSMODEL_OPENCV8= lens model - Using a rich splined-stereographic lens model And we saw evidence that the splined model does a better job of representing reality. Can we quantify that? Let's compute the difference. There's an obvious algorithm: given a pixel $\vec q_0$ we 1. Unproject $\vec q_0$ to a fixed point $\vec p$ using lens 0 2. Project $\vec p$ back to pixel coords $\vec q_1$ using lens 1 3. Report the reprojection difference $\vec q_1 - \vec q_0$ [[file:figures/diff-notransform.svg]] This is a very common thing to want to do, so mrcal provides a [[file:mrcal-show-projection-diff.html][tool]] to do it. Let's compare the two models: #+begin_src sh mrcal-show-projection-diff \ --intrinsics-only \ --cbmax 15 \ --unset key \ opencv8.cameramodel \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export mkdir -p ~/projects/mrcal-doc-external/figures/diff D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ mrcal-show-projection-diff \ --intrinsics-only \ --cbmax 15 \ --unset key \ $D/{opencv8,splined}.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/diff/diff-radius0-heatmap-splined-opencv8.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' #+end_src [[file:external/figures/diff/diff-radius0-heatmap-splined-opencv8.png]] Well that's strange. The reported differences really do have units of /pixels/. Are the two models really /that/ different? If we ask for the vector field of differences instead of a heat map, we get a hint about what's going on: #+begin_src sh mrcal-show-projection-diff \ --intrinsics-only \ --vectorfield \ --vectorscale 10 \ --gridn 30 20 \ --cbmax 15 \ --unset key \ opencv8.cameramodel \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ mrcal-show-projection-diff \ --intrinsics-only \ --vectorfield \ --vectorscale 10 \ --gridn 30 20 \ --cbmax 15 \ --unset key \ $D/{opencv8,splined}.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/diff/diff-radius0-vectorfield-splined-opencv8.svg \ --terminal 'svg size 800,450 noenhanced solid dynamic font ",14"' mrcal-show-projection-diff \ --intrinsics-only \ --vectorfield \ --vectorscale 10 \ --gridn 30 20 \ --cbmax 15 \ --unset key \ $D/{opencv8,splined}.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/diff/diff-radius0-vectorfield-splined-opencv8.pdf \ --terminal 'pdf size 8in,6in noenhanced solid color font ",12"' #+end_src [[file:external/figures/diff/diff-radius0-vectorfield-splined-opencv8.svg]] This is a /very/ regular pattern. What does it mean? The issue is that each calibration produces noisy estimates of all the intrinsics and all the coordinate transformations: [[file:figures/uncertainty.svg]] The above plots projected the same $\vec p$ in the camera coordinate system, but that coordinate system has shifted between the two models we're comparing. So in the /fixed/ coordinate system attached to the camera housing, we weren't in fact projecting the same point. There exists some transformation between the camera coordinate system from the solution and the coordinate system defined by the physical camera housing. It is important to note that *this implied transformation is built-in to the intrinsics*. Even if we're not explicitly optimizing the camera pose, this implied transformation is still something that exists and moves around in response to noise. Rich models like the [[file:splined-models.org][splined stereographic models]] are able to encode a wide range of implied transformations, but even the simplest models have some transform that must be compensated for. The above vector field suggests that we need to pitch one of the cameras. We can automate this by adding a critical missing step to the procedure above between steps 1 and 2: - Transform $\vec p$ from the coordinate system of one camera to the coordinate system of the other camera [[file:figures/diff-yestransform.svg]] We don't know anything about the physical coordinate system of either camera, so we do the best we can: we compute a fit. The "right" transformation will transform $\vec p$ in such a way that the reported mismatches in $\vec q$ will be small. Lots of [[file:differencing.org][details]] are glossed-over here. Previously we passed =--intrinsics-only= to bypass this fit. Let's omit that option to get the the diff that we expect: #+begin_src sh mrcal-show-projection-diff \ --unset key \ opencv8.cameramodel \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ mrcal-show-projection-diff \ --unset key \ $D/{opencv8,splined}.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/diff/diff-splined-opencv8.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' #+end_src [[file:external/figures/diff/diff-splined-opencv8.png]] /Much/ better. As observed earlier, the Sony Alpha 7 III camera is applying some extra image processing that's not modeled by =LENSMODEL_OPENV8=, so we see an anomaly in the center. The models agree decently well past that, and then the error grows quickly as we move towards the edges. This differencing method is very powerful, and has numerous applications. For instance: - evaluating the manufacturing variation of different lenses - quantifying intrinsics drift due to mechanical or thermal stresses - testing different solution methods - underlying a [[file:tour-cross-validation.org][cross-validation scheme]] to gauge the reliability of a calibration result Many of these analyses immediately raise a question: how much of a difference do I expect to get from random noise, and how much is attributable to whatever I'm trying to measure? These questions can be answered conclusively by quantifying a model's projection uncertainty, so let's talk about that now. * Next Now we [[file:tour-uncertainty.org][compute the projection uncertainties of the models]] mrcal-2.4.1/doc/tour-effect-of-range.org000066400000000000000000000210331456301662300200160ustar00rootroot00000000000000#+title: A tour of mrcal: range dependence #+OPTIONS: toc:nil * Previous We just [[file:tour-cross-validation.org][compared results of two different calibrations to gauge solution quality]] * The effect of range in differencing and uncertainty computations Earlier I talked about model [[file:tour-differencing.org][differencing]] and estimation of [[file:tour-uncertainty.org][projection uncertainty]]. In both cases I glossed over one important detail that I would like to revisit now. A refresher: - To compute a diff, I unproject $\vec q_0$ to a point in space $\vec p$ (in camera coordinates), transform it, and project that back to the other camera to get $\vec q_1$ - To compute an uncertainty, I unproject $\vec q_0$ to (eventually) a point in space $\vec p_\mathrm{fixed}$ (in some fixed coordinate system), then project it back, propagating all the uncertainties of all the quantities used to compute the transformations and projection. The significant part is the specifics of "unproject $\vec q_0$". Unlike a projection operation, an /unprojection/ is ambiguous: given some camera-coordinate-system point $\vec p$ that projects to a pixel $\vec q$, we have $\vec q = \mathrm{project}\left(k \vec v\right)$ /for all/ $k$. So an unprojection gives you a direction, but no range. What that means in this case, is that we must choose a range of interest when computing diffs or uncertainties. It only makes sense to talk about a "diff when looking at points $r$ meters away" or "the projection uncertainty when looking out to $r$ meters". A surprising consequence of this is that while /projection/ is invariant to scaling ($k \vec v$ projects to the same $\vec q$ for all $k$), the uncertainty of this projection is /not/: [[file:figures/projection-scale-invariance.svg]] Let's look at the projection uncertainty at the center of the imager at different ranges for the =LENSMODEL_OPENCV8= model we computed earlier: #+begin_src sh mrcal-show-projection-uncertainty \ --vs-distance-at center \ --set 'yrange [0:0.1]' \ opencv8.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity export PYTHONPATH=(..(:A)); \ $PYTHONPATH/mrcal-show-projection-uncertainty \ --vs-distance-at center \ --set 'yrange [0:0.1]' \ $D/opencv8.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/uncertainty/uncertainty-vs-distance-at-center.svg \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' $PYTHONPATH/mrcal-show-projection-uncertainty \ --vs-distance-at center \ --set 'yrange [0:0.1]' \ $D/opencv8.cameramodel \ --hardcopy ~/projects/mrcal-doc-external/figures/uncertainty/uncertainty-vs-distance-at-center.pdf \ --terminal 'pdf size 8in,6in noenhanced solid color font ",12"' #+end_src [[file:external/figures/uncertainty/uncertainty-vs-distance-at-center.svg]] So the uncertainty grows without bound as we approach the camera. As we move away, there's a sweet spot where we have maximum confidence. And as we move further out still, we approach some uncertainty asymptote at infinity. Qualitatively this is the figure I see 100% of the time, with the position of the minimum and of the asymptote varying. Why is the uncertainty unbounded as we approach the camera? Because we're looking at the projection of a fixed point into a camera whose position is uncertain. As we get closer to the origin of the camera, the noise in the camera position dominates the projection, and the uncertainty shoots to infinity. What controls the range where we see the lowest uncertainty? The range where we observed the chessboards. I will prove this conclusively in the next section. It makes sense: the best uncertainty corresponds to the region where we have the most information. What controls the uncertainty at infinity? The empirical studies in the [[file:tour-choreography.org][next section]] answer that conclusively. This is a very important effect to characterize. In many applications the distance of observations at calibration time varies significantly from the working distance post-calibration. For instance, any application involving wide lenses will use closeup calibration images, but working images from much further out. We don't want to compute a calibration where the calibration-range uncertainty is great, but the working-range uncertainty is poor. I should emphasize that while unintuitive, this uncertainty-depends-on-range effect is very real. It isn't just something that you get out of some opaque equations, but it's observable in the field. We can't see it in [[file:tour-cross-validation.org][the cross validation diffs we just computed]] because the noncentral model errors dominate, but if we throw out all the observations away from the center, the noncentral errors disappear, and the effect is clearly seen empirically. #+begin_src sh :exports none :eval no-export D=/home/dima/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/ PYTHONPATH=~/projects/mrcal export PYTHONPATH for dance ($D/[23]-*) { < $dance/corners.vnl \ mrcal-cull-corners \ --imagersize 6000 3376 \ --cull-rad-off-center 1500 \ > /tmp/${dance:t}-corners-culled.vnl } lensmodel=LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=30_Ny=18_fov_x_deg=150; for dance ($D/[23]-*) { $PYTHONPATH/mrcal-calibrate-cameras \ --corners-cache /tmp/${dance:t}-corners-culled.vnl \ --lensmodel $lensmodel \ --focal 1900 \ --object-spacing 58.8e-3 \ --object-width-n 14 \ --outdir /tmp \ --imagersize 6000 3376 \ "*.JPG" mv /tmp/camera-0.cameramodel /tmp/${dance:t}-culled.cameramodel; } $PYTHONPATH/mrcal-show-projection-diff \ --cbmax 1 \ --no-uncertainties --radius 800 \ --unset key \ --hardcopy ~/projects/mrcal-doc-external/figures/cross-validation/diff-culled-at-infinity.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' \ /tmp/[23]-f22-infinity-culled.cameramodel $PYTHONPATH/mrcal-show-projection-diff \ --distance 1 \ --cbmax 1 \ --no-uncertainties --radius 800 \ --unset key \ --hardcopy ~/projects/mrcal-doc-external/figures/cross-validation/diff-culled-at-1m.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' \ /tmp/[23]-f22-infinity-culled.cameramodel #+end_src I threw out all points outside of a circle in the center with radius 1500 pixels (using the [[file:mrcal-cull-corners.html][=mrcal-cull-corners=]] tool). Cross-validation diff at 1m (chessboards are here; we expect this to be low): [[file:external/figures/cross-validation/diff-culled-at-1m.png]] And at infinity (uncertainty plot tells us that this should be ~ 3x worse): [[file:external/figures/cross-validation/diff-culled-at-infinity.png]] Clearly the prediction that uncertainties are lowest at the chessboard distance, and increase as we move away is borne out here empirically, by just looking at diffs. /Without/ computing the uncertainty curves. This effect is universal, and is especially clear when the uncertainties at the chessboard distance and at infinity are very different. How do we make sure that the uncertainty at infinity is still low, despite the fact that no chessboards were observed there? Read on. * Next We're now ready to [[file:tour-choreography.org][find the best chessboard-dancing technique]]. mrcal-2.4.1/doc/tour-initial-calibration.org000066400000000000000000001430211456301662300210060ustar00rootroot00000000000000#+title: A tour of mrcal: calibration #+OPTIONS: toc:t The is the first stage in the [[file:tour.org][tour of mrcal]]. * Gathering chessboard corners :PROPERTIES: :CUSTOM_ID: gathering-corners :END: We start by gathering images of a [[file:formulation.org::#calibration-object][chessboard]]. I use a large chessboard in order to fill the imager (details about why are on the [[file:tour-choreography.org][choreography page]]). My chessboard has 14x14 internal corners with a corner-corner spacing of 5.88cm. The whole thing is roughly 1m x 1m. A big chessboard such as this is often not completely rigid or completely flat. So I'm using a board backed with 1in of aluminum honeycomb, which addresses these issues: this board is both flat and stable. It took several iterations to settle on this material; see the [[file:how-to-calibrate.org::#chessboard-shape][how-to-calibrate page]] for details. An important consideration when gathering calibration images is keeping them in focus. As we shall see [[file:tour-choreography.org][later]], we want to gather as many close-up images as we can, so depth-of-field is the limiting factor. Moving the focus ring or the aperture ring affects the intrinsics, so ideally a single lens setting can cover both the calibration-time closeups and the working distance (presumably much further out). So for these tests I set the focus to infinity, and gather all my images at F22 to maximize the depth-of-field. To also avoid motion blur I need fast exposures, so I did all the image gathering outside, with bright natural lighting. When gathering real-world calibration data, compromises are often necessary; see the [[file:how-to-calibrate.org][how-to-calibrate page]] for details. I gathered some [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/images][calibration images]], and used [[https://github.com/dkogan/mrgingham/][mrgingham]] 1.22 to detect the [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/corners.vnl][chessboard corners]]: #+begin_src sh mrgingham --jobs 4 --gridn 14 '*.JPG' > corners.vnl #+end_src How well did we cover the imager? Did we get the edges and corners? #+begin_example $ < corners.vnl \ vnl-filter -p x,y | \ feedgnuplot --domain --square --set 'xrange [0:6000] noextend' --set 'yrange [3376:0] noextend' #+end_example #+begin_src sh :exports none :eval no-export mkdir -p ~/projects/mrcal-doc-external/figures/calibration/ D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ < $D/corners.vnl \ vnl-filter -p x,y | \ feedgnuplot --domain --square --set 'xrange [0:6000] noextend' --set 'yrange [3376:0] noextend' \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' \ --hardcopy ~/projects/mrcal-doc-external/figures/calibration/mrgingham-coverage.png #+end_src [[file:external/figures/calibration/mrgingham-coverage.png]] We did OK, except maybe at the top center. This is a good quick/dirty visualization of calibration data coverage, but as we'll see later, [[file:tour-uncertainty.org][we can do much better by looking at the projection uncertainty]]. If we had multiple cameras, the coverage for each one can be visualized by pre-filtering the =corners.vnl= to select specific image filenames. For instance: #+begin_src sh < corners.vnl \ vnl-filter -p x,y 'filename ~ "left"' | \ feedgnuplot .... #+end_src For an arbitrary image we can visualize the corner detections: #+begin_example $ < corners.vnl head -n5 ## generated with mrgingham --jobs 4 --gridn 14 *.JPG # filename x y level DSC06041.JPG 781.481013 1476.287623 0 DSC06041.JPG 847.070319 1444.378775 0 DSC06041.JPG 917.514046 1410.696402 0 $ f=DSC06067.JPG $ < corners.vnl \ vnl-filter \ --perl \ "filename eq \"$f\"" \ -p x,y,size='2**(1-level)' | \ feedgnuplot \ --unset key \ --image $f \ --domain \ --square \ --tuplesizeall 3 \ --with 'points pt 7 ps variable' #+end_example #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ f=$D/images/DSC06067.JPG < $D/corners.vnl \ vnl-filter \ --perl \ "filename eq \"${f:t}\"" \ -p x,y,size='2**(1-level)' | \ feedgnuplot \ --unset key \ --image $f \ --domain \ --square \ --tuplesizeall 3 \ --with 'points pt 7 ps variable' \ --hardcopy ~/projects/mrcal-doc-external/figures/calibration/mrgingham-results.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' #+end_src [[file:external/figures/calibration/mrgingham-results.png]] So in this image many of the corners were detected at full-resolution (level-0), but some required downsampling for the detector to find them. This is indicated by smaller circles. The downsampled points have less precision, so they are [[file:formulation.org::#noise-in-measurement-vector][weighed less in the optimization]]. How many images produced successful corner detections? #+begin_example $ < corners.vnl vnl-filter --has x -p filename | uniq | grep -v '#' | wc -l 84 #+end_example So we have 84 images with detected corners even though we captured 115 images. Most of the misses were probably images where the chessboard wasn't entirely in view, but some could be failures of mrgingham. In any case, 84 observations is usually plenty. If I had more that one camera, the image filenames would need to indicate what camera captured each image at which time. I usually name my images =frameFFF-cameraCCC.jpg=. Images with the same =FFF= are assumed to have been captured at the same instant in time. The exact pattern doesn't matter, but a constant pattern with a variable =FFF= and =CCC= is required. * Monocular calibration with the 8-parameter opencv model :PROPERTIES: :CUSTOM_ID: opencv8-model-solving :END: We have data. Let's calibrate. We begin with a lean model used commonly for wide lenses in other tools: [[file:lensmodels.org::#lensmodel-opencv][=LENSMODEL_OPENCV8=]]. Primarily this works via a rational radial "distortion" model. Projecting $\vec p$ in the camera coordinate system: \begin{aligned} \vec P &\equiv \frac{\vec p_{xy}}{p_z} \\ r &\equiv \left|\vec P\right| \\ \vec P_\mathrm{radial} &\equiv \frac{ 1 + k_0 r^2 + k_1 r^4 + k_4 r^6}{ 1 + k_5 r^2 + k_6 r^4 + k_7 r^6} \vec P \\ \vec q &= \vec f_{xy} \left( \vec P_\mathrm{radial} + \cdots \right) + \vec c_{xy} \end{aligned} where $\vec q$ is the resulting projected pixel, $k_i$ are the distortion parameters, $\vec f_{xy}$ is the focal lengths and $\vec c_{xy}$ is the center pixel of the imager. Let's compute the calibration using the [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras=]] tool: #+begin_src sh mrcal-calibrate-cameras \ --corners-cache corners.vnl \ --lensmodel LENSMODEL_OPENCV8 \ --focal 1900 \ --object-spacing 0.0588 \ --object-width-n 14 \ '*.JPG' #+end_src I'm specifying the initial rough estimate of the focal length (in pixels), the geometry of my chessboard, the lens model I want to use, chessboard corners we just detected and the image globs. I have just one camera, so I have one glob: =*.JPG=. With more cameras you'd have something like ='*-camera0.jpg' '*-camera1.jpg' '*-camera2.jpg'=. The [[file:mrcal-calibrate-cameras.html][=mrcal-calibrate-cameras=]] tool reports some high-level diagnostics, writes the output model(s) to disk, and exits: #+begin_example ## initial solve: geometry only ## RMS error: 9.523144801739077 ## initial solve: geometry and LENSMODEL_STEREOGRAPHIC core only =================== optimizing everything except board warp from seeded intrinsics mrcal.c(5351): Threw out some outliers (have a total of 129 now); going again ... mrcal.c(5351): Threw out some outliers (have a total of 511 now); going again ## final, full optimization mrcal.c(5351): Threw out some outliers (have a total of 534 now); going again mrcal.c(5351): Threw out some outliers (have a total of 553 now); going again mrcal.c(5351): Threw out some outliers (have a total of 564 now); going again ## RMS error: 0.4120879883977674 RMS reprojection error: 0.4 pixels Worst residual (by measurement): 1.8 pixels Noutliers: 564 out of 16464 total points: 3.4% of the data calobject_warp = [-0.00012726 -0.00014325] Wrote /tmp/camera-0.cameramodel #+end_example The resulting model is available [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/opencv8.cameramodel][here]]. This is a [[file:cameramodels.org][mrcal-native =.cameramodel= file]] containing at least the lens parameters and the geometry. We want to flag down any issues with the data that would violate the [[file:formulation.org::#noise-model][assumptions made by the solver]]. Let's start by sanity-checking the results. As we can see in the console output, the final RMS reprojection error was 0.4 pixels. Of the 16464 corner observations (84 observations of the board with 14*14 points each), 564 didn't fit the model well-enough, and were thrown out as [[file:formulation.org::#outlier-rejection][outliers]]. The [[file:formulation.org::#board-deformation][board flex]] was computed as 0.13mm horizontally, and 0.14mm vertically. That all sounds reasonable. Let's examine the solution further. We can either - =mrcal-calibrate-cameras --explore ...= to drop into a REPL after the computation is done. This allows us to look around in the Python session where the solution was computed. - Use the [[file:commandline-tools.org][=mrcal-show-...= commandline tools]] on the generated =xxx.cameramodel= files The =--explore= REPL can produce deeper feedback, but the commandline tools are more convenient, so I here I talk about those. What does the solve think about our geometry? Does it match reality? #+begin_src sh mrcal-show-geometry \ opencv8.cameramodel \ --show-calobjects \ --unset key \ --set 'xyplane 0' \ --set 'view 80,30,1.5' #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ mrcal-show-geometry $D/opencv8.cameramodel --unset key --set 'xyplane 0' --set 'view 80,30,1.5' --show-calobjects --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' --hardcopy ~/projects/mrcal-doc-external/figures/calibration/calibration-chessboards-geometry.svg mrcal-show-geometry $D/opencv8.cameramodel --unset key --set 'xyplane 0' --set 'view 80,30,1.5' --show-calobjects --terminal 'pdf size 8in,6in noenhanced solid color font ",12"' --hardcopy ~/projects/mrcal-doc-external/figures/calibration/calibration-chessboards-geometry.pdf #+end_src [[file:external/figures/calibration/calibration-chessboards-geometry.svg]] Here we see the [[file:formulation.org::#world-geometry][axes of our camera]] (purple) situated at the [[file:formulation.org::#world-geometry][reference coordinate system]]. In this solve, the camera coordinate system /is/ the reference coordinate system; this would look more interesting with more cameras. In front of the camera (along the $z$ axis) we can see the solved chessboard poses. There are a whole lot of them, and they're all sitting right in front of the camera with some heavy tilt. This matches with how this chessboard dance was performed: I followed the guidelines of the [[file:tour-choreography.org][dance study]]. ** Solve diagnostics :PROPERTIES: :CUSTOM_ID: opencv8-solve-diagnostics :END: Next, let's examine the residuals more closely. We have an overall RMS reprojection error value from above, but let's look at the full distribution of errors for /all/ the images and cameras: #+begin_src sh mrcal-show-residuals \ --histogram \ --set 'xrange [-2:2]' \ --unset key \ --binwidth 0.1 \ opencv8.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ mrcal-show-residuals \ --histogram \ --set 'xrange [-2:2]' \ --unset key \ --binwidth 0.1 \ --hardcopy "~/projects/mrcal-doc-external/figures/calibration/residuals-histogram-opencv8.svg" \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' \ $D/opencv8.cameramodel mrcal-show-residuals \ --histogram \ --set 'xrange [-2:2]' \ --unset key \ --binwidth 0.1 \ --hardcopy "~/projects/mrcal-doc-external/figures/calibration/residuals-histogram-opencv8.pdf" \ --terminal 'pdf size 8in,6in noenhanced solid color font ",12"' \ $D/opencv8.cameramodel Dout=~/projects/mrcal-doc-external/figures/calibration/histogram mkdir -p $Dout echo "The background color below must match mrcal.css. Adjust them together" > /dev/null echo "I'm hardcoding the image dimensions because of a gnuplot bug. Already fixed in git, but not released yet" > /dev/null echo "git: https://sourceforge.net/p/gnuplot/gnuplot-main/ci/b387dbedf38268c09df258e649fd8ec301c8e1c6/tree/term/cairo.trm?diff=660d60f022c48defaa140ba12d6a1fd931b4bfe5" > /dev/null echo "mailing list: https://sourceforge.net/p/gnuplot/mailman/gnuplot-beta/thread/874juhf80v.fsf%40dima.secretsauce.net/#msg37741736" > /dev/null mrcal-show-residuals \ --histogram \ --set 'xrange [-2:2]' \ --unset key \ --binwidth 0.1 \ --hardcopy "$Dout/00001.png" \ --title "Residual histogram: LENSMODEL_OPENCV8" \ --terminal 'pngcairo size 1024,768 notransparent background "#e8dfd0" noenhanced crop font ",12"' \ $D/opencv8.cameramodel #+end_src [[file:external/figures/calibration/residuals-histogram-opencv8.svg]] We would like to see a normal distribution (since that's what the [[file:formulation.org::#noise-model][noise model]] assumes), and we roughly do see that here. If the images were captured with varying illumination (which happens with different board orientations and a directional light source), the center cluster or the tails would get over-populated. That would be a violation of the noise model, but things still appear to work OK even in that case. Let's look deeper. If there's anything really wrong with our data, then we should see it in the worst-fitting images. Let's ask the tool to show us the worst one: #+begin_src sh mrcal-show-residuals-board-observation \ --from-worst \ --vectorscale 200 \ --circlescale 0.5 \ --set 'cbrange [0:2]' \ opencv8.cameramodel \ 0 #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ cd $D/images mrcal-show-residuals-board-observation \ --from-worst \ --vectorscale 200 \ --circlescale 0.5 \ --set 'cbrange [0:2]' \ --hardcopy "~/projects/mrcal-doc-external/figures/calibration/worst-opencv8.png" \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' \ $D/opencv8.cameramodel \ 0 Dout=~/projects/mrcal-doc-external/figures/calibration/worst mkdir -p $Dout echo "The background color below must match mrcal.css. Adjust them together" > /dev/null echo "I'm hardcoding the image dimensions because of a gnuplot bug. Already fixed in git, but not released yet" > /dev/null echo "git: https://sourceforge.net/p/gnuplot/gnuplot-main/ci/b387dbedf38268c09df258e649fd8ec301c8e1c6/tree/term/cairo.trm?diff=660d60f022c48defaa140ba12d6a1fd931b4bfe5" > /dev/null echo "mailing list: https://sourceforge.net/p/gnuplot/mailman/gnuplot-beta/thread/874juhf80v.fsf%40dima.secretsauce.net/#msg37741736" > /dev/null mrcal-show-residuals-board-observation \ --from-worst \ --vectorscale 200 \ --circlescale 0.5 \ --set 'cbrange [0:2]' \ --hardcopy "$Dout/00001.png" \ --title "Worst observation: LENSMODEL_OPENCV8" \ --terminal 'pngcairo size 1024,550 notransparent background "#e8dfd0" noenhanced crop font ",12"' \ $D/opencv8.cameramodel \ 0 #+end_src [[file:external/figures/calibration/worst-opencv8.png]] The residual vector for each chessboard corner in this observation is shown, scaled by a factor of 200 for legibility (the actual errors are tiny!) The circle color also indicates the magnitude of the errors. The size of each circle represents the weight given to that point. The weight is reduced for points that were detected at a lower resolution by the chessboard detector. So even high reprojection errors (shown as the vectors) could result in low measurements if the weight was low. Points thrown out as outliers are not shown at all. Residual plots such as this one are a good way to identify common data-gathering issues such as: - out-of focus images - images with motion blur - [[https://en.wikipedia.org/wiki/Rolling_shutter][rolling shutter]] effects - camera synchronization errors - chessboard detector failures - insufficiently-rich models (of the lens or of the chessboard shape or anything else) See the [[file:how-to-calibrate.org][how-to-calibrate page]] for practical details. Back to /this/ image. In absolute terms, even this worst-fitting image fits /really/ well. The RMS reprojection error in this image is 0.70 pixels. The residuals in this image look /mostly/ reasonable, but there is an issue: if the model fit this data well, the residuals would sample independent, random noise. Thus the residuals would all be uncorrelated with each other, but /here/ there's a pattern: we can see that the errors are mostly radial in the chessboard (they point to/from the center). A unmodeled chessboard flex could cause this kind of problem, for instance. This is a source of bias in this solution. Let's keep going, keeping this in mind. One issue with lean models such as =LENSMODEL_OPENCV8= (used here) is that the radial distortion is never quite right, especially as we move further and further away from the optical axis: this is the last point in the common-errors list above. The result of these radial distortion errors is high residuals in the corners and near the edges of the image. We can clearly see this here in the 10th-worst image (10th worst and not /the/ worst because the /really/ poor-fitting points are thrown out as outliers): #+begin_src sh mrcal-show-residuals-board-observation \ --from-worst \ --vectorscale 200 \ --circlescale 0.5 \ --set 'cbrange [0:2]' \ opencv8.cameramodel \ 10 #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ cd $D/images mrcal-show-residuals-board-observation \ --from-worst \ --vectorscale 200 \ --circlescale 0.5 \ --set 'cbrange [0:2]' \ --hardcopy "~/projects/mrcal-doc-external/figures/calibration/worst-incorner-opencv8.png" \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' \ $D/opencv8.cameramodel \ 10 Dout=~/projects/mrcal-doc-external/figures/calibration/worst-in-corner mkdir -p $Dout echo "The background color below must match mrcal.css. Adjust them together" > /dev/null echo "I'm hardcoding the image dimensions because of a gnuplot bug. Already fixed in git, but not released yet" > /dev/null echo "git: https://sourceforge.net/p/gnuplot/gnuplot-main/ci/b387dbedf38268c09df258e649fd8ec301c8e1c6/tree/term/cairo.trm?diff=660d60f022c48defaa140ba12d6a1fd931b4bfe5" > /dev/null echo "mailing list: https://sourceforge.net/p/gnuplot/mailman/gnuplot-beta/thread/874juhf80v.fsf%40dima.secretsauce.net/#msg37741736" > /dev/null mrcal-show-residuals-board-observation \ --from-worst \ --vectorscale 200 \ --circlescale 0.5 \ --set 'cbrange [0:2]' \ --hardcopy "$Dout/00001.png" \ --title "Observation in the corner: LENSMODEL_OPENCV8" \ --terminal 'pngcairo size 1024,550 notransparent background "#e8dfd0" noenhanced crop font ",12"' \ $D/opencv8.cameramodel \ 10 #+end_src [[file:external/figures/calibration/worst-incorner-opencv8.png]] Clearly /this/ image is a problem: the points near the corners have poor residuals, and the entire column of points at the edge was thrown out as outliers. We note that this is observation 47, so that we can come back to it later. And we can see this same high-error-in-the-corners effect in the residual magnitudes of all the observations: #+begin_src sh mrcal-show-residuals \ --magnitudes \ --set 'cbrange [0:1.5]' \ opencv8.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ mrcal-show-residuals \ --magnitudes \ --set 'cbrange [0:1.5]' \ --set 'pointsize 0.5' \ --hardcopy "~/projects/mrcal-doc-external/figures/calibration/residual-magnitudes-opencv8.png" \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' \ $D/opencv8.cameramodel Dout=~/projects/mrcal-doc-external/figures/calibration/magnitudes mkdir -p $Dout echo "The background color below must match mrcal.css. Adjust them together" > /dev/null echo "I'm hardcoding the image dimensions because of a gnuplot bug. Already fixed in git, but not released yet" > /dev/null echo "git: https://sourceforge.net/p/gnuplot/gnuplot-main/ci/b387dbedf38268c09df258e649fd8ec301c8e1c6/tree/term/cairo.trm?diff=660d60f022c48defaa140ba12d6a1fd931b4bfe5" > /dev/null echo "mailing list: https://sourceforge.net/p/gnuplot/mailman/gnuplot-beta/thread/874juhf80v.fsf%40dima.secretsauce.net/#msg37741736" > /dev/null mrcal-show-residuals \ --magnitudes \ --set 'cbrange [0:1.5]' \ --set 'pointsize 0.5' \ --hardcopy "$Dout/00001.png" \ --title "Residual magnitudes: LENSMODEL_OPENCV8" \ --terminal 'pngcairo size 1024,550 notransparent background "#e8dfd0" noenhanced crop font ",12"' \ $D/opencv8.cameramodel #+end_src [[file:external/figures/calibration/residual-magnitudes-opencv8.png]] In addition to the expected high errors at the edges, this plot also shows an anomalous ring of poorly-fitting observations at the center. This could maybe be caused by the solver sacrificing accuracy at the center of the image to get a better fit in the much larger areas further out? We shall see in a bit. Let's look at the systematic errors in another way: let's look at all the residuals over all the observations, color-coded by their direction, ignoring the magnitudes: #+begin_src sh mrcal-show-residuals \ --directions \ --unset key \ opencv8.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ mrcal-show-residuals \ --directions \ --unset key \ --set 'pointsize 0.5' \ --hardcopy "~/projects/mrcal-doc-external/figures/calibration/directions-opencv8.svg" \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' \ $D/opencv8.cameramodel mrcal-show-residuals \ --directions \ --unset key \ --set 'pointsize 0.5' \ --hardcopy "~/projects/mrcal-doc-external/figures/calibration/directions-opencv8.png" \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' \ $D/opencv8.cameramodel mrcal-show-residuals \ --directions \ --unset key \ --set 'pointsize 0.5' \ --hardcopy "~/projects/mrcal-doc-external/figures/calibration/directions-opencv8.pdf" \ --terminal 'pdf size 8in,6in noenhanced solid color font ",12"' \ $D/opencv8.cameramodel Dout=~/projects/mrcal-doc-external/figures/calibration/directions mkdir -p $Dout echo "The background color below must match mrcal.css. Adjust them together" > /dev/null echo "I'm hardcoding the image dimensions because of a gnuplot bug. Already fixed in git, but not released yet" > /dev/null echo "git: https://sourceforge.net/p/gnuplot/gnuplot-main/ci/b387dbedf38268c09df258e649fd8ec301c8e1c6/tree/term/cairo.trm?diff=660d60f022c48defaa140ba12d6a1fd931b4bfe5" > /dev/null echo "mailing list: https://sourceforge.net/p/gnuplot/mailman/gnuplot-beta/thread/874juhf80v.fsf%40dima.secretsauce.net/#msg37741736" > /dev/null mrcal-show-residuals \ --directions \ --unset key \ --set 'pointsize 0.5' \ --hardcopy "$Dout/00001.png" \ --title "Residual directions: LENSMODEL_OPENCV8" \ --terminal 'pngcairo size 1024,550 notransparent background "#e8dfd0" noenhanced crop font ",12"' \ $D/opencv8.cameramodel #+end_src [[file:external/figures/calibration/directions-opencv8.png]] As before, if the model fit the observations, the errors would represent random noise, and no color pattern would be discernible in these dots. But here we can clearly see the colors clustered together. This is not random noise, and is a /very/ clear indication that this lens model is not able to fit this data. It would be good to have a quantitative measure of these systematic patterns. At this time mrcal doesn't provide an automated way to do that. This will be added in the future. Clearly there're unmodeled errors in this solve. As we have seen, the errors here are all fairly small, but they become important when doing precision work like, for instance, long-range stereo. Let's fix it. * Monocular calibration with a splined stereographic model :PROPERTIES: :CUSTOM_ID: splined-stereographic-fit :END: Usable [[file:uncertainty.org][uncertainty quantification]] and accurate projections are major goals of mrcal. To achive these, mrcal supports a [[file:splined-models.org][/splined stereographic/ model]], briefly summarized below. We use this splined stereographic model to more precisely model the behavior or this lens. ** Splined stereographic model definition :PROPERTIES: :CUSTOM_ID: splined-model-definition :END: The base of a splined stereographic model is a [[file:lensmodels.org::#lensmodel-stereographic][stereographic projection]]. In this projection, a point that lies an angle $\theta$ off the camera's optical axis projects to $\left|\vec q - \vec q_\mathrm{center}\right| = 2 f \tan \frac{\theta}{2}$ pixels from the imager center, where $f$ is the focal length. Note that this representation supports projections behind the camera ($\theta > 90^\circ$) with a single singularity directly behind the camera. This is unlike the pinhole model, which has $\left|\vec q - \vec q_\mathrm{center}\right| = f \tan \theta$, and projects to infinity as $\theta \rightarrow 90^\circ$. The pinhole model can /not/ represent projections behind the imager. Basing the new model on a stereographic projection lifts the inherent forward-view-only limitation of =LENSMODEL_OPENCV8=. Let $\vec p$ be the camera-coordinate system point being projected. The angle off the optical axis is \[ \theta \equiv \tan^{-1} \frac{\left| \vec p_{xy} \right|}{p_z} \] The /normalized/ stereographic projection is \[ \vec u \equiv \frac{\vec p_{xy}}{\left| \vec p_{xy} \right|} 2 \tan\frac{\theta}{2} \] This initial projection operation unambiguously collapses the 3D point $\vec p$ into a 2D vector $\vec u$. We then use $\vec u$ to look-up an adjustment factor $\Delta \vec u$ using two splined surfaces: one for each of the two elements: \[ \Delta \vec u \equiv \left[ \begin{aligned} \Delta u_x \left( \vec u \right) \\ \Delta u_y \left( \vec u \right) \end{aligned} \right] \] We can then define the rest of the projection function: \[\vec q = \left[ \begin{aligned} f_x \left( u_x + \Delta u_x \right) + c_x \\ f_y \left( u_y + \Delta u_y \right) + c_y \end{aligned} \right] \] The parameters we can optimize are the spline control points and $f_x$, $f_y$, $c_x$ and $c_y$, the usual focal-length-in-pixels and imager-center values. ** Solving :PROPERTIES: :CUSTOM_ID: splined-model-solving :END: Let's run the same exact calibration as before, but using the richer model to specify the lens: #+begin_src sh mrcal-calibrate-cameras \ --corners-cache corners.vnl \ --lensmodel LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=30_Ny=18_fov_x_deg=150 \ --focal 1900 \ --object-spacing 0.0588 \ --object-width-n 14 \ '*.JPG' #+end_src Reported diagnostics: #+begin_example ## initial solve: geometry only ## RMS error: 9.523144801739077 ## initial solve: geometry and LENSMODEL_STEREOGRAPHIC core only =================== optimizing everything except board warp from seeded intrinsics mrcal.c(5351): Threw out some outliers (have a total of 28 now); going again ## final, full optimization ## RMS error: 0.24540598163794722 RMS reprojection error: 0.2 pixels Worst residual (by measurement): 1.3 pixels Noutliers: 28 out of 16464 total points: 0.2% of the data calobject_warp = [-1.26851438e-04 -8.03269701e-05] Wrote /tmp/camera-0.cameramodel #+end_example The resulting model is available [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/splined.cameramodel][here]]. The requested lens model =LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=30_Ny=18_fov_x_deg=150= is the only difference in the command. Unlike =LENSMODEL_OPENCV8=, /this/ model has some /configuration/ parameters: the spline order (we use cubic splines here), the spline density (here each spline surface has 30 x 18 knots), and the rough horizontal field-of-view we support (we specify about 150 degrees horizontal field of view). These parameters are fixed in the model, and are not subject to optimization. There're over 1000 lens parameters here, but the problem is sparse, so we can still process this in a reasonable amount of time. The previous =LENSMODEL_OPENCV8= solve had 564 points that fit so poorly, the solver threw them away as outliers; here we have only 28. The RMS reprojection error dropped from 0.4 pixels to 0.2 pixels. The estimated chessboard shape stayed roughly the same: flat. These are all what we expect and hope to see. Let's look at the residual distribution in /this/ solve, compared to before: #+begin_src sh mrcal-show-residuals \ --histogram \ --set 'xrange [-2:2]' \ --unset key \ --binwidth 0.1 \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ mrcal-show-residuals \ --histogram \ --set 'xrange [-2:2]' \ --unset key \ --binwidth 0.1 \ --hardcopy "~/projects/mrcal-doc-external/figures/calibration/residuals-histogram-splined.svg" \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' \ $D/splined.cameramodel mrcal-show-residuals \ --histogram \ --set 'xrange [-2:2]' \ --unset key \ --binwidth 0.1 \ --hardcopy "~/projects/mrcal-doc-external/figures/calibration/residuals-histogram-splined.pdf" \ --terminal 'pdf size 8in,6in noenhanced solid color font ",12"' \ $D/splined.cameramodel Dout=~/projects/mrcal-doc-external/figures/calibration/histogram mkdir -p $Dout echo "The background color below must match mrcal.css. Adjust them together" > /dev/null echo "I'm hardcoding the image dimensions because of a gnuplot bug. Already fixed in git, but not released yet" > /dev/null echo "git: https://sourceforge.net/p/gnuplot/gnuplot-main/ci/b387dbedf38268c09df258e649fd8ec301c8e1c6/tree/term/cairo.trm?diff=660d60f022c48defaa140ba12d6a1fd931b4bfe5" > /dev/null echo "mailing list: https://sourceforge.net/p/gnuplot/mailman/gnuplot-beta/thread/874juhf80v.fsf%40dima.secretsauce.net/#msg37741736" > /dev/null mrcal-show-residuals \ --histogram \ --set 'xrange [-2:2]' \ --unset key \ --binwidth 0.1 \ --hardcopy "$Dout/00002.png" \ --title "Residual histogram: LENSMODEL_SPLINED_STEREOGRAPHIC" \ --terminal 'pngcairo size 1024,768 notransparent background "#e8dfd0" noenhanced crop font ",12"' \ $D/splined.cameramodel ffmpeg \ -r 1 \ -y \ -f image2 \ -i "$Dout/%05d.png" \ -filter_complex "[0:v] split [a][b];[a] palettegen [p];[b][p] paletteuse" \ ~/projects/mrcal-doc-external/figures/calibration/histogram-opencv8-splined-animation.gif #+end_src [[file:external/figures/calibration/histogram-opencv8-splined-animation.gif]] This still has the nice bell curve, but the residuals are lower: the data fits better than before. Let's look at the worst-fitting single image: #+begin_src sh mrcal-show-residuals-board-observation \ --from-worst \ --vectorscale 200 \ --circlescale 0.5 \ --set 'cbrange [0:2]' \ splined.cameramodel \ 0 #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ cd $D/images mrcal-show-residuals-board-observation \ --from-worst \ --vectorscale 200 \ --circlescale 0.5 \ --set 'cbrange [0:2]' \ --hardcopy "~/projects/mrcal-doc-external/figures/calibration/worst-splined.png" \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' \ $D/splined.cameramodel \ 0 Dout=~/projects/mrcal-doc-external/figures/calibration/worst mkdir -p $Dout echo "The background color below must match mrcal.css. Adjust them together" > /dev/null echo "I'm hardcoding the image dimensions because of a gnuplot bug. Already fixed in git, but not released yet" > /dev/null echo "git: https://sourceforge.net/p/gnuplot/gnuplot-main/ci/b387dbedf38268c09df258e649fd8ec301c8e1c6/tree/term/cairo.trm?diff=660d60f022c48defaa140ba12d6a1fd931b4bfe5" > /dev/null echo "mailing list: https://sourceforge.net/p/gnuplot/mailman/gnuplot-beta/thread/874juhf80v.fsf%40dima.secretsauce.net/#msg37741736" > /dev/null mrcal-show-residuals-board-observation \ --from-worst \ --vectorscale 200 \ --circlescale 0.5 \ --set 'cbrange [0:2]' \ --hardcopy "$Dout/00002.png" \ --title "Worst observation: LENSMODEL_SPLINED_STEREOGRAPHIC" \ --terminal 'pngcairo size 1024,550 notransparent background "#e8dfd0" noenhanced crop font ",12"' \ $D/splined.cameramodel \ 0 ffmpeg \ -r 1 \ -y \ -f image2 \ -i "$Dout/%05d.png" \ -filter_complex "[0:v] split [a][b];[a] palettegen [p];[b][p] paletteuse" \ ~/projects/mrcal-doc-external/figures/calibration/worst-opencv8-splined-animation.gif #+end_src Interestingly, the worst observation here is the same one we saw with =LENSMODEL_OPENCV8=, so we can do a nice side-by-side comparison: [[file:external/figures/calibration/worst-opencv8-splined-animation.gif]] All the errors are significantly smaller. The previous radial pattern is still there, but is much less pronounced. #+begin_src sh :exports none :eval no-export Sometimes noncentral solves clearly fix this, and I can talk about it (notes here). Cross-validation is a better place to talk about it, anyway. A sneak peek: this is caused by an assumption of a central projection (assuming that all rays intersect at a single point). An experimental and not-entirely-complete [[https://github.com/dkogan/mrcal/tree/noncentral][support for noncentral projection in mrcal]] exists, and works /much/ better. The same frame, fitted with a noncentral projection: D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ PYTHONPATH=/home/dima/projects/mrcal-noncentral ~/projects/mrcal-noncentral/mrcal-show-residuals-board-observation \ --vectorscale 200 \ --circlescale 0.5 \ --set 'cbrange [0:2]' \ --hardcopy "~/projects/mrcal-doc-external/figures/calibration/worst-splined-noncentral.png" \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' \ $D/splined-noncentral.cameramodel \ 40 [[file:external/figures/calibration/worst-splined-noncentral.png]] This will be included in a future release of mrcal. In any case, these errors are small, so let's proceed. #+end_src What happens when we look at the image that showed a poor fit in the corner previously? It was observation 47. #+begin_src sh mrcal-show-residuals-board-observation \ --vectorscale 200 \ --circlescale 0.5 \ --set 'cbrange [0:2]' \ splined.cameramodel \ 47 #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ cd $D/images mrcal-show-residuals-board-observation \ --vectorscale 200 \ --circlescale 0.5 \ --set 'cbrange [0:2]' \ --hardcopy "~/projects/mrcal-doc-external/figures/calibration/worst-incorner-splined.png" \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' \ $D/splined.cameramodel \ 47 Dout=~/projects/mrcal-doc-external/figures/calibration/worst-in-corner mkdir -p $Dout echo "The background color below must match mrcal.css. Adjust them together" > /dev/null echo "I'm hardcoding the image dimensions because of a gnuplot bug. Already fixed in git, but not released yet" > /dev/null echo "git: https://sourceforge.net/p/gnuplot/gnuplot-main/ci/b387dbedf38268c09df258e649fd8ec301c8e1c6/tree/term/cairo.trm?diff=660d60f022c48defaa140ba12d6a1fd931b4bfe5" > /dev/null echo "mailing list: https://sourceforge.net/p/gnuplot/mailman/gnuplot-beta/thread/874juhf80v.fsf%40dima.secretsauce.net/#msg37741736" > /dev/null mrcal-show-residuals-board-observation \ --vectorscale 200 \ --circlescale 0.5 \ --set 'cbrange [0:2]' \ --hardcopy "$Dout/00002.png" \ --title "Observation in the corner: LENSMODEL_SPLINED_STEREOGRAPHIC" \ --terminal 'pngcairo size 1024,550 notransparent background "#e8dfd0" noenhanced crop font ",12"' \ $D/splined.cameramodel \ 47 ffmpeg \ -r 1 \ -y \ -f image2 \ -i "$Dout/%05d.png" \ -filter_complex "[0:v] split [a][b];[a] palettegen [p];[b][p] paletteuse" \ ~/projects/mrcal-doc-external/figures/calibration/worst-in-corner-opencv8-splined-animation.gif #+end_src [[file:external/figures/calibration/worst-in-corner-opencv8-splined-animation.gif]] And the residual magnitudes of all the observations: #+begin_src sh mrcal-show-residuals \ --magnitudes \ --set 'cbrange [0:1.5]' \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ mrcal-show-residuals \ --magnitudes \ --set 'cbrange [0:1.5]' \ --set 'pointsize 0.5' \ --hardcopy "~/projects/mrcal-doc-external/figures/calibration/residual-magnitudes-splined.png" \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' \ $D/splined.cameramodel Dout=~/projects/mrcal-doc-external/figures/calibration/magnitudes mkdir -p $Dout echo "The background color below must match mrcal.css. Adjust them together" > /dev/null echo "I'm hardcoding the image dimensions because of a gnuplot bug. Already fixed in git, but not released yet" > /dev/null echo "git: https://sourceforge.net/p/gnuplot/gnuplot-main/ci/b387dbedf38268c09df258e649fd8ec301c8e1c6/tree/term/cairo.trm?diff=660d60f022c48defaa140ba12d6a1fd931b4bfe5" > /dev/null echo "mailing list: https://sourceforge.net/p/gnuplot/mailman/gnuplot-beta/thread/874juhf80v.fsf%40dima.secretsauce.net/#msg37741736" > /dev/null mrcal-show-residuals \ --magnitudes \ --set 'cbrange [0:1.5]' \ --set 'pointsize 0.5' \ --hardcopy "$Dout/00002.png" \ --title "Residual magnitudes: LENSMODEL_SPLINED_STEREOGRAPHIC" \ --terminal 'pngcairo size 1024,550 notransparent background "#e8dfd0" noenhanced crop font ",12"' \ $D/splined.cameramodel ffmpeg \ -r 1 \ -y \ -f image2 \ -i "$Dout/%05d.png" \ -filter_complex "[0:v] split [a][b];[a] palettegen [p];[b][p] paletteuse" \ ~/projects/mrcal-doc-external/figures/calibration/residual-magnitudes-opencv8-splined-animation.gif #+end_src [[file:external/figures/calibration/residual-magnitudes-opencv8-splined-animation.gif]] Neat! The model fits the data at the edges now. And what about the residual directions? #+begin_src sh mrcal-show-residuals \ --directions \ --unset key \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ mrcal-show-residuals \ --directions \ --unset key \ --set 'pointsize 0.5' \ --hardcopy "~/projects/mrcal-doc-external/figures/calibration/directions-splined.svg" \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' \ $D/splined.cameramodel mrcal-show-residuals \ --directions \ --unset key \ --set 'pointsize 0.5' \ --hardcopy "~/projects/mrcal-doc-external/figures/calibration/directions-splined.png" \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' \ $D/splined.cameramodel mrcal-show-residuals \ --directions \ --unset key \ --set 'pointsize 0.5' \ --hardcopy "~/projects/mrcal-doc-external/figures/calibration/directions-splined.pdf" \ --terminal 'pdf size 8in,6in noenhanced solid color font ",12"' \ $D/splined.cameramodel Dout=~/projects/mrcal-doc-external/figures/calibration/directions mkdir -p $Dout echo "The background color below must match mrcal.css. Adjust them together" > /dev/null echo "I'm hardcoding the image dimensions because of a gnuplot bug. Already fixed in git, but not released yet" > /dev/null echo "git: https://sourceforge.net/p/gnuplot/gnuplot-main/ci/b387dbedf38268c09df258e649fd8ec301c8e1c6/tree/term/cairo.trm?diff=660d60f022c48defaa140ba12d6a1fd931b4bfe5" > /dev/null echo "mailing list: https://sourceforge.net/p/gnuplot/mailman/gnuplot-beta/thread/874juhf80v.fsf%40dima.secretsauce.net/#msg37741736" > /dev/null mrcal-show-residuals \ --directions \ --unset key \ --set 'pointsize 0.5' \ --hardcopy "$Dout/00002.png" \ --title "Residual directions: LENSMODEL_SPLINED_STEREOGRAPHIC" \ --terminal 'pngcairo size 1024,550 notransparent background "#e8dfd0" noenhanced crop font ",12"' \ $D/splined.cameramodel ffmpeg \ -r 1 \ -y \ -f image2 \ -i "$Dout/%05d.png" \ -filter_complex "[0:v] split [a][b];[a] palettegen [p];[b][p] paletteuse" \ ~/projects/mrcal-doc-external/figures/calibration/residual-directions-opencv8-splined-animation.gif #+end_src [[file:external/figures/calibration/residual-directions-opencv8-splined-animation.gif]] /Much/ better than before: the color clustering is /gone/. The poorly-fitting ring in the center is still there, but it is being modeled by this splined model far better than how =LENSMODEL_OPENCV8= did (error magnitudes are much better). We /do/ still see a clear pattern in the directions inside the ring, so it could still be improved: a denser spline spacing would do better. This is a peculiar image processing artifact of the Sony Alpha 7 III camera: from experience, other cameras using this lens do not exhibit this effect. See [[http://mrcal.secretsauce.net/docs-2.2/tour-initial-calibration.html][the tour of mrcal 2.2]] for instance; this used the same lens with a different camera. We can also visualize the [[file:splined-models.org][magnitude of the vector field defined by the splined surfaces]] $\left| \Delta \vec u \right|$: #+begin_src sh mrcal-show-splined-model-correction \ --set 'cbrange [0:0.1]' \ --unset grid \ --set 'xrange [:] noextend' \ --set 'yrange [:] noextend reverse' \ --set 'key opaque box' \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export mkdir -p ~/projects/mrcal-doc-external/figures/splined-models D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ mrcal-show-splined-model-correction \ --set 'cbrange [0:0.1]' \ --unset grid \ --set 'xrange [:] noextend' \ --set 'yrange [:] noextend reverse' \ --set 'key opaque box' \ --hardcopy "~/projects/mrcal-doc-external/figures/splined-models/splined-magnitude.png" \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' \ $D/splined.cameramodel #+end_src [[file:external/figures/splined-models/splined-magnitude.png]] Each X in the plot is a "knot" of the spline surface, a point where a control point value is defined. We're looking at the spline domain, so the axes of the plot are the normalized stereographic projection coordinates $u_x$ and $u_y$, and the knots are arranged in a regular grid. The region where the spline surface is well-defined begins at the 2nd knot from the edges; its boundary is shown as a thin green line. The valid-intrinsics region (the area where the intrinsics are confident because we had sufficient chessboard observations there) is shown as a thick, green curve. Since each $\vec u$ projects to a pixel coordinate $\vec q$ in some nonlinear way, this curve is not straight. We want the valid-intrinsics region to lie entirely within the spline-in-bounds region, and we get that here nicely. If some observations did lie outside the spline-in-bounds regions, the projection behavior there would be less flexible than the rest of the model, resulting in less realistic uncertainties, and a larger-fov splined model would be more appropriate. See [[file:splined-models.org::#splined models field of view selection][the lensmodel documentation]] for more detail. Alternately, I can look at the spline surface as a function of the pixel coordinates: #+begin_src sh mrcal-show-splined-model-correction \ --set 'cbrange [0:0.1]' \ --imager-domain \ --unset grid \ --set 'xrange [:] noextend' \ --set 'yrange [:] noextend reverse' \ --set 'key opaque box' \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ mrcal-show-splined-model-correction \ --set 'cbrange [0:0.1]' \ --imager-domain \ --unset grid \ --set 'xrange [:] noextend' \ --set 'yrange [:] noextend reverse' \ --set 'key opaque box' \ --hardcopy "~/projects/mrcal-doc-external/figures/splined-models/splined-magnitude-imager-domain.png" \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' \ $D/splined.cameramodel #+end_src [[file:external/figures/splined-models/splined-magnitude-imager-domain.png]] Now the valid-intrinsics region is straight, but the spline-in-bounds region is a curve. Projection at the edges is poorly-defined, so the boundary of the spline-in-bounds region appears irregular in this view. I can /also/ look at the correction vector field: #+begin_src sh mrcal-show-splined-model-correction \ --vectorfield \ --imager-domain \ --unset grid \ --set 'xrange [-300:6300]' \ --set 'yrange [3676:-300]' \ --set 'key opaque box' \ --gridn 40 30 \ splined.cameramodel #+end_src #+begin_src sh :exports none :eval no-export ### needed manual tweak in show_splined_model_correction(): "ps 2" -> "ps 1" ### gnuplot makes svg points too big D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ ~/projects/mrcal/mrcal-show-splined-model-correction \ --vectorfield \ --imager-domain \ --unset grid \ --set 'xrange [-300:6300]' \ --set 'yrange [3676:-300]' \ --set 'key opaque box' \ --gridn 40 30 \ --hardcopy "~/projects/mrcal-doc-external/figures/splined-models/splined-vectorfield-imager-domain.svg" \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' \ $D/splined.cameramodel #+end_src [[file:external/figures/splined-models/splined-vectorfield-imager-domain.svg]] This doesn't show anything noteworthy in this solve, but seeing it can be informative with other lenses. * Next Now we can [[file:tour-differencing.org][compare the calibrated models]]. mrcal-2.4.1/doc/tour-stereo.org000066400000000000000000000344601456301662300163770ustar00rootroot00000000000000#+title: A tour of mrcal: stereo processing #+OPTIONS: toc:nil * Previous We just [[file:tour-choreography.org][found the best chessboard-dancing technique]] * Stereo This is an overview of a more detailed discussion about [[file:stereo.org][dense stereo]]. #+begin_src sh :exports none :eval no-export # all the images downsampled for view on the page like this D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/stereo Dout=~/projects/mrcal-doc-external/figures/stereo mkdir -p $Dout for img ( $D/[01].jpg ) { \ convert $img -scale 12% $Dout/${img:r:t}.downsampled.${img:e} } #+end_src We computed intrinsics from chessboards observations earlier, so let's use these for stereo processing. I took several images off [[https://www.openstreetmap.org/#map=19/34.05565/-118.25333][a catwalk over Figueroa Street in downtown Los Angeles]]. This is the view South along Figueroa Street. There're tall buildings ahead and on either side, which makes an interesting stereo scene. The two images out of the camera look like this: [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/0.jpg][file:external/figures/stereo/0.downsampled.jpg]] [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/1.jpg][file:external/figures/stereo/1.downsampled.jpg]] All the full-size images are available by clicking on an image. The cameras are ~ 2m apart. In order to compute stereo images we need an accurate estimate of the relative geometry of the cameras, which we usually get as an output of the calibration process. /Here/ I only had one physical camera, so I did something different: - I calibrated the one camera monocularly, to get its intrinsics. This is what we computed thus far - I used this camera to take a pair of images from slightly different locations. This is the "stereo pair" - I used a separate tool to estimate the extrinsics from corresponding feature detections in the two images. For the purposes of this document the details of this don't matter Generating a stereo pair in this way works well to demo the stereo processing tools. It does break the [[file:triangulation.org][triangulation uncertainty reporting]], since we lose the uncertainty information in the extrinsics, however. Preserving this uncertainty, and propagating it through the recomputed extrinsics to triangulation is on the [[file:roadmap.org][mrcal roadmap]]. The resulting models we use for stereo processing: - [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/0.cameramodel][Left camera]] - [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/1.cameramodel][Right camera]] #+begin_src sh :exports none :eval no-export See external/2022-11-05--dtla-overpass--samyang--alpha7/notes.org for documentation about how I made these #+end_src I then use the [[file:mrcal-stereo.html][=mrcal-stereo=]] tool to compute rectification maps, rectify the images, compute disparities and convert them to ranges: #+begin_src sh mrcal-stereo \ --az-fov-deg 170 \ --az0-deg 10 \ --el-fov-deg 95 \ --el0-deg -15 \ --disparity-range 0 300 \ --sgbm-p1 600 \ --sgbm-p2 2400 \ --sgbm-uniqueness-ratio 5 \ --sgbm-disp12-max-diff 1 \ --sgbm-speckle-window-size 100 \ --sgbm-speckle-range 2 \ --force-grayscale \ --clahe \ [01].cameramodel \ [01].jpg \ #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/stereo; Dout=~/projects/mrcal-doc-external/figures/stereo PYTHONPATH=~/projects/mrcal; export PYTHONPATH; $PYTHONPATH/mrcal-stereo \ --az-fov-deg 170 \ --az0-deg 10 \ --el-fov-deg 95 \ --el0-deg -15 \ --disparity-range 0 300 \ --sgbm-p1 600 \ --sgbm-p2 2400 \ --sgbm-uniqueness-ratio 5 \ --sgbm-disp12-max-diff 1 \ --sgbm-speckle-window-size 100 \ --sgbm-speckle-range 2 \ --force-grayscale \ --clahe \ --outdir $D \ $D/[01].cameramodel \ $D/[01].jpg for img ( $D/*-{rectified,disparity,range}.png ) { \ convert $img -scale 12% $Dout/${img:r:t}.downsampled.${img:e} } #+end_src The =--sgbm-...= options configure the [[https://docs.opencv.org/4.5.3/d2/d85/classcv_1_1StereoSGBM.html][OpenCV SGBM stereo matcher]]. Not specifying them uses the OpenCV defaults, which usually produces poor results. The rectified images look like this: [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/0-rectified.png][file:external/figures/stereo/0-rectified.downsampled.png]] [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/1-rectified.png][file:external/figures/stereo/1-rectified.downsampled.png]] And the disparity and range images look like this: [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/0-disparity.png][file:external/figures/stereo/0-disparity.downsampled.png]] [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/0-range.png][file:external/figures/stereo/0-range.downsampled.png]] From a glance, this is clearly working well. If you've used other stereo libraries previously, these rectified images may look odd: these are fisheye images, so [[file:stereo.org::#stereo-rectification-models][the usual pinhole rectification would pull the corners out towards infinity]]. We don't see that here because [[file:mrcal-stereo.html][=mrcal-stereo=]] uses the [[file:lensmodels.org::#lensmodel-latlon][transverse equirectangular projection]] for rectification by default. This scheme samples the azimuth and elevation angles evenly, which minimizes the visual distortion inside each image row. Rectified models for this scene are generated by [[file:mrcal-stereo.html][=mrcal-stereo=]] [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/rectified0.cameramodel][here]] and [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/rectified1.cameramodel][here]]. See the [[file:stereo.org][stereo-processing documentation]] for details. * Geometry The rectified models define a system with axes - $x$: the baseline; from the origin of the left camera to the origin of the right camera - $y$: down - $z$: forward [[file:mrcal-stereo.html][=mrcal-stereo=]] selects the $y$ and $z$ axes to line up as much as possible with the geometry of the input models. Since the geometry of the actual cameras may not match the idealized rectified geometry (the "forward" view direction may not be orthogonal to the baseline), the usual expectations that $c_x \approx \frac{\mathrm{imagerwidth}}{2}$ and $c_y \approx \frac{\mathrm{imagerheight}}{2}$ are not necessarily true in the rectified system. Thus it's valuable to visualize the models /and/ the rectified field of view, for verification. [[file:mrcal-stereo.html][=mrcal-stereo=]] can do that: #+begin_src sh mrcal-stereo \ --az-fov-deg 170 \ --az0-deg 10 \ --el-fov-deg 95 \ --el0-deg -15 \ --set 'view 70,5' \ --viz geometry \ splined-[01].cameramodel #+end_src #+begin_src sh :exports none :eval no-export PYTHONPATH=~/projects/mrcal; export PYTHONPATH; $PYTHONPATH/mrcal-stereo \ --az-fov-deg 170 \ --az0-deg 10 \ --el-fov-deg 95 \ --el0-deg -15 \ --set 'view 70,5' \ --viz geometry \ --hardcopy $Dout/stereo-rectified-system.svg \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' \ $D/[01].cameramodel #+end_src [[file:external/figures/stereo/stereo-rectified-system.svg]] Here, the geometry /is/ mostly nominal and the rectified view (indicated by the purple lines) /does/ mostly lie along the $z$ axis. This is a 3D plot that can be rotated by the user when =mrcal-stereo --viz geometry= is executed, making the geometry clearer. * ranged pixels ground-truth :noexport: **** Buildings top of Paul Hastings building. 530m away horizontally, 200m vertically: 566m away https://en.wikipedia.org/wiki/City_National_Plaza top of 7th/metro building at 7th/figueroa: 860m horizontally, 108m vertically: 870m Figueroa Tower https://www.emporis.com/buildings/116486/figueroa-tower-los-angeles-ca-usa Top of library tower at 5th/figueroa. 529m horizontally, 300m vertically: 608m Near the top of the wilshire grand: 830m horizontall 270m vertically: 873 http://www.skyscrapercenter.com/building/wilshire-grand-center/9686 Near the top of the N Wells Fargo plaza building. 337m horizontally, 220m vertically: 402m https://en.wikipedia.org/wiki/Wells_Fargo_Center_(Los_Angeles) Los Angeles Center studios ~ 50m tall, on a hill. 520m horizontally: 522m 333 S Beaudry building. 291m horizontally 111m vertically: 311m https://www.emporis.com/buildings/116570/beaudry-center-los-angeles-ca-usa **** tests Command to test all the ranges #+begin_src sh :exports none :eval no-export PYTHONPATH=~/projects/mrcal; export PYTHONPATH what=opencv8; ( $PYTHONPATH/mrcal-triangulate $D/$what-[01].cameramodel $D/[01].jpg 2874 1231 --range-estimate 566 --search-radius 10 $PYTHONPATH/mrcal-triangulate $D/$what-[01].cameramodel $D/[01].jpg 2968 1767 --range-estimate 870 --search-radius 10 $PYTHONPATH/mrcal-triangulate $D/$what-[01].cameramodel $D/[01].jpg 1885 864 --range-estimate 594 --search-radius 10 $PYTHONPATH/mrcal-triangulate $D/$what-[01].cameramodel $D/[01].jpg 3090 1384 --range-estimate 862 --search-radius 10 $PYTHONPATH/mrcal-triangulate $D/$what-[01].cameramodel $D/[01].jpg 541 413 --range-estimate 402 --search-radius 10 $PYTHONPATH/mrcal-triangulate $D/$what-[01].cameramodel $D/[01].jpg 4489 1631 --range-estimate 522 --search-radius 10 $PYTHONPATH/mrcal-triangulate $D/$what-[01].cameramodel $D/[01].jpg 5483 930 --range-estimate 311 --search-radius 10 $PYTHONPATH/mrcal-triangulate $D/$what-[01].cameramodel $D/[01].jpg 5351 964 --range-estimate 311 --search-radius 10 ) | egrep 'q1|Range' #+end_src =tst.py= to just look at a set of ranged features, and to compute the extrinsics with a simple procrustes fit. Bypasses deltapose entirely. Works ok, but not amazingly well #+begin_src python :exports none :eval no-export #!/usr/bin/python3 import sys import numpy as np import numpysane as nps sys.path[:0] = '/home/dima/projects/mrcal', sys.path[:0] = '/home/dima/deltapose-lite', sys.path[:0] = '/home/dima/img_any', import mrcal model_intrinsics = mrcal.cameramodel(2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/splined.cameramodel') t01 = np.array((7.*12*2.54/100, 0, 0)) # 7ft separation on the x xy_xy_range = \ np.array(( (2874, 1231, 2831.68164062, 1233.9498291, 566.0), (2968, 1767, 2916.48388672, 1771.91601562, 870.0), (1885, 864, 1851.86499023, 843.52398682, 594.0), (3090, 1384, 3046.8894043, 1391.49401855, 862.0), (541, 413, 513.77832031, 355.37588501, 402.0), (4489, 1631, 4435.24023438, 1665.17492676, 522.0), (5483, 930, 5435.96582031, 987.39813232, 311.0), (5351, 964, 5304.21630859, 1018.49682617, 311.0), # Ranged pavement points. These don't appear to help (3592.350428, 3199.133514, 3198.330034, 3227.890159, 14.6), (3483.817362, 3094.172913, 3117.605605, 3115.684005, 15.76), )) xy_xy = None #xy_xy = np.array(( (3483.817362, 3094.172913, 3117.605605, 3115.684005),)) q0 = xy_xy_range[:,0:2] q1 = xy_xy_range[:,2:4] r = xy_xy_range[:,(4,)] # Points observed by camera0, represented in camera1 frame p0 = mrcal.unproject(q0, *model_intrinsics.intrinsics(), normalize=True)*r - t01 # The unit observation vectors from the two cameras, observed in camera1. These # must match via a rotation v0 = p0 / nps.dummy(nps.mag(p0), -1) v1 = mrcal.unproject(q1, *model_intrinsics.intrinsics(), normalize=True) R01 = mrcal.align_procrustes_vectors_R01(v0,v1) Rt01 = nps.glue(R01, t01, axis=-2) if xy_xy is not None: import deltapose_lite rt10 = mrcal.rt_from_Rt(mrcal.invert_Rt(Rt01)) p = \ deltapose_lite.compute_3d_intersection_lindstrom(rt10, model_intrinsics.intrinsics(), model_intrinsics.intrinsics(), xy_xy[:,0:2], xy_xy[:,2:4],) print(nps.mag(p)) sys.exit() model0 = mrcal.cameramodel(model_intrinsics) model0.extrinsics_Rt_toref(mrcal.identity_Rt()) model0.write('/tmp/0.cameramodel') model1 = mrcal.cameramodel(model_intrinsics) model1.extrinsics_Rt_toref( Rt01 ) model1.write('/tmp/1.cameramodel') #+end_src * Ranging :PROPERTIES: :CUSTOM_ID: tour-stereo-ranging :END: The [[file:mrcal-stereo.html][=mrcal-stereo=]] tool contains a visualizer that allows the user to quickly examine the stereo scene, evaluating the epipolar line alignment, disparities, ranges, etc. It can be invoked by runnung =mrcal-stereo --viz stereo ...=. After panning/zooming, pressing =r= to display ranges (not disparities), and clicking on the [[https://en.wikipedia.org/wiki/Wilshire_Grand_Center][Wilshire Grand building]] we get this: [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/mrcal-stereo-viz.png]] The computed range at that pixel is 965.52m. My estimated ground truth range is 873m. According to the linearized sensitivity reported by the tool, this corresponds to an error of $\frac{966\mathrm{m}-873\mathrm{m}}{241.3\frac{\mathrm{m}}{\mathrm{pixel}}} = 0.39 \mathrm{pixels}$. Usually, stereo matching errors are in the 1/2 - 1/3 pixel range, so this is in-line with expectations. Here we used dense stereo processing to compute a range map over the whole image. This is slow, and a lot of the time you can get away with computing ranges at a sparse set of points instead. So let's talk about [[file:tour-triangulation.org][triangulation routines]]. * Next We're ready to talk about [[file:tour-triangulation.org][triangulation routines]] mrcal-2.4.1/doc/tour-triangulation.org000066400000000000000000000244071456301662300177560ustar00rootroot00000000000000#+title: A tour of mrcal: triangulation #+OPTIONS: toc:nil #+LATEX_HEADER: \DeclareMathOperator*{\argmin}{argmin} #+LATEX_HEADER: \DeclareMathOperator*{\Var}{Var} #+BEGIN_HTML \( \DeclareMathOperator*{\argmin}{argmin} \DeclareMathOperator*{\Var}{Var} \) #+END_HTML * Previous We just looked at [[file:tour-stereo.org][dense stereo processing]] * Overview This is an overview of a more detailed discussion about [[file:triangulation.org][triangulation methods and uncertainty]]. We just generated a range map: an image where each pixel encodes a range along each corresponding observation vector. This is computed relatively efficiently, but computing a range value for /every/ pixel in the rectified image is still slow, and for many applications it isn't necessary. The mrcal triangulation routines take the opposite approach: given a discrete set of observed features, compute the position of just those features. In addition to being far faster, the triangulation routines propagate uncertainties and provide lots and lots of diagnostics to help debug incorrectly-reported ranges. mrcal's sparse triangulation capabilities are provided by the [[file:mrcal-triangulate.html][=mrcal-triangulate=]] tool and the [[file:mrcal-python-api-reference.html#-triangulate][=mrcal.triangulate()=]] Python routine. Each of these ingests - Some number of pairs of pixel observations $\left\{ \vec q_{0_i}, \vec q_{1_i} \right\}$ - The corresponding camera models - The corresponding images To produce - The position of the point in space $\vec p_i$ that produced these observations for each pair - A covariance matrix, reporting the uncertainty of each reported point $\Var\left( \vec p_i \right)$ and the covariances $\Var \left( \vec p_i, \vec p_j \right)$ * Triangulation Let's use our Downtown Los Angeles images. Before we start, one important caveat: there's only one camera, which was calibrated monocularly. The one camera was moved to capture the two images used to triangulate. The extrinsics were computed with a not-yet-in-mrcal tool, and mrcal cannot yet propagate the calibration noise in this scenario. Thus in this example we only propagate the observation-time noise. Image from the left camera: [[file:external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/0.jpg][file:external/figures/stereo/0.downsampled.jpg]] Let's compute the range to the top of the [[https://en.wikipedia.org/wiki/Wilshire_Grand_Center][Wilshire Grand building]], just as we [[file:tour-stereo.org::#tour-stereo-ranging][did earlier]]. The screenshot from =mrcal-stereo --viz= examined the pixel 2836.4,2045.7 in the /rectified/ image. Let's convert it back to the out-of-the-left-camera image: #+begin_example $ echo "2836.4 2045.7" | mrcal-reproject-points rectified0.cameramodel 0.cameramodel 2722.289377 1472.947733 #+end_example #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/stereo; echo "2836.4 2045.7" | ./mrcal-reproject-points $D/rectified0.cameramodel $D/0.cameramodel #+end_src Let's triangulate: #+begin_src sh mrcal-triangulate \ --range-estimate 873 \ --q-observation-stdev 0.3 \ --q-observation-stdev-correlation 0.1 \ --stabilize \ --template-size 31 17 \ --search-radius 10 \ --viz uncertainty \ [01].cameramodel \ [01].jpg \ 2722.289377 1472.947733 #+end_src #+begin_src sh :exports none :eval no-export Dout=~/projects/mrcal-doc-external/figures/triangulation mkdir -p $Dout D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/stereo PYTHONPATH=~/projects/mrcal; export PYTHONPATH; $PYTHONPATH/mrcal-triangulate \ --range-estimate 873 \ --q-observation-stdev 0.3 \ --q-observation-stdev-correlation 0.1 \ --stabilize \ --template-size 31 17 \ --search-radius 10 \ --viz uncertainty \ --hardcopy $Dout/wilshire-grand-ellipse.svg \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' \ $D/[01].cameramodel \ $D/[01].jpg \ 2722.289377 1472.947733 #+end_src Here we used the splined models computed [[file:tour-initial-calibration.org::#splined-model-solving][earlier]]. We gave the tool the true range (873m) to use as a reference. And we gave it the expected observation noise level: 0.3 pixels (a loose estimate based on empirical experience). We declared the left-camera/right-camera pixel observations to be correlated with a factor of 0.1 on the stdev, so the relevant cross terms of the covariance matrix are $(0.3*0.1 \mathrm{pixels})^2$. It's not yet clear how to get the true value of this correlation, but we can use this tool to gauge its effects. The [[file:mrcal-triangulate.html][=mrcal-triangulate=]] tool finds the corresponding feature in the second image using a template-match technique in [[file:mrcal-python-api-reference.html#-match_feature][=mrcal.match_feature()=]]. This operation could fail, so a diagnostic visualization can be requested by passing =--viz match=. This pops up an interactive window with the matched template overlaid in its best-fitting position so that a human can validate the match. The match was found correctly here. We could also pass =--viz uncertainty=, which shows the uncertainty ellipse. Unless we're looking very close in, this ellipse is almost always extremely long and extremely skinny. Here we have: [[file:external/figures/triangulation/wilshire-grand-ellipse.svg]] So looking at the ellipse usually isn't very useful, and the value printed in the statistics presents the same information in a more useful way. The [[file:mrcal-triangulate.html][=mrcal-triangulate=]] tool produces /lots/ of reported statistics: #+begin_example ## Feature [2722.289 1472.948] in the left image corresponds to [2804.984 1489.036] at 873.0m ## Feature match found at [2805.443 1488.697] ## q1 - q1_perfect_at_range = [ 0.459 -0.339] ## Triangulated point at [ -94.251 -116.462 958.337]; direction: [-0.097 -0.12 0.988] [camera coordinates] ## Triangulated point at [-96.121 -81.23 961.719]; direction: [-0.097 -0.084 0.992] [reference coordinates] ## Range: 969.98 m (error: 96.98 m) ## q0 - q0_triangulation = [-0.023 0.17 ] ## Uncertainty propagation: observation-time noise suggests worst confidence of sigma=104.058m along [ 0.098 0.12 -0.988] ## Observed-pixel range sensitivity: 246.003m/pixel (q1). Worst direction: [0.998 0.07 ]. Linearized correction: -0.394 pixels ## Calibration yaw (rotation in epipolar plane) sensitivity: -8949.66m/deg. Linearized correction: 0.011 degrees of yaw ## Calibration yaw (cam0 y axis) sensitivity: -8795.81m/deg. Linearized correction: 0.011 degrees of yaw ## Calibration pitch (tilt of epipolar plane) sensitivity: 779.47m/deg. ## Calibration translation sensitivity: 529.52m/m. Worst direction: [0.986 0. 0.165]. Linearized correction: -0.18 meters of translation ## Optimized yaw (rotation in epipolar plane) correction = 0.012 degrees ## Optimized pitch (tilt of epipolar plane) correction = 0.009 degrees ## Optimized relative yaw (1 <- 0): 0.444 degrees #+end_example We see that - The range we compute here is 969.98m, not 873m as desired - There's a difference of [-0.023 0.17] pixels between the triangulated point and the observation in the left camera: the epipolar lines are aligned well. This should be 0, ideally, but 0.17 pixels is easily explainable by pixel noise - With the given observation noise, the 1-sigma uncertainty in the range is 104.058m, almost exactly in the observation direction. This is very similar to the actual error of 96.98m - Moving the matched feature coordinate in the right image affects the range at worst at a rate of 246.003 m/pixel. Unsurprisingly, the most sensitive direction of motion is left/right. At this rate, it would take 0.394 pixels of motion to "fix" our range measurement - Similarly, we compute and report the range sensitivity of extrinsic yaw (defined as the rotation in the epipolar plane or around the y axis of the left camera). In either case, an extrinsics yaw shift of 0.011 degrees would "fix" the range measurement. - We also compute sensitivities for pitch and translation, but we don't expect those to affect the range very much, and we see that - Finally, we reoptimize the extrinsics, and compute a better yaw correction to "fix" the range: 0.012 degrees. This is different from the previous value of 0.011 degrees because that computation used a /linearized/ yaw-vs-range dependence, but the reoptimization doesn't. This is all quite useful, and suggests that a small extrinsics error is likely the biggest problem. What about =--q-observation-stdev-correlation=? What would be the effect of more or less correlation in our pixel observations? Running the same command with - =--q-observation-stdev-correlation 0= (the left and right pixel observations are independent) produces #+begin_example ## Uncertainty propagation: observation-time noise suggests worst confidence of sigma=104.580m along [ 0.098 0.12 -0.988] #+end_example - =--q-observation-stdev-correlation 1= (the left and right pixel observations are perfectly coupled) produces #+begin_example ## Uncertainty propagation: observation-time noise suggests worst confidence of sigma=5.707m along [-0.095 -0.144 0.985] #+end_example I.e. correlations in the pixel measurements decrease our range uncertainty. To the point where perfectly-correlated observations produce almost perfect ranging. We'll still have range errors, but they would come from other sources than slightly mismatched feature observations. A future update to mrcal will include a method to propagate uncertainty through to re-solved extrinsics and /then/ to triangulation. That will fill-in the biggest missing piece in the error modeling here. mrcal-2.4.1/doc/tour-uncertainty.org000066400000000000000000000411241456301662300174360ustar00rootroot00000000000000#+title: A tour of mrcal: quantifying uncertainty #+OPTIONS: toc:t * Previous We just [[file:tour-differencing.org][compared the calibrated models]]. * Projection uncertainty An overview follows; see the [[file:formulation.org::#noise-model][noise model]] and [[file:uncertainty.org][projection uncertainty]] pages for details. We calibrated this camera using two different models, and we have strong evidence that the =LENSMODEL_SPLINED_STEREOGRAPHIC= solve is better than the =LENSMODEL_OPENCV8= solve. We even know the difference between these two results. But we don't know the deviation from the /true/ solution. In other words: is the =LENSMODEL_SPLINED_STEREOGRAPHIC= solution good-enough, and can we use it in further work (mapping, state estimation, etc...)? To answer that question, let's consider the sources of error that affect calibration quality: - *Sampling error*. Our computations are based on fitting a model to observations of chessboard corners. These observations aren't perfect, and contain a sample of some noise distribution. We can [[file:formulation.org::#noise-model][characterize this distribution]] and we can then analytically predict the effects of that noise. We do that here. - *Model error*. These result when the solver's model of the world is insufficient to describe what is actually happening. When model errors are present, even the best set of parameters aren't able to completely fit the data. Some sources of model errors: motion blur, unsynchronized cameras, chessboard detector errors, too-simple (or unstable) [[file:lensmodels.org][lens models]] or chessboard deformation models, and so on. Since these errors are unmodeled (by definition), we can't analytically predict their effects. Instead we try hard to force these errors to zero, so that we can ignore them. We do this by using rich-enough models and by gathering clean data. I will talk about detecting model errors in [[file:tour-cross-validation.org][the next section of the tour of mrcal (cross-validation diffs)]]. Let's do as much as we can analytically: let's gauge the effects of sampling error by computing a /projection uncertainty/ for a model. Given a camera-coordinate point $\vec p$ we compute the projected pixel coordinate $\vec q$ (a "projection"), along with the covariance $\mathrm{Var} \left(\vec q\right)$ to represent the uncertainty due to the calibration-time noise in the observations of the chessboard corners. With $\mathrm{Var} \left(\vec q\right)$ we can - Propagate this uncertainty downstream to whatever uses the projection operation, for example to get the uncertainty of ranges from a triangulation - Evaluate how precise a given calibration is, and to run studies about how to do better - Quantify overfitting effects - Quantify the baseline noise level for informed interpretation of model differences - Intelligently select the region used to compute the implied transformation when computing differences These are quite important. Since splined models can have 1000s of parameters, overfitting could be a concern. But the projection uncertainty computation explicitly measures the effects of sampling errors, so if we're too sensitive to input noise, the uncertainty results would clearly tell us that. ** Derivation summary It is a reasonable assumption that each $x$ and $y$ measurement in every detected chessboard corner contains independent, gaussian noise. This noise is hard to measure directly (there's an [[https://github.com/dkogan/mrgingham/blob/master/mrgingham-observe-pixel-uncertainty][attempt]] in mrgingham), so we estimate it from the solve residuals. We then have the diagonal matrix representing the variance our input noise: $\mathrm{Var}\left( \vec q_\mathrm{ref} \right)$. We propagate this input noise through the optimization, to find out how this noise would affect the calibration solution. Given some perturbation of the inputs, we can derive the resulting perturbation in the optimization state: $\Delta \vec b = M \Delta \vec q_\mathrm{ref}$ for some matrix $M$ we can compute. The [[file:formulation.org::#state-vector][state vector $\vec b$]] contains /everything/: the intrinsics of all the lenses, the geometry of all the cameras and chessboards, the chessboard shape, etc. We have the variance of the input noise, so we can compute the variance of the state vector: \[ \mathrm{Var}(\vec b) = M \mathrm{Var}\left(\vec q_\mathrm{ref}\right) M^T \] Now we need to propagate this uncertainty in the optimization state through a projection. Let's say we have a point $\vec p_\mathrm{fixed}$ defined in some /fixed/ coordinate system. We need to transform it to the camera coordinate system before we can project it: \[ \vec q = \mathrm{project}\left( \mathrm{transform}\left( \vec p_\mathrm{fixed} \right)\right) \] So $\vec q$ is a function of the intrinsics and the transformation. Both of these are functions of the optimization state, so we can propagate our noise in the optimization state $\vec b$: \[ \mathrm{Var}\left( \vec q \right) = \frac{\partial \vec q}{\partial \vec b} \mathrm{Var}\left( \vec b \right) \frac{\partial \vec q}{\partial \vec b}^T \] There lots and lots of omitted details here, so please read the [[file:uncertainty.org][full documentation]] if interested. ** Simulation Let's run some synthetic-data analysis to validate this approach. This all comes directly from the mrcal test suite: Let's place 4 cameras using a =LENSMODEL_OPENCV4= (simple and fast) model side by side, and let's have them look at 50 chessboards, with randomized positions and orientations. #+begin_src sh test/test-projection-uncertainty.py \ --fixed cam0 \ --model opencv4 \ --do-sample \ --make-documentation-plots '' #+end_src #+begin_src sh :exports none :eval no-export cd ~/projects/mrcal mkdir -p ~/projects/mrcal-doc-external/figures/uncertainty/ test/test-projection-uncertainty.py \ --fixed cam0 \ --model opencv4 \ --do-sample \ --make-documentation-plots \ ~/projects/mrcal-doc-external/figures/uncertainty/simulated-uncertainty-opencv4 #+end_src The synthetic geometry looks like this: [[file:external/figures/uncertainty/simulated-uncertainty-opencv4--simulated-geometry.svg]] The solved coordinate system of each camera is shown. Each observed chessboard is shown as a zigzag connecting all the corners in order. The cameras each see: [[file:external/figures/uncertainty/simulated-uncertainty-opencv4--simulated-observations.svg]] The purple points are the observed chessboard corners. All the chessboards are roughly at the center of the scene, so the left camera sees objects on the right side of its view, and the right camera sees objects on the left. We want to evaluate the uncertainty of a calibration made with these observations. So we run 100 randomized trials, where each time we - add a bit of noise to the observations - compute the calibration - look at what happens to the projection of an arbitrary point $\vec q$ on the imager: the marked $\color{red}{\ast}$ in the plots above A confident calibration would have low $\mathrm{Var}\left(\vec q\right)$, and projections would be insensitive to observation noise: the $\color{red}{\ast}$ wouldn't move much as we add input noise. By contrast, a poor calibration would have high uncertainty, and the $\color{red}{\ast}$ would move significantly due to random observation noise. The above command runs the trials, following the reprojection of $\color{red}{\ast}$. We plot the empirical 1-sigma ellipse computed from these samples, and also the 1-sigma ellipse predicted by the [[file:mrcal-python-api-reference.html#-projection_uncertainty][=mrcal.projection_uncertainty()=]] routine. This is the routine that implements the scheme described above, but does so analytically, without any sampling. It is thus much faster. [[file:external/figures/uncertainty/simulated-uncertainty-opencv4--distribution-onepoint.svg]] Clearly the two ellipses (blue and green) line up well, so there's good agreement between the observed and predicted uncertainties. So from now on we will use the predictions only. We see that the reprojection uncertainties of this point are different for each camera. This happens because the distribution of chessboard observations is different in each camera. We're looking at a point in the top-left quadrant of the imager. And as we saw before, this point was surrounded by chessboard observations only in the first camera. In the second and third cameras, this point was on the edge of region of chessboard observations. And in the last camera, the observations were all quite far away from this query point. In /that/ camera, we have no data about the lens behavior in this area, and we're extrapolating. We should expect to have the best uncertainty in the first camera, worse uncertainties in the next two cameras, and poor uncertainty in the last camera. And this is exactly what we observe. Now that we validated the relatively quick-to-compute [[file:mrcal-python-api-reference.html#-projection_uncertainty][=mrcal.projection_uncertainty()=]] estimates, let's use them to compute uncertainty maps across the whole imager, not just at a single point: [[file:external/figures/uncertainty/simulated-uncertainty-opencv4--uncertainty-wholeimage-noobservations.svg]] As expected, we see that the sweet spot is different for each camera, and it tracks the location of the chessboard observations. And we can see that the $\color{red}{\ast}$ is in the sweet spot only in the first camera. ** Using a splined model Let's focus on the last camera. Here the chessboard observations were nowhere near the focus point, and we reported an expected reprojection error of ~0.8 pixels. This is significantly worse than the other cameras, but it's not terrible in absolute terms. If an error of 0.8 pixels is acceptable for our application, could we use that calibration result to project points around the $\color{red}{\ast}$? Unfortunately, we cannot. We didn't observe any chessboards there, so we don't know how the lens behaves in that area. The optimistic result reported by the uncertainty algorithm isn't wrong, but it's not answering the question we're asking. We're computing how observation noise affects the whole optimizer state, including the lens parameters (=LENSMODEL_OPENCV4= in this case). And then we compute how the noise in those lens parameters and geometry affects projection. The =LENSMODEL_OPENCV4= model is very lean (has few parameters). This gives it stiffness, which prevents the projection $\vec q$ from moving very far in response to noise, which we then interpret as a relatively-low uncertainty of 0.8 pixels. If we used a model with more parameters, the extra flexibility would allow the projection to move much further in response to noise, and we'd see a higher uncertainty. So here our choice of lens model itself is giving us low uncertainties. If we knew for a fact that the true lens is 100% representable by a =LENSMODEL_OPENCV4= model, then this would be be correct, but that never happens in reality. So *lean models always produce overly-optimistic uncertainty estimates*. This is yet another advantage of splined models: they're flexible, so the model itself has little effect on the reported uncertainty. And we get the behavior we want: reported uncertainty is driven /only/ by the data we have gathered. Let's re-run this analysis using a splined model, and let's look at the same uncertainty plots as above (note: this is /slow/): #+begin_src sh test/test-projection-uncertainty.py \ --fixed cam0 \ --model splined \ --do-sample \ --make-documentation-plots '' #+end_src #+begin_src sh :exports none :eval no-export test/test-projection-uncertainty.py \ --fixed cam0 \ --model splined \ --do-sample \ --make-documentation-plots \ ~/projects/mrcal-doc-external/figures/uncertainty/simulated-uncertainty-splined #+end_src [[file:external/figures/uncertainty/simulated-uncertainty-splined--uncertainty-wholeimage-noobservations.svg]] As expected, the reported uncertainties are now far worse. In fact, we can see that only the first camera's projection is truly reliable at the $\color{red}{\ast}$. This is representative of reality. To further clarify where the uncertainty region comes from, let's overlay the chessboard observations onto it: [[file:external/figures/uncertainty/simulated-uncertainty-splined--uncertainty-wholeimage-observations.svg]] The connection between the usable-projection region and the observed-chessboards region is indisputable. This plot also sheds some light on the effects of spline density. If we had a denser spline, some of the gaps in-between the chessboard observations would show up as poor-uncertainty regions. This hasn't yet been studied on real-world data. Given this, I claim that we want to use splined models in most situations, even for long lenses which roughly follow the pinhole model. The basis of mrcal's splined models is the stereographic projection, which is identical to a pinhole projection when representing a long lens, so the splined models will also fit long lenses well. The only downside to using a splined model in general is the extra required computational cost. It isn't terrible today, and will get better with time. And for that low price we get the extra precision (no lens follows the lean models when you look closely enough) and we get truthful uncertainty reporting. ** Revisiting uncertainties from the earlier calibrations :PROPERTIES: :CUSTOM_ID: tour-uncertainty-splined-model-uncertainties :END: We started this by calibrating a camera using a =LENSMODEL_OPENCV8= model, and then again with a splined model. Let's look at the uncertainty of those solves using the handy [[file:mrcal-show-projection-uncertainty.html][=mrcal-show-projection-uncertainty=]] tool. First, the =LENSMODEL_OPENCV8= solve: #+begin_src sh mrcal-show-projection-uncertainty opencv8.cameramodel --cbmax 1 --unset key #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ mrcal-show-projection-uncertainty \ $D/opencv8.cameramodel \ --cbmax 1 \ --unset key \ --hardcopy ~/projects/mrcal-doc-external/figures/uncertainty/uncertainty-opencv8.svg \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' mrcal-show-projection-uncertainty \ $D/opencv8.cameramodel \ --cbmax 1 \ --unset key \ --hardcopy ~/projects/mrcal-doc-external/figures/uncertainty/uncertainty-opencv8.pdf \ --terminal 'pdf size 8in,6in noenhanced solid color font ",12"' mrcal-show-projection-uncertainty \ $D/opencv8.cameramodel \ --cbmax 1 \ --unset key \ --hardcopy ~/projects/mrcal-doc-external/figures/uncertainty/uncertainty-opencv8.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' #+end_src [[file:external/figures/uncertainty/uncertainty-opencv8.png]] And the splined solve: #+begin_src sh mrcal-show-projection-uncertainty splined.cameramodel --cbmax 1 --unset key #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/ mrcal-show-projection-uncertainty \ $D/splined.cameramodel \ --cbmax 1 \ --unset key \ --hardcopy ~/projects/mrcal-doc-external/figures/uncertainty/uncertainty-splined.svg \ --terminal 'svg size 800,600 noenhanced solid dynamic font ",14"' mrcal-show-projection-uncertainty \ $D/splined.cameramodel \ --cbmax 1 \ --unset key \ --hardcopy ~/projects/mrcal-doc-external/figures/uncertainty/uncertainty-splined.pdf \ --terminal 'pdf size 8in,6in noenhanced solid color font ",12"' mrcal-show-projection-uncertainty \ $D/splined.cameramodel \ --cbmax 1 \ --unset key \ --hardcopy ~/projects/mrcal-doc-external/figures/uncertainty/uncertainty-splined.png \ --terminal 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' #+end_src [[file:external/figures/uncertainty/uncertainty-splined.png]] As expected, the splined model produces less optimistic (but more realistic) uncertainty reports. In [[file:tour-differencing.org][the last section]] we compared our two calibrated models, and the difference looked like this: [[file:external/figures/diff/diff-splined-opencv8.png]] Clearly the errors predicted by the projection uncertainty plots don't account for the large differences we see here: roughly we want to see $\mathrm{difference} \approx \mathrm{uncertainty}_0 + \mathrm{uncertainty}_1$. The reason for this is non-negligible model errors, so this is a good time to talk about cross-validation. * Next Now [[file:tour-cross-validation.org][we compare results of two different calibrations to gauge solution quality]]. mrcal-2.4.1/doc/tour.org000066400000000000000000000041001456301662300150640ustar00rootroot00000000000000#+title: A tour of mrcal #+OPTIONS: toc:nil mrcal is a toolkit that provides improved methods for making and using camera models (calibration, tracking, mapping, photogrammetry, etc). The best way to convey a sense of the capabilities is to demonstrate some real-world usage scenarios. So let's go through a full calibration sequence starting with chessboard images, and eventually finishing with stereo processing and triangulation. This page is a high-level overview of all the techniques that make mrcal different and better than other tools. For more details, please see the links in [[file:index.org][the main documentation]]. For /practical/ details, please see the [[file:how-to-calibrate.org][how-to-calibrate page]] and the [[file:recipes.org][recipes page]]. All images in these articles have been gathered with a Sony Alpha 7 III SLR. I want to stress-test the system, so I'm using the widest lens I can find: a Samyang 12mm F2.8 fisheye lens. This lens has a ~ 180deg field of view corner to corner, and about 160deg field of view horizontally. In these demos I'm using only one camera, so I'm going to run a /monocular/ calibration to compute the intrinsics (the lens parameters). mrcal is fully able to calibrate any N cameras at a time, I'm just using the one camera /here/. The tour is split over a number of pages: 1. [[file:tour-initial-calibration.org][We gather calibration images, and perform some initial calibrations]] 2. [[file:tour-differencing.org][Differencing: we compare several of the calibrated models]] 3. [[file:tour-uncertainty.org][Uncertainty estimation: we compute the projection uncertainties of the models]] 4. [[file:tour-cross-validation.org][Cross-validation: we compare results of two different calibrations to gauge solution quality]] 5. [[file:tour-effect-of-range.org][We discuss the effect of range in differencing and uncertainty computations]] 6. [[file:tour-choreography.org][We use the uncertainty analysis to find the best chessboard-dancing technique]] 7. [[file:tour-stereo.org][Stereo processing]] 8. [[file:tour-triangulation.org][Triangulation]] mrcal-2.4.1/doc/triangulation-symmetric.fig000066400000000000000000000021721456301662300207520ustar00rootroot00000000000000#FIG 3.2 Produced by xfig version 3.2.8 Portrait Center Metric Letter 100.00 Single -2 1200 2 0 32 #a0a0a0 5 1 0 1 0 7 50 -1 -1 4.000 0 1 0 0 6972.141 3778.305 6694 3506 6605 3649 6584 3749 5 1 0 1 0 7 50 -1 -1 4.000 0 0 0 0 1565.734 920.799 1795 1057 1658 1171 1452 1162 6 6930 3375 7380 3780 2 3 0 2 2 7 50 -1 -1 12.000 0 0 7 0 0 5 7053 3626 6953 3402 7351 3402 7252 3626 7053 3626 2 3 0 2 2 7 50 -1 -1 12.000 0 0 7 0 0 5 6953 3626 7351 3626 7351 3754 6953 3754 6953 3626 -6 6 -225 3330 225 3780 2 3 0 2 1 7 50 -1 -1 12.000 0 0 7 0 0 5 -107 3626 -207 3402 191 3402 92 3626 -107 3626 2 3 0 2 1 7 50 -1 -1 12.000 0 0 7 0 0 5 -207 3626 191 3626 191 3754 -207 3754 -207 3626 -6 1 3 0 1 0 0 50 -1 20 0.000 1 0.0000 1575 945 45 45 1575 945 1620 945 2 1 1 1 0 7 50 -1 -1 8.000 0 0 7 0 0 1 3150 1575 2 1 0 3 0 7 50 -1 -1 8.000 2 0 -1 0 0 3 0 3735 1575 945 7155 3735 2 1 1 1 0 7 50 -1 -1 8.000 0 0 -1 0 0 2 1 3747 7155 3747 4 1 0 50 -1 16 14 0.0000 5 180 915 3645 3690 baseline\001 4 0 0 50 -1 16 14 0.0000 5 180 615 900 2385 range\001 4 1 0 50 -1 32 14 0.0000 5 210 120 6507 3647 f\001 4 1 0 50 -1 32 14 0.0000 5 165 120 1669 1372 q\001 mrcal-2.4.1/doc/triangulation.org000066400000000000000000000513451456301662300167700ustar00rootroot00000000000000#+TITLE: Triangulation methods and uncertainty #+OPTIONS: toc:t #+LATEX_HEADER: \DeclareMathOperator*{\argmin}{argmin} #+LATEX_HEADER: \DeclareMathOperator*{\Var}{Var} #+BEGIN_HTML \( \DeclareMathOperator*{\argmin}{argmin} \DeclareMathOperator*{\Var}{Var} \) #+END_HTML A very common thing to want to do with a calibrated camera system is to convert a pair of pixel observations of a feature to a point in space that produced these observations, a process known as [[https://en.wikipedia.org/wiki/Triangulation_(computer_vision)][triangulation]]. mrcal supports both sparse triangulation (processing a small number of discrete pixel observations) and dense triangulation (processing every pixel in a pair of images; [[file:stereo.org][stereo vision]]). This can be sensitive to noise, creating a strong need for proper error modeling and propagation. Here I describe mrcal's sparse triangulation capabilities: the [[file:mrcal-triangulate.html][=mrcal-triangulate=]] tool and the [[file:mrcal-python-api-reference.html#-triangulate][=mrcal.triangulate()=]] Python routine. * Overview Let's say we have an idealized geometry: [[file:figures/triangulation-symmetric.svg]] Let $b \equiv \mathrm{baseline}$ and $r \equiv \mathrm{range}$. Two cameras are looking at a point in space. Given two camera models and a pair of pixel observations we can compute the range to the point. Basic geometry tells us that \[\frac{r}{\sin \phi} = \frac{b}{\sin \theta}\] When looking far away, straight ahead, we have $\theta \approx 0$ and $\phi \approx 90^\circ$, so \[ r \approx \frac{b}{\theta}\] Differentiating, we get \[\frac{\mathrm{d}r}{\mathrm{d}\theta} \propto \frac{b}{\theta^2} \propto \frac{r^2}{b}\] Thus a small error in $\theta$ causes an error in the computed range that is proportional to the /square/ of $r$. This relationship sets the fundamental limit for the ranging capabilities of stereo systems: if you try to look out too far, the precision of $\theta$ required to get a precise-enough $r$ becomes unattainable. And because we have $r^2$, this range limit is approached very quickly. A bigger baseline helps, but does so only linearly. The angle $\theta$ comes from the extrinsics and intrinsics in the camera model, so the noise modeling and uncertainty propagation in mrcal are essential to a usable long-range stereo system. * Triangulation routines Before we can talk about quantifying the uncertainty of a triangulation operation, we should define what that operation is. Each triangulation operation takes as input - Two camera models. Intrinsics (lens behavior) and extrinsics (geometry) are required for both - Pixel coordinates $\vec q$ of the same observed feature in the two images captured by each camera And it outputs - A point $\vec p$ in space that produced the given pixel observations The "right" way to implement this operation is to minimize the reprojection error: \[ E\left(\vec p\right) \equiv \left\lVert \vec q_0 - \mathrm{project}_\mathrm{cam0}\left(\vec p\right) \right\rVert^2 + \left\lVert \vec q_1 - \mathrm{project}_\mathrm{cam1}\left(\vec p\right) \right\rVert^2 \] \[ \vec p^* \equiv \argmin{E\left(\vec p\right)} \] This is correct, but it's complex and requires a nonlinear optimization, which limits the usefulness of this approach. mrcal implements several slightly-imprecise but /much/ faster methods to compute a triangulation. All of these precompute $\vec v \equiv \mathrm{unproject} \left( \vec q \right)$, and then operate purely geometrically. The methods are described in these papers, listed in chronological order: - "Triangulation Made Easy", Peter Lindstrom. IEEE Conference on Computer Vision and Pattern Recognition, 2010 - "Closed-Form Optimal Two-View Triangulation Based on Angular Errors", Seong Hun Lee and Javier Civera. https://arxiv.org/abs/1903.09115 - "Triangulation: Why Optimize?", Seong Hun Lee and Javier Civera https://arxiv.org/abs/1907.11917 The last paper compares the available methods from /all/ the papers. A [[https://github.com/dkogan/mrcal/blob/master/analyses/triangulation/study.py][triangulation study]] is available to evaluate the precision and accuracy of the existing methods. Currently =leecivera_mid2= is recommended for most usages. Note that all of the Lee-Civera methods work geometrically off observation vectors, not pixel coordinates directly. This carries an implicit assumption that the angular resolution is constant across the whole imager. This is usually somewhat true, but the extent depends on the specific lens and camera. Use the [[file:recipes.org::#visualizing-resolution][resolution-visualization tool]] to check. The triangulation methods available in mrcal: ** =geometric= This is the basic [[https://en.wikipedia.org/wiki/Triangulation_(computer_vision)#Mid-point_method][midpoint method]]: it computes the point in space that minimizes the distance between the two observation rays. This is the simplest method, but also produces the most bias. Not recommended. Implemented in [[file:mrcal-python-api-reference.html#-triangulate_geometric][=mrcal.triangulate_geometric()=]] (in Python) and [[https://www.github.com/dkogan/mrcal/blob/master/triangulation.h#mrcal_triangulate_geometric][=mrcal_triangulate_geometric()=]] (in C). ** =lindstrom= Described in the "Triangulation Made Easy" paper above. The method is a close approximation to a reprojection error minimization (the "right" approach above) /if we have pinhole lenses/. Implemented in [[file:mrcal-python-api-reference.html#-triangulate_lindstrom][=mrcal.triangulate_lindstrom()=]] (in Python) and [[https://www.github.com/dkogan/mrcal/blob/master/triangulation.h#mrcal_triangulate_lindstrom][=mrcal_triangulate_lindstrom()=]] (in C). ** =leecivera_l1= Described in the "Closed-Form Optimal Two-View Triangulation Based on Angular Errors" paper above. Minimizes the L1 norm of the observation angle error. Implemented in [[file:mrcal-python-api-reference.html#-triangulate_leecivera_l1][=mrcal.triangulate_leecivera_l1()=]] (in Python) and [[https://www.github.com/dkogan/mrcal/blob/master/triangulation.h#mrcal_triangulate_leecivera_l1][=mrcal_triangulate_leecivera_l1()=]] (in C). ** =leecivera_linf= Described in the "Closed-Form Optimal Two-View Triangulation Based on Angular Errors" paper above. Minimizes the L-infinity norm of the observation angle error. Implemented in [[file:mrcal-python-api-reference.html#-triangulate_leecivera_linf][=mrcal.triangulate_leecivera_linf()=]] (in Python) and [[https://www.github.com/dkogan/mrcal/blob/master/triangulation.h#mrcal_triangulate_leecivera_linf][=mrcal_triangulate_leecivera_linf()=]] (in C). ** =leecivera_mid2= Described in the "Triangulation: Why Optimize?" paper above: this is the "Mid2" method. Doesn't explicitly minimize anything, but rather is a heuristic that works well in practice. Implemented in [[file:mrcal-python-api-reference.html#-triangulate_leecivera_mid2][=mrcal.triangulate_leecivera_mid2()=]] (in Python) and [[https://www.github.com/dkogan/mrcal/blob/master/triangulation.h#mrcal_triangulate_leecivera_mid2][=mrcal_triangulate_leecivera_mid2()=]] (in C). ** =leecivera_wmid2= Described in the "Triangulation: Why Optimize?" paper above: this is the "wMid2" method. Doesn't explicitly minimize anything, but rather is a heuristic that works well in practice. Similar to =leecivera_mid2=, but contains a bit of extra logic to improve the behavior for points very close to the cameras (not satisfying $r \gg b$). Implemented in [[file:mrcal-python-api-reference.html#-triangulate_leecivera_wmid2][=mrcal.triangulate_leecivera_wmid2()=]] (in Python) and [[https://www.github.com/dkogan/mrcal/blob/master/triangulation.h#mrcal_triangulate_leecivera_wmid2][=mrcal_triangulate_leecivera_wmid2()=]] (in C). * Triangulation uncertainty We compute the uncertainty of a triangulation operation using the usual error-propagation technique: - We define the input noise - We compute the operation through which we're propagating this input noise, evaluating the gradients of the output in respect to all the noisy inputs - We assume the behavior is locally linear and that the input noise is Gaussian, which allows us to easily compute the output noise using the usual noise-propagation relationship ** Noise sources We want to capture the effect of two different sources of error: - /Calibration-time/ noise. We propagate the noise in chessboard observations obtained during the chessboard dance. This is the [[file:formulation.org::#noise-model-inputs][noise]] that we propagate when evaluating [[file:uncertainty.org][projection uncertainty]]. This is specified in the =--q-calibration-stdev= argument to [[file:mrcal-triangulate.html][=mrcal-triangulate=]] or in the =q_calibration_stdev= argument to [[file:mrcal-python-api-reference.html#-triangulate][=mrcal.triangulate()=]]. This is usually known from the calibration, and we can request the calibrated value by passing a stdev of -1. See the relevant interface documentation (just-mentioned links) for details. - /Observation-time/ noise. Each triangulation processes observations $\vec q$ of a feature in space. These are noisy, and we propagate that noise. As with calibration-time noise, this noise is assumed to be normally distributed and independent in $x$ and $y$. This is specified in the =--q-observation-stdev= argument to [[file:mrcal-triangulate.html][=mrcal-triangulate=]] or in the =q_observation_stdev= argument to [[file:mrcal-python-api-reference.html#-triangulate][=mrcal.triangulate()=]]. A common source of these pixel observations is a pixel correlation operation where a patch in one image is matched against the second image. Corresponding pixel observations observed this way are correlated: the noise in $\vec q_0$ not independent of the noise in $\vec q_1$. I do not yet know how to estimate this correlation, but the tools are able to ingest and propagate such an estimate: using the =--q-observation-stdev-correlation= commandline option to [[file:mrcal-triangulate.html][=mrcal-triangulate=]] or the =q_observation_stdev_correlation= argument to [[file:mrcal-python-api-reference.html#-triangulate][=mrcal.triangulate()=]]. Note that when thinking about observation-time noise in /dense/ stereo processing, we generally assume that $\vec q_0$ is known perfectly and that there is no correlation at all between the $\vec q_0$ and $\vec q_1$ observations. A bit more thought is needed to figure out how to talk about this noise propagation properly. A big point to note here is that repeated observations of the same feature have independent observation-time noise. So these observation-time errors average out with multiple observations. This is /not/ true of the calibration-time noise however. Using the same calibration to observe a feature multiple times will produce correlated triangulation results. So calibration-time noise is biased, and it is thus essential to make and use low-uncertainty calibrations to minimize this effect. ** Example uncertainties The [[https://github.com/dkogan/mrcal/blob/master/test/test-triangulation-uncertainty.py][=test-triangulation-uncertainty.py=]] test generates synthetic models and triangulation scenarios. It can be used to produce an illustrative diagram: #+begin_src sh test/test-triangulation-uncertainty.py \ --do-sample \ --cache write \ --observed-point -2 0 10 \ --fixed cam0 \ --Nsamples 200 \ --Ncameras 2 \ --q-observation-stdev-correlation 0.5 \ --q-calibration-stdev 0.2 \ --q-observation-stdev 0.2 \ --make-documentation-plots '' #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external test/test-triangulation-uncertainty.py \ --do-sample \ --cache write \ --observed-point -2 0 10 \ --fixed cam0 \ --Nsamples 200 \ --Ncameras 2 \ --q-observation-stdev-correlation 0.5 \ --q-calibration-stdev 0.2 \ --q-observation-stdev 0.2 \ --make-documentation-plots $D/figures/triangulation/sample #+end_src [[file:external/figures/triangulation/sample--ellipses.svg]] Here we have *two* cameras arranged in the usual left/right stereo configuration, looking at *two* points at (-2,10)m and (2,10)m. We generate calibration and observation noise, and display the results in the horizontal plane. The vertical dimension is insignificant here, so it is not shown, even though all the computations are performed in full 3D. For each of the two observed points we display: - The empirical noise samples, and the 1-sigma ellipse they represent - The predicted 1-sigma ellipse for the calibration-time noise - The predicted 1-sigma ellipse for the observation-time noise - The predicted 1-sigma ellipse for the joint noise We can see that the observed and predicted covariances line up nicely. We can also see that the observation-time noise acts primarily in the forward/backward direction, while the calibration-time noise has a much larger lateral effect. This pattern varies greatly depending on the lenses and the calibration and the geometry. As we get further out, the uncertainty in the forward/backward direction dominates for both noise sources, as expected. ** Stabilization In the above plot, the uncertainties are displayed in the coordinate system of the left camera. But, as described on the [[file:uncertainty.org::#propagating-through-projection][projection uncertainty page]], the origin and orientation of each camera's coordinate system is subject to calibration noise: [[file:figures/uncertainty.svg]] So what we usually want to do is to consider the covariance of the triangulation in the coordinates of the camera housing, /not/ the camera coordinate system. We achieve this with "stabilization", computed exactly as described on the [[file:uncertainty.org::#propagating-through-projection][projection uncertainty page]]. We can recompute the triangulation uncertainty in the previous example (same geometry, lens, etc), but with stabilization enabled: #+begin_src sh test/test-triangulation-uncertainty.py \ --do-sample \ --cache write \ --observed-point -2 0 10 \ --fixed cam0 \ --Nsamples 200 \ --Ncameras 2 \ --q-observation-stdev-correlation 0.5 \ --q-calibration-stdev 0.2 \ --q-observation-stdev 0.2 \ --stabilize \ --make-documentation-plots '' #+end_src #+begin_src sh :exports none :eval no-export D=~/projects/mrcal-doc-external test/test-triangulation-uncertainty.py \ --do-sample \ --cache write \ --observed-point -2 0 10 \ --fixed cam0 \ --Nsamples 200 \ --Ncameras 2 \ --q-observation-stdev-correlation 0.5 \ --q-calibration-stdev 0.2 \ --q-observation-stdev 0.2 \ --stabilize \ --make-documentation-plots $D/figures/triangulation/sample-stabilized #+end_src [[file:external/figures/triangulation/sample-stabilized--ellipses.svg]] We can now clearly see that the forward/backward uncertainty was a real effect, /but/ the lateral uncertainty was largely due to the moving camera coordinate system. ** Calibration-time noise produces correlated estimates As mentioned above, the calibration-time noise produces correlations (and thus biases) in the triangulated measurements. Since the [[https://github.com/dkogan/mrcal/blob/master/test/test-triangulation-uncertainty.py][=test-triangulation-uncertainty.py=]] command triangulates two different points, we can directly observe these correlations. Let's look at the magnitude of each element of $\Var {\vec p_{01}}$ where $\vec p_{01}$ is a 6-dimensional vector that contains both the triangulated 3D points: $\vec p_{01} \equiv \left[ \begin{array}{cc} \vec p_0 \\ \vec p_1 \end{array} \right]$. If we had /only/ observation-time noise, $\vec p_0$ and $\vec p_1$ would be independent, and the off-diagonal terms in the covariance matrix would be 0. However, we also have calibration-time noise, so the errors are correlated: [[file:external/figures/triangulation/sample--p0-p1-magnitude-covariance.png]] As before, the exact pattern varies greatly depending on the lenses and the calibration and the geometry, but calibration-time noise always creates these correlations. To reduce these correlations and the biases they cause: lower the uncertainty of your calibrations by [[file:tour-choreography.org][dancing better]] ** Assumptions break down at infinity :PROPERTIES: :CUSTOM_ID: triangulation-problems-as-infinity :END: When propagating noise, mrcal makes the very common assumption that everything is locally linear. This makes things simple, and is right most of the time. However, when running the triangulation routines with near-parallel rays, this assumptions can break down. Let's run another simulation, but observing a more distant point, with more observation-time noise, no calibration-time noise, and gathering more samples: #+begin_src sh test/test-triangulation-uncertainty.py \ --do-sample \ --cache write \ --observed-point -200 0 2000 \ --fixed cam0 \ --Nsamples 2000 \ --Ncameras 2 \ --q-observation-stdev-correlation 0.5 \ --q-observation-stdev 0.4 \ --stabilize \ --make-documentation-plots '' #+end_src #+begin_src sh :exports none :eval no-export # applied this patch to make the plots look nicer # --- a/test/test-triangulation-uncertainty.py # +++ b/test/test-triangulation-uncertainty.py # @@ -961,7 +961,7 @@ if args.make_documentation_plots is not None: # **processoptions) # processoptions = copy.deepcopy(processoptions_base) # - binwidth = np.sqrt(Var_distance) / 4. # + binwidth = np.sqrt(Var_distance) / 1. # equation_distance_observed_gaussian = \ # mrcal.fitted_gaussian_equation(x = distance_sampled, # binwidth = binwidth, D=~/projects/mrcal-doc-external test/test-triangulation-uncertainty.py \ --do-sample \ --cache write \ --observed-point -200 0 2000 \ --fixed cam0 \ --Nsamples 2000 \ --Ncameras 2 \ --q-observation-stdev-correlation 0.5 \ --q-observation-stdev 0.4 \ --stabilize \ --make-documentation-plots $D/figures/triangulation/sample-stabilized-near-parallel #+end_src The range to the observed point: [[file:external/figures/triangulation/sample-stabilized-near-parallel--range-to-p0.svg]] The two points in the synthetic world are at $(\pm 200, 0, 2000)m$ so the true range is ~ $2010m$. We see that the calibration-time noise has little effect here. More importantly, we also see that the predicted distribution of the range to the point is gaussian (as we assume), but the empirical distribution is /not/ gaussian: there's a much more significant tail on the long end. This makes sense. If the observation rays are near-parallel, small errors that make the rays /more/ parallel push the range to infinity; while small errors that bring the rays together have a more modest, finite effect. Similarly, when we look at the distance between our two points we get this distribution: [[file:external/figures/triangulation/sample-stabilized-near-parallel--distance-p1-p0.svg]] We see the same asymmetric non-gaussian distribution. Empirically I observe this distance-between-points distribution become more non-gaussian, faster than the range-to-point distribution. At this time I do not know how much this matters or what to do about it, but these limitations are good to keep in mind. * Applications Visual tracking of an object over time is one application that would benefit from a more complete error model of its input. Repeated noisy observations of a moving object $\vec q_{01}(t)$ can be triangulated into a noisy estimate of the object motion $\vec p(t)$. If for each point in time $t$ we have $\Var \vec p(t)$, we can combine everything into an estimate $\hat p(t)$. The better our covariances, the closer the estimate. The [[file:mrcal-python-api-reference.html#-triangulate][=mrcal.triangulate()=]] routine can be used to compute the triangulations, and to report the full covariances matrices. * Applying these techniques See the [[file:tour-triangulation.org][tour of mrcal]] for an application of these routines to real-world data mrcal-2.4.1/doc/uncertainty.fig000066400000000000000000000051631456301662300164300ustar00rootroot00000000000000#FIG 3.2 Produced by xfig version 3.2.7b Portrait Center Metric Letter 100.00 Single -2 1200 2 0 32 #a0a0a0 6 229 1243 637 1697 2 3 0 4 1 7 50 -1 -1 0.000 0 0 7 0 0 5 386 1273 386 1667 259 1667 259 1273 386 1273 2 3 0 4 1 7 50 -1 -1 0.000 0 0 7 0 0 5 386 1372 607 1273 607 1667 386 1569 386 1372 -6 6 7489 94 8598 1234 2 1 0 1 32 7 40 -1 -1 0.000 0 0 7 1 1 3 1 1 1.00 90.00 120.00 1 1 1.00 90.00 120.00 7682 94 7526 981 8412 1138 2 1 0 1 32 7 40 -1 -1 0.000 0 0 7 1 1 3 1 1 1.00 90.00 120.00 1 1 1.00 90.00 120.00 7496 364 7728 1234 8598 1001 2 1 0 2 0 7 30 -1 -1 0.000 0 0 7 1 1 3 1 1 1.00 90.00 120.00 1 1 1.00 90.00 120.00 7552 256 7631 1153 8527 1074 -6 6 7235 1745 8162 3032 2 1 0 1 32 7 40 -1 -1 0.000 0 0 7 1 1 3 1 1 1.00 90.00 120.00 1 1 1.00 90.00 120.00 7822 1745 7244 2436 7933 3015 2 1 0 1 32 7 40 -1 -1 0.000 0 0 7 1 1 3 1 1 1.00 90.00 120.00 1 1 1.00 90.00 120.00 7525 1886 7292 2756 8162 2989 2 1 0 2 0 7 30 -1 -1 0.000 0 0 7 1 1 3 1 1 1.00 90.00 120.00 1 1 1.00 90.00 120.00 7629 1821 7250 2636 8064 3017 -6 6 135 450 1260 1620 2 1 0 2 0 7 30 -1 -1 0.000 0 0 7 1 1 3 1 1 1.00 90.00 120.00 1 1 1.00 90.00 120.00 320 577 320 1477 1220 1477 2 1 0 1 32 7 40 -1 -1 0.000 0 0 7 1 1 3 1 1 1.00 90.00 120.00 1 1 1.00 90.00 120.00 183 693 339 1580 1226 1423 2 1 0 1 32 7 40 -1 -1 0.000 0 0 7 1 1 3 1 1 1.00 90.00 120.00 1 1 1.00 90.00 120.00 482 485 249 1355 1118 1588 -6 1 3 0 1 0 0 50 -1 20 0.000 1 0.0000 6892 252 45 45 6892 252 6937 252 2 1 0 3 0 7 50 -1 -1 8.000 0 0 7 0 0 2 308 1478 6892 250 2 1 0 1 32 7 40 -1 -1 0.000 0 0 7 1 1 3 1 1 1.00 90.00 120.00 1 1 1.00 90.00 120.00 3242 1190 2935 2036 3780 2344 2 1 0 1 32 7 40 -1 -1 0.000 0 0 7 1 1 3 1 1 1.00 90.00 120.00 1 1 1.00 90.00 120.00 3012 1423 3090 2321 3988 2242 2 1 0 2 0 7 30 -1 -1 0.000 0 0 7 1 1 3 1 1 1.00 90.00 120.00 1 1 1.00 90.00 120.00 3087 1327 3009 2223 3905 2302 4 0 4 50 -1 16 14 0.0000 5 225 2115 540 540 poses and intrinsics\001 4 0 4 50 -1 16 14 0.0000 5 180 1485 3330 1440 The reference\001 4 0 4 50 -1 16 14 0.0000 5 225 1650 3330 1620 coord system is\001 4 0 4 50 -1 16 14 0.0000 5 180 990 3330 1800 uncertain\001 4 0 4 50 -1 16 14 0.0000 5 180 2160 540 360 Estimates of camera\001 4 0 4 50 -1 16 14 0.0000 5 180 1395 540 720 are uncertain\001 4 0 12 50 -1 16 14 0.0000 5 180 1275 360 1980 The camera\001 4 0 12 50 -1 16 14 0.0000 5 180 1305 360 2160 itself is fixed\001 4 2 4 50 -1 16 14 0.0000 5 225 2010 7740 1485 Chessboard poses\001 4 2 4 50 -1 16 14 0.0000 5 180 1395 7740 1665 are uncertain\001 4 2 12 50 -1 16 14 0.0000 5 225 1500 6660 180 a FIXED point\001 4 2 12 50 -1 16 14 0.0000 5 225 1725 6660 0 We're observing\001 mrcal-2.4.1/doc/uncertainty.org000066400000000000000000000413621456301662300164530ustar00rootroot00000000000000#+TITLE: Projection uncertainty #+OPTIONS: toc:t After a calibration has been computed, it is essential to get a sense of how good the calibration is (how closely it represents reality). Traditional (non-mrcal) calibration routines rely on one metric of calibration quality: the residual fit error. This is clearly inadequate because we can always improve this metric by throwing away some input data, and it doesn't make sense that using less data would make a calibration /better/. There are two main sources of error in the calibration solve. Without these errors, the calibration data would fit perfectly, producing a solve residual vector that's exactly $\vec 0$. The two sources of error are: - *Sampling error*. Our computations are based on fitting a model to observations of chessboard corners. These observations aren't perfect, and contain a sample of some noise distribution. We can [[file:formulation.org::#noise-model][characterize this distribution]] and we can analytically predict the effects of that noise - *Model error*. These result when the solver's model of the world is insufficient to describe what is actually happening. When model errors are present, even the best set of parameters aren't able to completely fit the data. Some sources of model errors: motion blur, unsynchronized cameras, chessboard detector errors, too-simple (or unstable) [[file:lensmodels.org][lens models]] or chessboard deformation models, and so on. Since these errors are unmodeled (by definition), we can't analytically predict their effects. Instead we try hard to force these errors to zero, so that we can ignore them. We do this by using rich-enough models and by gathering clean data. To detect model errors we [[file:how-to-calibrate.org::#interpreting-results][look at the solve diagnostics]] and we compute [[file:tour-cross-validation.org][cross-validation diffs]]. Let's do as much as we can analytically: let's gauge the effects of sampling error by computing a /projection uncertainty/ for a model. Since /only/ the sampling error is evaluated: *Any promises of a high-quality low-uncertainty calibration are valid only if the model errors are small*. The method to estimate the projection uncertainty is accessed via the [[file:mrcal-python-api-reference.html#-projection_uncertainty][=mrcal.projection_uncertainty()=]] function. Here the "uncertainty" is the sensitivity to sampling error: the calibration-time pixel noise. This tells us how good a calibration is (we aim for low projection uncertainties), and it can tell us how good the downstream results are as well (by propagating projection uncertainties through the downstream computation). To estimate the projection uncertainty we: 1. Estimate the [[file:formulation.org::#noise-model-inputs][noise in the chessboard observations]] 2. Propagate that noise to the optimal parameters $\vec b^*$ reported by the calibration routine 3. Propagate the uncertainty in calibration parameters $\vec b^*$ through the projection function to get uncertainty in the resulting pixel coordinate $\vec q$ This overall approach is sound, but it implies some limitations: - Once again, model errors are not included in this uncertainty estimate - The choice of lens model affects the reported uncertainties. Lean models (those with few parameters) are less flexible than rich models, and don't fit general lenses as well as rich models do. This stiffness also serves to limit the model's response to noise in their parameters. Thus the above method will report less uncertainty for leaner models than rich models. So, unless we're /sure/ that a given lens follows some particular lens model perfectly, a [[file:splined-models.org][splined lens model]] (i.e. a very rich model) is recommended for truthful uncertainty reporting. Otherwise the reported confidence comes from the model itself, rather than the calibration data. - Currently the uncertainty estimates can be computed only from a vanilla calibration problem: a set of stationary cameras observing a moving calibration object. Other formulations can be used to compute the lens parameters as well (structure-from-motion while also computing the lens models for instance), but at this time the uncertainty computations cannot handle those cases. It can be done, but the current method needs to be extended to do so. * Estimating the input noise We're measuring the sensitivity to the noise in the calibration-time observations. In order to propagate this noise, we need to know what that input noise is. The current approach is described in the [[file:formulation.org::#noise-model][optimization problem formulation]]. * Propagating input noise to the state vector We solved the [[file:formulation.org][least squares problem]], so we have the optimal state vector $\vec b^*$. We apply a perturbation to the observations $\vec q_\mathrm{ref}$, reoptimize this slightly-perturbed least-squares problem, assuming everything is linear, and look at what happens to the optimal state vector $\vec b^*$. We have \[ E \equiv \left \Vert \vec x \right \Vert ^2 \] \[ J \equiv \frac{\partial \vec x}{\partial \vec b} \] At the optimum $E$ is minimized, so \[ \frac{\partial E}{\partial \vec b} \left(\vec b = \vec b^* \right) = 2 J^T \vec x^* = 0 \] We perturb the problem: \[ E( \vec b + \Delta \vec b, \vec q_\mathrm{ref} + \Delta \vec q_\mathrm{ref})) \approx \left \Vert \vec x + \frac{\partial \vec x}{\partial \vec b} \Delta \vec b + \frac{\partial \vec x}{\partial \vec q_\mathrm{ref}} \Delta \vec q_\mathrm{ref} \right \Vert ^2 = \left \Vert \vec x + J \Delta \vec b + \frac{\partial \vec x}{\partial \vec q_\mathrm{ref}} \Delta \vec q_\mathrm{ref} \right \Vert ^2 \] And we reoptimize: \[ \frac{\mathrm{d}E}{\mathrm{d}\Delta \vec b} \approx 2 \left( \vec x + J \Delta \vec b + \frac{\partial \vec x}{\partial \vec q_\mathrm{ref}} {\Delta \vec q_\mathrm{ref}} \right)^T J = 0\] We started at an optimum, so $\vec x = \vec x^*$ and $J^T \vec x^* = 0$, and thus \[ J^T J \Delta \vec b = -J^T \frac{\partial \vec x}{\partial \vec q_\mathrm{ref}} {\Delta \vec q_\mathrm{ref}} \] As defined on the [[file:formulation.org::#noise-model][input noise page]], we have \[ \vec x_\mathrm{observations} = W (\vec q - \vec q_\mathrm{ref}) \] where $W$ is a diagonal matrix of weights. These are the only elements of $\vec x$ that depend on $\vec q_\mathrm{ref}$. Let's assume the non-observation elements of $\vec x$ are at the end, so \[ \frac{\partial \vec x}{\partial \vec q_\mathrm{ref}} = \left[ \begin{array}{cc} - W \\ 0 \end{array} \right] \] and thus \[ J^T J \Delta \vec b = J_\mathrm{observations}^T W \Delta \vec q_\mathrm{ref} \] So if we perturb the input observation vector $q_\mathrm{ref}$ by $\Delta q_\mathrm{ref}$, the resulting effect on the optimal parameters is $\Delta \vec b = M \Delta \vec q_\mathrm{ref}$ where \[ M = \left( J^T J \right)^{-1} J_\mathrm{observations}^T W \] As usual, \[ \mathrm{Var}(\vec b) = M \mathrm{Var}\left(\vec q_\mathrm{ref}\right) M^T \] As stated on the [[file:formulation.org::#noise-model][input noise page]], we're assuming independent noise on all observed pixels, with a standard deviation inversely proportional to the weight: \[ \mathrm{Var}\left( \vec q_\mathrm{ref} \right) = \sigma^2 W^{-2} \] so \begin{aligned} \mathrm{Var}\left(\vec b\right) &= \sigma^2 M W^{-2} M^T \\ &= \sigma^2 \left( J^T J \right)^{-1} J_\mathrm{observations}^T W W^{-2} W J_\mathrm{observations} \left( J^T J \right)^{-1} \\ &= \sigma^2 \left( J^T J \right)^{-1} J_\mathrm{observations}^T J_\mathrm{observations} \left( J^T J \right)^{-1} \end{aligned} If we have no regularization, then $J_\mathrm{observations} = J$ and we can simplify even further: \[\mathrm{Var}\left(\vec b\right) = \sigma^2 \left( J^T J \right)^{-1} \] Note that these expressions do not explicitly depend on $W$, but the weights still have an effect, since they are a part of $J$. So if an observation $i$ were to become less precise, $w_i$ and $x_i$ and $J_i$ would all decrease. And as a result, $\mathrm{Var}\left(\vec b\right)$ would increase, as expected. * Propagating the state vector noise through projection :PROPERTIES: :CUSTOM_ID: propagating-through-projection :END: We now have the variance of the full optimization state $\vec b$, and we want to propagate this through projection to end up with an estimate of uncertainty at any given pixel $\vec q$. The state vector $\vec b$ is a random variable, and we know its distribution. To evaluate the projection uncertainty we want to project a /fixed/ point, to see how this projection $\vec q$ moves around as the chessboards and cameras and intrinsics shift due to the uncertainty in $\vec b$. In other words, we want to project a point defined in the coordinate system of the camera housing, as the origin of the mathematical camera moves around inside this housing: [[file:figures/uncertainty.svg]] How do we operate on points in a fixed coordinate system when all the coordinate systems we have are floating random variables? We use the most fixed thing we have: chessboards. As with the camera housing, the chessboards themselves are fixed in space. We have noisy camera observations of the chessboards that implicitly produce estimates of the fixed transformation $T_{\mathrm{cf}_i}$ for each chessboard $i$. The explicit transformations that we /actually/ have in $\vec b$ all relate to a floating reference coordinate system: $T_\mathrm{cr}$ and $T_\mathrm{rf}$. /That/ coordinate system doesn't have any physical meaning, and it's useless in producing our fixed point. Thus if we project points from a chessboard frame, we would be unaffected by the untethered reference coordinate system. So points in a chessboard frame are somewhat "fixed" for our purposes. To begin, let's focus on just /one/ chessboard frame: frame 0. We want to know the uncertainty at a pixel coordinate $\vec q$, so let's unproject and transform $\vec q$ out to frame 0: \[ \vec p_{\mathrm{frame}_0} = T_{\mathrm{f}_0\mathrm{r}} T_\mathrm{rc} \mathrm{unproject}\left( \vec q \right) \] We then transform and project $\vec p_{\mathrm{frame}_0}$ back to the imager to get $\vec q^+$. But here we take into account the uncertainties of each transformation to get the desired projection uncertainty $\mathrm{Var}\left(\vec q^+ - \vec q\right)$. The full data flow looks like this, with all the perturbed quantities marked with a $+$ superscript. \[ \vec q^+ \xleftarrow{\mathrm{intrinsics}^+} \vec p^+_\mathrm{camera} \xleftarrow{T^+_\mathrm{cr}} \vec p^+_{\mathrm{reference}_0} \xleftarrow{T^+_{\mathrm{rf}_0}} \vec p_{\mathrm{frame}_0} \xleftarrow{T_\mathrm{fr}} \vec p_\mathrm{reference} \xleftarrow{T_\mathrm{rc}} \vec p_\mathrm{camera} \xleftarrow{\mathrm{intrinsics}} \vec q \] This works, but it depends on $\vec p_{\mathrm{frame}_0}$ being "fixed". We can do better. We're observing more than one chessboard, and /in aggregate/ all the chessboard frames can represent an even-more "fixed" frame. Currently we take a very simple approach towards combinining the frames: we compute the mean of all the $\vec p^+_\mathrm{reference}$ estimates from each frame. The full data flow then looks like this: \begin{aligned} & \swarrow & \vec p^+_{\mathrm{reference}_0} & \xleftarrow{T^+_{\mathrm{rf}_0}} & \vec p_{\mathrm{frame}_0} & \nwarrow & \\ \vec q^+ \xleftarrow{\mathrm{intrinsics}^+} \vec p^+_\mathrm{camera} \xleftarrow{T^+_\mathrm{cr}} \vec p^+_\mathrm{reference} & \xleftarrow{\mathrm{mean}} & \vec p^+_{\mathrm{reference}_1} & \xleftarrow{T^+_{\mathrm{rf}_1}} & \vec p_{\mathrm{frame}_1} & \xleftarrow{T_\mathrm{fr}} & \vec p_\mathrm{reference} \xleftarrow{T_\mathrm{rc}} \vec p_\mathrm{camera} \xleftarrow{\mathrm{intrinsics}} \vec q \\ & \nwarrow & \vec p^+_{\mathrm{reference}_2} & \xleftarrow{T^+_{\mathrm{rf}_2}} & \vec p_{\mathrm{frame}_2} & \swarrow \end{aligned} This is better, but there's another issue. What is the transformation relating the original and perturbed reference coordinate systems? \[ T_{\mathrm{r}^+\mathrm{r}} = \mathrm{mean}_i \left( T_{\mathrm{r}^+\mathrm{f}_i} T_{\mathrm{f}_i\mathrm{r}} \right) \] Each transformation $T$ includes a rotation matrix $R$, so the above constructs a new rotation as a mean of multiple rotation matrices, which is aphysical: the resulting matrix is not a valid rotation. In practice, the perturbations are tiny, and this is sufficiently close. Extreme geometries do break it, and this will be fixed in the future. So to summarize, to compute the projection uncertainty at a pixel $\vec q$ we 1. Unproject $\vec q$ and transform to /each/ chessboard coordinate system to obtain $\vec p_{\mathrm{frame}_i}$ 2. Transform and project back to $\vec q^+$, useing the mean of all the $\vec p_{\mathrm{reference}_i}$ and taking into account uncertainties We have $\vec q^+\left(\vec b\right) = \mathrm{project}\left( T_\mathrm{cr} \, \mathrm{mean}_i \left( T_{\mathrm{rf}_i} \vec p_{\mathrm{frame}_i} \right) \right)$ where the transformations $T$ and the intrinsics used in $\mathrm{project}()$ come directly from the optimization state vector $\vec b$. So \[ \mathrm{Var}\left( \vec q \right) = \frac{\partial \vec q^+}{\partial \vec b} \mathrm{Var}\left( \vec b \right) \frac{\partial \vec q^+}{\partial \vec b}^T \] We computed $\mathrm{Var}\left( \vec b \right)$ earlier, and $\frac{\partial \vec q^+}{\partial \vec b}$ comes from the projection expression above. The [[file:mrcal-python-api-reference.html#-projection_uncertainty][=mrcal.projection_uncertainty()=]] function implements this logic. For the special-case of visualizing the uncertainties, call the any of the uncertainty visualization functions: - [[file:mrcal-python-api-reference.html#-show_projection_uncertainty][=mrcal.show_projection_uncertainty()=]]: Visualize the uncertainty in camera projection - [[file:mrcal-python-api-reference.html#-show_projection_uncertainty_vs_distance][=mrcal.show_projection_uncertainty_vs_distance()=]]: Visualize the uncertainty in camera projection along one observation ray or use the [[file:mrcal-show-projection-uncertainty.html][=mrcal-show-projection-uncertainty=]] tool. A sample uncertainty map of the splined model calibration from the [[file:tour-uncertainty.org][tour of mrcal]] looking out to infinity: #+begin_src sh mrcal-show-projection-uncertainty splined.cameramodel --cbmax 1 --unset key #+end_src #+begin_src sh :exports none :eval no-export # THIS IS GENERATED IN tour-uncertainty.org #+end_src [[file:external/figures/uncertainty/uncertainty-splined.png]] * The effect of range :PROPERTIES: :CUSTOM_ID: effect-of-range :END: We glossed over an important detail in the above derivation. Unlike a projection operation, an /unprojection/ is ambiguous: given some camera-coordinate-system point $\vec p$ that projects to a pixel $\vec q$, we have $\vec q = \mathrm{project}\left(k \vec v\right)$ /for all/ $k$. So an unprojection gives you a direction, but no range. The direct implication of this is that we can't ask for an "uncertainty at pixel coordinate $\vec q$". Rather we must ask about "uncertainty at pixel coordinate $\vec q$ looking $x$ meters out". And a surprising consequence of that is that while /projection/ is invariant to scaling ($k \vec v$ projects to the same $\vec q$ for any $k$), the uncertainty of projection is /not/ invariant to this scaling: [[file:figures/projection-scale-invariance.svg]] Let's look at the projection uncertainty at the center of the imager at different ranges for an arbitrary model: #+begin_src sh mrcal-show-projection-uncertainty \ --vs-distance-at center \ --set 'yrange [0:0.1]' \ opencv8.cameramodel #+end_src #+begin_src sh :exports none :eval no-export # THIS IS GENERATED IN tour-effect-of-range.org #+end_src [[file:external/figures/uncertainty/uncertainty-vs-distance-at-center.svg]] So the uncertainty grows without bound as we approach the camera. As we move away, there's a sweet spot where we have maximum confidence. And as we move further out still, we approach some uncertainty asymptote at infinity. Qualitatively this is the figure I see 100% of the time, with the position of the minimum and of the asymptote varying. As we approach the camera, the uncertainty is unbounded because we're looking at the projection of a fixed point into a camera whose position is uncertain. As we get closer to the origin, the noise in the camera position dominates the projection, and the uncertainty shoots to infinity. The "sweet spot" where the uncertainty is lowest sits at the range where we observed the chessboards. The uncertainty we asymptotically approach at infinity is set by the [[file:tour-choreography.org][specifics of the chessboard dance]]. See the [[file:tour-uncertainty.org][tour of mrcal]] for a simulation validating this approach of quantifying uncertainty and for some empirical results. mrcal-2.4.1/doc/versions.org000066400000000000000000000027601456301662300157550ustar00rootroot00000000000000#+TITLE: mrcal releases #+OPTIONS: toc:nil Latest release is mrcal 2.4 (2024/01/22): [[http://mrcal.secretsauce.net/docs-2.4][documentation]] and [[https://github.com/dkogan/mrcal/releases/tag/v2.4][code]] and [[file:news-2.4.org][release and migration notes]] * Releases - mrcal 1.0.1 (2021/02/23): [[http://mrcal.secretsauce.net/docs-1.0][documentation]] and [[https://github.com/dkogan/mrcal/releases/tag/v1.0.1][code]] - mrcal 2.0 (2021/11/07): [[http://mrcal.secretsauce.net/docs-2.0][documentation]] and [[https://github.com/dkogan/mrcal/releases/tag/v2.0][code]] and [[file:news-2.0.org][release and migration notes]] - mrcal 2.1 (2021/11/19): [[http://mrcal.secretsauce.net/docs-2.1][documentation]] and [[https://github.com/dkogan/mrcal/releases/tag/v2.1][code]] and [[file:news-2.1.org][release and migration notes]] - mrcal 2.2 (2022/10/03): [[http://mrcal.secretsauce.net/docs-2.2][documentation]] and [[https://github.com/dkogan/mrcal/releases/tag/v2.2][code]] and [[file:news-2.2.org][release and migration notes]] - mrcal 2.3 (2023/05/04): [[http://mrcal.secretsauce.net/docs-2.3][documentation]] and [[https://github.com/dkogan/mrcal/releases/tag/v2.3][code]] and [[file:news-2.3.org][release and migration notes]] - mrcal 2.4 (2024/01/22): [[http://mrcal.secretsauce.net/docs-2.4][documentation]] and [[https://github.com/dkogan/mrcal/releases/tag/v2.4][code]] and [[file:news-2.4.org][release and migration notes]] * Future See the [[file:roadmap.org][roadmap]] for thoughts about future directions mrcal-2.4.1/elas-genpywrap.py000066400000000000000000000202301456301662300161270ustar00rootroot00000000000000#!/usr/bin/python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Python-wrap the libelas stereo matching ''' import sys import os import numpy as np import numpysane as nps import numpysane_pywrap as npsp docstring_module = '''libelas stereo matching This is the written-in-C Python extension module that wraps the stereo matching routine in libelas. All functions are exported into the mrcal module. So you can call these via mrcal._elas_npsp.fff() or mrcal.fff(). The latter is preferred. ''' m = npsp.module( name = "_elas_npsp", header = '#include "stereo-matching-libelas.h"', docstring = docstring_module ) m.function( "stereo_matching_libelas", r'''Compute a stereo disparity map using libelas SYNOPSIS image0 = mrcal.load_image('left.png', bpp = 8, channels = 1) image1 = mrcal.load_image('right.png', bpp = 8, channels = 1) disparity0, disparity1 = \ mrcal.stereo_matching_libelas(image0, image1) libelas is an external library able to compute disparity maps. This function provides a Python interface to this library. This function supports broadcasting fully. The inputs are given as np.uint8 grayscale images. They don't need to be stored densely, but the strides must match between the two images. The output disparities are returned as np.float32 images. These are stored densely. Both left and right disparities are currently returned. The matcher options are given in keyword arguments. Anything omitted will be taken from the "ROBOTICS" setting, as defined in libelas/src/elas.h. ARGUMENTS - image0: an array of shape (H,W) and dtype np.uint8. This is the left rectified image - image1: an array of shape (H,W) and dtype np.uint8. This is the right rectified image The rest are parameters, with the description coming directly from the comment in libelas/src/elas.h - disparity_min: min disparity - disparity_max: max disparity - support_threshold: max. uniqueness ratio (best vs. second best support match) - support_texture: min texture for support points - candidate_stepsize: step size of regular grid on which support points are matched - incon_window_size: window size of inconsistent support point check - incon_threshold: disparity similarity threshold for support point to be considered consistent - incon_min_support: minimum number of consistent support points - add_corners: add support points at image corners with nearest neighbor disparities - grid_size: size of neighborhood for additional support point extrapolation - beta: image likelihood parameter - gamma: prior constant - sigma: prior sigma - sradius: prior sigma radius - match_texture: min texture for dense matching - lr_threshold: disparity threshold for left/right consistency check - speckle_sim_threshold: similarity threshold for speckle segmentation - speckle_size: maximal size of a speckle (small speckles get removed) - ipol_gap_width: interpolate small gaps (left<->right, top<->bottom) - filter_median: optional median filter (approximated) - filter_adaptive_mean: optional adaptive mean filter (approximated) - postprocess_only_left: saves time by not postprocessing the right image - subsampling: saves time by only computing disparities for each 2nd pixel. For this option D1 and D2 must be passed with size width/2 x height/2 (rounded towards zero) RETURNED VALUE A length-2 tuple containing the left and right disparity images. Each one is a numpy array with the same shape as the input images, but with dtype.np=float32 ''', args_input = ('image0', 'image1'), prototype_input = (('H','W'), ('H','W')), prototype_output = (('H','W'), ('H','W')), # default values are the "ROBOTICS" setting, as defined in elas.h extra_args = (("int", "disparity_min", "0", "i"), ("int", "disparity_max", "255", "i"), ("float", "support_threshold", "0.85", "f"), ("int", "support_texture", "10", "i"), ("int", "candidate_stepsize", "5", "i"), ("int", "incon_window_size", "5", "i"), ("int", "incon_threshold", "5", "i"), ("int", "incon_min_support", "5", "i"), ("bool", "add_corners", "0", "p"), ("int", "grid_size", "20", "i"), ("float", "beta", "0.02", "f"), ("float", "gamma", "3", "f"), ("float", "sigma", "1", "f"), ("float", "sradius", "2", "f"), ("int", "match_texture", "1", "i"), ("int", "lr_threshold", "2", "i"), ("float", "speckle_sim_threshold", "1", "f"), ("int", "speckle_size", "200", "i"), ("int", "ipol_gap_width", "3", "i"), ("bool", "filter_median", "0", "p"), ("bool", "filter_adaptive_mean", "1", "p"), ("bool", "postprocess_only_left", "1", "p"), ("bool", "subsampling", "0", "p" )), Ccode_validate = r'''return CHECK_CONTIGUOUS_AND_SETERROR__output0() && CHECK_CONTIGUOUS_AND_SETERROR__output1() && strides_slice__image0[1] == 1 && strides_slice__image1[1] == 1 && strides_slice__image0[0] == strides_slice__image1[0];''', Ccode_slice_eval = \ { (np.uint8,np.uint8, np.float32, np.float32): r''' mrcal_stereo_matching_libelas( (float*)data_slice__output0, (float*)data_slice__output1, (const uint8_t*)data_slice__image0, (const uint8_t*)data_slice__image1, dims_slice__image0[1], dims_slice__image0[0], strides_slice__image0[0], *disparity_min, *disparity_max, *support_threshold, *support_texture, *candidate_stepsize, *incon_window_size, *incon_threshold, *incon_min_support, *add_corners, *grid_size, *beta, *gamma, *sigma, *sradius, *match_texture, *lr_threshold, *speckle_sim_threshold, *speckle_size, *ipol_gap_width, *filter_median, *filter_adaptive_mean, *postprocess_only_left, *subsampling ); return true; '''}, ) m.write() mrcal-2.4.1/footer.pod000066400000000000000000000006631456301662300146310ustar00rootroot00000000000000=head1 REPOSITORY L =head1 AUTHOR Dima Kogan, C<< >> =head1 LICENSE AND COPYRIGHT Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. Government sponsorship acknowledged. All rights reserved. Licensed under the Apache License, Version 2.0 (the "License"); You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 mrcal-2.4.1/knots_for_splined_models.docstring000066400000000000000000000027101456301662300216250ustar00rootroot00000000000000Return a tuple of locations of x and y spline knots SYNOPSIS print(mrcal.knots_for_splined_models('LENSMODEL_SPLINED_STEREOGRAPHIC_order=2_Nx=4_Ny=3_fov_x_deg=200')) ( array([-3.57526078, -1.19175359, 1.19175359, 3.57526078]), array([-2.38350719, 0. , 2.38350719])) Splined models are defined by the locations of their control points. These are arranged in a grid, the size and density of which is set by the model configuration. This function returns a tuple: - the locations of the knots along the x axis - the locations of the knots along the y axis The values in these arrays correspond to whatever is used to index the splined surface. In the case of LENSMODEL_SPLINED_STEREOGRAPHIC, these are the normalized stereographic projection coordinates. These can be unprojected to observation vectors at the knots: ux,uy = mrcal.knots_for_splined_models('LENSMODEL_SPLINED_STEREOGRAPHIC_order=2_Nx=4_Ny=3_fov_x_deg=200') u = np.ascontiguousarray(nps.mv(nps.cat(*np.meshgrid(ux,uy)), 0, -1)) v = mrcal.unproject_stereographic(u) # v[index_y, index_x] is now an observation vector that will project to this # knot ARGUMENTS - lensmodel: the "LENSMODEL_..." string we're querying. This function only makes sense for "LENSMODEL_SPLINED_..." models RETURNED VALUE A tuple: - An array of shape (Nx,) representing the knot locations along the x axis - An array of shape (Ny,) representing the knot locations along the y axis mrcal-2.4.1/lensmodel_metadata_and_config.docstring000066400000000000000000000017011456301662300225300ustar00rootroot00000000000000Returns a model's meta-information and configuration SYNOPSIS import pprint pprint.pprint(mrcal.lensmodel_metadata_and_config('LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=16_Ny=14_fov_x_deg=200')) {'Nx': 16, 'Ny': 14, 'can_project_behind_camera': 1, 'fov_x_deg': 200, 'has_core': 1, 'has_gradients': 1, 'order': 3} Each lens model has some metadata (inherent properties of a model family) and may have some configuration (parameters that specify details about the model, but aren't subject to optimization). The configuration parameters are embedded in the model string. This function returns a dict containing the metadata and all the configuration values. See the documentation for details: http://mrcal.secretsauce.net/lensmodels.html#representation ARGUMENTS - lensmodel: the "LENSMODEL_..." string we're querying RETURNED VALUE A dict containing all the metadata and configuration properties for that model mrcal-2.4.1/lensmodel_num_params.docstring000066400000000000000000000026301456301662300207450ustar00rootroot00000000000000Get the number of lens parameters for a particular model type SYNOPSIS print(mrcal.lensmodel_num_params('LENSMODEL_OPENCV4')) 8 I support a number of lens models, which have different numbers of parameters. Given a lens model, this returns how many parameters there are. Some models have no configuration, and there's a static mapping between the lensmodel string and the parameter count. Some other models DO have some configuration values inside the model string (LENSMODEL_SPLINED_STEREOGRAPHIC_... for instance), and the number of parameters is computed using the configuration values. The lens model is given as a string such as LENSMODEL_PINHOLE LENSMODEL_OPENCV4 LENSMODEL_CAHVOR LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=16_Ny=12_fov_x_deg=100 The full list can be obtained with mrcal.supported_lensmodels() Note that when optimizing a lens model, some lens parameters may be locked down, resulting in fewer parameters than this function returns. To retrieve the number of parameters used to represent the intrinsics of a camera in an optimization, call mrcal.num_intrinsics_optimization_params(). Or to get the number of parameters used to represent the intrinsics of ALL the cameras in an optimization, call mrcal.num_states_intrinsics() ARGUMENTS - lensmodel: the "LENSMODEL_..." string we're querying RETURNED VALUE An integer number of parameters needed to describe a lens of the given type mrcal-2.4.1/load_image.docstring000066400000000000000000000027561456301662300166330ustar00rootroot00000000000000Load an image from disk into a numpy array SYNOPSIS image = \ mrcal.load_image("scene.jpg", bits_per_pixel = 8, channels = 1) ## image is now a numpy array of shape (height,width) containing the ## pixel data This is a completely uninteresting image-loading routine. It's like any other image-loading routine out there; use any that you like. This exists because cv2 is very slow. This wraps the mrcal_image_TYPE_load() functions. At this time I support only these 3 data formats: - bits_per_pixel = 8, channels = 1: 8-bit grayscale data - bits_per_pixel = 16, channels = 1: 16-bit grayscale data - bits_per_pixel = 24, channels = 3: BGR color data With the exception of 16-bit grayscale data, the load function will convert the input image to the requested format. At this time, loading 16-bit grayscale data requires that the input image matches that format. If the bits_per_pixel, channels arguments are omitted or set to <= 0, we will load the image in whatever format it appears on disk. ARGUMENTS - filename: the image on disk to load - bits_per_pixel: optional integer describing the requested bit depth. Must be 8 or 16 or 24. If omitted or <= 0, we use the bit depth of the image on disk - channels: optional integer describing the number of channels in the image. Integer. Must be 1 or 3. If omitted or <= 0, we use the channel count of the image on disk RETURNED VALUE A numpy array containing the pixel data mrcal-2.4.1/measurement_index_boards.docstring000066400000000000000000000055041456301662300216120ustar00rootroot00000000000000Return the measurement index of the start of a given board observation SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() x = mrcal.optimizer_callback(**optimization_inputs)[1] Nmeas = mrcal.num_measurements_boards ( **optimization_inputs) i_meas0 = mrcal.measurement_index_boards(0, **optimization_inputs) x_boards_all = x[i_meas0:i_meas0+Nmeas] The optimization algorithm tries to minimize the norm of a "measurements" vector x. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. The mrcal.measurement_index_...() functions report where particular items end up in the vector of measurements. THIS function reports the index in the measurement vector where a particular board observation begins. When solving calibration problems, most if not all of the measurements will come from these observations. These are stored contiguously. In order to determine the layout, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - i_observation_board: an integer indicating which board observation we're querying - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_frames do_optimize_calobject_warp do_apply_regularization optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed Nobservations_board Nobservations_point calibration_object_width_n calibration_object_height_n optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting the variable index in the measurements vector where the measurements for this particular board observation start mrcal-2.4.1/measurement_index_points.docstring000066400000000000000000000055161456301662300216570ustar00rootroot00000000000000Return the measurement index of the start of a given point observation SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() x = mrcal.optimizer_callback(**optimization_inputs)[1] Nmeas = mrcal.num_measurements_points( **optimization_inputs) i_meas0 = mrcal.measurement_index_points(0, **optimization_inputs) x_points_all = x[i_meas0:i_meas0+Nmeas] The optimization algorithm tries to minimize the norm of a "measurements" vector x. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. The mrcal.measurement_index_...() functions report where particular items end up in the vector of measurements. THIS function reports the index in the measurement vector where a particular point observation begins. When solving structure-from-motion problems, most if not all of the measurements will come from these observations. These are stored contiguously. In order to determine the layout, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - i_observation_point: an integer indicating which point observation we're querying - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_frames do_optimize_calobject_warp do_apply_regularization optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed Nobservations_board Nobservations_point calibration_object_width_n calibration_object_height_n optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting the variable index in the measurements vector where the measurements for this particular point observation start mrcal-2.4.1/measurement_index_regularization.docstring000066400000000000000000000053551456301662300234030ustar00rootroot00000000000000Return the index of the start of the regularization measurements SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() x = mrcal.optimizer_callback(**optimization_inputs)[1] Nmeas = mrcal.num_measurements_regularization( **optimization_inputs) i_meas0 = mrcal.measurement_index_regularization(**optimization_inputs) x_regularization = x[i_meas0:i_meas0+Nmeas] The optimization algorithm tries to minimize the norm of a "measurements" vector x. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. The mrcal.measurement_index_...() functions report where particular items end up in the vector of measurements. THIS function reports the index in the measurement vector where the regularization terms begin. These don't model physical effects, but guide the solver away from obviously-incorrect solutions, and resolve ambiguities. This helps the solver converge to the right solution, quickly. In order to determine the layout, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_frames do_optimize_calobject_warp do_apply_regularization optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed Nobservations_board Nobservations_point calibration_object_width_n calibration_object_height_n optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting where in the measurement vector the regularization terms start mrcal-2.4.1/minimath/000077500000000000000000000000001456301662300144305ustar00rootroot00000000000000mrcal-2.4.1/minimath/LICENSE000066400000000000000000000002061456301662300154330ustar00rootroot00000000000000Copyright 2011 Oblong Industries This library is distributed under the terms of the GNU LGPL .mrcal-2.4.1/minimath/README000066400000000000000000000040541456301662300153130ustar00rootroot00000000000000This is a copy of libminimath 0.7 from https://github.com/dkogan/libminimath I also added an extra minimath-extra.h. This will be added to libminimath eventually This is a very simple C library to implement basic linear algebra routines for small matrices. Libraries such as BLAS are highly optimized for large matrices, but their overhead often makes them suboptimal for very small matrices. By contrast, this library has very simple, predefined functions for the various routines it supports. These functions are NOT at all optimized at the source level, but they are simple, and the C compiler can generally do a very good job optimizing these. All the routines are in a header, so the compiler is free to aggressively inline the code, as it sees fit. Supported are various ways to compute norms of vectors, multiply matrices and solve linear systems. The suffix of every function determines where its output goes. The ..._vout functions store their output in a new vector, generally given as the last argument. The ..._vaccum functions are the same except the output is added to the data already in that vector instead of overwriting. With neither of these suffixes, the functions store their output into the vector pointed to by the first argument. Many functions have ...._scaled flavors that can apply a scale factor to the given operation. The scale factor is in the last argument. Matrices are stored row-first. Dimensions are given col-first. Vectors are treated as row vectors. So for instance, a '3x2' matrix M stored in double[] {1.0, 2.0, 3.0, 4.0, 5.0, 6.0} implies [ 1.0 2.0 ] M = [ 3.0 4.0 ] [ 5.0 6.0 ] a 3-vector v = [ 11.0 12.0 13.0 ] can be multiplied by M to compute v*M using the mul_vec3_gen32_... family of functions. Example: #include #include int main(void) { double M[] = {1.0, 2.0, 3.0, 4.0, 5.0, 6.0}; double v[] = {11.0, 12.0, 13.0}; mul_vec3_gen32(v, M); printf("%f %f\n", v[0], v[1]); return 0; } C99-compliant compiler required. THIS LIBRARY IS UNDER DEVELOPMENT AND THE APIs MAY CHANGE AT ANY TIME mrcal-2.4.1/minimath/minimath-extra.h000066400000000000000000004676561456301662300175600ustar00rootroot00000000000000#pragma once // Extra functions I'm using in mrcal. I'm going to replace this whole library // eventually, to make things nicer. These new functions will be a part of the // replacement, and I'm not going to be thorough and I'm not going to add tests // until I do that. // Upper triangle is stored, in the usual row-major order. __attribute__((unused)) static int index_sym66(int i, int j) { // In the top-right triangle I have i<=j, and // index = N*i+j - sum(i, i=0..i) // = N*i+j - (i+1)*i/2 // = (N*2 - i - 1)*i/2 + j const int N=6; if(i<=j) return (N*2-i-1)*i/2 + j; else return (N*2-j-1)*j/2 + i; } __attribute__((unused)) static int index_sym66_assume_upper(int i, int j) { const int N=6; return (N*2-i-1)*i/2 + j; } __attribute__((unused)) static void mul_gen33_gen33insym66(// output double* restrict P, int P_strideelems0, int P_strideelems1, // input const double* A, int A_strideelems0, int A_strideelems1, const double* Bsym66, int B_i0, int B_j0, const double scale) { for(int iout=0; iout<3; iout++) for(int jout=0; jout<3; jout++) { P[iout*P_strideelems0 + jout*P_strideelems1] = 0; for(int k=0; k<3; k++) { P[iout*P_strideelems0 + jout*P_strideelems1] += A[iout*A_strideelems0 + k*A_strideelems1] * Bsym66[index_sym66(k+B_i0, jout+B_j0)]; } P[iout*P_strideelems0 + jout*P_strideelems1] *= scale; } } // Assumes the output is symmetric, and only computes the upper triangle __attribute__((unused)) static void mul_gen33_gen33_into33insym66_accum(// output double* restrict Psym66, int P_i0, int P_j0, // input const double* A, int A_strideelems0, int A_strideelems1, const double* B, int B_strideelems0, int B_strideelems1, const double scale) { for(int iout=0; iout<3; iout++) for(int jout=0; jout<3; jout++) { if(jout + P_j0 < iout + P_i0) { // Wrong triangle. Set it up to look at the right triangle // during the next loop interation jout = iout + P_i0 - P_j0 - 1; continue; } for(int k=0; k<3; k++) { Psym66[index_sym66_assume_upper(iout+P_i0, jout+P_j0)] += A[iout*A_strideelems0 + k *A_strideelems1] * B[k *B_strideelems0 + jout*B_strideelems1] * scale; } } } __attribute__((unused)) static void set_gen33_from_gen33insym66(// output double* restrict P, int P_strideelems0, int P_strideelems1, // input const double* Msym66, int M_i0, int M_j0, const double scale) { for(int iout=0; iout<3; iout++) for(int jout=0; jout<3; jout++) P[iout*P_strideelems0 + jout*P_strideelems1] = Msym66[index_sym66(iout+M_i0, jout+M_j0)] * scale; } // Assumes the output is symmetric, and only computes the upper triangle __attribute__((unused)) static void set_33insym66_from_gen33_accum(// output double* restrict Psym66, int P_i0, int P_j0, // input const double* M, int M_strideelems0, int M_strideelems1, const double scale) { for(int iout=0; iout<3; iout++) for(int jout=0; jout<3; jout++) { if(jout + P_j0 < iout + P_i0) { // Wrong triangle. Set it up to look at the right triangle // during the next loop interation jout = iout + P_i0 - P_j0 - 1; continue; } Psym66[index_sym66_assume_upper(iout+P_i0, jout+P_j0)] += M[iout*M_strideelems0 + jout*M_strideelems1] * scale; } } // This is completely unreasonable. I'm almost certainly going to replace it __attribute__((unused)) static double cofactors_sym6(const double* restrict m, double* restrict c) { /* Just like in libminimath; adding 6x6 version. I use the maxima result verbatim, except: - mNNN -> m[NNN] - XXX^2 -> XXX*XXX maxima session: (%i1) display2d : false; (%i2) sym6 : matrix([m0,m1, m2, m3, m4, m5 ], [m1,m6, m7, m8, m9, m10], [m2,m7, m11, m12,m13, m14], [m3,m8, m12, m15,m16, m17], [m4,m9, m13, m16,m18, m19], [m5,m10,m14, m17,m19, m20]); (%i10) num( ev(invert(sym6),detout) ); (%o10) matrix([(-m7*((-m12*((-m16*(m20*m9-m10*m19))+m17*(m19*m9-m10*m18) +(m18*m20-m19^2)*m8)) +m13*((-m15*(m20*m9-m10*m19))+m17*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m8) -m14*((-m15*(m19*m9-m10*m18))+m16*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m8) +(m15*(m18*m20-m19^2)-m16*(m16*m20-m17*m19) +m17*(m16*m19-m17*m18)) *m7)) +m8*((-m11*((-m16*(m20*m9-m10*m19))+m17*(m19*m9-m10*m18) +(m18*m20-m19^2)*m8)) +m13*((-m12*(m20*m9-m10*m19))+m17*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m8) -m14*((-m12*(m19*m9-m10*m18))+m16*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m8) +(m12*(m18*m20-m19^2)-m16*(m13*m20-m14*m19) +m17*(m13*m19-m14*m18)) *m7) -m9*((-m11*((-m15*(m20*m9-m10*m19))+m17*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m8)) +m12*((-m12*(m20*m9-m10*m19))+m17*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m8) -m14*((-m12*(m17*m9-m10*m16))+m15*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m8) +(m12*(m16*m20-m17*m19)-m15*(m13*m20-m14*m19) +m17*(m13*m17-m14*m16)) *m7) +m10*((-m11*((-m15*(m19*m9-m10*m18))+m16*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m8)) +m12*((-m12*(m19*m9-m10*m18))+m16*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m8) -m13*((-m12*(m17*m9-m10*m16))+m15*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m8) +(m12*(m16*m19-m17*m18)-m15*(m13*m19-m14*m18) +m16*(m13*m17-m14*m16)) *m7) +(m11*(m15*(m18*m20-m19^2)-m16*(m16*m20-m17*m19) +m17*(m16*m19-m17*m18)) -m12*(m12*(m18*m20-m19^2)-m16*(m13*m20-m14*m19) +m17*(m13*m19-m14*m18)) +m13*(m12*(m16*m20-m17*m19)-m15*(m13*m20-m14*m19) +m17*(m13*m17-m14*m16)) -m14*(m12*(m16*m19-m17*m18)-m15*(m13*m19-m14*m18) +m16*(m13*m17-m14*m16))) *m6, m2*((-m12*((-m16*(m20*m9-m10*m19))+m17*(m19*m9-m10*m18) +(m18*m20-m19^2)*m8)) +m13*((-m15*(m20*m9-m10*m19))+m17*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m8) -m14*((-m15*(m19*m9-m10*m18))+m16*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m8) +(m15*(m18*m20-m19^2)-m16*(m16*m20-m17*m19) +m17*(m16*m19-m17*m18)) *m7) -m3*((-m11*((-m16*(m20*m9-m10*m19))+m17*(m19*m9-m10*m18) +(m18*m20-m19^2)*m8)) +m13*((-m12*(m20*m9-m10*m19))+m17*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m8) -m14*((-m12*(m19*m9-m10*m18))+m16*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m8) +(m12*(m18*m20-m19^2)-m16*(m13*m20-m14*m19) +m17*(m13*m19-m14*m18)) *m7) +m4*((-m11*((-m15*(m20*m9-m10*m19))+m17*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m8)) +m12*((-m12*(m20*m9-m10*m19))+m17*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m8) -m14*((-m12*(m17*m9-m10*m16))+m15*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m8) +(m12*(m16*m20-m17*m19)-m15*(m13*m20-m14*m19) +m17*(m13*m17-m14*m16)) *m7) -m5*((-m11*((-m15*(m19*m9-m10*m18))+m16*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m8)) +m12*((-m12*(m19*m9-m10*m18))+m16*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m8) -m13*((-m12*(m17*m9-m10*m16))+m15*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m8) +(m12*(m16*m19-m17*m18)-m15*(m13*m19-m14*m18) +m16*(m13*m17-m14*m16)) *m7) -m1*(m11*(m15*(m18*m20-m19^2)-m16*(m16*m20-m17*m19) +m17*(m16*m19-m17*m18)) -m12*(m12*(m18*m20-m19^2)-m16*(m13*m20-m14*m19) +m17*(m13*m19-m14*m18)) +m13*(m12*(m16*m20-m17*m19)-m15*(m13*m20-m14*m19) +m17*(m13*m17-m14*m16)) -m14*(m12*(m16*m19-m17*m18)-m15*(m13*m19-m14*m18) +m16*(m13*m17-m14*m16))), (-m2*((-m8*((-m16*(m20*m9-m10*m19))+m17*(m19*m9-m10*m18) +(m18*m20-m19^2)*m8)) +m9*((-m15*(m20*m9-m10*m19))+m17*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m8) -m10*((-m15*(m19*m9-m10*m18))+m16*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m8) +(m15*(m18*m20-m19^2)-m16*(m16*m20-m17*m19) +m17*(m16*m19-m17*m18)) *m6)) +m3*((-m7*((-m16*(m20*m9-m10*m19))+m17*(m19*m9-m10*m18) +(m18*m20-m19^2)*m8)) +m9*((-m12*(m20*m9-m10*m19))+m17*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m8) -m10*((-m12*(m19*m9-m10*m18))+m16*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m8) +(m12*(m18*m20-m19^2)-m16*(m13*m20-m14*m19) +m17*(m13*m19-m14*m18)) *m6) -m4*((-m7*((-m15*(m20*m9-m10*m19))+m17*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m8)) +m8*((-m12*(m20*m9-m10*m19))+m17*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m8) -m10*((-m12*(m17*m9-m10*m16))+m15*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m8) +(m12*(m16*m20-m17*m19)-m15*(m13*m20-m14*m19) +m17*(m13*m17-m14*m16)) *m6) +m5*((-m7*((-m15*(m19*m9-m10*m18))+m16*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m8)) +m8*((-m12*(m19*m9-m10*m18))+m16*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m8) -m9*((-m12*(m17*m9-m10*m16))+m15*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m8) +(m12*(m16*m19-m17*m18)-m15*(m13*m19-m14*m18) +m16*(m13*m17-m14*m16)) *m6) +m1*((m12*(m16*m20-m17*m19)-m15*(m13*m20-m14*m19) +m17*(m13*m17-m14*m16)) *m9 -(m12*(m18*m20-m19^2)-m16*(m13*m20-m14*m19) +m17*(m13*m19-m14*m18)) *m8 +(m15*(m18*m20-m19^2)-m16*(m16*m20-m17*m19) +m17*(m16*m19-m17*m18)) *m7 -m10*(m12*(m16*m19-m17*m18)-m15*(m13*m19-m14*m18) +m16*(m13*m17-m14*m16))), m2*((-m8*((-m13*(m20*m9-m10*m19))+m14*(m19*m9-m10*m18) +(m18*m20-m19^2)*m7)) +m9*((-m12*(m20*m9-m10*m19))+m14*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m7) -m10*((-m12*(m19*m9-m10*m18))+m13*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m7) +(m12*(m18*m20-m19^2)-m13*(m16*m20-m17*m19) +m14*(m16*m19-m17*m18)) *m6) -m3*((-m7*((-m13*(m20*m9-m10*m19))+m14*(m19*m9-m10*m18) +(m18*m20-m19^2)*m7)) +m9*((-m11*(m20*m9-m10*m19))+m14*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m7) -m10*((-m11*(m19*m9-m10*m18))+m13*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m7) +(m11*(m18*m20-m19^2)-m13*(m13*m20-m14*m19) +m14*(m13*m19-m14*m18)) *m6) +m4*((-m7*((-m12*(m20*m9-m10*m19))+m14*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m7)) +m8*((-m11*(m20*m9-m10*m19))+m14*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m7) -m10*((-m11*(m17*m9-m10*m16))+m12*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m7) +(m11*(m16*m20-m17*m19)-m12*(m13*m20-m14*m19) +m14*(m13*m17-m14*m16)) *m6) -m5*((-m7*((-m12*(m19*m9-m10*m18))+m13*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m7)) +m8*((-m11*(m19*m9-m10*m18))+m13*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m7) -m9*((-m11*(m17*m9-m10*m16))+m12*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m7) +(m11*(m16*m19-m17*m18)-m12*(m13*m19-m14*m18) +m13*(m13*m17-m14*m16)) *m6) -m1*((m11*(m16*m20-m17*m19)-m12*(m13*m20-m14*m19) +m14*(m13*m17-m14*m16)) *m9 -(m11*(m18*m20-m19^2)-m13*(m13*m20-m14*m19) +m14*(m13*m19-m14*m18)) *m8 +(m12*(m18*m20-m19^2)-m13*(m16*m20-m17*m19) +m14*(m16*m19-m17*m18)) *m7 -m10*(m11*(m16*m19-m17*m18)-m12*(m13*m19-m14*m18) +m13*(m13*m17-m14*m16))), (-m2*(((-m12*(m20*m8-m10*m17))+m14*(m17*m8-m10*m15) +(m15*m20-m17^2)*m7) *m9 -m8*((-m13*(m20*m8-m10*m17))+m14*(m19*m8-m10*m16) +(m16*m20-m17*m19)*m7) -m10*((-m12*(m19*m8-m10*m16))+m13*(m17*m8-m10*m15) +(m15*m19-m16*m17)*m7) +(m12*(m16*m20-m17*m19)-m13*(m15*m20-m17^2) +m14*(m15*m19-m16*m17)) *m6)) +m3*(((-m11*(m20*m8-m10*m17))+m14*(m14*m8-m10*m12) +(m12*m20-m14*m17)*m7) *m9 -m7*((-m13*(m20*m8-m10*m17))+m14*(m19*m8-m10*m16) +(m16*m20-m17*m19)*m7) -m10*((-m11*(m19*m8-m10*m16))+m13*(m14*m8-m10*m12) +(m12*m19-m14*m16)*m7) +(m11*(m16*m20-m17*m19)-m13*(m12*m20-m14*m17) +m14*(m12*m19-m14*m16)) *m6) +m5*((-((-m11*(m17*m8-m10*m15))+m12*(m14*m8-m10*m12) +(m12*m17-m14*m15)*m7) *m9) -m7*((-m12*(m19*m8-m10*m16))+m13*(m17*m8-m10*m15) +(m15*m19-m16*m17)*m7) +m8*((-m11*(m19*m8-m10*m16))+m13*(m14*m8-m10*m12) +(m12*m19-m14*m16)*m7) +(m11*(m15*m19-m16*m17)-m12*(m12*m19-m14*m16) +m13*(m12*m17-m14*m15)) *m6) +m1*((m11*(m15*m20-m17^2)-m12*(m12*m20-m14*m17) +m14*(m12*m17-m14*m15)) *m9 -(m11*(m16*m20-m17*m19)-m13*(m12*m20-m14*m17) +m14*(m12*m19-m14*m16)) *m8 +(m12*(m16*m20-m17*m19)-m13*(m15*m20-m17^2) +m14*(m15*m19-m16*m17)) *m7 -m10*(m11*(m15*m19-m16*m17)-m12*(m12*m19-m14*m16) +m13*(m12*m17-m14*m15))) -m4*((-m7*((-m12*(m20*m8-m10*m17))+m14*(m17*m8-m10*m15) +(m15*m20-m17^2)*m7)) +m8*((-m11*(m20*m8-m10*m17))+m14*(m14*m8-m10*m12) +(m12*m20-m14*m17)*m7) -m10*((-m11*(m17*m8-m10*m15))+m12*(m14*m8-m10*m12) +(m12*m17-m14*m15)*m7) +(m11*(m15*m20-m17^2)-m12*(m12*m20-m14*m17) +m14*(m12*m17-m14*m15)) *m6), m2*((-m8*((-m13*(m19*m8-m17*m9))+m14*(m18*m8-m16*m9) +(m16*m19-m17*m18)*m7)) +m9*((-m12*(m19*m8-m17*m9))+m14*(m16*m8-m15*m9) +(m15*m19-m16*m17)*m7) -m10*((-m12*(m18*m8-m16*m9))+m13*(m16*m8-m15*m9) +(m15*m18-m16^2)*m7) +(m12*(m16*m19-m17*m18)-m13*(m15*m19-m16*m17) +m14*(m15*m18-m16^2)) *m6) -m3*((-m7*((-m13*(m19*m8-m17*m9))+m14*(m18*m8-m16*m9) +(m16*m19-m17*m18)*m7)) +m9*((-m11*(m19*m8-m17*m9))+m14*(m13*m8-m12*m9) +(m12*m19-m13*m17)*m7) -m10*((-m11*(m18*m8-m16*m9))+m13*(m13*m8-m12*m9) +(m12*m18-m13*m16)*m7) +(m11*(m16*m19-m17*m18)-m13*(m12*m19-m13*m17) +m14*(m12*m18-m13*m16)) *m6) +m4*((-m7*((-m12*(m19*m8-m17*m9))+m14*(m16*m8-m15*m9) +(m15*m19-m16*m17)*m7)) +m8*((-m11*(m19*m8-m17*m9))+m14*(m13*m8-m12*m9) +(m12*m19-m13*m17)*m7) -m10*((-m11*(m16*m8-m15*m9))+m12*(m13*m8-m12*m9) +(m12*m16-m13*m15)*m7) +(m11*(m15*m19-m16*m17)-m12*(m12*m19-m13*m17) +m14*(m12*m16-m13*m15)) *m6) -m5*((-m7*((-m12*(m18*m8-m16*m9))+m13*(m16*m8-m15*m9) +(m15*m18-m16^2)*m7)) +m8*((-m11*(m18*m8-m16*m9))+m13*(m13*m8-m12*m9) +(m12*m18-m13*m16)*m7) -m9*((-m11*(m16*m8-m15*m9))+m12*(m13*m8-m12*m9) +(m12*m16-m13*m15)*m7) +(m11*(m15*m18-m16^2)-m12*(m12*m18-m13*m16) +m13*(m12*m16-m13*m15)) *m6) -m1*((m11*(m15*m19-m16*m17)-m12*(m12*m19-m13*m17) +m14*(m12*m16-m13*m15)) *m9 -(m11*(m16*m19-m17*m18)-m13*(m12*m19-m13*m17) +m14*(m12*m18-m13*m16)) *m8 +(m12*(m16*m19-m17*m18)-m13*(m15*m19-m16*m17) +m14*(m15*m18-m16^2)) *m7 -m10*(m11*(m15*m18-m16^2)-m12*(m12*m18-m13*m16) +m13*(m12*m16-m13*m15)))], [((-m11*((-m15*(m20*m4-m19*m5))+m17*(m17*m4-m16*m5) +(m16*m20-m17*m19)*m3)) +m12*((-m12*(m20*m4-m19*m5))+m17*(m14*m4-m13*m5) +(m13*m20-m14*m19)*m3) -m14*((-m12*(m17*m4-m16*m5))+m15*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m3) +m2*(m12*(m16*m20-m17*m19)-m15*(m13*m20-m14*m19) +m17*(m13*m17-m14*m16))) *m9 -((-m11*((-m16*(m20*m4-m19*m5))+m17*(m19*m4-m18*m5) +(m18*m20-m19^2)*m3)) +m13*((-m12*(m20*m4-m19*m5))+m17*(m14*m4-m13*m5) +(m13*m20-m14*m19)*m3) -m14*((-m12*(m19*m4-m18*m5))+m16*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m3) +m2*(m12*(m18*m20-m19^2)-m16*(m13*m20-m14*m19) +m17*(m13*m19-m14*m18))) *m8 +((-m12*((-m16*(m20*m4-m19*m5))+m17*(m19*m4-m18*m5) +(m18*m20-m19^2)*m3)) +m13*((-m15*(m20*m4-m19*m5))+m17*(m17*m4-m16*m5) +(m16*m20-m17*m19)*m3) -m14*((-m15*(m19*m4-m18*m5))+m16*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m3) +m2*(m15*(m18*m20-m19^2)-m16*(m16*m20-m17*m19) +m17*(m16*m19-m17*m18))) *m7 -m10*((-m11*((-m15*(m19*m4-m18*m5))+m16*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m3)) +m12*((-m12*(m19*m4-m18*m5))+m16*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m3) -m13*((-m12*(m17*m4-m16*m5))+m15*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m3) +(m12*(m16*m19-m17*m18)-m15*(m13*m19-m14*m18) +m16*(m13*m17-m14*m16)) *m2) -m1*(m11*(m15*(m18*m20-m19^2)-m16*(m16*m20-m17*m19) +m17*(m16*m19-m17*m18)) -m12*(m12*(m18*m20-m19^2)-m16*(m13*m20-m14*m19) +m17*(m13*m19-m14*m18)) +m13*(m12*(m16*m20-m17*m19)-m15*(m13*m20-m14*m19) +m17*(m13*m17-m14*m16)) -m14*(m12*(m16*m19-m17*m18)-m15*(m13*m19-m14*m18) +m16*(m13*m17-m14*m16))), (-m2*((-m12*((-m16*(m20*m4-m19*m5))+m17*(m19*m4-m18*m5) +(m18*m20-m19^2)*m3)) +m13*((-m15*(m20*m4-m19*m5))+m17*(m17*m4-m16*m5) +(m16*m20-m17*m19)*m3) -m14*((-m15*(m19*m4-m18*m5))+m16*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m3) +m2*(m15*(m18*m20-m19^2)-m16*(m16*m20-m17*m19) +m17*(m16*m19-m17*m18)))) +m3*((-m11*((-m16*(m20*m4-m19*m5))+m17*(m19*m4-m18*m5) +(m18*m20-m19^2)*m3)) +m13*((-m12*(m20*m4-m19*m5))+m17*(m14*m4-m13*m5) +(m13*m20-m14*m19)*m3) -m14*((-m12*(m19*m4-m18*m5))+m16*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m3) +m2*(m12*(m18*m20-m19^2)-m16*(m13*m20-m14*m19) +m17*(m13*m19-m14*m18))) -m4*((-m11*((-m15*(m20*m4-m19*m5))+m17*(m17*m4-m16*m5) +(m16*m20-m17*m19)*m3)) +m12*((-m12*(m20*m4-m19*m5))+m17*(m14*m4-m13*m5) +(m13*m20-m14*m19)*m3) -m14*((-m12*(m17*m4-m16*m5))+m15*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m3) +m2*(m12*(m16*m20-m17*m19)-m15*(m13*m20-m14*m19) +m17*(m13*m17-m14*m16))) +m5*((-m11*((-m15*(m19*m4-m18*m5))+m16*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m3)) +m12*((-m12*(m19*m4-m18*m5))+m16*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m3) -m13*((-m12*(m17*m4-m16*m5))+m15*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m3) +(m12*(m16*m19-m17*m18)-m15*(m13*m19-m14*m18) +m16*(m13*m17-m14*m16)) *m2) +m0*(m11*(m15*(m18*m20-m19^2)-m16*(m16*m20-m17*m19) +m17*(m16*m19-m17*m18)) -m12*(m12*(m18*m20-m19^2)-m16*(m13*m20-m14*m19) +m17*(m13*m19-m14*m18)) +m13*(m12*(m16*m20-m17*m19)-m15*(m13*m20-m14*m19) +m17*(m13*m17-m14*m16)) -m14*(m12*(m16*m19-m17*m18)-m15*(m13*m19-m14*m18) +m16*(m13*m17-m14*m16))), m2*(((-m15*(m20*m4-m19*m5))+m17*(m17*m4-m16*m5) +(m16*m20-m17*m19)*m3) *m9 -((-m16*(m20*m4-m19*m5))+m17*(m19*m4-m18*m5) +(m18*m20-m19^2)*m3) *m8 -m10*((-m15*(m19*m4-m18*m5))+m16*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m3) +m1*(m15*(m18*m20-m19^2)-m16*(m16*m20-m17*m19) +m17*(m16*m19-m17*m18))) -m3*(((-m12*(m20*m4-m19*m5))+m17*(m14*m4-m13*m5) +(m13*m20-m14*m19)*m3) *m9 -((-m16*(m20*m4-m19*m5))+m17*(m19*m4-m18*m5) +(m18*m20-m19^2)*m3) *m7 -m10*((-m12*(m19*m4-m18*m5))+m16*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m3) +m1*(m12*(m18*m20-m19^2)-m16*(m13*m20-m14*m19) +m17*(m13*m19-m14*m18))) -m5*((-((-m12*(m17*m4-m16*m5))+m15*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m3) *m9) +((-m12*(m19*m4-m18*m5))+m16*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m3) *m8 -((-m15*(m19*m4-m18*m5))+m16*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m3) *m7 +m1*(m12*(m16*m19-m17*m18)-m15*(m13*m19-m14*m18) +m16*(m13*m17-m14*m16))) -m0*((m12*(m16*m20-m17*m19)-m15*(m13*m20-m14*m19) +m17*(m13*m17-m14*m16)) *m9 -(m12*(m18*m20-m19^2)-m16*(m13*m20-m14*m19) +m17*(m13*m19-m14*m18)) *m8 +(m15*(m18*m20-m19^2)-m16*(m16*m20-m17*m19) +m17*(m16*m19-m17*m18)) *m7 -m10*(m12*(m16*m19-m17*m18)-m15*(m13*m19-m14*m18) +m16*(m13*m17-m14*m16))) +m4*(((-m12*(m20*m4-m19*m5))+m17*(m14*m4-m13*m5) +(m13*m20-m14*m19)*m3) *m8 -((-m15*(m20*m4-m19*m5))+m17*(m17*m4-m16*m5) +(m16*m20-m17*m19)*m3) *m7 -m10*((-m12*(m17*m4-m16*m5))+m15*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m3) +m1*(m12*(m16*m20-m17*m19)-m15*(m13*m20-m14*m19) +m17*(m13*m17-m14*m16))), (-m2*(((-m12*(m20*m4-m19*m5))+m14*(m17*m4-m16*m5) +m2*(m16*m20-m17*m19)) *m9 -((-m13*(m20*m4-m19*m5))+m14*(m19*m4-m18*m5) +m2*(m18*m20-m19^2)) *m8 -m10*((-m12*(m19*m4-m18*m5))+m13*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m2) +m1*(m12*(m18*m20-m19^2)-m13*(m16*m20-m17*m19) +m14*(m16*m19-m17*m18)))) +m3*(((-m11*(m20*m4-m19*m5))+m14*(m14*m4-m13*m5) +m2*(m13*m20-m14*m19)) *m9 -((-m13*(m20*m4-m19*m5))+m14*(m19*m4-m18*m5) +m2*(m18*m20-m19^2)) *m7 -m10*((-m11*(m19*m4-m18*m5))+m13*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m2) +m1*(m11*(m18*m20-m19^2)-m13*(m13*m20-m14*m19) +m14*(m13*m19-m14*m18))) +m5*((-((-m11*(m17*m4-m16*m5))+m12*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m2) *m9) +((-m11*(m19*m4-m18*m5))+m13*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m2) *m8 -((-m12*(m19*m4-m18*m5))+m13*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m2) *m7 +m1*(m11*(m16*m19-m17*m18)-m12*(m13*m19-m14*m18) +m13*(m13*m17-m14*m16))) +m0*((m11*(m16*m20-m17*m19)-m12*(m13*m20-m14*m19) +m14*(m13*m17-m14*m16)) *m9 -(m11*(m18*m20-m19^2)-m13*(m13*m20-m14*m19) +m14*(m13*m19-m14*m18)) *m8 +(m12*(m18*m20-m19^2)-m13*(m16*m20-m17*m19) +m14*(m16*m19-m17*m18)) *m7 -m10*(m11*(m16*m19-m17*m18)-m12*(m13*m19-m14*m18) +m13*(m13*m17-m14*m16))) -m4*(((-m11*(m20*m4-m19*m5))+m14*(m14*m4-m13*m5) +m2*(m13*m20-m14*m19)) *m8 -((-m12*(m20*m4-m19*m5))+m14*(m17*m4-m16*m5) +m2*(m16*m20-m17*m19)) *m7 -m10*((-m11*(m17*m4-m16*m5))+m12*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m2) +m1*(m11*(m16*m20-m17*m19)-m12*(m13*m20-m14*m19) +m14*(m13*m17-m14*m16))), m2*(((-m12*(m20*m3-m17*m5))+m14*(m17*m3-m15*m5) +m2*(m15*m20-m17^2)) *m9 -((-m13*(m20*m3-m17*m5))+m14*(m19*m3-m16*m5) +m2*(m16*m20-m17*m19)) *m8 -m10*((-m12*(m19*m3-m16*m5))+m13*(m17*m3-m15*m5) +(m15*m19-m16*m17)*m2) +m1*(m12*(m16*m20-m17*m19)-m13*(m15*m20-m17^2) +m14*(m15*m19-m16*m17))) -m3*(((-m11*(m20*m3-m17*m5))+m14*(m14*m3-m12*m5) +m2*(m12*m20-m14*m17)) *m9 -((-m13*(m20*m3-m17*m5))+m14*(m19*m3-m16*m5) +m2*(m16*m20-m17*m19)) *m7 -m10*((-m11*(m19*m3-m16*m5))+m13*(m14*m3-m12*m5) +(m12*m19-m14*m16)*m2) +m1*(m11*(m16*m20-m17*m19)-m13*(m12*m20-m14*m17) +m14*(m12*m19-m14*m16))) -m5*((-((-m11*(m17*m3-m15*m5))+m12*(m14*m3-m12*m5) +(m12*m17-m14*m15)*m2) *m9) +((-m11*(m19*m3-m16*m5))+m13*(m14*m3-m12*m5) +(m12*m19-m14*m16)*m2) *m8 -((-m12*(m19*m3-m16*m5))+m13*(m17*m3-m15*m5) +(m15*m19-m16*m17)*m2) *m7 +m1*(m11*(m15*m19-m16*m17)-m12*(m12*m19-m14*m16) +m13*(m12*m17-m14*m15))) -m0*((m11*(m15*m20-m17^2)-m12*(m12*m20-m14*m17) +m14*(m12*m17-m14*m15)) *m9 -(m11*(m16*m20-m17*m19)-m13*(m12*m20-m14*m17) +m14*(m12*m19-m14*m16)) *m8 +(m12*(m16*m20-m17*m19)-m13*(m15*m20-m17^2) +m14*(m15*m19-m16*m17)) *m7 -m10*(m11*(m15*m19-m16*m17)-m12*(m12*m19-m14*m16) +m13*(m12*m17-m14*m15))) +m4*(((-m11*(m20*m3-m17*m5))+m14*(m14*m3-m12*m5) +m2*(m12*m20-m14*m17)) *m8 -((-m12*(m20*m3-m17*m5))+m14*(m17*m3-m15*m5) +m2*(m15*m20-m17^2)) *m7 -m10*((-m11*(m17*m3-m15*m5))+m12*(m14*m3-m12*m5) +(m12*m17-m14*m15)*m2) +m1*(m11*(m15*m20-m17^2)-m12*(m12*m20-m14*m17) +m14*(m12*m17-m14*m15))), (-m2*(((-m12*(m19*m3-m17*m4))+m14*(m16*m3-m15*m4) +(m15*m19-m16*m17)*m2) *m9 -((-m13*(m19*m3-m17*m4))+m14*(m18*m3-m16*m4) +(m16*m19-m17*m18)*m2) *m8 -m10*((-m12*(m18*m3-m16*m4))+m13*(m16*m3-m15*m4) +(m15*m18-m16^2)*m2) +m1*(m12*(m16*m19-m17*m18)-m13*(m15*m19-m16*m17) +m14*(m15*m18-m16^2)))) +m3*(((-m11*(m19*m3-m17*m4))+m14*(m13*m3-m12*m4) +(m12*m19-m13*m17)*m2) *m9 -((-m13*(m19*m3-m17*m4))+m14*(m18*m3-m16*m4) +(m16*m19-m17*m18)*m2) *m7 -m10*((-m11*(m18*m3-m16*m4))+m13*(m13*m3-m12*m4) +(m12*m18-m13*m16)*m2) +m1*(m11*(m16*m19-m17*m18)-m13*(m12*m19-m13*m17) +m14*(m12*m18-m13*m16))) +m5*((-((-m11*(m16*m3-m15*m4))+m12*(m13*m3-m12*m4) +(m12*m16-m13*m15)*m2) *m9) +((-m11*(m18*m3-m16*m4))+m13*(m13*m3-m12*m4) +(m12*m18-m13*m16)*m2) *m8 -((-m12*(m18*m3-m16*m4))+m13*(m16*m3-m15*m4) +(m15*m18-m16^2)*m2) *m7 +m1*(m11*(m15*m18-m16^2)-m12*(m12*m18-m13*m16) +m13*(m12*m16-m13*m15))) +m0*((m11*(m15*m19-m16*m17)-m12*(m12*m19-m13*m17) +m14*(m12*m16-m13*m15)) *m9 -(m11*(m16*m19-m17*m18)-m13*(m12*m19-m13*m17) +m14*(m12*m18-m13*m16)) *m8 +(m12*(m16*m19-m17*m18)-m13*(m15*m19-m16*m17) +m14*(m15*m18-m16^2)) *m7 -m10*(m11*(m15*m18-m16^2)-m12*(m12*m18-m13*m16) +m13*(m12*m16-m13*m15))) -m4*(((-m11*(m19*m3-m17*m4))+m14*(m13*m3-m12*m4) +(m12*m19-m13*m17)*m2) *m8 -((-m12*(m19*m3-m17*m4))+m14*(m16*m3-m15*m4) +(m15*m19-m16*m17)*m2) *m7 -m10*((-m11*(m16*m3-m15*m4))+m12*(m13*m3-m12*m4) +(m12*m16-m13*m15)*m2) +m1*(m11*(m15*m19-m16*m17)-m12*(m12*m19-m13*m17) +m14*(m12*m16-m13*m15)))], [m8*(m13*(m17*(m10*m4-m5*m9)+m3*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m8) -m14*(m16*(m10*m4-m5*m9)+m3*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m8) +m2*((-m16*(m20*m9-m10*m19))+m17*(m19*m9-m10*m18) +(m18*m20-m19^2)*m8) -((-m16*(m20*m4-m19*m5))+m17*(m19*m4-m18*m5) +(m18*m20-m19^2)*m3) *m7) -m9*(m12*(m17*(m10*m4-m5*m9)+m3*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m8) -m14*(m15*(m10*m4-m5*m9)+m3*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m8) +m2*((-m15*(m20*m9-m10*m19))+m17*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m8) -((-m15*(m20*m4-m19*m5))+m17*(m17*m4-m16*m5) +(m16*m20-m17*m19)*m3) *m7) +m10*(m12*(m16*(m10*m4-m5*m9)+m3*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m8) -m13*(m15*(m10*m4-m5*m9)+m3*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m8) +m2*((-m15*(m19*m9-m10*m18))+m16*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m8) -((-m15*(m19*m4-m18*m5))+m16*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m3) *m7) +m1*((-m12*((-m16*(m20*m9-m10*m19))+m17*(m19*m9-m10*m18) +(m18*m20-m19^2)*m8)) +m13*((-m15*(m20*m9-m10*m19))+m17*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m8) -m14*((-m15*(m19*m9-m10*m18))+m16*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m8) +(m15*(m18*m20-m19^2)-m16*(m16*m20-m17*m19) +m17*(m16*m19-m17*m18)) *m7) -((-m12*((-m16*(m20*m4-m19*m5))+m17*(m19*m4-m18*m5) +(m18*m20-m19^2)*m3)) +m13*((-m15*(m20*m4-m19*m5))+m17*(m17*m4-m16*m5) +(m16*m20-m17*m19)*m3) -m14*((-m15*(m19*m4-m18*m5))+m16*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m3) +m2*(m15*(m18*m20-m19^2)-m16*(m16*m20-m17*m19) +m17*(m16*m19-m17*m18))) *m6, (-m3*(m13*(m17*(m10*m4-m5*m9)+m3*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m8) -m14*(m16*(m10*m4-m5*m9)+m3*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m8) +m2*((-m16*(m20*m9-m10*m19))+m17*(m19*m9-m10*m18) +(m18*m20-m19^2)*m8) -((-m16*(m20*m4-m19*m5))+m17*(m19*m4-m18*m5) +(m18*m20-m19^2)*m3) *m7)) +m4*(m12*(m17*(m10*m4-m5*m9)+m3*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m8) -m14*(m15*(m10*m4-m5*m9)+m3*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m8) +m2*((-m15*(m20*m9-m10*m19))+m17*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m8) -((-m15*(m20*m4-m19*m5))+m17*(m17*m4-m16*m5) +(m16*m20-m17*m19)*m3) *m7) -m5*(m12*(m16*(m10*m4-m5*m9)+m3*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m8) -m13*(m15*(m10*m4-m5*m9)+m3*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m8) +m2*((-m15*(m19*m9-m10*m18))+m16*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m8) -((-m15*(m19*m4-m18*m5))+m16*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m3) *m7) -m0*((-m12*((-m16*(m20*m9-m10*m19))+m17*(m19*m9-m10*m18) +(m18*m20-m19^2)*m8)) +m13*((-m15*(m20*m9-m10*m19))+m17*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m8) -m14*((-m15*(m19*m9-m10*m18))+m16*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m8) +(m15*(m18*m20-m19^2)-m16*(m16*m20-m17*m19) +m17*(m16*m19-m17*m18)) *m7) +m1*((-m12*((-m16*(m20*m4-m19*m5))+m17*(m19*m4-m18*m5) +(m18*m20-m19^2)*m3)) +m13*((-m15*(m20*m4-m19*m5))+m17*(m17*m4-m16*m5) +(m16*m20-m17*m19)*m3) -m14*((-m15*(m19*m4-m18*m5))+m16*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m3) +m2*(m15*(m18*m20-m19^2)-m16*(m16*m20-m17*m19) +m17*(m16*m19-m17*m18))), m3*(m9*(m17*(m10*m4-m5*m9)+m3*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m8) -m10*(m16*(m10*m4-m5*m9)+m3*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m8) +m1*((-m16*(m20*m9-m10*m19))+m17*(m19*m9-m10*m18) +(m18*m20-m19^2)*m8) -((-m16*(m20*m4-m19*m5))+m17*(m19*m4-m18*m5) +(m18*m20-m19^2)*m3) *m6) -m4*(m8*(m17*(m10*m4-m5*m9)+m3*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m8) -m10*(m15*(m10*m4-m5*m9)+m3*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m8) +m1*((-m15*(m20*m9-m10*m19))+m17*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m8) -((-m15*(m20*m4-m19*m5))+m17*(m17*m4-m16*m5) +(m16*m20-m17*m19)*m3) *m6) +m5*(m8*(m16*(m10*m4-m5*m9)+m3*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m8) -m9*(m15*(m10*m4-m5*m9)+m3*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m8) +m1*((-m15*(m19*m9-m10*m18))+m16*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m8) -((-m15*(m19*m4-m18*m5))+m16*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m3) *m6) +m0*((-m8*((-m16*(m20*m9-m10*m19))+m17*(m19*m9-m10*m18) +(m18*m20-m19^2)*m8)) +m9*((-m15*(m20*m9-m10*m19))+m17*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m8) -m10*((-m15*(m19*m9-m10*m18))+m16*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m8) +(m15*(m18*m20-m19^2)-m16*(m16*m20-m17*m19) +m17*(m16*m19-m17*m18)) *m6) -m1*(((-m15*(m20*m4-m19*m5))+m17*(m17*m4-m16*m5) +(m16*m20-m17*m19)*m3) *m9 -((-m16*(m20*m4-m19*m5))+m17*(m19*m4-m18*m5) +(m18*m20-m19^2)*m3) *m8 -m10*((-m15*(m19*m4-m18*m5))+m16*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m3) +m1*(m15*(m18*m20-m19^2)-m16*(m16*m20-m17*m19) +m17*(m16*m19-m17*m18))), (-m3*(m9*(m14*(m10*m4-m5*m9)+m2*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m7) -m10*(m13*(m10*m4-m5*m9)+m2*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m7) +m1*((-m13*(m20*m9-m10*m19))+m14*(m19*m9-m10*m18) +(m18*m20-m19^2)*m7) -((-m13*(m20*m4-m19*m5))+m14*(m19*m4-m18*m5) +m2*(m18*m20-m19^2)) *m6)) +m4*(m8*(m14*(m10*m4-m5*m9)+m2*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m7) -m10*(m12*(m10*m4-m5*m9)+m2*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m7) +m1*((-m12*(m20*m9-m10*m19))+m14*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m7) -((-m12*(m20*m4-m19*m5))+m14*(m17*m4-m16*m5) +m2*(m16*m20-m17*m19)) *m6) -m5*(m8*(m13*(m10*m4-m5*m9)+m2*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m7) -m9*(m12*(m10*m4-m5*m9)+m2*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m7) +m1*((-m12*(m19*m9-m10*m18))+m13*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m7) -((-m12*(m19*m4-m18*m5))+m13*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m2) *m6) -m0*((-m8*((-m13*(m20*m9-m10*m19))+m14*(m19*m9-m10*m18) +(m18*m20-m19^2)*m7)) +m9*((-m12*(m20*m9-m10*m19))+m14*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m7) -m10*((-m12*(m19*m9-m10*m18))+m13*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m7) +(m12*(m18*m20-m19^2)-m13*(m16*m20-m17*m19) +m14*(m16*m19-m17*m18)) *m6) +m1*(((-m12*(m20*m4-m19*m5))+m14*(m17*m4-m16*m5) +m2*(m16*m20-m17*m19)) *m9 -((-m13*(m20*m4-m19*m5))+m14*(m19*m4-m18*m5) +m2*(m18*m20-m19^2)) *m8 -m10*((-m12*(m19*m4-m18*m5))+m13*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m2) +m1*(m12*(m18*m20-m19^2)-m13*(m16*m20-m17*m19) +m14*(m16*m19-m17*m18))), m3*((m14*(m10*m3-m5*m8)+m2*(m20*m8-m10*m17)-(m20*m3-m17*m5)*m7) *m9 -m10*(m13*(m10*m3-m5*m8)+m2*(m19*m8-m10*m16) -(m19*m3-m16*m5)*m7) +m1*((-m13*(m20*m8-m10*m17))+m14*(m19*m8-m10*m16) +(m16*m20-m17*m19)*m7) -((-m13*(m20*m3-m17*m5))+m14*(m19*m3-m16*m5) +m2*(m16*m20-m17*m19)) *m6) +m5*((-(m12*(m10*m3-m5*m8)+m2*(m17*m8-m10*m15) -(m17*m3-m15*m5)*m7) *m9) +m8*(m13*(m10*m3-m5*m8)+m2*(m19*m8-m10*m16) -(m19*m3-m16*m5)*m7) +m1*((-m12*(m19*m8-m10*m16))+m13*(m17*m8-m10*m15) +(m15*m19-m16*m17)*m7) -((-m12*(m19*m3-m16*m5))+m13*(m17*m3-m15*m5) +(m15*m19-m16*m17)*m2) *m6) +m0*(((-m12*(m20*m8-m10*m17))+m14*(m17*m8-m10*m15) +(m15*m20-m17^2)*m7) *m9 -m8*((-m13*(m20*m8-m10*m17))+m14*(m19*m8-m10*m16) +(m16*m20-m17*m19)*m7) -m10*((-m12*(m19*m8-m10*m16))+m13*(m17*m8-m10*m15) +(m15*m19-m16*m17)*m7) +(m12*(m16*m20-m17*m19)-m13*(m15*m20-m17^2) +m14*(m15*m19-m16*m17)) *m6) -m1*(((-m12*(m20*m3-m17*m5))+m14*(m17*m3-m15*m5) +m2*(m15*m20-m17^2)) *m9 -((-m13*(m20*m3-m17*m5))+m14*(m19*m3-m16*m5) +m2*(m16*m20-m17*m19)) *m8 -m10*((-m12*(m19*m3-m16*m5))+m13*(m17*m3-m15*m5) +(m15*m19-m16*m17)*m2) +m1*(m12*(m16*m20-m17*m19)-m13*(m15*m20-m17^2) +m14*(m15*m19-m16*m17))) -m4*(m8*(m14*(m10*m3-m5*m8)+m2*(m20*m8-m10*m17) -(m20*m3-m17*m5)*m7) -m10*(m12*(m10*m3-m5*m8)+m2*(m17*m8-m10*m15) -(m17*m3-m15*m5)*m7) +m1*((-m12*(m20*m8-m10*m17))+m14*(m17*m8-m10*m15) +(m15*m20-m17^2)*m7) -((-m12*(m20*m3-m17*m5))+m14*(m17*m3-m15*m5) +m2*(m15*m20-m17^2)) *m6), (-m3*(m9*(m14*(m3*m9-m4*m8)+m2*(m19*m8-m17*m9) -(m19*m3-m17*m4)*m7) -m10*(m13*(m3*m9-m4*m8)+m2*(m18*m8-m16*m9) -(m18*m3-m16*m4)*m7) +m1*((-m13*(m19*m8-m17*m9))+m14*(m18*m8-m16*m9) +(m16*m19-m17*m18)*m7) -((-m13*(m19*m3-m17*m4))+m14*(m18*m3-m16*m4) +(m16*m19-m17*m18)*m2) *m6)) +m4*(m8*(m14*(m3*m9-m4*m8)+m2*(m19*m8-m17*m9) -(m19*m3-m17*m4)*m7) -m10*(m12*(m3*m9-m4*m8)+m2*(m16*m8-m15*m9) -(m16*m3-m15*m4)*m7) +m1*((-m12*(m19*m8-m17*m9))+m14*(m16*m8-m15*m9) +(m15*m19-m16*m17)*m7) -((-m12*(m19*m3-m17*m4))+m14*(m16*m3-m15*m4) +(m15*m19-m16*m17)*m2) *m6) -m5*(m8*(m13*(m3*m9-m4*m8)+m2*(m18*m8-m16*m9) -(m18*m3-m16*m4)*m7) -m9*(m12*(m3*m9-m4*m8)+m2*(m16*m8-m15*m9) -(m16*m3-m15*m4)*m7) +m1*((-m12*(m18*m8-m16*m9))+m13*(m16*m8-m15*m9) +(m15*m18-m16^2)*m7) -((-m12*(m18*m3-m16*m4))+m13*(m16*m3-m15*m4) +(m15*m18-m16^2)*m2) *m6) -m0*((-m8*((-m13*(m19*m8-m17*m9))+m14*(m18*m8-m16*m9) +(m16*m19-m17*m18)*m7)) +m9*((-m12*(m19*m8-m17*m9))+m14*(m16*m8-m15*m9) +(m15*m19-m16*m17)*m7) -m10*((-m12*(m18*m8-m16*m9))+m13*(m16*m8-m15*m9) +(m15*m18-m16^2)*m7) +(m12*(m16*m19-m17*m18)-m13*(m15*m19-m16*m17) +m14*(m15*m18-m16^2)) *m6) +m1*(((-m12*(m19*m3-m17*m4))+m14*(m16*m3-m15*m4) +(m15*m19-m16*m17)*m2) *m9 -((-m13*(m19*m3-m17*m4))+m14*(m18*m3-m16*m4) +(m16*m19-m17*m18)*m2) *m8 -m10*((-m12*(m18*m3-m16*m4))+m13*(m16*m3-m15*m4) +(m15*m18-m16^2)*m2) +m1*(m12*(m16*m19-m17*m18)-m13*(m15*m19-m16*m17) +m14*(m15*m18-m16^2)))], [(-m7*(m13*(m17*(m10*m4-m5*m9)+m3*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m8) -m14*(m16*(m10*m4-m5*m9)+m3*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m8) +m2*((-m16*(m20*m9-m10*m19))+m17*(m19*m9-m10*m18) +(m18*m20-m19^2)*m8) -((-m16*(m20*m4-m19*m5))+m17*(m19*m4-m18*m5) +(m18*m20-m19^2)*m3) *m7)) +m9*(m11*(m17*(m10*m4-m5*m9)+m3*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m8) -m14*(m12*(m10*m4-m5*m9)+m3*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m8) +m2*((-m12*(m20*m9-m10*m19))+m17*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m8) -((-m12*(m20*m4-m19*m5))+m17*(m14*m4-m13*m5) +(m13*m20-m14*m19)*m3) *m7) -m10*(m11*(m16*(m10*m4-m5*m9)+m3*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m8) -m13*(m12*(m10*m4-m5*m9)+m3*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m8) +m2*((-m12*(m19*m9-m10*m18))+m16*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m8) -((-m12*(m19*m4-m18*m5))+m16*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m3) *m7) -m1*((-m11*((-m16*(m20*m9-m10*m19))+m17*(m19*m9-m10*m18) +(m18*m20-m19^2)*m8)) +m13*((-m12*(m20*m9-m10*m19))+m17*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m8) -m14*((-m12*(m19*m9-m10*m18))+m16*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m8) +(m12*(m18*m20-m19^2)-m16*(m13*m20-m14*m19) +m17*(m13*m19-m14*m18)) *m7) +((-m11*((-m16*(m20*m4-m19*m5))+m17*(m19*m4-m18*m5) +(m18*m20-m19^2)*m3)) +m13*((-m12*(m20*m4-m19*m5))+m17*(m14*m4-m13*m5) +(m13*m20-m14*m19)*m3) -m14*((-m12*(m19*m4-m18*m5))+m16*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m3) +m2*(m12*(m18*m20-m19^2)-m16*(m13*m20-m14*m19) +m17*(m13*m19-m14*m18))) *m6, m2*(m13*(m17*(m10*m4-m5*m9)+m3*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m8) -m14*(m16*(m10*m4-m5*m9)+m3*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m8) +m2*((-m16*(m20*m9-m10*m19))+m17*(m19*m9-m10*m18) +(m18*m20-m19^2)*m8) -((-m16*(m20*m4-m19*m5))+m17*(m19*m4-m18*m5) +(m18*m20-m19^2)*m3) *m7) -m4*(m11*(m17*(m10*m4-m5*m9)+m3*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m8) -m14*(m12*(m10*m4-m5*m9)+m3*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m8) +m2*((-m12*(m20*m9-m10*m19))+m17*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m8) -((-m12*(m20*m4-m19*m5))+m17*(m14*m4-m13*m5) +(m13*m20-m14*m19)*m3) *m7) +m5*(m11*(m16*(m10*m4-m5*m9)+m3*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m8) -m13*(m12*(m10*m4-m5*m9)+m3*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m8) +m2*((-m12*(m19*m9-m10*m18))+m16*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m8) -((-m12*(m19*m4-m18*m5))+m16*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m3) *m7) +m0*((-m11*((-m16*(m20*m9-m10*m19))+m17*(m19*m9-m10*m18) +(m18*m20-m19^2)*m8)) +m13*((-m12*(m20*m9-m10*m19))+m17*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m8) -m14*((-m12*(m19*m9-m10*m18))+m16*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m8) +(m12*(m18*m20-m19^2)-m16*(m13*m20-m14*m19) +m17*(m13*m19-m14*m18)) *m7) -m1*((-m11*((-m16*(m20*m4-m19*m5))+m17*(m19*m4-m18*m5) +(m18*m20-m19^2)*m3)) +m13*((-m12*(m20*m4-m19*m5))+m17*(m14*m4-m13*m5) +(m13*m20-m14*m19)*m3) -m14*((-m12*(m19*m4-m18*m5))+m16*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m3) +m2*(m12*(m18*m20-m19^2)-m16*(m13*m20-m14*m19) +m17*(m13*m19-m14*m18))), (-m2*(m9*(m17*(m10*m4-m5*m9)+m3*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m8) -m10*(m16*(m10*m4-m5*m9)+m3*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m8) +m1*((-m16*(m20*m9-m10*m19))+m17*(m19*m9-m10*m18) +(m18*m20-m19^2)*m8) -((-m16*(m20*m4-m19*m5))+m17*(m19*m4-m18*m5) +(m18*m20-m19^2)*m3) *m6)) +m4*(m7*(m17*(m10*m4-m5*m9)+m3*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m8) -m10*(m12*(m10*m4-m5*m9)+m3*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m8) +m1*((-m12*(m20*m9-m10*m19))+m17*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m8) -((-m12*(m20*m4-m19*m5))+m17*(m14*m4-m13*m5) +(m13*m20-m14*m19)*m3) *m6) -m5*(m7*(m16*(m10*m4-m5*m9)+m3*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m8) -m9*(m12*(m10*m4-m5*m9)+m3*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m8) +m1*((-m12*(m19*m9-m10*m18))+m16*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m8) -((-m12*(m19*m4-m18*m5))+m16*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m3) *m6) -m0*((-m7*((-m16*(m20*m9-m10*m19))+m17*(m19*m9-m10*m18) +(m18*m20-m19^2)*m8)) +m9*((-m12*(m20*m9-m10*m19))+m17*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m8) -m10*((-m12*(m19*m9-m10*m18))+m16*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m8) +(m12*(m18*m20-m19^2)-m16*(m13*m20-m14*m19) +m17*(m13*m19-m14*m18)) *m6) +m1*(((-m12*(m20*m4-m19*m5))+m17*(m14*m4-m13*m5) +(m13*m20-m14*m19)*m3) *m9 -((-m16*(m20*m4-m19*m5))+m17*(m19*m4-m18*m5) +(m18*m20-m19^2)*m3) *m7 -m10*((-m12*(m19*m4-m18*m5))+m16*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m3) +m1*(m12*(m18*m20-m19^2)-m16*(m13*m20-m14*m19) +m17*(m13*m19-m14*m18))), m2*(m9*(m14*(m10*m4-m5*m9)+m2*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m7) -m10*(m13*(m10*m4-m5*m9)+m2*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m7) +m1*((-m13*(m20*m9-m10*m19))+m14*(m19*m9-m10*m18) +(m18*m20-m19^2)*m7) -((-m13*(m20*m4-m19*m5))+m14*(m19*m4-m18*m5) +m2*(m18*m20-m19^2)) *m6) -m4*(m7*(m14*(m10*m4-m5*m9)+m2*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m7) -m10*(m11*(m10*m4-m5*m9)+m2*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m7) +m1*((-m11*(m20*m9-m10*m19))+m14*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m7) -((-m11*(m20*m4-m19*m5))+m14*(m14*m4-m13*m5) +m2*(m13*m20-m14*m19)) *m6) +m5*(m7*(m13*(m10*m4-m5*m9)+m2*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m7) -m9*(m11*(m10*m4-m5*m9)+m2*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m7) +m1*((-m11*(m19*m9-m10*m18))+m13*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m7) -((-m11*(m19*m4-m18*m5))+m13*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m2) *m6) +m0*((-m7*((-m13*(m20*m9-m10*m19))+m14*(m19*m9-m10*m18) +(m18*m20-m19^2)*m7)) +m9*((-m11*(m20*m9-m10*m19))+m14*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m7) -m10*((-m11*(m19*m9-m10*m18))+m13*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m7) +(m11*(m18*m20-m19^2)-m13*(m13*m20-m14*m19) +m14*(m13*m19-m14*m18)) *m6) -m1*(((-m11*(m20*m4-m19*m5))+m14*(m14*m4-m13*m5) +m2*(m13*m20-m14*m19)) *m9 -((-m13*(m20*m4-m19*m5))+m14*(m19*m4-m18*m5) +m2*(m18*m20-m19^2)) *m7 -m10*((-m11*(m19*m4-m18*m5))+m13*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m2) +m1*(m11*(m18*m20-m19^2)-m13*(m13*m20-m14*m19) +m14*(m13*m19-m14*m18))), (-m2*((m14*(m10*m3-m5*m8)+m2*(m20*m8-m10*m17) -(m20*m3-m17*m5)*m7) *m9 -m10*(m13*(m10*m3-m5*m8)+m2*(m19*m8-m10*m16) -(m19*m3-m16*m5)*m7) +m1*((-m13*(m20*m8-m10*m17))+m14*(m19*m8-m10*m16) +(m16*m20-m17*m19)*m7) -((-m13*(m20*m3-m17*m5))+m14*(m19*m3-m16*m5) +m2*(m16*m20-m17*m19)) *m6)) -m5*((-(m11*(m10*m3-m5*m8)+m2*(m14*m8-m10*m12) -(m14*m3-m12*m5)*m7) *m9) +m7*(m13*(m10*m3-m5*m8)+m2*(m19*m8-m10*m16) -(m19*m3-m16*m5)*m7) +m1*((-m11*(m19*m8-m10*m16))+m13*(m14*m8-m10*m12) +(m12*m19-m14*m16)*m7) -((-m11*(m19*m3-m16*m5))+m13*(m14*m3-m12*m5) +(m12*m19-m14*m16)*m2) *m6) -m0*(((-m11*(m20*m8-m10*m17))+m14*(m14*m8-m10*m12) +(m12*m20-m14*m17)*m7) *m9 -m7*((-m13*(m20*m8-m10*m17))+m14*(m19*m8-m10*m16) +(m16*m20-m17*m19)*m7) -m10*((-m11*(m19*m8-m10*m16))+m13*(m14*m8-m10*m12) +(m12*m19-m14*m16)*m7) +(m11*(m16*m20-m17*m19)-m13*(m12*m20-m14*m17) +m14*(m12*m19-m14*m16)) *m6) +m1*(((-m11*(m20*m3-m17*m5))+m14*(m14*m3-m12*m5) +m2*(m12*m20-m14*m17)) *m9 -((-m13*(m20*m3-m17*m5))+m14*(m19*m3-m16*m5) +m2*(m16*m20-m17*m19)) *m7 -m10*((-m11*(m19*m3-m16*m5))+m13*(m14*m3-m12*m5) +(m12*m19-m14*m16)*m2) +m1*(m11*(m16*m20-m17*m19)-m13*(m12*m20-m14*m17) +m14*(m12*m19-m14*m16))) +m4*(m7*(m14*(m10*m3-m5*m8)+m2*(m20*m8-m10*m17) -(m20*m3-m17*m5)*m7) -m10*(m11*(m10*m3-m5*m8)+m2*(m14*m8-m10*m12) -(m14*m3-m12*m5)*m7) +m1*((-m11*(m20*m8-m10*m17))+m14*(m14*m8-m10*m12) +(m12*m20-m14*m17)*m7) -((-m11*(m20*m3-m17*m5))+m14*(m14*m3-m12*m5) +m2*(m12*m20-m14*m17)) *m6), m2*(m9*(m14*(m3*m9-m4*m8)+m2*(m19*m8-m17*m9) -(m19*m3-m17*m4)*m7) -m10*(m13*(m3*m9-m4*m8)+m2*(m18*m8-m16*m9) -(m18*m3-m16*m4)*m7) +m1*((-m13*(m19*m8-m17*m9))+m14*(m18*m8-m16*m9) +(m16*m19-m17*m18)*m7) -((-m13*(m19*m3-m17*m4))+m14*(m18*m3-m16*m4) +(m16*m19-m17*m18)*m2) *m6) -m4*(m7*(m14*(m3*m9-m4*m8)+m2*(m19*m8-m17*m9) -(m19*m3-m17*m4)*m7) -m10*(m11*(m3*m9-m4*m8)+m2*(m13*m8-m12*m9) -(m13*m3-m12*m4)*m7) +m1*((-m11*(m19*m8-m17*m9))+m14*(m13*m8-m12*m9) +(m12*m19-m13*m17)*m7) -((-m11*(m19*m3-m17*m4))+m14*(m13*m3-m12*m4) +(m12*m19-m13*m17)*m2) *m6) +m5*(m7*(m13*(m3*m9-m4*m8)+m2*(m18*m8-m16*m9) -(m18*m3-m16*m4)*m7) -m9*(m11*(m3*m9-m4*m8)+m2*(m13*m8-m12*m9) -(m13*m3-m12*m4)*m7) +m1*((-m11*(m18*m8-m16*m9))+m13*(m13*m8-m12*m9) +(m12*m18-m13*m16)*m7) -((-m11*(m18*m3-m16*m4))+m13*(m13*m3-m12*m4) +(m12*m18-m13*m16)*m2) *m6) +m0*((-m7*((-m13*(m19*m8-m17*m9))+m14*(m18*m8-m16*m9) +(m16*m19-m17*m18)*m7)) +m9*((-m11*(m19*m8-m17*m9))+m14*(m13*m8-m12*m9) +(m12*m19-m13*m17)*m7) -m10*((-m11*(m18*m8-m16*m9))+m13*(m13*m8-m12*m9) +(m12*m18-m13*m16)*m7) +(m11*(m16*m19-m17*m18)-m13*(m12*m19-m13*m17) +m14*(m12*m18-m13*m16)) *m6) -m1*(((-m11*(m19*m3-m17*m4))+m14*(m13*m3-m12*m4) +(m12*m19-m13*m17)*m2) *m9 -((-m13*(m19*m3-m17*m4))+m14*(m18*m3-m16*m4) +(m16*m19-m17*m18)*m2) *m7 -m10*((-m11*(m18*m3-m16*m4))+m13*(m13*m3-m12*m4) +(m12*m18-m13*m16)*m2) +m1*(m11*(m16*m19-m17*m18)-m13*(m12*m19-m13*m17) +m14*(m12*m18-m13*m16)))], [m7*(m12*(m17*(m10*m4-m5*m9)+m3*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m8) -m14*(m15*(m10*m4-m5*m9)+m3*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m8) +m2*((-m15*(m20*m9-m10*m19))+m17*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m8) -((-m15*(m20*m4-m19*m5))+m17*(m17*m4-m16*m5) +(m16*m20-m17*m19)*m3) *m7) -m8*(m11*(m17*(m10*m4-m5*m9)+m3*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m8) -m14*(m12*(m10*m4-m5*m9)+m3*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m8) +m2*((-m12*(m20*m9-m10*m19))+m17*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m8) -((-m12*(m20*m4-m19*m5))+m17*(m14*m4-m13*m5) +(m13*m20-m14*m19)*m3) *m7) +m10*(m11*(m15*(m10*m4-m5*m9)+m3*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m8) -m12*(m12*(m10*m4-m5*m9)+m3*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m8) +m2*((-m12*(m17*m9-m10*m16))+m15*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m8) -((-m12*(m17*m4-m16*m5))+m15*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m3) *m7) +m1*((-m11*((-m15*(m20*m9-m10*m19))+m17*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m8)) +m12*((-m12*(m20*m9-m10*m19))+m17*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m8) -m14*((-m12*(m17*m9-m10*m16))+m15*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m8) +(m12*(m16*m20-m17*m19)-m15*(m13*m20-m14*m19) +m17*(m13*m17-m14*m16)) *m7) -((-m11*((-m15*(m20*m4-m19*m5))+m17*(m17*m4-m16*m5) +(m16*m20-m17*m19)*m3)) +m12*((-m12*(m20*m4-m19*m5))+m17*(m14*m4-m13*m5) +(m13*m20-m14*m19)*m3) -m14*((-m12*(m17*m4-m16*m5))+m15*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m3) +m2*(m12*(m16*m20-m17*m19)-m15*(m13*m20-m14*m19) +m17*(m13*m17-m14*m16))) *m6, (-m2*(m12*(m17*(m10*m4-m5*m9)+m3*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m8) -m14*(m15*(m10*m4-m5*m9)+m3*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m8) +m2*((-m15*(m20*m9-m10*m19))+m17*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m8) -((-m15*(m20*m4-m19*m5))+m17*(m17*m4-m16*m5) +(m16*m20-m17*m19)*m3) *m7)) +m3*(m11*(m17*(m10*m4-m5*m9)+m3*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m8) -m14*(m12*(m10*m4-m5*m9)+m3*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m8) +m2*((-m12*(m20*m9-m10*m19))+m17*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m8) -((-m12*(m20*m4-m19*m5))+m17*(m14*m4-m13*m5) +(m13*m20-m14*m19)*m3) *m7) -m5*(m11*(m15*(m10*m4-m5*m9)+m3*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m8) -m12*(m12*(m10*m4-m5*m9)+m3*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m8) +m2*((-m12*(m17*m9-m10*m16))+m15*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m8) -((-m12*(m17*m4-m16*m5))+m15*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m3) *m7) -m0*((-m11*((-m15*(m20*m9-m10*m19))+m17*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m8)) +m12*((-m12*(m20*m9-m10*m19))+m17*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m8) -m14*((-m12*(m17*m9-m10*m16))+m15*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m8) +(m12*(m16*m20-m17*m19)-m15*(m13*m20-m14*m19) +m17*(m13*m17-m14*m16)) *m7) +m1*((-m11*((-m15*(m20*m4-m19*m5))+m17*(m17*m4-m16*m5) +(m16*m20-m17*m19)*m3)) +m12*((-m12*(m20*m4-m19*m5))+m17*(m14*m4-m13*m5) +(m13*m20-m14*m19)*m3) -m14*((-m12*(m17*m4-m16*m5))+m15*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m3) +m2*(m12*(m16*m20-m17*m19)-m15*(m13*m20-m14*m19) +m17*(m13*m17-m14*m16))), m2*(m8*(m17*(m10*m4-m5*m9)+m3*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m8) -m10*(m15*(m10*m4-m5*m9)+m3*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m8) +m1*((-m15*(m20*m9-m10*m19))+m17*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m8) -((-m15*(m20*m4-m19*m5))+m17*(m17*m4-m16*m5) +(m16*m20-m17*m19)*m3) *m6) -m3*(m7*(m17*(m10*m4-m5*m9)+m3*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m8) -m10*(m12*(m10*m4-m5*m9)+m3*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m8) +m1*((-m12*(m20*m9-m10*m19))+m17*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m8) -((-m12*(m20*m4-m19*m5))+m17*(m14*m4-m13*m5) +(m13*m20-m14*m19)*m3) *m6) +m5*(m7*(m15*(m10*m4-m5*m9)+m3*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m8) -m8*(m12*(m10*m4-m5*m9)+m3*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m8) +m1*((-m12*(m17*m9-m10*m16))+m15*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m8) -((-m12*(m17*m4-m16*m5))+m15*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m3) *m6) +m0*((-m7*((-m15*(m20*m9-m10*m19))+m17*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m8)) +m8*((-m12*(m20*m9-m10*m19))+m17*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m8) -m10*((-m12*(m17*m9-m10*m16))+m15*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m8) +(m12*(m16*m20-m17*m19)-m15*(m13*m20-m14*m19) +m17*(m13*m17-m14*m16)) *m6) -m1*(((-m12*(m20*m4-m19*m5))+m17*(m14*m4-m13*m5) +(m13*m20-m14*m19)*m3) *m8 -((-m15*(m20*m4-m19*m5))+m17*(m17*m4-m16*m5) +(m16*m20-m17*m19)*m3) *m7 -m10*((-m12*(m17*m4-m16*m5))+m15*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m3) +m1*(m12*(m16*m20-m17*m19)-m15*(m13*m20-m14*m19) +m17*(m13*m17-m14*m16))), (-m2*(m8*(m14*(m10*m4-m5*m9)+m2*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m7) -m10*(m12*(m10*m4-m5*m9)+m2*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m7) +m1*((-m12*(m20*m9-m10*m19))+m14*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m7) -((-m12*(m20*m4-m19*m5))+m14*(m17*m4-m16*m5) +m2*(m16*m20-m17*m19)) *m6)) +m3*(m7*(m14*(m10*m4-m5*m9)+m2*(m20*m9-m10*m19) -(m20*m4-m19*m5)*m7) -m10*(m11*(m10*m4-m5*m9)+m2*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m7) +m1*((-m11*(m20*m9-m10*m19))+m14*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m7) -((-m11*(m20*m4-m19*m5))+m14*(m14*m4-m13*m5) +m2*(m13*m20-m14*m19)) *m6) -m5*(m7*(m12*(m10*m4-m5*m9)+m2*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m7) -m8*(m11*(m10*m4-m5*m9)+m2*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m7) +m1*((-m11*(m17*m9-m10*m16))+m12*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m7) -((-m11*(m17*m4-m16*m5))+m12*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m2) *m6) -m0*((-m7*((-m12*(m20*m9-m10*m19))+m14*(m17*m9-m10*m16) +(m16*m20-m17*m19)*m7)) +m8*((-m11*(m20*m9-m10*m19))+m14*(m14*m9-m10*m13) +(m13*m20-m14*m19)*m7) -m10*((-m11*(m17*m9-m10*m16))+m12*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m7) +(m11*(m16*m20-m17*m19)-m12*(m13*m20-m14*m19) +m14*(m13*m17-m14*m16)) *m6) +m1*(((-m11*(m20*m4-m19*m5))+m14*(m14*m4-m13*m5) +m2*(m13*m20-m14*m19)) *m8 -((-m12*(m20*m4-m19*m5))+m14*(m17*m4-m16*m5) +m2*(m16*m20-m17*m19)) *m7 -m10*((-m11*(m17*m4-m16*m5))+m12*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m2) +m1*(m11*(m16*m20-m17*m19)-m12*(m13*m20-m14*m19) +m14*(m13*m17-m14*m16))), m2*(m8*(m14*(m10*m3-m5*m8)+m2*(m20*m8-m10*m17) -(m20*m3-m17*m5)*m7) -m10*(m12*(m10*m3-m5*m8)+m2*(m17*m8-m10*m15) -(m17*m3-m15*m5)*m7) +m1*((-m12*(m20*m8-m10*m17))+m14*(m17*m8-m10*m15) +(m15*m20-m17^2)*m7) -((-m12*(m20*m3-m17*m5))+m14*(m17*m3-m15*m5) +m2*(m15*m20-m17^2)) *m6) -m3*(m7*(m14*(m10*m3-m5*m8)+m2*(m20*m8-m10*m17) -(m20*m3-m17*m5)*m7) -m10*(m11*(m10*m3-m5*m8)+m2*(m14*m8-m10*m12) -(m14*m3-m12*m5)*m7) +m1*((-m11*(m20*m8-m10*m17))+m14*(m14*m8-m10*m12) +(m12*m20-m14*m17)*m7) -((-m11*(m20*m3-m17*m5))+m14*(m14*m3-m12*m5) +m2*(m12*m20-m14*m17)) *m6) +m5*(m7*(m12*(m10*m3-m5*m8)+m2*(m17*m8-m10*m15) -(m17*m3-m15*m5)*m7) -m8*(m11*(m10*m3-m5*m8)+m2*(m14*m8-m10*m12) -(m14*m3-m12*m5)*m7) +m1*((-m11*(m17*m8-m10*m15))+m12*(m14*m8-m10*m12) +(m12*m17-m14*m15)*m7) -((-m11*(m17*m3-m15*m5))+m12*(m14*m3-m12*m5) +(m12*m17-m14*m15)*m2) *m6) +m0*((-m7*((-m12*(m20*m8-m10*m17))+m14*(m17*m8-m10*m15) +(m15*m20-m17^2)*m7)) +m8*((-m11*(m20*m8-m10*m17))+m14*(m14*m8-m10*m12) +(m12*m20-m14*m17)*m7) -m10*((-m11*(m17*m8-m10*m15))+m12*(m14*m8-m10*m12) +(m12*m17-m14*m15)*m7) +(m11*(m15*m20-m17^2)-m12*(m12*m20-m14*m17) +m14*(m12*m17-m14*m15)) *m6) -m1*(((-m11*(m20*m3-m17*m5))+m14*(m14*m3-m12*m5) +m2*(m12*m20-m14*m17)) *m8 -((-m12*(m20*m3-m17*m5))+m14*(m17*m3-m15*m5) +m2*(m15*m20-m17^2)) *m7 -m10*((-m11*(m17*m3-m15*m5))+m12*(m14*m3-m12*m5) +(m12*m17-m14*m15)*m2) +m1*(m11*(m15*m20-m17^2)-m12*(m12*m20-m14*m17) +m14*(m12*m17-m14*m15))), (-m2*(m8*(m14*(m3*m9-m4*m8)+m2*(m19*m8-m17*m9) -(m19*m3-m17*m4)*m7) -m10*(m12*(m3*m9-m4*m8)+m2*(m16*m8-m15*m9) -(m16*m3-m15*m4)*m7) +m1*((-m12*(m19*m8-m17*m9))+m14*(m16*m8-m15*m9) +(m15*m19-m16*m17)*m7) -((-m12*(m19*m3-m17*m4))+m14*(m16*m3-m15*m4) +(m15*m19-m16*m17)*m2) *m6)) +m3*(m7*(m14*(m3*m9-m4*m8)+m2*(m19*m8-m17*m9) -(m19*m3-m17*m4)*m7) -m10*(m11*(m3*m9-m4*m8)+m2*(m13*m8-m12*m9) -(m13*m3-m12*m4)*m7) +m1*((-m11*(m19*m8-m17*m9))+m14*(m13*m8-m12*m9) +(m12*m19-m13*m17)*m7) -((-m11*(m19*m3-m17*m4))+m14*(m13*m3-m12*m4) +(m12*m19-m13*m17)*m2) *m6) -m5*(m7*(m12*(m3*m9-m4*m8)+m2*(m16*m8-m15*m9) -(m16*m3-m15*m4)*m7) -m8*(m11*(m3*m9-m4*m8)+m2*(m13*m8-m12*m9) -(m13*m3-m12*m4)*m7) +m1*((-m11*(m16*m8-m15*m9))+m12*(m13*m8-m12*m9) +(m12*m16-m13*m15)*m7) -((-m11*(m16*m3-m15*m4))+m12*(m13*m3-m12*m4) +(m12*m16-m13*m15)*m2) *m6) -m0*((-m7*((-m12*(m19*m8-m17*m9))+m14*(m16*m8-m15*m9) +(m15*m19-m16*m17)*m7)) +m8*((-m11*(m19*m8-m17*m9))+m14*(m13*m8-m12*m9) +(m12*m19-m13*m17)*m7) -m10*((-m11*(m16*m8-m15*m9))+m12*(m13*m8-m12*m9) +(m12*m16-m13*m15)*m7) +(m11*(m15*m19-m16*m17)-m12*(m12*m19-m13*m17) +m14*(m12*m16-m13*m15)) *m6) +m1*(((-m11*(m19*m3-m17*m4))+m14*(m13*m3-m12*m4) +(m12*m19-m13*m17)*m2) *m8 -((-m12*(m19*m3-m17*m4))+m14*(m16*m3-m15*m4) +(m15*m19-m16*m17)*m2) *m7 -m10*((-m11*(m16*m3-m15*m4))+m12*(m13*m3-m12*m4) +(m12*m16-m13*m15)*m2) +m1*(m11*(m15*m19-m16*m17)-m12*(m12*m19-m13*m17) +m14*(m12*m16-m13*m15)))], [(-m7*(m12*(m16*(m10*m4-m5*m9)+m3*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m8) -m13*(m15*(m10*m4-m5*m9)+m3*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m8) +m2*((-m15*(m19*m9-m10*m18))+m16*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m8) -((-m15*(m19*m4-m18*m5))+m16*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m3) *m7)) +m8*(m11*(m16*(m10*m4-m5*m9)+m3*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m8) -m13*(m12*(m10*m4-m5*m9)+m3*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m8) +m2*((-m12*(m19*m9-m10*m18))+m16*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m8) -((-m12*(m19*m4-m18*m5))+m16*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m3) *m7) -m9*(m11*(m15*(m10*m4-m5*m9)+m3*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m8) -m12*(m12*(m10*m4-m5*m9)+m3*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m8) +m2*((-m12*(m17*m9-m10*m16))+m15*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m8) -((-m12*(m17*m4-m16*m5))+m15*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m3) *m7) -m1*((-m11*((-m15*(m19*m9-m10*m18))+m16*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m8)) +m12*((-m12*(m19*m9-m10*m18))+m16*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m8) -m13*((-m12*(m17*m9-m10*m16))+m15*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m8) +(m12*(m16*m19-m17*m18)-m15*(m13*m19-m14*m18) +m16*(m13*m17-m14*m16)) *m7) +((-m11*((-m15*(m19*m4-m18*m5))+m16*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m3)) +m12*((-m12*(m19*m4-m18*m5))+m16*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m3) -m13*((-m12*(m17*m4-m16*m5))+m15*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m3) +(m12*(m16*m19-m17*m18)-m15*(m13*m19-m14*m18) +m16*(m13*m17-m14*m16)) *m2) *m6, m2*(m12*(m16*(m10*m4-m5*m9)+m3*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m8) -m13*(m15*(m10*m4-m5*m9)+m3*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m8) +m2*((-m15*(m19*m9-m10*m18))+m16*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m8) -((-m15*(m19*m4-m18*m5))+m16*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m3) *m7) -m3*(m11*(m16*(m10*m4-m5*m9)+m3*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m8) -m13*(m12*(m10*m4-m5*m9)+m3*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m8) +m2*((-m12*(m19*m9-m10*m18))+m16*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m8) -((-m12*(m19*m4-m18*m5))+m16*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m3) *m7) +m4*(m11*(m15*(m10*m4-m5*m9)+m3*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m8) -m12*(m12*(m10*m4-m5*m9)+m3*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m8) +m2*((-m12*(m17*m9-m10*m16))+m15*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m8) -((-m12*(m17*m4-m16*m5))+m15*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m3) *m7) +m0*((-m11*((-m15*(m19*m9-m10*m18))+m16*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m8)) +m12*((-m12*(m19*m9-m10*m18))+m16*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m8) -m13*((-m12*(m17*m9-m10*m16))+m15*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m8) +(m12*(m16*m19-m17*m18)-m15*(m13*m19-m14*m18) +m16*(m13*m17-m14*m16)) *m7) -m1*((-m11*((-m15*(m19*m4-m18*m5))+m16*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m3)) +m12*((-m12*(m19*m4-m18*m5))+m16*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m3) -m13*((-m12*(m17*m4-m16*m5))+m15*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m3) +(m12*(m16*m19-m17*m18)-m15*(m13*m19-m14*m18) +m16*(m13*m17-m14*m16)) *m2), (-m2*(m8*(m16*(m10*m4-m5*m9)+m3*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m8) -m9*(m15*(m10*m4-m5*m9)+m3*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m8) +m1*((-m15*(m19*m9-m10*m18))+m16*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m8) -((-m15*(m19*m4-m18*m5))+m16*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m3) *m6)) +m3*(m7*(m16*(m10*m4-m5*m9)+m3*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m8) -m9*(m12*(m10*m4-m5*m9)+m3*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m8) +m1*((-m12*(m19*m9-m10*m18))+m16*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m8) -((-m12*(m19*m4-m18*m5))+m16*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m3) *m6) -m4*(m7*(m15*(m10*m4-m5*m9)+m3*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m8) -m8*(m12*(m10*m4-m5*m9)+m3*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m8) +m1*((-m12*(m17*m9-m10*m16))+m15*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m8) -((-m12*(m17*m4-m16*m5))+m15*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m3) *m6) -m0*((-m7*((-m15*(m19*m9-m10*m18))+m16*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m8)) +m8*((-m12*(m19*m9-m10*m18))+m16*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m8) -m9*((-m12*(m17*m9-m10*m16))+m15*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m8) +(m12*(m16*m19-m17*m18)-m15*(m13*m19-m14*m18) +m16*(m13*m17-m14*m16)) *m6) +m1*((-((-m12*(m17*m4-m16*m5))+m15*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m3) *m9) +((-m12*(m19*m4-m18*m5))+m16*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m3) *m8 -((-m15*(m19*m4-m18*m5))+m16*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m3) *m7 +m1*(m12*(m16*m19-m17*m18)-m15*(m13*m19-m14*m18) +m16*(m13*m17-m14*m16))), m2*(m8*(m13*(m10*m4-m5*m9)+m2*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m7) -m9*(m12*(m10*m4-m5*m9)+m2*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m7) +m1*((-m12*(m19*m9-m10*m18))+m13*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m7) -((-m12*(m19*m4-m18*m5))+m13*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m2) *m6) -m3*(m7*(m13*(m10*m4-m5*m9)+m2*(m19*m9-m10*m18) -(m19*m4-m18*m5)*m7) -m9*(m11*(m10*m4-m5*m9)+m2*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m7) +m1*((-m11*(m19*m9-m10*m18))+m13*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m7) -((-m11*(m19*m4-m18*m5))+m13*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m2) *m6) +m4*(m7*(m12*(m10*m4-m5*m9)+m2*(m17*m9-m10*m16) -(m17*m4-m16*m5)*m7) -m8*(m11*(m10*m4-m5*m9)+m2*(m14*m9-m10*m13) -(m14*m4-m13*m5)*m7) +m1*((-m11*(m17*m9-m10*m16))+m12*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m7) -((-m11*(m17*m4-m16*m5))+m12*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m2) *m6) +m0*((-m7*((-m12*(m19*m9-m10*m18))+m13*(m17*m9-m10*m16) +(m16*m19-m17*m18)*m7)) +m8*((-m11*(m19*m9-m10*m18))+m13*(m14*m9-m10*m13) +(m13*m19-m14*m18)*m7) -m9*((-m11*(m17*m9-m10*m16))+m12*(m14*m9-m10*m13) +(m13*m17-m14*m16)*m7) +(m11*(m16*m19-m17*m18)-m12*(m13*m19-m14*m18) +m13*(m13*m17-m14*m16)) *m6) -m1*((-((-m11*(m17*m4-m16*m5))+m12*(m14*m4-m13*m5) +(m13*m17-m14*m16)*m2) *m9) +((-m11*(m19*m4-m18*m5))+m13*(m14*m4-m13*m5) +(m13*m19-m14*m18)*m2) *m8 -((-m12*(m19*m4-m18*m5))+m13*(m17*m4-m16*m5) +(m16*m19-m17*m18)*m2) *m7 +m1*(m11*(m16*m19-m17*m18)-m12*(m13*m19-m14*m18) +m13*(m13*m17-m14*m16))), (-m2*((-(m12*(m10*m3-m5*m8)+m2*(m17*m8-m10*m15) -(m17*m3-m15*m5)*m7) *m9) +m8*(m13*(m10*m3-m5*m8)+m2*(m19*m8-m10*m16) -(m19*m3-m16*m5)*m7) +m1*((-m12*(m19*m8-m10*m16))+m13*(m17*m8-m10*m15) +(m15*m19-m16*m17)*m7) -((-m12*(m19*m3-m16*m5))+m13*(m17*m3-m15*m5) +(m15*m19-m16*m17)*m2) *m6)) +m3*((-(m11*(m10*m3-m5*m8)+m2*(m14*m8-m10*m12) -(m14*m3-m12*m5)*m7) *m9) +m7*(m13*(m10*m3-m5*m8)+m2*(m19*m8-m10*m16) -(m19*m3-m16*m5)*m7) +m1*((-m11*(m19*m8-m10*m16))+m13*(m14*m8-m10*m12) +(m12*m19-m14*m16)*m7) -((-m11*(m19*m3-m16*m5))+m13*(m14*m3-m12*m5) +(m12*m19-m14*m16)*m2) *m6) -m0*((-((-m11*(m17*m8-m10*m15))+m12*(m14*m8-m10*m12) +(m12*m17-m14*m15)*m7) *m9) -m7*((-m12*(m19*m8-m10*m16))+m13*(m17*m8-m10*m15) +(m15*m19-m16*m17)*m7) +m8*((-m11*(m19*m8-m10*m16))+m13*(m14*m8-m10*m12) +(m12*m19-m14*m16)*m7) +(m11*(m15*m19-m16*m17)-m12*(m12*m19-m14*m16) +m13*(m12*m17-m14*m15)) *m6) +m1*((-((-m11*(m17*m3-m15*m5))+m12*(m14*m3-m12*m5) +(m12*m17-m14*m15)*m2) *m9) +((-m11*(m19*m3-m16*m5))+m13*(m14*m3-m12*m5) +(m12*m19-m14*m16)*m2) *m8 -((-m12*(m19*m3-m16*m5))+m13*(m17*m3-m15*m5) +(m15*m19-m16*m17)*m2) *m7 +m1*(m11*(m15*m19-m16*m17)-m12*(m12*m19-m14*m16) +m13*(m12*m17-m14*m15))) -m4*(m7*(m12*(m10*m3-m5*m8)+m2*(m17*m8-m10*m15) -(m17*m3-m15*m5)*m7) -m8*(m11*(m10*m3-m5*m8)+m2*(m14*m8-m10*m12) -(m14*m3-m12*m5)*m7) +m1*((-m11*(m17*m8-m10*m15))+m12*(m14*m8-m10*m12) +(m12*m17-m14*m15)*m7) -((-m11*(m17*m3-m15*m5))+m12*(m14*m3-m12*m5) +(m12*m17-m14*m15)*m2) *m6), m2*(m8*(m13*(m3*m9-m4*m8)+m2*(m18*m8-m16*m9) -(m18*m3-m16*m4)*m7) -m9*(m12*(m3*m9-m4*m8)+m2*(m16*m8-m15*m9) -(m16*m3-m15*m4)*m7) +m1*((-m12*(m18*m8-m16*m9))+m13*(m16*m8-m15*m9) +(m15*m18-m16^2)*m7) -((-m12*(m18*m3-m16*m4))+m13*(m16*m3-m15*m4) +(m15*m18-m16^2)*m2) *m6) -m3*(m7*(m13*(m3*m9-m4*m8)+m2*(m18*m8-m16*m9) -(m18*m3-m16*m4)*m7) -m9*(m11*(m3*m9-m4*m8)+m2*(m13*m8-m12*m9) -(m13*m3-m12*m4)*m7) +m1*((-m11*(m18*m8-m16*m9))+m13*(m13*m8-m12*m9) +(m12*m18-m13*m16)*m7) -((-m11*(m18*m3-m16*m4))+m13*(m13*m3-m12*m4) +(m12*m18-m13*m16)*m2) *m6) +m4*(m7*(m12*(m3*m9-m4*m8)+m2*(m16*m8-m15*m9) -(m16*m3-m15*m4)*m7) -m8*(m11*(m3*m9-m4*m8)+m2*(m13*m8-m12*m9) -(m13*m3-m12*m4)*m7) +m1*((-m11*(m16*m8-m15*m9))+m12*(m13*m8-m12*m9) +(m12*m16-m13*m15)*m7) -((-m11*(m16*m3-m15*m4))+m12*(m13*m3-m12*m4) +(m12*m16-m13*m15)*m2) *m6) +m0*((-m7*((-m12*(m18*m8-m16*m9))+m13*(m16*m8-m15*m9) +(m15*m18-m16^2)*m7)) +m8*((-m11*(m18*m8-m16*m9))+m13*(m13*m8-m12*m9) +(m12*m18-m13*m16)*m7) -m9*((-m11*(m16*m8-m15*m9))+m12*(m13*m8-m12*m9) +(m12*m16-m13*m15)*m7) +(m11*(m15*m18-m16^2)-m12*(m12*m18-m13*m16) +m13*(m12*m16-m13*m15)) *m6) -m1*((-((-m11*(m16*m3-m15*m4))+m12*(m13*m3-m12*m4) +(m12*m16-m13*m15)*m2) *m9) +((-m11*(m18*m3-m16*m4))+m13*(m13*m3-m12*m4) +(m12*m18-m13*m16)*m2) *m8 -((-m12*(m18*m3-m16*m4))+m13*(m16*m3-m15*m4) +(m15*m18-m16^2)*m2) *m7 +m1*(m11*(m15*m18-m16^2)-m12*(m12*m18-m13*m16) +m13*(m12*m16-m13*m15)))]) Test program: void main(void) { const double a[] = { 1.9826929 , 0.49539104, 1.21536243, 0.98610923, 1.68623959, 1.0331091 , 1.96643809, 1.42962549, 0.9336305 , 1.96542156, 0.6086516 , 0.81542249, 0.74012536, 0.83940333, 1.58604071, 0.1338364 , 1.03314221, 0.44817192, 1.97146512, 0.27591278, 1.51474051 }; double c[21]; int N=6; double det = cofactors_sym6(a, c); printf("det = %f\n", det); printf("\n\n"); double p[36] = {}; for(int iout=0; iout m.*m, m. -> m[.] (%i36) determinant(sym2); (%o36) m0*m2-m1^2 (%i37) determinant(sym3); (%o37) m0*(m3*m5-m4^2)-m1*(m1*m5-m2*m4)+m2*(m1*m4-m2*m3) (%i38) determinant(sym4); (%o38) m0*(m4*(m7*m9-m8^2)-m5*(m5*m9-m6*m8)+m6*(m5*m8-m6*m7)) -m1*(m1*(m7*m9-m8^2)-m5*(m2*m9-m3*m8)+m6*(m2*m8-m3*m7)) +m2*(m1*(m5*m9-m6*m8)-m4*(m2*m9-m3*m8)+m6*(m2*m6-m3*m5)) -m3*(m1*(m5*m8-m6*m7)-m4*(m2*m8-m3*m7)+m5*(m2*m6-m3*m5)) (%i100) determinant(sym5); (%o100) -m3*(-m8*((m3*m8-m4*m7)*m9+m2*(m11*m7-m10*m8)-(m11*m3-m10*m4)*m6) +m1*(-(m14*m7-m13*m8)*m9+m11*(m11*m7-m10*m8)+(m10*m14-m11*m13)*m6) -m5*(-(m14*m3-m13*m4)*m9+m11*(m11*m3-m10*m4)+(m10*m14-m11*m13)*m2) +m6*(m11*(m3*m8-m4*m7)+m2*(m14*m7-m13*m8)-(m14*m3-m13*m4)*m6)) +m4*(-m7*((m3*m8-m4*m7)*m9+m2*(m11*m7-m10*m8)-(m11*m3-m10*m4)*m6) +m1*(-(m13*m7-m12*m8)*m9+m10*(m11*m7-m10*m8) +(m10*m13-m11*m12)*m6) -m5*(-(m13*m3-m12*m4)*m9+m10*(m11*m3-m10*m4) +(m10*m13-m11*m12)*m2) +m6*(m10*(m3*m8-m4*m7)+m2*(m13*m7-m12*m8)-(m13*m3-m12*m4)*m6)) +m0*(m7*(-(m14*m7-m13*m8)*m9+m11*(m11*m7-m10*m8) +(m10*m14-m11*m13)*m6) -m8*(-(m13*m7-m12*m8)*m9+m10*(m11*m7-m10*m8) +(m10*m13-m11*m12)*m6) +m5*((m12*m14-m13^2)*m9-m10*(m10*m14-m11*m13) +m11*(m10*m13-m11*m12)) -m6*(-m10*(m14*m7-m13*m8)+m11*(m13*m7-m12*m8) +(m12*m14-m13^2)*m6)) -m1*(m7*(-(m14*m3-m13*m4)*m9+m11*(m11*m3-m10*m4) +(m10*m14-m11*m13)*m2) -m8*(-(m13*m3-m12*m4)*m9+m10*(m11*m3-m10*m4) +(m10*m13-m11*m12)*m2) +m1*((m12*m14-m13^2)*m9-m10*(m10*m14-m11*m13) +m11*(m10*m13-m11*m12)) -(-m10*(m14*m3-m13*m4)+m11*(m13*m3-m12*m4)+(m12*m14-m13^2)*m2) *m6) +m2*(m7*(m11*(m3*m8-m4*m7)+m2*(m14*m7-m13*m8)-(m14*m3-m13*m4)*m6) -m8*(m10*(m3*m8-m4*m7)+m2*(m13*m7-m12*m8)-(m13*m3-m12*m4)*m6) +m1*(-m10*(m14*m7-m13*m8)+m11*(m13*m7-m12*m8)+(m12*m14-m13^2)*m6) -(-m10*(m14*m3-m13*m4)+m11*(m13*m3-m12*m4)+(m12*m14-m13^2)*m2) *m5) */ #if 0 #error You really should be using the cofactors functions below to do this. So far Ive only needed the determinant as a part of computing the inverse, and the below functions do this much more efficiently static inline double det_sym2(const double* m) { return m[0]*m[2]-m[1]*m[1]; } static inline double det_sym3(const double* m) { return m[0]*(m[3]*m[5]-m[4]*m[4])-m[1]*(m[1]*m[5]-m[2]*m[4])+m[2]*(m[1]*m[4]-m[2]*m[3]); } static inline double det_sym4(const double* m) { return +m[0]*(m[4]*(m[7]*m[9]-m[8]*m[8])-m[5]*(m[5]*m[9]-m[6]*m[8])+m[6]*(m[5]*m[8]-m[6]*m[7])) -m[1]*(m[1]*(m[7]*m[9]-m[8]*m[8])-m[5]*(m[2]*m[9]-m[3]*m[8])+m[6]*(m[2]*m[8]-m[3]*m[7])) +m[2]*(m[1]*(m[5]*m[9]-m[6]*m[8])-m[4]*(m[2]*m[9]-m[3]*m[8])+m[6]*(m[2]*m[6]-m[3]*m[5])) -m[3]*(m[1]*(m[5]*m[8]-m[6]*m[7])-m[4]*(m[2]*m[8]-m[3]*m[7])+m[5]*(m[2]*m[6]-m[3]*m[5])); } static inline double det_sym5(const double* m) { return -m[3]*(-m[8]*((m[3]*m[8]-m[4]*m[7])*m[9]+m[2]*(m[11]*m[7]-m[10]*m[8])-(m[11]*m[3]-m[10]*m[4])*m[6]) +m[1]*(-(m[14]*m[7]-m[13]*m[8])*m[9]+m[11]*(m[11]*m[7]-m[10]*m[8])+(m[10]*m[14]-m[11]*m[13])*m[6]) -m[5]*(-(m[14]*m[3]-m[13]*m[4])*m[9]+m[11]*(m[11]*m[3]-m[10]*m[4])+(m[10]*m[14]-m[11]*m[13])*m[2]) +m[6]*(m[11]*(m[3]*m[8]-m[4]*m[7])+m[2]*(m[14]*m[7]-m[13]*m[8])-(m[14]*m[3]-m[13]*m[4])*m[6])) +m[4]*(-m[7]*((m[3]*m[8]-m[4]*m[7])*m[9]+m[2]*(m[11]*m[7]-m[10]*m[8])-(m[11]*m[3]-m[10]*m[4])*m[6]) +m[1]*(-(m[13]*m[7]-m[12]*m[8])*m[9]+m[10]*(m[11]*m[7]-m[10]*m[8]) +(m[10]*m[13]-m[11]*m[12])*m[6]) -m[5]*(-(m[13]*m[3]-m[12]*m[4])*m[9]+m[10]*(m[11]*m[3]-m[10]*m[4]) +(m[10]*m[13]-m[11]*m[12])*m[2]) +m[6]*(m[10]*(m[3]*m[8]-m[4]*m[7])+m[2]*(m[13]*m[7]-m[12]*m[8])-(m[13]*m[3]-m[12]*m[4])*m[6])) +m[0]*(m[7]*(-(m[14]*m[7]-m[13]*m[8])*m[9]+m[11]*(m[11]*m[7]-m[10]*m[8]) +(m[10]*m[14]-m[11]*m[13])*m[6]) -m[8]*(-(m[13]*m[7]-m[12]*m[8])*m[9]+m[10]*(m[11]*m[7]-m[10]*m[8]) +(m[10]*m[13]-m[11]*m[12])*m[6]) +m[5]*((m[12]*m[14]-m[13]*m[13])*m[9]-m[10]*(m[10]*m[14]-m[11]*m[13]) +m[11]*(m[10]*m[13]-m[11]*m[12])) -m[6]*(-m[10]*(m[14]*m[7]-m[13]*m[8])+m[11]*(m[13]*m[7]-m[12]*m[8]) +(m[12]*m[14]-m[13]*m[13])*m[6])) -m[1]*(m[7]*(-(m[14]*m[3]-m[13]*m[4])*m[9]+m[11]*(m[11]*m[3]-m[10]*m[4]) +(m[10]*m[14]-m[11]*m[13])*m[2]) -m[8]*(-(m[13]*m[3]-m[12]*m[4])*m[9]+m[10]*(m[11]*m[3]-m[10]*m[4]) +(m[10]*m[13]-m[11]*m[12])*m[2]) +m[1]*((m[12]*m[14]-m[13]*m[13])*m[9]-m[10]*(m[10]*m[14]-m[11]*m[13]) +m[11]*(m[10]*m[13]-m[11]*m[12])) -(-m[10]*(m[14]*m[3]-m[13]*m[4])+m[11]*(m[13]*m[3]-m[12]*m[4])+(m[12]*m[14]-m[13]*m[13])*m[2]) *m[6]) +m[2]*(m[7]*(m[11]*(m[3]*m[8]-m[4]*m[7])+m[2]*(m[14]*m[7]-m[13]*m[8])-(m[14]*m[3]-m[13]*m[4])*m[6]) -m[8]*(m[10]*(m[3]*m[8]-m[4]*m[7])+m[2]*(m[13]*m[7]-m[12]*m[8])-(m[13]*m[3]-m[12]*m[4])*m[6]) +m[1]*(-m[10]*(m[14]*m[7]-m[13]*m[8])+m[11]*(m[13]*m[7]-m[12]*m[8])+(m[12]*m[14]-m[13]*m[13])*m[6]) -(-m[10]*(m[14]*m[3]-m[13]*m[4])+m[11]*(m[13]*m[3]-m[12]*m[4])+(m[12]*m[14]-m[13]*m[13])*m[2]) *m[5]); } #endif /* I now do inverses. I return transposed cofactors. Original matrix * cofactors / det = identity As before, I replaced m.^2 -> m.*m, m. -> m[.] I also removed the lower triangle, since I'm dealing with symmetric matrices here Session: (%i64) num( ev(invert(sym2),detout) ); (%o64) matrix([m2,-m1],[-m1,m0]) (%i65) num( ev(invert(sym3),detout) ); (%o65) matrix([m3*m5-m4^2,m2*m4-m1*m5,m1*m4-m2*m3], [m2*m4-m1*m5,m0*m5-m2^2,m1*m2-m0*m4], [m1*m4-m2*m3,m1*m2-m0*m4,m0*m3-m1^2]) (%i66) num( ev(invert(sym4),detout) ); (%o66) matrix([m4*(m7*m9-m8^2)-m5*(m5*m9-m6*m8)+m6*(m5*m8-m6*m7), -m1*(m7*m9-m8^2)+m2*(m5*m9-m6*m8)-m3*(m5*m8-m6*m7), m1*(m5*m9-m6*m8)-m2*(m4*m9-m6^2)+m3*(m4*m8-m5*m6), -m1*(m5*m8-m6*m7)+m2*(m4*m8-m5*m6)-m3*(m4*m7-m5^2)], [-m1*(m7*m9-m8^2)+m5*(m2*m9-m3*m8)-m6*(m2*m8-m3*m7), m0*(m7*m9-m8^2)-m2*(m2*m9-m3*m8)+m3*(m2*m8-m3*m7), -m0*(m5*m9-m6*m8)+m2*(m1*m9-m3*m6)-m3*(m1*m8-m3*m5), m0*(m5*m8-m6*m7)-m2*(m1*m8-m2*m6)+m3*(m1*m7-m2*m5)], [m1*(m5*m9-m6*m8)-m4*(m2*m9-m3*m8)+m6*(m2*m6-m3*m5), -m0*(m5*m9-m6*m8)+m1*(m2*m9-m3*m8)-m3*(m2*m6-m3*m5), m0*(m4*m9-m6^2)-m1*(m1*m9-m3*m6)+m3*(m1*m6-m3*m4), -m0*(m4*m8-m5*m6)+m1*(m1*m8-m2*m6)-m3*(m1*m5-m2*m4)], [-m1*(m5*m8-m6*m7)+m4*(m2*m8-m3*m7)-m5*(m2*m6-m3*m5), m0*(m5*m8-m6*m7)-m1*(m2*m8-m3*m7)+m2*(m2*m6-m3*m5), -m0*(m4*m8-m5*m6)+m1*(m1*m8-m3*m5)-m2*(m1*m6-m3*m4), m0*(m4*m7-m5^2)-m1*(m1*m7-m2*m5)+m2*(m1*m5-m2*m4)]) (%i103) num( ev(invert(sym5),detout) ); (%o103) matrix([m7*(-(m14*m7-m13*m8)*m9+m11*(m11*m7-m10*m8) +(m10*m14-m11*m13)*m6) -m8*(-(m13*m7-m12*m8)*m9+m10*(m11*m7-m10*m8) +(m10*m13-m11*m12)*m6) +m5*((m12*m14-m13^2)*m9-m10*(m10*m14-m11*m13) +m11*(m10*m13-m11*m12)) -m6*(-m10*(m14*m7-m13*m8)+m11*(m13*m7-m12*m8) +(m12*m14-m13^2)*m6), -m3*(-(m14*m7-m13*m8)*m9+m11*(m11*m7-m10*m8) +(m10*m14-m11*m13)*m6) +m4*(-(m13*m7-m12*m8)*m9+m10*(m11*m7-m10*m8) +(m10*m13-m11*m12)*m6) -m1*((m12*m14-m13^2)*m9-m10*(m10*m14-m11*m13) +m11*(m10*m13-m11*m12)) +m2*(-m10*(m14*m7-m13*m8)+m11*(m13*m7-m12*m8) +(m12*m14-m13^2)*m6), -m2*(-m7*(m14*m7-m13*m8)+m8*(m13*m7-m12*m8) +(m12*m14-m13^2)*m5) +m3*(-m6*(m14*m7-m13*m8)+m8*(m11*m7-m10*m8) +(m10*m14-m11*m13)*m5) -m4*(-m6*(m13*m7-m12*m8)+m7*(m11*m7-m10*m8) +(m10*m13-m11*m12)*m5) +m1*((m10*m13-m11*m12)*m8-(m10*m14-m11*m13)*m7 +(m12*m14-m13^2)*m6), -m3*(m8*(m11*m6-m8*m9)+m5*(m14*m9-m11^2)-m6*(m14*m6-m11*m8)) +m4*(m7*(m11*m6-m8*m9)+m5*(m13*m9-m10*m11) -m6*(m13*m6-m10*m8)) -m1*(-m7*(m14*m9-m11^2)+m8*(m13*m9-m10*m11) +(m10*m14-m11*m13)*m6) +m2*(-m7*(m14*m6-m11*m8)+m8*(m13*m6-m10*m8) +(m10*m14-m11*m13)*m5), m3*(m8*(m10*m6-m7*m9)+m5*(m13*m9-m10*m11)-m6*(m13*m6-m11*m7)) -m4*(m7*(m10*m6-m7*m9)+m5*(m12*m9-m10^2)-m6*(m12*m6-m10*m7)) +m1*(-m7*(m13*m9-m10*m11)+m8*(m12*m9-m10^2) +(m10*m13-m11*m12)*m6) -m2*((m12*m6-m10*m7)*m8-m7*(m13*m6-m11*m7) +(m10*m13-m11*m12)*m5)], [-m7*(-(m14*m3-m13*m4)*m9+m11*(m11*m3-m10*m4) +(m10*m14-m11*m13)*m2) +m8*(-(m13*m3-m12*m4)*m9+m10*(m11*m3-m10*m4) +(m10*m13-m11*m12)*m2) -m1*((m12*m14-m13^2)*m9-m10*(m10*m14-m11*m13) +m11*(m10*m13-m11*m12)) +(-m10*(m14*m3-m13*m4)+m11*(m13*m3-m12*m4) +(m12*m14-m13^2)*m2) *m6, m3*(-(m14*m3-m13*m4)*m9+m11*(m11*m3-m10*m4) +(m10*m14-m11*m13)*m2) -m4*(-(m13*m3-m12*m4)*m9+m10*(m11*m3-m10*m4) +(m10*m13-m11*m12)*m2) +m0*((m12*m14-m13^2)*m9-m10*(m10*m14-m11*m13) +m11*(m10*m13-m11*m12)) -m2*(-m10*(m14*m3-m13*m4)+m11*(m13*m3-m12*m4) +(m12*m14-m13^2)*m2), m2*((m13*m3-m12*m4)*m8-(m14*m3-m13*m4)*m7+m1*(m12*m14-m13^2)) -m3*((m11*m3-m10*m4)*m8-(m14*m3-m13*m4)*m6 +m1*(m10*m14-m11*m13)) -m0*((m10*m13-m11*m12)*m8-(m10*m14-m11*m13)*m7 +(m12*m14-m13^2)*m6) +m4*((m11*m3-m10*m4)*m7-(m13*m3-m12*m4)*m6 +m1*(m10*m13-m11*m12)), m3*(m8*(m11*m2-m4*m9)+m1*(m14*m9-m11^2)-(m14*m2-m11*m4)*m6) -m4*(m7*(m11*m2-m4*m9)+m1*(m13*m9-m10*m11) -(m13*m2-m10*m4)*m6) +m0*(-m7*(m14*m9-m11^2)+m8*(m13*m9-m10*m11) +(m10*m14-m11*m13)*m6) -m2*((m13*m2-m10*m4)*m8-(m14*m2-m11*m4)*m7 +m1*(m10*m14-m11*m13)), -m3*(m8*(m10*m2-m3*m9)+m1*(m13*m9-m10*m11)-(m13*m2-m11*m3)*m6) +m4*(m7*(m10*m2-m3*m9)+m1*(m12*m9-m10^2)-(m12*m2-m10*m3)*m6) -m0*(-m7*(m13*m9-m10*m11)+m8*(m12*m9-m10^2) +(m10*m13-m11*m12)*m6) +m2*((m12*m2-m10*m3)*m8-(m13*m2-m11*m3)*m7 +m1*(m10*m13-m11*m12))], [m7*(m11*(m3*m8-m4*m7)+m2*(m14*m7-m13*m8)-(m14*m3-m13*m4)*m6) -m8*(m10*(m3*m8-m4*m7)+m2*(m13*m7-m12*m8)-(m13*m3-m12*m4)*m6) +m1*(-m10*(m14*m7-m13*m8)+m11*(m13*m7-m12*m8) +(m12*m14-m13^2)*m6) -(-m10*(m14*m3-m13*m4)+m11*(m13*m3-m12*m4) +(m12*m14-m13^2)*m2) *m5, -m3*(m11*(m3*m8-m4*m7)+m2*(m14*m7-m13*m8)-(m14*m3-m13*m4)*m6) +m4*(m10*(m3*m8-m4*m7)+m2*(m13*m7-m12*m8)-(m13*m3-m12*m4)*m6) -m0*(-m10*(m14*m7-m13*m8)+m11*(m13*m7-m12*m8) +(m12*m14-m13^2)*m6) +m1*(-m10*(m14*m3-m13*m4)+m11*(m13*m3-m12*m4) +(m12*m14-m13^2)*m2), m3*(m8*(m3*m8-m4*m7)+m1*(m14*m7-m13*m8)-(m14*m3-m13*m4)*m5) -m4*(m7*(m3*m8-m4*m7)+m1*(m13*m7-m12*m8)-(m13*m3-m12*m4)*m5) +m0*(-m7*(m14*m7-m13*m8)+m8*(m13*m7-m12*m8) +(m12*m14-m13^2)*m5) -m1*((m13*m3-m12*m4)*m8-(m14*m3-m13*m4)*m7 +m1*(m12*m14-m13^2)), -m3*(m8*(m2*m8-m4*m6)+m1*(m14*m6-m11*m8)-(m14*m2-m11*m4)*m5) +m4*(m7*(m2*m8-m4*m6)+m1*(m13*m6-m10*m8)-(m13*m2-m10*m4)*m5) -m0*(-m7*(m14*m6-m11*m8)+m8*(m13*m6-m10*m8) +(m10*m14-m11*m13)*m5) +m1*((m13*m2-m10*m4)*m8-(m14*m2-m11*m4)*m7 +m1*(m10*m14-m11*m13)), m3*((m2*m7-m3*m6)*m8+m1*(m13*m6-m11*m7)-(m13*m2-m11*m3)*m5) +m0*((m12*m6-m10*m7)*m8-m7*(m13*m6-m11*m7) +(m10*m13-m11*m12)*m5) -m1*((m12*m2-m10*m3)*m8-(m13*m2-m11*m3)*m7 +m1*(m10*m13-m11*m12)) -m4*(m7*(m2*m7-m3*m6)+m1*(m12*m6-m10*m7) -(m12*m2-m10*m3)*m5)], [m8*((m3*m8-m4*m7)*m9+m2*(m11*m7-m10*m8)-(m11*m3-m10*m4)*m6) -m1*(-(m14*m7-m13*m8)*m9+m11*(m11*m7-m10*m8) +(m10*m14-m11*m13)*m6) +m5*(-(m14*m3-m13*m4)*m9+m11*(m11*m3-m10*m4) +(m10*m14-m11*m13)*m2) -m6*(m11*(m3*m8-m4*m7)+m2*(m14*m7-m13*m8) -(m14*m3-m13*m4)*m6), -m4*((m3*m8-m4*m7)*m9+m2*(m11*m7-m10*m8)-(m11*m3-m10*m4)*m6) +m0*(-(m14*m7-m13*m8)*m9+m11*(m11*m7-m10*m8) +(m10*m14-m11*m13)*m6) -m1*(-(m14*m3-m13*m4)*m9+m11*(m11*m3-m10*m4) +(m10*m14-m11*m13)*m2) +m2*(m11*(m3*m8-m4*m7)+m2*(m14*m7-m13*m8) -(m14*m3-m13*m4)*m6), -m2*(m8*(m3*m8-m4*m7)+m1*(m14*m7-m13*m8)-(m14*m3-m13*m4)*m5) +m4*(m6*(m3*m8-m4*m7)+m1*(m11*m7-m10*m8)-(m11*m3-m10*m4)*m5) -m0*(-m6*(m14*m7-m13*m8)+m8*(m11*m7-m10*m8) +(m10*m14-m11*m13)*m5) +m1*((m11*m3-m10*m4)*m8-(m14*m3-m13*m4)*m6 +m1*(m10*m14-m11*m13)), m0*(m8*(m11*m6-m8*m9)+m5*(m14*m9-m11^2)-m6*(m14*m6-m11*m8)) -m4*(m1*(m11*m6-m8*m9)-m5*(m11*m2-m4*m9)+m6*(m2*m8-m4*m6)) -m1*(m8*(m11*m2-m4*m9)+m1*(m14*m9-m11^2)-(m14*m2-m11*m4)*m6) +m2*(m8*(m2*m8-m4*m6)+m1*(m14*m6-m11*m8)-(m14*m2-m11*m4)*m5), -m0*(m8*(m10*m6-m7*m9)+m5*(m13*m9-m10*m11)-m6*(m13*m6-m11*m7)) +m4*(m1*(m10*m6-m7*m9)-m5*(m10*m2-m3*m9)+m6*(m2*m7-m3*m6)) +m1*(m8*(m10*m2-m3*m9)+m1*(m13*m9-m10*m11) -(m13*m2-m11*m3)*m6) -m2*((m2*m7-m3*m6)*m8+m1*(m13*m6-m11*m7) -(m13*m2-m11*m3)*m5)], [-m7*((m3*m8-m4*m7)*m9+m2*(m11*m7-m10*m8)-(m11*m3-m10*m4)*m6) +m1*(-(m13*m7-m12*m8)*m9+m10*(m11*m7-m10*m8) +(m10*m13-m11*m12)*m6) -m5*(-(m13*m3-m12*m4)*m9+m10*(m11*m3-m10*m4) +(m10*m13-m11*m12)*m2) +m6*(m10*(m3*m8-m4*m7)+m2*(m13*m7-m12*m8) -(m13*m3-m12*m4)*m6), m3*((m3*m8-m4*m7)*m9+m2*(m11*m7-m10*m8)-(m11*m3-m10*m4)*m6) -m0*(-(m13*m7-m12*m8)*m9+m10*(m11*m7-m10*m8) +(m10*m13-m11*m12)*m6) +m1*(-(m13*m3-m12*m4)*m9+m10*(m11*m3-m10*m4) +(m10*m13-m11*m12)*m2) -m2*(m10*(m3*m8-m4*m7)+m2*(m13*m7-m12*m8) -(m13*m3-m12*m4)*m6), m2*(m7*(m3*m8-m4*m7)+m1*(m13*m7-m12*m8)-(m13*m3-m12*m4)*m5) -m3*(m6*(m3*m8-m4*m7)+m1*(m11*m7-m10*m8)-(m11*m3-m10*m4)*m5) +m0*(-m6*(m13*m7-m12*m8)+m7*(m11*m7-m10*m8) +(m10*m13-m11*m12)*m5) -m1*((m11*m3-m10*m4)*m7-(m13*m3-m12*m4)*m6 +m1*(m10*m13-m11*m12)), -m0*(m7*(m11*m6-m8*m9)+m5*(m13*m9-m10*m11)-m6*(m13*m6-m10*m8)) +m3*(m1*(m11*m6-m8*m9)-m5*(m11*m2-m4*m9)+m6*(m2*m8-m4*m6)) +m1*(m7*(m11*m2-m4*m9)+m1*(m13*m9-m10*m11) -(m13*m2-m10*m4)*m6) -m2*(m7*(m2*m8-m4*m6)+m1*(m13*m6-m10*m8)-(m13*m2-m10*m4)*m5), m0*(m7*(m10*m6-m7*m9)+m5*(m12*m9-m10^2)-m6*(m12*m6-m10*m7)) -m3*(m1*(m10*m6-m7*m9)-m5*(m10*m2-m3*m9)+m6*(m2*m7-m3*m6)) -m1*(m7*(m10*m2-m3*m9)+m1*(m12*m9-m10^2)-(m12*m2-m10*m3)*m6) +m2*(m7*(m2*m7-m3*m6)+m1*(m12*m6-m10*m7) -(m12*m2-m10*m3)*m5)]) */ static inline double cofactors_sym2(const double* restrict m, double* restrict c) { c[0] = m[2]; c[1] = -m[1]; c[2] = -m[1]; return m[0]*c[0] + m[1]*c[1]; } static inline double cofactors_sym3(const double* restrict m, double* restrict c) { c[0] = m[3]*m[5]-m[4]*m[4]; c[1] = m[2]*m[4]-m[1]*m[5]; c[2] = m[1]*m[4]-m[2]*m[3]; c[3] = m[0]*m[5]-m[2]*m[2]; c[4] = m[1]*m[2]-m[0]*m[4]; c[5] = m[0]*m[3]-m[1]*m[1]; return m[0]*c[0] + m[1]*c[1] + m[2]*c[2]; } static inline double cofactors_sym4(const double* restrict m, double* restrict c) { c[0] = m[4]*(m[7]*m[9]-m[8]*m[8])-m[5]*(m[5]*m[9]-m[6]*m[8])+m[6]*(m[5]*m[8]-m[6]*m[7]); c[1] = -m[1]*(m[7]*m[9]-m[8]*m[8])+m[2]*(m[5]*m[9]-m[6]*m[8])-m[3]*(m[5]*m[8]-m[6]*m[7]); c[2] = m[1]*(m[5]*m[9]-m[6]*m[8])-m[2]*(m[4]*m[9]-m[6]*m[6])+m[3]*(m[4]*m[8]-m[5]*m[6]); c[3] = -m[1]*(m[5]*m[8]-m[6]*m[7])+m[2]*(m[4]*m[8]-m[5]*m[6])-m[3]*(m[4]*m[7]-m[5]*m[5]); c[4] = m[0]*(m[7]*m[9]-m[8]*m[8])-m[2]*(m[2]*m[9]-m[3]*m[8])+m[3]*(m[2]*m[8]-m[3]*m[7]); c[5] = -m[0]*(m[5]*m[9]-m[6]*m[8])+m[2]*(m[1]*m[9]-m[3]*m[6])-m[3]*(m[1]*m[8]-m[3]*m[5]); c[6] = m[0]*(m[5]*m[8]-m[6]*m[7])-m[2]*(m[1]*m[8]-m[2]*m[6])+m[3]*(m[1]*m[7]-m[2]*m[5]); c[7] = m[0]*(m[4]*m[9]-m[6]*m[6])-m[1]*(m[1]*m[9]-m[3]*m[6])+m[3]*(m[1]*m[6]-m[3]*m[4]); c[8] = -m[0]*(m[4]*m[8]-m[5]*m[6])+m[1]*(m[1]*m[8]-m[2]*m[6])-m[3]*(m[1]*m[5]-m[2]*m[4]); c[9] = m[0]*(m[4]*m[7]-m[5]*m[5])-m[1]*(m[1]*m[7]-m[2]*m[5])+m[2]*(m[1]*m[5]-m[2]*m[4]); return m[0]*c[0] + m[1]*c[1] + m[2]*c[2] + m[3]*c[3]; } static inline double cofactors_sym5(const double* restrict m, double* restrict c) { c[0] = m[7]*(-(m[14]*m[7]-m[13]*m[8])*m[9]+m[11]*(m[11]*m[7]-m[10]*m[8])+(m[10]*m[14]-m[11]*m[13])*m[6])-m[8]*(-(m[13]*m[7]-m[12]*m[8])*m[9]+m[10]*(m[11]*m[7]-m[10]*m[8])+(m[10]*m[13]-m[11]*m[12])*m[6])+m[5]*((m[12]*m[14]-m[13]*m[13])*m[9]-m[10]*(m[10]*m[14]-m[11]*m[13])+m[11]*(m[10]*m[13]-m[11]*m[12]))-m[6]*(-m[10]*(m[14]*m[7]-m[13]*m[8])+m[11]*(m[13]*m[7]-m[12]*m[8])+(m[12]*m[14]-m[13]*m[13])*m[6]); c[1] = -m[3]*(-(m[14]*m[7]-m[13]*m[8])*m[9]+m[11]*(m[11]*m[7]-m[10]*m[8])+(m[10]*m[14]-m[11]*m[13])*m[6])+m[4]*(-(m[13]*m[7]-m[12]*m[8])*m[9]+m[10]*(m[11]*m[7]-m[10]*m[8])+(m[10]*m[13]-m[11]*m[12])*m[6])-m[1]*((m[12]*m[14]-m[13]*m[13])*m[9]-m[10]*(m[10]*m[14]-m[11]*m[13])+m[11]*(m[10]*m[13]-m[11]*m[12]))+m[2]*(-m[10]*(m[14]*m[7]-m[13]*m[8])+m[11]*(m[13]*m[7]-m[12]*m[8])+(m[12]*m[14]-m[13]*m[13])*m[6]); c[2] = -m[2]*(-m[7]*(m[14]*m[7]-m[13]*m[8])+m[8]*(m[13]*m[7]-m[12]*m[8])+(m[12]*m[14]-m[13]*m[13])*m[5])+m[3]*(-m[6]*(m[14]*m[7]-m[13]*m[8])+m[8]*(m[11]*m[7]-m[10]*m[8])+(m[10]*m[14]-m[11]*m[13])*m[5])-m[4]*(-m[6]*(m[13]*m[7]-m[12]*m[8])+m[7]*(m[11]*m[7]-m[10]*m[8])+(m[10]*m[13]-m[11]*m[12])*m[5])+m[1]*((m[10]*m[13]-m[11]*m[12])*m[8]-(m[10]*m[14]-m[11]*m[13])*m[7]+(m[12]*m[14]-m[13]*m[13])*m[6]); c[3] = -m[3]*(m[8]*(m[11]*m[6]-m[8]*m[9])+m[5]*(m[14]*m[9]-m[11]*m[11])-m[6]*(m[14]*m[6]-m[11]*m[8]))+m[4]*(m[7]*(m[11]*m[6]-m[8]*m[9])+m[5]*(m[13]*m[9]-m[10]*m[11])-m[6]*(m[13]*m[6]-m[10]*m[8]))-m[1]*(-m[7]*(m[14]*m[9]-m[11]*m[11])+m[8]*(m[13]*m[9]-m[10]*m[11])+(m[10]*m[14]-m[11]*m[13])*m[6])+m[2]*(-m[7]*(m[14]*m[6]-m[11]*m[8])+m[8]*(m[13]*m[6]-m[10]*m[8])+(m[10]*m[14]-m[11]*m[13])*m[5]); c[4] = m[3]*(m[8]*(m[10]*m[6]-m[7]*m[9])+m[5]*(m[13]*m[9]-m[10]*m[11])-m[6]*(m[13]*m[6]-m[11]*m[7]))-m[4]*(m[7]*(m[10]*m[6]-m[7]*m[9])+m[5]*(m[12]*m[9]-m[10]*m[10])-m[6]*(m[12]*m[6]-m[10]*m[7]))+m[1]*(-m[7]*(m[13]*m[9]-m[10]*m[11])+m[8]*(m[12]*m[9]-m[10]*m[10])+(m[10]*m[13]-m[11]*m[12])*m[6])-m[2]*((m[12]*m[6]-m[10]*m[7])*m[8]-m[7]*(m[13]*m[6]-m[11]*m[7])+(m[10]*m[13]-m[11]*m[12])*m[5]); c[5] = m[3]*(-(m[14]*m[3]-m[13]*m[4])*m[9]+m[11]*(m[11]*m[3]-m[10]*m[4])+(m[10]*m[14]-m[11]*m[13])*m[2])-m[4]*(-(m[13]*m[3]-m[12]*m[4])*m[9]+m[10]*(m[11]*m[3]-m[10]*m[4])+(m[10]*m[13]-m[11]*m[12])*m[2])+m[0]*((m[12]*m[14]-m[13]*m[13])*m[9]-m[10]*(m[10]*m[14]-m[11]*m[13])+m[11]*(m[10]*m[13]-m[11]*m[12]))-m[2]*(-m[10]*(m[14]*m[3]-m[13]*m[4])+m[11]*(m[13]*m[3]-m[12]*m[4])+(m[12]*m[14]-m[13]*m[13])*m[2]); c[6] = m[2]*((m[13]*m[3]-m[12]*m[4])*m[8]-(m[14]*m[3]-m[13]*m[4])*m[7]+m[1]*(m[12]*m[14]-m[13]*m[13]))-m[3]*((m[11]*m[3]-m[10]*m[4])*m[8]-(m[14]*m[3]-m[13]*m[4])*m[6]+m[1]*(m[10]*m[14]-m[11]*m[13]))-m[0]*((m[10]*m[13]-m[11]*m[12])*m[8]-(m[10]*m[14]-m[11]*m[13])*m[7]+(m[12]*m[14]-m[13]*m[13])*m[6])+m[4]*((m[11]*m[3]-m[10]*m[4])*m[7]-(m[13]*m[3]-m[12]*m[4])*m[6]+m[1]*(m[10]*m[13]-m[11]*m[12])); c[7] = m[3]*(m[8]*(m[11]*m[2]-m[4]*m[9])+m[1]*(m[14]*m[9]-m[11]*m[11])-(m[14]*m[2]-m[11]*m[4])*m[6])-m[4]*(m[7]*(m[11]*m[2]-m[4]*m[9])+m[1]*(m[13]*m[9]-m[10]*m[11])-(m[13]*m[2]-m[10]*m[4])*m[6])+m[0]*(-m[7]*(m[14]*m[9]-m[11]*m[11])+m[8]*(m[13]*m[9]-m[10]*m[11])+(m[10]*m[14]-m[11]*m[13])*m[6])-m[2]*((m[13]*m[2]-m[10]*m[4])*m[8]-(m[14]*m[2]-m[11]*m[4])*m[7]+m[1]*(m[10]*m[14]-m[11]*m[13])); c[8] = -m[3]*(m[8]*(m[10]*m[2]-m[3]*m[9])+m[1]*(m[13]*m[9]-m[10]*m[11])-(m[13]*m[2]-m[11]*m[3])*m[6])+m[4]*(m[7]*(m[10]*m[2]-m[3]*m[9])+m[1]*(m[12]*m[9]-m[10]*m[10])-(m[12]*m[2]-m[10]*m[3])*m[6])-m[0]*(-m[7]*(m[13]*m[9]-m[10]*m[11])+m[8]*(m[12]*m[9]-m[10]*m[10])+(m[10]*m[13]-m[11]*m[12])*m[6])+m[2]*((m[12]*m[2]-m[10]*m[3])*m[8]-(m[13]*m[2]-m[11]*m[3])*m[7]+m[1]*(m[10]*m[13]-m[11]*m[12])); c[9] = m[3]*(m[8]*(m[3]*m[8]-m[4]*m[7])+m[1]*(m[14]*m[7]-m[13]*m[8])-(m[14]*m[3]-m[13]*m[4])*m[5])-m[4]*(m[7]*(m[3]*m[8]-m[4]*m[7])+m[1]*(m[13]*m[7]-m[12]*m[8])-(m[13]*m[3]-m[12]*m[4])*m[5])+m[0]*(-m[7]*(m[14]*m[7]-m[13]*m[8])+m[8]*(m[13]*m[7]-m[12]*m[8])+(m[12]*m[14]-m[13]*m[13])*m[5])-m[1]*((m[13]*m[3]-m[12]*m[4])*m[8]-(m[14]*m[3]-m[13]*m[4])*m[7]+m[1]*(m[12]*m[14]-m[13]*m[13])); c[10] = -m[3]*(m[8]*(m[2]*m[8]-m[4]*m[6])+m[1]*(m[14]*m[6]-m[11]*m[8])-(m[14]*m[2]-m[11]*m[4])*m[5])+m[4]*(m[7]*(m[2]*m[8]-m[4]*m[6])+m[1]*(m[13]*m[6]-m[10]*m[8])-(m[13]*m[2]-m[10]*m[4])*m[5])-m[0]*(-m[7]*(m[14]*m[6]-m[11]*m[8])+m[8]*(m[13]*m[6]-m[10]*m[8])+(m[10]*m[14]-m[11]*m[13])*m[5])+m[1]*((m[13]*m[2]-m[10]*m[4])*m[8]-(m[14]*m[2]-m[11]*m[4])*m[7]+m[1]*(m[10]*m[14]-m[11]*m[13])); c[11] = m[3]*((m[2]*m[7]-m[3]*m[6])*m[8]+m[1]*(m[13]*m[6]-m[11]*m[7])-(m[13]*m[2]-m[11]*m[3])*m[5])+m[0]*((m[12]*m[6]-m[10]*m[7])*m[8]-m[7]*(m[13]*m[6]-m[11]*m[7])+(m[10]*m[13]-m[11]*m[12])*m[5])-m[1]*((m[12]*m[2]-m[10]*m[3])*m[8]-(m[13]*m[2]-m[11]*m[3])*m[7]+m[1]*(m[10]*m[13]-m[11]*m[12]))-m[4]*(m[7]*(m[2]*m[7]-m[3]*m[6])+m[1]*(m[12]*m[6]-m[10]*m[7])-(m[12]*m[2]-m[10]*m[3])*m[5]); c[12] = m[0]*(m[8]*(m[11]*m[6]-m[8]*m[9])+m[5]*(m[14]*m[9]-m[11]*m[11])-m[6]*(m[14]*m[6]-m[11]*m[8]))-m[4]*(m[1]*(m[11]*m[6]-m[8]*m[9])-m[5]*(m[11]*m[2]-m[4]*m[9])+m[6]*(m[2]*m[8]-m[4]*m[6]))-m[1]*(m[8]*(m[11]*m[2]-m[4]*m[9])+m[1]*(m[14]*m[9]-m[11]*m[11])-(m[14]*m[2]-m[11]*m[4])*m[6])+m[2]*(m[8]*(m[2]*m[8]-m[4]*m[6])+m[1]*(m[14]*m[6]-m[11]*m[8])-(m[14]*m[2]-m[11]*m[4])*m[5]); c[13] = -m[0]*(m[8]*(m[10]*m[6]-m[7]*m[9])+m[5]*(m[13]*m[9]-m[10]*m[11])-m[6]*(m[13]*m[6]-m[11]*m[7]))+m[4]*(m[1]*(m[10]*m[6]-m[7]*m[9])-m[5]*(m[10]*m[2]-m[3]*m[9])+m[6]*(m[2]*m[7]-m[3]*m[6]))+m[1]*(m[8]*(m[10]*m[2]-m[3]*m[9])+m[1]*(m[13]*m[9]-m[10]*m[11])-(m[13]*m[2]-m[11]*m[3])*m[6])-m[2]*((m[2]*m[7]-m[3]*m[6])*m[8]+m[1]*(m[13]*m[6]-m[11]*m[7])-(m[13]*m[2]-m[11]*m[3])*m[5]); c[14] = m[0]*(m[7]*(m[10]*m[6]-m[7]*m[9])+m[5]*(m[12]*m[9]-m[10]*m[10])-m[6]*(m[12]*m[6]-m[10]*m[7]))-m[3]*(m[1]*(m[10]*m[6]-m[7]*m[9])-m[5]*(m[10]*m[2]-m[3]*m[9])+m[6]*(m[2]*m[7]-m[3]*m[6]))-m[1]*(m[7]*(m[10]*m[2]-m[3]*m[9])+m[1]*(m[12]*m[9]-m[10]*m[10])-(m[12]*m[2]-m[10]*m[3])*m[6])+m[2]*(m[7]*(m[2]*m[7]-m[3]*m[6])+m[1]*(m[12]*m[6]-m[10]*m[7])-(m[12]*m[2]-m[10]*m[3])*m[5]); return m[0]*c[0] + m[1]*c[1] + m[2]*c[2] + m[3]*c[3] + m[4]*c[4]; } /* The upper-triangular and lower-triangular routines have a similar API to the symmetric ones. Note that as with symmetric matrices, we don't store redundant data, and we store data row-first. So the upper-triangular matrices have N elements in the first row in memory, but lower-triangular matrices have only 1. Inverses of triangular matrices are similarly triangular, and that's how I store them Session: // upper triangular (%i2) ut2 : matrix([m0,m1],[0,m2]); (%o2) matrix([m0,m1],[0,m2]) (%i3) ut3 : matrix([m0,m1,m2],[0,m3,m4],[0,0,m5]); (%o3) matrix([m0,m1,m2],[0,m3,m4],[0,0,m5]) (%i4) ut4 : matrix([m0,m1,m2,m3],[0,m4,m5,m6],[0,0,m7,m8],[0,0,0,m9]); (%o4) matrix([m0,m1,m2,m3],[0,m4,m5,m6],[0,0,m7,m8],[0,0,0,m9]) (%i5) ut5 : matrix([m0,m1,m2,m3,m4],[0,m5,m6,m7,m8],[0,0,m9,m10,m11],[0,0,0,m12,m13],[0,0,0,0,m14]); (%o5) matrix([m0,m1,m2,m3,m4],[0,m5,m6,m7,m8],[0,0,m9,m10,m11], [0,0,0,m12,m13],[0,0,0,0,m14]) (%i11) num( ev(invert(ut2),detout) ); (%o11) matrix([m2,-m1],[0,m0]) (%i12) num( ev(invert(ut3),detout) ); (%o12) matrix([m3*m5,-m1*m5,m1*m4-m2*m3],[0,m0*m5,-m0*m4],[0,0,m0*m3]) (%i13) num( ev(invert(ut4),detout) ); (%o13) matrix([m4*m7*m9,-m1*m7*m9,m1*m5*m9-m2*m4*m9, (-m1*(m5*m8-m6*m7))+m2*m4*m8-m3*m4*m7], [0,m0*m7*m9,-m0*m5*m9,m0*(m5*m8-m6*m7)], [0,0,m0*m4*m9,-m0*m4*m8],[0,0,0,m0*m4*m7]) (%i14) num( ev(invert(ut5),detout) ); (%o14) matrix([m12*m14*m5*m9,-m1*m12*m14*m9,m1*m12*m14*m6-m12*m14*m2*m5, (-m1*(m10*m14*m6-m14*m7*m9))-m14*m3*m5*m9+m10*m14*m2*m5, m1*(m12*m8*m9-m13*m7*m9+(m10*m13-m11*m12)*m6) -m12*m4*m5*m9+m13*m3*m5*m9-(m10*m13-m11*m12)*m2*m5], [0,m0*m12*m14*m9,-m0*m12*m14*m6,m0*(m10*m14*m6-m14*m7*m9), -m0*(m12*m8*m9-m13*m7*m9+(m10*m13-m11*m12)*m6)], [0,0,m0*m12*m14*m5,-m0*m10*m14*m5,m0*(m10*m13-m11*m12)*m5], [0,0,0,m0*m14*m5*m9,-m0*m13*m5*m9],[0,0,0,0,m0*m12*m5*m9]) // lower-triangular (%i19) lt2 : matrix([m0,0],[m1,m2]); (%o19) matrix([m0,0],[m1,m2]) (%i20) lt3 : matrix([m0,0,0],[m1,m2,0],[m3,m4,m5]); (%o20) matrix([m0,0,0],[m1,m2,0],[m3,m4,m5]) (%i21) lt4 : matrix([m0,0,0,0],[m1,m2,0,0],[m3,m4,m5,0],[m6,m7,m8,m9]); (%o21) matrix([m0,0,0,0],[m1,m2,0,0],[m3,m4,m5,0],[m6,m7,m8,m9]) (%i22) lt5 : matrix([m0,0,0,0,0],[m1,m2,0,0,0],[m3,m4,m5,0,0],[m6,m7,m8,m9,0],[m10,m11,m12,m13,m14]); (%o22) matrix([m0,0,0,0,0],[m1,m2,0,0,0],[m3,m4,m5,0,0],[m6,m7,m8,m9,0], [m10,m11,m12,m13,m14]) (%i23) num( ev(invert(lt2),detout) ); (%o23) matrix([m2,0],[-m1,m0]) (%i24) num( ev(invert(lt3),detout) ); (%o24) matrix([m2*m5,0,0],[-m1*m5,m0*m5,0],[m1*m4-m2*m3,-m0*m4,m0*m2]) (%i25) num( ev(invert(lt4),detout) ); (%o25) matrix([m2*m5*m9,0,0,0],[-m1*m5*m9,m0*m5*m9,0,0], [m1*m4*m9-m2*m3*m9,-m0*m4*m9,m0*m2*m9,0], [m2*(m3*m8-m5*m6)-m1*(m4*m8-m5*m7),m0*(m4*m8-m5*m7),-m0*m2*m8, m0*m2*m5]) (%i26) num( ev(invert(lt5),detout) ); (%o26) matrix([m14*m2*m5*m9,0,0,0,0],[-m1*m14*m5*m9,m0*m14*m5*m9,0,0,0], [m1*m14*m4*m9-m14*m2*m3*m9,-m0*m14*m4*m9,m0*m14*m2*m9,0,0], [m2*(m14*m3*m8-m14*m5*m6)-m1*(m14*m4*m8-m14*m5*m7), m0*(m14*m4*m8-m14*m5*m7),-m0*m14*m2*m8,m0*m14*m2*m5,0], [m1*(m4*(m13*m8-m12*m9)-m5*(m13*m7-m11*m9)) -m2*(m3*(m13*m8-m12*m9)-m5*(m13*m6-m10*m9)), -m0*(m4*(m13*m8-m12*m9)-m5*(m13*m7-m11*m9)), m0*m2*(m13*m8-m12*m9),-m0*m13*m2*m5,m0*m2*m5*m9]) */ static inline double cofactors_ut2(const double* restrict m, double* restrict c) { int i=0; c[i++] = m[2]; c[i++] = -m[1]; c[i++] = m[0]; return m[0]*m[2]; } static inline double cofactors_ut3(const double* restrict m, double* restrict c) { int i=0; c[i++] = m[3]*m[5]; c[i++] = -m[1]*m[5]; c[i++] = m[1]*m[4]-m[2]*m[3]; c[i++] = m[0]*m[5]; c[i++] = -m[0]*m[4]; c[i++] = m[0]*m[3]; return m[0]*m[3]*m[5]; } static inline double cofactors_ut4(const double* restrict m, double* restrict c) { int i=0; c[i++] = m[4]*m[7]*m[9]; c[i++] = -m[1]*m[7]*m[9]; c[i++] = m[1]*m[5]*m[9]-m[2]*m[4]*m[9]; c[i++] = (-m[1]*(m[5]*m[8]-m[6]*m[7]))+m[2]*m[4]*m[8]-m[3]*m[4]*m[7]; c[i++] = m[0]*m[7]*m[9]; c[i++] = -m[0]*m[5]*m[9]; c[i++] = m[0]*(m[5]*m[8]-m[6]*m[7]); c[i++] = m[0]*m[4]*m[9]; c[i++] = -m[0]*m[4]*m[8]; c[i++] = m[0]*m[4]*m[7]; return m[0]*m[4]*m[7]*m[9]; } static inline double cofactors_ut5(const double* restrict m, double* restrict c) { int i=0; c[i++] = m[12]*m[14]*m[5]*m[9]; c[i++] = -m[1]*m[12]*m[14]*m[9]; c[i++] = m[1]*m[12]*m[14]*m[6]-m[12]*m[14]*m[2]*m[5]; c[i++] = (-m[1]*(m[10]*m[14]*m[6]-m[14]*m[7]*m[9]))-m[14]*m[3]*m[5]*m[9]+m[10]*m[14]*m[2]*m[5]; c[i++] = m[1]*(m[12]*m[8]*m[9]-m[13]*m[7]*m[9]+(m[10]*m[13]-m[11]*m[12])*m[6])-m[12]*m[4]*m[5]*m[9]+m[13]*m[3]*m[5]*m[9]-(m[10]*m[13]-m[11]*m[12])*m[2]*m[5]; c[i++] = m[0]*m[12]*m[14]*m[9]; c[i++] = -m[0]*m[12]*m[14]*m[6]; c[i++] = m[0]*(m[10]*m[14]*m[6]-m[14]*m[7]*m[9]); c[i++] = -m[0]*(m[12]*m[8]*m[9]-m[13]*m[7]*m[9]+(m[10]*m[13]-m[11]*m[12])*m[6]); c[i++] = m[0]*m[12]*m[14]*m[5]; c[i++] = -m[0]*m[10]*m[14]*m[5]; c[i++] = m[0]*(m[10]*m[13]-m[11]*m[12])*m[5]; c[i++] = m[0]*m[14]*m[5]*m[9]; c[i++] = -m[0]*m[13]*m[5]*m[9]; c[i++] = m[0]*m[12]*m[5]*m[9]; return m[0]*m[5]*m[9]*m[12]*m[14]; } static inline double cofactors_lt2(const double* restrict m, double* restrict c) { int i=0; c[i++] = m[2]; c[i++] = -m[1]; c[i++] = m[0]; return m[0]*m[2]; } static inline double cofactors_lt3(const double* restrict m, double* restrict c) { int i=0; c[i++] = m[2]*m[5]; c[i++] = -m[1]*m[5]; c[i++] = m[0]*m[5]; c[i++] = m[1]*m[4]-m[2]*m[3]; c[i++] = -m[0]*m[4]; c[i++] = m[0]*m[2]; return m[0]*m[2]*m[5]; } static inline double cofactors_lt4(const double* restrict m, double* restrict c) { int i=0; c[i++] = m[2]*m[5]*m[9]; c[i++] = -m[1]*m[5]*m[9]; c[i++] = m[0]*m[5]*m[9]; c[i++] = m[1]*m[4]*m[9]-m[2]*m[3]*m[9]; c[i++] = -m[0]*m[4]*m[9]; c[i++] = m[0]*m[2]*m[9]; c[i++] = m[2]*(m[3]*m[8]-m[5]*m[6])-m[1]*(m[4]*m[8]-m[5]*m[7]); c[i++] = m[0]*(m[4]*m[8]-m[5]*m[7]); c[i++] = -m[0]*m[2]*m[8]; c[i++] = m[0]*m[2]*m[5]; return m[0]*m[2]*m[5]*m[9]; } static inline double cofactors_lt5(const double* restrict m, double* restrict c) { int i=0; c[i++] = m[14]*m[2]*m[5]*m[9]; c[i++] = -m[1]*m[14]*m[5]*m[9]; c[i++] = m[0]*m[14]*m[5]*m[9]; c[i++] = m[1]*m[14]*m[4]*m[9]-m[14]*m[2]*m[3]*m[9]; c[i++] = -m[0]*m[14]*m[4]*m[9]; c[i++] = m[0]*m[14]*m[2]*m[9]; c[i++] = m[2]*(m[14]*m[3]*m[8]-m[14]*m[5]*m[6])-m[1]*(m[14]*m[4]*m[8]-m[14]*m[5]*m[7]); c[i++] = m[0]*(m[14]*m[4]*m[8]-m[14]*m[5]*m[7]); c[i++] = -m[0]*m[14]*m[2]*m[8]; c[i++] = m[0]*m[14]*m[2]*m[5]; c[i++] = m[1]*(m[4]*(m[13]*m[8]-m[12]*m[9])-m[5]*(m[13]*m[7]-m[11]*m[9]))-m[2]*(m[3]*(m[13]*m[8]-m[12]*m[9])-m[5]*(m[13]*m[6]-m[10]*m[9])); c[i++] = -m[0]*(m[4]*(m[13]*m[8]-m[12]*m[9])-m[5]*(m[13]*m[7]-m[11]*m[9])); c[i++] = m[0]*m[2]*(m[13]*m[8]-m[12]*m[9]); c[i++] = -m[0]*m[13]*m[2]*m[5]; c[i++] = m[0]*m[2]*m[5]*m[9]; return m[0]*m[2]*m[5]*m[9]*m[14]; } /* (%i27) a : matrix([a0,a1,a2],[0,a3,a4],[0,0,a5]); (%o27) matrix([a0,a1,a2],[0,a3,a4],[0,0,a5]) (%i28) b : matrix([b0,b1,b2],[0,b3,b4],[0,0,b5]); (%o28) matrix([b0,b1,b2],[0,b3,b4],[0,0,b5]) (%i29) a . b; (%o29) matrix([a0*b0,a1*b3+a0*b1,a2*b5+a1*b4+a0*b2],[0,a3*b3,a4*b5+a3*b4],[0,0,a5*b5]) */ static inline void mul_ut3_ut3(const double* restrict a, const double* restrict b, double* restrict ab) { ab[0] = a[0] * b[0]; ab[1] = a[1] * b[3]+a[0] * b[1]; ab[2] = a[2] * b[5]+a[1] * b[4]+a[0] * b[2]; ab[3] = a[3] * b[3]; ab[4] = a[4] * b[5]+a[3] * b[4]; ab[5] = a[5] * b[5]; } // symmetrix 3x3 by symmetrix 3x3, written into a new non-symmetric matrix, // scaled. This is a special-case function that I needed for something... static inline void mul_sym33_sym33_scaled_out(const double* restrict s0, const double* restrict s1, double* restrict mout, double scale) { // (%i106) matrix([m0_0,m0_1,m0_2], // [m0_1,m0_3,m0_4], // [m0_2,m0_4,m0_5]) . // matrix([m1_0,m1_1,m1_2], // [m1_1,m1_3,m1_4], // [m1_2,m1_4,m1_5]); // (%o106) matrix([m0_2*m1_2+m0_1*m1_1+m0_0*m1_0,m0_2*m1_4+m0_1*m1_3+m0_0*m1_1, // m0_2*m1_5+m0_1*m1_4+m0_0*m1_2], // [m0_4*m1_2+m0_3*m1_1+m0_1*m1_0,m0_4*m1_4+m0_3*m1_3+m0_1*m1_1, // m0_4*m1_5+m0_3*m1_4+m0_1*m1_2], // [m0_5*m1_2+m0_4*m1_1+m0_2*m1_0,m0_5*m1_4+m0_4*m1_3+m0_2*m1_1, // m0_5*m1_5+m0_4*m1_4+m0_2*m1_2]) mout[0] = scale * (s0[2]*s1[2]+s0[1]*s1[1]+s0[0]*s1[0]); mout[1] = scale * (s0[2]*s1[4]+s0[1]*s1[3]+s0[0]*s1[1]); mout[2] = scale * (s0[2]*s1[5]+s0[1]*s1[4]+s0[0]*s1[2]); mout[3] = scale * (s0[4]*s1[2]+s0[3]*s1[1]+s0[1]*s1[0]); mout[4] = scale * (s0[4]*s1[4]+s0[3]*s1[3]+s0[1]*s1[1]); mout[5] = scale * (s0[4]*s1[5]+s0[3]*s1[4]+s0[1]*s1[2]); mout[6] = scale * (s0[5]*s1[2]+s0[4]*s1[1]+s0[2]*s1[0]); mout[7] = scale * (s0[5]*s1[4]+s0[4]*s1[3]+s0[2]*s1[1]); mout[8] = scale * (s0[5]*s1[5]+s0[4]*s1[4]+s0[2]*s1[2]); } static inline void outerproduct3(const double* restrict v, double* restrict P) { P[0] = v[0]*v[0]; P[1] = v[0]*v[1]; P[2] = v[0]*v[2]; P[3] = v[1]*v[1]; P[4] = v[1]*v[2]; P[5] = v[2]*v[2]; } static inline void outerproduct3_scaled(const double* restrict v, double* restrict P, double scale) { P[0] = scale * v[0]*v[0]; P[1] = scale * v[0]*v[1]; P[2] = scale * v[0]*v[2]; P[3] = scale * v[1]*v[1]; P[4] = scale * v[1]*v[2]; P[5] = scale * v[2]*v[2]; } // conjugate 2 vectors (a, b) through a symmetric matrix S: a->transpose x S x b // (%i2) sym3 : matrix([s0,s1,s2], // [s1,s3,s4], // [s2,s4,s5]); // (%o2) matrix([s0,s1,s2],[s1,s3,s4],[s2,s4,s5]) // (%i6) a : matrix([a0],[a1],[a2]); // (%o6) matrix([a0],[a1],[a2]) // (%i7) b : matrix([b0],[b1],[b2]); // (%o7) matrix([b0],[b1],[b2]) // (%i10) transpose(a) . sym3 . b; // (%o10) a2*(b2*s5+b1*s4+b0*s2)+a1*(b2*s4+b1*s3+b0*s1)+a0*(b2*s2+b1*s1+b0*s0) static inline double conj_3(const double* restrict a, const double* restrict s, const double* restrict b) { return a[2]*(b[2]*s[5]+b[1]*s[4]+b[0]*s[2])+a[1]*(b[2]*s[4]+b[1]*s[3]+b[0]*s[1])+a[0]*(b[2]*s[2]+b[1]*s[1]+b[0]*s[0]); } // Given an orthonormal matrix, returns the det. This is always +1 or -1 static inline double det_orthonormal33(const double* m) { // cross(row0,row1) = det * row3 // I find a nice non-zero element of row3, and see if the signs match if( m[6] < -0.1 ) { // looking at col0 of the last row. It is <0 double cross = m[1]*m[5] - m[2]*m[4]; return cross > 0.0 ? -1.0 : 1.0; } if( m[6] > 0.1) { // looking at col0 of the last row. It is > 0 double cross = m[1]*m[5] - m[2]*m[4]; return cross > 0.0 ? 1.0 : -1.0; } if( m[7] < -0.1 ) { // looking at col1 of the last row. It is <0 double cross = m[2]*m[3] - m[0]*m[5]; return cross > 0.0 ? -1.0 : 1.0; } if( m[7] > 0.1) { // looking at col1 of the last row. It is > 0 double cross = m[2]*m[3] - m[0]*m[5]; return cross > 0.0 ? 1.0 : -1.0; } if( m[8] < -0.1 ) { // looking at col2 of the last row. It is <0 double cross = m[0]*m[4] - m[1]*m[3]; return cross > 0.0 ? -1.0 : 1.0; } // last option. This MUST be true, so I don't even bother to check { // looking at col2 of the last row. It is > 0 double cross = m[0]*m[4] - m[1]*m[3]; return cross > 0.0 ? 1.0 : -1.0; } } static void minimath_xchg(double* m, int i, int j) { double t = m[i]; m[i] = m[j]; m[j] = t; } static inline void gen33_transpose(double* m) { minimath_xchg(m, 1, 3); minimath_xchg(m, 2, 6); minimath_xchg(m, 5, 7); } static inline void gen33_transpose_vout(const double* m, double* mout) { for(int i=0; i<3; i++) for(int j=0; j<3; j++) mout[i*3+j] = m[j*3+i]; } static inline double cofactors_gen33(// output double* restrict c, // input const double* restrict m) { /* (%i1) display2d : false; (%o1) false (%i5) linel : 100000; (%o5) 100000 (%i6) mat33 : matrix( [m0,m1,m2], [m3,m4,m5], [m6,m7,m8] ); (%o6) matrix([m0,m1,m2],[m3,m4,m5],[m6,m7,m8]) (%i7) num( ev(invert(mat33)), detout ); (%o7) matrix([(m4*m8-m5*m7)/(m0*(m4*m8-m5*m7)+m1*(m5*m6-m3*m8)+m2*(m3*m7-m4*m6)),(m2*m7-m1*m8)/(m0*(m4*m8-m5*m7)+m1*(m5*m6-m3*m8)+m2*(m3*m7-m4*m6)),(m1*m5-m2*m4)/(m0*(m4*m8-m5*m7)+m1*(m5*m6-m3*m8)+m2*(m3*m7-m4*m6))],[(m5*m6-m3*m8)/(m0*(m4*m8-m5*m7)+m1*(m5*m6-m3*m8)+m2*(m3*m7-m4*m6)),(m0*m8-m2*m6)/(m0*(m4*m8-m5*m7)+m1*(m5*m6-m3*m8)+m2*(m3*m7-m4*m6)),(m2*m3-m0*m5)/(m0*(m4*m8-m5*m7)+m1*(m5*m6-m3*m8)+m2*(m3*m7-m4*m6))],[(m3*m7-m4*m6)/(m0*(m4*m8-m5*m7)+m1*(m5*m6-m3*m8)+m2*(m3*m7-m4*m6)),(m1*m6-m0*m7)/(m0*(m4*m8-m5*m7)+m1*(m5*m6-m3*m8)+m2*(m3*m7-m4*m6)),(m0*m4-m1*m3)/(m0*(m4*m8-m5*m7)+m1*(m5*m6-m3*m8)+m2*(m3*m7-m4*m6))]) (%i8) determinant(mat33); (%o8) m0*(m4*m8-m5*m7)-m1*(m3*m8-m5*m6)+m2*(m3*m7-m4*m6) */ double det = m[0]*(m[4]*m[8]-m[5]*m[7])-m[1]*(m[3]*m[8]-m[5]*m[6])+m[2]*(m[3]*m[7]-m[4]*m[6]); c[0] = m[4]*m[8]-m[5]*m[7]; c[1] = m[2]*m[7]-m[1]*m[8]; c[2] = m[1]*m[5]-m[2]*m[4]; c[3] = m[5]*m[6]-m[3]*m[8]; c[4] = m[0]*m[8]-m[2]*m[6]; c[5] = m[2]*m[3]-m[0]*m[5]; c[6] = m[3]*m[7]-m[4]*m[6]; c[7] = m[1]*m[6]-m[0]*m[7]; c[8] = m[0]*m[4]-m[1]*m[3]; return det; } #ifdef __cplusplus #undef restrict #endif mrcal-2.4.1/minimath/minimath_generate.pl000077500000000000000000000264101456301662300204530ustar00rootroot00000000000000#!/usr/bin/env perl use strict; use warnings; use feature qw(say); use List::Util qw(min); use List::MoreUtils qw(pairwise); say "// THIS IS AUTO-GENERATED BY $0. DO NOT EDIT BY HAND\n"; say "// This contains dot products, norms, basic vector arithmetic and multiplication\n"; my @sizes = 2..6; # the dot products, norms and basic arithmetic functions take the size as an # argument. I'm assuming that the compiler will expand these out for each # particular invocation dotProducts(); norms(); vectorArithmetic(); foreach my $n(@sizes) { matrixVectorSym($n); foreach my $m (@sizes) { matrixVectorGen($n, $m) } matrixMatrixSym($n); matrixMatrixGen($n); } # this is only defined for N=3. I haven't made the others yet and I don't yet need them matrixMatrixMatrixSym(3); sub dotProducts { print < vout static inline void add_vec_vout(int n, const double* restrict a, const double* restrict b, double* restrict vout) { for(int i=0; i vout static inline void sub_vec_vout(int n, const double* restrict a, const double* restrict b, double* restrict vout) { for(int i=0; i 0); for my $i(0..$n-1) { my $isym_row = _getSymmetricIndices_row(\%isymHash, $i, $n); my @cols = 0..$n-1; our ($a,$b); my @sum_components = pairwise {"s[$a]*v[$b]"} @$isym_row, @cols; $vout .= " vout[$i] = " . join(' + ', @sum_components) . ";\n"; } $vout .= "}"; print _multiplicationVersions($vout, $n, $n); } sub matrixVectorGen { my $n = shift; my $m = shift; # I now make NxM matrix-vector multiplication. I describe matrices math-style # with the number of rows first (NxM has N rows, M columns). I store the # matrices row-first and treat vectors as row-vectors. Thus these functons # compute v*A where v is the row vector and A is the NxM matrix my $vout = <{$key} ) { $hash->{$key} = $hash->{next}; $hash->{next}++; } push @isym, $hash->{$key}; } return \@isym; } sub _getFirstDataArg { my $v = shift; # I have a string with a bunch of functions. Get the first argument. I ASSUME # THE FIRST ARGUMENT HAS THE SAME NAME IN ALL OF THESE my ($arg0) = $v =~ m/^static inline.*\(.*?double\* restrict ([a-z0-9_]+),/m or die "Couldn't recognize function in '$v'"; return $arg0; } sub _makeInplace_mulVector { my $v = shift; my $arg0 = shift; my $n = shift; my $m = shift; # rename functions $v =~ s/_vout//gm; # get rid of the 'vout argument' $v =~ s/, double\* restrict vout//gm; # un-const first argument $v =~ s/^(static inline.*\(.*?)const (double.*)$/$1$2/gm; # use the first argument instead of vout $v =~ s/vout/$arg0/gm; # if we're asked to make some temporary variables, do it if(defined $n) { # if no $m is given, use $m; $m //= $n; my $nt = min($n-1,$m); # use the temporaries instead of the main variable when possible foreach my $t(0..$nt-1) { $v =~ s/(=.*)${arg0}\[$t\]/$1t[$t]/mg; } # define the temporaries. I need one fewer than n my $tempDef = " double t[$nt] = {" . join(', ', map {"${arg0}[$_]"} 0..$nt-1) . "};"; $v =~ s/^\{$/{\n$tempDef/mg; } return $v; } sub _makeInplace_mulMatrix { my $v = shift; # rename functions $v =~ s/_vout//gm; # get rid of the 'vout argument' $v =~ s/, double\* restrict vout//gm; # un-const first argument $v =~ s/^(static inline.*\(.*?)const (double.*)$/$1$2/gm; # use the first argument instead of vout $v =~ s/,[^\),]*vout[^\),]*([\),])/$1/gm; return $v; } sub _makeVaccum { my $v = shift; # rename functions $v =~ s/_vout/_vaccum/gm; # vout -> vaccum $v =~ s/vout/vaccum/gm; # make sure we accumulate $v =~ s/(vaccum\[.*?\]\s*)=/$1+=/gm; # better comment $v =~ s/-> vaccum/-> + vaccum/gm; return $v; } sub _makeScaled_arithmetic { my $f = shift; # rename functions $f =~ s/^(static inline .*)(\s*\()/${1}_scaled$2/gm; # add the scale argument $f =~ s/^(static inline .*)\)$/$1, double scale)/gm; # apply the scaling $f =~ s/([+-]) b/$1 scale*b/gm; return $f; } sub _makeScaled_mulVector { my $f = shift; # rename functions $f =~ s/^(static inline .*)(\s*\()/${1}_scaled$2/gm; # add the scale argument $f =~ s/^(static inline .*)\)$/$1, double scale)/gm; # apply the scaling $f =~ s/(.*=\s*)([^{}]*?);$/${1}scale * ($2);/gm; return $f; } sub _makeScaled_mulMatrix { my $f = shift; # rename functions $f =~ s/^(static inline .*)(\s*\()/${1}_scaled$2/gm; # add the scale argument $f =~ s/^(static inline .*)\)$/$1, double scale)/gm; # apply the scaling. This is simply an argument to the vector function I call $f =~ s/^(\s*mul_.*)(\).*)/$1, scale$2/gm; # apply the scaling. Call the _scaled vector function $f =~ s/^(\s*mul_.*?)(\s*\()/${1}_scaled$2/gm; return $f; } mrcal-2.4.1/mrcal-calibrate-cameras000077500000000000000000001252411456301662300172100ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Calibrate some synchronized, stationary cameras SYNOPSIS $ mrcal-calibrate-cameras --corners-cache corners.vnl --lensmodel LENSMODEL_OPENCV8 --focal 1700 --object-spacing 0.01 --object-width-n 10 --outdir /tmp --pairs 'left*.png' 'right*.png' ... lots of output as the solve runs ... Done! RMS reprojection error: 1.9 pixels Worst reprojection error: 7.8 pixels Noutliers: 319 out of 17100 total points: 1.9% of the data Wrote /tmp/camera0-0.cameramodel Wrote /tmp/camera0-1.cameramodel This tool uses the generic mrcal platform to solve a common specific problem of N-camera calibration using observations of a chessboard. Please see the mrcal documentation at http://mrcal.secretsauce.net/how-to-calibrate.html for details. ''' import sys import argparse import re import os def parse_args(): def positive_float(string): try: value = float(string) except: print(f"argument MUST be a positive floating-point number. Got '{string}'", file=sys.stderr) sys.exit(1) if value <= 0: print(f"argument MUST be a positive floating-point number. Got '{string}'", file=sys.stderr) sys.exit(1) return value def positive_int(string): try: value = int(string) except: print(f"argument MUST be a positive integer. Got '{string}'", file=sys.stderr) sys.exit(1) if value <= 0 or abs(value-float(string)) > 1e-6: print(f"argument MUST be a positive integer. Got '{string}'", file=sys.stderr) sys.exit(1) return value parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--lensmodel', required=False, help='''Which lens model we're using. This is a string "LENSMODEL_....". Required unless we have a --seed. See http://mrcal.secretsauce.net/how-to-calibrate.html for notes about how to select a model''') parser.add_argument('--focal', type=str, help=r'''Initial estimate of the focal length, in pixels. Required unless --seed is given. See http://mrcal.secretsauce.net/how-to-calibrate.html for notes about how to estimate a focal length. This is either a single value to use for all the cameras, or a comma-separated whitespace-less list of values to use for each camera. If such a list is given, it must match the number of cameras being calibrated''') parser.add_argument('--imagersize', nargs=2, type=int, required=False, help='''Size of the imager. This is only required if we pass --corners-cache AND if none of the image files on disk actually exist and if we don't have a --seed. If we do have a --seed, the --imagersize values must match the --seed exactly''') parser.add_argument('--outdir', type=lambda d: d if os.path.isdir(d) else \ parser.error(f"--outdir requires an existing directory as the arg, but got '{d}'"), default='.', help='Directory for the output camera models') parser.add_argument('--object-spacing', required=False, type=float, help='Width of each square in the calibration board, in meters') parser.add_argument('--object-width-n', type=int, default=10, help='''How many points the calibration board has per horizontal side. If omitted we default to 10''') parser.add_argument('--object-height-n', type=int, help='''How many points the calibration board has per vertical side. If omitted, we assume a square object, setting height=width''') parser.add_argument('--seed', required=False, type=str, help='''A comma-separated whitespace-less list of camera model globs to use as a seed for the intrinsics and extrinsics. The number of models must match the number of cameras exactly. Expanded globs are sorted alphanumerically. This is useful to bootstrap the solve or to validate an existing set of models, or to recompute just the extrinsics or just the intrinsics of a solve. If omitted, we estimate a seed. Exclusive with --focal. If given, --imagersize is omitted or it must match EXACTLY with whatever is in the --seed models''') parser.add_argument('--jobs', '-j', type=int, default=1, help='''How much parallelization we want. Like GNU make. Affects only the chessboard corner finder. If we are reading a cache file, this does nothing''') parser.add_argument('--corners-cache', type=lambda f: f if os.path.exists(f) or not os.path.isdir(f) else \ parser.error(f"--corners-cache requires an existing, readable file as the arg or a non-existing path, but got '{f}'"), required=False, help=r'''Path to the corner-finder results. If this file exists, I use the corners in this file. If it doesn't exist, I invoke mrgingham to compute the corners, and I write the results to that path. And THEN I compute the calibration off those observations. This file is a vnlog with legend "# filename x y level" (exactly what mrgingham reports). Each rown is an observed corners. If an image had no observations, a single row "filename - - -" is expected. The "level" is the decimation level used in detecting that corner. "0" means "full-resolution", "1" means "half-resolution", "2" means "quarter-resolution" and so on. A level of "-" or <0 means "skip this point". This is how incomplete board observations are specified. A file with a missing "level" column will fill in "0" for all corners. A non-mrgingham grid detector may be used by running that separately, and using this option to read the output. A detector may output weights instead of a decimation level in the last column. Pass --corners-cache-has-weights to interpret the data in that way''') parser.add_argument('--corners-cache-has-weights', action='store_true', help='''By default the corners we read in --corners-cache have columns "filename x y level". If the last column is a weight instead of a decimation level, pass this option. This is useful to support non-mrgingham chessboard detectors''') parser.add_argument('--pairs', action='store_true', help='''By default, we are calibrating a set of N independent cameras. If we actually have a number of stereo pairs, pass this argument. It changes the filename format of the models written to disk (cameraPAIR-INDEXINPAIR.cameramodel), and will report some uncertainties about geometry inside each pair. Consecutive cameras in the given list are paired up, and an even number of cameras is required''') parser.add_argument('--skip-regularization', action='store_true', required=False, default=False, help='''By default we apply regularization in the solver in the final optimization. This discourages obviously-wrong solutions, but can introduce a bias. With this option, regularization isn't applied''') parser.add_argument('--skip-outlier-rejection', action='store_true', required=False, default=False, help='''By default we throw out outliers. This option turns that off''') parser.add_argument('--skip-extrinsics-solve', action='store_true', required=False, default=False, help='''Keep the seeded extrinsics, if given. Allowed only if --seed''') parser.add_argument('--skip-intrinsics-solve', action='store_true', required=False, default=False, help='''Keep the seeded intrinsics, if given. Allowed only if --seed''') parser.add_argument('--skip-calobject-warp-solve', action='store_true', required=False, default=False, help='''By default we assume the calibration target is slightly deformed, and we compute this deformation. If we want to assume that it is flat, pass this option.''') parser.add_argument('--valid-intrinsics-region-parameters', nargs = 5, default = (1, 0.5, 1.5, 3, 0), type = float, help='''For convenience we compute a valid-intrinsics region to describe the results of the calibration. This is a watered-down interpretation of the projection uncertainty that is easy to interpret. The logic computing this is somewhat crude, and may go away in the future. The defaults should be reasonable, so if in doubt, leave these alone. The intent is to produce usable output even if we're using a lean lens model where the computed uncertainty is always overly optimistic. We bin the observations into a grid, and use mrcal._report_regional_statistics() to get the residual statistics in each bin. We then contour the bins to produce the valid-intrinsics region. If we're using a rich lens model (LENSMODEL_SPLINED_...), then we only look at the uncertainty, and not at the other statistics. This argument takes 5 parameters. The uncertainty is computed at a range valid_intrinsics_region_parameters[4]. If <= 0, I look out to infinity. The default is 0. A region is valid only if the projection uncertainty < valid_intrinsics_region_parameters[0] * observed_pixel_uncertainty. The default is 1. A region is valid only if the mean-abs-residuals is < valid_intrinsics_region_parameters[1] (only for lean models). The default is 0.5. A region is valid only if the residuals stdev is < valid_intrinsics_region_parameters[2] * observed_pixel_uncertainty (only for lean models). The default is 1.5. A region is valid only if it contains at least valid_intrinsics_region_parameters[3] observations (only for lean models). The default is 3.''') parser.add_argument('--verbose-solver', action='store_true', required=False, default=False, help='''By default the final stage of the solver doesn't say much. This option turns on verbosity to get lots of diagnostics. This is generally not very useful to end users''') parser.add_argument('--explore', action='store_true', required=False, default=False, help='''After the solve open an interactive shell to examine the solution''') parser.add_argument('images', type=str, nargs='+', help='''A glob-per-camera for the images. Include a glob for each camera. It is assumed that the image filenames in each glob are of of the form xxxNNNyyy where xxx and yyy are common to all images in the set, and NNN varies. This NNN is a frame number, and identical frame numbers across different globs signify a time-synchronized observation. I.e. you can pass 'left*.jpg' and 'right*.jpg' to find images 'left0.jpg', 'left1.jpg', ..., 'right0.jpg', 'right1.jpg', ...''') return parser.parse_args() args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README if args.object_spacing is None: print("WARNING: assuming default calibration-object spacing of 0.1m. If this is wrong, all distances will be off by a scale factor", file = sys.stderr) args.object_spacing = 0.1 if args.object_height_n is None: args.object_height_n = args.object_width_n import numpy as np import scipy.linalg import numpysane as nps import copy import time import glob import mrcal # wider printing is more convenient here np.set_printoptions(linewidth=300) def get_imagersize_one(icamera, indices_frame_camera, paths, args_imagersize, seedmodels): r'''Returns the imager size for a given camera This reports the size for ONE camera. I only look at the first match. It is assumed that all the images matching this glob have the same imager size. If I have a corners cache, then this is the ONLY place where I'd need the images on disk at all. If the user passes --imagersize, then I really don't need the images. ''' if args_imagersize is not None: return args_imagersize if seedmodels is not None: return seedmodels[icamera].imagersize() try: iobservation0_thiscamera = next( i for i in range(len(paths)) if indices_frame_camera[i,1] == icamera ) except: print(f"Couldn't find any images for camera '{icamera}'", file=sys.stderr) sys.exit(1) try: img = mrcal.load_image(paths[iobservation0_thiscamera], bits_per_pixel = 8, channels = 1) except: print(f"I needed to read '{paths[iobservation0_thiscamera]}' to get an imagersize, but couldn't open it, and get image dimensions from it. Make the images findable, or pass --imagersize", file=sys.stderr) sys.exit(1) h,w = img.shape[:2] return [w,h] def solve_initial(args, seedmodels, imagersizes, observations, indices_frame_camera): '''Solve an incrementally-expanding optimization problem in several passes observations[...,2] start out as the initial outlier set, and are modified by this function to represent the expanded outlier set ''' indices_frame_camintrinsics_camextrinsics = \ nps.glue(indices_frame_camera, indices_frame_camera[:,(1,)]-1, axis=-1) def compute_seed(): # I have no seed. I compute a rough seed, and run a few preliminary, # incremental optimizations to get it reasonably-close to the right # answer intrinsics_data,extrinsics_rt_fromref,frames_rt_toref = \ mrcal.seed_stereographic(imagersizes = imagersizes, focal_estimate = args.focal, indices_frame_camera = indices_frame_camera, observations = observations, object_spacing = args.object_spacing) sys.stderr.write("## initial solve: geometry only\n") lensmodel = 'LENSMODEL_STEREOGRAPHIC' stats = mrcal.optimize(intrinsics = intrinsics_data, extrinsics_rt_fromref = extrinsics_rt_fromref, frames_rt_toref = frames_rt_toref, observations_board = observations, indices_frame_camintrinsics_camextrinsics = indices_frame_camintrinsics_camextrinsics, lensmodel = lensmodel, imagersizes = imagersizes, do_optimize_intrinsics_core = False, do_optimize_intrinsics_distortions= False, do_optimize_calobject_warp = False, calibration_object_spacing = args.object_spacing, do_apply_outlier_rejection = False, do_apply_regularization = False, verbose = False) sys.stderr.write(f"## RMS error: {stats['rms_reproj_error__pixels']:.02f}\n\n") sys.stderr.write("## initial solve: geometry and LENSMODEL_STEREOGRAPHIC core only\n") stats = mrcal.optimize(intrinsics = intrinsics_data, extrinsics_rt_fromref = extrinsics_rt_fromref, frames_rt_toref = frames_rt_toref, observations_board = observations, indices_frame_camintrinsics_camextrinsics = indices_frame_camintrinsics_camextrinsics, lensmodel = lensmodel, imagersizes = imagersizes, do_optimize_intrinsics_core = True, do_optimize_intrinsics_distortions= False, do_optimize_calobject_warp = False, calibration_object_spacing = args.object_spacing, do_apply_outlier_rejection = False, do_apply_regularization = False, verbose = False) extrinsics_Rt_fromref = mrcal.Rt_from_rt( extrinsics_rt_fromref ) return \ intrinsics_data, \ extrinsics_Rt_fromref, \ frames_rt_toref def compute_seed_from_existing_models(): # The caller made sure that all the models use the same lens model lensmodel = seedmodels[0].intrinsics()[0] intrinsics_data = nps.cat( *[m.intrinsics()[1] for m in seedmodels]) # I keep the relative camera poses constant, but place camera0 at the # origin Rt_r0 = seedmodels[0].extrinsics_Rt_toref() extrinsics_Rt_fromref = \ nps.cat( *[ mrcal.compose_Rt( m.extrinsics_Rt_fromref(),Rt_r0) for m in seedmodels[1:]]) if extrinsics_Rt_fromref.size == 0: # No extrinsics. Represent as 0 Rt transforms extrinsics_Rt_fromref = np.zeros((0,4,3), dtype=float) # I have a GOOD extrinsics estimate, so I could compute a GOOD frame # pose estimate by triangulating: # # import deltapose_lite # for corresponding images: # for points in chessboard: # lindstrom to get point in 3d # procrustes fit to get frame transformation # # But this takes a lot of typing, and wouldn't handle special cases: # - what if for a given frame only 1 camera is observing the board? # - what if for a given frame more than 2 cameras are observing the board? # # So I do the less-accurate-but-more-robust thing using pinhole # monocular observations. This is what mrcal.seed_stereographic() # does in the no-seed-available case calobject_poses_local_Rt_cf = \ mrcal.estimate_monocular_calobject_poses_Rt_tocam( indices_frame_camera, observations, args.object_spacing, seedmodels) frames_rt_toref = \ mrcal.estimate_joint_frame_poses( calobject_poses_local_Rt_cf, extrinsics_Rt_fromref, indices_frame_camera, args.object_width_n, args.object_height_n, args.object_spacing) if 0: # I was seeing an issue with incorrectly-seeded frames_rt_toref, and # I thought that pre-optimizing it would fix it, so I wrote this # code. That issue was actually caused by something else, making # this code unnecessary, but I'm leaving it here, in case it becomes # useful later. For debugging, I'm printing the before/after # frames_rt_toref so that we can see if this pre-optimization does # anything print("pre-optimization; before: rt_cf[:2]") print(frames_rt_toref[:2]) # I have a rough estimate of the geometry. Before it's usable I need # to refine it using the optimizer. I lock down EVERYTHING except # frames_rt_toref, since the seed gives me everything else sys.stderr.write("## reoptimizing frames_rt_toref\n") stats = mrcal.optimize(intrinsics_data, mrcal.rt_from_Rt(extrinsics_Rt_fromref), frames_rt_toref, None, observations, indices_frame_camintrinsics_camextrinsics, None, None, lensmodel, imagersizes = imagersizes, do_optimize_intrinsics_core = False, do_optimize_intrinsics_distortions= False, do_optimize_calobject_warp = False, do_optimize_extrinsics = False, do_optimize_frames = True, calibration_object_spacing = args.object_spacing, do_apply_outlier_rejection = False, do_apply_regularization = False, verbose = False) sys.stderr.write(f"## RMS error: {stats['rms_reproj_error__pixels']:.02f}\n\n") print("pre-optimization; after: rt_cf[:2]") print(frames_rt_toref[:2]) return \ intrinsics_data, \ extrinsics_Rt_fromref, \ frames_rt_toref, if seedmodels is None: intrinsics_data, \ extrinsics_Rt_fromref, \ frames_rt_toref = compute_seed() else: intrinsics_data, \ extrinsics_Rt_fromref, \ frames_rt_toref = compute_seed_from_existing_models() def expand_intrinsics(lensmodel, intrinsics_data): NnewDistortions = \ mrcal.lensmodel_num_params(lensmodel) - \ intrinsics_data.shape[-1] newDistortions = \ (np.random.random((Ncameras, NnewDistortions)) - 0.5)*2. *1e-6 m = re.search("OPENCV([0-9]+)", lensmodel) if m: Nd = int(m.group(1)) if Nd >= 8: # Push down the rational components of the seed. I'd like these all to # sit at 0 ideally. The radial distortion in opencv is x_distorted = # x*scale where r2 = norm2(xy - xyc) and # # scale = (1 + k0 r2 + k1 r4 + k4 r6)/(1 + k5 r2 + k6 r4 + k7 r6) # # Note that k2,k3 are tangential (NOT radial) distortion components. # Note that the r6 factor in the numerator is only present for # >=LENSMODEL_OPENCV5. Note that the denominator is only present for >= # LENSMODEL_OPENCV8. The danger with a rational model is that it's # possible to get into a situation where scale ~ 0/0 ~ 1. This would # have very poorly behaved derivatives. If all the rational coefficients # are ~0, then the denominator is always ~1, and this problematic case # can't happen. I favor that. newDistortions[5:8] *= 1e-3 return nps.glue( intrinsics_data, newDistortions, axis=-1 ) # Alrighty. All the preliminary business is finished. I should have a usable # seed now. And thus I now run the main optimization loop lensmodel = args.lensmodel intrinsics_data = expand_intrinsics(lensmodel, intrinsics_data) print("=================== optimizing everything{}from seeded intrinsics". \ format(" except board warp " if not args.skip_calobject_warp_solve else " ")) extrinsics_rt_fromref = mrcal.rt_from_Rt(extrinsics_Rt_fromref) # splined models have a core, but those variables are largely redundant with # the spline parameters. So I run another pre-solve to get reasonable values # for the core, and then I lock it down do_optimize_intrinsics_core = not args.skip_intrinsics_solve if re.match("LENSMODEL_SPLINED_STEREOGRAPHIC_", lensmodel): do_optimize_intrinsics_core = False optimization_inputs = \ dict( intrinsics = intrinsics_data, extrinsics_rt_fromref = extrinsics_rt_fromref, frames_rt_toref = frames_rt_toref, points = None, observations_board = observations, indices_frame_camintrinsics_camextrinsics = indices_frame_camintrinsics_camextrinsics, observations_point = None, indices_point_camintrinsics_camextrinsics = None, lensmodel = lensmodel, imagersizes = imagersizes, calobject_warp = None, do_optimize_intrinsics_core = do_optimize_intrinsics_core, do_optimize_intrinsics_distortions = not args.skip_intrinsics_solve, do_optimize_extrinsics = not args.skip_extrinsics_solve, do_optimize_frames = True, do_optimize_calobject_warp = False, calibration_object_spacing = args.object_spacing, do_apply_outlier_rejection = not args.skip_outlier_rejection, do_apply_regularization = True, verbose = False, imagepaths = paths ) mrcal.optimize( **optimization_inputs ) return optimization_inputs # expand ~/ into $HOME/ args.images = [os.path.expanduser(g) for g in args.images] Ncameras = len(args.images) if Ncameras > 10: print(f"Got {Ncameras} image globs. It should be one glob per camera, and this sounds like WAY too many cameras. Did you forget to escape your glob?", file=sys.stderr) sys.exit(1) if args.pairs and Ncameras % 2: print(f"With --pairs I must have gotten an even number of cameras, but instead got {Ncameras}", file=sys.stderr) sys.exit(1) if args.seed: if args.focal is not None: print("Exactly one of --focal and --seed MUST be given", file=sys.stderr) sys.exit(1) def seedmodels_iterator(): for g in args.seed.split(','): globbed_filenames = sorted(glob.glob(g)) if 0 == len(globbed_filenames): print(f"seed glob '{g}' matched no files!", file=sys.stderr) sys.exit(1) for f in globbed_filenames: yield mrcal.cameramodel(f) seedmodels = list(seedmodels_iterator()) if Ncameras != len(seedmodels): print(f"I saw {Ncameras} image globs, but {len(seedmodels)} --seed models. Both represent cameras, so I should have identical counts", file=sys.stderr) sys.exit(1) if args.imagersize is not None: for m in seedmodels: if args.imagersize != list(m.imagersize()): print(f"Both --seed and --imagersize were given, so they must match exactly. But I had --imagersize {args.imagersize} and one model has imagersize() = {m.imagersize()}", file=sys.stderr) sys.exit(1) lensmodel = seedmodels[0].intrinsics()[0] for m in seedmodels[1:]: if lensmodel != m.intrinsics()[0]: print(f"I expect all cameras to use the same lens model, but --seed saw {lensmodel} and {m.intrinsics()[0]}", file=sys.stderr) sys.exit(1) if args.lensmodel is None: args.lensmodel = lensmodel elif args.lensmodel != lensmodel: print(f"Error: the lensmodel in --seed ({lensmodel}) does not match the given --lensmodel ({args.lensmodel}). With --seed you can omit --lensmodel", file=sys.stderr) sys.exit(1) else: if args.focal is None: print("Exactly one of --focal and --seed MUST be given", file=sys.stderr) sys.exit(1) try: args.focal = [ float(f.strip()) for f in args.focal.split(',') ] except: print(f"--focal must be given a positive floating-point value, or a comma-separated list of such values", file=sys.stderr) sys.exit(1) if not all(f>0 for f in args.focal): print("--focal must be given a POSITIVE floating-point value, or a comma-separated list of such values. Some weren't positive", file=sys.stderr) sys.exit(1) if not (len(args.focal) == 1 or \ len(args.focal) == Ncameras): print(f"--focal must be a single value, or a comma-separated list of exactly Ncameras such values. Received Ncameras={Ncameras} image globs and {len(args.focal)} focal lengths", file=sys.stderr) sys.exit(1) if not args.lensmodel: print("--lensmodel is required if no --seed", file=sys.stderr) sys.exit(1) if args.skip_extrinsics_solve: print("--skip-extrinsics-solve requires --seed", file=sys.stderr) sys.exit(1) if args.skip_intrinsics_solve: print("--skip-intrinsics-solve requires --seed", file=sys.stderr) sys.exit(1) seedmodels = None try: observations, indices_frame_camera, paths = \ mrcal.compute_chessboard_corners(args.object_width_n, args.object_height_n, globs_per_camera = args.images, corners_cache_vnl = args.corners_cache, jobs = args.jobs, weight_column_kind = 'weight' if args.corners_cache_has_weights else 'level') except Exception as e: print(f"Error extracting or reading chessboard corners: {e}", file=sys.stderr) sys.exit(1) Nobservations = len(observations) # list of imager sizes; one per camera imagersizes = np.array([get_imagersize_one(icamera, indices_frame_camera, paths, args.imagersize, seedmodels) for icamera in range(Ncameras)], dtype=np.int32) optimization_inputs = \ solve_initial(args, seedmodels, imagersizes, observations, indices_frame_camera) if not args.skip_calobject_warp_solve: calobject_warp = np.array((0,0), dtype=float) else: calobject_warp = None print("## final, full optimization", file=sys.stderr) optimization_inputs['calobject_warp'] = calobject_warp optimization_inputs['do_optimize_calobject_warp'] = not args.skip_calobject_warp_solve optimization_inputs['do_apply_regularization'] = not args.skip_regularization optimization_inputs['do_apply_outlier_rejection'] = not args.skip_outlier_rejection optimization_inputs['verbose'] = args.verbose_solver # If we're skipping the regularization step, I do EVERYTHING else before the # final regularization-free step. Turning that off allows the solution to # wander, and I want to help it as much as possible to not do that if not optimization_inputs['do_apply_regularization']: optimization_inputs['do_apply_regularization']= True optimization_inputs['verbose'] = False stats = mrcal.optimize(**optimization_inputs) optimization_inputs['do_apply_regularization']= False optimization_inputs['verbose'] = args.verbose_solver stats = mrcal.optimize(**optimization_inputs) sys.stderr.write(f"## RMS error: {stats['rms_reproj_error__pixels']:.02f}\n") report = f"RMS reprojection error: {stats['rms_reproj_error__pixels']:.01f} pixels\n" Npoints_chessboard = args.object_width_n*args.object_height_n*Nobservations # shape (Nobservations,Nheight,Nwidth,2) residuals = \ stats['x'][:Npoints_chessboard*2]. \ reshape(Nobservations, args.object_height_n, args.object_width_n, 2) worst_point_err = np.sqrt(np.max(nps.norm2( nps.clump(residuals, n=3) ))) report += f"Worst residual (by measurement): {worst_point_err:.01f} pixels\n" if not args.skip_outlier_rejection: report += "Noutliers: {} out of {} total points: {:.01f}% of the data\n". \ format(stats['Noutliers'], args.object_height_n*args.object_width_n*len(observations), 100.0 * stats['Noutliers'] / (args.object_height_n*args.object_width_n*len(observations))) if calobject_warp is not None: report += f"calobject_warp = {calobject_warp}\n" print(report) models = \ [ mrcal.cameramodel( \ optimization_inputs = optimization_inputs, icam_intrinsics = icam ) \ for icam in range(len(optimization_inputs['intrinsics'])) ] # shape (Nobservations) nonoutliers_per_observation = \ np.sum( nps.clump( (observations[...,2] > 0.).astype(int), n = -2 ), axis = -1 ) # shape (Nobservations,) rms_residual_perobservation = \ np.sqrt( nps.norm2( nps.clump(residuals,n=-3) ) / nonoutliers_per_observation ) # shape (Nobservations,) i_observations_sorted_from_worst = \ list(reversed(np.argsort(rms_residual_perobservation))) if not args.skip_intrinsics_solve and \ args.valid_intrinsics_region_parameters is not None: observed_pixel_uncertainty = \ np.std(mrcal.residuals_board(optimization_inputs, residuals = stats['x']).ravel()) threshold_uncertainty = args.valid_intrinsics_region_parameters[0] * observed_pixel_uncertainty threshold_mean = args.valid_intrinsics_region_parameters[1] threshold_stdev = args.valid_intrinsics_region_parameters[2] * observed_pixel_uncertainty threshold_count = args.valid_intrinsics_region_parameters[3] distance = args.valid_intrinsics_region_parameters[4] for i in range(Ncameras): try: models[i].valid_intrinsics_region( \ mrcal.calibration._compute_valid_intrinsics_region(models[i], threshold_uncertainty, threshold_mean, threshold_stdev, threshold_count, distance)) except Exception as e: print(f"WARNING: Couldn't compute valid-intrinsics region for camera {i}. Will continue without. Error: {e}", file = sys.stderr) # The note says how we ran this, and contains the commented-out report note = \ f"generated on {time.strftime('%Y-%m-%d %H:%M:%S')} with {' '.join(mrcal.shellquote(s) for s in sys.argv)}\n" + \ report for icam in range(len(models)): filename_base = \ f'{args.outdir}/camera{icam//2}-{icam%2}' \ if args.pairs \ else f'{args.outdir}/camera-{icam}' cameramodelfile = filename_base + '.cameramodel' models[icam].write(cameramodelfile, note = note) print(f"Wrote {cameramodelfile}") if not args.explore: sys.exit(0) # We're exploring! import gnuplotlib as gp print('\n') print(r'''Solution-examination REPL. Potential things to look at: show_geometry() show_residuals_board_observation_worst(i_observation_in_order_from_worst) show_residuals_board_observation(i_observation, vectorscale=20) show_projection_uncertainty(icam) show_valid_intrinsics_region(icam) show_residuals_vectorfield( icam) show_residuals_magnitudes( icam) show_residuals_directions( icam) show_residuals_histogram( icam) show_residuals_regional( icam) show_distortion_off_pinhole( icam, vectorfield=False) show_distortion_off_pinhole_radial(icam) show_splined_model_correction(icam) stats i_observations_sorted_from_worst rms_residual_perobservation paths[i_observations_sorted_from_worst[0]] calobject_warp ''') # I want multiple plots to be able to be shown at once. I store the gnuplotlib # objects into values in this dict plots = dict() def show_generic_per_cam(f, icam, **kwargs): '''Generic show-things function that plots one camera/plot''' global plots icam_all = (icam,) if icam is not None else range(Ncameras) for icam in icam_all: plots[f.__name__ + str(icam)] = \ f(models[icam], extratitle = f"camera {icam}", **kwargs) def show_generic(f, *args, **kwargs): '''Generic show-things function that plots all cameras/plot''' global plots plots[f.__name__] = f(*args, **kwargs) def show_splined_model_correction (icam = None, **kwargs): show_generic_per_cam(mrcal.show_splined_model_correction, icam, **kwargs) def show_projection_uncertainty (icam = None, **kwargs): show_generic_per_cam(mrcal.show_projection_uncertainty, icam, **kwargs) def show_valid_intrinsics_region (icam = None, **kwargs): show_generic_per_cam(mrcal.show_valid_intrinsics_region, icam, **kwargs) def show_residuals_vectorfield (icam = None, **kwargs): show_generic_per_cam(mrcal.show_residuals_vectorfield, icam, residuals=stats['x'], **kwargs) def show_residuals_magnitudes (icam = None, **kwargs): show_generic_per_cam(mrcal.show_residuals_magnitudes, icam, residuals=stats['x'], **kwargs) def show_residuals_directions (icam = None, **kwargs): show_generic_per_cam(mrcal.show_residuals_directions, icam, residuals=stats['x'], **kwargs) def show_residuals_regional (icam = None, **kwargs): show_generic_per_cam(mrcal.show_residuals_regional, icam, residuals=stats['x'], **kwargs) def show_distortion_off_pinhole (icam = None, **kwargs): show_generic_per_cam(mrcal.show_distortion_off_pinhole, icam, **kwargs) def show_distortion_off_pinhole_radial(icam = None, **kwargs): show_generic_per_cam(mrcal.show_distortion_off_pinhole_radial, icam, **kwargs) def show_geometry(**kwargs): show_generic(mrcal.show_geometry, models, **kwargs) def show_residuals_board_observation(i_observation, **kwargs): return show_generic( mrcal.show_residuals_board_observation, optimization_inputs, i_observation, paths = paths, i_observations_sorted_from_worst = i_observations_sorted_from_worst, residuals = stats['x'], **kwargs) def show_residuals_board_observation_worst(i_observation_from_worst, **kwargs): return show_generic( mrcal.show_residuals_board_observation, optimization_inputs, i_observation_from_worst, from_worst = True, paths = paths, i_observations_sorted_from_worst = i_observations_sorted_from_worst, residuals = stats['x'], **kwargs) def show_residuals_histogram(icam = None, **kwargs): show_generic(mrcal.show_residuals_histogram, optimization_inputs, icam, residuals=stats['x'], **kwargs) import IPython IPython.embed() mrcal-2.4.1/mrcal-convert-lensmodel000077500000000000000000001143101456301662300173040ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Converts a camera model from one lens model to another SYNOPSIS $ mrcal-convert-lensmodel --viz LENSMODEL_OPENCV4 left.cameramodel ... lots of output as the solve runs ... RMS error of the solution: 3.40256580058 pixels. Wrote 'left-LENSMODEL_OPENCV4.cameramodel' ... a plot pops up showing the differences ... Given one camera model, this tool computes another camera model that represents the same camera, but utilizes a different lens model. While lens models all exist to solve the same problem, the different representations don't map to one another perfectly, and this tool finds the best-fitting parameters of the target lens model. Two different methods are implemented: 1. If the given cameramodel file contains optimization_inputs, then we have all the data that was used to compute this model in the first place, and we can re-run the original optimization, using the new lens model. This is the default behavior, and is the preferred choice. However it can only work with models that were computed by mrcal originally. We re-run the full original solve, even it contained multiple cameras, unless --monocular is given. With that option, we re-solve only the subset of the images observed by the one requested camera 2. We can sample a grid of points on the imager, unproject them to observation vectors in the camera coordinate system, and then fit a new camera model that reprojects these vectors as closely to the original pixel coordinates as possible. This can be applied to models that didn't come from mrcal. Select this mode by passing --sampled. Since camera models (lens parameters AND geometry) are computed off real pixel observations, the confidence of the projections varies greatly across the imager and across observation distances. The first method uses the original data, so it implicitly respects these uncertainties: uncertain areas in the original model will be uncertain in the new model as well. The second method, however, doesn't have this information: it doesn't know which parts of the imager and space are reliable, so the results suffer. As always, the intrinsics have some baked-in geometry information. Both methods optimize intrinsics AND extrinsics, and output cameramodels with updated versions of both. If --sampled: we can request that only the intrinsics be optimized by passing --intrinsics-only. Also, if --sampled and not --intrinsics-only: we fit the extrinsics off 3D points, not just observation directions. The distance from the camera to the points is set by --distance. This can take a comma-separated list of distances to use. It's STRONGLY recommended to ask for two different distances: - A "near" distance: where we expect the intrinsics to have the most accuracy. At the range of the chessboards, usually - A "far" distance: at "infinity". A few km is good usually. The reason for this is that --sampled solves at a single distance aren't sufficiently constrained. If we ask for a single far distance: "--distance 1000" for instance, we can easily get an extrinsics shift of 100m. This is aphysical: changing the intrinsics could shift the camera origin by a few mm, but not 100m. Conceptually we want to perform a rotation-only extrinsics solve, but this isn't yet implemented. Passing both a near and far distance appears to constrain the extrinsics well in practice. The computed extrinsics transform is printed on the console, with a warning if an aphysical shift was computed. Do pay attention to the console output. Sampled solves are sometimes sensitive to the optimization seed. To control for this, pass --num-trials to evaluate the solve multiple times from different random seeds, and to pick the best one. These solves are usually quick, so there's no harm in passing something like "--num-trials 10". We need to consider that the model we're trying to fit may not fit the original model in all parts of the imager. Usually this is a factor when converting wide-angle cameramodels to use a leaner model: a decent fit will be possible at the center, with more and more divergence as we move towards the edges. We handle this with the --where and --radius options to allow the user to select the area of the imager that is used for the fit: observations outside the selected area are thrown out. This region is centered on the point given by --where (or at the center of the imager, if --where is omitted). The radius of this region is given by --radius. If '--radius 0' then we use ALL the data. A radius<0 can be used to set the size of the no-data margin at the corners; in this case I'll use r = sqrt(width^2 + height^2)/2. - abs(radius) There's a balance to strike here. A larger radius means that we'll try to fit as well as we can in a larger area. This might mean that we won't fit well anywhere, but we won't do terribly anywhere, either. A smaller area means that we give up on the outer regions entirely (resulting in very poor fits there), but we'll be able to fit much better in the areas that remain. Generally empirical testing is required to find a good compromise: pass --viz to see the resulting differences. Note that --radius and --where applies only if we're optimizing sampled reprojections; if we're using the original optimization inputs, the options are illegal. The output is written to a file on disk, with the same filename as the input model, but with the new lensmodel added to the filename. ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--sampled', action='store_true', help='''Instead of solving the original calibration problem using the new lens model, use sampled imager points. This produces biased results, but can be used even if the original optimization_inputs aren't available''') parser.add_argument('--gridn', type=int, default = (30,20), nargs = 2, help='''Used if --sampled. How densely we should sample the imager. By default we use a 30x20 grid''') parser.add_argument('--distance', type=str, help='''Required if --sampled and not --intrinsics-only. A sampled solve fits the intrinsics and extrinsics to match up reprojections of a grid of observed pixels. The points being projected are set a particular distance (set by this argument) from the camera. Set this to the distance that is expected to be most confident for the given cameramodel. Points at infinity aren't supported yet: specify a high distance instead. We can fit multiple distances at the same time by passing them here in a comma-separated, whitespace-less list. If multiple distances are given, we fit the model using ALL the distances, but --viz displays the difference for the FIRST distance given. See the description above. Without --sampled, this is used for the visualization only''') parser.add_argument('--intrinsics-only', action='store_true', help='''Used if --sampled. By default I optimize the intrinsics and extrinsics to find the closest reprojection. If for whatever reason we know that the camera coordinate system was already right, or we need to keep the original extrinsics, pass --intrinsics-only. The resulting extrinsics will be the same, but the fit will not be as good. In many cases, optimizing extrinsics is required to get a usable fit, so --intrinsics-only may not be an option if accurate results are required.''') parser.add_argument('--where', type=float, nargs=2, help='''Used with or without --sampled. I use a subset of the imager to compute the fit. The active region is a circle centered on this point. If omitted, we will focus on the center of the imager''') parser.add_argument('--radius', type=float, help='''Used with or without --sampled. I use a subset of the imager to compute the fit. The active region is a circle with a radius given by this parameter. If radius == 0, I'll use the whole imager for the fit. If radius < 0, this parameter specifies the width of the region at the corners that I should ignore: I will use sqrt(width^2 + height^2)/2. - abs(radius). This is valid ONLY if we're focusing at the center of the imager. By default I ignore a large-ish chunk area at the corners.''') parser.add_argument('--monocular', action='store_true', help='''Used if not --sampled. By default we re-solve the full calibration problem that was used to originally obtain the input model, even if it contained multiple cameras. If --monocular, we re-solve only a subset of the original problem, using ONLY the observations made by THIS camera''') parser.add_argument('--viz', action='store_true', help='''Visualize the differences between the input and output models. If we have --distance, the FIRST given distance is used to display the fit error''') parser.add_argument('--cbmax', type=float, default=4, help='''Maximum range of the colorbar''') parser.add_argument('--title', type=str, default = None, help='''Used if --viz. Title string for the diff plot. Overrides the default title. Exclusive with --extratitle''') parser.add_argument('--extratitle', type=str, default = None, help='''Used if --viz. Additional string for the plot to append to the default title. Exclusive with --title''') parser.add_argument('--hardcopy', type=str, help='''Used if --viz. Write the diff output to disk, instead of making an interactive plot''') parser.add_argument('--terminal', type=str, help=r'''Used if --viz. gnuplotlib terminal. The default is good almost always, so most people don't need this option''') parser.add_argument('--set', type=str, action='append', help='''Used if --viz. Extra 'set' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('--unset', type=str, action='append', help='''Used if --viz. Extra 'unset' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('--force', '-f', action='store_true', default=False, help='''By default existing models on disk are not overwritten. Pass --force to overwrite them without complaint''') parser.add_argument('--outdir', type=lambda d: d if os.path.isdir(d) else \ parser.error(f"--outdir requires an existing directory as the arg, but got '{d}'"), help='''Directory to write the output into. If omitted, we use the directory of the input model''') parser.add_argument('--num-trials', type = int, default = 1, help='''If given, run the solve more than once. Useful in case random initialization produces noticeably different results. By default we run just one trial, which is enough most of the time''') parser.add_argument('to', type=str, help='The target lens model') parser.add_argument('model', default='-', nargs='?', type=str, help='''Input camera model. If omitted or "-", we read standard input and write to standard output''') args = parser.parse_args() if args.title is not None and \ args.extratitle is not None: print("Error: --title and --extratitle are exclusive", file=sys.stderr) sys.exit(1) if args.distance is not None: try: args.distance = [float(d) for d in args.distance.split(',')] except: print("Error: distances must be given a comma-separated list of floats in --distance", file=sys.stderr) sys.exit(1) return args args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README import numpy as np import numpysane as nps import time import copy import mrcal lensmodel_to = args.to try: meta = mrcal.lensmodel_metadata_and_config(lensmodel_to) except Exception as e: print(f"Invalid lens model '{lensmodel_to}': couldn't get the metadata: {e}", file=sys.stderr) sys.exit(1) if not meta['has_gradients']: print(f"lens model {lensmodel_to} is not supported at this time: its gradients aren't implemented", file=sys.stderr) sys.exit(1) try: Ndistortions = mrcal.lensmodel_num_params(lensmodel_to) - 4 except: print(f"Unknown lens model: '{lensmodel_to}'", file=sys.stderr) sys.exit(1) try: m = mrcal.cameramodel(args.model) except Exception as e: print(f"Couldn't load camera model '{args.model}': {e}", file=sys.stderr) sys.exit(1) if args.model == '-': # Input read from stdin. Write output to stdout file_output = sys.stdout else: if args.outdir is None: filename_base,extension = os.path.splitext(args.model) file_output = f"{filename_base}-{lensmodel_to}{extension}" else: f,extension = os.path.splitext(args.model) directory,filename_base = os.path.split(f) file_output = f"{args.outdir}/{filename_base}-{lensmodel_to}{extension}" if os.path.exists(file_output) and not args.force: print(f"ERROR: '{file_output}' already exists. Not overwriting this file. Pass -f to overwrite", file=sys.stderr) sys.exit(1) lensmodel_from = m.intrinsics()[0] if lensmodel_from == lensmodel_to: print(f"Input and output have the same lens model {lensmodel_from}. Nothing to do", file=sys.stderr) print("RMS error of the solution: 0 pixels.", file=sys.stderr) sys.exit(0) if not args.sampled: if args.intrinsics_only: print("--intrinsics-only requires --sampled", file=sys.stderr) sys.exit(1) if not (mrcal.lensmodel_metadata_and_config(lensmodel_from)['has_core'] and \ mrcal.lensmodel_metadata_and_config(lensmodel_to )['has_core']): print("Without --sampled, the TO and FROM models must support contain an intrinsics core. It COULD work otherwise, but somebody needs to implement it", file=sys.stderr) sys.exit(1) optimization_inputs = m.optimization_inputs() if optimization_inputs is None: print("optimization_inputs not available in this model, so only sampled fits are possible. Pass --sampled", file=sys.stderr) sys.exit(1) icam_intrinsics = m.icam_intrinsics() if args.monocular: if optimization_inputs['indices_point_camintrinsics_camextrinsics'] is not None and \ optimization_inputs['indices_point_camintrinsics_camextrinsics'].size > 0: print("--monocular can be used ONLY to re-optimize vanilla calibration problems. This one has points", file=sys.stderr) sys.exit(1) intrinsics = \ optimization_inputs['intrinsics'] imagersizes = \ optimization_inputs['imagersizes'] extrinsics_rt_fromref = \ optimization_inputs['extrinsics_rt_fromref'] frames_rt_toref = \ optimization_inputs['frames_rt_toref'] indices_frame_camintrinsics_camextrinsics = \ optimization_inputs['indices_frame_camintrinsics_camextrinsics'] observations_board = \ optimization_inputs['observations_board'] if 'imagepaths' in optimization_inputs: imagepaths = \ optimization_inputs['imagepaths'] mask_observations = indices_frame_camintrinsics_camextrinsics[:,1] == icam_intrinsics indices_frame_camintrinsics_camextrinsics = \ indices_frame_camintrinsics_camextrinsics[mask_observations] observations_board = \ observations_board[mask_observations] if 'imagepaths' in optimization_inputs: imagepaths = \ imagepaths[mask_observations] ### Now I must cull the extrinsics and frames to only use these ### observations # intrinsics indices_frame_camintrinsics_camextrinsics[:,1] = 0 intrinsics = intrinsics [(icam_intrinsics,), :] imagersizes = imagersizes[(icam_intrinsics,), :] # extrinsics icam_extrinsics = \ indices_frame_camintrinsics_camextrinsics[0,2] if not np.all(indices_frame_camintrinsics_camextrinsics[:,2] == icam_extrinsics): print("Error: --monocular can work ONLY if the calibration-time cameras are stationary. Here the requested camera was moving", file=sys.stderr) sys.exit(1) indices_frame_camintrinsics_camextrinsics[:,2] = -1 if icam_extrinsics >= 0: # I'm moving the reference to lie at this one new camera. Transform # everything rt_cam_reforig = extrinsics_rt_fromref[icam_extrinsics] rt_refnew_reforig = rt_cam_reforig frames_rt_toref = mrcal.compose_rt( rt_refnew_reforig, frames_rt_toref ) extrinsics_rt_fromref = np.empty((0,6), dtype=float) # frames frames_rt_toref = frames_rt_toref[indices_frame_camintrinsics_camextrinsics[:,0], :] Nframes = len(indices_frame_camintrinsics_camextrinsics) indices_frame_camintrinsics_camextrinsics[:,0] = np.arange(Nframes) # store everythin back into the inputs optimization_inputs['intrinsics'] = \ intrinsics optimization_inputs['imagersizes'] = \ imagersizes optimization_inputs['extrinsics_rt_fromref'] = \ extrinsics_rt_fromref optimization_inputs['frames_rt_toref'] = \ frames_rt_toref optimization_inputs['indices_frame_camintrinsics_camextrinsics'] = \ indices_frame_camintrinsics_camextrinsics optimization_inputs['observations_board'] = \ observations_board if 'imagepaths' in optimization_inputs: optimization_inputs['imagepaths'] = \ imagepaths icam_intrinsics = 0 optimization_inputs_before = copy.deepcopy(optimization_inputs) intrinsics_from = optimization_inputs['intrinsics'] intrinsics_from_core = intrinsics_from[..., :4] Ncameras = len(intrinsics_from) # Ignore observations in the corners, as requested if not (args.radius is None or args.radius == 0): for icam in range(Ncameras): dims = optimization_inputs['imagersizes'][icam].astype(float) if args.where is None: focus_center = (dims - 1) / 2 else: focus_center = args.where if args.radius > 0: r = args.radius else: if nps.norm2(focus_center - (dims - 1.) / 2) > 1e-3: print("A radius <0 is only implemented if we're focusing on the imager center", file=sys.stderr) sys.exit(1) r = nps.mag(dims)/2. + args.radius indices_cam = optimization_inputs['indices_frame_camintrinsics_camextrinsics'][:,1] observations = optimization_inputs['observations_board'] mask_thiscam = indices_cam == icam mask_past_radius = nps.norm2(observations[...,:2] - focus_center) > r*r observations[nps.mv(mask_thiscam, -1, -3) * mask_past_radius, 2] = -1 optimization_inputs['verbose'] = False optimization_inputs['lensmodel'] = lensmodel_to optimization_inputs['intrinsics'] = np.zeros((Ncameras,Ndistortions+4), dtype=float) optimization_inputs['intrinsics'][:,:4] = intrinsics_from_core # I do this in stages, similar to how mrcal-calibrate-cameras does it. First # just the frames and extrinsics. Assuming a core-only intrinsics optimization_inputs['do_optimize_intrinsics_core'] = False optimization_inputs['do_optimize_intrinsics_distortions']= False optimization_inputs['do_optimize_calobject_warp'] = False optimization_inputs['do_apply_outlier_rejection'] = False optimization_inputs['do_apply_regularization'] = False stats = mrcal.optimize(**optimization_inputs) # Then I optimize the core also optimization_inputs['do_optimize_intrinsics_core'] = True stats = mrcal.optimize(**optimization_inputs) # Then the intrinsics too optimization_inputs['do_optimize_intrinsics_distortions']= True optimization_inputs['do_apply_outlier_rejection'] = True optimization_inputs['do_apply_regularization'] = True if re.match("LENSMODEL_SPLINED_STEREOGRAPHIC_", lensmodel_to): # splined models have a core, but those variables are largely redundant # with the spline parameters. So I lock down the core when targeting # splined models optimization_inputs['do_optimize_intrinsics_core'] = False # stolen expand_intrinsics() in mrcal-calibrate-extrinsics. Please consolidate optimization_inputs['intrinsics'][:,4:] = \ (np.random.random((Ncameras, Ndistortions)) - 0.5)*2. *1e-6 modelmatch = re.search("OPENCV([0-9]+)", lensmodel_to) if modelmatch: Nd = int(modelmatch.group(1)) if Nd >= 8: # Push down the rational components of the seed. I'd like these all to # sit at 0 ideally. The radial distortion in opencv is x_distorted = # x*scale where r2 = norm2(xy - xyc) and # # scale = (1 + k0 r2 + k1 r4 + k4 r6)/(1 + k5 r2 + k6 r4 + k7 r6) # # Note that k2,k3 are tangential (NOT radial) distortion components. # Note that the r6 factor in the numerator is only present for # >=LENSMODEL_OPENCV5. Note that the denominator is only present for >= # LENSMODEL_OPENCV8. The danger with a rational model is that it's # possible to get into a situation where scale ~ 0/0 ~ 1. This would # have very poorly behaved derivatives. If all the rational coefficients # are ~0, then the denominator is always ~1, and this problematic case # can't happen. I favor that. optimization_inputs['intrinsics'][:,4:][:,5:8] *= 1e-3 stats = mrcal.optimize(**optimization_inputs) # And finally I do the calobject_warp too optimization_inputs['do_optimize_calobject_warp'] = True stats = mrcal.optimize(**optimization_inputs) # I pick the inlier set using the post-solve inliers/outliers. The solve # could add some outliers, but it won't take any away, so the union of the # before/after inlier sets is just the post-solve set idx_inliers_after = optimization_inputs['observations_board'][...,2] > 0 calobject_camframe_before = \ mrcal.hypothesis_board_corner_positions(icam_intrinsics, **optimization_inputs_before, idx_inliers = idx_inliers_after )[-2] calobject_camframe_after = \ mrcal.hypothesis_board_corner_positions(icam_intrinsics, **optimization_inputs, idx_inliers = idx_inliers_after )[-2] # This is a procrustes-based transformation. This transform is usable, but # isn't based on camera observations, and often produces poor diffs if used # directly. Let mrcal.projection_diff() figure out the implied_Rt10 instead # of using this implied_Rt10 = mrcal.align_procrustes_points_Rt01(calobject_camframe_after, calobject_camframe_before) # For the purposes of visualization I use what I was given. Or the mean # observation distance if I was given nothing if args.distance is None: distance_for_diff = np.mean(nps.mag(calobject_camframe_after)) else: distance_for_diff = np.array(args.distance) print(f"RMS error of the solution: {stats['rms_reproj_error__pixels']} pixels.", file=sys.stderr) m_to = mrcal.cameramodel( optimization_inputs = optimization_inputs, icam_intrinsics = icam_intrinsics ) else: # Sampled solve. I grid the imager, unproject and fit intrinsics_from = m.intrinsics() if args.distance is None: if args.intrinsics_only: # We're only looking at the intrinsics, so the distance doesn't # matter. I pick an arbitrary value args.distance = [10.] else: print("--sampled without --intrinsics-only REQUIRES --distance", file=sys.stderr) sys.exit(1) if args.monocular: print("--monocular doesn't work with --sampled", file=sys.stderr) sys.exit(1) dims = m.imagersize() if dims is None: print("Warning: imager size not available. Using centerpixel*2", file=sys.stderr) dims = intrinsics_from[1][2:4] * 2 if args.radius is None: # By default use 1/4 of the smallest dimension args.radius = -np.min(m.imagersize()) // 4 print(f"Default radius: {args.radius}. We're ignoring the regions {-args.radius} pixels from each corner", file=sys.stderr) if args.where is not None and \ nps.norm2(args.where - (dims - 1.) / 2) > 1e-3: print("A radius <0 is only implemented if we're focusing on the imager center: use an explicit --radius, or omit --where", file=sys.stderr) sys.exit(1) # Alrighty. Let's actually do the work. I do this: # # 1. Sample the imager space with the known model # 2. Unproject to get the 3d observation vectors # 3. Solve a new model that fits those vectors to the known observations, but # using the new model ### I sample the pixels in an NxN grid Nx,Ny = args.gridn qx = np.linspace(0, dims[0]-1, Nx) qy = np.linspace(0, dims[1]-1, Ny) # q is (Ny*Nx, 2). Each slice of q[:] is an (x,y) pixel coord q = np.ascontiguousarray( nps.transpose(nps.clump( nps.cat(*np.meshgrid(qx,qy)), n=-2)) ) if args.radius != 0: # we use a subset of the input data for the fit if args.where is None: focus_center = (dims - 1.) / 2. else: focus_center = args.where if args.radius > 0: r = args.radius else: if nps.norm2(focus_center - (dims - 1.) / 2) > 1e-3: print("A radius <0 is only implemented if we're focusing on the imager center", file=sys.stderr) sys.exit(1) r = nps.mag(dims)/2. + args.radius grid_off_center = q - focus_center i = nps.norm2(grid_off_center) < r*r q = q[i, ...] # To visualize the sample grid: # import gnuplotlib as gp # gp.plot(q[:,0], q[:,1], _with='points pt 7 ps 2', xrange=[0,3904],yrange=[3904,0], wait=1, square=1) # sys.exit() intrinsics_from = m.intrinsics() ### I unproject this, with broadcasting # shape (Ndistances,) d = np.array(args.distance) # shape (Ndistances, Ny*Nx, 2) q = q * np.ones((d.size,1,1)) # shape (Ndistances, Ny*Nx, 3) p = mrcal.unproject( q, *intrinsics_from, normalize = True ) * \ nps.mv(d, -1, -3) # shape (Ndistances*Ny*Nx, 2) q = nps.clump(q, n=2) # shape (Ndistances*Ny*Nx, 3) p = nps.clump(p, n=2) # The list of distances. The meaning is the same as expected by # mrcal.show_projection_diff(): we visualize the diff of the FIRST distance distance_for_diff = d # Ignore any failed unprojections i_finite = np.isfinite(p[:,0]) p = p[i_finite] q = q[i_finite] Npoints = len(q) weights = np.ones((Npoints,), dtype=float) ### Solve! ### I solve the optimization a number of times with different random seed ### values, taking the best-fitting results. This is required for the richer ### models such as LENSMODEL_OPENCV8 err_rms_best = 1e10 intrinsics_data_best = None extrinsics_rt_fromref_best = None for i in range(args.num_trials): # random seed for the new intrinsics intrinsics_core = intrinsics_from[1][:4] distortions = (np.random.rand(Ndistortions) - 0.5) * 1e-3 # random initial seed intrinsics_to_values = nps.dummy(nps.glue(intrinsics_core, distortions, axis=-1), axis=-2) # each point has weight 1.0 observations_points = nps.glue(q, nps.transpose(weights), axis=-1) observations_points = np.ascontiguousarray(observations_points) # must be contiguous. mrcal.optimize() should really be more lax here # Which points we're observing. This is dense and kinda silly for this # application. Each slice is (i_point,i_camera,i_camera-1). Initially O # do everything in camera-0 coordinates, and I do not move the # extrinsics indices_point_camintrinsics_camextrinsics = np.zeros((Npoints,3), dtype=np.int32) indices_point_camintrinsics_camextrinsics[:,0] = \ np.arange(Npoints, dtype=np.int32) indices_point_camintrinsics_camextrinsics[:,1] = 0 indices_point_camintrinsics_camextrinsics[:,2] = -1 optimization_inputs = \ dict(intrinsics = intrinsics_to_values, extrinsics_rt_fromref = None, frames_rt_toref = None, # no frames. Just points points = p, observations_board = None, # no board observations indices_frame_camintrinsics_camextrinsics = None, # no board observations observations_point = observations_points, indices_point_camintrinsics_camextrinsics = indices_point_camintrinsics_camextrinsics, lensmodel = lensmodel_to, imagersizes = nps.atleast_dims(dims, -2), # I'm not optimizing the point positions (frames), so these # need to be set to be inactive, and to include the ranges I do # have point_min_range = np.min(d) * 0.9, point_max_range = np.max(d) * 1.1, # I optimize the lens parameters. That's the whole point do_optimize_intrinsics_core = True, do_optimize_intrinsics_distortions = True, do_optimize_extrinsics = False, # NOT optimizing the observed point positions do_optimize_frames = False ) if re.match("LENSMODEL_SPLINED_STEREOGRAPHIC_", lensmodel_to): # splined models have a core, but those variables are largely redundant # with the spline parameters. So I lock down the core when targetting # splined models optimization_inputs['do_optimize_intrinsics_core'] = False stats = mrcal.optimize(**optimization_inputs, # No outliers. I have the points that I have do_apply_outlier_rejection = False, verbose = False) if not args.intrinsics_only: # go again, but refine this solution, allowing us to fit the # extrinsics too optimization_inputs['indices_point_camintrinsics_camextrinsics'][:,2] = \ np.zeros ((Npoints,), dtype = np.int32) optimization_inputs['extrinsics_rt_fromref'] = (np.random.rand(1,6) - 0.5) * 1e-6 optimization_inputs['do_optimize_extrinsics'] = True stats = mrcal.optimize(**optimization_inputs, # No outliers. I have the points that I have do_apply_outlier_rejection = False, verbose = False) err_rms = stats['rms_reproj_error__pixels'] print(f"RMS error of this solution: {err_rms} pixels.", file=sys.stderr) if err_rms < err_rms_best: err_rms_best = err_rms intrinsics_data_best = optimization_inputs['intrinsics'][0,:].copy() if not args.intrinsics_only: extrinsics_rt_fromref_best = optimization_inputs['extrinsics_rt_fromref'][0,:].copy() if intrinsics_data_best is None: print("No valid intrinsics found!", file=sys.stderr) sys.exit(1) if args.num_trials > 1: print(f"RMS error of the BEST solution: {err_rms_best} pixels.", file=sys.stderr) m_to = mrcal.cameramodel( intrinsics = (lensmodel_to, intrinsics_data_best.ravel()), imagersize = dims ) if args.intrinsics_only: implied_Rt10 = mrcal.identity_Rt() else: implied_Rt10 = mrcal.Rt_from_rt(extrinsics_rt_fromref_best) if not (args.sampled and args.intrinsics_only): implied_rt10 = mrcal.rt_from_Rt(implied_Rt10) print(f"Transformation cam_fitted <-- cam_input: rotation: {nps.mag(implied_rt10[:3])*180./np.pi:.03f} degrees, translation: {np.array2string(implied_rt10[3:], precision=2)} m", file=sys.stderr) dist_shift = nps.mag(implied_rt10[3:]) if dist_shift > 0.01: msg = f"## WARNING: fitted camera moved by {dist_shift:.03f}m. This is probably aphysically high, and something is wrong." if args.distance is not None and args.sampled: print(msg + " Pass both a high and a low --distance?", file=sys.stderr) else: print(msg, file=sys.stderr) m_to.extrinsics_Rt_fromref( mrcal.compose_Rt( implied_Rt10, mrcal.Rt_from_rt( m.extrinsics_rt_fromref()))) note = \ "generated on {} with {}\n". \ format(time.strftime("%Y-%m-%d %H:%M:%S"), ' '.join(mrcal.shellquote(s) for s in sys.argv)) m_to.write(file_output, note=note) if isinstance(file_output, str): print(f"Wrote '{file_output}'", file=sys.stderr) if args.viz: plotkwargs_extra = {} if args.set is not None: plotkwargs_extra['set'] = args.set if args.unset is not None: plotkwargs_extra['unset'] = args.unset if args.title is not None: plotkwargs_extra['title'] = args.title if args.extratitle is not None: plotkwargs_extra['extratitle'] = args.extratitle # If this is a sampled solve, we don't have projection uncertainties. But we # do have an implied_Rt10 based on observations, and we can feed that to the # diff directly. # # If this is NOT a sampled solve, then the implied_Rt10 comes from a # Procrustes fit (minimizing error in 3D space), which is usually not # close-enough to get a diff. We let the diff method figure out the # implied_Rt10, and we use the uncertainties that we have to do it if args.sampled: use_uncertainties = False else: implied_Rt10 = None use_uncertainties = True plot,_ = mrcal.show_projection_diff( (m, m_to), implied_Rt10 = implied_Rt10, distance = distance_for_diff, cbmax = args.cbmax, gridn_width = None if args.gridn is None else args.gridn[0], gridn_height = None if args.gridn is None else args.gridn[1], use_uncertainties = use_uncertainties, hardcopy = args.hardcopy, terminal = args.terminal, **plotkwargs_extra) if args.hardcopy is None: plot.wait() mrcal-2.4.1/mrcal-cull-corners000077500000000000000000000236601456301662300162630ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Filters a corners.vnl on stdin to cut out some points SYNOPSIS $ < corners.vnl mrcal-cull-corners --cull-left-of 1000 > corners.culled.vnl This tool reads a set of corner detections on stdin, throws some of them out, and writes the result to stdout. This is useful for testing and evaluating the performance of the mrcal calibration tools. The specific operation of this tool is defined on which --cull-... option is given. Exactly one is required: --cull-left-of X: throw away all corner observations to the left of the given X coordinate --cull-rad-off-center D: throw away all corner observations further than D away from the center. --imagersize or --where must be given also so that we know where the center is. If D < 0: we cull the points -D or closer to the corners: we use a radius of sqrt(width^2 + height^2)/2. - abs(D) --cull-random-observations-ratio R: throws away a ratio R object observations at random. To throw out half of all object observations, pass R = 0.5. --object-width-n and --object-height-n are then required to make the parsing work --cull-left-of X and --cull-rad-off-center throw out individual points. This is done by keeping the point in the output data stream, but setting its decimation level to '-'. The downstream tools then know to ignore those points --cull-random-observations-ratio throws out whole object observations, not just individual points. These removed observations do not appear in the output data stream at all This tool exists primarily for testing, and probably you don't want to use it. The filtering is crude, and the tool might report chessboard observations with very few remaining points. You PROBABLY want to post-process the output to keep only observations with enough points. For instance: mrcal-cull-corners ... > culled-raw.vnl vnl-join --vnl-sort - -j filename culled-raw.vnl \ <(< culled-raw.vnl vnl-filter -p filename --has level | vnl-uniq -c | vnl-filter 'count > 20' -p filename ) \ > culled.vnl ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--object-width-n', type=int, help='''How many points the calibration board has per horizontal side. This is required if --cull-random-observation-ratio''') parser.add_argument('--object-height-n', type=int, help='''How many points the calibration board has per vertical side. If omitted, I assume a square object and use the same value as --object-width-n''') parser.add_argument('--imagersize', nargs=2, type=int, help='''Size of the imager. If --cull-rad-off-center is given: we require --imagersize or --where''') parser.add_argument('--cull-left-of', required=False, type=float, help='''Throw out all observations with x < the given value. Exclusive with the other --cull-... options''') parser.add_argument('--cull-rad-off-center', required=False, type=float, help='''Throw out all observations with dist_from_center > the given value. Exclusive with the other --cull-... options. If --cull-rad-off-center is given: we require --imagersize or --where''') parser.add_argument('--cull-random-observations-ratio', required=False, type=float, help='''Throw out a random number of board observations. The ratio of observations is given as the argument. 1.0 = throw out ALL the observations; 0.0 = throw out NONE of the observations. Exclusive with the other --cull-... options''') parser.add_argument('--where', type=float, nargs=2, help='''Used with --cull-rad-off-center. Specifies the location of the "center" point. If omitted, we use the center of the imager. May NOT be given if --cull-rad-off-center < 0. If --cull-rad-off-center is given: we require --imagersize or --where''') parser.add_argument('--filename', type=str, action='append', help='''Apply the filtering only to observations where the filename matches the given regex. May be given multiple times: filenames that match ANY of the given regexen are culled. If omitted, we cull ALL the observations. Exclusive with --cull-random-observations-ratio''') return parser.parse_args() args = parse_args() Nculloptions = 0 if args.cull_left_of is not None: Nculloptions += 1 if args.cull_rad_off_center is not None: Nculloptions += 1 if args.cull_random_observations_ratio is not None: Nculloptions += 1 if Nculloptions != 1: print("Exactly one --cull-... option must be given", file=sys.stderr) sys.exit(1) if args.object_width_n is not None and args.object_height_n is None: args.object_height_n = args.object_width_n if args.cull_random_observations_ratio: if (args.object_width_n is None or args.object_height_n is None): print("--cull-random-observation-ratio requires --object-width-n and --object-height-n", file=sys.stderr) sys.exit(1) if args.filename is not None: print("--cull-random-observation-ratio is exclusive with --filename", file=sys.stderr) sys.exit(1) if args.cull_rad_off_center is not None: if args.imagersize is None and args.where is None: print("--cull-rad-off-center requires --imagersize or --where", file=sys.stderr) sys.exit(1) if args.cull_rad_off_center < 0 and args.where is not None: print("--cull-rad-off-center < 0 may not be given with --where", file=sys.stderr) sys.exit(1) import re import numpy as np import numpysane as nps import mrcal import time print(f"## generated on {time.strftime('%Y-%m-%d %H:%M:%S')} with {' '.join(mrcal.shellquote(s) for s in sys.argv)}") if args.cull_left_of is not None or args.cull_rad_off_center is not None: # Simple file parsing. if args.filename is None: filename_filter = None else: filename_filter_string = '|'.join(f"(?:{s})" for s in args.filename) filename_filter = re.compile(filename_filter_string) if args.cull_rad_off_center is not None: if args.cull_rad_off_center >= 0: if args.where is None: c = (np.array(args.imagersize, dtype=float) - 1.) / 2. else: c = np.array(args.where, dtype=float) r = args.cull_rad_off_center else: dims = np.array(args.imagersize, dtype=float) c = (dims - 1.) / 2. r = nps.mag(dims)/2. + args.cull_rad_off_center for l in sys.stdin: if re.match('\s*(?:##|$)',l): sys.stdout.write(l) continue if l == '# filename x y level\n': sys.stdout.write(l) break print("This tool REQUIRES a vnlog with legend matching EXACTLY '# filename x y level'. Giving up", file=sys.stderr) sys.exit(1) for l in sys.stdin: if re.match('\s*(?:#|$)',l): sys.stdout.write(l) continue f = l.split() if f[1] == '-': sys.stdout.write(l) continue if filename_filter is not None and \ not filename_filter.search(f[0]): sys.stdout.write(l) continue if args.cull_left_of is not None and float(f[1]) > args.cull_left_of: sys.stdout.write(l) continue if args.cull_rad_off_center is not None and \ nps.norm2(np.array((float(f[1]), float(f[2]))) - c) < r*r: sys.stdout.write(l) continue # Cull the point! f[3] = '-' sys.stdout.write(' '.join(f) + '\n') sys.exit() observations, _, paths = \ mrcal.compute_chessboard_corners(W = args.object_width_n, H = args.object_height_n, corners_cache_vnl = sys.stdin, weight_column_kind = 'weight') N_keep = int(round((1.0 - args.cull_random_observations_ratio) * len(observations))) indices_keep = np.sort(np.random.choice(len(observations), N_keep, replace=False)) # shape (N, Nh,Nw,3) observations = observations[indices_keep] paths = [paths[i] for i in indices_keep] # shape (N, Nh*Nw, 3) observations = nps.mv( nps.clump(nps.mv(observations, -1,-3), n = -2), -2, -1) # I cut out the data. Now I reconstitute the corners.vnl print('# filename x y level') for i in range(len(paths)): path = paths[i] for j in range(observations.shape[-2]): l = observations[i][j][2] if l < 0: l = '-' else: l = int(l) print(f"{path} {observations[i][j][0]} {observations[i][j][1]} {l}") mrcal-2.4.1/mrcal-from-cahvor000077500000000000000000000072111456301662300160700ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Converts a .cahvor-formatted camera model to the .cameramodel file format SYNOPSIS $ mrcal-from-cahvor model1.cahvor model2.cahvor Wrote model1.cameramodel Wrote model2.cameramodel File formats supported by mrcal are described at http://mrcal.secretsauce.net/cameramodels.html#cameramodel-file-formats This tool converts the given model(s) to the cameramodel file format. No changes to the content are made; this is purely a format converter (the mrcal-convert-lensmodel tool fits different lens models instead). Model filenames are given on the commandline. Output is written to the same directory, with the same filename, but with a .cameramodel extension. If the model is omitted or given as "-", the input is read from standard input, and the output is written to standard output ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--force', '-f', action='store_true', default=False, help='''By default existing files are not overwritten. Pass --force to overwrite them without complaint''') parser.add_argument('--outdir', required=False, type=lambda d: d if os.path.isdir(d) else \ parser.error("--outdir requires an existing directory as the arg, but got '{}'".format(d)), help='''Directory to write the output models into. If omitted, we write the output models to the same directory as the input models''') parser.add_argument('model', default=['-'], nargs='*', type=str, help='''Input camera model''') return parser.parse_args() args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README Nstdin = sum(1 for m in args.model if m=='-') if Nstdin > 1: print(f"At most one model can be read from standard input ('-'), but I got {Nstdin}", file=sys.stderr) sys.exit(1) import mrcal for model in args.model: if model == '-': try: m = mrcal.cameramodel(model) except KeyboardInterrupt: sys.exit(1) except Exception as e: print(e, file=sys.stderr) sys.exit(1) m.write(sys.stdout) else: base,extension = os.path.splitext(model) if extension.lower() == '.cameramodel': print("Input file is already in the cameramodel format (judging from the filename). Doing nothing", file=sys.stderr) sys.exit(0) if args.outdir is not None: base = args.outdir + '/' + os.path.split(base)[1] filename_out = base + '.cameramodel' if not args.force and os.path.exists(filename_out): print(f"Target model '{filename_out}' already exists. Doing nothing with this model. Pass -f to overwrite", file=sys.stderr) else: m = mrcal.cameramodel(model) m.write(filename_out) print("Wrote " + filename_out) mrcal-2.4.1/mrcal-from-kalibr000077500000000000000000000335371456301662300160640ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Converts a kalibr-formatted camera model to the .cameramodel file format SYNOPSIS $ mrcal-from-kalibr model.yaml Wrote model-cam0.cameramodel Wrote model-cam1.cameramodel File formats supported by mrcal are described at http://mrcal.secretsauce.net/cameramodels.html#cameramodel-file-formats This tool converts the given model(s) to the mrcal-native .cameramodel file format. No changes to the content are made; this is purely a format converter (the mrcal-convert-lensmodel tool fits different lens models instead). Model filenames are given on the commandline. Output is written to the same directory, with the same filename, but annotated with the camera name from the data file, and with a .cameramodel extension. If the model is omitted or given as "-", the input is read from standard input, and the output is written to standard output Unlike mrcal .cameramodel files where one camera is described by one file, the .yaml files used by kalibr are intended to describe multiple cameras. This format conversion tool will write out multiple .cameramodel file to represent the given data. To select a single camera, pass --camera CAMERA. By default we set the extrinsics of camera-0 as they appear in the input: the "previous" camera from camera-0 is used as the reference coordinate system. If we want to force camera-0 to have an identity transform, pass --cam0-at-reference. Usually this will be the case anyway in the input data, but this option makes sure. The kalibr format is described at https://github.com/ethz-asl/kalibr/wiki/Yaml-formats At this time we only support - LENSMODEL_PINHOLE - LENSMODEL_OPENCV4 - LENSMODEL_CAHVOR (experimental) - LENSMODEL_CAHVORE (experimental) which corresponds to camera_model == 'pinhole' and distortion_model in ('radtan','none') ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--cam0-at-reference', action='store_true', default=False, help='''By default we set the extrinsics of camera-0 as they appear in the input. If we want to force camera-0 to have an identity transform, pass --cam0-at-reference. Usually this will be the case anyway in the input data, but this option makes sure''') parser.add_argument('--camera', help='''Kalibr model files may contain multiple cameras, selected by this argument. If omitted, all available cameras will be read. If given, we read JUST the one requested camera''') parser.add_argument('--force', '-f', action='store_true', default=False, help='''By default existing files are not overwritten. Pass --force to overwrite them without complaint''') parser.add_argument('--outdir', required=False, type=lambda d: d if os.path.isdir(d) else \ parser.error("--outdir requires an existing directory as the arg, but got '{}'".format(d)), help='''Directory to write the output models into. If omitted, we write the output models to the same directory as the input models''') parser.add_argument('model', default=['-'], nargs='*', type=str, help='''Input camera model; '-' to read standard input''') args = parser.parse_args() if len(args.model) > 1: print("ERROR: only one input file may be processed", file=sys.stderr) sys.exit(1) args.model = args.model[0] return args args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README import mrcal import mrcal.cahvor import yaml import numpy as np import numpysane as nps Rt_camprev_ref = None # stolen from mrcal-to-kalibr. Please consolidate def Rt_is_identity(Rt): cos_th = (np.trace(Rt[:3,:]) - 1.) / 2. # cos_th ~ 1 - x^2/2 th_sq = (1 - cos_th)*2. norm2_t = nps.norm2(Rt[3,:]) return norm2_t < 1e-12 and th_sq < 1e-12 def convert_one(d,name): global Rt_camprev_ref # I expect at least this structure: # # camera_model: pinhole # intrinsics: [461.629, 460.152, 362.680, 246.049] # distortion_model: radtan # distortion_coeffs: [-0.27695497, 0.06712482, 0.00087538, 0.00011556] # resolution: [752, 480] # T_cn_cnm1: # - [ 0.99998854, 0.00216014, 0.00427195,-0.11003785] # - [-0.00221074, 0.99992702, 0.01187697, 0.00045792] # - [-0.00424598,-0.01188627, 0.99992034,-0.00064487] # - [0.0, 0.0, 0.0, 1.0] # # T_cn_cnm1 may be omitted: I use an identity transform in that case camera_model_known = set(('pinhole', 'cahvor','cahvore'),) if not d['camera_model'] in camera_model_known: print(f"ERROR: at this time I only support kalibr camera_model: {camera_model_known}; got camera_model={d['camera_model']}", file=sys.stderr) sys.exit(1) if not re.match('cahvor',d['camera_model']): # The "usual" path distortion_model_known = set(('radtan','none'),) if not d['distortion_model'] in distortion_model_known: print(f"ERROR: at this time I only support kalibr distortion_model: {distortion_model_known}; got distortion_model={d['distortion_model']}", file=sys.stderr) sys.exit(1) if d['distortion_model'] == 'radtan': intrinsics = ('LENSMODEL_OPENCV4', np.array(d['intrinsics'] + d['distortion_coeffs'], dtype=float)) else: intrinsics = ('LENSMODEL_PINHOLE', np.array(d['intrinsics'], dtype=float)) m = mrcal.cameramodel( intrinsics = intrinsics, imagersize = np.array(d['resolution'], dtype=int) ) else: # cahvor or cahvore. This can only come from the hacked kalibr at jpl if 'distortion_model' in d: print(f"ERROR: camera_model={d['camera_model']}, so no distortion_model should have been given, but we have distortion_model={d['distortion_model']}", file=sys.stderr) sys.exit(1) intrinsics = np.array(d['intrinsics']) if d['camera_model'] == 'cahvor': if intrinsics.size != 6*3: print(f"ERROR: camera_model='cahvor' should have {6*3} intrinsics values, but got {intrinsics.size}", file=sys.stderr) sys.exit(1) C,A,H,V,O,R = intrinsics.reshape(6,3) E = None else: # cahvore if intrinsics.size != 7*3: print(f"ERROR: camera_model='cahvor' should have {7*3} intrinsics values, but got {intrinsics.size}", file=sys.stderr) sys.exit(1) C,A,H,V,O,R,E = intrinsics.reshape(7,3) try: m = mrcal.cahvor._construct_model(C,A,H,V,O,R,E, is_cahvor_or_cahvore = True, is_cahvore = E is not None, cahvore_linearity = d.get('cahvore_linearity',0.37), Dimensions = np.array(d['resolution'],dtype=np.int32), name = name) except Exception as e: print(f"ERROR: couldn't parse cahvor(e) model: {e}", file=sys.stderr) sys.exit(1) if not Rt_is_identity(m.extrinsics_Rt_fromref()): print(f"ERROR: given cahvor(e) model has non-identity extrinsics. These may conflict with the extrinsics in the rest of the kalibr file", file=sys.stderr) sys.exit(1) if not 'T_cn_cnm1' in d: Rt_cam_camprev = mrcal.identity_Rt() else: T_cn_cnm1 = np.array(d['T_cn_cnm1']) if T_cn_cnm1.shape != (4,4): print(f"ERROR: T_cn_cnm1 must be a 4x4 array; got T_cn_cnm1.shape={T_cn_cnm1.shape}", file=sys.stderr) sys.exit() if np.any(T_cn_cnm1[3,:] - np.array((0,0,0,1))): print(f"ERROR: T_cn_cnm1 must have a last row of (0,0,0,1); got {T_cn_cnm1[3,:]}", file=sys.stderr) sys.exit() # The documentation is here: # # https://github.com/ethz-asl/kalibr/wiki/Yaml-formats # # It says: # # T_cn_cnm1 camera extrinsic transformation, always with respect to the # last camera in the chain (e.g. cam1: T_cn_cnm1 = T_c1_c0, takes cam0 to # cam1 coordinates) # # This isn't clear. I assume "last" means "previous" R_cam_camprev = T_cn_cnm1[:3,:3] if nps.norm2((nps.matmult(R_cam_camprev, R_cam_camprev.T) - np.eye(3)).ravel()) > 1e-12: print(f"ERROR: T_cn_cnm1[:3,:3] must be a valid rotation. Instead it is {T_cn_cnm1[:3,:3]}", file=sys.stderr) sys.exit(1) t_cam_camprev = T_cn_cnm1[:3, 3] Rt_cam_camprev = nps.glue(R_cam_camprev,t_cam_camprev, axis=-2) if Rt_camprev_ref is not None: Rt_cam_ref = mrcal.compose_Rt(Rt_cam_camprev, Rt_camprev_ref) else: # This is the first camera. What do we use as our reference? if args.cam0_at_reference: Rt_cam_ref = mrcal.identity_Rt() else: # By default the "prev cam" from cam0 is the reference Rt_cam_ref = Rt_cam_camprev Rt_camprev_ref = Rt_cam_ref # for the next one m.extrinsics_Rt_fromref(Rt_cam_ref) return m def convert_all(f, which): # which is None = "all cameras" try: D = yaml.safe_load(f) except yaml.scanner.ScannerError as e: print("Error parsing YAML:\n\n") print(e) sys.exit(1) if len(D) == 0: print("Zero models read from input", file=sys.stderr) sys.exit(1) if 'camera_model' in D: # one camera; stored inline d = D if which is not None: print(f"Error: a single in-line model found in the file, but a specific camera is requested: '{which}'. Omit --camera", file=sys.stderr) sys.exit(1) try: return ( \ (None, convert_one(d,'camera')), ) except KeyError as e: print(f"Error parsing input; missing key: {e}", file=sys.stderr) sys.exit(1) if which is not None and \ not which in D: print(f"Error: asked for camera '{which}', but the given file contains only these cameras: {tuple(D.keys())}", file=sys.stderr) sys.exit(1) # The extrinsics are specified as a serial chain. So I need to parse all the # cameras, even if I only need to save one models = dict() for name,d in D.items(): try: models[name] = convert_one(d,name) except KeyError as e: print(f"Error parsing input; missing key: {e}", file=sys.stderr) sys.exit(1) if which is None: # all cameras requested return [ (name, models[name]) \ for name in models.keys() ] return ( \ (which, models[which]), ) if args.model == '-': if sys.stdin.isatty(): # This isn't an error per-se. But most likely the user ran this # without redirecting any data into it. Without this check the # program will sit there, waiting for input. Which will look strange # to an unsuspecting user print("Trying to read a model from standard input, but no file is being redirected into it", file=sys.stderr) sys.exit(1) names_models = convert_all(sys.stdin, which = args.camera) if len(names_models) > 1: print(f"Reading from standard input may only produce ONE model on stdout, but got more here. Pass --camera to select the camera you want; available cameras: {list(n for n,m in names_models)}", file=sys.stderr) sys.exit(1) names_models[0][1].write(sys.stdout) else: base,extension = os.path.splitext(args.model) if extension.lower() == '.cameramodel': print("Input file is already in the cameramodel format (judging from the filename). Doing nothing", file=sys.stderr) sys.exit(0) if args.outdir is not None: base = args.outdir + '/' + os.path.split(base)[1] with open(args.model, "r") as f: names_models = convert_all(f, which = args.camera) for name,model in names_models: if name is None: name = '' else: name = f"-{name}" filename_out = f"{base}{name}.cameramodel" if not args.force and os.path.exists(filename_out): print(f"Target model '{filename_out}' already exists. Doing nothing with this model. Pass -f to overwrite", file=sys.stderr) continue model.write(filename_out) print("Wrote " + filename_out) mrcal-2.4.1/mrcal-from-ros000077500000000000000000000101241456301662300154060ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 ### THIS IS LARGELY A COPY OF mrcal-from-cahvor. Please consolidate r'''Converts a ROS/OpenCV-formatted camera model to the .cameramodel file format SYNOPSIS $ mrcal-from-ros model1.yaml model2.yaml Wrote model1.cameramodel Wrote model2.cameramodel $ rostopic echo -n1 -b tst.bag /camera/camera_info \ | head -n -1 \ | mrcal-from-ros \ > model.cameramodel File formats supported by mrcal are described at http://mrcal.secretsauce.net/cameramodels.html#cameramodel-file-formats This tool converts the given model(s) to the cameramodel file format. No changes to the content are made; this is purely a format converter (the mrcal-convert-lensmodel tool fits different lens models instead). Model filenames are given on the commandline. Output is written to the same directory, with the same filename, but with a .cameramodel extension. If the model is omitted or given as "-", the input is read from standard input, and the output is written to standard output. Note: there's no corresponding mrcal-to-ros tool at this time, because the behavior of such a tool isn't well-defined. Talk to me if this would be useful to you, to clarify what it should do, exactly. ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--force', '-f', action='store_true', default=False, help='''By default existing files are not overwritten. Pass --force to overwrite them without complaint''') parser.add_argument('--outdir', required=False, type=lambda d: d if os.path.isdir(d) else \ parser.error("--outdir requires an existing directory as the arg, but got '{}'".format(d)), help='''Directory to write the output models into. If omitted, we write the output models to the same directory as the input models''') parser.add_argument('model', default=['-'], nargs='*', type=str, help='''Input camera model''') return parser.parse_args() args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README Nstdin = sum(1 for m in args.model if m=='-') if Nstdin > 1: print(f"At most one model can be read from standard input ('-'), but I got {Nstdin}", file=sys.stderr) sys.exit(1) import mrcal for model in args.model: if model == '-': try: m = mrcal.cameramodel(model) except KeyboardInterrupt: sys.exit(1) except Exception as e: print(e, file=sys.stderr) sys.exit(1) m.write(sys.stdout) else: base,extension = os.path.splitext(model) if extension.lower() == '.cameramodel': print("Input file is already in the cameramodel format (judging from the filename). Doing nothing", file=sys.stderr) sys.exit(0) if args.outdir is not None: base = args.outdir + '/' + os.path.split(base)[1] filename_out = base + '.cameramodel' if not args.force and os.path.exists(filename_out): print(f"Target model '{filename_out}' already exists. Doing nothing with this model. Pass -f to overwrite", file=sys.stderr) else: m = mrcal.cameramodel(model) m.write(filename_out) print("Wrote " + filename_out) mrcal-2.4.1/mrcal-genpywrap.py000066400000000000000000001266561456301662300163240ustar00rootroot00000000000000#!/usr/bin/python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Python-wrap the mrcal routines that can be done with numpysane_pywrap ''' import sys import os import numpy as np import numpysane as nps import numpysane_pywrap as npsp docstring_module = '''Low-level routines for core mrcal operations This is the written-in-C Python extension module that underlies the core (un)project routines, and several low-level operations. Most of the functions in this module (those prefixed with "_") are not meant to be called directly, but have Python wrappers that should be used instead. All functions are exported into the mrcal module. So you can call these via mrcal._mrcal_npsp.fff() or mrcal.fff(). The latter is preferred. ''' m = npsp.module( name = "_mrcal_npsp", docstring = docstring_module, header = r''' #include "mrcal.h" #include static bool validate_lensmodel_un_project(// out; valid if we returned true mrcal_lensmodel_t* lensmodel, // in const char* lensmodel_str, int Nintrinsics_in_arg, bool is_project) { if(lensmodel_str == NULL) { PyErr_Format(PyExc_RuntimeError, "The 'lensmodel' argument is required"); return false; } mrcal_lensmodel_from_name(lensmodel, lensmodel_str); if( !mrcal_lensmodel_type_is_valid(lensmodel->type) ) { PyErr_Format(PyExc_RuntimeError, "Couldn't parse 'lensmodel' argument '%s'", lensmodel_str); return false; } mrcal_lensmodel_metadata_t meta = mrcal_lensmodel_metadata(lensmodel); if( !is_project && !meta.has_gradients ) { PyErr_Format(PyExc_RuntimeError, "The internal _unproject() routine requires lens models that have gradients implemented. Use the Python mrcal.unproject() as a workaround"); return false; } int NlensParams = mrcal_lensmodel_num_params(lensmodel); if( NlensParams != Nintrinsics_in_arg ) { PyErr_Format(PyExc_RuntimeError, "Lens model '%s' has %d parameters, but the given array has %d", lensmodel_str, NlensParams, Nintrinsics_in_arg); return false; } return true; } ''') # NOTE: these projection functions are not as fast as they SHOULD be. In fact # using numpysane_pywrap() is currently causing a performance hit of about 10%. # This should be improved by speeding up the main broadcasting loop in # numpysane_pywrap. I recall it being more complex than it should be. This bit # of python works to benchmark: r""" import numpy as np import mrcal import time m = mrcal.cameramodel('test/data/cam0.splined.cameramodel') v = np.random.random((2000,3000,3)) v[..., 2] += 10. t0 = time.time() mapxy = mrcal.project( v, *m.intrinsics() ) print(time.time()-t0) """ # To test the broadcast-using-the-mrcal-loop, apply this patch: r""" diff --git a/mrcal-genpywrap.py b/mrcal-genpywrap.py index 666f48e..2a4edff 100644 --- a/mrcal-genpywrap.py +++ b/mrcal-genpywrap.py @@ -89,7 +93,7 @@ args_input = ('points', 'intrinsics'), - prototype_input = ((3,), ('Nintrinsics',)), - prototype_output = (2,), + prototype_input = (('N',3,), ('Nintrinsics',)), + prototype_output = ('N',2,), extra_args = (("const char*", "lensmodel", "NULL", "s"),), @@ -113,7 +117,7 @@ _project_withgrad() in mrcal-genpywrap.py. Please keep them in sync Ccode_slice_eval = \ {np.float64: r''' - const int N = 1; + const int N = dims_slice__points[0]; if(cookie->lensmodel.type == MRCAL_LENSMODEL_CAHVORE) return _mrcal_project_internal_cahvore( """ # I see 0.9 sec with the code as is, and 0.8 sec with the patch. Or before I # moved on to this whole npsp thing in 482728c. As it stands, the patch is not # committable. It assumes contiguous memory, and it'll produce incorrect output # shapes if we try to broadcast on intrinsics_data. These are all fixable, and # I'm moving on for now m.function( "_project", """Internal point-projection routine This is the internals for mrcal.project(). As a user, please call THAT function, and see the docs for that function. The differences: - This is just the no-gradients function. The internal function that reports the gradients also is _project_withgrad - To make the broadcasting work, the argument order in this function is different. numpysane_pywrap broadcasts the leading arguments, so this function takes the lensmodel (the one argument that does not broadcast) last - To speed things up, this function doesn't call the C mrcal_project(), but uses the _mrcal_project_internal...() functions instead. That allows as much as possible of the outer init stuff to be moved outside of the slice computation loop This function is wrapped with numpysane_pywrap, so the points and the intrinsics broadcast as expected The outer logic (outside the loop-over-N-points) is duplicated in mrcal_project() and in the python wrapper definition in _project() and _project_withgrad() in mrcal-genpywrap.py. Please keep them in sync """, args_input = ('points', 'intrinsics'), prototype_input = ((3,), ('Nintrinsics',)), prototype_output = (2,), extra_args = (("const char*", "lensmodel", "NULL", "s"),), Ccode_cookie_struct = ''' mrcal_lensmodel_t lensmodel; int Nintrinsics; mrcal_projection_precomputed_t precomputed; ''', Ccode_validate = r''' if( !( validate_lensmodel_un_project(&cookie->lensmodel, lensmodel, dims_slice__intrinsics[0], true) && CHECK_CONTIGUOUS_AND_SETERROR_ALL())) return false; cookie->Nintrinsics = mrcal_lensmodel_num_params(&cookie->lensmodel); _mrcal_precompute_lensmodel_data(&cookie->precomputed, &cookie->lensmodel); return true; ''', Ccode_slice_eval = \ {np.float64: r''' const int N = 1; if(MRCAL_LENSMODEL_IS_OPENCV(cookie->lensmodel.type) || cookie->lensmodel.type == MRCAL_LENSMODEL_PINHOLE) { _mrcal_project_internal_opencv( (mrcal_point2_t*)data_slice__output, NULL, NULL, (const mrcal_point3_t*)data_slice__points, N, (const double*)data_slice__intrinsics, cookie->Nintrinsics); return true; } return _mrcal_project_internal((mrcal_point2_t*)data_slice__output, NULL, NULL, (const mrcal_point3_t*)data_slice__points, N, &cookie->lensmodel, // core, distortions concatenated (const double*)data_slice__intrinsics, cookie->Nintrinsics, &cookie->precomputed); '''}, ) m.function( "_project_withgrad", """Internal point-projection routine This is the internals for mrcal.project(). As a user, please call THAT function, and see the docs for that function. The differences: - This is just the gradients-returning function. The internal function that skips those is _project - To make the broadcasting work, the argument order in this function is different. numpysane_pywrap broadcasts the leading arguments, so this function takes the lensmodel (the one argument that does not broadcast) last - To speed things up, this function doesn't call the C mrcal_project(), but uses the _mrcal_project_internal...() functions instead. That allows as much as possible of the outer init stuff to be moved outside of the slice computation loop This function is wrapped with numpysane_pywrap, so the points and the intrinsics broadcast as expected The outer logic (outside the loop-over-N-points) is duplicated in mrcal_project() and in the python wrapper definition in _project() and _project_withgrad() in mrcal-genpywrap.py. Please keep them in sync """, args_input = ('points', 'intrinsics'), prototype_input = ((3,), ('Nintrinsics',)), prototype_output = ((2,), (2,3), (2,'Nintrinsics')), extra_args = (("const char*", "lensmodel", "NULL", "s"),), Ccode_cookie_struct = ''' mrcal_lensmodel_t lensmodel; int Nintrinsics; mrcal_projection_precomputed_t precomputed; ''', Ccode_validate = r''' if( !( validate_lensmodel_un_project(&cookie->lensmodel, lensmodel, dims_slice__intrinsics[0], true) && CHECK_CONTIGUOUS_AND_SETERROR_ALL())) return false; mrcal_lensmodel_metadata_t meta = mrcal_lensmodel_metadata(&cookie->lensmodel); if(!meta.has_gradients) { PyErr_Format(PyExc_RuntimeError, "_project(get_gradients=True) requires a lens model that has gradient support"); return false; } cookie->Nintrinsics = mrcal_lensmodel_num_params(&cookie->lensmodel); _mrcal_precompute_lensmodel_data(&cookie->precomputed, &cookie->lensmodel); return true; ''', Ccode_slice_eval = \ {np.float64: r''' const int N = 1; return _mrcal_project_internal((mrcal_point2_t*)data_slice__output0, (mrcal_point3_t*)data_slice__output1, (double*) data_slice__output2, (const mrcal_point3_t*)data_slice__points, N, &cookie->lensmodel, // core, distortions concatenated (const double*)data_slice__intrinsics, cookie->Nintrinsics, &cookie->precomputed); '''}, ) m.function( "_unproject", """Internal point-unprojection routine This is the internals for mrcal.unproject(). As a user, please call THAT function, and see the docs for that function. The differences: - To make the broadcasting work, the argument order in this function is different. numpysane_pywrap broadcasts the leading arguments, so this function takes the lensmodel (the one argument that does not broadcast) last - This function requires gradients, so it does not support some lens models; CAHVORE for instance - To speed things up, this function doesn't call the C mrcal_unproject(), but uses the _mrcal_unproject_internal...() functions instead. That allows as much as possible of the outer init stuff to be moved outside of the slice computation loop This function is wrapped with numpysane_pywrap, so the points and the intrinsics broadcast as expected The outer logic (outside the loop-over-N-points) is duplicated in mrcal_unproject() and in the python wrapper definition in _unproject() mrcal-genpywrap.py. Please keep them in sync """, args_input = ('points', 'intrinsics'), prototype_input = ((2,), ('Nintrinsics',)), prototype_output = (3,), extra_args = (("const char*", "lensmodel", "NULL", "s"),), Ccode_cookie_struct = ''' mrcal_lensmodel_t lensmodel; mrcal_projection_precomputed_t precomputed; ''', Ccode_validate = r''' if( !( validate_lensmodel_un_project(&cookie->lensmodel, lensmodel, dims_slice__intrinsics[0], false) && CHECK_CONTIGUOUS_AND_SETERROR_ALL())) return false; _mrcal_precompute_lensmodel_data(&cookie->precomputed, &cookie->lensmodel); return true; ''', Ccode_slice_eval = \ {np.float64: r''' const int N = 1; return _mrcal_unproject_internal((mrcal_point3_t*)data_slice__output, (const mrcal_point2_t*)data_slice__points, N, &cookie->lensmodel, // core, distortions concatenated (const double*)data_slice__intrinsics, &cookie->precomputed); '''}, ) project_simple_doc = """Internal projection routine This is the internals for mrcal.project_{what}(). As a user, please call THAT function, and see the docs for that function. The differences: - This is just the no-gradients function. The internal function that reports the gradients also is _project_{what}_withgrad() This function is wrapped with numpysane_pywrap, so the points broadcast as expected """ project_withgrad_simple_doc = """Internal projection routine with gradients This is the internals for mrcal.project_{what}(). As a user, please call THAT function, and see the docs for that function. The differences: - This is just the gradient-reporting function. The internal function that does not report the gradients is _project_{what}() This function is wrapped with numpysane_pywrap, so the points broadcast as expected """ unproject_simple_doc = """Internal unprojection routine This is the internals for mrcal.unproject_{what}(). As a user, please call THAT function, and see the docs for that function. The differences: - This is just the no-gradients function. The internal function that reports the gradients also is _unproject_{what}_withgrad() This function is wrapped with numpysane_pywrap, so the points broadcast as expected """ unproject_withgrad_simple_doc = """Internal unprojection routine This is the internals for mrcal.unproject_{what}(). As a user, please call THAT function, and see the docs for that function. The differences: - This is just the gradient-reporting function. The internal function that does not report the gradients is _unproject_{what}() This function is wrapped with numpysane_pywrap, so the points broadcast as expected """ simple_kwargs_base = \ dict(args_input = ('points','fxycxy'), Ccode_validate = r'''return CHECK_CONTIGUOUS_AND_SETERROR_ALL();''') project_simple_kwargs = \ dict( prototype_input = ((3,),(4,)), prototype_output = (2,)) project_withgrad_simple_kwargs = \ dict( prototype_input = ((3,),(4,)), prototype_output = ((2,), (2,3))) unproject_simple_kwargs = \ dict( prototype_input = ((2,),(4,)), prototype_output = (3,)) unproject_withgrad_simple_kwargs = \ dict( prototype_input = ((2,),(4,)), prototype_output = ((3,), (3,2))) project_simple_code = ''' const double* fxycxy = (const double*)data_slice__fxycxy; mrcal_project_{what}((mrcal_point2_t*)data_slice__output, NULL, (const mrcal_point3_t*)data_slice__points, 1, fxycxy); return true;''' project_withgrad_simple_code = ''' const double* fxycxy = (const double*)data_slice__fxycxy; mrcal_project_{what}((mrcal_point2_t*)data_slice__output0, (mrcal_point3_t*)data_slice__output1, (const mrcal_point3_t*)data_slice__points, 1, fxycxy); return true;''' unproject_simple_code = ''' const double* fxycxy = (const double*)data_slice__fxycxy; mrcal_unproject_{what}((mrcal_point3_t*)data_slice__output, NULL, (const mrcal_point2_t*)data_slice__points, 1, fxycxy); return true;''' unproject_withgrad_simple_code = ''' const double* fxycxy = (const double*)data_slice__fxycxy; mrcal_unproject_{what}((mrcal_point3_t*)data_slice__output0, (mrcal_point2_t*)data_slice__output1, (const mrcal_point2_t*)data_slice__points, 1, fxycxy); return true;''' for what in ('pinhole', 'stereographic', 'lonlat', 'latlon'): m.function( f"_project_{what}", project_simple_doc.format(what = what), Ccode_slice_eval = {np.float64: project_simple_code.format(what = what)}, **project_simple_kwargs, **simple_kwargs_base ) m.function( f"_project_{what}_withgrad", project_withgrad_simple_doc.format(what = what), Ccode_slice_eval = {np.float64: project_withgrad_simple_code.format(what = what)}, **project_withgrad_simple_kwargs, **simple_kwargs_base ) m.function( f"_unproject_{what}", unproject_simple_doc.format(what = what), Ccode_slice_eval = {np.float64: unproject_simple_code.format(what = what)}, **unproject_simple_kwargs, **simple_kwargs_base ) m.function( f"_unproject_{what}_withgrad", unproject_withgrad_simple_doc.format(what = what), Ccode_slice_eval = {np.float64: unproject_withgrad_simple_code.format(what = what)}, **unproject_withgrad_simple_kwargs, **simple_kwargs_base ) m.function( "_A_Jt_J_At", """Computes matmult(A,Jt,J,At) for a sparse J This is used in the internals of projection_uncertainty(). A has shape (2,Nstate) J has shape (Nmeasurements,Nstate). J is large and sparse We use the Nleading_rows_J leading rows of J. This integer is passed-in as an argument. matmult(A, Jt, J, At) has shape (2,2) The input matrices are large, but the result is very small. I can't see a way to do this efficiently in pure Python, so I'm writing this. J is sparse, stored by row. This is the scipy.sparse.csr_matrix representation, and is also how CHOLMOD stores Jt (CHOLMOD stores by column, so the same data looks like Jt to CHOLMOD). The sparse J is given here as the p,i,x arrays from CHOLMOD, equivalent to the indptr,indices,data members of scipy.sparse.csr_matrix respectively. """, args_input = ('A', 'Jp', 'Ji', 'Jx'), prototype_input = (('Nx','Nstate'), ('Np',), ('Nix',), ('Nix',)), prototype_output = ('Nx','Nx'), extra_args = (("int", "Nleading_rows_J", "-1", "i"),), Ccode_validate = r''' if(*Nleading_rows_J <= 0) { PyErr_Format(PyExc_RuntimeError, "Nleading_rows_J must be passed, and must be > 0"); return false; } return CHECK_CONTIGUOUS_AND_SETERROR_ALL();''', Ccode_slice_eval = \ { (np.float64, np.int32, np.int32, np.float64, np.float64): r''' // I'm computing A Jt J At = sum(outer(ja,ja)) where ja is each // row of matmult(J,At). Rows of matmult(J,At) are // matmult(jt,At) where jt are rows of J. So the logic is: // // For each row jt of J: // jta = matmult(jt,At); // jta has shape (Nx,) // accumulate( outer(jta,jta) ) int32_t Nx = dims_slice__A[0]; int32_t Nstate = dims_slice__A[1]; const double* A = (const double* )data_slice__A; const int32_t* Jp = (const int32_t*)data_slice__Jp; const int32_t* Ji = (const int32_t*)data_slice__Ji; const double* Jx = (const double* )data_slice__Jx; double* out = ( double* )data_slice__output; for(int i=0; i 0"); return false; } return CHECK_CONTIGUOUS_AND_SETERROR_ALL();''', Ccode_slice_eval = \ { (np.float64, np.int32, np.int32, np.float64, np.float64): r''' // I'm computing A Jt J At = sum(outer(ja,ja)) where ja is each // row of matmult(J,At). Rows of matmult(J,At) are // matmult(jt,At) where jt are rows of J. So the logic is: // // For each row jt of J: // jta = matmult(jt,At); // jta has shape (Nx,) // accumulate( outer(jta,jta) ) const int32_t Nx = 2; // dims_slice__A[0] will always be 2 const int32_t Nstate = dims_slice__A[1]; const double* A = (const double* )data_slice__A; const int32_t* Jp = (const int32_t*)data_slice__Jp; const int32_t* Ji = (const int32_t*)data_slice__Ji; const double* Jx = (const double* )data_slice__Jx; double* out = ( double* )data_slice__output; for(int i=0; i (3,3) print( q0.shape ) ===> (100, 2) q1 = mrcal.apply_homography(H10, q0) print( q1.shape ) ===> (100, 2) A homography maps from pixel coordinates observed in one camera to pixel coordinates in another. For points represented in homogeneous coordinates ((k*x, k*y, k) to represent a pixel (x,y) for any k) a homography is a linear map H. Since homogeneous coordinates are unique only up-to-scale, the homography matrix H is also unique up to scale. If two pinhole cameras are observing a planar surface, there exists a homography that relates observations of the plane in the two cameras. This function supports broadcasting fully. ARGUMENTS - H: an array of shape (..., 3,3). This is the homography matrix. This is unique up-to-scale, so a homography H is functionally equivalent to k*H for any non-zero scalar k - q: an array of shape (..., 2). The pixel coordinates we are mapping RETURNED VALUE An array of shape (..., 2) containing the pixels q after the homography was applied ''', args_input = ('H', 'v'), prototype_input = ((3,3), (2,)), prototype_output = (2,), Ccode_slice_eval = \ { np.float64: apply_homography_body, np.float32: apply_homography_body }, ) body__apply_color_map = r''' const int H = dims_slice__array[0]; const int W = dims_slice__array[1]; {T} T_a_min; if( *a_min < (double)({T_min}) ) T_a_min = {T_min}; else if( *a_min > (double)({T_max}) ) T_a_min = {T_max}; else T_a_min = ({T})(*a_min); {T} T_a_max; if( *a_max < (double)({T_min}) ) T_a_max = {T_min}; else if( *a_max > (double)({T_max}) ) T_a_max = {T_max}; else T_a_max = ({T})(*a_max); mrcal_image_bgr_t out = {.height = H, .width = W, .stride = strides_slice__output[0], .data = data_slice__output}; mrcal_image_{Tname}_t in = {.height = H, .width = W, .stride = strides_slice__array[0], .data = ({T}*)data_slice__array}; return mrcal_apply_color_map_{Tname}(&out, &in, (*a_min)==DBL_MAX,(*a_max)==DBL_MIN, false, T_a_min, T_a_max, *function_red, *function_green, *function_blue); ''' m.function( "apply_color_map", """Color-code an array SYNOPSIS image = produce_data() print( image.shape ) ===> (480, 640) image_colorcoded = mrcal.apply_color_map(image) print( image_colorcoded.shape ) ===> (480, 640, 3) print( image_colorcoded.dtype ) ===> dtype('uint8') mrcal.save_image('data.png', image_colorcoded) This is very similar to cv2.applyColorMap() but more flexible in several important ways. Differences: - Supports arrays of any shape. Most of the time the input is 2-dimensional images, but this isn't required - Supports any input data type, NOT limited to 8-bit images like cv2.applyColorMap() - Supports gnuplot color maps instead of MATLAB ones The color map is applied to each value in the input, each one producing an BGR row of shape (3,). So output.shape is input.shape + (3,). The output has dtype=numpy.uint8, so these arrays can be output as images, and visualized using any image-viewing tools. This function uses gnuplot's color maps, specified as rgbformulae: http://gnuplot.info/docs_6.0/loc14176.html http://gnuplot.info/docs_6.0/loc14246.html This is selected by passing (function_red,function_blue,function_green) integers, selecting different functions for each color channel. The default is the default gnuplot colormap: 7,5,15. This is a nice black-violet-blue-purple-red-orange-yellow map, appropriate for most usages. A colormap may be visualized with gnuplot. For instance to see the "AFM hot" colormap, run this gnuplot script: set palette rgbformulae 34,35,36 test palette The definition of each colormap function is given by "show palette rgbformulae" in gnuplot: > show palette rgbformulae * there are 37 available rgb color mapping formulae: 0: 0 1: 0.5 2: 1 3: x 4: x^2 5: x^3 6: x^4 7: sqrt(x) 8: sqrt(sqrt(x)) 9: sin(90x) 10: cos(90x) 11: |x-0.5| 12: (2x-1)^2 13: sin(180x) 14: |cos(180x)| 15: sin(360x) 16: cos(360x) 17: |sin(360x)| 18: |cos(360x)| 19: |sin(720x)| 20: |cos(720x)| 21: 3x 22: 3x-1 23: 3x-2 24: |3x-1| 25: |3x-2| 26: (3x-1)/2 27: (3x-2)/2 28: |(3x-1)/2| 29: |(3x-2)/2| 30: x/0.32-0.78125 31: 2*x-0.84 32: 4x;1;-2x+1.84;x/0.08-11.5 33: |2*x - 0.5| 34: 2*x 35: 2*x - 0.5 36: 2*x - 1 * negative numbers mean inverted=negative colour component * thus the ranges in `set pm3d rgbformulae' are -36..36 ARGUMENTS - array: input numpy array - a_min: optional value indicating the lower bound of the values we color map. All input values outside of the range [a_min,a_max] are clipped. If omitted, we use array.min() - a_max: optional value indicating the upper bound of the values we color map. All input values outside of the range [a_min,a_max] are clipped. If omitted, we use array.max() - function_red function_green function_blue: optional integers selecting the color maps for each channel. See the full docstring for this function for detail RETURNED VALUE The color-mapped output array of shape array.shape + (3,) and containing 8-bit unsigned integers. The last row is the BGR color-mapped values. """, args_input = ('array',), prototype_input = (('H','W'),), prototype_output = ( 'H','W', 3), extra_args = (("double", "a_min", "DBL_MAX", "d"), ("double", "a_max", "DBL_MIN", "d"), ("int", "function_red", "7", "i"), ("int", "function_green", "5", "i"), ("int", "function_blue", "15", "i"), ), # I require contiguity of the last dimension only Ccode_validate = r''' /* If I have no data, just call the thing contiguous. This is useful */ /* because np.ascontiguousarray doesn't set contiguous alignment */ /* for empty arrays */ const bool isempty__array = dims_slice__array[0] == 0 || dims_slice__array[1] == 0; if(!isempty__array && strides_slice__array[1] != sizeof_element__array) { PyErr_Format(PyExc_RuntimeError, "Array 'array' must be contiguous in the last dimension"); return false; } const bool isempty__output = dims_slice__output[0] == 0 || dims_slice__output[1] == 0; if(!isempty__output && ( strides_slice__output[1] != sizeof_element__output*3 || strides_slice__output[2] != sizeof_element__output ) ) { PyErr_Format(PyExc_RuntimeError, "Array 'output' must be contiguous in the last dimension"); return false; } return true;''', Ccode_slice_eval = \ { (np. int8, np.uint8): body__apply_color_map \ .replace('{T}', 'int8_t') \ .replace('{Tname}', 'int8') \ .replace('{T_min}', 'INT8_MIN') \ .replace('{T_max}', 'INT8_MAX'), (np.uint8, np.uint8): body__apply_color_map \ .replace('{T}', 'uint8_t') \ .replace('{Tname}', 'uint8') \ .replace('{T_min}', '0') \ .replace('{T_max}', 'UINT8_MAX'), (np. int16, np.uint8): body__apply_color_map \ .replace('{T}', 'int16_t') \ .replace('{Tname}', 'int16') \ .replace('{T_min}', 'INT16_MIN') \ .replace('{T_max}', 'INT16_MAX'), (np.uint16, np.uint8): body__apply_color_map \ .replace('{T}', 'uint16_t') \ .replace('{Tname}', 'uint16') \ .replace('{T_min}', '0') \ .replace('{T_max}', 'UINT16_MAX'), (np. int32, np.uint8): body__apply_color_map \ .replace('{T}', 'int32_t') \ .replace('{Tname}', 'int32') \ .replace('{T_min}', 'INT32_MIN') \ .replace('{T_max}', 'INT32_MAX'), (np.uint32, np.uint8): body__apply_color_map \ .replace('{T}', 'uint32_t') \ .replace('{Tname}', 'uint32') \ .replace('{T_min}', '0') \ .replace('{T_max}', 'UINT32_MAX'), (np. int64, np.uint8): body__apply_color_map \ .replace('{T}', 'int64_t') \ .replace('{Tname}', 'int64') \ .replace('{T_min}', 'INT64_MIN') \ .replace('{T_max}', 'INT64_MAX'), (np.uint64, np.uint8): body__apply_color_map \ .replace('{T}', 'uint64_t') \ .replace('{Tname}', 'uint64') \ .replace('{T_min}', '0') \ .replace('{T_max}', 'UINT64_MAX'), (np.float32, np.uint8): body__apply_color_map \ .replace('{T}', 'float') \ .replace('{Tname}', 'float') \ .replace('{T_min}', 'FLT_MIN') \ .replace('{T_max}', 'FLT_MAX'), (np.float64, np.uint8): body__apply_color_map \ .replace('{T}', 'double') \ .replace('{Tname}', 'double') \ .replace('{T_min}', 'DBL_MIN') \ .replace('{T_max}', 'DBL_MAX'), }, ) m.function( "_stereo_range_sparse", """Internal wrapper of mrcal_stereo_range_sparse() """, args_input = ('disparity', 'qrect0', 'disparity_min', 'disparity_max', 'fxycxy_rectified', 'baseline' ), prototype_input = (('N',), ('N',2,), (), (), (4,), ()), prototype_output = ( 'N', ), extra_args = (("const char*", "rectification_model_type", "NULL", "s"),), Ccode_cookie_struct = ''' mrcal_lensmodel_type_t type; ''', Ccode_validate = r''' cookie->type = mrcal_lensmodel_type_from_name(rectification_model_type); // the mrcal_stereo_range_...() functions will check to make sure // the type is valid return CHECK_CONTIGUOUS_AND_SETERROR_ALL();''', Ccode_slice_eval = \ { (float,float,float,float,float,float, float): ''' const int N = dims_slice__output[0]; return mrcal_stereo_range_sparse(// output (double*)data_slice__output, // input (double*)data_slice__disparity, (const mrcal_point2_t*)data_slice__qrect0, N, *(double*)data_slice__disparity_min, *(double*)data_slice__disparity_max, // models_rectified cookie->type, (double*)data_slice__fxycxy_rectified, *(double*)data_slice__baseline); ''' }, ) m.function( "_stereo_range_dense", """Internal wrapper of mrcal_stereo_range_dense() """, args_input = ('disparity_scaled', 'disparity_scale', 'disparity_scaled_min', 'disparity_scaled_max', 'fxycxy_rectified', 'baseline' ), prototype_input = (('H','W'), (), (), (), (4,), ()), prototype_output = ('H','W'), extra_args = (("const char*", "rectification_model_type", "NULL", "s"),), Ccode_cookie_struct = ''' mrcal_lensmodel_type_t type; ''', Ccode_validate = r''' cookie->type = mrcal_lensmodel_type_from_name(rectification_model_type); // the mrcal_stereo_range_...() functions will check to make sure // the type is valid if(strides_slice__disparity_scaled[1] != sizeof_element__disparity_scaled) { PyErr_Format(PyExc_RuntimeError, "Array 'disparity_scaled' must be contiguous in the last dimension"); return false; } if( strides_slice__output[1] != sizeof_element__output ) { PyErr_Format(PyExc_RuntimeError, "Array 'output' must be contiguous in the last dimension"); return false; } return CHECK_CONTIGUOUS_AND_SETERROR_ALL();''', Ccode_slice_eval = \ { (np.uint16,np.uint16,np.uint16,np.uint16,float,float, float): ''' const int H = dims_slice__disparity_scaled[0]; const int W = dims_slice__disparity_scaled[1]; return mrcal_stereo_range_dense( // output &(mrcal_image_double_t){.height = H, .width = W, .stride = strides_slice__output[0], .data = data_slice__output}, // input &(mrcal_image_uint16_t){.height = H, .width = W, .stride = strides_slice__disparity_scaled[0], .data = data_slice__disparity_scaled}, *(uint16_t*)data_slice__disparity_scale, *(uint16_t*)data_slice__disparity_scaled_min, *(uint16_t*)data_slice__disparity_scaled_max, // models_rectified cookie->type, (double*)data_slice__fxycxy_rectified, *(double*)data_slice__baseline); ''' }, ) m.write() mrcal-2.4.1/mrcal-graft-models000077500000000000000000000226131456301662300162340ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Combines the intrinsics of one cameramodel with the extrinsics of another SYNOPSIS # We have intrinsics.cameramodel containing improved intrinsics from a later # calibration, and extrinsics.cameramodel that has the old intrinsics, but the # right extrinsics $ mrcal-graft-models intrinsics.cameramodel extrinsics.cameramodel > joint.cameramodel Combined intrinsics from 'intrinsics.cameramodel' Extrinsics from 'exrinsics.cameramodel' $ mrcal-show-projection-diff joint.cameramodel extrinsics.cameramodel [A plot pops up showing a low difference, just representing the two sets of intrinsics. The recalibrated models have a large implied extrinsics difference, but the diff tool computed and applised the implied transformation] $ mrcal-show-projection-diff --radius 0 joint.cameramodel extrinsics.cameramodel [A plot pops up showing a high difference. Here the diff tool didn't apply the implied transformation, so the differences in extrinsics are evident. Thus here, joint.cameramodel is not a drop-in replacement for extrinsics.cameramodel] $ mrcal-graft-models --radius -1 intrinsics.cameramodel extrinsics.cameramodel > joint.cameramodel Transformation cam1 <-- cam0: rotation: 8.429 degrees, translation: [0. 0. 0.] m Combined intrinsics from 'intrinsics.cameramodel' Extrinsics from 'exrinsics.cameramodel' $ mrcal-show-projection-diff --radius 0 joint.cameramodel extrinsics.cameramodel [A plot pops up showing a low difference. The graft tool applied the implied transformation, so the models match without the diff tool needing to transform anything. Thus here, joint.cameramodel IS a drop-in replacement for extrinsics.cameramodel] This tool combines intrinsics and extrinsics from different sources into a single model. The output is written to standard output. A common use case is a system where the intrinsics are calibrated prior to moving the cameras to their final location, and then computing the extrinsics separately after the cameras are moved. If we have computed such a combined model, and we decide to recompute the intrinsics afterwards, we can graft the new intrinsics to the previous extrinsics. By default, this wouldn't be a drop-in replacement for the previous model, since the intrinsics come with an implied geometric transformation, which will be different in the new intrinsics. By passing a non-zero --radius value, we can compute and apply the implied geometric transformation, so the combined model would be usable as a drop-in replacement. The implied transformation logic is controlled by a number of commandline arguments, same ones as used by the mrcal-show-projection-diff tool. The only difference in options is that THIS tool uses --radius 0 by default, so we do not compute or apply the implied transformation unless asked. Pass --radius with a non-zero argument to compute and apply the implied transformation. ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--gridn', type=int, default = (60,40), nargs = 2, help='''Used if we're computing the implied-by-the-intrinsics transformation. How densely we should sample the imager. By default we use a 60x40 grid''') parser.add_argument('--distance', type=str, help='''Used if we're computing the implied-by-the-intrinsics transformation. By default we compute the implied transformation for points infinitely far away from the camera. If we want to look closer in, the desired observation distance can be given in this argument. We can also fit multiple distances at the same time by passing them here in a comma-separated, whitespace-less list''') parser.add_argument('--where', type=float, nargs=2, help='''Used if we're computing the implied-by-the-intrinsics transformation. Center of the region of interest used for the transformation fit. It is usually impossible for the models to match everywhere, but focusing on a particular area can work better. The implied transformation will be fit to match as large as possible an area centered on this argument. If omitted, we will focus on the center of the imager''') parser.add_argument('--radius', type=float, default=0., help='''Used if we're computing the implied-by-the-intrinsics transformation. Radius of the region of interest. If ==0 (the default), we do NOT fit an implied transformation at all. If <0, we use a "reasonable" value: the whole imager if we're using uncertainties, or min(width,height)/6 if --no-uncertainties. To fit with data across the whole imager in either case, pass in a very large radius''') parser.add_argument('--no-uncertainties', action = 'store_true', default = False, help='''Used if we're computing the implied-by-the-intrinsics transformation. By default we use the uncertainties in the model to weigh the fit. This will focus the fit on the confident region in the models without --where or --radius. The computation will run faster with --no-uncertainties, but the default --where and --radius may need to be adjusted''') parser.add_argument('intrinsics', type=str, help='''Input camera model for the intrinsics. If "-" is given, we read standard input. Both the intrinsics and extrinsics sources may not be "-"''') parser.add_argument('extrinsics', type=str, help='''Input camera model for the extrinsics. If "-" is given, we read standard input. Both the intrinsics and extrinsics sources may not be "-"''') args = parser.parse_args() if args.intrinsics == "-" and args.extrinsics == "-": print("Error: both intrinsics and extrinsics may not be given as '-'", file=sys.stderr) sys.exit(1) return args args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README import numpy as np import numpysane as nps import mrcal import time model_intrinsics = mrcal.cameramodel(args.intrinsics) model_extrinsics = mrcal.cameramodel(args.extrinsics) if args.distance is None: distance = None else: try: distance = [float(d) for d in args.distance.split(',')] except: print("Error: distances must be given a comma-separated list of floats in --distance", file=sys.stderr) sys.exit(1) if args.radius == 0: rt_cr = model_extrinsics.extrinsics_rt_fromref() model_intrinsics.extrinsics_rt_fromref(rt_cr) else: difflen,diff,q0, Rt_camoldintrinsics_camnewintrinsics = \ mrcal.projection_diff((model_intrinsics, model_extrinsics), gridn_width = args.gridn[0], gridn_height = args.gridn[1], intrinsics_only = False, distance = distance, use_uncertainties = not args.no_uncertainties, focus_center = args.where, focus_radius = args.radius) rt10 = mrcal.rt_from_Rt(Rt_camoldintrinsics_camnewintrinsics) print(f"Transformation cam1 <-- cam0: rotation: {nps.mag(rt10[:3])*180./np.pi:.03f} degrees, translation: {rt10[3:]} m", file = sys.stderr) rt_camoldintrinsics_ref = model_extrinsics.extrinsics_rt_fromref() rt_camnewintrinsics_ref = \ mrcal.compose_rt( mrcal.rt_from_Rt( mrcal.invert_Rt(Rt_camoldintrinsics_camnewintrinsics)), rt_camoldintrinsics_ref) model_intrinsics.extrinsics_rt_fromref(rt_camnewintrinsics_ref) note = \ "Generated on {} with {}\n".format(time.strftime("%Y-%m-%d %H:%M:%S"), ' '.join(mrcal.shellquote(s) for s in sys.argv)) print(f"Combined\nIntrinsics from '{args.intrinsics}'\nExtrinsics from '{args.extrinsics}'", file = sys.stderr) model_intrinsics.write(sys.stdout, note=note) mrcal-2.4.1/mrcal-image.c000066400000000000000000000225611456301662300151520ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #include #include #include #include #include "mrcal-image.h" #include "util.h" // for diagnostics __attribute__((unused)) static void report_image_details(/* const; FreeImage doesn't support that */ FIBITMAP* fib, const char* what) { MSG("%s colortype = %d bpp = %d dimensions: (%d,%d), pitch = %d", what, (int)FreeImage_GetColorType(fib), (int)FreeImage_GetBPP (fib), (int)FreeImage_GetWidth (fib), (int)FreeImage_GetHeight (fib), (int)FreeImage_GetPitch (fib)); } static bool generic_save(const char* filename, const void* _image, int bits_per_pixel) { bool result = false; FIBITMAP* fib = NULL; // This may actually be a different mrcal_image_xxx_t type, but all the // fields line up anyway const mrcal_image_uint8_t* image = (const mrcal_image_uint8_t*)_image; if(image->w == 0 || image->h == 0) { MSG("Asked to save an empty image: dimensions (%d,%d)!", image->w, image->h); goto done; } #if defined HAVE_OLD_LIBFREEIMAGE && HAVE_OLD_LIBFREEIMAGE if(bits_per_pixel == 16) MSG("WARNING: you have an old build of libfreeimage. It has trouble writing 16bpp images, so '%s' will probably be written incorrectly. You should upgrade your libfreeimage and rebuild", filename); fib = FreeImage_ConvertFromRawBits( (BYTE*)image->data, image->width, image->height, image->stride, bits_per_pixel, 0,0,0, // Top row is stored first true); #else // I do NOT reuse the input data because this function actually changes the // input buffer to flip it upside-down instead of accessing the bits in the // correct order fib = FreeImage_ConvertFromRawBitsEx(true, (BYTE*)image->data, (bits_per_pixel == 16) ? FIT_UINT16 : FIT_BITMAP, image->width, image->height, image->stride, bits_per_pixel, 0,0,0, // Top row is stored first true); #endif FREE_IMAGE_FORMAT format = FreeImage_GetFIFFromFilename(filename); if(format == FIF_UNKNOWN) { MSG("FreeImage doesn't know how to save '%s'", filename); goto done; } int flags = format == FIF_JPEG ? 96 : 0; if(!FreeImage_Save(format, fib, filename, flags)) { MSG("FreeImage couldn't save '%s'", filename); goto done; } result = true; done: if(fib != NULL) FreeImage_Unload(fib); return result; } bool mrcal_image_uint8_save (const char* filename, const mrcal_image_uint8_t* image) { return generic_save(filename, image, 8); } bool mrcal_image_uint16_save(const char* filename, const mrcal_image_uint16_t* image) { return generic_save(filename, image, 16); } bool mrcal_image_bgr_save(const char* filename, const mrcal_image_bgr_t* image) { return generic_save(filename, image, 24); } static bool generic_load(// output // mrcal_image_uint8_t if bits_per_pixel == 8 // mrcal_image_uint16_t if bits_per_pixel == 16 // mrcal_image_bgr_t if bits_per_pixel == 24 void* _image, // if >0: this is the requested bits_per_pixel. If == 0: we // get this from the input image, and set the value on the // return int* bits_per_pixel, // input const char* filename) { bool result = false; FIBITMAP* fib = NULL; FIBITMAP* fib_converted = NULL; FREE_IMAGE_FORMAT format = FreeImage_GetFileType(filename,0); if(format == FIF_UNKNOWN) { MSG("Couldn't load '%s': FreeImage_GetFileType() failed", filename); goto done; } fib = FreeImage_Load(format, filename, 0); if(fib == NULL) { MSG("Couldn't load '%s': FreeImage_Load() failed", filename); goto done; } // FreeImage loads images upside-down, so I flip it around if(!FreeImage_FlipVertical(fib)) { MSG("Couldn't flip the image"); goto done; } // might not be "uint8_t" necessarily, but all the fields still line up mrcal_image_uint8_t* image = NULL; FREE_IMAGE_COLOR_TYPE color_type_expected; const char* what_expected; if(*bits_per_pixel == 0) { // autodetect FREE_IMAGE_COLOR_TYPE color_type_have = FreeImage_GetColorType(fib); if(color_type_have == FIC_RGB || color_type_have == FIC_PALETTE) { *bits_per_pixel = 24; } else if(color_type_have == FIC_MINISBLACK) { unsigned int bpp_have = FreeImage_GetBPP(fib); if(bpp_have == 16) *bits_per_pixel = 16; else *bits_per_pixel = 8; } else { MSG("Couldn't auto-detect image type. I only know about FIC_RGB, FIC_PALETTE, FIC_MINISBLACK"); goto done; } } if(*bits_per_pixel == 8) { color_type_expected = FIC_MINISBLACK; what_expected = "grayscale"; fib_converted = FreeImage_ConvertToGreyscale(fib); if(fib_converted == NULL) { MSG("Couldn't FreeImage_ConvertToGreyscale()"); goto done; } } else if(*bits_per_pixel == 16) { color_type_expected = FIC_MINISBLACK; what_expected = "16-bit grayscale"; // At this time, 16bpp grayscale images can only be read directly from // the input. I cannot be given a different kind of input, and convert // the images to 16bpp grayscale fib_converted = fib; } else if(*bits_per_pixel == 24) { color_type_expected = FIC_RGB; what_expected = "bgr 24-bit"; fib_converted = FreeImage_ConvertTo24Bits(fib); if(fib_converted == NULL) { MSG("Couldn't FreeImage_ConvertTo24Bits()"); goto done; } } else { MSG("Input bits_per_pixel must be 8 or 16 or 24; got %d", *bits_per_pixel); goto done; } if(!(FreeImage_GetColorType(fib_converted) == color_type_expected && FreeImage_GetBPP(fib_converted) == (unsigned)*bits_per_pixel)) { MSG("Loaded and preprocessed image isn't %s", what_expected); goto done; } // This may actually be a different mrcal_image_xxx_t type, but all the // fields line up anyway image = (mrcal_image_uint8_t*)_image; image->width = (int)FreeImage_GetWidth (fib_converted); image->height = (int)FreeImage_GetHeight(fib_converted); image->stride = (int)FreeImage_GetPitch (fib_converted); int size = image->stride*image->height; if(posix_memalign((void**)&image->data, 16UL, size) != 0) { MSG("%s('%s') couldn't allocate image: malloc(%d) failed", __func__, filename, size); goto done; } memcpy( image->data, FreeImage_GetBits(fib_converted), size ); result = true; done: if(fib != NULL) FreeImage_Unload(fib); if(fib_converted != NULL && fib_converted != fib) FreeImage_Unload(fib_converted); return result; } bool mrcal_image_uint8_load(// output mrcal_image_uint8_t* image, // input const char* filename) { int bits_per_pixel = 8; return generic_load(image, &bits_per_pixel, filename); } bool mrcal_image_uint16_load(// output mrcal_image_uint16_t* image, // input const char* filename) { int bits_per_pixel = 16; return generic_load(image, &bits_per_pixel, filename); } bool mrcal_image_bgr_load (// output mrcal_image_bgr_t* image, // input const char* filename) { int bits_per_pixel = 24; return generic_load(image, &bits_per_pixel, filename); } bool mrcal_image_anytype_load(// output // This is ONE of the known types mrcal_image_uint8_t* image, int* bits_per_pixel, int* channels, // input const char* filename) { *bits_per_pixel = 0; if(!generic_load(image, bits_per_pixel, filename)) return false; switch(*bits_per_pixel) { case 8: case 16: *channels = 1; break; case 24: *channels = 3; break; default: MSG("Getting here is a bug"); return false; } return true; } mrcal-2.4.1/mrcal-image.h000066400000000000000000000137051456301662300151570ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #pragma once // mrcal images. These are completely uninteresting, and don't do anything // better that other image read/write APIS. If you have image libraries running, // use those. If not, the ones defined here should be light and painless // I support several image types: // - "uint8": 8-bit grayscale // - "uint16": 16-bit grayscale (using the system endian-ness) // - "bgr": 24-bit BGR color // // Each type defines several functions in the MRCAL_IMAGE_DECLARE() macro: // // - mrcal_image_TYPE_t container image // - mrcal_image_TYPE_at(mrcal_image_TYPE_t* image, int x, int y) // - mrcal_image_TYPE_at_const(const mrcal_image_TYPE_t* image, int x, int y) // - mrcal_image_TYPE_t mrcal_image_TYPE_crop(mrcal_image_TYPE_t* image, in x0, int y0, int w, int h) // - mrcal_image_TYPE_save (const char* filename, const mrcal_image_TYPE_t* image); // - mrcal_image_TYPE_load( mrcal_image_TYPE_t* image, const char* filename); // // The image-loading functions require a few notes: // // An image structure to fill in is given. image->data will be allocated to the // proper size. It is the caller's responsibility to free(image->data) when // they're done. Usage sample: // // mrcal_image_uint8_t image; // mrcal_image_uint8_load(&image, image_filename); // .... do stuff ... // free(image.data); // // mrcal_image_uint8_load() converts images to 8-bpp grayscale. Color and // palettized images are accepted // // mrcal_image_uint16_load() does NOT convert images. The images being read must // already be stored as 16bpp grayscale images // // mrcal_image_bgr_load() converts images to 24-bpp color #include #include typedef struct { uint8_t bgr[3]; } mrcal_bgr_t; #define MRCAL_IMAGE_DECLARE(T, Tname) \ typedef struct \ { \ union \ { \ /* in pixels */ \ struct {int w, h;}; \ struct {int width, height;}; \ struct {int cols, rows;}; \ }; \ int stride; /* in bytes */ \ T* data; \ } mrcal_image_ ## Tname ## _t; \ \ static inline \ T* mrcal_image_ ## Tname ## _at(mrcal_image_ ## Tname ## _t* image, int x, int y) \ { \ return &image->data[x + y*image->stride / sizeof(T)]; \ } \ \ static inline \ const T* mrcal_image_ ## Tname ## _at_const(const mrcal_image_ ## Tname ## _t* image, int x, int y) \ { \ return &image->data[x + y*image->stride / sizeof(T)]; \ } \ \ static inline \ mrcal_image_ ## Tname ## _t \ mrcal_image_ ## Tname ## _crop(mrcal_image_ ## Tname ## _t* image, \ int x0, int y0, \ int w, int h) \ { \ return (mrcal_image_ ## Tname ## _t){ .w = w, \ .h = h, \ .stride = image->stride, \ .data = mrcal_image_ ## Tname ## _at(image,x0,y0) }; \ } #define MRCAL_IMAGE_SAVE_LOAD_DECLARE(T, Tname) \ bool mrcal_image_ ## Tname ## _save (const char* filename, const mrcal_image_ ## Tname ## _t* image); \ bool mrcal_image_ ## Tname ## _load( mrcal_image_ ## Tname ## _t* image, const char* filename); // Common images types MRCAL_IMAGE_DECLARE(uint8_t, uint8); MRCAL_IMAGE_DECLARE(uint16_t, uint16); MRCAL_IMAGE_DECLARE(mrcal_bgr_t, bgr); MRCAL_IMAGE_SAVE_LOAD_DECLARE(uint8_t, uint8); MRCAL_IMAGE_SAVE_LOAD_DECLARE(uint16_t, uint16); MRCAL_IMAGE_SAVE_LOAD_DECLARE(mrcal_bgr_t, bgr); // Uncommon types. Not everything supports these MRCAL_IMAGE_DECLARE(int8_t, int8); MRCAL_IMAGE_DECLARE(int16_t, int16); MRCAL_IMAGE_DECLARE(int32_t, int32); MRCAL_IMAGE_DECLARE(uint32_t, uint32); MRCAL_IMAGE_DECLARE(int64_t, int64); MRCAL_IMAGE_DECLARE(uint64_t, uint64); MRCAL_IMAGE_DECLARE(float, float); MRCAL_IMAGE_DECLARE(double, double); // Load the image into whatever type is stored on disk bool mrcal_image_anytype_load(// output // This is ONE of the known types mrcal_image_uint8_t* image, int* bits_per_pixel, int* channels, // input const char* filename); mrcal-2.4.1/mrcal-internal.h000066400000000000000000000113271456301662300157070ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #pragma once // THESE ARE NOT A PART OF THE EXTERNAL API. Exported for the mrcal python // wrapper only // These models have no precomputed data typedef struct {} mrcal_LENSMODEL_PINHOLE__precomputed_t; typedef struct {} mrcal_LENSMODEL_STEREOGRAPHIC__precomputed_t; typedef struct {} mrcal_LENSMODEL_LONLAT__precomputed_t; typedef struct {} mrcal_LENSMODEL_LATLON__precomputed_t; typedef struct {} mrcal_LENSMODEL_OPENCV4__precomputed_t; typedef struct {} mrcal_LENSMODEL_OPENCV5__precomputed_t; typedef struct {} mrcal_LENSMODEL_OPENCV8__precomputed_t; typedef struct {} mrcal_LENSMODEL_OPENCV12__precomputed_t; typedef struct {} mrcal_LENSMODEL_CAHVOR__precomputed_t; typedef struct {} mrcal_LENSMODEL_CAHVORE__precomputed_t; // The splined stereographic models configuration parameters can be used to // compute the segment size. I cache this computation typedef struct { // The distance between adjacent knots (1 segment) is u_per_segment = // 1/segments_per_u double segments_per_u; } mrcal_LENSMODEL_SPLINED_STEREOGRAPHIC__precomputed_t; typedef struct { bool ready; union { #define PRECOMPUTED_STRUCT(s,n) mrcal_ ##s##__precomputed_t s##__precomputed; MRCAL_LENSMODEL_LIST(PRECOMPUTED_STRUCT); #undef PRECOMPUTED_STRUCT }; } mrcal_projection_precomputed_t; void _mrcal_project_internal_opencv( // outputs mrcal_point2_t* q, mrcal_point3_t* dq_dp, // may be NULL double* dq_dintrinsics_nocore, // may be NULL // inputs const mrcal_point3_t* p, int N, const double* intrinsics, int Nintrinsics); bool _mrcal_project_internal( // out mrcal_point2_t* q, // Stored as a row-first array of shape (N,2,3). Each // trailing ,3 dimension element is a mrcal_point3_t mrcal_point3_t* dq_dp, // core, distortions concatenated. Stored as a row-first // array of shape (N,2,Nintrinsics). This is a DENSE array. // High-parameter-count lens models have very sparse // gradients here, and the internal project() function // returns those sparsely. For now THIS function densifies // all of these double* dq_dintrinsics, // in const mrcal_point3_t* p, int N, const mrcal_lensmodel_t* lensmodel, // core, distortions concatenated const double* intrinsics, int Nintrinsics, const mrcal_projection_precomputed_t* precomputed); void _mrcal_precompute_lensmodel_data(mrcal_projection_precomputed_t* precomputed, const mrcal_lensmodel_t* lensmodel); bool _mrcal_unproject_internal( // out mrcal_point3_t* out, // in const mrcal_point2_t* q, int N, const mrcal_lensmodel_t* lensmodel, // core, distortions concatenated const double* intrinsics, const mrcal_projection_precomputed_t* precomputed); // Report the number of non-zero entries in the optimization jacobian int _mrcal_num_j_nonzero(int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, const mrcal_observation_board_t* observations_board, const mrcal_observation_point_t* observations_point, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel); mrcal-2.4.1/mrcal-is-within-valid-intrinsics-region000077500000000000000000000112261456301662300223220ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Reports which input points lie within the valid-intrinsics region SYNOPSIS $ < points-in.vnl mrcal-is-within-valid-intrinsics-region --cols-xy x y camera.cameramodel > points-annotated.vnl mrcal camera models may have an estimate of the region of the imager where the intrinsics are trustworthy (originally computed with a low-enough error and uncertainty). When using a model, we may want to process points that fall outside of this region differently from points that fall within this region. This tool augments an incoming vnlog with a new column, indicating whether each point does or does not fall within the region. The input data comes in on standard input, and the output data is written to standard output. Both are vnlog data: a human-readable table of ascii text. The names of the x and y columns in the input are given in the required --cols-xy argument. The output contains all the columns from the input, with an extra column appended at the end, containing the results. The name of this column can be specified with --col-output, but this can be omitted if the default 'is-within-valid-intrinsics-region' is acceptable. ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--cols-xy', required=True, type=str, nargs=2, help='''The names of the columns in the input containing the x and y pixel coordinates respectively. This is required''') parser.add_argument('--col-output', required=False, type=str, default='is-within-valid-intrinsics-region', help='''The name of the column to append in the output. This is optional; a reasonable default will be used if omitted''') parser.add_argument('model', type=str, help='''Camera model''') return parser.parse_args() args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README import numpy as np import numpysane as nps import subprocess import mrcal import io try: model = mrcal.cameramodel(args.model) except Exception as e: print(f"Couldn't load camera model '{args.model}': {e}", file=sys.stderr) sys.exit(1) if model.valid_intrinsics_region() is None: print("The given model has no valid-intrinsics region defined!", file=sys.stderr) sys.exit(1) # I want to be able to add to any arbitrary existing columns, so I slurp. # Good-enough for now. in_file = sys.stdin.read() cmd = ('vnl-filter', '-p', '__linenumber=NR', '-p', f'^{args.cols_xy[0]}$', '-p', f'^{args.cols_xy[1]}$') try: ixy_text = subprocess.check_output(cmd, shell = False, encoding = 'ascii', input = in_file) except: print(f"Couldn't read columns {args.cols_xy} from the input", file = sys.stderr) sys.exit(1) ixy = nps.atleast_dims(np.loadtxt(io.StringIO(ixy_text)), -2) mask = mrcal.is_within_valid_intrinsics_region(ixy[..., 1:], model) fd_read,fd_write = os.pipe() os.set_inheritable(fd_read, True) pid = os.fork() if pid == 0: # Child. I write the mask back to the pipe. The parent will join it os.close(fd_read) with open(f"/dev/fd/{fd_write}", 'w') as f: np.savetxt(f, nps.transpose(nps.cat(ixy[...,0], mask)), fmt='%06d %d', header=f'__linenumber {args.col_output}') os.close(fd_write) sys.exit(0) # parent. join the input data, and the data coming in from the child os.close(fd_write) # I don't re-sort the input. NR was printed with %06d so it's already sorted. cmd = f"vnl-filter --skipcomments -p __linenumber='sprintf(\"%06d\",NR)',. | vnl-join -j __linenumber - /dev/fd/{fd_read} | vnl-filter -p \\!__linenumber" subprocess.run( cmd, shell = True, close_fds = False, encoding = 'ascii', input = in_file ) os.close(fd_read) mrcal-2.4.1/mrcal-opencv.c000066400000000000000000000170471456301662300153650ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #include "mrcal.h" // The implementation of _mrcal_project_internal_opencv is based on opencv. The // sources have been heavily modified, but the opencv logic remains. This // function is a cut-down cvProjectPoints2Internal() to keep only the // functionality I want and to use my interfaces. Putting this here allows me to // drop the C dependency on opencv. Which is a good thing, since opencv dropped // their C API // // from opencv-4.2.0+dfsg/modules/calib3d/src/calibration.cpp // // Copyright (C) 2000-2008, Intel Corporation, all rights reserved. // Copyright (C) 2009, Willow Garage Inc., all rights reserved. // Third party copyrights are property of their respective owners. // // Redistribution and use in source and binary forms, with or without modification, // are permitted provided that the following conditions are met: // // * Redistribution's of source code must retain the above copyright notice, // this list of conditions and the following disclaimer. // // * Redistribution's in binary form must reproduce the above copyright notice, // this list of conditions and the following disclaimer in the documentation // and/or other materials provided with the distribution. // // * The name of the copyright holders may not be used to endorse or promote products // derived from this software without specific prior written permission. // // This software is provided by the copyright holders and contributors "as is" and // any express or implied warranties, including, but not limited to, the implied // warranties of merchantability and fitness for a particular purpose are disclaimed. // In no event shall the Intel Corporation or contributors be liable for any direct, // indirect, incidental, special, exemplary, or consequential damages // (including, but not limited to, procurement of substitute goods or services; // loss of use, data, or profits; or business interruption) however caused // and on any theory of liability, whether in contract, strict liability, // or tort (including negligence or otherwise) arising in any way out of // NOT A PART OF THE EXTERNAL API. This is exported for the mrcal python wrapper // only void _mrcal_project_internal_opencv( // outputs mrcal_point2_t* q, mrcal_point3_t* dq_dp, // may be NULL double* dq_dintrinsics_nocore, // may be NULL // inputs const mrcal_point3_t* p, int N, const double* intrinsics, int Nintrinsics) { const double fx = intrinsics[0]; const double fy = intrinsics[1]; const double cx = intrinsics[2]; const double cy = intrinsics[3]; double k[12] = {}; for(int i=0; i 2 ) { dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 0) + 2] = fx*a1; dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 1) + 2] = fy*a3; dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 0) + 3] = fx*a2; dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 1) + 3] = fy*a1; if( Nintrinsics-4 > 4 ) { dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 0) + 4] = fx*x*icdist2*r6; dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 1) + 4] = fy*y*icdist2*r6; if( Nintrinsics-4 > 5 ) { dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 0) + 5] = fx*x*cdist*(-icdist2)*icdist2*r2; dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 1) + 5] = fy*y*cdist*(-icdist2)*icdist2*r2; dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 0) + 6] = fx*x*cdist*(-icdist2)*icdist2*r4; dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 1) + 6] = fy*y*cdist*(-icdist2)*icdist2*r4; dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 0) + 7] = fx*x*cdist*(-icdist2)*icdist2*r6; dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 1) + 7] = fy*y*cdist*(-icdist2)*icdist2*r6; if( Nintrinsics-4 > 8 ) { dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 0) + 8] = fx*r2; //s1 dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 1) + 8] = fy*0; //s1 dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 0) + 9] = fx*r4; //s2 dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 1) + 9] = fy*0; //s2 dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 0) + 10] = fx*0; //s3 dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 1) + 10] = fy*r2; //s3 dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 0) + 11] = fx*0; //s4 dq_dintrinsics_nocore[(Nintrinsics-4)*(2*i + 1) + 11] = fy*r4; //s4 } } } } } } } mrcal-2.4.1/mrcal-pywrap.c000066400000000000000000004505051456301662300154150ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #define NPY_NO_DEPRECATED_API NPY_API_VERSION #include #include #include #include #include #include #include #if (CHOLMOD_VERSION > (CHOLMOD_VER_CODE(2,2))) && (CHOLMOD_VERSION < (CHOLMOD_VER_CODE(4,0))) #include #endif #include "mrcal.h" #include "mrcal-image.h" #include "stereo.h" #define IS_NULL(x) ((x) == NULL || (PyObject*)(x) == Py_None) #define BARF(fmt, ...) PyErr_Format(PyExc_RuntimeError, "%s:%d %s(): "fmt, __FILE__, __LINE__, __func__, ## __VA_ARGS__) // Python is silly. There's some nuance about signal handling where it sets a // SIGINT (ctrl-c) handler to just set a flag, and the python layer then reads // this flag and does the thing. Here I'm running C code, so SIGINT would set a // flag, but not quit, so I can't interrupt the solver. Thus I reset the SIGINT // handler to the default, and put it back to the python-specific version when // I'm done #define SET_SIGINT() struct sigaction sigaction_old; \ do { \ if( 0 != sigaction(SIGINT, \ &(struct sigaction){ .sa_handler = SIG_DFL }, \ &sigaction_old) ) \ { \ BARF("sigaction() failed"); \ goto done; \ } \ } while(0) #define RESET_SIGINT() do { \ if( 0 != sigaction(SIGINT, \ &sigaction_old, NULL )) \ BARF("sigaction-restore failed"); \ } while(0) #define PERCENT_S_COMMA(s,n) "'%s'," #define COMMA_LENSMODEL_NAME(s,n) , mrcal_lensmodel_name_unconfigured( &(mrcal_lensmodel_t){.type = MRCAL_##s} ) #define VALID_LENSMODELS_FORMAT "(" MRCAL_LENSMODEL_LIST(PERCENT_S_COMMA) ")" #define VALID_LENSMODELS_ARGLIST MRCAL_LENSMODEL_LIST(COMMA_LENSMODEL_NAME) #define CHECK_CONTIGUOUS(x) do { \ if( !PyArray_IS_C_CONTIGUOUS(x) ) \ { \ BARF("All inputs must be c-style contiguous arrays (" #x ")"); \ return false; \ } } while(0) #define COMMA , #define ARG_DEFINE( name, pytype, initialvalue, parsecode, parseprearg, name_pyarrayobj, npy_type, dims_ref) pytype name = initialvalue; #define ARG_LIST_DEFINE(name, pytype, initialvalue, parsecode, parseprearg, name_pyarrayobj, npy_type, dims_ref) pytype name, #define ARG_LIST_CALL( name, pytype, initialvalue, parsecode, parseprearg, name_pyarrayobj, npy_type, dims_ref) name, #define NAMELIST( name, pytype, initialvalue, parsecode, parseprearg, name_pyarrayobj, npy_type, dims_ref) #name , #define PARSECODE( name, pytype, initialvalue, parsecode, parseprearg, name_pyarrayobj, npy_type, dims_ref) parsecode #define PARSEARG( name, pytype, initialvalue, parsecode, parseprearg, name_pyarrayobj, npy_type, dims_ref) parseprearg &name, #define FREE_PYARRAY( name, pytype, initialvalue, parsecode, parseprearg, name_pyarrayobj, npy_type, dims_ref) Py_XDECREF(name_pyarrayobj); #define PYMETHODDEF_ENTRY(function_prefix, name, args) {#name, \ (PyCFunction)function_prefix ## name, \ args, \ function_prefix ## name ## _docstring} #define CHECK_LAYOUT( name, pytype, initialvalue, parsecode, parseprearg, name_pyarrayobj, npy_type, dims_ref) \ { \ const int dims[] = dims_ref; \ int ndims = (int)sizeof(dims)/(int)sizeof(dims[0]); \ if(!_check_layout( #name, (PyArrayObject*)name_pyarrayobj, (int)npy_type, #npy_type, dims, ndims, #dims_ref, true )) \ goto done; \ } static bool _check_layout(const char* name, PyArrayObject* pyarrayobj, int npy_type, const char* npy_type_string, const int* dims_ref, int Ndims_ref, const char* dims_ref_string, bool do_check_for_contiguity) { if(!IS_NULL(pyarrayobj)) { if( Ndims_ref > 0 ) { if( PyArray_NDIM(pyarrayobj) != Ndims_ref ) { BARF("'%s' must have exactly %d dims; got %d", name, Ndims_ref, PyArray_NDIM(pyarrayobj)); return false; } for(int i=0; i= 0 && dims_ref[i] != PyArray_DIMS(pyarrayobj)[i]) { BARF("'%s' must have dimensions '%s' where <0 means 'any'. Dims %d got %ld instead", name, dims_ref_string, i, PyArray_DIMS(pyarrayobj)[i]); return false; } } if( npy_type >= 0 ) { if( PyArray_TYPE(pyarrayobj) != npy_type ) { BARF("'%s' must have type: %s", name, npy_type_string); return false; } if( do_check_for_contiguity && !PyArray_IS_C_CONTIGUOUS(pyarrayobj) ) { BARF("'%s' must be c-style contiguous", name); return false; } } } return true; } // adds a reference to P,I,X, unless an error is reported static PyObject* csr_from_cholmod_sparse( PyObject* P, PyObject* I, PyObject* X ) { // I do the Python equivalent of this; // scipy.sparse.csr_matrix((data, indices, indptr)) PyObject* result = NULL; PyObject* module = NULL; PyObject* method = NULL; PyObject* args = NULL; if(NULL == (module = PyImport_ImportModule("scipy.sparse"))) { BARF("Couldn't import scipy.sparse. I need that to represent J"); goto done; } if(NULL == (method = PyObject_GetAttrString(module, "csr_matrix"))) { BARF("Couldn't find 'csr_matrix' in scipy.sparse"); goto done; } // Here I'm assuming specific types in my cholmod arrays. I tried to // _Static_assert it, but internally cholmod uses void*, so I can't do that PyObject* MatrixDef = PyTuple_Pack(3, X, I, P); args = PyTuple_Pack(1, MatrixDef); Py_DECREF(MatrixDef); if(NULL == (result = PyObject_CallObject(method, args))) goto done; // reuse already-set error // Testing code to dump out a dense representation of this matrix to a file. // Can compare that file to what this function returns like this: // Jf = np.fromfile("/tmp/J_17014_444.dat").reshape(17014,444) // np.linalg.norm( Jf - J.toarray() ) // { // #define P(A, index) ((unsigned int*)((A)->p))[index] // #define I(A, index) ((unsigned int*)((A)->i))[index] // #define X(A, index) ((double* )((A)->x))[index] // char logfilename[128]; // sprintf(logfilename, "/tmp/J_%d_%d.dat",(int)Jt->ncol,(int)Jt->nrow); // FILE* fp = fopen(logfilename, "w"); // double* Jrow; // Jrow = malloc(Jt->nrow*sizeof(double)); // for(unsigned int icol=0; icolncol; icol++) // { // memset(Jrow, 0, Jt->nrow*sizeof(double)); // for(unsigned int i=P(Jt, icol); inrow,fp); // } // fclose(fp); // free(Jrow); // #undef P // #undef I // #undef X // } done: Py_XDECREF(module); Py_XDECREF(method); Py_XDECREF(args); return result; } // A container for a CHOLMOD factorization typedef struct { PyObject_HEAD // if(inited_common), the "common" has been initialized // if(factorization), the factorization has been initialized // // So to use the object we need inited_common && factorization bool inited_common; cholmod_common common; cholmod_factor* factorization; // optimizer_callback should return it // and I should have two solve methods: } CHOLMOD_factorization; // stolen from libdogleg static int cholmod_error_callback(const char* s, ...) { va_list ap; va_start(ap, s); int ret = vfprintf(stderr, s, ap); va_end(ap); fprintf(stderr, "\n"); return ret; } // for my internal C usage static void _CHOLMOD_factorization_release_internal(CHOLMOD_factorization* self) { if( self->factorization ) { cholmod_free_factor(&self->factorization, &self->common); self->factorization = NULL; } if( self->inited_common ) cholmod_finish(&self->common); self->inited_common = false; } // for my internal C usage static bool _CHOLMOD_factorization_init_from_cholmod_sparse(CHOLMOD_factorization* self, cholmod_sparse* Jt) { if( !self->inited_common ) { if( !cholmod_start(&self->common) ) { BARF("Error trying to cholmod_start"); return false; } self->inited_common = true; // stolen from libdogleg // I want to use LGPL parts of CHOLMOD only, so I turn off the supernodal routines. This gave me a // 25% performance hit in the solver for a particular set of optical calibration data. self->common.supernodal = 0; // I want all output to go to STDERR, not STDOUT #if (CHOLMOD_VERSION <= (CHOLMOD_VER_CODE(2,2))) self->common.print_function = cholmod_error_callback; #elif (CHOLMOD_VERSION < (CHOLMOD_VER_CODE(4,0))) CHOLMOD_FUNCTION_DEFAULTS ; CHOLMOD_FUNCTION_PRINTF(&self->common) = cholmod_error_callback; #else SuiteSparse_config_printf_func_set(cholmod_error_callback); #endif } self->factorization = cholmod_analyze(Jt, &self->common); if(self->factorization == NULL) { BARF("cholmod_analyze() failed"); return false; } if( !cholmod_factorize(Jt, self->factorization, &self->common) ) { BARF("cholmod_factorize() failed"); return false; } if(self->factorization->minor != self->factorization->n) { BARF("Got singular JtJ!"); return false; } return true; } static int CHOLMOD_factorization_init(CHOLMOD_factorization* self, PyObject* args, PyObject* kwargs) { // Any existing factorization goes away. If this function fails, we lose the // existing factorization, which is fine. I'm placing this on top so that // __init__() will get rid of the old state _CHOLMOD_factorization_release_internal(self); // error by default int result = -1; char* keywords[] = {"J", NULL}; PyObject* Py_J = NULL; PyObject* module = NULL; PyObject* csr_matrix_type = NULL; PyObject* Py_shape = NULL; PyObject* Py_nnz = NULL; PyObject* Py_data = NULL; PyObject* Py_indices = NULL; PyObject* Py_indptr = NULL; PyObject* Py_has_sorted_indices = NULL; PyObject* Py_h = NULL; PyObject* Py_w = NULL; if( !PyArg_ParseTupleAndKeywords(args, kwargs, "|O:CHOLMOD_factorization.__init__", keywords, &Py_J)) goto done; if( Py_J == NULL ) { // Success. Nothing to do result = 0; goto done; } if(NULL == (module = PyImport_ImportModule("scipy.sparse"))) { BARF("Couldn't import scipy.sparse. I need that to represent J"); goto done; } if(NULL == (csr_matrix_type = PyObject_GetAttrString(module, "csr_matrix"))) { BARF("Couldn't find 'csr_matrix' in scipy.sparse"); goto done; } if(!PyObject_IsInstance(Py_J, csr_matrix_type)) { BARF("Argument J is must have type scipy.sparse.csr_matrix"); goto done; } #define GETATTR(x) \ if(NULL == (Py_ ## x = PyObject_GetAttrString(Py_J, #x))) \ { \ BARF("Couldn't get J." # x); \ goto done; \ } GETATTR(shape); GETATTR(nnz); GETATTR(data); GETATTR(indices); GETATTR(indptr); GETATTR(has_sorted_indices); if(!PySequence_Check(Py_shape)) { BARF("J.shape should be an iterable"); goto done; } int lenshape = PySequence_Length(Py_shape); if( lenshape != 2 ) { if(lenshape < 0) BARF("Failed to get len(J.shape)"); else BARF("len(J.shape) should be exactly 2, but instead got %d", lenshape); goto done; } Py_h = PySequence_GetItem(Py_shape, 0); if(Py_h == NULL) { BARF("Error getting J.shape[0]"); goto done; } Py_w = PySequence_GetItem(Py_shape, 1); if(Py_w == NULL) { BARF("Error getting J.shape[1]"); goto done; } long nnz; if(PyLong_Check(Py_nnz)) nnz = PyLong_AsLong(Py_nnz); else { BARF("Error interpreting nnz as an integer"); goto done; } long h; if(PyLong_Check(Py_h)) h = PyLong_AsLong(Py_h); else { BARF("Error interpreting J.shape[0] as an integer"); goto done; } long w; if(PyLong_Check(Py_w)) w = PyLong_AsLong(Py_w); else { BARF("Error interpreting J.shape[1] as an integer"); goto done; } #define CHECK_NUMPY_ARRAY(x, dtype) \ if( !PyArray_Check((PyArrayObject*)Py_ ## x) ) \ { \ BARF("J."#x " must be a numpy array"); \ goto done; \ } \ if( 1 != PyArray_NDIM((PyArrayObject*)Py_ ## x) ) \ { \ BARF("J."#x " must be a 1-dimensional numpy array. Instead got %d dimensions", \ PyArray_NDIM((PyArrayObject*)Py_ ## x)); \ goto done; \ } \ if( PyArray_TYPE((PyArrayObject*)Py_ ## x) != dtype ) \ { \ BARF("J."#x " must have dtype: " #dtype); \ goto done; \ } \ if( !PyArray_IS_C_CONTIGUOUS((PyArrayObject*)Py_ ## x) ) \ { \ BARF("J."#x " must live in contiguous memory"); \ goto done; \ } CHECK_NUMPY_ARRAY(data, NPY_FLOAT64); CHECK_NUMPY_ARRAY(indices, NPY_INT32); CHECK_NUMPY_ARRAY(indptr, NPY_INT32); // OK, the input looks good. I guess I can tell CHOLMOD about it // My convention is to store row-major matrices, but CHOLMOD stores // col-major matrices. So I keep the same data, but tell CHOLMOD that I'm // storing Jt and not J cholmod_sparse Jt = { .nrow = w, .ncol = h, .nzmax = nnz, .p = PyArray_DATA((PyArrayObject*)Py_indptr), .i = PyArray_DATA((PyArrayObject*)Py_indices), .x = PyArray_DATA((PyArrayObject*)Py_data), .stype = 0, // not symmetric .itype = CHOLMOD_INT, .xtype = CHOLMOD_REAL, .dtype = CHOLMOD_DOUBLE, .sorted = PyObject_IsTrue(Py_has_sorted_indices), .packed = 1 }; if(!_CHOLMOD_factorization_init_from_cholmod_sparse(self, &Jt)) goto done; result = 0; done: if(result != 0) _CHOLMOD_factorization_release_internal(self); Py_XDECREF(module); Py_XDECREF(csr_matrix_type); Py_XDECREF(Py_shape); Py_XDECREF(Py_nnz); Py_XDECREF(Py_data); Py_XDECREF(Py_indices); Py_XDECREF(Py_indptr); Py_XDECREF(Py_has_sorted_indices); Py_XDECREF(Py_h); Py_XDECREF(Py_w); return result; #undef GETATTR #undef CHECK_NUMPY_ARRAY } static void CHOLMOD_factorization_dealloc(CHOLMOD_factorization* self) { _CHOLMOD_factorization_release_internal(self); Py_TYPE(self)->tp_free((PyObject*)self); } static PyObject* CHOLMOD_factorization_str(CHOLMOD_factorization* self) { if(!(self->inited_common && self->factorization)) return PyUnicode_FromString("No factorization given"); return PyUnicode_FromFormat("Initialized with a valid factorization. N=%d", self->factorization->n); } static PyObject* CHOLMOD_factorization_solve_xt_JtJ_bt(CHOLMOD_factorization* self, PyObject* args, PyObject* kwargs) { cholmod_dense* M = NULL; cholmod_dense* Y = NULL; cholmod_dense* E = NULL; // error by default PyObject* result = NULL; PyObject* Py_out = NULL; char* keywords[] = {"bt", NULL}; PyObject* Py_bt = NULL; if(!(self->inited_common && self->factorization)) { BARF("No factorization has been computed"); goto done; } if( !PyArg_ParseTupleAndKeywords(args, kwargs, "O:CHOLMOD_factorization.solve_xt_JtJ_bt", keywords, &Py_bt)) goto done; if( Py_bt == NULL || !PyArray_Check((PyArrayObject*)Py_bt) ) { BARF("bt must be a numpy array"); goto done; } int ndim = PyArray_NDIM((PyArrayObject*)Py_bt); if( ndim < 1 ) { BARF("bt must be at least a 1-dimensional numpy array. Instead got %d dimensions", ndim); goto done; } int Nstate = (int)PyArray_DIMS((PyArrayObject*)Py_bt)[ndim-1]; int Nrhs = (int)PyArray_SIZE((PyArrayObject*)Py_bt) / Nstate; if( self->factorization->n != (unsigned)Nstate ) { BARF("bt must be a 2-dimensional numpy array with %d cols (that's what the factorization has). Instead got %d cols", self->factorization->n, Nstate); goto done; } if( PyArray_TYPE((PyArrayObject*)Py_bt) != NPY_FLOAT64 ) { BARF("bt must have dtype=float"); goto done; } if( !PyArray_IS_C_CONTIGUOUS((PyArrayObject*)Py_bt) ) { BARF("bt must live in contiguous memory"); goto done; } // Alright. b looks good-enough to use if( 0 == Nrhs ) { // Degenerate input (0 columns). Just return it, and I'm done result = Py_bt; Py_INCREF(result); goto done; } cholmod_dense b = { .nrow = Nstate, .ncol = Nrhs, .nzmax = Nrhs * Nstate, .d = Nstate, .x = PyArray_DATA((PyArrayObject*)Py_bt), .xtype = CHOLMOD_REAL, .dtype = CHOLMOD_DOUBLE }; Py_out = PyArray_SimpleNew(ndim, PyArray_DIMS((PyArrayObject*)Py_bt), NPY_DOUBLE); if(Py_out == NULL) { BARF("Couldn't allocate Py_out"); goto done; } cholmod_dense out = { .nrow = Nstate, .ncol = Nrhs, .nzmax = Nrhs * Nstate, .d = Nstate, .x = PyArray_DATA((PyArrayObject*)Py_out), .xtype = CHOLMOD_REAL, .dtype = CHOLMOD_DOUBLE }; M = &out; Y = NULL; E = NULL; if(!cholmod_solve2( CHOLMOD_A, self->factorization, &b, NULL, &M, NULL, &Y, &E, &self->common)) { BARF("cholmod_solve2() failed"); goto done; } if( M != &out ) { BARF("cholmod_solve2() reallocated out! We leaked memory"); goto done; } Py_INCREF(Py_out); result = Py_out; done: if(E != NULL) cholmod_free_dense (&E, &self->common); if(Y != NULL) cholmod_free_dense (&Y, &self->common); Py_XDECREF(Py_out); return result; } static PyObject* CHOLMOD_factorization_rcond(CHOLMOD_factorization* self, PyObject* NPY_UNUSED(args)) { if(!(self->inited_common && self->factorization)) { BARF("No factorization has been computed"); return NULL; } return PyFloat_FromDouble(cholmod_rcond( self->factorization, &self->common)); } static const char CHOLMOD_factorization_docstring[] = #include "CHOLMOD_factorization.docstring.h" ; static const char CHOLMOD_factorization_solve_xt_JtJ_bt_docstring[] = #include "CHOLMOD_factorization_solve_xt_JtJ_bt.docstring.h" ; static const char CHOLMOD_factorization_rcond_docstring[] = #include "CHOLMOD_factorization_rcond.docstring.h" ; static PyMethodDef CHOLMOD_factorization_methods[] = { PYMETHODDEF_ENTRY(CHOLMOD_factorization_, solve_xt_JtJ_bt, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(CHOLMOD_factorization_, rcond, METH_NOARGS), {} }; #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wmissing-braces" // PyObject_HEAD_INIT throws // warning: missing braces around initializer [] // This isn't mine to fix, so I'm ignoring it static PyTypeObject CHOLMOD_factorization_type = { PyObject_HEAD_INIT(NULL) .tp_name = "mrcal.CHOLMOD_factorization", .tp_basicsize = sizeof(CHOLMOD_factorization), .tp_new = PyType_GenericNew, .tp_init = (initproc)CHOLMOD_factorization_init, .tp_dealloc = (destructor)CHOLMOD_factorization_dealloc, .tp_methods = CHOLMOD_factorization_methods, .tp_str = (reprfunc)CHOLMOD_factorization_str, .tp_flags = Py_TPFLAGS_DEFAULT, .tp_doc = CHOLMOD_factorization_docstring, }; #pragma GCC diagnostic pop // For the C code. Create a new Python CHOLMOD_factorization object from a C // cholmod_sparse structure static PyObject* CHOLMOD_factorization_from_cholmod_sparse(cholmod_sparse* Jt) { PyObject* self = PyObject_CallObject((PyObject*)&CHOLMOD_factorization_type, NULL); if(NULL == self) return NULL; if(!_CHOLMOD_factorization_init_from_cholmod_sparse((CHOLMOD_factorization*)self, Jt)) { Py_DECREF(self); return NULL; } return self; } static bool parse_lensmodel_from_arg(// output mrcal_lensmodel_t* lensmodel, // input const char* lensmodel_cstring) { mrcal_lensmodel_from_name(lensmodel, lensmodel_cstring); if( !mrcal_lensmodel_type_is_valid(lensmodel->type) ) { switch(lensmodel->type) { case MRCAL_LENSMODEL_INVALID: // this should never (rarely?) happen BARF("Lens model '%s': error parsing", lensmodel_cstring); return false; case MRCAL_LENSMODEL_INVALID_BADCONFIG: BARF("Lens model '%s': error parsing the required configuration", lensmodel_cstring); return false; case MRCAL_LENSMODEL_INVALID_MISSINGCONFIG: BARF("Lens model '%s': missing the required configuration", lensmodel_cstring); return false; case MRCAL_LENSMODEL_INVALID_TYPE: BARF("Invalid lens model type was passed in: '%s'. Must be one of " VALID_LENSMODELS_FORMAT, lensmodel_cstring VALID_LENSMODELS_ARGLIST); return false; default: BARF("Lens model '%s' produced an unexpected error: lensmodel->type=%d. This should never happen", lensmodel_cstring, (int)lensmodel->type); return false; } return false; } return true; } static PyObject* lensmodel_metadata_and_config(PyObject* NPY_UNUSED(self), PyObject* args) { PyObject* result = NULL; char* lensmodel_string = NULL; if(!PyArg_ParseTuple( args, "s", &lensmodel_string )) goto done; mrcal_lensmodel_t lensmodel; if(!parse_lensmodel_from_arg(&lensmodel, lensmodel_string)) goto done; mrcal_lensmodel_metadata_t meta = mrcal_lensmodel_metadata(&lensmodel); #define MRCAL_ITEM_BUILDVALUE_DEF( name, type, pybuildvaluecode, PRIcode,SCNcode, bitfield, cookie) " s "pybuildvaluecode #define MRCAL_ITEM_BUILDVALUE_VALUE(name, type, pybuildvaluecode, PRIcode,SCNcode, bitfield, cookie) , #name, cookie name if(lensmodel.type == MRCAL_LENSMODEL_CAHVORE ) result = Py_BuildValue("{" MRCAL_LENSMODEL_META_LIST(MRCAL_ITEM_BUILDVALUE_DEF, ) MRCAL_LENSMODEL_CAHVORE_CONFIG_LIST(MRCAL_ITEM_BUILDVALUE_DEF, ) "}" MRCAL_LENSMODEL_META_LIST(MRCAL_ITEM_BUILDVALUE_VALUE, meta.) MRCAL_LENSMODEL_CAHVORE_CONFIG_LIST(MRCAL_ITEM_BUILDVALUE_VALUE, lensmodel.LENSMODEL_CAHVORE__config.)); else if(lensmodel.type == MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC ) result = Py_BuildValue("{" MRCAL_LENSMODEL_META_LIST(MRCAL_ITEM_BUILDVALUE_DEF, ) MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC_CONFIG_LIST(MRCAL_ITEM_BUILDVALUE_DEF, ) "}" MRCAL_LENSMODEL_META_LIST(MRCAL_ITEM_BUILDVALUE_VALUE, meta.) MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC_CONFIG_LIST(MRCAL_ITEM_BUILDVALUE_VALUE, lensmodel.LENSMODEL_SPLINED_STEREOGRAPHIC__config.)); else result = Py_BuildValue("{" MRCAL_LENSMODEL_META_LIST(MRCAL_ITEM_BUILDVALUE_DEF, ) "}" MRCAL_LENSMODEL_META_LIST(MRCAL_ITEM_BUILDVALUE_VALUE, meta.)); Py_INCREF(result); done: return result; } static PyObject* knots_for_splined_models(PyObject* NPY_UNUSED(self), PyObject* args) { PyObject* result = NULL; PyArrayObject* py_ux = NULL; PyArrayObject* py_uy = NULL; char* lensmodel_string = NULL; if(!PyArg_ParseTuple( args, "s", &lensmodel_string )) goto done; mrcal_lensmodel_t lensmodel; if(!parse_lensmodel_from_arg(&lensmodel, lensmodel_string)) goto done; if(lensmodel.type != MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC) { BARF( "This function works only with the MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC model. %s passed in", lensmodel_string); goto done; } { double ux[lensmodel.LENSMODEL_SPLINED_STEREOGRAPHIC__config.Nx]; double uy[lensmodel.LENSMODEL_SPLINED_STEREOGRAPHIC__config.Ny]; if(!mrcal_knots_for_splined_models(ux,uy, &lensmodel)) { BARF( "mrcal_knots_for_splined_models() failed"); goto done; } npy_intp dims[1]; dims[0] = lensmodel.LENSMODEL_SPLINED_STEREOGRAPHIC__config.Nx; py_ux = (PyArrayObject*)PyArray_SimpleNew(1, dims, NPY_DOUBLE); if(py_ux == NULL) { BARF("Couldn't allocate ux"); goto done; } dims[0] = lensmodel.LENSMODEL_SPLINED_STEREOGRAPHIC__config.Ny; py_uy = (PyArrayObject*)PyArray_SimpleNew(1, dims, NPY_DOUBLE); if(py_uy == NULL) { BARF("Couldn't allocate uy"); goto done; } memcpy(PyArray_DATA(py_ux), ux, lensmodel.LENSMODEL_SPLINED_STEREOGRAPHIC__config.Nx*sizeof(double)); memcpy(PyArray_DATA(py_uy), uy, lensmodel.LENSMODEL_SPLINED_STEREOGRAPHIC__config.Ny*sizeof(double)); } result = Py_BuildValue("OO", py_ux, py_uy); done: Py_XDECREF(py_ux); Py_XDECREF(py_uy); return result; } static PyObject* lensmodel_num_params(PyObject* NPY_UNUSED(self), PyObject* args) { PyObject* result = NULL; char* lensmodel_string = NULL; if(!PyArg_ParseTuple( args, "s", &lensmodel_string )) goto done; mrcal_lensmodel_t lensmodel; if(!parse_lensmodel_from_arg(&lensmodel, lensmodel_string)) goto done; int Nparams = mrcal_lensmodel_num_params(&lensmodel); result = Py_BuildValue("i", Nparams); done: return result; } static PyObject* supported_lensmodels(PyObject* NPY_UNUSED(self), PyObject* NPY_UNUSED(args)) { PyObject* result = NULL; const char* const* names = mrcal_supported_lensmodel_names(); // I now have a NULL-terminated list of NULL-terminated strings. Get N int N=0; while(names[N] != NULL) N++; result = PyTuple_New(N); if(result == NULL) { BARF("Failed PyTuple_New(%d)", N); goto done; } for(int i=0; i 0) { if( calibration_object_spacing <= 0.0 ) { BARF("We have board observations, so calibration_object_spacing MUST be a valid float > 0"); return false; } if(do_optimize_calobject_warp && IS_NULL(calobject_warp)) { BARF("do_optimize_calobject_warp is True, so calobject_warp MUST be given as an array to seed the optimization and to receive the results"); return false; } } int Nobservations_point = PyArray_DIMS(observations_point)[0]; if( PyArray_DIMS(indices_point_camintrinsics_camextrinsics)[0] != Nobservations_point ) { BARF("Inconsistent Nobservations_point: 'observations_point...' says %ld, 'indices_point_camintrinsics_camextrinsics' says %ld", Nobservations_point, PyArray_DIMS(indices_point_camintrinsics_camextrinsics)[0]); return false; } // I reuse the single-lensmodel validation function. That function expects // ONE set of intrinsics instead of N intrinsics, like this function does. // But I already did the CHECK_LAYOUT() at the start of this function, and // I'm not going to do that again here: passing do_check_layout=false. So // that difference doesn't matter if(!lensmodel_one_validate_args(mrcal_lensmodel, lensmodel, intrinsics, false)) return false; // make sure the indices arrays are valid: the data is monotonic and // in-range int Nframes = PyArray_DIMS(frames_rt_toref)[0]; int iframe_last = -1; int icam_intrinsics_last = -1; int icam_extrinsics_last = -1; for(int i_observation=0; i_observation= Nframes) { BARF("iframe MUST be in [0,%d], instead got %d in row %d of indices_frame_camintrinsics_camextrinsics", Nframes-1, iframe, i_observation); return false; } if(icam_intrinsics < 0 || icam_intrinsics >= Ncameras_intrinsics) { BARF("icam_intrinsics MUST be in [0,%d], instead got %d in row %d of indices_frame_camintrinsics_camextrinsics", Ncameras_intrinsics-1, icam_intrinsics, i_observation); return false; } if(icam_extrinsics < -1 || icam_extrinsics >= Ncameras_extrinsics) { BARF("icam_extrinsics MUST be in [-1,%d], instead got %d in row %d of indices_frame_camintrinsics_camextrinsics", Ncameras_extrinsics-1, icam_extrinsics, i_observation); return false; } // And then I check monotonicity if(iframe == iframe_last) { if( icam_intrinsics < icam_intrinsics_last ) { BARF("icam_intrinsics MUST be monotonically increasing in indices_frame_camintrinsics_camextrinsics. Instead row %d (frame %d) of indices_frame_camintrinsics_camextrinsics has icam_intrinsics=%d after previously seeing icam_intrinsics=%d", i_observation, iframe, icam_intrinsics, icam_intrinsics_last); return false; } if( icam_extrinsics < icam_extrinsics_last ) { BARF("icam_extrinsics MUST be monotonically increasing in indices_frame_camintrinsics_camextrinsics. Instead row %d (frame %d) of indices_frame_camintrinsics_camextrinsics has icam_extrinsics=%d after previously seeing icam_extrinsics=%d", i_observation, iframe, icam_extrinsics, icam_extrinsics_last); return false; } } else if( iframe < iframe_last ) { BARF("iframe MUST be monotonically increasing in indices_frame_camintrinsics_camextrinsics. Instead row %d of indices_frame_camintrinsics_camextrinsics has iframe=%d after previously seeing iframe=%d", i_observation, iframe, iframe_last); return false; } iframe_last = iframe; icam_intrinsics_last = icam_intrinsics; icam_extrinsics_last = icam_extrinsics; } int Npoints = PyArray_DIMS(points)[0]; if( Npoints > 0 ) { if(Npoints_fixed > Npoints) { BARF("I have Npoints=len(points)=%d, but Npoints_fixed=%d. Npoints_fixed > Npoints makes no sense", Npoints, Npoints_fixed); return false; } if(point_min_range <= 0.0 || point_max_range <= 0.0 || point_min_range >= point_max_range) { BARF("Point observations were given, so point_min_range and point_max_range MUST have been given usable values > 0 and max>min"); return false; } } else { if(Npoints_fixed) { BARF("No 'points' were given, so it's 'Npoints_fixed' doesn't do anything, and shouldn't be given"); return false; } } for(int i_observation=0; i_observation= Npoints) { BARF("i_point MUST be in [0,%d], instead got %d in row %d of indices_point_camintrinsics_camextrinsics", Npoints-1, i_point, i_observation); return false; } if(icam_intrinsics < 0 || icam_intrinsics >= Ncameras_intrinsics) { BARF("icam_intrinsics MUST be in [0,%d], instead got %d in row %d of indices_point_camintrinsics_camextrinsics", Ncameras_intrinsics-1, icam_intrinsics, i_observation); return false; } if(icam_extrinsics < -1 || icam_extrinsics >= Ncameras_extrinsics) { BARF("icam_extrinsics MUST be in [-1,%d], instead got %d in row %d of indices_point_camintrinsics_camextrinsics", Ncameras_extrinsics-1, icam_extrinsics, i_observation); return false; } } return true; done: return false; } static void fill_c_observations_board(// out mrcal_observation_board_t* c_observations_board, // in int Nobservations_board, const PyArrayObject* indices_frame_camintrinsics_camextrinsics) { for(int i_observation=0; i_observation0; if(do_optimize_intrinsics_distortions < 0) do_optimize_intrinsics_core = Ncameras_intrinsics>0; if(do_optimize_extrinsics < 0) do_optimize_extrinsics = Ncameras_extrinsics>0; if(do_optimize_frames < 0) do_optimize_frames = Nframes>0; if(do_optimize_calobject_warp < 0) do_optimize_calobject_warp = Nobservations_board>0; return (mrcal_problem_selections_t) { .do_optimize_intrinsics_core = do_optimize_intrinsics_core, .do_optimize_intrinsics_distortions= do_optimize_intrinsics_distortions, .do_optimize_extrinsics = do_optimize_extrinsics, .do_optimize_frames = do_optimize_frames, .do_optimize_calobject_warp = do_optimize_calobject_warp, .do_apply_regularization = do_apply_regularization, .do_apply_outlier_rejection = do_apply_outlier_rejection }; } static PyObject* _optimize(bool is_optimize, // or optimizer_callback PyObject* args, PyObject* kwargs) { PyObject* result = NULL; PyArrayObject* b_packed_final = NULL; PyArrayObject* x_final = NULL; PyObject* pystats = NULL; PyArrayObject* P = NULL; PyArrayObject* I = NULL; PyArrayObject* X = NULL; PyObject* factorization = NULL; PyObject* jacobian = NULL; OPTIMIZE_ARGUMENTS_REQUIRED(ARG_DEFINE); OPTIMIZE_ARGUMENTS_OPTIONAL(ARG_DEFINE); OPTIMIZER_CALLBACK_ARGUMENTS_OPTIONAL_EXTRA(ARG_DEFINE); int calibration_object_height_n = -1; int calibration_object_width_n = -1; SET_SIGINT(); if(is_optimize) { char* keywords[] = { OPTIMIZE_ARGUMENTS_REQUIRED(NAMELIST) OPTIMIZE_ARGUMENTS_OPTIONAL(NAMELIST) NULL}; if(!PyArg_ParseTupleAndKeywords( args, kwargs, OPTIMIZE_ARGUMENTS_REQUIRED(PARSECODE) "|$" OPTIMIZE_ARGUMENTS_OPTIONAL(PARSECODE) ":mrcal.optimize", keywords, OPTIMIZE_ARGUMENTS_REQUIRED(PARSEARG) OPTIMIZE_ARGUMENTS_OPTIONAL(PARSEARG) NULL)) goto done; } else { // optimizer_callback char* keywords[] = { OPTIMIZE_ARGUMENTS_REQUIRED(NAMELIST) OPTIMIZE_ARGUMENTS_OPTIONAL(NAMELIST) OPTIMIZER_CALLBACK_ARGUMENTS_OPTIONAL_EXTRA(NAMELIST) NULL}; if(!PyArg_ParseTupleAndKeywords( args, kwargs, OPTIMIZE_ARGUMENTS_REQUIRED(PARSECODE) "|$" OPTIMIZE_ARGUMENTS_OPTIONAL(PARSECODE) OPTIMIZER_CALLBACK_ARGUMENTS_OPTIONAL_EXTRA(PARSECODE) ":mrcal.optimizer_callback", keywords, OPTIMIZE_ARGUMENTS_REQUIRED(PARSEARG) OPTIMIZE_ARGUMENTS_OPTIONAL(PARSEARG) OPTIMIZER_CALLBACK_ARGUMENTS_OPTIONAL_EXTRA(PARSEARG) NULL)) goto done; } // Some of my input arguments can be empty (None). The code all assumes that // everything is a properly-dimensioned numpy array, with "empty" meaning // some dimension is 0. Here I make this conversion. The user can pass None, // and we still do the right thing. // // There's a silly implementation detail here: if you have a preprocessor // macro M(x), and you pass it M({1,2,3}), the preprocessor see 3 separate // args, not 1. That's why I have a __VA_ARGS__ here and why I instantiate a // separate dims[] (PyArray_SimpleNew is a macro too) #define SET_SIZE0_IF_NONE(x, type, ...) \ ({ \ if( IS_NULL(x) ) \ { \ if( x != NULL ) Py_DECREF(x); \ npy_intp dims[] = {__VA_ARGS__}; \ x = (PyArrayObject*)PyArray_SimpleNew(sizeof(dims)/sizeof(dims[0]), \ dims, type); \ } \ }) SET_SIZE0_IF_NONE(extrinsics_rt_fromref, NPY_DOUBLE, 0,6); SET_SIZE0_IF_NONE(frames_rt_toref, NPY_DOUBLE, 0,6); SET_SIZE0_IF_NONE(observations_board, NPY_DOUBLE, 0,179,171,3); // arbitrary numbers; shouldn't matter SET_SIZE0_IF_NONE(indices_frame_camintrinsics_camextrinsics, NPY_INT32, 0,3); SET_SIZE0_IF_NONE(points, NPY_DOUBLE, 0, 3); SET_SIZE0_IF_NONE(observations_point, NPY_DOUBLE, 0, 3); SET_SIZE0_IF_NONE(indices_point_camintrinsics_camextrinsics, NPY_INT32, 0, 3); SET_SIZE0_IF_NONE(imagersizes, NPY_INT32, 0, 2); #undef SET_NULL_IF_NONE mrcal_lensmodel_t mrcal_lensmodel; // Check the arguments for optimize(). If optimizer_callback, then the other // stuff is defined, but it all has valid, default values if( !optimize_validate_args(&mrcal_lensmodel, is_optimize, OPTIMIZE_ARGUMENTS_REQUIRED(ARG_LIST_CALL) OPTIMIZE_ARGUMENTS_OPTIONAL(ARG_LIST_CALL) OPTIMIZER_CALLBACK_ARGUMENTS_OPTIONAL_EXTRA(ARG_LIST_CALL) NULL)) goto done; // Can't compute a factorization without a jacobian. That's what we're factoring if(!no_factorization) no_jacobian = false; { int Ncameras_intrinsics = PyArray_DIMS(intrinsics)[0]; int Ncameras_extrinsics = PyArray_DIMS(extrinsics_rt_fromref)[0]; int Nframes = PyArray_DIMS(frames_rt_toref)[0]; int Npoints = PyArray_DIMS(points)[0]; int Nobservations_board = PyArray_DIMS(observations_board)[0]; int Nobservations_point = PyArray_DIMS(observations_point)[0]; if( Nobservations_board > 0 ) { calibration_object_height_n = PyArray_DIMS(observations_board)[1]; calibration_object_width_n = PyArray_DIMS(observations_board)[2]; } // The checks in optimize_validate_args() make sure these casts are kosher double* c_intrinsics = (double*) PyArray_DATA(intrinsics); mrcal_pose_t* c_extrinsics = (mrcal_pose_t*) PyArray_DATA(extrinsics_rt_fromref); mrcal_pose_t* c_frames = (mrcal_pose_t*) PyArray_DATA(frames_rt_toref); mrcal_point3_t* c_points = (mrcal_point3_t*)PyArray_DATA(points); mrcal_calobject_warp_t* c_calobject_warp = IS_NULL(calobject_warp) ? NULL : (mrcal_calobject_warp_t*)PyArray_DATA(calobject_warp); mrcal_point3_t* c_observations_board_pool = (mrcal_point3_t*)PyArray_DATA(observations_board); // must be contiguous; made sure above mrcal_observation_board_t c_observations_board[Nobservations_board]; fill_c_observations_board(// output c_observations_board, // input Nobservations_board, indices_frame_camintrinsics_camextrinsics); mrcal_observation_point_t c_observations_point[Nobservations_point]; fill_c_observations_point(// output c_observations_point, // input Nobservations_point, indices_point_camintrinsics_camextrinsics, observations_point); mrcal_problem_selections_t problem_selections = construct_problem_selections( do_optimize_intrinsics_core, do_optimize_intrinsics_distortions, do_optimize_extrinsics, do_optimize_frames, do_optimize_calobject_warp, do_apply_regularization, do_apply_outlier_rejection, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Nobservations_board ); mrcal_problem_constants_t problem_constants = {.point_min_range = point_min_range, .point_max_range = point_max_range}; int Nmeasurements = mrcal_num_measurements(Nobservations_board, Nobservations_point, calibration_object_width_n, calibration_object_height_n, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, problem_selections, &mrcal_lensmodel); int Nintrinsics_state = mrcal_num_intrinsics_optimization_params(problem_selections, &mrcal_lensmodel); // input int* c_imagersizes = PyArray_DATA(imagersizes); int Nstate = mrcal_num_states(Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, Nobservations_board, problem_selections, &mrcal_lensmodel); // both optimize() and optimizer_callback() use this b_packed_final = (PyArrayObject*)PyArray_SimpleNew(1, ((npy_intp[]){Nstate}), NPY_DOUBLE); double* c_b_packed_final = PyArray_DATA(b_packed_final); x_final = (PyArrayObject*)PyArray_SimpleNew(1, ((npy_intp[]){Nmeasurements}), NPY_DOUBLE); double* c_x_final = PyArray_DATA(x_final); if( is_optimize ) { // we're wrapping mrcal_optimize() const int Npoints_fromBoards = Nobservations_board * calibration_object_width_n*calibration_object_height_n; mrcal_stats_t stats = mrcal_optimize( c_b_packed_final, Nstate*sizeof(double), c_x_final, Nmeasurements*sizeof(double), c_intrinsics, c_extrinsics, c_frames, c_points, c_calobject_warp, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, c_observations_board, c_observations_point, Nobservations_board, Nobservations_point, c_observations_board_pool, &mrcal_lensmodel, c_imagersizes, problem_selections, &problem_constants, calibration_object_spacing, calibration_object_width_n, calibration_object_height_n, verbose, false); if(stats.rms_reproj_error__pixels < 0.0) { // Error! I throw an exception BARF("mrcal.optimize() failed!"); goto done; } pystats = PyDict_New(); if(pystats == NULL) { BARF("PyDict_New() failed!"); goto done; } #define MRCAL_STATS_ITEM_POPULATE_DICT(type, name, pyconverter) \ { \ PyObject* obj = pyconverter( (type)stats.name); \ if( obj == NULL) \ { \ BARF("Couldn't make PyObject for '" #name "'"); \ goto done; \ } \ \ if( 0 != PyDict_SetItemString(pystats, #name, obj) ) \ { \ BARF("Couldn't add to stats dict '" #name "'"); \ Py_DECREF(obj); \ goto done; \ } \ } MRCAL_STATS_ITEM(MRCAL_STATS_ITEM_POPULATE_DICT); if( 0 != PyDict_SetItemString(pystats, "b_packed", (PyObject*)b_packed_final) ) { BARF("Couldn't add to stats dict 'b_packed'"); goto done; } if( 0 != PyDict_SetItemString(pystats, "x", (PyObject*)x_final) ) { BARF("Couldn't add to stats dict 'x'"); goto done; } result = pystats; Py_INCREF(result); } else { // we're wrapping mrcal_optimizer_callback() int N_j_nonzero = _mrcal_num_j_nonzero(Nobservations_board, Nobservations_point, calibration_object_width_n, calibration_object_height_n, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, c_observations_board, c_observations_point, problem_selections, &mrcal_lensmodel); cholmod_sparse Jt = { .nrow = Nstate, .ncol = Nmeasurements, .nzmax = N_j_nonzero, .stype = 0, .itype = CHOLMOD_INT, .xtype = CHOLMOD_REAL, .dtype = CHOLMOD_DOUBLE, .sorted = 1, .packed = 1 }; if(!no_jacobian) { // above I made sure that no_jacobian was false if !no_factorization P = (PyArrayObject*)PyArray_SimpleNew(1, ((npy_intp[]){Nmeasurements + 1}), NPY_INT32); I = (PyArrayObject*)PyArray_SimpleNew(1, ((npy_intp[]){N_j_nonzero }), NPY_INT32); X = (PyArrayObject*)PyArray_SimpleNew(1, ((npy_intp[]){N_j_nonzero }), NPY_DOUBLE); Jt.p = PyArray_DATA(P); Jt.i = PyArray_DATA(I); Jt.x = PyArray_DATA(X); } if(!mrcal_optimizer_callback( // out c_b_packed_final, Nstate*sizeof(double), c_x_final, Nmeasurements*sizeof(double), no_jacobian ? NULL : &Jt, // in c_intrinsics, c_extrinsics, c_frames, c_points, c_calobject_warp, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, c_observations_board, c_observations_point, Nobservations_board, Nobservations_point, c_observations_board_pool, &mrcal_lensmodel, c_imagersizes, problem_selections, &problem_constants, calibration_object_spacing, calibration_object_width_n, calibration_object_height_n, verbose) ) { BARF("mrcal_optimizer_callback() failed!'"); goto done; } if(no_factorization) { factorization = Py_None; Py_INCREF(factorization); } else { // above I made sure that no_jacobian was false if !no_factorization factorization = CHOLMOD_factorization_from_cholmod_sparse(&Jt); if(factorization == NULL) { // Couldn't compute factorization. I don't barf, but set the // factorization to None factorization = Py_None; Py_INCREF(factorization); PyErr_Clear(); } } if(no_jacobian) { jacobian = Py_None; Py_INCREF(jacobian); } else { jacobian = csr_from_cholmod_sparse((PyObject*)P, (PyObject*)I, (PyObject*)X); if(jacobian == NULL) { // reuse the existing error goto done; } } result = PyTuple_Pack(4, (PyObject*)b_packed_final, (PyObject*)x_final, jacobian, factorization); } } done: OPTIMIZE_ARGUMENTS_REQUIRED(FREE_PYARRAY); OPTIMIZE_ARGUMENTS_OPTIONAL(FREE_PYARRAY); OPTIMIZER_CALLBACK_ARGUMENTS_OPTIONAL_EXTRA(FREE_PYARRAY); Py_XDECREF(b_packed_final); Py_XDECREF(x_final); Py_XDECREF(pystats); Py_XDECREF(P); Py_XDECREF(I); Py_XDECREF(X); Py_XDECREF(factorization); Py_XDECREF(jacobian); RESET_SIGINT(); return result; } static PyObject* optimizer_callback(PyObject* NPY_UNUSED(self), PyObject* args, PyObject* kwargs) { return _optimize(false, args, kwargs); } static PyObject* optimize(PyObject* NPY_UNUSED(self), PyObject* args, PyObject* kwargs) { return _optimize(true, args, kwargs); } // The state_index_... python functions don't need the full data but many of // them do need to know the dimensionality of the data. Thus these can take the // same arguments as optimizer_callback(). OR in lieu of that, the dimensions can // be passed-in explicitly with arguments // // If both are given, the explicit arguments take precedence. If neither are // given, I assume 0. // // This means that the arguments that are required in optimizer_callback() are // only optional here typedef int (callback_state_index_t)(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections); #define STATE_INDEX_GENERIC(f, ...) state_index_generic(callback_ ## f, \ #f, \ __VA_ARGS__ ) static PyObject* state_index_generic(callback_state_index_t cb, const char* called_function, PyObject* self, PyObject* args, PyObject* kwargs, bool need_lensmodel, bool negative_result_allowed, const char* argname) { // This is VERY similar to _pack_unpack_state(). Please consolidate // Also somewhat similar to _optimize() PyObject* result = NULL; OPTIMIZE_ARGUMENTS_REQUIRED(ARG_DEFINE); OPTIMIZE_ARGUMENTS_OPTIONAL(ARG_DEFINE); int i = -1; int Ncameras_intrinsics = -1; int Ncameras_extrinsics = -1; int Nframes = -1; int Npoints = -1; int Nobservations_board = -1; int Nobservations_point = -1; char* keywords[] = { (char*)argname, "Ncameras_intrinsics", "Ncameras_extrinsics", "Nframes", "Npoints", "Nobservations_board", "Nobservations_point", OPTIMIZE_ARGUMENTS_REQUIRED(NAMELIST) OPTIMIZE_ARGUMENTS_OPTIONAL(NAMELIST) NULL}; // needs to be big-enough to store the largest-possible called_function #define CALLED_FUNCTION_BUFFER "123456789012345678901234567890123456789012345678901234567890" char arg_string[] = "i" "|$" // everything is kwarg-only and optional. I apply logic down the // line to get what I need "iiiiii" OPTIMIZE_ARGUMENTS_REQUIRED(PARSECODE) OPTIMIZE_ARGUMENTS_OPTIONAL(PARSECODE) ":mrcal." CALLED_FUNCTION_BUFFER; if(strlen(CALLED_FUNCTION_BUFFER) < strlen(called_function)) { BARF("CALLED_FUNCTION_BUFFER too small for '%s'. This is a a bug", called_function); goto done; } arg_string[strlen(arg_string) - strlen(CALLED_FUNCTION_BUFFER)] = '\0'; strcat(arg_string, called_function); if(argname != NULL) { if(!PyArg_ParseTupleAndKeywords( args, kwargs, arg_string, keywords, &i, &Ncameras_intrinsics, &Ncameras_extrinsics, &Nframes, &Npoints, &Nobservations_board, &Nobservations_point, OPTIMIZE_ARGUMENTS_REQUIRED(PARSEARG) OPTIMIZE_ARGUMENTS_OPTIONAL(PARSEARG) NULL)) goto done; } else { if(!PyArg_ParseTupleAndKeywords( args, kwargs, // skip the initial "i". There is no "argname" here &arg_string[1], &keywords [1], &Ncameras_intrinsics, &Ncameras_extrinsics, &Nframes, &Npoints, &Nobservations_board, &Nobservations_point, OPTIMIZE_ARGUMENTS_REQUIRED(PARSEARG) OPTIMIZE_ARGUMENTS_OPTIONAL(PARSEARG) NULL)) goto done; } #undef CALLED_FUNCTION_BUFFER mrcal_lensmodel_t mrcal_lensmodel = {}; if(need_lensmodel) { if(lensmodel == NULL) { BARF("The 'lensmodel' argument is required"); goto done; } if(!parse_lensmodel_from_arg(&mrcal_lensmodel, lensmodel)) goto done; } // checks dimensionality of array !IS_NULL. So if any array isn't passed-in, // that's OK! After I do this and if !IS_NULL, then I can ask for array // dimensions safely OPTIMIZE_ARGUMENTS_REQUIRED(CHECK_LAYOUT); OPTIMIZE_ARGUMENTS_OPTIONAL(CHECK_LAYOUT); // If explicit dimensions are given, use them. If they're not given, but we // have an array, use those dimensions. If an array isn't given either, use // 0 if(Ncameras_intrinsics < 0) Ncameras_intrinsics = IS_NULL(intrinsics) ? 0 : PyArray_DIMS(intrinsics) [0]; if(Ncameras_extrinsics < 0) Ncameras_extrinsics = IS_NULL(extrinsics_rt_fromref) ? 0 : PyArray_DIMS(extrinsics_rt_fromref) [0]; if(Nframes < 0) Nframes = IS_NULL(frames_rt_toref) ? 0 : PyArray_DIMS(frames_rt_toref) [0]; if(Npoints < 0) Npoints = IS_NULL(points) ? 0 : PyArray_DIMS(points) [0]; if(Nobservations_board < 0) Nobservations_board = IS_NULL(observations_board) ? 0 : PyArray_DIMS(observations_board) [0]; if(Nobservations_point < 0) Nobservations_point = IS_NULL(observations_point) ? 0 : PyArray_DIMS(observations_point) [0]; int calibration_object_height_n = -1; int calibration_object_width_n = -1; if( Nobservations_board > 0 ) { calibration_object_height_n = PyArray_DIMS(observations_board)[1]; calibration_object_width_n = PyArray_DIMS(observations_board)[2]; } mrcal_problem_selections_t problem_selections = construct_problem_selections( do_optimize_intrinsics_core, do_optimize_intrinsics_distortions, do_optimize_extrinsics, do_optimize_frames, do_optimize_calobject_warp, do_apply_regularization, do_apply_outlier_rejection, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Nobservations_board ); int index = cb(i, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, Nobservations_board, Nobservations_point, calibration_object_width_n, calibration_object_height_n, indices_frame_camintrinsics_camextrinsics, indices_point_camintrinsics_camextrinsics, observations_point, &mrcal_lensmodel, problem_selections); if(PyErr_Occurred()) goto done; // Either <0 or INT_MAX means "error", and I return None from Python. // negative_result_allowed controls which of the two modes we're in if( ( negative_result_allowed && index != INT_MAX) || (!negative_result_allowed && index >= 0) ) { result = PyLong_FromLong(index); } else { result = Py_None; Py_INCREF(result); } done: OPTIMIZE_ARGUMENTS_REQUIRED(FREE_PYARRAY) ; OPTIMIZE_ARGUMENTS_OPTIONAL(FREE_PYARRAY) ; return result; } static int callback_state_index_intrinsics(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { return mrcal_state_index_intrinsics(i, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, Nobservations_board, problem_selections, lensmodel); } static PyObject* state_index_intrinsics(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(state_index_intrinsics, self, args, kwargs, true, false, "icam_intrinsics"); } static int callback_num_states_intrinsics(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { return mrcal_num_states_intrinsics(Ncameras_intrinsics, problem_selections, lensmodel); } static PyObject* num_states_intrinsics(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(num_states_intrinsics, self, args, kwargs, true, false, NULL); } static int callback_state_index_extrinsics(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { return mrcal_state_index_extrinsics(i, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, Nobservations_board, problem_selections, lensmodel); } static PyObject* state_index_extrinsics(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(state_index_extrinsics, self, args, kwargs, true, false, "icam_extrinsics"); } static int callback_num_states_extrinsics(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { return mrcal_num_states_extrinsics(Ncameras_extrinsics, problem_selections); } static PyObject* num_states_extrinsics(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(num_states_extrinsics, self, args, kwargs, false, false, NULL); } static int callback_state_index_frames(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { return mrcal_state_index_frames(i, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, Nobservations_board, problem_selections, lensmodel); } static PyObject* state_index_frames(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(state_index_frames, self, args, kwargs, true, false, "iframe"); } static int callback_num_states_frames(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { return mrcal_num_states_frames(Nframes, problem_selections); } static PyObject* num_states_frames(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(num_states_frames, self, args, kwargs, false, false, NULL); } static int callback_state_index_points(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { return mrcal_state_index_points(i, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, Nobservations_board, problem_selections, lensmodel); } static PyObject* state_index_points(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(state_index_points, self, args, kwargs, true, false, "i_point"); } static int callback_num_states_points(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { return mrcal_num_states_points(Npoints, Npoints_fixed, problem_selections); } static PyObject* num_states_points(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(num_states_points, self, args, kwargs, false, false, NULL); } static int callback_state_index_calobject_warp(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { return mrcal_state_index_calobject_warp( Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, Nobservations_board, problem_selections, lensmodel); } static PyObject* state_index_calobject_warp(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(state_index_calobject_warp, self, args, kwargs, true, false, NULL); } static int callback_num_states_calobject_warp(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { return mrcal_num_states_calobject_warp(problem_selections, Nobservations_board); } static PyObject* num_states_calobject_warp(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(num_states_calobject_warp, self, args, kwargs, false, false, NULL); } static int callback_num_states(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { return mrcal_num_states(Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, Nobservations_board, problem_selections, lensmodel); } static PyObject* num_states(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(num_states, self, args, kwargs, true, false, NULL); } static int callback_num_intrinsics_optimization_params(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { return mrcal_num_intrinsics_optimization_params(problem_selections, lensmodel); } static PyObject* num_intrinsics_optimization_params(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(num_intrinsics_optimization_params, self, args, kwargs, true, false, NULL); } static int callback_measurement_index_boards(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { if(calibration_object_width_n < 0) return -1; return mrcal_measurement_index_boards(i, Nobservations_board, Nobservations_point, calibration_object_width_n, calibration_object_height_n); } static PyObject* measurement_index_boards(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(measurement_index_boards, self, args, kwargs, false, false, "i_observation_board"); } static int callback_num_measurements_boards(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { if(calibration_object_width_n < 0) return 0; return mrcal_num_measurements_boards(Nobservations_board, calibration_object_width_n, calibration_object_height_n); } static PyObject* num_measurements_boards(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(num_measurements_boards, self, args, kwargs, false, false, NULL); } static int callback_measurement_index_points(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { return mrcal_measurement_index_points(i, Nobservations_board, Nobservations_point, calibration_object_width_n, calibration_object_height_n); } static PyObject* measurement_index_points(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(measurement_index_points, self, args, kwargs, false, false, "i_observation_point"); } static int callback_num_measurements_points(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { return mrcal_num_measurements_points(Nobservations_point); } static PyObject* num_measurements_points(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(num_measurements_points, self, args, kwargs, false, false, NULL); } static int callback_measurement_index_regularization(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { return mrcal_measurement_index_regularization(calibration_object_width_n, calibration_object_height_n, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, Nobservations_board, Nobservations_point, problem_selections, lensmodel); } static PyObject* measurement_index_regularization(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(measurement_index_regularization, self, args, kwargs, true, false, NULL); } static int callback_num_measurements_regularization(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { return mrcal_num_measurements_regularization(Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, Nobservations_board, problem_selections, lensmodel); } static PyObject* num_measurements_regularization(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(num_measurements_regularization, self, args, kwargs, true, false, NULL); } static int callback_num_measurements(int i, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { return mrcal_num_measurements(Nobservations_board, Nobservations_point, calibration_object_width_n, calibration_object_height_n, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, problem_selections, lensmodel); } static PyObject* num_measurements(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(num_measurements, self, args, kwargs, true, false, NULL); } static int callback_corresponding_icam_extrinsics(int icam_intrinsics, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, const PyArrayObject* indices_frame_camintrinsics_camextrinsics, const PyArrayObject* indices_point_camintrinsics_camextrinsics, const PyArrayObject* observations_point, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections) { // Negative results ARE allowed here, so I return INT_MAX on error if( icam_intrinsics < 0 || icam_intrinsics >= Ncameras_intrinsics ) { BARF("The given icam_intrinsics=%d is out of bounds. Must be >= 0 and < %d", icam_intrinsics, Ncameras_intrinsics); return INT_MAX; } int icam_extrinsics; if(Nobservations_board > 0 && indices_frame_camintrinsics_camextrinsics == NULL) { BARF("Have Nobservations_board > 0, but indices_frame_camintrinsics_camextrinsics == NULL. Some required arguments missing?"); return INT_MAX; } mrcal_observation_board_t c_observations_board[Nobservations_board]; fill_c_observations_board(// output c_observations_board, // input Nobservations_board, indices_frame_camintrinsics_camextrinsics); if(Nobservations_point > 0) { if(indices_point_camintrinsics_camextrinsics == NULL) { BARF("Have Nobservations_point > 0, but indices_point_camintrinsics_camextrinsics == NULL. Some required arguments missing?"); return INT_MAX; } if(observations_point == NULL) { BARF("Have Nobservations_point > 0, but observations_point == NULL. Some required arguments missing?"); return INT_MAX; } } mrcal_observation_point_t c_observations_point[Nobservations_point]; fill_c_observations_point(// output c_observations_point, // input Nobservations_point, indices_point_camintrinsics_camextrinsics, observations_point); if(!mrcal_corresponding_icam_extrinsics(&icam_extrinsics, icam_intrinsics, Ncameras_intrinsics, Ncameras_extrinsics, Nobservations_board, c_observations_board, Nobservations_point, c_observations_point)) { BARF("Error calling mrcal_corresponding_icam_extrinsics()"); return INT_MAX; } // might be <0. This is OK because negative_result_allowed is true here return icam_extrinsics; } static PyObject* corresponding_icam_extrinsics(PyObject* self, PyObject* args, PyObject* kwargs) { return STATE_INDEX_GENERIC(corresponding_icam_extrinsics, self, args, kwargs, false, true, // negative_result_allowed here "icam_intrinsics"); } static PyObject* _pack_unpack_state(PyObject* self, PyObject* args, PyObject* kwargs, bool pack) { // This is VERY similar to STATE_INDEX_GENERIC(). Please consolidate PyObject* result = NULL; OPTIMIZE_ARGUMENTS_REQUIRED(ARG_DEFINE); OPTIMIZE_ARGUMENTS_OPTIONAL(ARG_DEFINE); PyArrayObject* b = NULL; int Ncameras_intrinsics = -1; int Ncameras_extrinsics = -1; int Nframes = -1; int Npoints = -1; int Nobservations_board = -1; int Nobservations_point = -1; char* keywords[] = { "b", "Ncameras_intrinsics", "Ncameras_extrinsics", "Nframes", "Npoints", "Nobservations_board", "Nobservations_point", OPTIMIZE_ARGUMENTS_REQUIRED(NAMELIST) OPTIMIZE_ARGUMENTS_OPTIONAL(NAMELIST) NULL}; #define UNPACK_STATE "unpack_state" char arg_string[] = "O&" "|$" // everything is kwarg-only and optional. I apply logic down the // line to get what I need "iiiiii" OPTIMIZE_ARGUMENTS_REQUIRED(PARSECODE) OPTIMIZE_ARGUMENTS_OPTIONAL(PARSECODE) ":mrcal." UNPACK_STATE; if(pack) { arg_string[strlen(arg_string) - strlen(UNPACK_STATE)] = '\0'; strcat(arg_string, "pack_state"); } #undef UNPACK_STATE if(!PyArg_ParseTupleAndKeywords( args, kwargs, arg_string, keywords, PyArray_Converter, &b, &Ncameras_intrinsics, &Ncameras_extrinsics, &Nframes, &Npoints, &Nobservations_board, &Nobservations_point, OPTIMIZE_ARGUMENTS_REQUIRED(PARSEARG) OPTIMIZE_ARGUMENTS_OPTIONAL(PARSEARG) NULL)) goto done; if(lensmodel == NULL) { BARF("The 'lensmodel' argument is required"); goto done; } mrcal_lensmodel_t mrcal_lensmodel; if(!parse_lensmodel_from_arg(&mrcal_lensmodel, lensmodel)) goto done; // checks dimensionality of array !IS_NULL. So if any array isn't passed-in, // that's OK! After I do this and if !IS_NULL, then I can ask for array // dimensions safely OPTIMIZE_ARGUMENTS_REQUIRED(CHECK_LAYOUT); OPTIMIZE_ARGUMENTS_OPTIONAL(CHECK_LAYOUT); // If explicit dimensions are given, use them. If they're not given, but we // have an array, use those dimensions. If an array isn't given either, use // 0 if(Ncameras_intrinsics < 0) Ncameras_intrinsics = IS_NULL(intrinsics) ? 0 : PyArray_DIMS(intrinsics) [0]; if(Ncameras_extrinsics < 0) Ncameras_extrinsics = IS_NULL(extrinsics_rt_fromref) ? 0 : PyArray_DIMS(extrinsics_rt_fromref) [0]; if(Nframes < 0) Nframes = IS_NULL(frames_rt_toref) ? 0 : PyArray_DIMS(frames_rt_toref) [0]; if(Npoints < 0) Npoints = IS_NULL(points) ? 0 : PyArray_DIMS(points) [0]; if(Nobservations_board < 0) Nobservations_board = IS_NULL(observations_board) ? 0 : PyArray_DIMS(observations_board) [0]; if(Nobservations_point < 0) Nobservations_point = IS_NULL(observations_point) ? 0 : PyArray_DIMS(observations_point) [0]; mrcal_problem_selections_t problem_selections = construct_problem_selections( do_optimize_intrinsics_core, do_optimize_intrinsics_distortions, do_optimize_extrinsics, do_optimize_frames, do_optimize_calobject_warp, do_apply_regularization, do_apply_outlier_rejection, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Nobservations_board ); if( PyArray_TYPE(b) != NPY_DOUBLE ) { BARF("The given array MUST have values of type 'float'"); goto done; } if( !PyArray_IS_C_CONTIGUOUS(b) ) { BARF("The given array MUST be a C-style contiguous array"); goto done; } int ndim = PyArray_NDIM(b); npy_intp* dims = PyArray_DIMS(b); if( ndim < 1 ) { BARF("The given array MUST have at least one dimension"); goto done; } int Nstate = mrcal_num_states(Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, Nobservations_board, problem_selections, &mrcal_lensmodel); if( dims[ndim-1] != Nstate ) { BARF("The given array MUST have last dimension of size Nstate=%d; instead got %ld", Nstate, dims[ndim-1]); goto done; } double* x = (double*)PyArray_DATA(b); if(pack) for(int i=0; i 0) || (bits_per_pixel > 0 && channels <= 0)) { BARF("Both bits_per_pixel and channels should be given valid values >0, or neither should be"); goto done; } if(bits_per_pixel <= 0) { if(!mrcal_image_anytype_load(&image, &bits_per_pixel, &channels, filename)) { BARF("Error loading image '%s' with autodetected bits_per_pixel,channels", filename); goto done; } } // I support a small number of combinations: // - bits_per_pixel = 8, channels = 1 // - bits_per_pixel = 16, channels = 1 // - bits_per_pixel = 24, channels = 3 if(bits_per_pixel == 8 && channels == 1) { if(image.data == NULL && !mrcal_image_uint8_load((mrcal_image_uint8_t*)&image, filename)) { BARF("Error loading image '%s'", filename); goto done; } image_array = PyArray_SimpleNew(2, ((npy_intp[]){image.h, image.w}), NPY_UINT8); } else if(bits_per_pixel == 16 && channels == 1) { if(image.data == NULL && !mrcal_image_uint16_load((mrcal_image_uint16_t*)&image, filename)) { BARF("Error loading image '%s'", filename); goto done; } image_array = PyArray_SimpleNew(2, ((npy_intp[]){image.h, image.w}), NPY_UINT16); } else if(bits_per_pixel == 24 && channels == 3) { if(image.data == NULL && !mrcal_image_bgr_load((mrcal_image_bgr_t*)&image, filename)) { BARF("Error loading image '%s' with bits_per_pixel=%d and channels=%d", filename, bits_per_pixel, channels); goto done; } image_array = PyArray_SimpleNew(3, ((npy_intp[]){image.h, image.w, 3}), NPY_UINT8); } else { BARF("Unsupported format requested. I only support (bits_per_pixel,channels) = (8,1) and (16,1) and (24,3)"); goto done; } if(image_array == NULL) goto done; // The numpy array is dense, but the image array may not be. Copy one line // at a time for(int i=0; i 1e6) az0_deg_autodetect = true; if( !lensmodel_one_validate_args(&mrcal_lensmodel0, LENSMODEL_ONE_ARGUMENTS(ARG_LIST_CALL, 0) true /* DO check the layout */ )) goto done; if(!parse_lensmodel_from_arg(&rectification_model, rectification_model_string)) goto done; if(!rectified_system_validate_args(RECTIFIED_SYSTEM_ARGUMENTS(ARG_LIST_CALL) NULL)) goto done; if(!mrcal_rectified_system( // output imagersize_rectified, PyArray_DATA(fxycxy_rectified), PyArray_DATA(rt_rect0_ref), &baseline, // input, output &pixels_per_deg_az, &pixels_per_deg_el, // input, output &azel_fov_deg, &azel0_deg, // input &mrcal_lensmodel0, PyArray_DATA(intrinsics0), PyArray_DATA(rt_cam0_ref), PyArray_DATA(rt_cam1_ref), rectification_model.type, az0_deg_autodetect, el0_deg_autodetect, az_fov_deg_autodetect, el_fov_deg_autodetect)) { BARF("mrcal_rectified_system() failed!"); goto done; } result = Py_BuildValue("(ddiiOOddddd)", pixels_per_deg_az, pixels_per_deg_el, imagersize_rectified[0], imagersize_rectified[1], fxycxy_rectified, rt_rect0_ref, baseline, azel_fov_deg.x, azel_fov_deg.y, azel0_deg.x, azel0_deg.y); done: LENSMODEL_ONE_ARGUMENTS(FREE_PYARRAY, 0); RECTIFIED_SYSTEM_ARGUMENTS(FREE_PYARRAY); Py_XDECREF(fxycxy_rectified); Py_XDECREF(rt_rect0_ref); return result; } // LENSMODEL_ONE_ARGUMENTS followed by these #define RECTIFICATION_MAPS_ARGUMENTS(_) \ _(r_cam0_ref, PyArrayObject*, NULL, "O&", PyArray_Converter COMMA, r_cam0_ref, NPY_DOUBLE, {3} ) \ _(r_cam1_ref, PyArrayObject*, NULL, "O&", PyArray_Converter COMMA, r_cam1_ref, NPY_DOUBLE, {3} ) \ _(r_rect0_ref, PyArrayObject*, NULL, "O&", PyArray_Converter COMMA, r_rect0_ref, NPY_DOUBLE, {3} ) \ _(rectification_maps, PyArrayObject*, NULL, "O&", PyArray_Converter COMMA, rectification_maps, NPY_FLOAT, {2 COMMA -1 COMMA -1 COMMA 2} ) static bool rectification_maps_validate_args(RECTIFICATION_MAPS_ARGUMENTS(ARG_LIST_DEFINE) void* dummy __attribute__((unused))) { RECTIFICATION_MAPS_ARGUMENTS(CHECK_LAYOUT); return true; done: return false; } static PyObject* _rectification_maps(PyObject* NPY_UNUSED(self), PyObject* args, PyObject* kwargs) { PyObject* result = NULL; unsigned int imagersize_rectified[2]; LENSMODEL_ONE_ARGUMENTS(ARG_DEFINE, 0); LENSMODEL_ONE_ARGUMENTS(ARG_DEFINE, 1); LENSMODEL_ONE_ARGUMENTS(ARG_DEFINE, _rectified); RECTIFICATION_MAPS_ARGUMENTS(ARG_DEFINE); // input mrcal_lensmodel_t mrcal_lensmodel0; mrcal_lensmodel_t mrcal_lensmodel1; mrcal_lensmodel_t mrcal_lensmodel_rectified; char* keywords[] = { LENSMODEL_ONE_ARGUMENTS(NAMELIST, 0) LENSMODEL_ONE_ARGUMENTS(NAMELIST, 1) LENSMODEL_ONE_ARGUMENTS(NAMELIST, _rectified) RECTIFICATION_MAPS_ARGUMENTS(NAMELIST) NULL}; // This function is internal, so EVERYTHING is required if(!PyArg_ParseTupleAndKeywords( args, kwargs, LENSMODEL_ONE_ARGUMENTS(PARSECODE, 0) LENSMODEL_ONE_ARGUMENTS(PARSECODE, 1) LENSMODEL_ONE_ARGUMENTS(PARSECODE, _rectified) RECTIFICATION_MAPS_ARGUMENTS(PARSECODE) ":mrcal.rectification_maps", keywords, LENSMODEL_ONE_ARGUMENTS(PARSEARG, 0) LENSMODEL_ONE_ARGUMENTS(PARSEARG, 1) LENSMODEL_ONE_ARGUMENTS(PARSEARG, _rectified) RECTIFICATION_MAPS_ARGUMENTS(PARSEARG) NULL )) goto done; if( !lensmodel_one_validate_args(&mrcal_lensmodel0, LENSMODEL_ONE_ARGUMENTS(ARG_LIST_CALL, 0) true /* DO check the layout */ )) goto done; if( !lensmodel_one_validate_args(&mrcal_lensmodel1, LENSMODEL_ONE_ARGUMENTS(ARG_LIST_CALL, 1) true /* DO check the layout */ )) goto done; if( !lensmodel_one_validate_args(&mrcal_lensmodel_rectified, LENSMODEL_ONE_ARGUMENTS(ARG_LIST_CALL, _rectified) true /* DO check the layout */ )) goto done; if(!rectification_maps_validate_args(RECTIFICATION_MAPS_ARGUMENTS(ARG_LIST_CALL) NULL)) goto done; // rectification_maps has shape (Ncameras=2, Nel, Naz, Nxy=2) imagersize_rectified[0] = PyArray_DIMS(rectification_maps)[2]; imagersize_rectified[1] = PyArray_DIMS(rectification_maps)[1]; if(!mrcal_rectification_maps( // output PyArray_DATA(rectification_maps), // input &mrcal_lensmodel0, PyArray_DATA(intrinsics0), PyArray_DATA(r_cam0_ref), &mrcal_lensmodel1, PyArray_DATA(intrinsics1), PyArray_DATA(r_cam1_ref), mrcal_lensmodel_rectified.type, PyArray_DATA(intrinsics_rectified), imagersize_rectified, PyArray_DATA(r_rect0_ref))) { BARF("mrcal_rectification_maps() failed!"); goto done; } Py_INCREF(Py_None); result = Py_None; done: LENSMODEL_ONE_ARGUMENTS(FREE_PYARRAY, 0); LENSMODEL_ONE_ARGUMENTS(FREE_PYARRAY, 1); RECTIFICATION_MAPS_ARGUMENTS(FREE_PYARRAY); return result; } static const char state_index_intrinsics_docstring[] = #include "state_index_intrinsics.docstring.h" ; static const char state_index_extrinsics_docstring[] = #include "state_index_extrinsics.docstring.h" ; static const char state_index_frames_docstring[] = #include "state_index_frames.docstring.h" ; static const char state_index_points_docstring[] = #include "state_index_points.docstring.h" ; static const char state_index_calobject_warp_docstring[] = #include "state_index_calobject_warp.docstring.h" ; static const char num_states_intrinsics_docstring[] = #include "num_states_intrinsics.docstring.h" ; static const char num_states_extrinsics_docstring[] = #include "num_states_extrinsics.docstring.h" ; static const char num_states_frames_docstring[] = #include "num_states_frames.docstring.h" ; static const char num_states_points_docstring[] = #include "num_states_points.docstring.h" ; static const char num_states_calobject_warp_docstring[] = #include "num_states_calobject_warp.docstring.h" ; static const char pack_state_docstring[] = #include "pack_state.docstring.h" ; static const char unpack_state_docstring[] = #include "unpack_state.docstring.h" ; static const char measurement_index_boards_docstring[] = #include "measurement_index_boards.docstring.h" ; static const char measurement_index_points_docstring[] = #include "measurement_index_points.docstring.h" ; static const char measurement_index_regularization_docstring[] = #include "measurement_index_regularization.docstring.h" ; static const char num_measurements_boards_docstring[] = #include "num_measurements_boards.docstring.h" ; static const char num_measurements_points_docstring[] = #include "num_measurements_points.docstring.h" ; static const char num_measurements_regularization_docstring[] = #include "num_measurements_regularization.docstring.h" ; static const char num_measurements_docstring[] = #include "num_measurements.docstring.h" ; static const char corresponding_icam_extrinsics_docstring[] = #include "corresponding_icam_extrinsics.docstring.h" ; static const char num_states_docstring[] = #include "num_states.docstring.h" ; static const char num_intrinsics_optimization_params_docstring[] = #include "num_intrinsics_optimization_params.docstring.h" ; static const char optimize_docstring[] = #include "optimize.docstring.h" ; static const char optimizer_callback_docstring[] = #include "optimizer_callback.docstring.h" ; static const char lensmodel_metadata_and_config_docstring[] = #include "lensmodel_metadata_and_config.docstring.h" ; static const char lensmodel_num_params_docstring[] = #include "lensmodel_num_params.docstring.h" ; static const char supported_lensmodels_docstring[] = #include "supported_lensmodels.docstring.h" ; static const char knots_for_splined_models_docstring[] = #include "knots_for_splined_models.docstring.h" ; static const char load_image_docstring[] = #include "load_image.docstring.h" ; static const char save_image_docstring[] = #include "save_image.docstring.h" ; static const char _rectified_resolution_docstring[] = #include "_rectified_resolution.docstring.h" ; static const char _rectified_system_docstring[] = #include "_rectified_system.docstring.h" ; static const char _rectification_maps_docstring[] = #include "_rectification_maps.docstring.h" ; static PyMethodDef methods[] = { PYMETHODDEF_ENTRY(,optimize, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(,optimizer_callback, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, state_index_intrinsics, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, state_index_extrinsics, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, state_index_frames, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, state_index_points, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, state_index_calobject_warp, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, num_states_intrinsics, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, num_states_extrinsics, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, num_states_frames, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, num_states_points, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, num_states_calobject_warp, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, num_states, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, num_intrinsics_optimization_params,METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, pack_state, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, unpack_state, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, measurement_index_boards, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, measurement_index_points, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, measurement_index_regularization,METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, num_measurements_boards, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, num_measurements_points, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, num_measurements_regularization, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, num_measurements, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, corresponding_icam_extrinsics, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(,lensmodel_metadata_and_config,METH_VARARGS), PYMETHODDEF_ENTRY(,lensmodel_num_params, METH_VARARGS), PYMETHODDEF_ENTRY(,supported_lensmodels, METH_NOARGS), PYMETHODDEF_ENTRY(,knots_for_splined_models, METH_VARARGS), PYMETHODDEF_ENTRY(, load_image, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(, save_image, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(,_rectified_resolution, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(,_rectified_system, METH_VARARGS | METH_KEYWORDS), PYMETHODDEF_ENTRY(,_rectification_maps, METH_VARARGS | METH_KEYWORDS), {} }; static void _init_mrcal_common(PyObject* module) { Py_INCREF(&CHOLMOD_factorization_type); PyModule_AddObject(module, "CHOLMOD_factorization", (PyObject *)&CHOLMOD_factorization_type); } #define MODULE_DOCSTRING \ "Low-level routines for core mrcal operations\n" \ "\n" \ "This is the written-in-C Python extension module that underlies the routines in\n" \ "mrcal.h. Most of the functions in this module (those prefixed with \"_\") are\n" \ "not meant to be called directly, but have Python wrappers that should be used\n" \ "instead.\n" \ "\n" \ "All functions are exported into the mrcal module. So you can call these via\n" \ "mrcal._mrcal.fff() or mrcal.fff(). The latter is preferred.\n" static struct PyModuleDef module_def = { PyModuleDef_HEAD_INIT, "_mrcal", MODULE_DOCSTRING, -1, methods }; PyMODINIT_FUNC PyInit__mrcal(void) { if (PyType_Ready(&CHOLMOD_factorization_type) < 0) return NULL; PyObject* module = PyModule_Create(&module_def); _init_mrcal_common(module); import_array(); return module; } mrcal-2.4.1/mrcal-reproject-image000077500000000000000000000615501456301662300167300ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Remaps a captured image into another camera model SYNOPSIS ### To "undistort" images to reproject to a pinhole projection $ mrcal-reproject-image --to-pinhole camera0.cameramodel image*.jpg Wrote image0-pinhole.jpg Wrote image1-pinhole.jpg ... ### To reproject images from one lens model to another $ mrcal-reproject-image camera0.cameramodel camera1.cameramodel image*.jpg Wrote image0-reprojected.jpg Wrote image1-reprojected.jpg Wrote image2-reprojected.jpg ... ### To reproject two sets of images to a common pihole projection $ mrcal-reproject-image --to-pinhole camera0.cameramodel camera1.cameramodel 'image*-cam0.jpg' 'image*-cam1.jpg' Wrote image0-reprojected.jpg Wrote image1-reprojected.jpg Wrote image2-reprojected.jpg ... ### To "manually" stereo-rectify a pair of images $ mrcal-stereo \ --az-fov-deg 80 \ --el-fov-deg 50 \ --outdir /tmp \ left.cameramodel \ right.cameramodel Wrote '/tmp/rectified0.cameramodel' Wrote '/tmp/rectified1.cameramodel' $ mrcal-reproject-image \ --outdir /tmp \ /tmp/left.cameramodel \ /tmp/rectified0.cameramodel \ left.jpg Wrote /tmp/left-reprojected.jpg $ mrcal-reproject-image \ --outdir /tmp \ /tmp/right.cameramodel \ /tmp/rectified1.cameramodel \ right.jpg Wrote /tmp/right-reprojected.jpg $ mrcal-stereo \ --already-rectified \ --outdir /tmp \ /tmp/rectified[01].cameramodel \ /tmp/left-reprojected.jpg \ /tmp/right-reprojected.jpg # This is the same as using mrcal-stereo to do all the work: $ mrcal-stereo \ --az-fov-deg 80 \ --el-fov-deg 50 \ --outdir /tmp \ left.cameramodel \ right.cameramodel \ left.jpg \ right.jpg This tool takes image(s) of a scene captured by one camera model, and produces image(s) of the same scene, as it would appear if captured by a different model, taking into account both the different lens parameters and geometries. This is similar to mrcal-reproject-points, but acts on a full image, rather than a discrete set of points. There are several modes of operation, depending on how many camera models are given, and whether --to-pinhole is given, and whether --plane-n,--plane-d are given. To "undistort" (remap to a pinhole projection) a set of images captured using a particular camera model, invoke this tool like this: mrcal-reproject-image --to-pinhole model0.cameramodel image*.jpg Each of the given images will be reprojected, and written to disk as "image....-reprojected.jpg". The pinhole model used for the reprojection will be written to standard output. To remap images of a scene captured by model0 to images of the same scene captured by model1, do this: mrcal-reproject-image model0.cameramodel model1.cameramodel image*.jpg Each of the given images will be reprojected, and written to disk as "image....-reprojected.jpg". Nothing will be written to standard output. By default, full relative extrinsics between the two models are used in the reprojection. The unprojection distance (given with --distance) is infinity by default, so only the relative rotation is used by default. To ignore the extrinsics entirely, pass --intrinsics-only. A common use case is to validate the relative intrinsics and extrinsics in two models. If you have a pair of models and a pair of observed images, you can compute the reprojection, and compare the reprojection-to-model1 to images that were actually captured by model1. If the intrinsics and extrinsics were correct, then the two images would line up exactly for relevant objects (far-away observations with the default --distance, ground plane with --plane-n, etc). Computing this reprojection map is often very slow. But if the use case is comparing two sets of captured images, the next, much faster invocation method can be used. To remap images of a scene captured by model0 and images of the same scene captured by model1 to a common pinhole projection, do this: mrcal-reproject-image --to-pinhole model0.cameramodel model1.cameramodel 'image*-cam0.jpg' 'image*-cam1.jpg' A pinhole model is constructed that has the same extrinsics as model1, and both sets of images are reprojected to this model. This is similar to the previous mode, but since we're projecting to a pinhole model, this computes much faster. The generated pinhole model is written to standard output. Finally instead of reprojecting to match up images of objects at infinity, it is possible to reproject to match up images of arbitrary planes. This can be done by a command like this: mrcal-reproject-image --to-pinhole --plane-n 1.1 2.2 3.3 --plane-d 4.4 model0.cameramodel model1.cameramodel 'image*-cam0.jpg' 'image*-cam1.jpg' If the models were already pinhole-projected, this does the same thing as mrcal-reproject-image --plane-n 1.1 2.2 3.3 --plane-d 4.4 model0.cameramodel model1.cameramodel 'image*-cam0.jpg' This maps observations of a given plane in camera0 coordinates to where this plane would be observed in camera1 coordinates. This requires both models to be passed-in. And ALL the intrinsics, extrinsics and the plane representation are used. If all of these are correct, the observations of this plane would line up exactly in the remapped-camera0 image and the camera1 image. The plane is represented in camera0 coordinates by a normal vector given by --plane-n, and the distance to the normal given by plane-d. The plane is all points p such that inner(p,planen) = planed. planen does not need to be normalized. This mode does not require --to-pinhole, but it makes the computations run much faster, as before. If --to-pinhole, then we generate a pinhole model, that is written to standard output. By default, the focal length of this pinhole model is the same as that of the input model. The "zoom" level of this pinhole model can be adjusted by passing --scale-focal SCALE, or more precisely by passing --fit. --fit takes an argument that is one of - "corners": make sure all of the corners of the original image remain in-bounds of the pinhole projection - "centers-horizontal": make sure the extreme left-center and right-center points in the original image remain in-bounds of the pinhole projection - "centers-vertical": make sure the extreme top-center and bottom-center points in the original image remain in-bounds of the pinhole projection - A list of pixel coordinates x0,y0,x1,y1,x2,y2,.... The focal-length will be chosen to fit all of the given points By default, the resolution of the generated pinhole model is the same as the resolution of the input model. This can be adjusted by passing --scale-image. For instance, passing "--scale-image 0.5" will generate a pinhole model and images that are half the size of the input images, in both the width and height. The output image(s) are written into the same directory as the input image(s), with annotations in the filename. This tool will refuse to overwrite any existing files unless --force is given. It is often desired to apply transformations to lots of images in bulk. To make this go faster, this tool supports the -j JOBS option. This works just like in Make: the work will be parallelized among JOBS simultaneous processes. Unlike make, the JOBS value must be specified. ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--to-pinhole', action="store_true", help='''If given, we reproject the images to a pinhole model that's generated off the MODEL-FROM and --fit, --scale-focal, --scale-image. The generated pinhole model is written to the standard output''') parser.add_argument('--intrinsics-only', action='store_true', help='''If two camera models are given, then by default the full relative transformation is used in the reprojection. If we want to use the intrinsics ONLY, pass this option''') parser.add_argument('--distance', type=float, help='''The fundamental operation of this tool is to unproject points from one camera, and to reproject them into the other. The distance used for the unprojection is set by this argument. If omitted, infinity is used; this is equivalent to only using the rotation component of the relative transformation between the cameras. This option only makes sense without --intrinsics-only and without --plane-n/--plane-d''') parser.add_argument('--fit', type=str, required=False, help='''If we generate a target pinhole model (if --to-pinhole is given) then we can choose the focal length of the target model. This is a "zoom" operation. By default just use whatever value model-from has. Or we scale it by the value given in --scale-focal. Or we use --fit to scale the focal length intelligently. The --fit argument could be one of ("corners", "centers-horizontal", "centers-vertical"), or the argument could be given as a list of points x0,y0,x1,y1,x2,y2,.... The focal length scale would then be chosen to zoom in as far as possible, while fitting all of these points''') parser.add_argument('--scale-focal', type=float, help='''If we generate a target pinhole model (if --to-pinhole is given) then we can choose the focal length of the target model. This is a "zoom" operation. By default just use whatever value model-from has. Or we scale it by the value given in --scale-focal. Or we use --fit to scale the focal length intelligently.''') parser.add_argument('--scale-image', type=float, help='''If we generate a target pinhole model (if --to-pinhole is given) then we can choose the dimensions of the output image. By default we use the dimensions of model-from. If --scale-image is given, we use this value to scale the imager dimensions of model-from. This parameter changes the RESOLUTION of the output, unlike --scale-focal, which ZOOMS the output''') parser.add_argument('--plane-n', type=float, nargs=3, help='''We're reprojecting a plane. The normal vector to this plane is given here, in from-camera coordinates. The normal does not need to be normalized; any scaling is compensated in planed. The plane is all points p such that inner(p,planen) = planed''') parser.add_argument('--plane-d', type=float, help='''We're reprojecting a plane. The distance-along-the-normal to the plane, in from-camera coordinates is given here. The plane is all points p such that inner(p,planen) = planed''') parser.add_argument('--outdir', required=False, type=lambda d: d if os.path.isdir(d) else \ parser.error("--outdir requires an existing directory as the arg, but got '{}'".format(d)), help='''Directory to write the output images into. If omitted, we write the output images to the same directory as the input images''') parser.add_argument('--valid-intrinsics-region', action='store_true', help='''If given, we annotate the images with the FROM model's valid-intrinsics region''') parser.add_argument('--mask-valid-intrinsics-region', action='store_true', help='''If given, we draw everything outside the FROM model's valid-intrinsics region as black. So the unreliable regions aren't even drawn''') parser.add_argument('--force', '-f', action='store_true', default=False, help='''By default existing files are not overwritten. Pass --force to overwrite them without complaint''') parser.add_argument('--jobs', '-j', type=int, required=False, default=1, help='''parallelize the processing JOBS-ways. This is like Make, except you're required to explicitly specify a job count.''') parser.add_argument('model-from', type=str, help='''Camera model for the FROM image(s). If "-' is given, we read standard input''') parser.add_argument('model-to-and-image-globs', type=str, nargs='+', help='''Optionally, the camera model for the TO image. Followed, by the from/to image globs. See the mrcal-reproject-image documentation for the details.''') args = parser.parse_args() # use _ instead of - in attribute names so that I can access them easier args.model_to_and_image_globs = getattr(args, 'model-to-and-image-globs') args.model_from = getattr(args, 'model-from') delattr(args, 'model-to-and-image-globs') delattr(args, 'model-from') return args args = parse_args() import mrcal # I have to manually process this because the first model-to-and-image-globs # element's identity is ambiguous in a way I can't communicate to argparse. # It can be model-to or it can be the first image glob def load_model_or_keep_filename(filename): try: m = mrcal.cameramodel(filename) except: m = filename return m mi = [load_model_or_keep_filename(f) for f in args.model_to_and_image_globs] args.model_to = [ m for m in mi if isinstance(m,mrcal.cameramodel) ] args.imageglobs = [ m for m in mi if not isinstance(m,mrcal.cameramodel) ] delattr(args, 'model_to_and_image_globs') if len(args.model_to) == 0: args.model_to = None elif len(args.model_to) == 1: args.model_to = args.model_to[0] else: print(f"At most one model-to can be given. Instead got {len(args.model_to)} of them. Giving up.", file=sys.stderr) sys.exit(1) if args.model_from == '-' and \ args.model_to == '-': print("At most one model can be given at '-' to read standard input. Giving up.", file=sys.stderr) sys.exit(1) if not args.to_pinhole: if args.fit is not None or \ args.scale_focal is not None or \ args.scale_image is not None: print("--fit, --scale-focal, --scale-image make sense ONLY with --to-pinhole", file = sys.stderr) sys.exit(1) else: if args.fit is not None and \ args.scale_focal is not None: print("--fit and --scale-focal are mutually exclusive", file=sys.stderr) sys.exit(1) if args.model_to is None and \ args.intrinsics_only: print("--intrinsics-only makes sense ONLY when both the FROM and TO camera models are given", file=sys.stderr) sys.exit(1) if args.scale_image is not None and args.scale_image <= 1e-6: print("--scale-image should be given a reasonable value > 0", file=sys.stderr) sys.exit(1) if (args.plane_n is None and args.plane_d is not None) or \ (args.plane_n is not None and args.plane_d is None): print("--plane-n and --plane-d should both be given or neither should be", file=sys.stderr) sys.exit(1) if args.plane_n is not None and \ args.intrinsics_only: print("We're looking at remapping a plane (--plane-d, --plane-n are given), so --intrinsics-only doesn't make sense", file=sys.stderr) sys.exit(1) if args.distance is not None and \ (args.plane_n is not None or args.intrinsics_only): print("--distance makes sense only without --plane-n/--plane-d and without --intrinsics-only", file=sys.stderr) sys.exit(1) import numpy as np import numpysane as nps if args.fit is not None: if re.match(r"^[0-9\.e-]+(,[0-9\.e-]+)*$", args.fit): xy = np.array([int(x) for x in args.fit.split(',')], dtype=float) Nxy = len(xy) if Nxy % 2 or Nxy < 4: print(f"If passing pixel coordinates to --fit, I need at least 2 x,y pairs. Instead got {Nxy} values", file=sys.stderr) sys.exit(1) args.fit = xy.reshape(Nxy//2, 2) elif re.match("^(corners|centers-horizontal|centers-vertical)$", args.fit): # this is valid. nothing to do pass else: print("--fit must be a comma-separated list of numbers or one of ('corners','centers-horizontal','centers-vertical')", file=sys.stderr) sys.exit(1) import glob import multiprocessing import signal import time model_from = mrcal.cameramodel(args.model_from) if not args.to_pinhole: if not args.model_to: print("Either --to-pinhole or the TO camera model MUST be given. Giving up", file=sys.stderr) sys.exit(1) if len(args.imageglobs) < 1: print("No --to-pinhole with both TO and FROM models given: must have at least one set of image globs. Giving up", file=sys.stderr) sys.exit(1) model_to = args.model_to else: if not args.model_to: if len(args.imageglobs) < 1: print("--to-pinhole with only the FROM models given: must have at least one set of image globs. Giving up", file=sys.stderr) sys.exit(1) model_to = mrcal.pinhole_model_for_reprojection(model_from, args.fit, scale_focal = args.scale_focal, scale_image = args.scale_image) print( "## generated on {} with {}".format(time.strftime("%Y-%m-%d %H:%M:%S"), ' '.join(mrcal.shellquote(s) for s in sys.argv)) ) print("# Generated pinhole model:") model_to.write(sys.stdout) else: if len(args.imageglobs) != 2: print("--to-pinhole with both the TO and FROM models given: must have EXACTLY two image globs. Giving up", file=sys.stderr) sys.exit(1) model_to = args.model_to model_target = mrcal.pinhole_model_for_reprojection(model_to, args.fit, scale_focal = args.scale_focal, scale_image = args.scale_image) print( "## generated on {} with {}".format(time.strftime("%Y-%m-%d %H:%M:%S"), ' '.join(mrcal.shellquote(s) for s in sys.argv)) ) print("# Generated pinhole model:") model_target.write(sys.stdout) if args.plane_n is not None: if args.model_to is None: print("Plane remapping requires BOTH camera models to be given", file=sys.stderr) sys.exit(1) args.plane_n = np.array(args.plane_n, dtype=float) # I do the same thing in mrcal-stereo. Please consolidate # # weird business to handle weird signal handling in multiprocessing. I want # things like the user hitting C-c to work properly. So I ignore SIGINT for the # children. And I want the parent's blocking wait for results to respond to # signals. Which means map_async() instead of map(), and wait(big number) # instead of wait() signal_handler_sigint = signal.signal(signal.SIGINT, signal.SIG_IGN) signal.signal(signal.SIGINT, signal_handler_sigint) # This stuff needs to be global for the multiprocessing pool to pick it up. It # really is quite terrible. All I REALLY want is some os.fork() calls... model_valid_intrinsics_region = None mapxy = None model_imagersize = None def _transform_this(inout): try: image = mrcal.load_image(inout[0]) except: print(f"Couldn't load '{inout[0]}'", file=sys.stderr) return if image.shape[0] != model_imagersize[1] or \ image.shape[1] != model_imagersize[0]: print(f"Couldn't process {inout[0]}: image dimensions don't match the input model dimensions. Image size: [{image.shape[1]} {image.shape[0]}]. model.imagersize(): {model_imagersize}", file=sys.stderr) return if model_valid_intrinsics_region is not None: mrcal.annotate_image__valid_intrinsics_region(image, model_valid_intrinsics_region) image_transformed = mrcal.transform_image(image, mapxy) mrcal.save_image(inout[1], image_transformed) print(f"Wrote {inout[1]}", file=sys.stderr) def process(model_from, model_to, image_globs, suffix, intrinsics_only, distance, plane_n, plane_d): def target_image_filename(filename_in, suffix): base,extension = os.path.splitext(filename_in) if len(extension) != 4: print(f"imagefile must end in .xxx where 'xxx' is some image extension. Instead got '{filename_in}'", file=sys.stderr) sys.exit(1) if args.outdir is not None: base = args.outdir + '/' + os.path.split(base)[1] filename_out = f"{base}-{suffix}{extension}" if not args.force and os.path.exists(filename_out): print(f"Target image '{filename_out}' already exists. Doing nothing, and giving up. Pass -f to overwrite", file=sys.stderr) sys.exit(1) return filename_out filenames_in = [f for g in image_globs for f in glob.glob(g)] if len(filenames_in) == 0: print(f"Globs '{image_globs}' matched no files!", file=sys.stderr) sys.exit(1) filenames_out = [target_image_filename(f, suffix) for f in filenames_in] filenames_inout = zip(filenames_in, filenames_out) global mapxy global model_valid_intrinsics_region global model_imagersize if args.valid_intrinsics_region: model_valid_intrinsics_region = model_from model_imagersize = model_from.imagersize() mapxy = mrcal.image_transformation_map(model_from, model_to, intrinsics_only = intrinsics_only, distance = distance, plane_n = plane_n, plane_d = plane_d, mask_valid_intrinsics_region_from = \ args.mask_valid_intrinsics_region,) if args.jobs > 1: # Normal parallelized path pool = multiprocessing.Pool(args.jobs) try: mapresult = pool.map_async(_transform_this, filenames_inout) # like wait(), but will barf if something goes wrong. I don't actually care # about the results mapresult.get(1000000) except: pool.terminate() pool.close() pool.join() else: # Serial path. Useful for debugging for f in filenames_inout: _transform_this(f) if args.to_pinhole and args.model_to: # I'm reprojecting each of my sets of images to a pinhole model (a DIFFERENT # model from TO and FROM) process(model_from, model_target, (args.imageglobs[0],), "pinhole-remapped", args.intrinsics_only, args.distance, args.plane_n, args.plane_d) process(model_to, model_target, (args.imageglobs[1],), "pinhole", args.intrinsics_only, args.distance, None, None) else: # Simple case. I have my two models, and I reproject all the images process(model_from, model_to, args.imageglobs, "reprojected", args.intrinsics_only, args.distance, args.plane_n, args.plane_d) mrcal-2.4.1/mrcal-reproject-points000077500000000000000000000065611456301662300171630ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Reprojects pixel observations from one model to another SYNOPSIS $ < points-in.vnl mrcal-reproject-points from.cameramodel to.cameramodel > points-out.vnl This tool takes a set of pixel observations of points captured by one camera model, and transforms them into observations of the same points captured by another model. This is similar to mrcal-reproject-image, but acts on discrete points, rather than on whole images. The two sets of intrinsics are always used. The translation component of the extrinsics is always ignored; the rotation is ignored as well if --intrinsics-only. This allows one to combine multiple image-processing techniques that expect different projections. For instance, planes projected using a pinhole projection have some nice properties, and we can use those after running this tool. The input data comes in on standard input, and the output data is written to standard output. Both are vnlog data: human-readable text with 2 columns: x and y pixel coords. Comments are allowed, and start with the '#' character. ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--intrinsics-only', action='store_true', help='''By default, the relative camera rotation is used in the transformation. If we want to use the intrinsics ONLY, pass --intrinsics-only. Note that relative translation is ALWAYS ignored''') parser.add_argument('model-from', type=str, help='''Camera model for the input points.''') parser.add_argument('model-to', type=str, help='''Camera model for the output points.''') return parser.parse_args() args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README import numpy as np import numpysane as nps import mrcal import time model_from = mrcal.cameramodel(getattr(args, 'model-from')) model_to = mrcal.cameramodel(getattr(args, 'model-to')) p = nps.atleast_dims(np.genfromtxt(sys.stdin), -2) v = mrcal.unproject(p, *model_from.intrinsics()) print( "## generated on {} with {}".format(time.strftime("%Y-%m-%d %H:%M:%S"), ' '.join(mrcal.shellquote(s) for s in sys.argv)) ) if not args.intrinsics_only: Rt_to_from = \ mrcal.compose_Rt( model_to. extrinsics_Rt_fromref(), model_from.extrinsics_Rt_toref () ) if nps.norm2(Rt_to_from[3,:]) > 1e-6: print(f"## WARNING: {sys.argv[0]} ignores relative translations, which were non-zero here. t_to_from = {Rt_to_from[3,:]}") v = nps.matmult(Rt_to_from[:3,:], nps.dummy(v, -1))[..., 0] p = mrcal.project (v, *model_to.intrinsics()) np.savetxt(sys.stdout, p, fmt='%f', header='x y') mrcal-2.4.1/mrcal-show-distortion-off-pinhole000077500000000000000000000146401456301662300212310ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Visualize the behavior or a lens model SYNOPSIS $ mrcal-show-distortion-off-pinhole --vectorfield left.cameramodel ... a plot pops up showing the vector field of the difference from a pinhole projection This tool is used to examine how a lens model behaves. Depending on the model, the vectors could be very large or very small, and we can scale them by passing '--vectorscale s'. By default we sample in a 60x40 grid, but this spacing can be controlled by passing '--gridn w h'. By default we render a heat map of the lens effects. We can also see the vectorfield by passing in --vectorfield. Or we can see the radial distortion curve by passing --radial ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--gridn', type=int, default = (60,40), nargs = 2, help='''How densely we should sample the imager. By default we report a 60x40 grid''') parser.add_argument('--vectorscale', type=float, default = 1.0, help='''Scale the vectors by this factor. Default is 1.0 (report the truth), but this is often too small to see''') parser.add_argument('--radial', action='store_true', help='''Show the radial distortion scale factor instead of a colormap/vectorfield''') parser.add_argument('--vectorfield', action = 'store_true', default = False, help='''Plot the diff as a vector field instead of as a heat map. The vector field contains more information (magnitude AND direction), but is less clear at a glance''') parser.add_argument('--show-fisheye-projections', action='store_true', help='''If given, the radial plots include the behavior of common fisheye projections, in addition to the behavior of THIS lens''') parser.add_argument('--cbmax', type=float, default=10, help='''Maximum range of the colorbar''') parser.add_argument('--title', type=str, default = None, help='''Title string for the plot. Overrides the default title. Exclusive with --extratitle''') parser.add_argument('--extratitle', type=str, default = None, help='''Additional string for the plot to append to the default title. Exclusive with --title''') parser.add_argument('--hardcopy', type=str, help='''Write the output to disk, instead of making an interactive plot''') parser.add_argument('--terminal', type=str, help=r'''gnuplotlib terminal. The default is good almost always, so most people don't need this option''') parser.add_argument('--set', type=str, action='append', help='''Extra 'set' directives to pass to gnuplotlib. May be given multiple times''') parser.add_argument('--unset', type=str, action='append', help='''Extra 'unset' directives to pass to gnuplotlib. May be given multiple times''') parser.add_argument('model', type=str, help='''Input camera model. If "-' is given, we read standard input''') return parser.parse_args() args = parse_args() if args.title is not None and \ args.extratitle is not None: print("--title and --extratitle are exclusive", file=sys.stderr) sys.exit(1) # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README import numpy as np import numpysane as nps import mrcal try: model = mrcal.cameramodel(args.model) except Exception as e: print(f"Couldn't load camera model '{args.model}': {e}", file=sys.stderr) sys.exit(1) if args.radial and args.vectorfield: sys.stderr.write("Usage error: at most one of --radial and --vectorfield can be given\n") sys.exit(1) plotkwargs = {} if args.set is not None: plotkwargs['set'] = args.set if args.unset is not None: plotkwargs['unset'] = args.unset if args.title is not None: plotkwargs['title'] = args.title if args.extratitle is not None: plotkwargs['extratitle'] = args.extratitle if args.radial: try: plot = \ mrcal.show_distortion_off_pinhole_radial(model, show_fisheye_projections = args.show_fisheye_projections, hardcopy = args.hardcopy, terminal = args.terminal, **plotkwargs) except Exception as e: print(f"Error: {e}", file=sys.stderr) sys.exit(1) else: plot = mrcal.show_distortion_off_pinhole(model, vectorfield = args.vectorfield, vectorscale = args.vectorscale, cbmax = args.cbmax, gridn_width = args.gridn[0], gridn_height = args.gridn[1], hardcopy = args.hardcopy, terminal = args.terminal, **plotkwargs) if args.hardcopy is None: plot.wait() mrcal-2.4.1/mrcal-show-geometry000077500000000000000000000167201456301662300164630ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Displays the calibration-time geometry: the cameras and the observed objects SYNOPSIS $ mrcal-show-geometry *.cameramodel ... a plot pops up showing the camera arrangement This tool visualizes the relative geometry between several cameras and the calibration objects they observed when computing the calibration. ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--axis-scale', type=float, help='''Scale for the camera axes. By default a reasonable default is chosen (see mrcal.show_geometry() for the logic)''') parser.add_argument('--title', type=str, default = None, help='''Title string for the plot''') parser.add_argument('--hardcopy', type=str, help='''Write the output to disk, instead of making an interactive plot. The output filename is given in the option''') parser.add_argument('--terminal', type=str, help=r'''The gnuplotlib terminal. The default is almost always right, so most people don't need this option''') parser.add_argument('--show-calobjects', action='store_true', help='''If given, draw the calibration object observations from the FIRST given camera model that contains the optimization_inputs. Unlike --show-calobjects-thiscamera, this option displays the calibration objects observed by ALL cameras at calibration time. Exclusive with --show-calobjects-thiscamera''') parser.add_argument('--show-calobjects-thiscamera', action='store_true', help='''If given, draw the calibration object observations from the FIRST given camera model that contains the optimization_inputs. Unlike --show-calobjects, this option displays the calibration objects observed ONLY by the FIRST camera at calibration time. Exclusive with --show-calobjects''') parser.add_argument('--show-points', action='store_true', help='''If given, draw the point observations from the FIRST given camera model that contains the optimization_inputs. Unlike --show-points-thiscamera, this option displays the points observed by ALL cameras at calibration time. Exclusive with --show-points-thiscamera''') parser.add_argument('--show-points-thiscamera', action='store_true', help='''If given, draw the point observations from the FIRST given camera model that contains the optimization_inputs. Unlike --show-points, this option displays the calibration objects observed ONLY by the FIRST camera at calibration time. Exclusive with --show-points''') parser.add_argument('--transforms', type=str, help='''Optional transforms.txt. This is a legacy file representing an extra transformation for each camera pair. If you need this, you know what it is''') parser.add_argument('--set', type=str, action='append', help='''Extra 'set' directives to pass to gnuplotlib. May be given multiple times''') parser.add_argument('--unset', type=str, action='append', help='''Extra 'unset' directives to pass to gnuplotlib. May be given multiple times''') parser.add_argument('models', type = str, nargs= '+', help='''Camera models to visualize. Any N cameras can be given''') return parser.parse_args() args = parse_args() if args.show_calobjects and args.show_calobjects_thiscamera: print("--show-calobjects and --show-calobjects-thiscamera are exclusive", file=sys.stderr) sys.exit(1) if args.show_points and args.show_points_thiscamera: print("--show-points and --show-points-thiscamera are exclusive", file=sys.stderr) sys.exit(1) # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README import numpy as np import numpysane as nps import gnuplotlib as gp import mrcal def openmodel(f): try: return mrcal.cameramodel(f) except Exception as e: print(f"Couldn't load camera model '{f}': {e}", file=sys.stderr) sys.exit(1) models = [openmodel(modelfilename) for modelfilename in args.models] cameras_Rt_plot_ref = None if args.transforms is not None: import mrcal.cahvor transforms = mrcal.cahvor.read_transforms(args.transforms) def get_pair(icam): f = args.models[icam] m = re.search("camera([0-9]+)", f) return int(m.group(1)) def Rt_plot_ref(icam): try: pair = get_pair(icam) Rt_ins_ref = transforms['ins_from_camera'][pair] return Rt_ins_ref except: return None cameras_Rt_plot_ref = [ Rt_plot_ref(icam) for icam in range(len(models))] plotkwargs = {} if args.title is not None: plotkwargs['title' ] = args.title if args.hardcopy is not None: plotkwargs['hardcopy'] = args.hardcopy if args.terminal is not None: plotkwargs['terminal'] = args.terminal if args.set is not None: gp.add_plot_option( plotkwargs, 'set', args.set) if args.unset is not None: gp.add_plot_option( plotkwargs, 'unset', args.unset) if args.show_calobjects: show_calobjects = 'all' elif args.show_calobjects_thiscamera: show_calobjects = 'thiscamera' else: show_calobjects = False if args.show_points: show_points = 'all' elif args.show_points_thiscamera: show_points = 'thiscamera' else: show_points = False plot = mrcal.show_geometry(models, cameranames = args.models, cameras_Rt_plot_ref = cameras_Rt_plot_ref, show_calobjects = show_calobjects, show_points = show_points, axis_scale = args.axis_scale, **plotkwargs) if args.hardcopy is None: plot.wait() mrcal-2.4.1/mrcal-show-projection-diff000077500000000000000000000541061456301662300177120ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Visualize the difference in projection between N models SYNOPSIS $ mrcal-show-projection-diff before.cameramodel after.cameramodel ... a plot pops up showing how these two models differ in their projections The operation of this tool is documented at http://mrcal.secretsauce.net/differencing.html This tool visualizes the results of mrcal.projection_diff() It is often useful to compare the projection behavior of two camera models. For instance, one may want to validate a calibration by comparing the results of two different chessboard dances. Or one may want to evaluate the stability of the intrinsics in response to mechanical or thermal stresses. This tool makes these comparisons, and produces a visualization of the results. In the most common case we're given exactly 2 models to compare. We then display the projection difference as either a vector field or a heat map. If we're given more than 2 models, then a vector field isn't possible and we instead display as a heatmap the standard deviation of the differences between models 1..N and model0. The top-level operation of this tool: - Grid the imager - Unproject each point in the grid using one camera model - Apply a transformation to map this point from one camera's coord system to the other. How we obtain this transformation is described below - Project the transformed points to the other camera - Look at the resulting pixel difference in the reprojection Several arguments control how we obtain the transformation. Top-level logic: if --intrinsics-only: Rt10 = identity_Rt() else: if --radius 0: Rt10 = relative_extrinsics(models) else: Rt10 = implied_Rt10__from_unprojections() The details of how the comparison is computed, and the meaning of the arguments controlling this, are in the docstring of mrcal.projection_diff(). ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--gridn', type=int, default = (60,40), nargs = 2, help='''How densely we should sample the imager. By default we use a 60x40 grid''') parser.add_argument('--distance', type=str, help='''Has an effect only without --intrinsics-only. The projection difference varies depending on the range to the observed world points, with the queried range set in this argument. If omitted we look out to infinity. We can also fit multiple distances at the same time by passing them here in a comma-separated, whitespace-less list. If multiple distances are given, we fit the implied-by-the-intrinsics transformation using ALL the distances, but we display the difference for the FIRST distance given.''') parser.add_argument('--intrinsics-only', action='store_true', help='''If given, we evaluate the intrinsics of each lens in isolation by assuming that the coordinate systems of each camera line up exactly''') parser.add_argument('--where', type=float, nargs=2, help='''Center of the region of interest for this diff. Used only without --intrinsics-only and without "--radius 0". It is usually impossible for the models to match everywhere, but focusing on a particular area can work better. The implied transformation will be fit to match as large as possible an area centered on this argument. If omitted, we will focus on the center of the imager''') parser.add_argument('--radius', type=float, default=-1., help='''Radius of the region of interest. If ==0, we do NOT fit an implied transformation at all, but use the transformations in the models. If omitted or <0, we use a "reasonable" value: the whole imager if we're using uncertainties, or min(width,height)/6 if --no-uncertainties. To fit with data across the whole imager in either case, pass in a very large radius''') parser.add_argument('--same-dance', action='store_true', default=False, help=argparse.SUPPRESS) '''--same-dance IS NOT READY FOR PUBLIC CONSUMPTION. It is purposely undocumented. If given, I assume that the given models all came from the same calibration dance, and I can thus compute implied_Rt10 geometrically, instead of fitting projections. Valid only if we're given exactly two models. Exclusive with --where and --radius (those control the fit that we skip with --same-dance If putting this back, this was a part of the docstring for this tool: - If we know that our models came from different interpretations of the same board dance (using different lens models or optimization parameters, for instance), we can use the geometry of the cameras and frames to compute implied_Rt10. Indicate this case by passing --same-dance ''' parser.add_argument('--observations', action='store_true', default=False, help='''If given, I show where the chessboard corners were observed at calibration time. These should correspond to the low-diff regions.''') parser.add_argument('--valid-intrinsics-region', action='store_true', default=False, help='''If given, I overlay the valid-intrinsics regions onto the plot''') parser.add_argument('--cbmax', type=float, default=4, help='''Maximum range of the colorbar''') parser.add_argument('--title', type=str, default = None, help='''Title string for the plot. Overrides the default title. Exclusive with --extratitle''') parser.add_argument('--extratitle', type=str, default = None, help='''Additional string for the plot to append to the default title. Exclusive with --title''') parser.add_argument('--vectorfield', action = 'store_true', default = False, help='''Plot the diff as a vector field instead of as a heat map. The vector field contains more information (magnitude AND direction), but is less clear at a glance''') parser.add_argument('--vectorscale', type = float, default = 1.0, help='''If plotting a vectorfield, scale all the vectors by this factor. Useful to improve legibility if the vectors are too small to see''') parser.add_argument('--directions', action = 'store_true', help='''If given, the plots are color-coded by the direction of the error, instead of the magnitude''') parser.add_argument('--no-uncertainties', action = 'store_true', help='''Used only without --intrinsics-only and without "--radius 0". By default we use the uncertainties in the model to weigh the fit. This will focus the fit on the confident region in the models without --where or --radius. The computation will run faster with --no-uncertainties, but the default --where and --radius may need to be adjusted''') parser.add_argument('--hardcopy', type=str, help='''Write the output to disk, instead of making an interactive plot''') parser.add_argument('--terminal', type=str, help=r'''gnuplotlib terminal. The default is good almost always, so most people don't need this option''') parser.add_argument('--set', type=str, action='append', help='''Extra 'set' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('--unset', type=str, action='append', help='''Extra 'unset' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('models', type=str, nargs='+', help='''Camera models to diff''') args = parser.parse_args() if len(args.models) < 2: print(f"I need at least two models to diff. Instead got '{args.models}'", file=sys.stderr) sys.exit(1) if args.title is not None and \ args.extratitle is not None: print("--title and --extratitle are exclusive", file=sys.stderr) sys.exit(1) return args args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README if args.vectorscale != 1.0 and not args.vectorfield: print("Error: --vectorscale only makes sense with --vectorfield", file = sys.stderr) sys.exit(1) if args.distance is None: distance = None else: try: distance = [float(d) for d in args.distance.split(',')] except: print("Error: distances must be given a comma-separated list of floats in --distance", file = sys.stderr) sys.exit(1) if len(args.models) > 2: if args.vectorfield: print("Error: --vectorfield works only with exactly 2 models", file = sys.stderr) sys.exit(1) if args.directions: print("Error: --directions works only with exactly 2 models", file = sys.stderr) sys.exit(1) if args.same_dance: print("Error: --same-dance works only with exactly 2 models", file = sys.stderr) sys.exit(1) if args.same_dance and \ (args.where is not None or args.radius >= 0): print("Error: --same-dance is exclusive with --where and --radius", file = sys.stderr) sys.exit(1) import mrcal import numpy as np import numpysane as nps plotkwargs_extra = {} if args.set is not None: plotkwargs_extra['set'] = args.set if args.unset is not None: plotkwargs_extra['unset'] = args.unset if args.title is not None: plotkwargs_extra['title'] = args.title if args.extratitle is not None: plotkwargs_extra['extratitle'] = args.extratitle def openmodel(f): try: return mrcal.cameramodel(f) except Exception as e: print(f"Couldn't load camera model '{f}': {e}", file=sys.stderr) sys.exit(1) models = [openmodel(modelfilename) for modelfilename in args.models] if args.same_dance: # EXPERIMENTAL, UNDOCUMENTED STUFF if 1: # default method: fit the corner observations in the coord system of the # camera. Each observation contributes a point to the fit # I need to make sure to pick the same inlier set when choosing the frame # observations. I pick the intersection of the two i_f_ci_ce = [model.optimization_inputs()['indices_frame_camintrinsics_camextrinsics'] \ for model in models] if i_f_ci_ce[0].shape != i_f_ci_ce[1].shape or \ not np.all(i_f_ci_ce[0] == i_f_ci_ce[1]): print(f"--same-dance means that the two models must have an identical indices_frame_camintrinsics_camextrinsics, but they do not. Shapes {i_f_ci_ce[0].shape},{i_f_ci_ce[1].shape}", file=sys.stderr) sys.exit(1) obs = [model.optimization_inputs()['observations_board'] \ for model in models] if obs[0].shape != obs[1].shape: print(f"--same-dance means that the two models must have an identically-laid-out observations_board, but they do not. Shapes {obs[0].shape},{obs[1].shape}", file=sys.stderr) sys.exit(1) idx_inliers = [ obs[i][ ...,2] > 0 \ for i in range(len(models)) ] calobjects = \ [ mrcal.hypothesis_board_corner_positions(model.icam_intrinsics(), **model.optimization_inputs(), idx_inliers = idx_inliers[0]*idx_inliers[1] )[-2] \ for model in models ] Rt10 = mrcal.align_procrustes_points_Rt01(calobjects[1], calobjects[0]) elif 1: # new method being tested. Fit the corners in the ref coordinate # systems. This explicitly models the extra existing rotation, so it # should be most correct optimization_inputs0 = models[0].optimization_inputs() optimization_inputs1 = models[1].optimization_inputs() calobject_height,calobject_width = optimization_inputs0['observations_board'].shape[1:3] calobject_spacing = optimization_inputs0['calibration_object_spacing'] # shape (Nh, Nw, 3) calibration_object0 = \ mrcal.ref_calibration_object(calobject_width, calobject_height, calobject_spacing, calobject_warp = optimization_inputs0['calobject_warp']) calibration_object1 = \ mrcal.ref_calibration_object(calobject_width, calobject_height, calobject_spacing, calobject_warp = optimization_inputs1['calobject_warp']) # shape (Nframes, Nh, Nw, 3) pcorners_ref0 = \ mrcal.transform_point_rt( nps.mv( optimization_inputs0['frames_rt_toref'], -2, -4), calibration_object0 ) pcorners_ref1 = \ mrcal.transform_point_rt( nps.mv( optimization_inputs1['frames_rt_toref'], -2, -4), calibration_object1 ) # shape (4,3) Rt_ref10 = mrcal.align_procrustes_points_Rt01(# shape (N,3) nps.clump(pcorners_ref1, n=3), # shape (N,3) nps.clump(pcorners_ref0, n=3)) # I have the ref-ref transform. I convert to a cam-cam transform icam_extrinsics0 = \ mrcal.corresponding_icam_extrinsics(models[0].icam_intrinsics(), **optimization_inputs0) icam_extrinsics1 = \ mrcal.corresponding_icam_extrinsics(models[1].icam_intrinsics(), **optimization_inputs1) if icam_extrinsics0 >= 0: Rt_cr0 = mrcal.Rt_from_rt(optimization_inputs0['extrinsics_rt_fromref'][icam_extrinsics0]) else: Rt_cr0 = mrcal.identity_Rt() if icam_extrinsics1 >= 0: Rt_cr1 = mrcal.Rt_from_rt(optimization_inputs1['extrinsics_rt_fromref'][icam_extrinsics1]) else: Rt_cr1 = mrcal.identity_Rt() Rt10 = \ mrcal.compose_Rt(Rt_cr1, Rt_ref10, mrcal.invert_Rt(Rt_cr0)) else: # default method used in the uncertainty computation. compute the mean # of the frame points optimization_inputs0 = models[0].optimization_inputs() icam_intrinsics0 = models[0].icam_intrinsics() icam_extrinsics0 = \ mrcal.corresponding_icam_extrinsics(icam_intrinsics0, **optimization_inputs0) if icam_extrinsics0 >= 0: Rt_rc0 = mrcal.invert_Rt(mrcal.Rt_from_rt(optimization_inputs0['extrinsics_rt_fromref'][icam_extrinsics0])) else: Rt_rc0 = mrcal.identity_Rt() Rt_fr0 = mrcal.invert_Rt(mrcal.Rt_from_rt(optimization_inputs0['frames_rt_toref'])) optimization_inputs1 = models[1].optimization_inputs() icam_intrinsics1 = models[1].icam_intrinsics() icam_extrinsics1 = \ mrcal.corresponding_icam_extrinsics(icam_intrinsics1, **optimization_inputs1) if icam_extrinsics1 >= 0: Rt_cr1 = mrcal.Rt_from_rt(optimization_inputs1['extrinsics_rt_fromref'][icam_extrinsics1]) else: Rt_cr1 = mrcal.identity_Rt() Rt_rf1 = mrcal.Rt_from_rt(optimization_inputs1['frames_rt_toref']) # not a geometric transformation: the R is not in SO3 Rt_r1r0 = np.mean( mrcal.compose_Rt(Rt_rf1, Rt_fr0), axis=-3) Rt_c1c0 = mrcal.compose_Rt( Rt_cr1, Rt_r1r0, Rt_rc0) q0 = models[0].imagersize()*2./5. v0_cam = mrcal.unproject(q0, optimization_inputs0['lensmodel'], optimization_inputs0['intrinsics'][icam_intrinsics0], normalize = True) p0_cam = v0_cam * (1e5 if distance is None else distance) # print(f"v0_cam = {v0_cam}") # print(f"reprojected = {mrcal.project(v0_cam, optimization_inputs0['lensmodel'], optimization_inputs0['intrinsics'][icam_intrinsics0])}") # print(f"reprojected other = {mrcal.project(np.array([-0.2471004,-0.21598248,0.9446126 ]), optimization_inputs0['lensmodel'], optimization_inputs0['intrinsics'][icam_intrinsics0])}") # print(f"reprojected other = {mrcal.project(np.array([-0.2471004,-0.21598248,0.9446126 ]), *models[0].intrinsics())}") # print(f"p0_cam = {p0_cam}") p0_ref = mrcal.transform_point_Rt(Rt_rc0, p0_cam) p0_frame = mrcal.transform_point_Rt(Rt_fr0, p0_ref) p1_refall = mrcal.transform_point_Rt(Rt_rf1, p0_frame) p1_ref = np.mean(p1_refall, axis=0) # print(f"p0_ref = {p0_ref}") # print(f"rt_rf0[0] = {optimization_inputs0['frames_rt_toref'][0]}") # print(f"Rt_fr0[0] = {Rt_fr0[0]}") # print(f"p0_frame = {p0_frame}") # print(f"p1_refall = {p1_refall}") # print(f"p1_ref = {p1_ref}") p1_cam = mrcal.transform_point_Rt(Rt_cr1, p1_ref) q1 = mrcal.project(p1_cam, *models[1].intrinsics()) # print(f"p1_cam = {p1_cam}") # print(f"q1 = {q1}") # print(f"before:\n{Rt10}") Rt10 = Rt_r1r0 # print(f"after:\n{Rt10}") # print(f"--same-dance Rt10: {Rt10}") # print(f"--same-dance Ninliers = {np.count_nonzero(idx_inliers[0]*idx_inliers[1])} Ntotal = {np.size(idx_inliers[0])}") # print(f"idx_inliers[0].shape: {idx_inliers[0].shape}") # import gnuplotlib as gp # gp.plot(nps.mag(calobjects[0] - calobjects[1]), wait=1) # # gp.plot( (calobjects[0] - calobjects[1],), tuplesize=-3, _with='points', square=1, _3d=1, xlabel='x', ylabel = 'y', zlabel = 'z') # # import IPython # # IPython.embed() # # sys.exit() if args.observations: optimization_inputs = [ m.optimization_inputs() for m in models ] if any( oi is None for oi in optimization_inputs ): print("mrcal-show-projection-diff --observations requires optimization_inputs to be available for all models, but this is missing for some models", file=sys.stderr) sys.exit(1) plot,Rt10 = mrcal.show_projection_diff(models, gridn_width = args.gridn[0], gridn_height = args.gridn[1], observations = args.observations, valid_intrinsics_region = args.valid_intrinsics_region, distance = distance, intrinsics_only = args.intrinsics_only, use_uncertainties = not args.no_uncertainties, focus_center = args.where, focus_radius = args.radius, vectorfield = args.vectorfield, vectorscale = args.vectorscale, directions = args.directions, hardcopy = args.hardcopy, terminal = args.terminal, cbmax = args.cbmax, **plotkwargs_extra) if not args.intrinsics_only and args.radius != 0 and \ Rt10 is not None and Rt10.shape == (4,3): rt10 = mrcal.rt_from_Rt(Rt10) print(f"Transformation cam1 <-- cam0: rotation: {nps.mag(rt10[:3])*180./np.pi:.03f} degrees, translation: {rt10[3:]} m") dist_shift = nps.mag(rt10[3:]) if dist_shift > 0.01: msg = f"## WARNING: fitted camera moved by {dist_shift:.03f}m. This is probably aphysically high, and something is wrong. Pass both a high and a low --distance? See the docs at http://mrcal.secretsauce.net/differencing.html" print(msg, file=sys.stderr) if args.hardcopy is None: plot.wait() mrcal-2.4.1/mrcal-show-projection-uncertainty000077500000000000000000000224441456301662300213470ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Visualize the expected projection error due to noise in calibration-time input SYNOPSIS $ mrcal-show-projection-uncertainty left.cameramodel ... a plot pops up showing the projection uncertainty of the intrinsics in ... this model The operation of this tool is documented at http://mrcal.secretsauce.net/uncertainty.html A calibration process produces the best-fitting camera parameters. To be able to use these parameters we must know how trustworthy they are. This tool examines the uncertainty of projection using a given camera model. The projection operation uses the intrinsics only, but the uncertainty must take into account the calibration-time extrinsics and the calibration-time observed object poses as well. This tool visualizes the expected value of projection error across the imager. Areas with a high expected projection error are unreliable, and observations in those regions cannot be used for further work (localization, mapping, etc). There are several modes of operation: - By default we look at projection of points some distance away from the camera (given by --distance). We evaluate the uncertainty of these projections everywhere across the imager, and display the results as a heatmap with overlaid contours - With --vs-distance-at we evaluate the uncertainty along an observation ray mapping to a single pixel. We show the uncertainty vs distances from the camera along this ray See http://mrcal.secretsauce.net/uncertainty.html for a full description of the computation performed here ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--vs-distance-at', type=str, help='''If given, we don't compute the uncertainty everywhere in the image at a constant distance from the camera, but instead we look at different distances at one pixel. This option takes a single argument: the "X,Y" pixel coordinate we care about, or "center" to look at the center of the imager or "centroid" to look at the center of the calibration-time chessboards. This is exclusive with --gridn and --distance and --observations and --cbmax''') parser.add_argument('--gridn', type=int, default = (60,40), nargs = 2, help='''How densely we should sample the imager. By default we use a 60x40 grid''') parser.add_argument('--distance', type=float, help='''By default we display the projection uncertainty infinitely far away from the camera. If we want to look closer in, the desired observation distance can be given in this argument''') parser.add_argument('--isotropic', action='store_true', default=False, help='''By default I display the expected value of the projection error in the worst possible direction of this error. If we want to plot the RMS of the worst and best directions, pass --isotropic. If we assume the errors will apply evenly in all directions, then we can use this metric, which is potentially easier to compute''') parser.add_argument('--observations', action='store_true', default=False, help='''If given, I display the pixel observations at calibration time. This should correspond to the low-uncertainty regions.''') parser.add_argument('--valid-intrinsics-region', action='store_true', default=False, help='''If given, I overlay the valid-intrinsics region onto the plot''') parser.add_argument('--cbmax', type=float, default=3, help='''Maximum range of the colorbar''') parser.add_argument('--title', type=str, default = None, help='''Title string for the plot. Overrides the default title. Exclusive with --extratitle''') parser.add_argument('--extratitle', type=str, default = None, help='''Additional string for the plot to append to the default title. Exclusive with --title''') parser.add_argument('--hardcopy', type=str, help='''Write the output to disk, instead of an interactive plot''') parser.add_argument('--terminal', type=str, help=r'''gnuplotlib terminal. The default is good almost always, so most people don't need this option''') parser.add_argument('--set', type=str, action='append', help='''Extra 'set' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('--unset', type=str, action='append', help='''Extra 'unset' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('model', type=str, help='''Input camera model. If "-' is given, we read standard input''') return parser.parse_args() args = parse_args() if args.title is not None and \ args.extratitle is not None: print("--title and --extratitle are exclusive", file=sys.stderr) sys.exit(1) # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README import numpy as np import mrcal if args.vs_distance_at is not None: if args.distance is not None or \ args.observations: print("--vs-distance-at is exclusive with --gridn and --distance and --observations and --cbmax", file=sys.stderr) sys.exit(1) if re.match('center$|centroid$', args.vs_distance_at): pass elif re.match('[0-9\.eEdD+-]+,[0-9\.eEdD+-]+$', args.vs_distance_at): # pixel coordinate given args.vs_distance_at = \ np.array([float(x) for x in args.vs_distance_at.split(',')]) else: print("--vs-distance-at must be given 'center' or 'centroid' or X,Y (pixel coordinates)", file=sys.stderr) sys.exit(1) plotkwargs_extra = {} if args.set is not None: plotkwargs_extra['set'] = args.set if args.unset is not None: plotkwargs_extra['unset'] = args.unset if args.title is not None: plotkwargs_extra['title'] = args.title if args.extratitle is not None: plotkwargs_extra['extratitle'] = args.extratitle try: model = mrcal.cameramodel(args.model) except Exception as e: print(f"Couldn't load camera model '{args.model}': {e}", file=sys.stderr) sys.exit(1) if model.optimization_inputs() is None: print("ERROR: optimization_inputs are unavailable in this model. Uncertainty cannot be computed", file = sys.stderr) sys.exit() if args.vs_distance_at is not None: plot = mrcal.show_projection_uncertainty_vs_distance(model, where = args.vs_distance_at, isotropic = args.isotropic, hardcopy = args.hardcopy, terminal = args.terminal, **plotkwargs_extra) else: plot = mrcal.show_projection_uncertainty(model, gridn_width = args.gridn[0], gridn_height = args.gridn[1], distance = args.distance, isotropic = args.isotropic, observations = args.observations, valid_intrinsics_region = args.valid_intrinsics_region, hardcopy = args.hardcopy, terminal = args.terminal, cbmax = args.cbmax, **plotkwargs_extra) if args.hardcopy is None: plot.wait() mrcal-2.4.1/mrcal-show-residuals000077500000000000000000000264651456301662300166320ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Visualize calibration residuals in an imager SYNOPSIS $ mrcal-show-residuals --vectorfield left.cameramodel ... a plot pops up showing the vector field of residuals for this camera This tool supports several different modes, selected by the commandline arguments. Exactly one of these mode options must be given: --vectorfield Visualize the optimized residuals as a vector field. Each vector runs from the observed chessboard corner to its prediction at the optimal solution. --magnitudes Visualize the optimized residual magnitudes as color-coded points. Similar to --vectorfield, but instead of a vector, each residual is plotted as a colored circle, coded by the MAGNITUDE of the error. This is usually more legible. --directions Visualize the optimized residual directions as color-coded points. Similar to --vectorfield, but instead of a vector, each residual is plotted as a colored circle, coded by the DIRECTION of the error. This is very useful in detecting biases caused by a poorly-fitting lens model: these show up as clusters of similar color, instead of a random distribution. --regional Visualize the optimized residuals, broken up by region. The imager of a camera is subdivided into bins. The residual statistics are then computed for each bin separately. We can then clearly see areas of insufficient data (observation counts will be low). And we can clearly see lens-model-induced biases (non-zero mean) and we can see heteroscedasticity (uneven standard deviation). The mrcal-calibrate-cameras tool uses these metrics to construct a valid-intrinsics region for the models it computes. This serves as a quick/dirty method of modeling projection reliability, which can be used even if projection uncertainty cannot be computed. --histogram Visualize the distribution of the optimized residuals. We display a histogram of residuals and overlay it with an idealized gaussian distribution. ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) mode_group = parser.add_mutually_exclusive_group(required = True) mode_group.add_argument('--vectorfield', action='store_true', help='''Visualize the optimized residuals as a vector field''') mode_group.add_argument('--magnitudes', action='store_true', help='''Visualize the optimized residual magnitudes as color-coded points''') mode_group.add_argument('--directions', action='store_true', help='''Visualize the optimized residual directions as color-coded points''') mode_group.add_argument('--regional', action='store_true', help='''Visualize the optimized residuals, broken up by region''') mode_group.add_argument('--histogram', action='store_true', help='''Visualize the distribution of the optimized residuals''') mode_group.add_argument('--histogram-this-camera', action='store_true', help='''If given, we show the histogram for residuals for THIS camera only. Otherwise (by default) we display the residuals for all the cameras in this solve. Implies --histogram''') parser.add_argument('--valid-intrinsics-region', action='store_true', help='''If given, I overlay the valid-intrinsics regions onto the plot. Applies to all the modes except --histogram''') parser.add_argument('--gridn', type=int, default = (20,14), nargs = 2, help='''How densely we should bin the imager. By default we use a 20x14 grid of bins. Applies only if --regional''') parser.add_argument('--binwidth', type=float, default=0.02, help='''The width of binds used for the histogram. Defaults to 0.02 pixels. Applies only if --histogram''') parser.add_argument('--vectorscale', type = float, default = 1.0, help='''Scale all the vectors by this factor. Useful to improve legibility if the vectors are too small to see. Applies only if --vectorfield''') parser.add_argument('--cbmax', type=float, help='''Maximum range of the colorbar used in --vectorfield, --magnitudes. If omitted, we autoscale''') parser.add_argument('--title', type=str, default = None, help='''Title string for the plot. Overrides the default title. Exclusive with --extratitle''') parser.add_argument('--extratitle', type=str, default = None, help='''Additional string for the plot to append to the default title. Exclusive with --title''') parser.add_argument('--hardcopy', type=str, help='''Write the output to disk, instead of making an interactive plot. If --regional, then several plots are made, and the --hardcopy argument is a base name: "--hardcopy /a/b/c/d.pdf" will produce plots in "/a/b/c/d.XXX.pdf" where XXX is the type of plot being made''') parser.add_argument('--terminal', type=str, help=r'''gnuplotlib terminal. The default is good almost always, so most people don't need this option''') parser.add_argument('--set', type=str, action='append', help='''Extra 'set' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('--unset', type=str, action='append', help='''Extra 'unset' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('model', type=str, help=r'''Camera model that contains the optimization_inputs that describe the solve. The displayed observations may come from ANY of the cameras in the solve, not necessarily the one given by this model''') args = parser.parse_args() if args.histogram_this_camera: args.histogram = True if args.title is not None and \ args.extratitle is not None: print("--title and --extratitle are exclusive", file=sys.stderr) sys.exit(1) return args args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README import mrcal import numpy as np import numpysane as nps plotkwargs_extra = {} if args.set is not None: plotkwargs_extra['set'] = args.set if args.unset is not None: plotkwargs_extra['unset'] = args.unset if args.title is not None: plotkwargs_extra['title'] = args.title if args.extratitle is not None: plotkwargs_extra['extratitle'] = args.extratitle try: model = mrcal.cameramodel(args.model) except Exception as e: print(f"Couldn't load camera model '{args.model}': {e}", file=sys.stderr) sys.exit(1) optimization_inputs = model.optimization_inputs() if optimization_inputs is None: print(f"Camera model '{args.model}' does not contain optimization inputs. Residuals aren't available", file=sys.stderr) sys.exit(1) residuals = mrcal.optimizer_callback(**optimization_inputs)[1] if not args.hardcopy: plotkwargs_extra['wait'] = True kwargs = dict(residuals = residuals, hardcopy = args.hardcopy, terminal = args.terminal, **plotkwargs_extra) if args.vectorfield: mrcal.show_residuals_vectorfield(model, vectorscale = args.vectorscale, valid_intrinsics_region = args.valid_intrinsics_region, cbmax = args.cbmax, **kwargs) elif args.magnitudes: mrcal.show_residuals_magnitudes(model, valid_intrinsics_region = args.valid_intrinsics_region, cbmax = args.cbmax, **kwargs) elif args.directions: mrcal.show_residuals_directions(model, valid_intrinsics_region = args.valid_intrinsics_region, **kwargs) elif args.histogram: mrcal.show_residuals_histogram(optimization_inputs, icam_intrinsics = model.icam_intrinsics() if args.histogram_this_camera else None, binwidth = args.binwidth, **kwargs) elif args.regional: plotargs = \ mrcal.show_residuals_regional(model, valid_intrinsics_region = args.valid_intrinsics_region, gridn_width = args.gridn[0], gridn_height = args.gridn[1], return_plot_args = args.hardcopy is None, **kwargs) if args.hardcopy: sys.exit(0) # This produces 3 plots. I want to pop up the 3 separate windows at the same # time, and I want to exit when all 3 are done import gnuplotlib as gp pids = [0,0,0] for i in range(3): pid = os.fork() if pid == 0: # child # make the plot, and wait for it to be closed by the user (data_tuples,plot_options) = plotargs[i] p = gp.gnuplotlib(**plot_options) p.plot(*data_tuples) sys.exit() # parent pids[i] = pid for i in range(3): os.waitpid(pids[i], 0) sys.exit() else: print("Unknown mode. Exactly one of the mutually-exclusive variables should have gotten through the argument parser. Is this an argparse bug?", file=sys.stderr) sys.exit(1) mrcal-2.4.1/mrcal-show-residuals-board-observation000077500000000000000000000342131456301662300222360ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Visualize calibration residuals for one or more observations of a board SYNOPSIS $ mrcal-show-residuals-board-observation --from-worst --explore left.cameramodel 0-2 ... a plot pops up showing the 3 worst-fitting chessboard observations in this ... solve. And a REPL opens up to allow further study The residuals come from the optimization inputs stored in the cameramodel file. A cameramodel that's missing this data cannot be used with this tool. To plot the residuals on top of the image used in the calibration the image paths are loaded from the optimization inputs. The paths are used directly, relative to the current directory. If the paths are unavailable or if the image cannot be read, the plot is made without the underlying image. ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--title', type=str, default = None, help='''Title string for the plot. Overrides the default title. Exclusive with --extratitle''') parser.add_argument('--extratitle', type=str, default = None, help='''Additional string for the plot to append to the default title. Exclusive with --title''') parser.add_argument('--vectorscale', type = float, default = 1.0, help='''Scale all the vectors by this factor. Useful to improve legibility if the vectors are too small to see''') parser.add_argument('--circlescale', type = float, default = 1.0, help='''Scale all the plotted circles by this factor. Useful to improve legibility if the vectors are too big or too small''') parser.add_argument('--cbmax', type=float, help='''Maximum range of the colorbar. If omitted, we autoscale''') parser.add_argument('--from-worst', action = 'store_true', help='''If given, the requested observations index from the worst-fitting observations to the best-fitting (observation 0 is the worst-fitting observation). Exclusive with --from-glob. By default we index the observations in the order they appear in the solve''') parser.add_argument('--from-glob', action = 'store_true', help='''If given, the requested observations are specified as glob(s) matching the image filenames. Exclusive with --from-worst''') parser.add_argument('--image-path-prefix', help='''If given, we prepend the given prefix to the image paths. Exclusive with --image-directory''') parser.add_argument('--image-directory', help='''If given, we extract the filenames from the image paths in the solve, and use the given directory to find those filenames. Exclusive with --image-path-prefix''') parser.add_argument('--hardcopy', type=str, help='''Write the output to disk, instead of making an interactive plot. If given, only ONE observation may be specified''') parser.add_argument('--terminal', type=str, help=r'''gnuplotlib terminal. The default is good almost always, so most people don't need this option''') parser.add_argument('--set', type=str, action='append', help='''Extra 'set' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('--unset', type=str, action='append', help='''Extra 'unset' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('--explore', action='store_true', help='''If given, the tool drops into a REPL before exiting, to allow the user to follow-up with more diagnostics''') parser.add_argument('model', type=str, help=r'''Camera model that contains the optimization_inputs that describe the solve. The displayed observations may come from ANY of the cameras in the solve, not necessarily the one given by this model''') parser.add_argument('observations', type=str, nargs='+', help=r'''The observations we're looking at. Unless --from-glob, these are a list of integers A and/or A-B ranges. By default these index the board observations in the order they appear in the solve. If --from-worst, then we index them from the worst-fitting to the best-fitting instead. If --from-glob then we treat the strings as globs to match against the image paths''') args = parser.parse_args() if args.image_path_prefix is not None and \ args.image_directory is not None: print("--image-path-prefix and --image-directory are mutually exclusive", file=sys.stderr) sys.exit(1) if args.from_worst and args.from_glob: print("--from-worst and --from-glob are mutually exclusive", file=sys.stderr) sys.exit(1) def list_ints_from_range_string(s): try: i = int(s) if i < 0: print(f"Observations should be a list of non-negative integers and/or A-B ranges. Invalid observation given: '{s}'", file=sys.stderr) sys.exit(1) return [i] except Exception as e: pass m = re.match("^([0-9]+)-([0-9]+)$", s) if m is None: print(f"Observations should be a list of non-negative integers and/or A-B ranges. Invalid observation given: '{s}'", file=sys.stderr) sys.exit(1) try: i0 = int(m.group(1)) i1 = int(m.group(2)) except Exception as e: print(f"Observations should be a list of non-negative integers and/or A-B ranges. Invalid observation given: '{s}'", file=sys.stderr) sys.exit(1) return list(range(i0,i1+1)) if not args.from_glob: args.observations = [o for obs in args.observations for o in list_ints_from_range_string(obs)] if args.hardcopy is not None: if len(args.observations) != 1: print(f"--hardcopy given, so exactly one observation should have been given. Instead got these observations: {args.observations}", file=sys.stderr) sys.exit(1) if args.title is not None and \ args.extratitle is not None: print("--title and --extratitle are exclusive", file=sys.stderr) sys.exit(1) return args args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README import mrcal import numpy as np import numpysane as nps import pprint plotkwargs_extra = {} if args.set is not None: plotkwargs_extra['set'] = args.set if args.unset is not None: plotkwargs_extra['unset'] = args.unset if args.title is not None: plotkwargs_extra['title'] = args.title if args.extratitle is not None: plotkwargs_extra['extratitle'] = args.extratitle try: model = mrcal.cameramodel(args.model) except Exception as e: print(f"Couldn't load camera model '{args.model}': {e}", file=sys.stderr) sys.exit(1) optimization_inputs = model.optimization_inputs() if optimization_inputs is None: print(f"Camera model '{args.model}' does not contain optimization inputs. Residuals aren't available", file=sys.stderr) sys.exit(1) try: paths = optimization_inputs['imagepaths'] except: # older models don't have this data paths = None if args.from_glob: if paths is None: print("--from-glob requires image paths, but the given model doesn't have them", file=sys.stderr) sys.exit(1) import fnmatch def matching_path_indices(obs): try: r = re.compile( fnmatch.translate(obs) ) except: print(f"Error translating, compiling glob '{obs}'", file=sys.stderr) sys.exit(1) m = [i for i in range(len(paths)) if r.match(paths[i])] if not m: print(f"Glob '{obs}' did not match any images", file=sys.stderr) sys.exit(1) return m args.observations = [i for obs in args.observations for i in matching_path_indices(obs)] residuals = mrcal.optimizer_callback(**optimization_inputs)[1] # for --explore indices_frame_camintrinsics_camextrinsics = optimization_inputs['indices_frame_camintrinsics_camextrinsics'] # i_observations_sorted_from_worst is available even if I don't need it. # --explore might want to look at it # shape (Nobservations, object_height_n, object_width_n, 3) observations = optimization_inputs['observations_board'] residuals_shape = observations.shape[:-1] + (2,) # shape (Nobservations, object_height_n, object_width_n, 2) residuals_reshaped = residuals[:np.product(residuals_shape)].reshape(*residuals_shape) # shape (Nobservations,) err_per_observation = nps.norm2(nps.clump(residuals_reshaped, n=-3)) i_observations_sorted_from_worst = \ list(reversed(np.argsort(err_per_observation))) def show(i_observation): try: mrcal.show_residuals_board_observation(optimization_inputs, i_observation, from_worst = args.from_worst, i_observations_sorted_from_worst = i_observations_sorted_from_worst, residuals = residuals, paths = paths, cbmax = args.cbmax, image_path_prefix = args.image_path_prefix, image_directory = args.image_directory, circlescale = args.circlescale, vectorscale = args.vectorscale, hardcopy = args.hardcopy, terminal = args.terminal, **plotkwargs_extra) except Exception as e: print(f"Couldn't show_residuals_board_observation(): {e}", file=sys.stderr) sys.exit(1) Nplots = len(args.observations) if args.hardcopy: for i in range(Nplots): show(args.observations[i]) print(f"Wrote {args.hardcopy}") sys.exit(0) plotkwargs_extra['wait'] = True pids = [0] * Nplots for i in range(Nplots): pid = os.fork() if pid == 0: # child # make the plot, and wait for it to be closed by the user show(args.observations[i]) sys.exit() # parent pids[i] = pid if args.explore: explore_message = \ f'''We're exploring. The first plot being shown can be re-created with: mrcal.show_residuals_board_observation(optimization_inputs, {args.observations[0]}, from_worst = args.from_worst, i_observations_sorted_from_worst = i_observations_sorted_from_worst, residuals = residuals, paths = paths, circlescale = args.circlescale, vectorscale = args.vectorscale, hardcopy = args.hardcopy, terminal = args.terminal, **{pprint.pformat(plotkwargs_extra)}) This is available via a shorthand function call show({args.observations[0]}) The first 10 worst-fitting observations (i_observations_sorted_from_worst[:10]) {i_observations_sorted_from_worst[:10]} The corresponding 10 (iframe, icamintrinsics, icamextrinsics) tuples (indices_frame_camintrinsics_camextrinsics[i_observations_sorted_from_worst[:10] ]): {indices_frame_camintrinsics_camextrinsics[ i_observations_sorted_from_worst[:10] ]} ''' if paths is not None: explore_message += \ f'''The corresponding image paths (paths[i_observations_sorted_from_worst[:10]]): {paths[i_observations_sorted_from_worst[:10]]} ''' explore_message += \ r""" The optimization inputs are available in the optimization_inputs dict """ print(explore_message) import IPython IPython.embed() for i in range(Nplots): os.waitpid(pids[i], 0) sys.exit() mrcal-2.4.1/mrcal-show-splined-model-correction000077500000000000000000000255421456301662300215330ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Visualizes the surface represented in a splined lens model SYNOPSIS $ mrcal-show-splined-model-correction cam.cameramodel ... a plot pops up showing the correction magnitude heatmap Splined models are parametrized by flexible surfaces that define the projection corrections (off some baseline model), and visualizing these corrections is useful for understanding the projection behavior. Details of these models are described in the documentation: http://mrcal.secretsauce.net/lensmodels.html#splined-stereographic-lens-model At this time LENSMODEL_SPLINED_STEREOGRAPHIC is the only splined model mrcal has, so the baseline model is always LENSMODEL_STEREOGRAPHIC. This tool produces a plot in the domain either of the input or the output of the spline functions. By default: The plot is presented based on the spline index. With LENSMODEL_SPLINED_STEREOGRAPHIC, this is the stereographic projection u. This is the "forward" direction, what the projection operation actually computes. In this view the knots form a regular grid, and the edge of the imager forms a (possibly very irregular) curve if --imager-domain: The plot is presented based on the pixels in the imager. This is the backward direction: the domain is the OUTPUT of the splined functions. In this view the knot layout is (possibly highly) irregular. The edge of the imager is a perfect rectangle. Separate from the domain, the data can be presented in 3 different ways: - Magnitude heatmap. This is the default. We plot mag(deltauxy). This displays the deviation from the baseline model as a heat map. - Individual heatmap. Selected by passing an "xy" argument. We plot deltaux or deltauy, depending on the value of xy. This displays the value of one of the two splined surfaces individually, as a heat map. - Vector field. Selected by --vectorfield. Displays the correction (deltaux, deltauy) as a vector field. The splined surfaces are defined by control points we call "knots". These knots are arranged in a fixed grid (defined by the model configuration) with the value at each knot set in the intrinsics vector. The configuration selects the control point density and the expected field of view of the lens. If the fov_x_deg configuration value is too big, many of the knots will lie well outside the visible area, and will not be used. This is wasteful. If fov_x_deg is too small, then some parts of the imager will lie outside of the spline-in-bounds region, resulting in less-flexible projection behavior at the edges of the imager. So the field of view should roughly match the actual lens+camera we're using, and we can evaluate that with this tool. This tool displays the spline-in-bounds region together with the usable projection region (either the valid-intrinsics region or the imager bounds). Ideally, the spline-in-bounds region is slightly bigger than the usable projection region. The usable projection region visualized by this tool is controlled by --show-imager-bounds. If omitted, we display the valid-intrinsics region. This is recommended, but keep in mind that this region is smaller than the full imager, so a fov_x_deg that aligns well for one calibration may be too small in a subsequent calibration of the same lens. If the subsequent calibration has better coverage, and thus a bigger valid-intrinsics region. If --show-imager-bounds: we use the imager bounds instead. The issue here is that the projection near the edges of the imager is usually poorly-defined because usually there isn't a lot of calibration data there. This makes the projection behavior at the imager edges unknowable. Consequently, plotting the projection at the imager edges is usually too alarming or not alarming enough. Passing --show-imager-bounds is thus recommended only if we have very good calibration coverage at the edge of the imager. ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--gridn', type=int, default = (60,40), nargs = 2, help='''The density of the plotted grid. By default we use a 60x40 grid''') parser.add_argument('--vectorfield', action = 'store_true', help='''Display the spline correction as a vector field. if --vectorfield: the 'xy' argument MUST be omitted''') parser.add_argument('--vectorscale', type = float, default = 1.0, help='''If plotting a vector field, scale all the vectors by this factor. Useful to improve legibility if the vectors are too small to see''') parser.add_argument('--title', type=str, default = None, help='''Title string for the plot. Overrides the default title. Exclusive with --extratitle''') parser.add_argument('--extratitle', type=str, default = None, help='''Additional string for the plot to append to the default title. Exclusive with --title''') parser.add_argument('--hardcopy', type=str, help='''Write the output to disk, instead of making an interactive plot''') parser.add_argument('--terminal', type=str, help=r'''gnuplotlib terminal. The default is good almost always, so most people don't need this option''') parser.add_argument('--set', type=str, action='append', help='''Extra 'set' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('--unset', type=str, action='append', help='''Extra 'unset' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('--imager-domain', action='store_true', help='''By default, this produces a visualization in the domain of the spline-index (normalized stereographic coordinates). Sometimes it's more informative to look at the imager domain instead, by passing this option''') parser.add_argument('--show-imager-bounds', action='store_true', help='''By default we communicate the usable projection region to the user by displaying the valid-intrinsics region. This isn't available in all models. To fall back on the boundary of the full imager, pass --show-imager-bounds. In the usual case of incomplete calibration-time coverage at the edges, this results in a very unrealistic representation of reality. Leaving this at the default is recommended''') parser.add_argument('--observations', action='store_true', default=False, help='''If given, I show where the chessboard corners were observed at calibration time. This is useful to evaluate the reported unprojectable regions.''') parser.add_argument('model', type=str, help='''Input camera model. If "-' is given, we read standard input''') parser.add_argument('xy', choices = ('x','y'), nargs = '?', help='''Optional 'x' or 'y': which surface we're looking at. MUST be omitted if --vectorfield. If omitted and not --vectorfield: we plot the magnitude of the (deltaux,deltauy) corretion vector''') args = parser.parse_args() if args.title is not None and \ args.extratitle is not None: print("--title and --extratitle are exclusive", file=sys.stderr) sys.exit(1) return args args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README import numpy as np import numpysane as nps import mrcal try: model = mrcal.cameramodel(args.model) except Exception as e: print(f"Couldn't load camera model '{args.model}': {e}", file=sys.stderr) sys.exit(1) lensmodel = model.intrinsics()[0] if not re.match('LENSMODEL_SPLINED', lensmodel): print(f"This only makes sense with splined models. Input uses {lensmodel}", file = sys.stderr) sys.exit(1) if not args.show_imager_bounds and \ model.valid_intrinsics_region() is None: print("The given model has no valid-intrinsics region. Pass --show-imager-bounds", file = sys.stderr) sys.exit(1) plotkwargs = {} if args.set is not None: plotkwargs['set'] = args.set if args.unset is not None: plotkwargs['unset'] = args.unset if args.title is not None: plotkwargs['title'] = args.title if args.extratitle is not None: plotkwargs['extratitle'] = args.extratitle try: plot = mrcal.show_splined_model_correction( model, vectorfield = args.vectorfield, xy = args.xy, imager_domain = args.imager_domain, gridn_width = args.gridn[0], gridn_height = args.gridn[1], vectorscale = args.vectorscale, valid_intrinsics_region = not args.show_imager_bounds, observations = args.observations, hardcopy = args.hardcopy, terminal = args.terminal, **plotkwargs) except Exception as e: print(f"Error: {e}", file=sys.stderr) sys.exit(1) if args.hardcopy is None: plot.wait() mrcal-2.4.1/mrcal-show-valid-intrinsics-region000077500000000000000000000154571456301662300214010ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Visualize the valid-intrinsics region SYNOPSIS $ mrcal-show-valid-intrinsics-region --write-image --image image.png left.cameramodel Wrote image-valid-intrinsics-region.png Given a camera model (or models), this tool displays the valid-intrinsics region(s). All the given models MUST contain a valid-intrinsics region. Empty regions are handled properly. If an image is given, the region is rendered overlaid onto the image. If --points then we also read x,y points from STDIN, and plot those too. By default, we use gnuplotlib to make an interactive plot. Alternately, pass --write-image to annotate a given image, and write the new image on disk. --write-image is not supported together with --points. ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--write-image', action='store_true', help='''By default I make a plot. If --write-image is given, I output an annotated image instead. The image to annotate is then required, and is given in --image''') parser.add_argument('--force', '-f', action='store_true', default=False, help='''With --write-image we refuse to overwrite any existing images. Pass --force to allow overwriting''') parser.add_argument('--points', action='store_true', help='''If given, I read a set of xy points from STDIN, and include them in the plot. This applies ONLY if not --write-image''') parser.add_argument('--title', type=str, default = None, help='''Extra title string for the plot''') parser.add_argument('--hardcopy', type=str, help='''Write the output to disk, instead of making an interactive plot''') parser.add_argument('--terminal', type=str, help=r'''gnuplotlib terminal. The default is good almost always, so most people don't need this option''') parser.add_argument('--set', type=str, action='append', help='''Extra 'set' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('--unset', type=str, action='append', help='''Extra 'unset' directives to gnuplotlib. Can be given multiple times''') parser.add_argument('--image', type=str, required = False, help='''Image to annotate. Used both with and without --write-image''') parser.add_argument('models', type=str, nargs='+', help='''Input camera model(s)''') return parser.parse_args() args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README if args.write_image: if args.image is None: print("--write-image NEEDS an image to annotate", file=sys.stderr) sys.exit(1) if args.title is not None or \ args.hardcopy is not None or \ args.terminal is not None or \ args.set is not None or \ args.unset is not None: print("--title and --hardcopy and --terminal and --set and --unset are only valid without --write-image", file=sys.stderr) sys.exit(1) if args.points: print("Currently --points is implemented ONLY if not --write-image", file=sys.stderr) sys.exit(1) import mrcal import numpy as np def openmodel(f): try: return mrcal.cameramodel(f) except Exception as e: print(f"Couldn't load camera model '{f}': {e}", file=sys.stderr) sys.exit(1) models = [openmodel(modelfilename) for modelfilename in args.models] if any( m.valid_intrinsics_region() is None for m in models ): print("Not all given models have a valid-intrinsics contour! Giving up", file=sys.stderr) sys.exit(1) if args.write_image: # this function stolen from mrcal-reproject-image. Please consolidate def target_image_filename(filename_in, suffix): base,extension = os.path.splitext(filename_in) if len(extension) != 4: print(f"imagefile must end in .xxx where 'xxx' is some image extension. Instead got '{filename_in}'", file=sys.stderr) sys.exit(1) filename_out = f"{base}-{suffix}{extension}" if not args.force and os.path.exists(filename_out): print(f"Target image '{filename_out}' already exists. Doing nothing, and giving up. Pass -f to overwrite", file=sys.stderr) sys.exit(1) return filename_out def target_image_filename(filename_in, suffix): base,extension = os.path.splitext(filename_in) if len(extension) != 4: print(f"imagefile must end in .xxx where 'xxx' is some image extension. Instead got '{filename_in}'", file=sys.stderr) sys.exit(1) filename_out = f"{base}-{suffix}{extension}" return filename_out imagefile_out = target_image_filename(args.image, 'valid-intrinsics-region') image_out = mrcal.load_image(args.image) for m in models: mrcal.annotate_image__valid_intrinsics_region(image_out, m) mrcal.save_image(imagefile_out, image_out) sys.stderr.write("Wrote {}\n".format(imagefile_out)) else: points = None if args.points: points = np.loadtxt(sys.stdin) plotkwargs_extra = {} if args.set is not None: plotkwargs_extra['set'] = args.set if args.unset is not None: plotkwargs_extra['unset'] = args.unset plot = mrcal.show_valid_intrinsics_region( \ models, cameranames = args.models, image = args.image, points = points, hardcopy = args.hardcopy, terminal = args.terminal, title = args.title, **plotkwargs_extra) if args.hardcopy is None: plot.wait() mrcal-2.4.1/mrcal-stereo000077500000000000000000001506771456301662300151650ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Stereo processing SYNOPSIS $ mrcal-stereo \ --az-fov-deg 90 \ --el-fov-deg 70 \ --pixels-per-deg -0.5 \ --disparity-range 0 100 \ --sgbm-block-size 5 \ --sgbm-p1 600 \ --sgbm-p2 2400 \ --sgbm-uniqueness-ratio 5 \ --sgbm-disp12-max-diff 1 \ --sgbm-speckle-window-size 200 \ --sgbm-speckle-range 2 \ --outdir /tmp \ left.cameramodel right.cameramodel \ left.jpg right.jpg Processing left.jpg and right.jpg Wrote '/tmp/rectified0.cameramodel' Wrote '/tmp/rectified1.cameramodel' Wrote '/tmp/left-rectified.png' Wrote '/tmp/right-rectified.png' Wrote '/tmp/left-disparity.png' Wrote '/tmp/left-range.png' Wrote '/tmp/points-cam0.vnl' Given a pair of calibrated cameras and pairs of images captured by these cameras, this tool runs the whole stereo processing sequence to produce disparity and range images and a point cloud array. mrcal functions are used to construct the rectified system. Currently only the OpenCV SGBM routine is available to perform stereo matching, but more options will be made available with time. The commandline arguments to configure the SGBM matcher (--sgbm-...) map to the corresponding OpenCV APIs. Omitting an --sgbm-... argument will result in the defaults being used in the cv2.StereoSGBM_create() call. Usually the cv2.StereoSGBM_create() defaults are terrible, and produce a disparity map that isn't great. The --sgbm-... arguments in the synopsis above are a good start to get usable stereo. The rectified system is constructed with the axes - x: from the origin of the first camera to the origin of the second camera (the baseline direction) - y: completes the system from x,z - z: the mean "forward" direction of the two input cameras, with the component parallel to the baseline subtracted off The active window in this system is specified using a few parameters. These refer to - the "azimuth" (or "az"): the direction along the baseline: rectified x axis - the "elevation" (or "el"): the direction across the baseline: rectified y axis The rectified field of view is given by the arguments --az-fov-deg and --el-fov-deg. At this time there's no auto-detection logic, and these must be given. Changing these is a "zoom" operation. To pan the stereo system, pass --az0-deg and/or --el0-deg. These specify the center of the rectified images, and are optional. Finally, the resolution of the rectified images is given with --pixels-per-deg. This is optional, and defaults to the resolution of the first input image. If we want to scale the input resolution, pass a value <0. For instance, to generate rectified images at half the first-input-image resolution, pass --pixels-per-deg=-0.5. Note that the Python argparse has a problem with negative numbers, so "--pixels-per-deg -0.5" does not work. The input images are specified by a pair of globs, so we can process many images with a single call. Each glob is expanded, and the filenames are sorted. The resulting lists of files are assumed to match up. There are several modes of operation: - No images given: we compute the rectified system only, writing the models to disk - No --viz argument given: we compute the rectified system and the disparity, and we write all output as images on disk - --viz geometry: we compute the rectified system, and display its geometry as a plot. No rectification is computed, and the images aren't used, and don't need to be passed in - --viz stereo: compute the rectified system and the disparity. We don't write anything to disk initially, but we invoke an interactive visualization tool to display the results. Requires pyFLTK (homepage: https://pyfltk.sourceforge.io) and GL_image_display (homepage: https://github.com/dkogan/GL_image_display) It is often desired to compute dense stereo for lots of images in bulk. To make this go faster, this tool supports the -j JOBS option. This works just like in Make: the work will be parallelized among JOBS simultaneous processes. Unlike make, the JOBS value must be specified. ''' import sys import argparse import re import os def parse_args(): def positive_float(string): try: value = float(string) except: print(f"argument MUST be a positive floating-point number. Got '{string}'", file=sys.stderr) sys.exit(1) if value <= 0: print(f"argument MUST be a positive floating-point number. Got '{string}'", file=sys.stderr) sys.exit(1) return value def positive_int(string): try: value = int(string) except: print(f"argument MUST be a positive integer. Got '{string}'", file=sys.stderr) sys.exit(1) if value <= 0 or abs(value-float(string)) > 1e-6: print(f"argument MUST be a positive integer. Got '{string}'", file=sys.stderr) sys.exit(1) return value parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) ######## geometry and rectification system parameters parser.add_argument('--az-fov-deg', type=float, help='''The field of view in the azimuth direction, in degrees. There's no auto-detection at this time, so this argument is required (unless --already-rectified)''') parser.add_argument('--el-fov-deg', type=float, help='''The field of view in the elevation direction, in degrees. There's no auto-detection at this time, so this argument is required (unless --already-rectified)''') parser.add_argument('--az0-deg', default = None, type=float, help='''The azimuth center of the rectified images. "0" means "the horizontal center of the rectified system is the mean forward direction of the two cameras projected to lie perpendicular to the baseline". If omitted, we align the center of the rectified system with the center of the two cameras' views''') parser.add_argument('--el0-deg', default = 0, type=float, help='''The elevation center of the rectified system. "0" means "the vertical center of the rectified system lies along the mean forward direction of the two cameras" Defaults to 0.''') parser.add_argument('--pixels-per-deg', help='''The resolution of the rectified images. This is either a whitespace-less, comma-separated list of two values (az,el) or a single value to be applied to both axes. If a resolution of >0 is requested, the value is used as is. If a resolution of <0 is requested, we use this as a scale factor on the resolution of the first input image. For instance, to downsample by a factor of 2, pass -0.5. By default, we use -1 for both axes: the resolution of the input image at the center of the rectified system.''') parser.add_argument('--rectification', choices=('LENSMODEL_PINHOLE', 'LENSMODEL_LATLON'), default = 'LENSMODEL_LATLON', help='''The lens model to use for rectification. Currently two models are supported: LENSMODEL_LATLON (the default) and LENSMODEL_PINHOLE. Pinhole stereo works badly for wide lenses and suffers from varying angular resolution across the image. LENSMODEL_LATLON rectification uses a transverse equirectangular projection, and does not suffer from these effects. It is thus the recommended model''') parser.add_argument('--already-rectified', action='store_true', help='''If given, assume the given models and images already represent a rectified system. This will be checked, and the models will be used as-is if the checks pass''') ######## image pre-filtering parser.add_argument('--clahe', action='store_true', help='''If given, apply CLAHE equalization to the images prior to the stereo matching. If --already-rectified, we still apply this equalization, if requested. Requires --force-grayscale''') parser.add_argument('--force-grayscale', action='store_true', help='''If given, convert the images to grayscale prior to doing anything else with them. By default, read the images in their default format, and pass those posibly-color images to all the processing steps. Required if --clahe''') ######## --viz parser.add_argument('--viz', choices=('geometry', 'stereo'), default='', help='''If given, we visualize either the rectified geometry or the stereo results. If --viz geometry: we construct the rectified stereo system, but instead of continuing with the stereo processing, we render the geometry of the stereo world; the images are ignored in this mode. If --viz stereo: we launch an interactive graphical tool to examine the rectification and stereo matching results; the Fl_Gl_Image_Widget Python library must be available''') parser.add_argument('--axis-scale', type=float, help='''Used if --viz geometry. Scale for the camera axes. By default a reasonable default is chosen (see mrcal.show_geometry() for the logic)''') parser.add_argument('--title', type=str, default = None, help='''Used if --viz geometry. Title string for the plot''') parser.add_argument('--hardcopy', type=str, help='''Used if --viz geometry. Write the output to disk, instead of making an interactive plot. The output filename is given in the option''') parser.add_argument('--terminal', type=str, help=r'''Used if --viz geometry. The gnuplotlib terminal. The default is almost always right, so most people don't need this option''') parser.add_argument('--set', type=str, action='append', help='''Used if --viz geometry. Extra 'set' directives to pass to gnuplotlib. May be given multiple times''') parser.add_argument('--unset', type=str, action='append', help='''Used if --viz geometry. Extra 'unset' directives to pass to gnuplotlib. May be given multiple times''') ######## stereo processing parser.add_argument('--force', '-f', action='store_true', default=False, help='''By default existing files are not overwritten. Pass --force to overwrite them without complaint''') parser.add_argument('--outdir', default='.', type=lambda d: d if os.path.isdir(d) else \ parser.error(f"--outdir requires an existing directory as the arg, but got '{d}'"), help='''Directory to write the output into. If omitted, we user the current directory''') parser.add_argument('--tag', help='''String to use in the output filenames. Non-specific output filenames if omitted ''') parser.add_argument('--disparity-range', type=int, nargs=2, default=(0,100), help='''The disparity limits to use in the search, in pixels. Two integers are expected: MIN_DISPARITY MAX_DISPARITY. Completely arbitrarily, we default to MIN_DISPARITY=0 and MAX_DISPARITY=100''') parser.add_argument('--valid-intrinsics-region', action='store_true', help='''If given, annotate the image with its valid-intrinsics region. This will end up in the rectified images, and make it clear where successful matching shouldn't be expected''') parser.add_argument('--range-image-limits', type=positive_float, nargs=2, default=(1,1000), help='''The nearest,furthest range to encode in the range image. Defaults to 1,1000, arbitrarily''') parser.add_argument('--stereo-matcher', choices=( 'SGBM', 'ELAS' ), default = 'SGBM', help='''The stereo-matching method. By default we use the "SGBM" method from OpenCV. libelas isn't always available, and must be enabled at compile-time by setting USE_LIBELAS=1 during the build''') parser.add_argument('--sgbm-block-size', type=int, default = 5, help='''A parameter for the OpenCV SGBM matcher. If omitted, 5 is used''') parser.add_argument('--sgbm-p1', type=int, help='''A parameter for the OpenCV SGBM matcher. If omitted, the OpenCV default is used''') parser.add_argument('--sgbm-p2', type=int, help='''A parameter for the OpenCV SGBM matcher. If omitted, the OpenCV default is used''') parser.add_argument('--sgbm-disp12-max-diff', type=int, help='''A parameter for the OpenCV SGBM matcher. If omitted, the OpenCV default is used''') parser.add_argument('--sgbm-pre-filter-cap', type=int, help='''A parameter for the OpenCV SGBM matcher. If omitted, the OpenCV default is used''') parser.add_argument('--sgbm-uniqueness-ratio', type=int, help='''A parameter for the OpenCV SGBM matcher. If omitted, the OpenCV default is used''') parser.add_argument('--sgbm-speckle-window-size', type=int, help='''A parameter for the OpenCV SGBM matcher. If omitted, the OpenCV default is used''') parser.add_argument('--sgbm-speckle-range', type=int, help='''A parameter for the OpenCV SGBM matcher. If omitted, the OpenCV default is used''') parser.add_argument('--sgbm-mode', choices=('SGBM','HH','HH4','SGBM_3WAY'), help='''A parameter for the OpenCV SGBM matcher. Must be one of ('SGBM','HH','HH4','SGBM_3WAY'). If omitted, the OpenCV default (SGBM) is used''') parser.add_argument('--write-point-cloud', action='store_true', help='''If given, we write out the point cloud as a .ply file. Each point is reported in the reference coordinate system, colored with the nearest-neighbor color of the camera0 image. This is disabled by default because this is potentially a very large file''') parser.add_argument('--jobs', '-j', type=int, required=False, default=1, help='''parallelize the processing JOBS-ways. This is like Make, except you're required to explicitly specify a job count. This applies when processing multiple sets of images with the same set of models''') parser.add_argument('models', type=str, nargs = 2, help='''Camera models representing cameras used to capture the images. Both intrinsics and extrinsics are used''') parser.add_argument('images', type=str, nargs='*', help='''The image globs to use for the stereo. If omitted, we only write out the rectified models. If given, exactly two image globs must be given''') args = parser.parse_args() if not (len(args.images) == 0 or \ len(args.images) == 2): print("Argument-parsing error: exactly 0 or exactly 2 images should have been given", file=sys.stderr) sys.exit(1) if args.pixels_per_deg is None: args.pixels_per_deg = (-1, -1) else: try: l = [float(x) for x in args.pixels_per_deg.split(',')] if len(l) < 1 or len(l) > 2: raise for x in l: if x == 0: raise args.pixels_per_deg = l except: print("""Argument-parsing error: --pixels_per_deg requires "RESX,RESY" or "RESXY", where RES... is a value <0 or >0""", file=sys.stderr) sys.exit(1) if not args.already_rectified and \ (args.az_fov_deg is None or \ args.el_fov_deg is None ): print("""Argument-parsing error: --az-fov-deg and --el-fov-deg are required if not --already-rectified""", file=sys.stderr) sys.exit(1) if args.clahe and not args.force_grayscale: print("--clahe requires --force-grayscale", file=sys.stderr) sys.exit(1) return args args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README import numpy as np import numpysane as nps import glob import mrcal if args.stereo_matcher == 'ELAS': if not hasattr(mrcal, 'stereo_matching_libelas'): print("ERROR: the ELAS stereo matcher isn't available. libelas must be installed, and enabled at compile-time with USE_LIBELAS=1. Pass '--stereo-matcher SGBM' instead", file=sys.stderr) sys.exit(1) if args.viz == 'stereo': try: from fltk import * except: print("The visualizer needs the pyFLTK tool. See https://pyfltk.sourceforge.io", file=sys.stderr) sys.exit(1) try: from Fl_Gl_Image_Widget import * except: print("The visualizer needs the GL_image_display library. See https://github.com/dkogan/GL_image_display", file=sys.stderr) sys.exit(1) if len(args.pixels_per_deg) == 2: pixels_per_deg_az,pixels_per_deg_el = args.pixels_per_deg else: pixels_per_deg_az = pixels_per_deg_el = args.pixels_per_deg[0] if args.tag is not None: args.tag = re.sub('[^a-zA-Z0-9_+-]+', '_', args.tag) def openmodel(f): try: return mrcal.cameramodel(f) except Exception as e: print(f"Couldn't load camera model '{f}': {e}", file=sys.stderr) sys.exit(1) models = [openmodel(modelfilename) for modelfilename in args.models] if not args.already_rectified: models_rectified = \ mrcal.rectified_system(models, az_fov_deg = args.az_fov_deg, el_fov_deg = args.el_fov_deg, az0_deg = args.az0_deg, el0_deg = args.el0_deg, pixels_per_deg_az = pixels_per_deg_az, pixels_per_deg_el = pixels_per_deg_el, rectification_model = args.rectification) else: models_rectified = models mrcal.stereo._validate_models_rectified(models_rectified) Rt_cam0_rect0 = \ mrcal.compose_Rt( models [0].extrinsics_Rt_fromref(), models_rectified[0].extrinsics_Rt_toref() ) Rt_cam1_rect1 = \ mrcal.compose_Rt( models [1].extrinsics_Rt_fromref(), models_rectified[1].extrinsics_Rt_toref() ) if args.viz == 'geometry': # Display the geometry of the two cameras in the stereo pair, and of the # rectified system plot_options = dict(terminal = args.terminal, hardcopy = args.hardcopy, _set = args.set, unset = args.unset, wait = args.hardcopy is None) if args.title is not None: plot_options['title'] = args.title data_tuples, plot_options = \ mrcal.show_geometry( list(models) + list(models_rectified), cameranames = ( "camera0", "camera1", "camera0-rectified", "camera1-rectified" ), show_calobjects = False, return_plot_args = True, axis_scale = args.axis_scale, **plot_options) Nside = 8 model = models_rectified[0] w,h = model.imagersize() linspace_w = np.linspace(0,w-1, Nside+1) linspace_h = np.linspace(0,h-1, Nside+1) # shape (Nloop, 2) qloop = \ nps.transpose( nps.glue( nps.cat( linspace_w, 0*linspace_w), nps.cat( 0*linspace_h[1:] + w-1, linspace_h[1:]), nps.cat( linspace_w[-2::-1], 0*linspace_w[-2::-1] + h-1), nps.cat( 0*linspace_h[-2::-1], linspace_h[-2::-1]), axis=-1) ) # shape (Nloop,3): unit vectors in cam-local coords v = mrcal.unproject(np.ascontiguousarray(qloop), *model.intrinsics(), normalize = True) # Scale the vectors to a nice-looking length. This is intended to work with # the defaults to mrcal.show_geometry(). That function sets the right,down # axis lengths to baseline/3. Here I default to a bit less: baseline/4 baseline = \ nps.mag(mrcal.compose_Rt( models_rectified[1].extrinsics_Rt_fromref(), models_rectified[0].extrinsics_Rt_toref())[3,:]) v *= baseline/4 # shape (Nloop,3): ref-coord system points p = mrcal.transform_point_Rt(model.extrinsics_Rt_toref(), v) # shape (Nloop,2,3). Nloop-length different lines with 2 points in each one p = nps.xchg(nps.cat(p,p), -2,-3) p[:,1,:] = model.extrinsics_Rt_toref()[3,:] data_tuples.append( (p, dict(tuplesize = -3, _with = 'lines lt 1',))) import gnuplotlib as gp gp.plot(*data_tuples, **plot_options) sys.exit() def write_output_one(tag, outdir, force, func, filename): if tag is None: tag = '' else: tag = '-' + tag f,e = os.path.splitext(filename) filename = f"{outdir}/{f}{tag}{e}" if os.path.exists(filename) and not force: print(f"WARNING: '{filename}' already exists. Not overwriting this file. Pass -f to overwrite") return func(filename) print(f"Wrote '{filename}'") def write_output_all(args, models, images, image_filenames, models_rectified, images_rectified, disparity, disparity_scale, disparity_colored, ranges, ranges_colored, force_override = False): image_filenames_base = \ [os.path.splitext(os.path.split(f)[1])[0] for f in image_filenames] if not args.already_rectified: write_output_one(args.tag, args.outdir, args.force or force_override, lambda filename: models_rectified[0].write(filename), 'rectified0.cameramodel') write_output_one(args.tag, args.outdir, args.force or force_override, lambda filename: models_rectified[1].write(filename), 'rectified1.cameramodel') write_output_one(args.tag, args.outdir, args.force or force_override, lambda filename: mrcal.save_image(filename, images_rectified[0]), image_filenames_base[0] + '-rectified.png') write_output_one(args.tag, args.outdir, args.force or force_override, lambda filename: mrcal.save_image(filename, images_rectified[1]), image_filenames_base[1] + '-rectified.png') write_output_one(args.tag, args.outdir, args.force or force_override, lambda filename: \ mrcal.save_image(filename, disparity_colored), image_filenames_base[0] + '-disparity.png') write_output_one(args.tag, args.outdir, args.force or force_override, lambda filename: \ mrcal.save_image(filename, disparity.astype(np.uint16)), image_filenames_base[0] + f'-disparity-uint16-scale{disparity_scale}.png') write_output_one(args.tag, args.outdir, args.force or force_override, lambda filename: \ mrcal.save_image(filename, ranges_colored), image_filenames_base[0] + '-range.png') if not args.write_point_cloud: return # generate and output the point cloud, in the cam0 coord system p_rect0 = \ mrcal.stereo_unproject(disparity = None, models_rectified = models_rectified, ranges = ranges) Rt_ref_rect0 = models_rectified[0].extrinsics_Rt_toref() Rt_cam0_ref = models [0].extrinsics_Rt_fromref() # Point cloud in ref coordinates # shape (H,W,3) p_ref = mrcal.transform_point_Rt(Rt_ref_rect0, p_rect0) # shape (N,3) p_ref = nps.clump(p_ref, n=2) # I set each point color to the nearest-pixel color in the original # image. I only report those points that are in-bounds (they SHOULD # be, but I make sure) q_cam0 = mrcal.project(mrcal.transform_point_Rt(Rt_cam0_ref, p_ref), *models[0].intrinsics()) # Without this sometimes q_cam0 can get nan, and this throws ugly warnings i = np.isfinite(q_cam0) i = np.min(i, axis=-1) # qx or qx being nan means the whole q is nan p_ref = p_ref [i,:] q_cam0 = q_cam0[i,:] H,W = images[0].shape[:2] q_cam0_integer = (q_cam0 + 0.5).astype(int) i = \ (q_cam0_integer[:,0] >= 0) * \ (q_cam0_integer[:,1] >= 0) * \ (q_cam0_integer[:,0] < W) * \ (q_cam0_integer[:,1] < H) p_ref = p_ref[i] q_cam0_integer = q_cam0_integer[i] image0 = images[0] if len(image0.shape) == 2 and args.force_grayscale: # I have a grayscale image, but the user asked for it for the # purposes of stereo. I reload without asking for grayscale. If # the image was a color one, that would be useful here. image0 = mrcal.load_image(image_filenames[0]) # shape (N,) if grayscale or # (N,3) if bgr color color = image0[q_cam0_integer[:,1], q_cam0_integer[:,0]] write_output_one(args.tag, args.outdir, args.force or force_override, lambda filename: \ mrcal.write_point_cloud_as_ply(filename, p_ref, color = color, binary = True), image_filenames_base[0] + '-points.ply') if len(args.images) == 0: # No images are given. Just write out the rectified models write_output_one(args.tag, args.outdir, args.force, lambda filename: models_rectified[0].write(filename), 'rectified0.cameramodel') write_output_one(args.tag, args.outdir, args.force, lambda filename: models_rectified[1].write(filename), 'rectified1.cameramodel') sys.exit(0) if not args.already_rectified: rectification_maps = mrcal.rectification_maps(models, models_rectified) image_filenames_all = [sorted(glob.glob(os.path.expanduser(g))) for g in args.images] if len(image_filenames_all[0]) != len(image_filenames_all[1]): print(f"First glob matches {len(image_filenames_all[0])} files, but the second glob matches {len(image_filenames_all[1])} files. These must be identical", file=sys.stderr) sys.exit(1) Nimages = len(image_filenames_all[0]) if Nimages == 0: print("The given globs matched 0 images. Nothing to do", file=sys.stderr) sys.exit(1) if args.viz == 'stereo' and Nimages > 1: print(f"The given globs matched {Nimages} images. But '--viz stereo' was given, so exactly ONE set of images is expected", file=sys.stderr) sys.exit(1) if args.clahe or args.stereo_matcher == 'SGBM': import cv2 if args.clahe: clahe = cv2.createCLAHE() clahe.setClipLimit(8) kwargs_load_image = dict() if args.force_grayscale: kwargs_load_image['bits_per_pixel'] = 8 kwargs_load_image['channels'] = 1 # Done with all the preliminaries. Run the stereo matching disparity_min,disparity_max = args.disparity_range if args.stereo_matcher == 'SGBM': # This is a hard-coded property of the OpenCV StereoSGBM implementation disparity_scale = 16 # round to nearest multiple of disparity_scale. The OpenCV StereoSGBM # implementation requires this num_disparities = disparity_max - disparity_min num_disparities = disparity_scale*round(num_disparities/disparity_scale) # I only add non-default args. StereoSGBM_create() doesn't like being given # None args kwargs_sgbm = dict() if args.sgbm_p1 is not None: kwargs_sgbm['P1'] = args.sgbm_p1 if args.sgbm_p2 is not None: kwargs_sgbm['P2'] = args.sgbm_p2 if args.sgbm_disp12_max_diff is not None: kwargs_sgbm['disp12MaxDiff'] = args.sgbm_disp12_max_diff if args.sgbm_uniqueness_ratio is not None: kwargs_sgbm['uniquenessRatio'] = args.sgbm_uniqueness_ratio if args.sgbm_speckle_window_size is not None: kwargs_sgbm['speckleWindowSize'] = args.sgbm_speckle_window_size if args.sgbm_speckle_range is not None: kwargs_sgbm['speckleRange'] = args.sgbm_speckle_range if args.sgbm_mode is not None: if args.sgbm_mode == 'SGBM': kwargs_sgbm['mode'] = cv2.StereoSGBM_MODE_SGBM elif args.sgbm_mode == 'HH': kwargs_sgbm['mode'] = cv2.StereoSGBM_MODE_HH elif args.sgbm_mode == 'HH4': kwargs_sgbm['mode'] = cv2.StereoSGBM_MODE_HH4 elif args.sgbm_mode == 'SGBM_3WAY': kwargs_sgbm['mode'] = cv2.StereoSGBM_MODE_SGBM_3WAY else: raise Exception("arg-parsing error. This is a bug. Please report") # blocksize is required, so I always pass it. There's a default set in # the argument parser, so this is never None kwargs_sgbm['blockSize'] = args.sgbm_block_size stereo_sgbm = \ cv2.StereoSGBM_create(minDisparity = disparity_min, numDisparities = num_disparities, **kwargs_sgbm) elif args.stereo_matcher == 'ELAS': disparity_scale = 1 else: raise Exception("Getting here is a bug") def process(i_image): image_filenames=(image_filenames_all[0][i_image], image_filenames_all[1][i_image]) print(f"Processing {os.path.split(image_filenames[0])[1]} and {os.path.split(image_filenames[1])[1]}") images = [mrcal.load_image(f, **kwargs_load_image) for f in image_filenames] # This doesn't really matter: I don't use the input imagersize. But a # mismatch suggests the user probably messed up, and it would save them time # to yell at them imagersize_image = np.array((images[0].shape[1], images[0].shape[0])) imagersize_model = models[0].imagersize() if np.any(imagersize_image - imagersize_model): print(f"Image '{image_filenames[0]}' dimensions {imagersize_image} don't match the model '{args.models[0]}' dimensions {imagersize_model}", file=sys.stderr) return False imagersize_image = np.array((images[1].shape[1], images[1].shape[0])) imagersize_model = models[1].imagersize() if np.any(imagersize_image - imagersize_model): print(f"Image '{image_filenames[1]}' dimensions {imagersize_image} don't match the model '{args.models[1]}' dimensions {imagersize_model}", file=sys.stderr) return False if args.clahe: images = [ clahe.apply(image) for image in images ] if len(images[0].shape) == 3: if args.stereo_matcher == 'ELAS': print("The ELAS matcher requires grayscale images. Pass --force-grayscale", file=sys.stderr) return False if args.valid_intrinsics_region: for i in range(2): mrcal.annotate_image__valid_intrinsics_region(images[i], models[i]) if not args.already_rectified: images_rectified = [mrcal.transform_image(images[i], rectification_maps[i]) \ for i in range(2)] else: images_rectified = images if args.stereo_matcher == 'SGBM': # opencv barfs if I give it a color image and a monochrome image, so I # convert if len(images_rectified[0].shape) == 2 and \ len(images_rectified[1].shape) == 3: disparity = stereo_sgbm.compute(images_rectified[0], cv2.cvtColor(images_rectified[1], cv2.COLOR_BGR2GRAY)) elif len(images_rectified[0].shape) == 3 and \ len(images_rectified[1].shape) == 2: disparity = stereo_sgbm.compute(cv2.cvtColor(images_rectified[0], cv2.COLOR_BGR2GRAY), images_rectified[1]) else: disparity = stereo_sgbm.compute(*images_rectified) elif args.stereo_matcher == 'ELAS': disparities = mrcal.stereo_matching_libelas(*images_rectified, disparity_min = disparity_min, disparity_max = disparity_max) disparity = disparities[0] disparity_colored = mrcal.apply_color_map(disparity, a_min = disparity_min*disparity_scale, a_max = disparity_max*disparity_scale) ranges = mrcal.stereo_range( disparity, models_rectified, disparity_scale = disparity_scale, disparity_min = disparity_min) ranges_colored = mrcal.apply_color_map(ranges, a_min = args.range_image_limits[0], a_max = args.range_image_limits[1],) if args.viz == 'stereo': # Earlier I confirmed that in this path Nimages==1 gui_stereo(images, image_filenames, images_rectified, disparity, disparity_colored, ranges, ranges_colored) else: write_output_all(args, models, images, image_filenames, models_rectified, images_rectified, disparity, disparity_scale, disparity_colored, ranges, ranges_colored) return True def gui_stereo(images, image_filenames, images_rectified, disparity, disparity_colored, ranges, ranges_colored): # Done with all the processing. Invoke the visualizer! UI_usage_message = r'''Usage: Left mouse button click/drag: pan Mouse wheel up/down/left/right: pan Ctrl-mouse wheel up/down: zoom 'u': reset view: zoom out, pan to the center 'd': show a colorized disparity image (default) 'r': show a colorized range image Right mouse button click: examine stereo at pixel TAB: transpose windows ''' def set_status(string, q_rect = None, q_input0 = None, q_input1 = None): # None means "use previous" if string is not None: set_status.string = string else: if not hasattr(set_status, 'string'): set_status.string = '' if q_rect is not None: set_status.qstring = \ f"q_rectified0 = {q_rect[0]:.1f},{q_rect[1]:.1f}\n" if q_input0 is not None: set_status.qstring += f"q_input_cam0 = {q_input0[0]:.1f},{q_input0[1]:.1f}\n" if q_input1 is not None: set_status.qstring += f"q_input_cam1 = {q_input1[0]:.1f},{q_input1[1]:.1f}\n" set_status.qstring += "\n" else: if not hasattr(set_status, 'qstring'): set_status.qstring = 'No current pixel\n\n' widget_status.value(UI_usage_message + "\n" + set_status.qstring + set_status.string) def write_output_interactive(widget): # cursor-setting needs threading. I don't bother with it yet # window.cursor(FL_CURSOR_WAIT) write_output_all(args, models, images, image_filenames, models_rectified, images_rectified, disparity, disparity_scale, disparity_colored, ranges, ranges_colored, force_override = True) # window.cursor(FL_CURSOR_DEFAULT) def process_tab(): x_image1 = widget_image1.x() y_image1 = widget_image1.y() x_disparity = widget_result.x() y_disparity = widget_result.y() widget_image1.position(x_disparity, y_disparity) widget_result.position(x_image1, y_image1) class Fl_Gl_Image_Widget_Derived(Fl_Gl_Image_Widget): def set_panzoom(self, x_centerpixel, y_centerpixel, visible_width_pixels): r'''Pan/zoom the image This is an override of the function to do this: any request to pan/zoom the widget will come here first. I dispatch any pan/zoom commands to all the widgets, so that they all work in unison. visible_width_pixels < 0 means: this is the redirected call; just call the base class ''' if visible_width_pixels < 0: return super().set_panzoom(x_centerpixel, y_centerpixel, -visible_width_pixels) # All the widgets should pan/zoom together result = \ all( w.set_panzoom(x_centerpixel, y_centerpixel, -visible_width_pixels) \ for w in (widget_image0, widget_image1, widget_result) ) # Switch back to THIS widget self.make_current() return result def set_cross_at(self, q, no_vertical = False): if q is None: return \ self.set_lines() x,y = q W,H = models_rectified[0].imagersize() if no_vertical: points = np.array( ((( -0.5, y), (W-0.5, y),),), dtype=np.float32) color_rgb = np.array((1,0,0), dtype=np.float32) else: points = np.array( ((( -0.5, y), (W-0.5, y)), ((x, -0.5), (x, H-0.5))), dtype=np.float32) color_rgb = np.array((0,0,1), dtype=np.float32) return \ self.set_lines( dict(points = points, color_rgb = color_rgb )) def handle(self, event): if event == FL_PUSH: if Fl.event_button() != FL_RIGHT_MOUSE: return super().handle(event) try: q0_rectified = \ np.array( self.map_pixel_image_from_viewport( (Fl.event_x(),Fl.event_y()), ), dtype=float ) except: set_status("Error converting pixel coordinates") widget_image0.set_cross_at(None) widget_image1.set_cross_at(None) widget_result.set_cross_at(None) return super().handle(event) if self is widget_image1: set_status("Please click in the left or disparity windows") widget_image0.set_cross_at(q0_rectified, no_vertical = True) widget_image1.set_cross_at(q0_rectified, no_vertical = True) widget_result.set_cross_at(q0_rectified, no_vertical = True) return super().handle(event) if not (q0_rectified[0] >= -0.5 and q0_rectified[0] <= images_rectified[0].shape[1]-0.5 and \ q0_rectified[1] >= -0.5 and q0_rectified[1] <= images_rectified[0].shape[0]-0.5): set_status("Out of bounds") widget_image0.set_cross_at(q0_rectified, no_vertical = True) widget_image1.set_cross_at(q0_rectified, no_vertical = True) widget_result.set_cross_at(q0_rectified, no_vertical = True) return super().handle(event) d = disparity[int(round(q0_rectified[-1])), int(round(q0_rectified[-2]))] if d < disparity_min*disparity_scale: set_status("No valid disparity at the clicked location") widget_image0.set_cross_at(q0_rectified) widget_image1.set_cross_at(q0_rectified, no_vertical = True) widget_result.set_cross_at(q0_rectified) return super().handle(event) if d == disparity_min*disparity_scale: set_status("Disparity: 0pixels\n" + "range: infinity\n") widget_image0.set_cross_at(q0_rectified) widget_image1.set_cross_at(q0_rectified) widget_result.set_cross_at(q0_rectified) return super().handle(event) widget_image0.set_cross_at(q0_rectified) widget_image1.set_cross_at(q0_rectified - np.array((d/disparity_scale, 0))) widget_result.set_cross_at(q0_rectified) delta = 1e-3 _range = mrcal.stereo_range( d, models_rectified, disparity_scale = disparity_scale, disparity_min = disparity_min, qrect0 = q0_rectified) _range_d = mrcal.stereo_range( d + delta*disparity_scale, models_rectified, disparity_scale = disparity_scale, disparity_min = disparity_min, qrect0 = q0_rectified) drange_ddisparity = np.abs(_range_d - _range) / delta # mrcal-triangulate tool: guts into a function. Call those # guts here, and display them in the window set_status(f"Disparity: {d/disparity_scale:.2f}pixels\n" + f"range: {_range:.2f}m\n" + f"drange/ddisparity: {drange_ddisparity:.5f}m/pixel") if 0: p0_rectified = \ mrcal.unproject(q0_rectified, *models_rectified[0].intrinsics(), normalize = True) * _range p0 = mrcal.transform_point_Rt( Rt_cam0_rect0, p0_rectified ) p1 = mrcal.transform_point_Rt( mrcal.compose_Rt( models[1].extrinsics_Rt_fromref(), models[0].extrinsics_Rt_toref()), p0 ) q0 = mrcal.project(p0, *models[0].intrinsics()) pt = \ mrcal.triangulate( nps.cat(q0, q1), models, stabilize_coords = True ) print(f"range = {_range:.2f}, {nps.mag(pt):.2f}") return 0 if event == FL_KEYDOWN: if Fl.event_key() == fltk.FL_Tab: process_tab() return 1 if Fl.event_key() == ord('d') or \ Fl.event_key() == ord('D'): widget_result. \ update_image(decimation_level = 0, image_data = disparity_colored) return 1 if Fl.event_key() == ord('r') or \ Fl.event_key() == ord('R'): widget_result. \ update_image(decimation_level = 0, image_data = ranges_colored) return 1 if event == FL_MOVE: q_rect = None q_input0 = None q_input1 = None try: q_rect = self.map_pixel_image_from_viewport( (Fl.event_x(),Fl.event_y()), ) except: pass if q_rect is not None: q_input0 = \ mrcal.project( mrcal.transform_point_Rt( Rt_cam0_rect0, mrcal.unproject(q_rect, *models_rectified[0].intrinsics())), *models[0].intrinsics()) q_input1 = \ mrcal.project( mrcal.transform_point_Rt( Rt_cam1_rect1, mrcal.unproject(q_rect, *models_rectified[1].intrinsics())), *models[1].intrinsics()) set_status(string = None, # keep old string q_rect = q_rect, q_input0 = q_input0, q_input1 = q_input1) # fall through to let parent handlers run return super().handle(event) class Fl_Multiline_Output_pass_keys(Fl_Multiline_Output): def handle(self, event): if event == FL_KEYDOWN: if Fl.event_key() == fltk.FL_Tab: process_tab() return 1 if Fl.event_key() == fltk.FL_Escape: window.hide() return super().handle(event) class Fl_Button_pass_keys(Fl_Button): def handle(self, event): if event == FL_KEYDOWN: if Fl.event_key() == fltk.FL_Tab: process_tab() return 1 if Fl.event_key() == fltk.FL_Escape: window.hide() return super().handle(event) window = Fl_Window(800, 600, "mrcal-stereo") widget_image0 = Fl_Gl_Image_Widget_Derived( 0, 0, 400,300) widget_image1 = Fl_Gl_Image_Widget_Derived( 0, 300, 400,300) widget_result = Fl_Gl_Image_Widget_Derived( 400, 0, 400,300) group_status = Fl_Group( 400,300, 400,300) widget_status = Fl_Multiline_Output_pass_keys(400,300, 400,300-30) widget_dowrite = Fl_Button_pass_keys( 400,300+300-30, 400,30, f'Write output to "{args.outdir}" (will overwrite)') widget_dowrite.callback(write_output_interactive) group_status.resizable(widget_status) group_status.end() set_status('') window.resizable(window) window.end() window.show() widget_image0. \ update_image(decimation_level = 0, image_data = images_rectified[0]) widget_image1. \ update_image(decimation_level = 0, image_data = images_rectified[1]) widget_result. \ update_image(decimation_level = 0, image_data = disparity_colored) Fl.run() sys.exit(0) if Nimages == 1 or args.jobs <= 1: # Serial path. Useful for debugging or if I only have one set of images for i in range(Nimages): process(i) sys.exit(0) ####### Parallel path import multiprocessing import signal # I do the same thing in mrcal-reproject-image. Please consolidate # # weird business to handle weird signal handling in multiprocessing. I want # things like the user hitting C-c to work properly. So I ignore SIGINT for the # children. And I want the parent's blocking wait for results to respond to # signals. Which means map_async() instead of map(), and wait(big number) # instead of wait() signal_handler_sigint = signal.signal(signal.SIGINT, signal.SIG_IGN) signal.signal(signal.SIGINT, signal_handler_sigint) pool = multiprocessing.Pool(args.jobs) try: mapresult = pool.map_async(process, np.arange(Nimages)) # like wait(), but will barf if something goes wrong. I don't actually care # about the results mapresult.get(1000000) except: pool.terminate() pool.close() pool.join() mrcal-2.4.1/mrcal-to-cahvor000077500000000000000000000070071456301662300155520ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Converts a cameramodel to the cahvor file format SYNOPSIS $ mrcal-to-cahvor model1.cameramodel model2.cameramodel Wrote model1.cahvor Wrote model2.cahvor File formats supported by mrcal are described at http://mrcal.secretsauce.net/cameramodels.html#cameramodel-file-formats This tool converts the given model(s) to the cahvor file format. No changes to the content are made; this is purely a format converter (the mrcal-convert-lensmodel tool fits different lens models instead). Model filenames are given on the commandline. Output is written to the same directory, with the same filename, but with a .cahvor extension. If the model is omitted or given as "-", the input is read from standard input, and the output is written to standard output ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--force', '-f', action='store_true', default=False, help='''By default existing files are not overwritten. Pass --force to overwrite them without complaint''') parser.add_argument('--outdir', required=False, type=lambda d: d if os.path.isdir(d) else \ parser.error("--outdir requires an existing directory as the arg, but got '{}'".format(d)), help='''Directory to write the output models into. If omitted, we write the output models to the same directory as the input models''') parser.add_argument('model', default=['-'], nargs='*', type=str, help='''Input camera model''') return parser.parse_args() args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README Nstdin = sum(1 for m in args.model if m=='-') if Nstdin > 1: print(f"At most one model can be read from standard input ('-'), but I got {Nstdin}", file=sys.stderr) sys.exit(1) import mrcal for model in args.model: if model == '-': try: m = mrcal.cameramodel(model) except KeyboardInterrupt: sys.exit(1) m.write(sys.stdout, cahvor = True) else: base,extension = os.path.splitext(model) if extension.lower() == '.cahvor': print("Input file is already in the cahvor format (judging from the filename). Doing nothing", file=sys.stderr) sys.exit(0) if args.outdir is not None: base = args.outdir + '/' + os.path.split(base)[1] filename_out = base + '.cahvor' if not args.force and os.path.exists(filename_out): print(f"Target model '{filename_out}' already exists. Doing nothing with this model. Pass -f to overwrite", file=sys.stderr) else: m = mrcal.cameramodel(model) m.write(filename_out) print("Wrote " + filename_out) mrcal-2.4.1/mrcal-to-kalibr000077500000000000000000000167001456301662300155340ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Converts cameramodel(s) to the file format used by kalibr SYNOPSIS $ mrcal-to-kalibr model1.cameramodel model2.cameramodel > model.yaml [model.yaml is now a kalibr model describing the two cameras] File formats supported by mrcal are described at http://mrcal.secretsauce.net/cameramodels.html#cameramodel-file-formats This tool converts the given model(s) to the .yaml format used by kalibr. No changes to the content are made; this is purely a format converter (the mrcal-convert-lensmodel tool fits different lens models instead). Unlike mrcal .cameramodel files where one camera is described by one file, the .yaml files used by kalibr are intended to describe multiple cameras. This format conversion tool will write out a single kalibr .yaml model containing ALL the given models. The names of the models in the kalibr data will be "cam0", "cam1", ... Since we always write out one kalibr model and since we don't know what it should be called, the output of this tool always goes to standard output. If the model is omitted or given as "-", the input is read from standard input, and only the one input model is processed. By default we set the extrinsics of camera-0 as they appear in the input: the reference coordinate system is set to the previous" camera from camera-0. If we want to force camera-0 to have an identity transform, pass --cam0-at-reference. The kalibr format is described at https://github.com/ethz-asl/kalibr/wiki/Yaml-formats At this time we only support - LENSMODEL_PINHOLE - LENSMODEL_OPENCV4 - LENSMODEL_CAHVOR (experimental) - LENSMODEL_CAHVORE (experimental) which corresponds to camera_model == 'pinhole' and distortion_model in ('radtan','none') ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--cam0-at-reference', action='store_true', default=False, help='''By default we set the extrinsics of camera-0 as they appear in the input. If we want to force camera-0 to have an identity transform, pass --cam0-at-reference. Usually this will be the case anyway in the input data, but this option makes sure''') parser.add_argument('model', default=['-'], nargs='*', type=str, help='''Input camera model''') return parser.parse_args() args = parse_args() # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README Nstdin = sum(1 for m in args.model if m=='-') if Nstdin > 1: print(f"At most one model can be read from standard input ('-'), but I got {Nstdin}", file=sys.stderr) sys.exit(1) import mrcal import mrcal.cahvor import numpy as np import numpysane as nps Rt_ref_camprev = None # stolen from mrcal-to-kalibr. Please consolidate def Rt_is_identity(Rt): cos_th = (np.trace(Rt[:3,:]) - 1.) / 2. # cos_th ~ 1 - x^2/2 th_sq = (1 - cos_th)*2. norm2_t = nps.norm2(Rt[3,:]) return norm2_t < 1e-12 and th_sq < 1e-12 def convert_one(i, model_filename): global Rt_ref_camprev model = mrcal.cameramodel(model_filename) lensmodel,intrinsics = model.intrinsics() lensmodel_type = re.match('LENSMODEL_[^_]*',lensmodel).group(0) imagersize = model.imagersize() Rt_cam_ref = model.extrinsics_Rt_fromref() if Rt_ref_camprev is not None: Rt_cam_camprev = mrcal.compose_Rt(Rt_cam_ref, Rt_ref_camprev) else: # This is the first camera. What do we use as our reference? if args.cam0_at_reference: Rt_cam_camprev = mrcal.identity_Rt() else: # By default the "prev cam" from cam0 is the reference Rt_cam_camprev = Rt_cam_ref Rt_ref_camprev = mrcal.invert_Rt(Rt_cam_ref) # for the next one lensmodel_known = set(('LENSMODEL_PINHOLE','LENSMODEL_OPENCV4', 'LENSMODEL_CAHVOR','LENSMODEL_CAHVORE'),) if not lensmodel_type in lensmodel_known: print(f"ERROR: kalibr only supports {lensmodel_known}, but '{model_filename}' uses {lensmodel_type}", file=sys.stderr) sys.exit(1) if lensmodel_type == 'LENSMODEL_OPENCV4': camera_model = 'pinhole' intrinsics = repr(list(intrinsics[:4])) distortion_model = 'radtan' distortion_coeffs = repr(list(intrinsics[4:])) cahvore_linearity = None elif lensmodel_type == 'LENSMODEL_PINHOLE': camera_model = 'pinhole' intrinsics = repr(list(intrinsics[:4])) distortion_model = 'none' distortion_coeffs = repr(list(intrinsics[4:])) cahvore_linearity = None else: # cahvor(e) distortion_model = None distortion_coeffs = None model_identity_extrinsics = mrcal.cameramodel(model) model_identity_extrinsics.extrinsics_Rt_fromref(mrcal.identity_Rt()) x = mrcal.cahvor._deconstruct_model(model_identity_extrinsics) if lensmodel_type == 'LENSMODEL_CAHVOR': camera_model = 'cahvor' intrinsics = repr(list(x['C']) + list(x['A']) + list(x['H']) + list(x['V']) + list(x['O']) + list(x['R'])) cahvore_linearity = None elif lensmodel_type == 'LENSMODEL_CAHVORE': camera_model = 'cahvore' intrinsics = repr(list(x['C']) + list(x['A']) + list(x['H']) + list(x['V']) + list(x['O']) + list(x['R']) + list(x['E'])) cahvore_linearity = mrcal.lensmodel_metadata_and_config(lensmodel)['linearity'] else: raise Exception("Getting here is a bug") # Identity transforms on the first camera are allowed to omit T_cn_cnm1 if i==0 and Rt_is_identity(Rt_cam_camprev): T_cn_cnm1 = None else: T_cn_cnm1 = np.eye(4, dtype=float) T_cn_cnm1[:3,:3] = Rt_cam_camprev[:3,:] T_cn_cnm1[:3, 3] = Rt_cam_camprev[ 3,:] return \ fr'''cam{i}: camera_model: {camera_model} intrinsics: {intrinsics}''' + \ (rf''' distortion_model: {distortion_model} distortion_coeffs: {distortion_coeffs}''' if distortion_model is not None else '') + \ (rf''' cahvore_linearity: {cahvore_linearity}''' if cahvore_linearity is not None else '') + \ (rf''' T_cn_cnm1: - {repr(list(T_cn_cnm1[0,:]))} - {repr(list(T_cn_cnm1[1,:]))} - {repr(list(T_cn_cnm1[2,:]))} - {repr(list(T_cn_cnm1[3,:]))}''' if T_cn_cnm1 is not None else '') + \ rf''' resolution: {repr(list(imagersize))} ''' yaml = ''.join(convert_one(i,model) for i,model in enumerate(args.model)) print(yaml) mrcal-2.4.1/mrcal-triangulate000077500000000000000000001121231456301662300161630ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Triangulate a feature in a pair of images to report a range SYNOPSIS $ mrcal-triangulate --range-estimate 870 left.cameramodel right.cameramodel left.jpg right.jpg 1234 2234 ## Feature [1234., 2234.] in the left image corresponds to [2917.9 1772.6] at 870.0m ## Feature match found at [2916.51891391 1771.86593517] ## q1 - q1_perfect_at_range = [-1.43873946 -0.76196924] ## Range: 677.699 m (error: -192.301 m) ## Reprojection error between triangulated point and q0: [5.62522473e-10 3.59364094e-09]pixels ## Observed-pixel range sensitivity: 103.641m/pixel (q1). Worst direction: [1. 0.]. Linearized correction: 1.855 pixels ## Calibration yaw sensitivity: -3760.702m/deg. Linearized correction: -0.051 degrees of yaw ## Calibration pitch sensitivity: 0.059m/deg. ## Calibration translation sensitivity: 319.484m/m. Worst direction: [1 0 0]. ## Linearized correction: 0.602 meters of translation ## Optimized yaw correction = -0.03983 degrees ## Optimized pitch correction = 0.03255 degrees ## Optimized relative yaw (1 <- 0): -1.40137 degrees Given a pair of images, a pair of camera models and a feature coordinate in the first image, finds the corresponding feature in the second image, and reports the range. This is similar to the stereo processing of a single pixel, but reports much more diagnostic information than stereo tools do. This is useful to evaluate ranging results. ''' import sys import argparse import re import os def parse_args(): def positive_float(string): try: value = float(string) except: print(f"argument MUST be a positive floating-point number. Got '{string}'", file=sys.stderr) sys.exit(1) if value <= 0: print(f"argument MUST be a positive floating-point number. Got '{string}'", file=sys.stderr) sys.exit(1) return value def positive_int(string): try: value = int(string) except: print(f"argument MUST be a positive integer. Got '{string}'", file=sys.stderr) sys.exit(1) if value <= 0 or abs(value-float(string)) > 1e-6: print(f"argument MUST be a positive integer. Got '{string}'", file=sys.stderr) sys.exit(1) return value parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--make-corrected-model1', action='store_true', help='''If given, we assume the --range-estimate is correct, and output to standard output a rotated camera1 to produce this range''') parser.add_argument('--template-size', type=positive_int, nargs=2, default = (13,13), help='''The size of the template used for feature matching, in pixel coordinates of the second image. Two arguments are required: width height. This is passed directly to mrcal.match_feature(). We default to 13x13''') parser.add_argument('--search-radius', type=positive_int, default = 20, help='''How far the feature-matching routine should search, in pixel coordinates of the second image. This should be larger if the range estimate is poor, especially, at near ranges. This is passed directly to mrcal.match_feature(). We default to 20 pixels''') parser.add_argument('--range-estimate', type=positive_float, default = 50, help='''Initial estimate of the range of the observed feature. This is used for the initial guess in the feature-matching. If omitted, I pick 50m, completely arbitrarily''') parser.add_argument('--plane-n', type=float, nargs=3, help='''If given, assume that we're looking at a plane in space, and take this into account when matching the template. The normal vector to this plane is given here, in camera-0 coordinates. The normal does not need to be normalized; any scaling is compensated in planed. The plane is all points p such that inner(p,planen) = planed''') parser.add_argument('--plane-d', type=float, help='''If given, assume that we're looking at a plane in space, and take this into account when matching the template. The distance-along-the-normal to the plane, in from-camera coordinates is given here. The plane is all points p such that inner(p,planen) = planed''') parser.add_argument('--q-calibration-stdev', type = float, help='''The uncertainty of the point observations at calibration time. If given, we report the analytically-computed effects of this noise. If a value <0 is passed-in, we infer the calibration-time noise from the optimal calibration-time residuals''') parser.add_argument('--q-observation-stdev', type = float, help='''The uncertainty of the point observations at observation time. If given, we report the analytically-computed effects of this noise.''') parser.add_argument('--q-observation-stdev-correlation', type = float, default = 0.0, help='''By default, the noise in the observation-time pixel observations is assumed independent. This isn't entirely realistic: observations of the same feature in multiple cameras originate from an imager correlation operation, so they will have some amount of correlation. If given, this argument specifies how much correlation. This is a value in [0,1] scaling the stdev. 0 means "independent" (the default). 1.0 means "100%% correlated".''') parser.add_argument('--stabilize-coords', '--stabilize', action = 'store_true', help='''If propagating calibration-time noise (--q-calibration-stdev != 0), we report the uncertainty ellipse in a stabilized coordinate system, compensating for the camera-0 coord system motion''') parser.add_argument('--method', choices=( 'geometric', 'lindstrom', 'leecivera-l1', 'leecivera-linf', 'leecivera-mid2', 'leecivera-wmid2' ), default = 'leecivera-mid2', help='''The triangulation method. By default we use the "Mid2" method from Lee-Civera's paper''') parser.add_argument('--corr-floor', type=float, default=0.9, help='''This is used to reject mrcal.match_feature() results. The default is 0.9: accept only very good matches. A lower threshold may still result in usable matches, but do interactively check the feature-matcher results by passing "--viz match"''') parser.add_argument('--viz', choices=('match', 'uncertainty'), help='''If given, we visualize either the feature-matcher results ("--viz match") or the uncertainty ellipse(s) ("--viz uncertainty"). By default, this produces an interactive gnuplot window. The feature-match visualization shows 2 overlaid images: the larger image being searched and the transformed template, placed at its best-fitting location. Each individual image can be hidden/shown by clicking on its legend in the top-right of the plot. It's generally most useful to show/hide the template to visually verify the resulting alignment.''') parser.add_argument('--title', type=str, default = None, help='''Title string for the --viz plot. Overrides the default title. Exclusive with --extratitle''') parser.add_argument('--extratitle', type=str, default = None, help='''Additional string for the --viz plot to append to the default title. Exclusive with --title''') parser.add_argument('--hardcopy', type=str, help='''Write the --viz output to disk, instead of an interactive plot''') parser.add_argument('--terminal', type=str, help=r'''The gnuplotlib terminal used in --viz. The default is good almost always, so most people don't need this option''') parser.add_argument('--set', type=str, action='append', help='''Extra 'set' directives to gnuplotlib for --viz. Can be given multiple times''') parser.add_argument('--unset', type=str, action='append', help='''Extra 'unset' directives to gnuplotlib --viz. Can be given multiple times''') parser.add_argument('--clahe', action='store_true', help='''If given, apply CLAHE equalization to the images prior to the matching''') parser.add_argument('models', type=str, nargs = 2, help='''Camera models for the images. Both intrinsics and extrinsics are used''') parser.add_argument('images_and_features', type=str, nargs=4, help='''The images and/or feature pixes coordinates to use for the triangulation. This is either IMAGE0 IMAGE1 FEATURE0X FEATURE0Y or FEATURE0X FEATURE0Y FEATURE1X FEATURE1Y. If images are given, the given pixel is a feature in image0, and we search for the corresponding feature in image1.''') args = parser.parse_args() if args.viz is None: args.viz = '' if args.title is not None and \ args.extratitle is not None: print("--title and --extratitle are exclusive", file=sys.stderr) sys.exit(1) return args args = parse_args() def float_or_none(s): try: f = float(s) except: f = None return f features = [float_or_none(s) for s in args.images_and_features] if (args.plane_n is None and args.plane_d is not None) or \ (args.plane_n is not None and args.plane_d is None): print("--plane-n and --plane-d should both be given or neither should be", file=sys.stderr) sys.exit(1) # arg-parsing is done before the imports so that --help works without building # stuff, so that I can generate the manpages and README import numpy as np if all(type(x) is float for x in features): q0 = np.array(features[:2], dtype=float) q1 = np.array(features[2:], dtype=float) images = None elif all(type(x) is float for x in features[2:]): q0 = np.array(features[2:], dtype=float) q1 = None images = args.images_and_features[:2] else: print(f"Need exactly 4 positional arguments: either IMAGE0 IMAGE1 FEATURE0X FEATURE0Y or FEATURE0X FEATURE0Y FEATURE1X FEATURE1Y", file=sys.stderr) sys.exit(1) import numpysane as nps import mrcal import mrcal.utils import scipy.optimize import time if args.method == 'geometric': method = mrcal.triangulate_geometric elif args.method == 'lindstrom': method = mrcal.triangulate_lindstrom elif args.method == 'leecivera-l1': method = mrcal.triangulate_leecivera_l1 elif args.method == 'leecivera-linf': method = mrcal.triangulate_leecivera_linf elif args.method == 'leecivera-mid2': method = mrcal.triangulate_leecivera_mid2 elif args.method == 'leecivera-wmid2': method = mrcal.triangulate_leecivera_wmid2 else: raise Exception("Getting here is a bug") def compute_H10_planes(models, q0, v0, plane_n, plane_d): r'''Report a homography for two cameras observing a point on a plane v0 is assumed normalized''' def get_R_abn(n): r'''Return a valid rotation matrix with the given n as the last column n is assumed to be a normal vector: nps.norm2(n) = 1 Returns a rotation matrix where the 3rd column is the given vector n. The first two vectors are arbitrary, but are guaranteed to produce a valid rotation: RtR = I, det(R) = 1 ''' # arbitrary, but can't be exactly n a = np.array((1., 0, 0, )) proj = nps.inner(a, n) if abs(proj) > 0.8: # Any other orthogonal vector will do. If this projection was > # 0.8, I'm guaranteed that all others will be smaller a = np.array((0, 1., 0, )) proj = nps.inner(a, n) a -= proj*n a /= nps.mag(a) b = np.cross(n,a) return nps.transpose(nps.cat(a,b,n)) Rt10 = mrcal.compose_Rt( models[1].extrinsics_Rt_fromref(), models[0].extrinsics_Rt_toref() ) R10 = Rt10[:3,:] t10 = Rt10[ 3,:] # The homography definition. Derived in many places. For instance in # "Motion and structure from motion in a piecewise planar environment" # by Olivier Faugeras, F. Lustman. H10 = plane_d * R10 + nps.outer(t10, plane_n) # Find the 3D point on the plane, and translate the homography to match them # up # inner(k*v0, n) = d -> k = d / inner(v0,n) k = plane_d / nps.inner(v0, plane_n) p0 = k * v0 p1 = mrcal.transform_point_Rt(Rt10, p0) # I now compute the "projection matrix" for the two cameras at p. Such a # matrix can only fully describe a pinhole lens, but I can compute the local # estimate from the gradient. For an observation vector v = (vx vy 1) I want # q = (K*v)[:2]/(K*v)[2]. Let # # K = [ K00 K02 ] # = [ 0 0 1 ] # # Where K00 is a (2,2) matrix and K02 is a (2,1) matrix. So q = K00 vxy # + K02. K00 = dq/dvxy K0 = np.eye(3, dtype=float) _, dq0_dvxy0,_ = mrcal.project(p0/p0[2], *models[0].intrinsics(), get_gradients=True) K0[:2,:2] = dq0_dvxy0[:,:2] K0[:2, 2] = q0 - nps.inner(K0[:2,:2], p0[:2]/p0[2]) # Now the same thing for K1 K1 = np.eye(3, dtype=float) q1,dq1_dvxy1,_ = mrcal.project(p1/p1[2], *models[1].intrinsics(), get_gradients=True) K1[:2,:2] = dq1_dvxy1[:,:2] K1[:2, 2] = q1 - nps.inner(K1[:2,:2], p1[:2]/p1[2]) H10 = nps.matmult( K1, H10, np.linalg.inv(K0) ) return H10 # ALTERNATIVE IMPLEMENTATION I MIGHT WANT LATER FOR OTHER PURPOSES: affine # transformation that has no projective behavior v0 = mrcal.unproject(q0, *models[0].intrinsics()) # k*v0 is on the plane: inner(k*v0, n) = d -> k = d/inner(v0,n) p0 = v0 * (plane_d / nps.inner(v0, plane_n)) # The coordinate in the plane are (u,v,n). (u,v) are in the plane, n is the # normal. p0 = R_cam0_uvn * p_uvn -> dp0/dp_uvn = R_cam0_uvn, dp0/dp_uv = # R_cam0_uv R_cam0_uv = get_R_abn(plane_n)[:,:2] _, dq0_dp0,_ = mrcal.project(p0, *models[0].intrinsics(), get_gradients=True) dq0_duv = nps.matmult(dq0_dp0, R_cam0_uv) # For the same (u,v,n) coord system we have p1 = R10 R_cam0_uvn * p_uvn + # t10 -> dp1/dp_uvn = R10 R_cam0_uvn, dp1/dp_uv = R10 R_cam0_uv p1 = mrcal.transform_point_Rt(Rt10, p0) q1,dq1_dp1,_ = mrcal.project(p1, *models[1].intrinsics(), get_gradients=True) dq1_duv = nps.matmult(dq1_dp1, Rt10[:3,:], R_cam0_uv) H10 = np.eye(3, dtype=float) nps.matmult2( dq1_duv, np.linalg.inv(dq0_duv), out = H10[:2,:2]) H10[:2,2] = q1 - mrcal.apply_homography(H10, q0) return H10 def visualize_match(args, match_feature_diagnostics, match_feature_out): import gnuplotlib as gp if match_feature_diagnostics is None: print("## WARNING: no feature matching was performed, so not visualizing the feature-matching results") else: data_tuples, plot_options = match_feature_out[2:] # don't plot the correlation map (the last plot data tuple) gp.plot( *data_tuples[:-1], **plot_options, wait = args.hardcopy is None) def visualize_uncertainty(args, Var_p_calibration, Var_p_observation, Var_p_joint, Rt01, p0): import gnuplotlib as gp if Var_p_calibration is None and \ Var_p_observation is None and \ Var_p_joint is None: print("## WARNING: don't have any ellipses, so not visualizing them") return def get__puv__R_uv_cam0(Rt01, p): # I remap the point to the epipolar-plane-centered coords: # - x: along the baseline # - y: forward to the point # - z: normal x = Rt01[3,:].copy() x /= nps.mag(x) y = p.copy() y -= nps.inner(x,y)*x y /= nps.mag(y) z = np.cross(x,y) R_uvn_cam0 = nps.cat(x,y,z) p_rotated = mrcal.rotate_point_R(R_uvn_cam0, p) return p_rotated[:2], R_uvn_cam0[:2,:] # I want to plot the ellipse in uv coords. So I want to plot # Var(R_uvn_cam0*p_cam0) = R_uv_cam0 Var(p_cam0) nps.transpose(R_uv_cam0) p_uv,R_uv_cam0 = get__puv__R_uv_cam0(Rt01, p0) plotargs = [] for what,var in ( ("Calibration-time", Var_p_calibration), ("Observation-time", Var_p_observation), ("Joint", Var_p_joint)): if var is None: continue var = nps.matmult( R_uv_cam0, var, nps.transpose(R_uv_cam0) ) plotargs.append( \ mrcal.utils._plot_arg_covariance_ellipse(p_uv, var, f"{what} noise") ) plot_options = dict(square = True, xlabel = 'Epipolar plane x (along the baseline) (m)', ylabel = 'Epipolar plane y (forward/back) (m)', title = "Uncertainty propagation", wait = args.hardcopy is None) if args.title is not None: plot_options['title'] = args.title if args.extratitle is not None: plot_options['title'] += f": {args.extratitle}" gp.add_plot_option(plot_options, _set = args.set, unset = args.unset, hardcopy = args.hardcopy, terminal = args.terminal, overwrite = True) gp.plot(*plotargs, **plot_options) np.set_printoptions(precision = 3, suppress = True) if images is not None: if args.clahe: import cv2 clahe = cv2.createCLAHE() clahe.setClipLimit(8) def imread(filename): try: image = mrcal.load_image(filename, bits_per_pixel = 8, channels = 1) except: print(f"Couldn't load '{filename}'", file=sys.stderr) sys.exit(1) if args.clahe: image = clahe.apply(image) return image images = [imread(f) for f in images] def openmodel(f): try: return mrcal.cameramodel(f) except Exception as e: print(f"Couldn't load camera model '{f}': {e}", file=sys.stderr) sys.exit(1) models = [openmodel(modelfilename) for modelfilename in args.models] if args.q_calibration_stdev is not None and \ args.q_calibration_stdev != 0: optimization_inputs = models[0].optimization_inputs() if optimization_inputs is None: print("optimization_inputs are not available, so I cannot propagate calibration-time noise", file=sys.stderr) sys.exit(1) if not models[0]._optimization_inputs_match(models[1]): print("The optimization_inputs for both models must be identical", file=sys.stderr) sys.exit(1) for i in (0,1): if models[i]._extrinsics_moved_since_calibration(): print(f"The given models must have been fixed inside the initial calibration. Model {i} has been moved", file=sys.stderr) sys.exit(1) print("## generated on {} with {}\n".format(time.strftime("%Y-%m-%d %H:%M:%S"), ' '.join(mrcal.shellquote(s) for s in sys.argv))) v0 = mrcal.unproject(q0, *models[0].intrinsics(), normalize = True) Rtr0 = models[0].extrinsics_Rt_toref() Rt01 = mrcal.compose_Rt( models[0].extrinsics_Rt_fromref(), models[1].extrinsics_Rt_toref() ) if q1 is not None: print(f"## Using user-supplied feature match at {q1}") match_feature_diagnostics = None else: if args.plane_n is not None: H10 = compute_H10_planes(models, q0, v0, np.array(args.plane_n), args.plane_d) else: # no plane defined. So I make up a plane that's the given distance away, # viewed head-on. # I compute the "mean" forward view of the cameras # "forward" for cam0 in cam0 coords n0 = np.array((0,0,1.)) # "forward" for cam1 in cam0 coords n1 = mrcal.rotate_point_R(Rt01[:3,:], np.array((0,0,1.))) n = n0+n1 # normalized "mean forward" in cam0 coords n /= nps.mag(n) # inner(n,k*v) = d d = nps.inner(n, args.range_estimate*v0) H10 = compute_H10_planes(models, q0, v0, n, d) q1_perfect = mrcal.apply_homography(H10, q0) print(f"## Feature {q0} in the left image corresponds to {q1_perfect} at {args.range_estimate}m") plotkwargs_extra = dict() if args.title is not None: plotkwargs_extra['title'] = args.title if args.extratitle is not None: plotkwargs_extra['extratitle'] = args.extratitle match_feature_out = \ mrcal.match_feature(*images, q0 = q0, H10 = H10, search_radius1 = args.search_radius, template_size1 = args.template_size, visualize = args.viz == 'match', return_plot_args = True, _set = args.set, unset = args.unset, hardcopy = args.hardcopy, terminal = args.terminal, **plotkwargs_extra) q1, match_feature_diagnostics = match_feature_out[:2] if q1 is None or \ match_feature_diagnostics['matchoutput_optimum_subpixel'] < args.corr_floor: print("## Feature-matching failed! Maybe increase the --search-radius or reduce --corr-floor?") sys.exit(1) print(f"## Feature match found at {q1}") print(f"## q1 - q1_perfect_at_range = {q1 - q1_perfect}") Var_p_calibration = None Var_p_observation = None Var_p_joint = None if args.q_calibration_stdev is None and \ args.q_observation_stdev is None: p0 = \ mrcal.triangulate( nps.cat(q0, q1), models, stabilize_coords = args.stabilize_coords, method = method ) elif args.q_calibration_stdev is not None and \ args.q_observation_stdev is None: p0, \ Var_p_calibration = \ mrcal.triangulate( nps.cat(q0, q1), models, q_calibration_stdev = args.q_calibration_stdev, stabilize_coords = args.stabilize_coords, method = method ) elif args.q_calibration_stdev is None and \ args.q_observation_stdev is not None: p0, \ Var_p_observation = \ mrcal.triangulate( nps.cat(q0, q1), models, q_observation_stdev = args.q_observation_stdev, q_observation_stdev_correlation = args.q_observation_stdev_correlation, stabilize_coords = args.stabilize_coords, method = method ) else: p0, \ Var_p_calibration, \ Var_p_observation, \ Var_p_joint = \ mrcal.triangulate( nps.cat(q0, q1), models, q_calibration_stdev = args.q_calibration_stdev, q_observation_stdev = args.q_observation_stdev, q_observation_stdev_correlation = args.q_observation_stdev_correlation, stabilize_coords = args.stabilize_coords, method = method ) if nps.norm2(p0) == 0: print("Observation rays divergent: feature is near infinity or a false match was found", file=sys.stderr) if args.viz == '': pass elif args.viz == 'match': visualize_match(args, match_feature_diagnostics, match_feature_out) else: raise Exception("Unknown --viz arg. This is a bug") sys.exit(1) # I use the lower-level triangulation function further on, for the empirical # sensitivity calculation. I call it here as a sanity check, to make sure that # mrcal.triangulate() gave me the same thing v1 = mrcal.unproject(q1, *models[1].intrinsics()) if nps.norm2( p0 - method( v0, v1, Rt01 = Rt01, v_are_local = True) ) > 1e-6: print("## WARNING: mrcal.triangulate() returned something different from the internal routine. This is a bug. The empirical sensitivities may be off") # worst-case rotation axis will be the yaw. This axis is the normal to the plane # containing the 2 cameras and the observed point n_epipolar_plane = np.cross(p0, Rt01[3,:]) n_epipolar_plane /= nps.mag(n_epipolar_plane) # I want n_epipolar_plane to point in the same direction as the cam0 y axis, since that's # the nominal yaw axis if n_epipolar_plane[1] < 0: n_epipolar_plane *= -1. # I also want to look at the pitch: the rotation around the baseline vector v_pitch = Rt01[3,:] / nps.mag(Rt01[3,:]) def get_rt10_perturbed( t01err = np.array((0,0,0)), r01err_yaw = 0, r01err_yaw_axis = None, r01err_pitch = 0, r01err_pitch_axis = None): # This is crude. I'm assuming that the two rotations are small, around # orthogonal axes, so they commute R = np.eye(3) if r01err_yaw: K = mrcal.skew_symmetric(r01err_yaw_axis) Ryaw = np.eye(3) + np.sin(r01err_yaw) * K + (1. - np.cos(r01err_yaw))*nps.matmult(K,K) R = Ryaw if r01err_pitch: K = mrcal.skew_symmetric(r01err_pitch_axis) Rpitch = np.eye(3) + np.sin(r01err_pitch) * K + (1. - np.cos(r01err_pitch))*nps.matmult(K,K) R = nps.matmult(R, Rpitch) rt10 = mrcal.rt_from_Rt( mrcal.compose_Rt(mrcal.invert_Rt(Rt01), nps.glue(R, np.zeros((3,)), axis=-2))) rt10[3:] -= t01err return rt10 def get_world_intersection_point(qerr1 = np.array((0,0)), **kwargs): rt10 = get_rt10_perturbed(**kwargs) v1 = mrcal.unproject(q1 + qerr1, *models[1].intrinsics()) return method( v0, v1, Rt01 = mrcal.invert_Rt( mrcal.Rt_from_rt(rt10) ), v_are_local = True) def get_range(**kwargs): # divergent rays have p = (0,0,0) p = get_world_intersection_point(**kwargs) return nps.mag(p) range0 = get_range() if range0 == 0: # The initial geometry produces a triangulation behind the camera. This is a # qualitatively different solution, so I don't report linear extrapolation results print("## Initial geometry is divergent. Not reporting sensitivities") else: range_err_have = range0 - args.range_estimate p0_ref = mrcal.transform_point_Rt(Rtr0, p0) v0_ref = mrcal.rotate_point_R(Rtr0[:3,:], v0) print(f"## Triangulated point at {p0}; direction: {v0} [camera coordinates]") print(f"## Triangulated point at {p0_ref}; direction: {v0_ref} [reference coordinates]") print("## Range: {:.2f} m (error: {:.2f} m)".format(range0, range_err_have)) print(f"## q0 - q0_triangulation = {q0 - mrcal.project(p0, *models[0].intrinsics())}") for what,var in ( ("calibration-time", Var_p_calibration), ("observation-time", Var_p_observation), ("joint", Var_p_joint)): if var is not None: l,v = mrcal.sorted_eig(var) # look at the least-confident direction sigma = np.sqrt(l[-1]) v = v[:,-1] print(f"## Uncertainty propagation: {what} noise suggests worst confidence of sigma={sigma:.3f}m along {v}") # half-assed sensitivity testing. Finite differences for each piece delta = 1e-3 rangeerr_worst_qerr = 0 for th in np.linspace(0,2.*np.pi, 90, endpoint=False): vq = np.array((np.cos(th),np.sin(th))) r = get_range(qerr1 = delta * vq) if r == 0: print("Sampled rays divergent", file=sys.stderr) sys.exit(1) rangeerr = np.abs(r - range0) if rangeerr > rangeerr_worst_qerr: rangeerr_worst_qerr = rangeerr vq_worst_err = vq print("## Observed-pixel range sensitivity: {:.3f}m/pixel (q1). Worst direction: {}. Linearized correction: {:.3f} pixels". \ format(rangeerr_worst_qerr/delta, vq_worst_err, -range_err_have/rangeerr_worst_qerr*delta )) # worst-case rotation axis will be the yaw. This axis is the normal to the plane # containing the 2 cameras and the observed point delta = 1e-6 r = get_range(r01err_yaw_axis = n_epipolar_plane, r01err_yaw = delta * np.pi/180.) if r == 0: print("Sampled rays divergent", file=sys.stderr) sys.exit(1) rangeerr_yaw = r - range0 print("## Calibration yaw (rotation in epipolar plane) sensitivity: {:.2f}m/deg. Linearized correction: {:.3f} degrees of yaw". \ format(rangeerr_yaw/delta, -range_err_have/rangeerr_yaw*delta)) r = get_range(r01err_yaw_axis = np.array((0., 1., 0.,)), r01err_yaw = delta * np.pi/180.) if r == 0: print("Sampled rays divergent", file=sys.stderr) sys.exit(1) rangeerr_yaw = r - range0 print("## Calibration yaw (cam0 y axis) sensitivity: {:.2f}m/deg. Linearized correction: {:.3f} degrees of yaw". \ format(rangeerr_yaw/delta, -range_err_have/rangeerr_yaw*delta)) # I also want to look at the pitch r = get_range(r01err_pitch_axis = v_pitch, r01err_pitch = delta * np.pi/180.) if r == 0: print("Sampled rays divergent", file=sys.stderr) sys.exit(1) rangeerr_pitch = r - range0 print("## Calibration pitch (tilt of epipolar plane) sensitivity: {:.2f}m/deg.".format(rangeerr_pitch/delta)) delta = 1e-3 rangeerr_worst_t01err = 0 for th in np.linspace(0, 2.*np.pi, 40, endpoint=False): for ph in np.linspace(0, np.pi, 20): vt01 = np.array((np.cos(ph) * np.sin(th), np.cos(ph) * np.cos(th), np.sin(ph))) r = get_range(t01err = delta * vt01) if r == 0: print("Sampled rays divergent", file=sys.stderr) sys.exit(1) rangeerr = np.abs(r - range0) if rangeerr > rangeerr_worst_t01err: rangeerr_worst_t01err = rangeerr vt01_worst_err = vt01 print("## Calibration translation sensitivity: {:.2f}m/m. Worst direction: {}. Linearized correction: {:.2f} meters of translation". \ format(rangeerr_worst_t01err/delta, vt01_worst_err, -range_err_have/rangeerr_worst_t01err*delta)) # I have a pixel coordinate given on the commandline and a range. I can use the # range to correct the yaw (x shift in the image). And I can tweak the pitch to # correct the y shift in the image. def get_range_err_yaw_pitch_sq(dyawdpitch): p = get_world_intersection_point(r01err_yaw_axis = n_epipolar_plane, r01err_yaw = dyawdpitch[0], r01err_pitch_axis = v_pitch, r01err_pitch = dyawdpitch[1]) r = nps.mag(p) if r == 0: # The intersection is behind the camera. I arbitrarily make the error # very large return 1e6 erange = r - args.range_estimate ereprojection = mrcal.project(p, *models[0].intrinsics()) - q0 # The range errors are generally much higher than pixel errors, so I scale # these. Nothing about any of this is particularly principled, but it is # useful for testing ereprojection *= 100 return erange*erange + nps.norm2(ereprojection) # If I'm divergent initially. I take discrete steps to make me # convergent, then I run an iterative method if get_range_err_yaw_pitch_sq((0,0)) < 1e6: # not divergent initially dyawdpitch = (0,0) else: print("## Initially divergent. Finding a usable operating point to begin optimization") step = 1. * np.pi/180.0 for d in np.array((( 1., 0.), (-1., 0.), ( 0., 1.), ( 0., -1.)))*step: i=0 while i < 180: dyawdpitch = i*d err = get_range_err_yaw_pitch_sq(dyawdpitch) if err < 1e6: # no longer divergent break i += 1 if err < 1e6: break if err >= 1e6: print("## Initial search couldn't make the rays converge. Will not report optimized corrections") dyawdpitch = None if dyawdpitch is not None: dyaw,dpitch = scipy.optimize.minimize(get_range_err_yaw_pitch_sq, dyawdpitch).x print("## Optimized yaw (rotation in epipolar plane) correction = {:.3f} degrees".format(dyaw/np.pi*180)) print("## Optimized pitch (tilt of epipolar plane) correction = {:.3f} degrees".format(dpitch/np.pi*180)) rt10 = get_rt10_perturbed(r01err_yaw_axis = n_epipolar_plane, r01err_yaw = dyaw, r01err_pitch_axis = v_pitch, r01err_pitch = dpitch) print("## Optimized relative yaw (1 <- 0): {:.3f} degrees".format(rt10[1] * 180./np.pi)) if args.make_corrected_model1: if dyaw is None: print("I can't make the corrected model if I couldn't compute the yaw,pitch shifts", file=sys.stderr) sys.exit(1) rt_1r = mrcal.compose_rt(rt10, models[0].extrinsics_rt_fromref()) models[1].extrinsics_rt_fromref(rt_1r) models[1].write(sys.stdout) if args.viz == '': pass elif args.viz == 'match': visualize_match(args, match_feature_diagnostics, match_feature_out) elif args.viz == 'uncertainty': visualize_uncertainty(args, Var_p_calibration, Var_p_observation, Var_p_joint, Rt01, p0) else: raise Exception("Unknown --viz arg. This is a bug") mrcal-2.4.1/mrcal-types.h000066400000000000000000000365111456301662300152410ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #pragma once #include #include #include "basic-geometry.h" //////////////////////////////////////////////////////////////////////////////// //////////////////// Lens models //////////////////////////////////////////////////////////////////////////////// // These are an "X macro": https://en.wikipedia.org/wiki/X_Macro // // The supported lens models and their parameter counts. Models with a // configuration may have a dynamic parameter count; this is indicated here with // a <0 value. These models report their parameter counts in the // LENSMODEL_XXX__lensmodel_num_params() function, called by // mrcal_lensmodel_num_params(). #define MRCAL_LENSMODEL_NOCONFIG_LIST(_) \ _(LENSMODEL_PINHOLE, 4) \ _(LENSMODEL_STEREOGRAPHIC, 4) /* Simple stereographic-only model */ \ _(LENSMODEL_LONLAT, 4) \ _(LENSMODEL_LATLON, 4) \ _(LENSMODEL_OPENCV4, 8) \ _(LENSMODEL_OPENCV5, 9) \ _(LENSMODEL_OPENCV8, 12) \ _(LENSMODEL_OPENCV12, 16) /* available in OpenCV >= 3.0.0) */ \ _(LENSMODEL_CAHVOR, 9) #define MRCAL_LENSMODEL_WITHCONFIG_STATIC_NPARAMS_LIST(_) \ _(LENSMODEL_CAHVORE, 12) #define MRCAL_LENSMODEL_WITHCONFIG_DYNAMIC_NPARAMS_LIST(_) \ _(LENSMODEL_SPLINED_STEREOGRAPHIC, -1) #define MRCAL_LENSMODEL_LIST(_) \ MRCAL_LENSMODEL_NOCONFIG_LIST(_) \ MRCAL_LENSMODEL_WITHCONFIG_STATIC_NPARAMS_LIST(_) \ MRCAL_LENSMODEL_WITHCONFIG_DYNAMIC_NPARAMS_LIST(_) // parametric models have no extra configuration typedef struct {} mrcal_LENSMODEL_PINHOLE__config_t; typedef struct {} mrcal_LENSMODEL_STEREOGRAPHIC__config_t; typedef struct {} mrcal_LENSMODEL_LONLAT__config_t; typedef struct {} mrcal_LENSMODEL_LATLON__config_t; typedef struct {} mrcal_LENSMODEL_OPENCV4__config_t; typedef struct {} mrcal_LENSMODEL_OPENCV5__config_t; typedef struct {} mrcal_LENSMODEL_OPENCV8__config_t; typedef struct {} mrcal_LENSMODEL_OPENCV12__config_t; typedef struct {} mrcal_LENSMODEL_CAHVOR__config_t; #define _MRCAL_ITEM_DEFINE_ELEMENT(name, type, pybuildvaluecode, PRIcode,SCNcode, bitfield, cookie) type name bitfield; #ifndef __cplusplus // This barfs with g++ 4.8, so I disable it for C++ in general. Checking it for // C code is sufficient _Static_assert(sizeof(uint16_t) == sizeof(unsigned short int), "I need a short to be 16-bit. Py_BuildValue doesn't let me just specify that. H means 'unsigned short'"); #endif // Configuration for CAHVORE. These are given as an an // "X macro": https://en.wikipedia.org/wiki/X_Macro #define MRCAL_LENSMODEL_CAHVORE_CONFIG_LIST(_, cookie) \ _(linearity, double, "d", ".2f", "lf", , cookie) typedef struct { MRCAL_LENSMODEL_CAHVORE_CONFIG_LIST(_MRCAL_ITEM_DEFINE_ELEMENT, ) } mrcal_LENSMODEL_CAHVORE__config_t; // Configuration for the splined stereographic models. These are given as an an // "X macro": https://en.wikipedia.org/wiki/X_Macro #define MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC_CONFIG_LIST(_, cookie) \ /* Maximum degree of each 1D polynomial. This is almost certainly 2 */ \ /* (quadratic splines, C1 continuous) or 3 (cubic splines, C2 continuous) */ \ _(order, uint16_t, "H", PRIu16,SCNu16, , cookie) \ /* We have a Nx by Ny grid of control points */ \ _(Nx, uint16_t, "H", PRIu16,SCNu16, , cookie) \ _(Ny, uint16_t, "H", PRIu16,SCNu16, , cookie) \ /* The horizontal field of view. Not including fov_y. It's proportional with */ \ /* Ny and Nx */ \ _(fov_x_deg, uint16_t, "H", PRIu16,SCNu16, , cookie) typedef struct { MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC_CONFIG_LIST(_MRCAL_ITEM_DEFINE_ELEMENT, ) } mrcal_LENSMODEL_SPLINED_STEREOGRAPHIC__config_t; // An X-macro-generated enum mrcal_lensmodel_type_t. This has an element for // each entry in MRCAL_LENSMODEL_LIST (with "MRCAL_" prepended). This lensmodel // type selects the lens model, but does NOT provide the configuration. // mrcal_lensmodel_t does that. #define _LIST_WITH_COMMA(s,n) ,MRCAL_ ## s typedef enum { // Generic error. Rarely used in current mrcal MRCAL_LENSMODEL_INVALID = -2, // Configuration parsing failed MRCAL_LENSMODEL_INVALID_BADCONFIG = -1, // A configuration was required, but was missing entirely MRCAL_LENSMODEL_INVALID_MISSINGCONFIG = -3, // The model type wasn't known MRCAL_LENSMODEL_INVALID_TYPE = -4, // Dummy entry. Must be -1 so that successive values start at 0 _MRCAL_LENSMODEL_DUMMY = -1 // The rest, starting with 0 MRCAL_LENSMODEL_LIST( _LIST_WITH_COMMA ) } mrcal_lensmodel_type_t; #undef _LIST_WITH_COMMA // Defines a lens model: the type AND the configuration values typedef struct { // The type of lensmodel. This is an enum, selecting elements of // MRCAL_LENSMODEL_LIST (with "MRCAL_" prepended) mrcal_lensmodel_type_t type; // A union of all the possible configuration structures. We pick the // structure type based on the value of "type union { #define CONFIG_STRUCT(s,n) mrcal_ ##s##__config_t s##__config; MRCAL_LENSMODEL_LIST(CONFIG_STRUCT); #undef CONFIG_STRUCT }; } mrcal_lensmodel_t; typedef union { struct { double x2, y2; }; double values[2]; } mrcal_calobject_warp_t; #define MRCAL_NSTATE_CALOBJECT_WARP ((int)((sizeof(mrcal_calobject_warp_t)/sizeof(double)))) //// ADD CHANGES TO THE DOCS IN lensmodels.org //// // An X-macro-generated mrcal_lensmodel_metadata_t. Each lens model type has // some metadata that describes its inherent properties. These properties can be // queried by calling mrcal_lensmodel_metadata() in C and // mrcal.lensmodel_metadata_and_config() in Python. The available properties and // their meaning are listed in MRCAL_LENSMODEL_META_LIST() #define MRCAL_LENSMODEL_META_LIST(_, cookie) \ /* If true, this model contains an "intrinsics core". This is described */ \ /* in mrcal_intrinsics_core_t. If present, the 4 core parameters ALWAYS */ \ /* appear at the start of a model's parameter vector */ \ _(has_core, bool, "i",,, :1, cookie) \ \ /* Whether a model is able to project points behind the camera */ \ /* (z<0 in the camera coordinate system). Models based on a pinhole */ \ /* projection (pinhole, OpenCV, CAHVOR(E)) cannot do this. models based */ \ /* on a stereographic projection (stereographic, splined stereographic) */ \ /* can */ \ _(can_project_behind_camera, bool, "i",,, :1, cookie) \ \ /* Whether gradients are available for this model. Currently only */ \ /* CAHVORE does not have gradients */ \ _(has_gradients, bool, "i",,, :1, cookie) \ \ /* Whether this is a noncentral model.Currently the only noncentral */ \ /* model we have is CAHVORE. There will be more later. */ \ _(noncentral, bool, "i",,, :1, cookie) typedef struct { MRCAL_LENSMODEL_META_LIST(_MRCAL_ITEM_DEFINE_ELEMENT, ) } mrcal_lensmodel_metadata_t; //////////////////////////////////////////////////////////////////////////////// //////////////////// Optimization //////////////////////////////////////////////////////////////////////////////// // Used to specify which camera is making an observation. The "intrinsics" index // is used to identify a specific camera, while the "extrinsics" index is used // to locate a camera in space. If I have a camera that is moving over time, the // intrinsics index will remain the same, while the extrinsics index will change typedef struct { // indexes the intrinsics array int intrinsics; // indexes the extrinsics array. -1 means "at coordinate system reference" int extrinsics; } mrcal_camera_index_t; // An observation of a calibration board. Each "observation" is ONE camera // observing a board typedef struct { // which camera is making this observation mrcal_camera_index_t icam; // indexes the "frames" array to select the pose of the calibration object // being observed int iframe; } mrcal_observation_board_t; // An observation of a discrete point. Each "observation" is ONE camera // observing a single point in space typedef struct { // which camera is making this observation mrcal_camera_index_t icam; // indexes the "points" array to select the position of the point being // observed int i_point; // Observed pixel coordinates. This works just like elements of // observations_board_pool: // // .x, .y are the pixel observations // .z is the weight of the observation. Most of the weights are expected to // be 1.0. Less precise observations have lower weights. // .z<0 indicates that this is an outlier. This is respected on // input // // Unlike observations_board_pool, outlier rejection is NOT YET IMPLEMENTED // for points, so outlier points will NOT be found and reported on output in // .z<0 mrcal_point3_t px; } mrcal_observation_point_t; // Bits indicating which parts of the optimization problem being solved. We can // ask mrcal to solve for ALL the lens parameters and ALL the geometry and // everything else. OR we can ask mrcal to lock down some part of the // optimization problem, and to solve for the rest. If any variables are locked // down, we use their initial values passed-in to mrcal_optimize() typedef struct { // If true, we solve for the intrinsics core. Applies only to those models // that HAVE a core (fx,fy,cx,cy) bool do_optimize_intrinsics_core : 1; // If true, solve for the non-core lens parameters bool do_optimize_intrinsics_distortions : 1; // If true, solve for the geometry of the cameras bool do_optimize_extrinsics : 1; // If true, solve for the poses of the calibration object bool do_optimize_frames : 1; // If true, optimize the shape of the calibration object bool do_optimize_calobject_warp : 1; // If true, apply the regularization terms in the solver bool do_apply_regularization : 1; // Whether to try to find NEW outliers. The outliers given on // input are respected regardless bool do_apply_outlier_rejection : 1; } mrcal_problem_selections_t; // Constants used in a mrcal optimization. This is similar to // mrcal_problem_selections_t, but contains numerical values rather than just // bits typedef struct { // The minimum distance of an observed discrete point from its observing // camera. Any observation of a point below this range will be penalized to // encourage the optimizer to move the point further away from the camera double point_min_range; // The maximum distance of an observed discrete point from its observing // camera. Any observation of a point abive this range will be penalized to // encourage the optimizer to move the point closer to the camera double point_max_range; } mrcal_problem_constants_t; // An X-macro-generated mrcal_stats_t. This structure is returned by the // optimizer, and contains some statistics about the optimization #define MRCAL_STATS_ITEM(_) \ /* The RMS error of the optimized fit at the optimum. Generally the residual */ \ /* vector x contains error values for each element of q, so N observed pixels */ \ /* produce 2N measurements: len(x) = 2*N. And the RMS error is */ \ /* sqrt( norm2(x) / N ) */ \ _(double, rms_reproj_error__pixels, PyFloat_FromDouble) \ \ /* How many pixel observations were thrown out as outliers. Each pixel */ \ /* observation produces two measurements. Note that this INCLUDES any */ \ /* outliers that were passed-in at the start */ \ _(int, Noutliers, PyLong_FromLong) #define MRCAL_STATS_ITEM_DEFINE(type, name, pyconverter) type name; typedef struct { MRCAL_STATS_ITEM(MRCAL_STATS_ITEM_DEFINE) } mrcal_stats_t; //////////////////////////////////////////////////////////////////////////////// //////////////////// Layout of the measurement and state vectors //////////////////////////////////////////////////////////////////////////////// // The "intrinsics core" of a camera. This defines the final step of a // projection operation. For instance with a pinhole model we have // // q[0] = focal_xy[0] * x/z + center_xy[0] // q[1] = focal_xy[1] * y/z + center_xy[1] typedef struct { double focal_xy [2]; double center_xy[2]; } mrcal_intrinsics_core_t; // structure containing a camera pose + lens model. Used for .cameramodel // input/output #define MRCAL_CAMERAMODEL_ELEMENTS_NO_INTRINSICS \ double rt_cam_ref[6]; \ unsigned int imagersize[2]; \ mrcal_lensmodel_t lensmodel \ typedef struct { MRCAL_CAMERAMODEL_ELEMENTS_NO_INTRINSICS; // mrcal_cameramodel_t works for all lensmodels, so its intrinsics count is // not known at compile time. mrcal_cameramodel_t is thus usable only as // part of a larger structure or as a mrcal_cameramodel_t* argument to // functions. To allocate new mrcal_cameramodel_t objects, use // mrcal_cameramodel_LENSMODEL_XXX_t or malloc() with the proper intrinsics // size taken into account double intrinsics[0]; } mrcal_cameramodel_t; #define DEFINE_mrcal_cameramodel_MODEL_t(s,n) \ typedef union \ { \ mrcal_cameramodel_t m; \ struct \ { \ MRCAL_CAMERAMODEL_ELEMENTS_NO_INTRINSICS; \ double intrinsics[n]; \ }; \ } mrcal_cameramodel_ ## s ## _t; MRCAL_LENSMODEL_NOCONFIG_LIST( DEFINE_mrcal_cameramodel_MODEL_t) MRCAL_LENSMODEL_WITHCONFIG_STATIC_NPARAMS_LIST(DEFINE_mrcal_cameramodel_MODEL_t) mrcal-2.4.1/mrcal.c000066400000000000000000007522101456301662300140730ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // Apparently I need this in MSVC to get constants #define _USE_MATH_DEFINES #include #include #include #include #include #include #include #include #include "mrcal.h" #include "minimath/minimath.h" #include "cahvore.h" #include "util.h" // These are parameter variable scales. They have the units of the parameters // themselves, so the optimizer sees x/SCALE_X for each parameter. I.e. as far // as the optimizer is concerned, the scale of each variable is 1. This doesn't // need to be precise; just need to get all the variables to be within the same // order of magnitute. This is important because the dogleg solve treats the // trust region as a ball in state space, and this ball is isotropic, and has a // radius that applies in every direction // // Can be visualized like this: // // b0,x0,J0 = mrcal.optimizer_callback(**optimization_inputs)[:3] // J0 = J0.toarray() // ss = np.sum(np.abs(J0), axis=-2) // gp.plot(ss, _set=mrcal.plotoptions_state_boundaries(**optimization_inputs)) // // This visualizes the overall effect of each variable. If the scales aren't // tuned properly, some variables will have orders of magnitude stronger // response than others, and the optimization problem won't converge well. // // The scipy.optimize.least_squares() function claims to be able to estimate // these automatically, without requiring these hard-coded values from the user. // See the description of the "x_scale" argument: // // https://docs.scipy.org/doc/scipy/reference/generated/scipy.optimize.least_squares.html // // Supposedly this paper describes the method: // // J. J. More, "The Levenberg-Marquardt Algorithm: Implementation and Theory," // Numerical Analysis, ed. G. A. Watson, Lecture Notes in Mathematics 630, // Springer Verlag, pp. 105-116, 1977. // // Please somebody look at this #define SCALE_INTRINSICS_FOCAL_LENGTH 500.0 #define SCALE_INTRINSICS_CENTER_PIXEL 20.0 #define SCALE_ROTATION_CAMERA (0.1 * M_PI/180.0) #define SCALE_TRANSLATION_CAMERA 1.0 #define SCALE_ROTATION_FRAME (15.0 * M_PI/180.0) #define SCALE_TRANSLATION_FRAME 1.0 #define SCALE_POSITION_POINT SCALE_TRANSLATION_FRAME #define SCALE_CALOBJECT_WARP 0.01 #define SCALE_DISTORTION 1.0 #define MSG_IF_VERBOSE(...) do { if(verbose) MSG( __VA_ARGS__ ); } while(0) // Returns a static string, using "..." as a placeholder for any configuration // values #define LENSMODEL_PRINT_CFG_ELEMENT_TEMPLATE(name, type, pybuildvaluecode, PRIcode,SCNcode, bitfield, cookie) \ "_" #name "=..." #define LENSMODEL_PRINT_CFG_ELEMENT_FMT(name, type, pybuildvaluecode, PRIcode,SCNcode, bitfield, cookie) \ "_" #name "=%" PRIcode #define LENSMODEL_PRINT_CFG_ELEMENT_VAR(name, type, pybuildvaluecode, PRIcode,SCNcode, bitfield, cookie) \ ,config->name #define LENSMODEL_SCAN_CFG_ELEMENT_FMT(name, type, pybuildvaluecode, PRIcode,SCNcode, bitfield, cookie) \ "_" #name "=%" SCNcode #define LENSMODEL_SCAN_CFG_ELEMENT_VAR(name, type, pybuildvaluecode, PRIcode,SCNcode, bitfield, cookie) \ ,&config->name #define LENSMODEL_SCAN_CFG_ELEMENT_PLUS1(name, type, pybuildvaluecode, PRIcode,SCNcode, bitfield, cookie) \ +1 const char* mrcal_lensmodel_name_unconfigured( const mrcal_lensmodel_t* lensmodel ) { switch(lensmodel->type) { #define CASE_STRING_NOCONFIG(s,n) case MRCAL_##s: ; \ return #s; #define _CASE_STRING_WITHCONFIG(s,n,s_CONFIG_LIST) case MRCAL_##s: ; \ return #s s_CONFIG_LIST(LENSMODEL_PRINT_CFG_ELEMENT_TEMPLATE, ); #define CASE_STRING_WITHCONFIG(s,n) _CASE_STRING_WITHCONFIG(s,n,MRCAL_ ## s ## _CONFIG_LIST) MRCAL_LENSMODEL_NOCONFIG_LIST( CASE_STRING_NOCONFIG ) MRCAL_LENSMODEL_WITHCONFIG_STATIC_NPARAMS_LIST( CASE_STRING_WITHCONFIG ) MRCAL_LENSMODEL_WITHCONFIG_DYNAMIC_NPARAMS_LIST( CASE_STRING_WITHCONFIG ) default: return NULL; #undef CASE_STRING_NOCONFIG #undef CASE_STRING_WITHCONFIG } return NULL; } // Write the model name WITH the full config into the given buffer. Identical to // mrcal_lensmodel_name_unconfigured() for configuration-free models static int LENSMODEL_CAHVORE__snprintf_model (char* out, int size, const mrcal_LENSMODEL_CAHVORE__config_t* config) { return snprintf( out, size, "LENSMODEL_CAHVORE" MRCAL_LENSMODEL_CAHVORE_CONFIG_LIST(LENSMODEL_PRINT_CFG_ELEMENT_FMT, ) MRCAL_LENSMODEL_CAHVORE_CONFIG_LIST(LENSMODEL_PRINT_CFG_ELEMENT_VAR, )); } static int LENSMODEL_SPLINED_STEREOGRAPHIC__snprintf_model (char* out, int size, const mrcal_LENSMODEL_SPLINED_STEREOGRAPHIC__config_t* config) { return snprintf( out, size, "LENSMODEL_SPLINED_STEREOGRAPHIC" MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC_CONFIG_LIST(LENSMODEL_PRINT_CFG_ELEMENT_FMT, ) MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC_CONFIG_LIST(LENSMODEL_PRINT_CFG_ELEMENT_VAR, )); } bool mrcal_lensmodel_name( char* out, int size, const mrcal_lensmodel_t* lensmodel ) { switch(lensmodel->type) { #define CASE_STRING_NOCONFIG(s,n) case MRCAL_##s: \ return size > snprintf(out,size, #s); #define CASE_STRING_WITHCONFIG(s,n) case MRCAL_##s: \ return size > s##__snprintf_model(out, size, &lensmodel->s##__config); MRCAL_LENSMODEL_NOCONFIG_LIST( CASE_STRING_NOCONFIG ) MRCAL_LENSMODEL_WITHCONFIG_STATIC_NPARAMS_LIST( CASE_STRING_WITHCONFIG ) MRCAL_LENSMODEL_WITHCONFIG_DYNAMIC_NPARAMS_LIST( CASE_STRING_WITHCONFIG ) default: return NULL; #undef CASE_STRING_NOCONFIG #undef CASE_STRING_WITHCONFIG } return NULL; } static bool LENSMODEL_CAHVORE__scan_model_config( mrcal_LENSMODEL_CAHVORE__config_t* config, const char* config_str) { int pos; int Nelements = 0 MRCAL_LENSMODEL_CAHVORE_CONFIG_LIST(LENSMODEL_SCAN_CFG_ELEMENT_PLUS1, ); return Nelements == sscanf( config_str, MRCAL_LENSMODEL_CAHVORE_CONFIG_LIST(LENSMODEL_SCAN_CFG_ELEMENT_FMT, )"%n" MRCAL_LENSMODEL_CAHVORE_CONFIG_LIST(LENSMODEL_SCAN_CFG_ELEMENT_VAR, ), &pos) && config_str[pos] == '\0'; } static bool LENSMODEL_SPLINED_STEREOGRAPHIC__scan_model_config( mrcal_LENSMODEL_SPLINED_STEREOGRAPHIC__config_t* config, const char* config_str) { int pos; int Nelements = 0 MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC_CONFIG_LIST(LENSMODEL_SCAN_CFG_ELEMENT_PLUS1, ); return Nelements == sscanf( config_str, MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC_CONFIG_LIST(LENSMODEL_SCAN_CFG_ELEMENT_FMT, )"%n" MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC_CONFIG_LIST(LENSMODEL_SCAN_CFG_ELEMENT_VAR, ), &pos) && config_str[pos] == '\0'; } const char* const* mrcal_supported_lensmodel_names( void ) { #define NAMESTRING_NOCONFIG(s,n) #s, #define _NAMESTRING_WITHCONFIG(s,n,s_CONFIG_LIST) #s s_CONFIG_LIST(LENSMODEL_PRINT_CFG_ELEMENT_TEMPLATE, ), #define NAMESTRING_WITHCONFIG(s,n) _NAMESTRING_WITHCONFIG(s,n,MRCAL_ ## s ## _CONFIG_LIST) static const char* names[] = { MRCAL_LENSMODEL_NOCONFIG_LIST( NAMESTRING_NOCONFIG) MRCAL_LENSMODEL_WITHCONFIG_STATIC_NPARAMS_LIST( NAMESTRING_WITHCONFIG) MRCAL_LENSMODEL_WITHCONFIG_DYNAMIC_NPARAMS_LIST(NAMESTRING_WITHCONFIG) NULL }; return names; } #undef LENSMODEL_PRINT_CFG_ELEMENT_TEMPLATE #undef LENSMODEL_PRINT_CFG_ELEMENT_FMT #undef LENSMODEL_PRINT_CFG_ELEMENT_VAR #undef LENSMODEL_SCAN_CFG_ELEMENT_FMT #undef LENSMODEL_SCAN_CFG_ELEMENT_VAR #undef LENSMODEL_SCAN_CFG_ELEMENT_PLUS1 // parses the model name AND the configuration into a mrcal_lensmodel_t structure. // On error returns false with lensmodel->type set to MRCAL_LENSMODEL_INVALID_... bool mrcal_lensmodel_from_name( // output mrcal_lensmodel_t* lensmodel, // input const char* name ) { #define CHECK_AND_RETURN_NOCONFIG(s,n) \ if( 0 == strcmp( name, #s) ) \ { \ *lensmodel = (mrcal_lensmodel_t){.type = MRCAL_##s}; \ return true; \ } #define CHECK_AND_RETURN_WITHCONFIG(s,n) \ /* Configured model. I need to extract the config from the string. */ \ /* The string format is NAME_cfg1=var1_cfg2=var2... */ \ { \ const int len_s = strlen(#s); \ if( 0 == strncmp( name, #s, len_s ) ) \ { \ if(name[len_s] == '\0') \ { \ *lensmodel = (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_INVALID_MISSINGCONFIG}; \ return false; \ } \ if(name[len_s] == '_') \ { \ /* found name. Now extract the config */ \ *lensmodel = (mrcal_lensmodel_t){.type = MRCAL_##s}; \ mrcal_##s##__config_t* config = &lensmodel->s##__config; \ \ const char* config_str = &name[len_s]; \ \ if(s##__scan_model_config(config, config_str)) \ return true; \ \ *lensmodel = (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_INVALID_BADCONFIG}; \ return false; \ } \ } \ } if(name == NULL) { *lensmodel = (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_INVALID_TYPE}; return false; } MRCAL_LENSMODEL_NOCONFIG_LIST( CHECK_AND_RETURN_NOCONFIG ); MRCAL_LENSMODEL_WITHCONFIG_STATIC_NPARAMS_LIST( CHECK_AND_RETURN_WITHCONFIG ); MRCAL_LENSMODEL_WITHCONFIG_DYNAMIC_NPARAMS_LIST( CHECK_AND_RETURN_WITHCONFIG ); *lensmodel = (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_INVALID_TYPE}; return false; #undef CHECK_AND_RETURN_NOCONFIG #undef CHECK_AND_RETURN_WITHCONFIG } // parses the model name only. The configuration is ignored. Even if it's // missing or unparseable. Unknown model names return // MRCAL_LENSMODEL_INVALID_TYPE mrcal_lensmodel_type_t mrcal_lensmodel_type_from_name( const char* name ) { #define CHECK_AND_RETURN_NOCONFIG(s,n) \ if( 0 == strcmp( name, #s) ) return MRCAL_##s; #define CHECK_AND_RETURN_WITHCONFIG(s,n) \ /* Configured model. If the name is followed by _ or nothing, I */ \ /* accept this model */ \ { \ const int len_s = strlen(#s); \ if( 0 == strncmp( name, #s, len_s) && \ ( name[len_s] == '\0' || \ name[len_s] == '_' ) ) \ return MRCAL_##s; \ } if(name == NULL) return MRCAL_LENSMODEL_INVALID_TYPE; MRCAL_LENSMODEL_NOCONFIG_LIST( CHECK_AND_RETURN_NOCONFIG ); MRCAL_LENSMODEL_WITHCONFIG_STATIC_NPARAMS_LIST( CHECK_AND_RETURN_WITHCONFIG ); MRCAL_LENSMODEL_WITHCONFIG_DYNAMIC_NPARAMS_LIST( CHECK_AND_RETURN_WITHCONFIG ); return MRCAL_LENSMODEL_INVALID_TYPE; #undef CHECK_AND_RETURN_NOCONFIG #undef CHECK_AND_RETURN_WITHCONFIG } mrcal_lensmodel_metadata_t mrcal_lensmodel_metadata( const mrcal_lensmodel_t* lensmodel ) { switch(lensmodel->type) { case MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC: case MRCAL_LENSMODEL_STEREOGRAPHIC: case MRCAL_LENSMODEL_LONLAT: case MRCAL_LENSMODEL_LATLON: return (mrcal_lensmodel_metadata_t) { .has_core = true, .can_project_behind_camera = true, .has_gradients = true, .noncentral = false}; case MRCAL_LENSMODEL_PINHOLE: case MRCAL_LENSMODEL_OPENCV4: case MRCAL_LENSMODEL_OPENCV5: case MRCAL_LENSMODEL_OPENCV8: case MRCAL_LENSMODEL_OPENCV12: case MRCAL_LENSMODEL_CAHVOR: return (mrcal_lensmodel_metadata_t) { .has_core = true, .can_project_behind_camera = false, .has_gradients = true, .noncentral = false }; case MRCAL_LENSMODEL_CAHVORE: return (mrcal_lensmodel_metadata_t) { .has_core = true, .can_project_behind_camera = false, .has_gradients = true, .noncentral = true }; default: ; } MSG("Unknown lens model %d. Barfing out", lensmodel->type); assert(0); } static bool modelHasCore_fxfycxcy( const mrcal_lensmodel_t* lensmodel ) { mrcal_lensmodel_metadata_t meta = mrcal_lensmodel_metadata(lensmodel); return meta.has_core; } static bool model_supports_projection_behind_camera( const mrcal_lensmodel_t* lensmodel ) { mrcal_lensmodel_metadata_t meta = mrcal_lensmodel_metadata(lensmodel); return meta.can_project_behind_camera; } static int LENSMODEL_SPLINED_STEREOGRAPHIC__lensmodel_num_params(const mrcal_LENSMODEL_SPLINED_STEREOGRAPHIC__config_t* config) { return // I have two surfaces: one for x and another for y (int)config->Nx * (int)config->Ny * 2 + // and I have a core 4; } int mrcal_lensmodel_num_params(const mrcal_lensmodel_t* lensmodel) { #define CHECK_CONFIG_NPARAM_NOCONFIG(s,n) \ _Static_assert(n >= 0, "no-config implies known-at-compile-time param count"); switch(lensmodel->type) { #define CASE_NUM_STATIC(s,n) \ case MRCAL_##s: return n; #define CASE_NUM_DYNAMIC(s,n) \ case MRCAL_##s: return s##__lensmodel_num_params(&lensmodel->s##__config); MRCAL_LENSMODEL_NOCONFIG_LIST( CASE_NUM_STATIC ) MRCAL_LENSMODEL_WITHCONFIG_STATIC_NPARAMS_LIST( CASE_NUM_STATIC ) MRCAL_LENSMODEL_WITHCONFIG_DYNAMIC_NPARAMS_LIST( CASE_NUM_DYNAMIC ) default: ; } return -1; #undef CASE_NUM_NOCONFIG #undef CASE_NUM_WITHCONFIG } static int get_num_distortions_optimization_params(mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel) { if( !problem_selections.do_optimize_intrinsics_distortions ) return 0; int N = mrcal_lensmodel_num_params(lensmodel); if(modelHasCore_fxfycxcy(lensmodel)) N -= 4; // ignoring fx,fy,cx,cy return N; } int mrcal_num_intrinsics_optimization_params(mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel) { int N = get_num_distortions_optimization_params(problem_selections, lensmodel); if( problem_selections.do_optimize_intrinsics_core && modelHasCore_fxfycxcy(lensmodel) ) N += 4; // fx,fy,cx,cy return N; } int mrcal_num_states(int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel) { return mrcal_num_states_intrinsics(Ncameras_intrinsics, problem_selections, lensmodel) + mrcal_num_states_extrinsics(Ncameras_extrinsics, problem_selections) + mrcal_num_states_frames(Nframes, problem_selections) + mrcal_num_states_points(Npoints, Npoints_fixed, problem_selections) + mrcal_num_states_calobject_warp( problem_selections, Nobservations_board); } static int num_regularization_terms_percamera(mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel) { if(!problem_selections.do_apply_regularization) return 0; // distortions int N = get_num_distortions_optimization_params(problem_selections, lensmodel); // optical center if(problem_selections.do_optimize_intrinsics_core) N += 2; return N; } int mrcal_measurement_index_boards(int i_observation_board, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n) { if(Nobservations_board <= 0) return -1; // *2 because I have separate x and y measurements return 0 + mrcal_num_measurements_boards(i_observation_board, calibration_object_width_n, calibration_object_height_n); } int mrcal_num_measurements_boards(int Nobservations_board, int calibration_object_width_n, int calibration_object_height_n) { if(Nobservations_board <= 0) return 0; // *2 because I have separate x and y measurements return Nobservations_board * calibration_object_width_n*calibration_object_height_n * 2; return mrcal_measurement_index_boards( Nobservations_board, 0,0, calibration_object_width_n, calibration_object_height_n); } int mrcal_measurement_index_points(int i_observation_point, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n) { if(Nobservations_point <= 0) return -1; // 3: x,y measurements, range normalization return mrcal_num_measurements_boards(Nobservations_board, calibration_object_width_n, calibration_object_height_n) + i_observation_point * 3; } int mrcal_num_measurements_points(int Nobservations_point) { // 3: x,y measurements, range normalization return Nobservations_point * 3; } int mrcal_measurement_index_regularization(int calibration_object_width_n, int calibration_object_height_n, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel) { if(mrcal_num_measurements_regularization(Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, Nobservations_board, problem_selections, lensmodel) <= 0) return -1; return mrcal_num_measurements_boards(Nobservations_board, calibration_object_width_n, calibration_object_height_n) + mrcal_num_measurements_points(Nobservations_point); } int mrcal_num_measurements_regularization(int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel) { return Ncameras_intrinsics * num_regularization_terms_percamera(problem_selections, lensmodel); } int mrcal_num_measurements(int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel) { return mrcal_num_measurements_boards( Nobservations_board, calibration_object_width_n, calibration_object_height_n) + mrcal_num_measurements_points(Nobservations_point) + mrcal_num_measurements_regularization(Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, Nobservations_board, problem_selections, lensmodel); } static bool has_calobject_warp(mrcal_problem_selections_t problem_selections, int Nobservations_board) { return problem_selections.do_optimize_calobject_warp && Nobservations_board>0; } int _mrcal_num_j_nonzero(int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, const mrcal_observation_board_t* observations_board, const mrcal_observation_point_t* observations_point, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel) { // each observation depends on all the parameters for THAT frame and for // THAT camera. Camera0 doesn't have extrinsics, so I need to loop through // all my observations // Each projected point has an x and y measurement, and each one depends on // some number of the intrinsic parameters. Parametric models are simple: // each one depends on ALL of the intrinsics. Splined models are sparse, // however, and there's only a partial dependence int Nintrinsics_per_measurement; if(lensmodel->type == MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC) { int run_len = lensmodel->LENSMODEL_SPLINED_STEREOGRAPHIC__config.order + 1; Nintrinsics_per_measurement = (problem_selections.do_optimize_intrinsics_core ? 4 : 0) + (problem_selections.do_optimize_intrinsics_distortions ? (run_len*run_len) : 0); } else Nintrinsics_per_measurement = mrcal_num_intrinsics_optimization_params(problem_selections, lensmodel); // x depends on fx,cx but NOT on fy, cy. And similarly for y. if( problem_selections.do_optimize_intrinsics_core && modelHasCore_fxfycxcy(lensmodel) ) Nintrinsics_per_measurement -= 2; int N = Nobservations_board * ( (problem_selections.do_optimize_frames ? 6 : 0) + (problem_selections.do_optimize_extrinsics ? 6 : 0) + (has_calobject_warp(problem_selections,Nobservations_board) ? MRCAL_NSTATE_CALOBJECT_WARP : 0) + Nintrinsics_per_measurement ); // initial estimate counts extrinsics for the reference camera, which need // to be subtracted off if(problem_selections.do_optimize_extrinsics) for(int i=0; i= 0 ) N += 2*6; // range normalization if(problem_selections.do_optimize_frames && observations_point[i].i_point < Npoints-Npoints_fixed ) N += 3; if( problem_selections.do_optimize_extrinsics && observations_point[i].icam.extrinsics >= 0 ) N += 6; } if(lensmodel->type == MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC) { if(problem_selections.do_apply_regularization) { // Each regularization term depends on // - two values for distortions // - one value for the center pixel N += Ncameras_intrinsics * 2 * num_regularization_terms_percamera(problem_selections, lensmodel); // I multiplied by 2, so I double-counted the center pixel // contributions. Subtract those off if(problem_selections.do_optimize_intrinsics_core) N -= Ncameras_intrinsics*2; } } else N += Ncameras_intrinsics * num_regularization_terms_percamera(problem_selections, lensmodel); return N; } // Used in the spline-based projection function. // // See bsplines.py for the derivation of the spline expressions and for // justification of the 2D scheme // // Here we sample two interpolated surfaces at once: one each for the x and y // focal-length scales // // The sampling function assumes evenly spaced knots. // a,b,c,d are sequential control points // x is in [0,1] between b and c. Function looks like this: // double A = fA(x); // double B = fB(x); // double C = fC(x); // double D = fD(x); // return A*a + B*b + C*c + D*d; // I need to sample many such 1D segments, so I compute A,B,C,D separately, // and apply them together static void get_sample_coeffs__cubic(double* ABCD, double* ABCDgrad, double x) { double x2 = x*x; double x3 = x2*x; ABCD[0] = (-x3 + 3*x2 - 3*x + 1)/6; ABCD[1] = (3 * x3/2 - 3*x2 + 2)/3; ABCD[2] = (-3 * x3 + 3*x2 + 3*x + 1)/6; ABCD[3] = x3 / 6; ABCDgrad[0] = -x2/2 + x - 1./2.; ABCDgrad[1] = 3*x2/2 - 2*x; ABCDgrad[2] = -3*x2/2 + x + 1./2.; ABCDgrad[3] = x2 / 2; } static void interp__cubic(double* out, const double* ABCDx, const double* ABCDy, // control points const double* c, int stridey) { double cinterp[4][2]; const int stridex = 2; for(int iy=0; iy<4; iy++) for(int k=0;k<2;k++) cinterp[iy][k] = ABCDx[0] * c[iy*stridey + 0*stridex + k] + ABCDx[1] * c[iy*stridey + 1*stridex + k] + ABCDx[2] * c[iy*stridey + 2*stridex + k] + ABCDx[3] * c[iy*stridey + 3*stridex + k]; for(int k=0;k<2;k++) out[k] = ABCDy[0] * cinterp[0][k] + ABCDy[1] * cinterp[1][k] + ABCDy[2] * cinterp[2][k] + ABCDy[3] * cinterp[3][k]; } static void sample_bspline_surface_cubic(double* out, double* dout_dx, double* dout_dy, double* ABCDx_ABCDy, double x, double y, // control points const double* c, int stridey // stridex is 2: the control points from the // two surfaces are next to each other. Better // cache locality maybe ) { double* ABCDx = &ABCDx_ABCDy[0]; double* ABCDy = &ABCDx_ABCDy[4]; // 4 samples along one dimension, and then one sample along the other // dimension, using the 4 samples as the control points. Order doesn't // matter. See bsplines.py // // I do this twice: one for each focal length surface double ABCDgradx[4]; double ABCDgrady[4]; get_sample_coeffs__cubic(ABCDx, ABCDgradx, x); get_sample_coeffs__cubic(ABCDy, ABCDgrady, y); // the intrinsics gradient is flatten(ABCDx[0..3] * ABCDy[0..3]) for both x // and y. By returning ABCD[xy] and not the cartesian products, I make // smaller temporary data arrays interp__cubic(out, ABCDx, ABCDy, c, stridey); interp__cubic(dout_dx, ABCDgradx, ABCDy, c, stridey); interp__cubic(dout_dy, ABCDx, ABCDgrady, c, stridey); } // The sampling function assumes evenly spaced knots. // a,b,c are sequential control points // x is in [-1/2,1/2] around b. Function looks like this: // double A = fA(x); // double B = fB(x); // double C = fC(x); // return A*a + B*b + C*c; // I need to sample many such 1D segments, so I compute A,B,C separately, // and apply them together static void get_sample_coeffs__quadratic(double* ABC, double* ABCgrad, double x) { double x2 = x*x; ABC[0] = (4*x2 - 4*x + 1)/8; ABC[1] = (3 - 4*x2)/4; ABC[2] = (4*x2 + 4*x + 1)/8; ABCgrad[0] = x - 1./2.; ABCgrad[1] = -2.*x; ABCgrad[2] = x + 1./2.; } static void interp__quadratic(double* out, const double* ABCx, const double* ABCy, // control points const double* c, int stridey) { double cinterp[3][2]; const int stridex = 2; for(int iy=0; iy<3; iy++) for(int k=0;k<2;k++) cinterp[iy][k] = ABCx[0] * c[iy*stridey + 0*stridex + k] + ABCx[1] * c[iy*stridey + 1*stridex + k] + ABCx[2] * c[iy*stridey + 2*stridex + k]; for(int k=0;k<2;k++) out[k] = ABCy[0] * cinterp[0][k] + ABCy[1] * cinterp[1][k] + ABCy[2] * cinterp[2][k]; } static void sample_bspline_surface_quadratic(double* out, double* dout_dx, double* dout_dy, double* ABCx_ABCy, double x, double y, // control points const double* c, int stridey // stridex is 2: the control points from the // two surfaces are next to each other. Better // cache locality maybe ) { double* ABCx = &ABCx_ABCy[0]; double* ABCy = &ABCx_ABCy[3]; // 3 samples along one dimension, and then one sample along the other // dimension, using the 3 samples as the control points. Order doesn't // matter. See bsplines.py // // I do this twice: one for each focal length surface double ABCgradx[3]; double ABCgrady[3]; get_sample_coeffs__quadratic(ABCx, ABCgradx, x); get_sample_coeffs__quadratic(ABCy, ABCgrady, y); // the intrinsics gradient is flatten(ABCx[0..3] * ABCy[0..3]) for both x // and y. By returning ABC[xy] and not the cartesian products, I make // smaller temporary data arrays interp__quadratic(out, ABCx, ABCy, c, stridey); interp__quadratic(dout_dx, ABCgradx, ABCy, c, stridey); interp__quadratic(dout_dy, ABCx, ABCgrady, c, stridey); } typedef struct { double _d_rj_rf[3*3]; double _d_rj_rc[3*3]; double _d_tj_tf[3*3]; double _d_tj_rc[3*3]; // _d_tj_tc is always identity // _d_tj_rf is always 0 // _d_rj_tf is always 0 // _d_rj_tc is always 0 } geometric_gradients_t; static void project_cahvor( // outputs mrcal_point2_t* restrict q, mrcal_point2_t* restrict dq_dfxy, double* restrict dq_dintrinsics_nocore, mrcal_point3_t* restrict dq_drcamera, mrcal_point3_t* restrict dq_dtcamera, mrcal_point3_t* restrict dq_drframe, mrcal_point3_t* restrict dq_dtframe, // inputs const mrcal_point3_t* restrict p, const mrcal_point3_t* restrict dp_drc, const mrcal_point3_t* restrict dp_dtc, const mrcal_point3_t* restrict dp_drf, const mrcal_point3_t* restrict dp_dtf, const double* restrict intrinsics, bool camera_at_identity, const mrcal_lensmodel_t* lensmodel) { int NdistortionParams = mrcal_lensmodel_num_params(lensmodel) - 4; // I perturb p, and then apply the focal length, center pixel stuff // normally mrcal_point3_t p_distorted; bool need_any_extrinsics_gradients = ( dq_drcamera != NULL ) || ( dq_dtcamera != NULL ) || ( dq_drframe != NULL ) || ( dq_dtframe != NULL ); // distortion parameter layout: // alpha // beta // r0 // r1 // r2 double alpha = intrinsics[4 + 0]; double beta = intrinsics[4 + 1]; double r0 = intrinsics[4 + 2]; double r1 = intrinsics[4 + 3]; double r2 = intrinsics[4 + 4]; double s_al = sin(alpha); double c_al = cos(alpha); double s_be = sin(beta); double c_be = cos(beta); // I parametrize the optical axis such that // - o(alpha=0, beta=0) = (0,0,1) i.e. the optical axis is at the center // if both parameters are 0 // - The gradients are cartesian. I.e. do/dalpha and do/dbeta are both // NOT 0 at (alpha=0,beta=0). This would happen at the poles (gimbal // lock), and that would make my solver unhappy double o [] = { s_al*c_be, s_be, c_al*c_be }; double do_dalpha[] = { c_al*c_be, 0, -s_al*c_be }; double do_dbeta[] = { -s_al*s_be, c_be, -c_al*s_be }; double norm2p = norm2_vec(3, p->xyz); double omega = dot_vec(3, p->xyz, o); double domega_dalpha = dot_vec(3, p->xyz, do_dalpha); double domega_dbeta = dot_vec(3, p->xyz, do_dbeta); double omega_recip = 1.0 / omega; double tau = norm2p * omega_recip*omega_recip - 1.0; double s__dtau_dalphabeta__domega_dalphabeta = -2.0*norm2p * omega_recip*omega_recip*omega_recip; double dmu_dtau = r1 + 2.0*tau*r2; double dmu_dxyz[3]; for(int i=0; i<3; i++) dmu_dxyz[i] = dmu_dtau * (2.0 * p->xyz[i] * omega_recip*omega_recip + s__dtau_dalphabeta__domega_dalphabeta * o[i]); double mu = r0 + tau*r1 + tau*tau*r2; double s__dmu_dalphabeta__domega_dalphabeta = dmu_dtau * s__dtau_dalphabeta__domega_dalphabeta; double dpdistorted_dpcam[3*3] = {}; double dpdistorted_ddistortion[3*NdistortionParams]; for(int i=0; i<3; i++) { double dmu_ddist[5] = { s__dmu_dalphabeta__domega_dalphabeta * domega_dalpha, s__dmu_dalphabeta__domega_dalphabeta * domega_dbeta, 1.0, tau, tau * tau }; dpdistorted_ddistortion[i*NdistortionParams + 0] = p->xyz[i] * dmu_ddist[0]; dpdistorted_ddistortion[i*NdistortionParams + 1] = p->xyz[i] * dmu_ddist[1]; dpdistorted_ddistortion[i*NdistortionParams + 2] = p->xyz[i] * dmu_ddist[2]; dpdistorted_ddistortion[i*NdistortionParams + 3] = p->xyz[i] * dmu_ddist[3]; dpdistorted_ddistortion[i*NdistortionParams + 4] = p->xyz[i] * dmu_ddist[4]; dpdistorted_ddistortion[i*NdistortionParams + 0] -= dmu_ddist[0] * omega*o[i]; dpdistorted_ddistortion[i*NdistortionParams + 1] -= dmu_ddist[1] * omega*o[i]; dpdistorted_ddistortion[i*NdistortionParams + 2] -= dmu_ddist[2] * omega*o[i]; dpdistorted_ddistortion[i*NdistortionParams + 3] -= dmu_ddist[3] * omega*o[i]; dpdistorted_ddistortion[i*NdistortionParams + 4] -= dmu_ddist[4] * omega*o[i]; dpdistorted_ddistortion[i*NdistortionParams + 0] -= mu * domega_dalpha*o[i]; dpdistorted_ddistortion[i*NdistortionParams + 1] -= mu * domega_dbeta *o[i]; dpdistorted_ddistortion[i*NdistortionParams + 0] -= mu * omega * do_dalpha[i]; dpdistorted_ddistortion[i*NdistortionParams + 1] -= mu * omega * do_dbeta [i]; dpdistorted_dpcam[3*i + i] = mu+1.0; for(int j=0; j<3; j++) { dpdistorted_dpcam[3*i + j] += (p->xyz[i] - omega*o[i]) * dmu_dxyz[j]; dpdistorted_dpcam[3*i + j] -= mu*o[i]*o[j]; } p_distorted.xyz[i] = p->xyz[i] + mu * (p->xyz[i] - omega*o[i]); } // q = fxy pxy/pz + cxy // dqx/dp = d( fx px/pz + cx ) = fx/pz^2 (pz [1 0 0] - px [0 0 1]) // dqy/dp = d( fy py/pz + cy ) = fy/pz^2 (pz [0 1 0] - py [0 0 1]) const double fx = intrinsics[0]; const double fy = intrinsics[1]; const double cx = intrinsics[2]; const double cy = intrinsics[3]; double pz_recip = 1. / p_distorted.z; q->x = p_distorted.x*pz_recip * fx + cx; q->y = p_distorted.y*pz_recip * fy + cy; if(need_any_extrinsics_gradients) { double dq_dp[2][3] = { { fx * pz_recip, 0, -fx*p_distorted.x*pz_recip*pz_recip}, { 0, fy * pz_recip, -fy*p_distorted.y*pz_recip*pz_recip} }; // This is for the DISTORTED p. // dq/deee = dq/dpdistorted dpdistorted/dpundistorted dpundistorted/deee double dq_dpundistorted[6]; mul_genN3_gen33_vout(2, (double*)dq_dp, dpdistorted_dpcam, dq_dpundistorted); // dq/deee = dq/dp dp/deee if(camera_at_identity) { if( dq_drcamera != NULL ) memset(dq_drcamera, 0, 6*sizeof(double)); if( dq_dtcamera != NULL ) memset(dq_dtcamera, 0, 6*sizeof(double)); if( dq_drframe != NULL ) mul_genN3_gen33_vout(2, (double*)dq_dpundistorted, (double*)dp_drf, (double*)dq_drframe); if( dq_dtframe != NULL ) memcpy(dq_dtframe, dq_dpundistorted, 6*sizeof(double)); } else { if( dq_drcamera != NULL ) mul_genN3_gen33_vout(2, (double*)dq_dpundistorted, (double*)dp_drc, (double*)dq_drcamera); if( dq_dtcamera != NULL ) mul_genN3_gen33_vout(2, (double*)dq_dpundistorted, (double*)dp_dtc, (double*)dq_dtcamera); if( dq_drframe != NULL ) mul_genN3_gen33_vout(2, (double*)dq_dpundistorted, (double*)dp_drf, (double*)dq_drframe ); if( dq_dtframe != NULL ) mul_genN3_gen33_vout(2, (double*)dq_dpundistorted, (double*)dp_dtf, (double*)dq_dtframe ); } } if( dq_dintrinsics_nocore != NULL ) { for(int i=0; ix = (q->x - cx)/fx; // dqx/dfx dq_dfxy->y = (q->y - cy)/fy; // dqy/dfy } } static bool project_cahvore( // outputs mrcal_point2_t* restrict q, mrcal_point2_t* restrict dq_dfxy, double* restrict dq_dintrinsics_nocore, mrcal_point3_t* restrict dq_drcamera, mrcal_point3_t* restrict dq_dtcamera, mrcal_point3_t* restrict dq_drframe, mrcal_point3_t* restrict dq_dtframe, // inputs const mrcal_point3_t* restrict p, const mrcal_point3_t* restrict dp_drc, const mrcal_point3_t* restrict dp_dtc, const mrcal_point3_t* restrict dp_drf, const mrcal_point3_t* restrict dp_dtf, const double* restrict intrinsics, bool camera_at_identity, const mrcal_lensmodel_t* lensmodel) { int NdistortionParams = mrcal_lensmodel_num_params(lensmodel) - 4; // This is 8: alpha,beta,R,E mrcal_point3_t p_distorted; double dpdistorted_ddistortion[8*3]; // 8 intrinsics parameters, nvec(p)=3 double dpdistorted_dpcam[3*3]; bool need_any_extrinsics_gradients = ( dq_drcamera != NULL ) || ( dq_dtcamera != NULL ) || ( dq_drframe != NULL ) || ( dq_dtframe != NULL ); if(!project_cahvore_internals( // outputs &p_distorted, dq_dintrinsics_nocore ? dpdistorted_ddistortion : NULL, need_any_extrinsics_gradients ? dpdistorted_dpcam : NULL, // inputs p, &intrinsics[4], lensmodel->LENSMODEL_CAHVORE__config.linearity)) return false; ////////////// exactly like in project_cahvor() above. Consolidate. // q = fxy pxy/pz + cxy // dqx/dp = d( fx px/pz + cx ) = fx/pz^2 (pz [1 0 0] - px [0 0 1]) // dqy/dp = d( fy py/pz + cy ) = fy/pz^2 (pz [0 1 0] - py [0 0 1]) const double fx = intrinsics[0]; const double fy = intrinsics[1]; const double cx = intrinsics[2]; const double cy = intrinsics[3]; double pz_recip = 1. / p_distorted.z; q->x = p_distorted.x*pz_recip * fx + cx; q->y = p_distorted.y*pz_recip * fy + cy; if(need_any_extrinsics_gradients) { double dq_dp[2][3] = { { fx * pz_recip, 0, -fx*p_distorted.x*pz_recip*pz_recip}, { 0, fy * pz_recip, -fy*p_distorted.y*pz_recip*pz_recip} }; // This is for the DISTORTED p. // dq/deee = dq/dpdistorted dpdistorted/dpundistorted dpundistorted/deee double dq_dpundistorted[6]; mul_genN3_gen33_vout(2, (double*)dq_dp, dpdistorted_dpcam, dq_dpundistorted); // dq/deee = dq/dp dp/deee if(camera_at_identity) { if( dq_drcamera != NULL ) memset(dq_drcamera, 0, 6*sizeof(double)); if( dq_dtcamera != NULL ) memset(dq_dtcamera, 0, 6*sizeof(double)); if( dq_drframe != NULL ) mul_genN3_gen33_vout(2, (double*)dq_dpundistorted, (double*)dp_drf, (double*)dq_drframe); if( dq_dtframe != NULL ) memcpy(dq_dtframe, dq_dpundistorted, 6*sizeof(double)); } else { if( dq_drcamera != NULL ) mul_genN3_gen33_vout(2, (double*)dq_dpundistorted, (double*)dp_drc, (double*)dq_drcamera); if( dq_dtcamera != NULL ) mul_genN3_gen33_vout(2, (double*)dq_dpundistorted, (double*)dp_dtc, (double*)dq_dtcamera); if( dq_drframe != NULL ) mul_genN3_gen33_vout(2, (double*)dq_dpundistorted, (double*)dp_drf, (double*)dq_drframe ); if( dq_dtframe != NULL ) mul_genN3_gen33_vout(2, (double*)dq_dpundistorted, (double*)dp_dtf, (double*)dq_dtframe ); } } if( dq_dintrinsics_nocore != NULL ) { for(int i=0; ix = (q->x - cx)/fx; // dqx/dfx dq_dfxy->y = (q->y - cy)/fy; // dqy/dfy } return true; } // These are all internals for project(). It was getting unwieldy otherwise static void _project_point_parametric( // outputs mrcal_point2_t* q, mrcal_point2_t* dq_dfxy, double* dq_dintrinsics_nocore, mrcal_point3_t* restrict dq_drcamera, mrcal_point3_t* restrict dq_dtcamera, mrcal_point3_t* restrict dq_drframe, mrcal_point3_t* restrict dq_dtframe, // inputs const mrcal_point3_t* p, const mrcal_point3_t* dp_drc, const mrcal_point3_t* dp_dtc, const mrcal_point3_t* dp_drf, const mrcal_point3_t* dp_dtf, const double* restrict intrinsics, bool camera_at_identity, const mrcal_lensmodel_t* lensmodel) { // u = distort(p, distortions) // q = uxy/uz * fxy + cxy if(!( lensmodel->type == MRCAL_LENSMODEL_PINHOLE || lensmodel->type == MRCAL_LENSMODEL_STEREOGRAPHIC || lensmodel->type == MRCAL_LENSMODEL_LONLAT || lensmodel->type == MRCAL_LENSMODEL_LATLON || MRCAL_LENSMODEL_IS_OPENCV(lensmodel->type) )) { MSG("Unhandled lens model: %d (%s)", lensmodel->type, mrcal_lensmodel_name_unconfigured(lensmodel)); assert(0); } mrcal_point3_t dq_dp[2]; if( lensmodel->type == MRCAL_LENSMODEL_PINHOLE ) mrcal_project_pinhole(q, dq_dp, p, 1, intrinsics); else if(lensmodel->type == MRCAL_LENSMODEL_STEREOGRAPHIC) mrcal_project_stereographic(q, dq_dp, p, 1, intrinsics); else if(lensmodel->type == MRCAL_LENSMODEL_LONLAT) mrcal_project_lonlat(q, dq_dp, p, 1, intrinsics); else if(lensmodel->type == MRCAL_LENSMODEL_LATLON) mrcal_project_latlon(q, dq_dp, p, 1, intrinsics); else { int Nintrinsics = mrcal_lensmodel_num_params(lensmodel); _mrcal_project_internal_opencv( q, dq_dp, dq_dintrinsics_nocore, p, 1, intrinsics, Nintrinsics); } // dq/deee = dq/dp dp/deee if(camera_at_identity) { if( dq_drcamera != NULL ) memset(dq_drcamera, 0, 6*sizeof(double)); if( dq_dtcamera != NULL ) memset(dq_dtcamera, 0, 6*sizeof(double)); if( dq_drframe != NULL ) mul_genN3_gen33_vout(2, (double*)dq_dp, (double*)dp_drf, (double*)dq_drframe); if( dq_dtframe != NULL ) memcpy(dq_dtframe, (double*)dq_dp, 6*sizeof(double)); } else { if( dq_drcamera != NULL ) mul_genN3_gen33_vout(2, (double*)dq_dp, (double*)dp_drc, (double*)dq_drcamera); if( dq_dtcamera != NULL ) mul_genN3_gen33_vout(2, (double*)dq_dp, (double*)dp_dtc, (double*)dq_dtcamera); if( dq_drframe != NULL ) mul_genN3_gen33_vout(2, (double*)dq_dp, (double*)dp_drf, (double*)dq_drframe ); if( dq_dtframe != NULL ) mul_genN3_gen33_vout(2, (double*)dq_dp, (double*)dp_dtf, (double*)dq_dtframe ); } // I have the projection, and I now need to propagate the gradients if( dq_dfxy ) { const double fx = intrinsics[0]; const double fy = intrinsics[1]; const double cx = intrinsics[2]; const double cy = intrinsics[3]; // I have the projection, and I now need to propagate the gradients // xy = fxy * distort(xy)/distort(z) + cxy dq_dfxy->x = (q->x - cx)/fx; // dqx/dfx dq_dfxy->y = (q->y - cy)/fy; // dqy/dfy } } // Compute a pinhole projection using a constant fxy, cxy void mrcal_project_pinhole( // output mrcal_point2_t* q, mrcal_point3_t* dq_dv, // May be NULL. Each point // gets a block of 2 mrcal_point3_t // objects // input const mrcal_point3_t* v, int N, const double* fxycxy) { const double fx = fxycxy[0]; const double fy = fxycxy[1]; const double cx = fxycxy[2]; const double cy = fxycxy[3]; // q = fxy pxy/pz + cxy // dqx/dp = d( fx px/pz + cx ) = fx/pz^2 (pz [1 0 0] - px [0 0 1]) // dqy/dp = d( fy py/pz + cy ) = fy/pz^2 (pz [0 1 0] - py [0 0 1]) for(int i=0; ix = v[i].x*pz_recip * fx + cx; q->y = v[i].y*pz_recip * fy + cy; if(dq_dv) { dq_dv[2*i + 0].x = fx * pz_recip; dq_dv[2*i + 0].y = 0; dq_dv[2*i + 0].z = -fx*v[i].x*pz_recip*pz_recip; dq_dv[2*i + 1].x = 0; dq_dv[2*i + 1].y = fy * pz_recip; dq_dv[2*i + 1].z = -fy*v[i].y*pz_recip*pz_recip; } } } // Compute a pinhole unprojection using a constant fxy, cxy void mrcal_unproject_pinhole( // output mrcal_point3_t* v, mrcal_point2_t* dv_dq, // May be NULL. Each point // gets a block of 3 // mrcal_point2_t objects // input const mrcal_point2_t* q, int N, const double* fxycxy) { const double fx = fxycxy[0]; const double fy = fxycxy[1]; const double cx = fxycxy[2]; const double cy = fxycxy[3]; double fx_recip = 1./fx; double fy_recip = 1./fy; for(int i=0; i u = (q-c)/f // mag(u) = tan(th/2)*2 // // So I can compute th. az comes from the direction of u. This is enough to // compute everything. th is in [0,pi]. // // [ sin(th) cos(az) ] [ cos(az) ] // v = [ sin(th) sin(az) ] ~ [ sin(az) ] // [ cos(th) ] [ 1/tan(th) ] // // mag(u) = tan(th/2)*2 -> mag(u)/2 = tan(th/2) -> // tan(th) = mag(u) / (1 - (mag(u)/2)^2) // 1/tan(th) = (1 - 1/4*mag(u)^2) / mag(u) // // This has a singularity at u=0 (imager center). But I can scale v to avoid // this. So // // [ cos(az) mag(u) ] // v = [ sin(az) mag(u) ] // [ 1 - 1/4*mag(u)^2 ] // // I can simplify this even more. az = atan2(u.y,u.x). cos(az) = u.x/mag(u) -> // // [ u.x ] // v = [ u.y ] // [ 1 - 1/4 mag(u)^2 ] // // Test script to confirm that the project/unproject expressions are // correct. unproj(proj(v))/v should be a constant // // import numpy as np // import numpysane as nps // f = 2000 // c = 1000 // def proj(v): // m = nps.mag(v) // scale = 2.0 / (m + v[..., 2]) // u = v[..., :2] * nps.dummy(scale, -1) // return u * f + c // def unproj(q): // u = (q-c)/f // muxy = nps.mag(u[..., :2]) // m = nps.mag(u) // return nps.mv(nps.cat( u[..., 0], // u[..., 1], // 1 - 1./4.* m*m), // 0, -1) // v = np.array(((1., 2., 3.), // (3., -2., -4.))) // print( unproj(proj(v)) / v) double fx_recip = 1./fx; double fy_recip = 1./fy; for(int i=0; i // dqx/dv = 1/(1 + (vx/vz)^2) 1/vz^2 ( dvx/dv vz - vx dvz/dv ) = // = [vz 0 -vx] / (vx^2 + vz^2) // // qy ~ arcsin( vy / mag(v) ) -> // dqy/dv = 1 / sqrt( 1 - vy^2/norm2(v) ) 1/norm2(v) (dvy/dv mag(v) - dmag(v)/dv vy) // = 1 / sqrt( norm2(v) - vy^2 ) 1/mag(v) ( [0 mag(v) 0] - v/mag(v) vy) // = 1 / sqrt( norm2(v) - vy^2 ) ( [0 1 0] - v/norm2(v) vy) // = 1 / sqrt( vx^2 + vz^2 ) ( [0 1 0] - v/norm2(v) vy) for(int i=0; i vx = vz tan(lon) // -> 1-sin^2(lat) = vz^2 (1 + tan^2(lon)) = // cos^2(lat) = (vz/cos(lon))^2 // // -> vx = cos(lat) sin(lon) // vy = sin(lat) // vz = cos(lat) cos(lon) // // mag(v) is arbitrary, and I can simplify: // // -> v_unnormalized_x = sin(lon) // v_unnormalized_y = tan(lat) // v_unnormalized_z = cos(lon) // // If the computational cost of tan(lat) is smaller than of // sin(lat),cos(lat) and 2 multiplications, then this is a better // representation. A quick web search tells me that the cost of sincos ~ the // cost of either sin or cos. And that tan is more costly. So I use the // normalized form // // dv/dlon = [ cos(lat) cos(lon) 0 -cos(lat) sin(lon)] // dv/dlat = [-sin(lat) sin(lon) cos(lat) -sin(lat) cos(lon)] double fx_recip = 1./fx; double fy_recip = 1./fy; for(int i=0; i u_width_needed/(Nknots-1) = u_interval_size * (1 - Nknots_margin/(Nknots - 1)) // ---> u_width_needed = u_interval_size * (Nknots - 1 - Nknots_margin) // ---> u_interval_size = u_width_needed / (Nknots - 1 - Nknots_margin) int Nknots_margin; if(config->order == 2) { Nknots_margin = 1; if(config->Nx < 3 || config->Ny < 3) { MSG("Quadratic splines: absolute minimum Nx, Ny is 3. Got Nx=%d Ny=%d. Barfing out", config->Nx, config->Ny); assert(0); } } else if(config->order == 3) { Nknots_margin = 2; if(config->Nx < 4 || config->Ny < 4) { MSG("Cubic splines: absolute minimum Nx, Ny is 4. Got Nx=%d Ny=%d. Barfing out", config->Nx, config->Ny); assert(0); } } else { MSG("I only support spline order 2 and 3"); assert(0); } double th_edge_x = (double)config->fov_x_deg/2. * M_PI / 180.; double u_edge_x = tan(th_edge_x / 2.) * 2; precomputed->segments_per_u = (config->Nx - 1 - Nknots_margin) / (u_edge_x*2.); } // NOT A PART OF THE EXTERNAL API. This is exported for the mrcal python wrapper // only void _mrcal_precompute_lensmodel_data(mrcal_projection_precomputed_t* precomputed, const mrcal_lensmodel_t* lensmodel) { // currently only this model has anything if(lensmodel->type == MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC) _mrcal_precompute_lensmodel_data_MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC ( &precomputed->LENSMODEL_SPLINED_STEREOGRAPHIC__precomputed, &lensmodel->LENSMODEL_SPLINED_STEREOGRAPHIC__config ); precomputed->ready = true; } bool mrcal_knots_for_splined_models( // buffers must hold at least // config->Nx and config->Ny values // respectively double* ux, double* uy, const mrcal_lensmodel_t* lensmodel) { if(lensmodel->type != MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC) { MSG("This function works only with the MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC model. '%s' passed in", mrcal_lensmodel_name_unconfigured(lensmodel)); return false; } mrcal_projection_precomputed_t precomputed_all; _mrcal_precompute_lensmodel_data(&precomputed_all, lensmodel); const mrcal_LENSMODEL_SPLINED_STEREOGRAPHIC__config_t* config = &lensmodel->LENSMODEL_SPLINED_STEREOGRAPHIC__config; const mrcal_LENSMODEL_SPLINED_STEREOGRAPHIC__precomputed_t* precomputed = &precomputed_all.LENSMODEL_SPLINED_STEREOGRAPHIC__precomputed; // The logic I'm reversing is // double ix = u.x*segments_per_u + (double)(Nx-1)/2.; for(int i=0; iNx; i++) ux[i] = ((double)i - (double)(config->Nx-1)/2.) / precomputed->segments_per_u; for(int i=0; iNy; i++) uy[i] = ((double)i - (double)(config->Ny-1)/2.) / precomputed->segments_per_u; return true; } static int get_Ngradients(const mrcal_lensmodel_t* lensmodel, int Nintrinsics) { int N = 0; bool has_core = modelHasCore_fxfycxcy(lensmodel); bool has_dense_intrinsics_grad = (lensmodel->type != MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC); bool has_sparse_intrinsics_grad = (lensmodel->type == MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC); int runlen = (lensmodel->type == MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC) ? (lensmodel->LENSMODEL_SPLINED_STEREOGRAPHIC__config.order + 1) : 0; if(has_core) // qx(fx) and qy(fy) N += 2; if(has_dense_intrinsics_grad) // each of (qx,qy) depends on all the non-core intrinsics N += 2 * (Nintrinsics-4); if(has_sparse_intrinsics_grad) { // spline coefficients N += 2*runlen; } return N; } static void propagate_extrinsics__splined( // output mrcal_point3_t* dq_deee, // input const mrcal_point3_t* dp_deee, const double* duxy_dp, const double* ddeltau_dux, const double* ddeltau_duy, const double fx, const double fy) { mrcal_point3_t du_deee[2]; mul_genN3_gen33_vout(2, (double*)duxy_dp, (double*)dp_deee, (double*)du_deee); for(int i=0; i<3; i++) { dq_deee[0].xyz[i] = fx * ( du_deee[0].xyz[i] * (1. + ddeltau_dux[0]) + ddeltau_duy[0] * du_deee[1].xyz[i]); dq_deee[1].xyz[i] = fy * ( du_deee[1].xyz[i] * (1. + ddeltau_duy[1]) + ddeltau_dux[1] * du_deee[0].xyz[i]); } } static void propagate_extrinsics_cam0__splined( // output mrcal_point3_t* dq_deee, // input const double* dux_dp, const double* duy_dp, const double* ddeltau_dux, const double* ddeltau_duy, const double fx, const double fy) { for(int i=0; i<3; i++) { dq_deee[0].xyz[i] = fx * ( dux_dp[i] * (1. + ddeltau_dux[0]) + ddeltau_duy[0] * duy_dp[i]); dq_deee[1].xyz[i] = fy * ( duy_dp[i] * (1. + ddeltau_duy[1]) + ddeltau_dux[1] * dux_dp[i]); } } static void _project_point_splined( // outputs mrcal_point2_t* q, mrcal_point2_t* dq_dfxy, double* grad_ABCDx_ABCDy, int* ivar0, // Gradient outputs. May be NULL mrcal_point3_t* restrict dq_drcamera, mrcal_point3_t* restrict dq_dtcamera, mrcal_point3_t* restrict dq_drframe, mrcal_point3_t* restrict dq_dtframe, // inputs const mrcal_point3_t* restrict p, const mrcal_point3_t* restrict dp_drc, const mrcal_point3_t* restrict dp_dtc, const mrcal_point3_t* restrict dp_drf, const mrcal_point3_t* restrict dp_dtf, const double* restrict intrinsics, bool camera_at_identity, int spline_order, uint16_t Nx, uint16_t Ny, double segments_per_u) { // projections out-of-bounds will yield SOME value (function remains // continuous as we move out-of-bounds), but it wont be particularly // meaningful // stereographic projection: // (from https://en.wikipedia.org/wiki/Fisheye_lens) // u = xy_unit * tan(th/2) * 2 // // I compute the normalized (focal-length = 1) projection, and // use that to look-up deltau // th is the angle between the observation and the projection // center // // sin(th) = mag_pxy/mag_p // cos(th) = z/mag_p // tan(th/2) = sin(th) / (1 + cos(th)) // tan(th/2) = mag_pxy/mag_p / (1 + z/mag_p) = // = mag_pxy / (mag_p + z) // u = xy_unit * tan(th/2) * 2 = // = xy/mag_pxy * mag_pxy/(mag_p + z) * 2 = // = xy / (mag_p + z) * 2 // // The stereographic projection is used to query the spline surface, and it // is also the projection baseline. I do // // q = (u + deltau(u)) * f + c // // If the spline surface is at 0 (deltau == 0) then this is a pure // stereographic projection double mag_p = sqrt( p->x*p->x + p->y*p->y + p->z*p->z ); double scale = 2.0 / (mag_p + p->z); mrcal_point2_t u = {.x = p->x * scale, .y = p->y * scale}; // du/dp = d/dp ( xy * scale ) // = pxy dscale/dp + [I; 0] scale // dscale/dp = d (2.0 / (mag_p + p->z))/dp = // = -2/()^2 ( [0,0,1] + dmag/dp) // = -2/()^2 ( [0,0,1] + 2pt/2mag) // = -2 scale^2/4 ( [0,0,1] + pt/mag) // = -scale^2/2 * ( [0,0,1] + pt/mag ) // = A*[0,0,1] + B*pt double A = -scale*scale / 2.; double B = A / mag_p; double du_dp[2][3] = { { p->x * (B * p->x) + scale, p->x * (B * p->y), p->x * (B * p->z + A) }, { p->y * (B * p->x), p->y * (B * p->y) + scale, p->y * (B * p->z + A) } }; double ix = u.x*segments_per_u + (double)(Nx-1)/2.; double iy = u.y*segments_per_u + (double)(Ny-1)/2.; mrcal_point2_t deltau; double ddeltau_dux[2]; double ddeltau_duy[2]; const double fx = intrinsics[0]; const double fy = intrinsics[1]; const double cx = intrinsics[2]; const double cy = intrinsics[3]; if( spline_order == 3 ) { int ix0 = (int)ix; int iy0 = (int)iy; // If out-of-bounds, clamp to the nearest valid spline segment. The // projection will fly off to infinity quickly (we're extrapolating a // polynomial), but at least it'll stay continuous if( ix0 < 1) ix0 = 1; else if(ix0 > Nx-3) ix0 = Nx-3; if( iy0 < 1) iy0 = 1; else if(iy0 > Ny-3) iy0 = Ny-3; *ivar0 = 4 + // skip the core 2*( (iy0-1)*Nx + (ix0-1) ); sample_bspline_surface_cubic(deltau.xy, ddeltau_dux, ddeltau_duy, grad_ABCDx_ABCDy, ix - ix0, iy - iy0, // control points &intrinsics[*ivar0], 2*Nx); } else if( spline_order == 2 ) { int ix0 = (int)(ix + 0.5); int iy0 = (int)(iy + 0.5); // If out-of-bounds, clamp to the nearest valid spline segment. The // projection will fly off to infinity quickly (we're extrapolating a // polynomial), but at least it'll stay continuous if( ix0 < 1) ix0 = 1; else if(ix0 > Nx-2) ix0 = Nx-2; if( iy0 < 1) iy0 = 1; else if(iy0 > Ny-2) iy0 = Ny-2; *ivar0 = 4 + // skip the core 2*( (iy0-1)*Nx + (ix0-1) ); sample_bspline_surface_quadratic(deltau.xy, ddeltau_dux, ddeltau_duy, grad_ABCDx_ABCDy, ix - ix0, iy - iy0, // control points &intrinsics[*ivar0], 2*Nx); } else { MSG("I only support spline order==2 or 3. Somehow got %d. This is a bug. Barfing", spline_order); assert(0); } // u = stereographic(p) // q = (u + deltau(u)) * f + c // // Extrinsics: // dqx/deee = fx (dux/deee + ddeltaux/du du/deee) // = fx ( dux/deee (1 + ddeltaux/dux) + ddeltaux/duy duy/deee) // dqy/deee = fy ( duy/deee (1 + ddeltauy/duy) + ddeltauy/dux dux/deee) q->x = (u.x + deltau.x) * fx + cx; q->y = (u.y + deltau.y) * fy + cy; if( dq_dfxy ) { // I have the projection, and I now need to propagate the gradients // xy = fxy * distort(xy)/distort(z) + cxy dq_dfxy->x = u.x + deltau.x; dq_dfxy->y = u.y + deltau.y; } // convert ddeltau_dixy to ddeltau_duxy for(int i=0; i<2; i++) { ddeltau_dux[i] *= segments_per_u; ddeltau_duy[i] *= segments_per_u; } if(camera_at_identity) { if( dq_drcamera != NULL ) memset(dq_drcamera->xyz, 0, 6*sizeof(double)); if( dq_dtcamera != NULL ) memset(dq_dtcamera->xyz, 0, 6*sizeof(double)); if( dq_drframe != NULL ) propagate_extrinsics__splined( dq_drframe, dp_drf, (const double*)du_dp, ddeltau_dux, ddeltau_duy, fx,fy); if( dq_dtframe != NULL ) propagate_extrinsics_cam0__splined( dq_dtframe, du_dp[0], du_dp[1], ddeltau_dux, ddeltau_duy, fx, fy); } else { if( dq_drcamera != NULL ) propagate_extrinsics__splined( dq_drcamera, dp_drc, (const double*)du_dp, ddeltau_dux, ddeltau_duy, fx,fy); if( dq_dtcamera != NULL ) propagate_extrinsics__splined( dq_dtcamera, dp_dtc, (const double*)du_dp, ddeltau_dux, ddeltau_duy, fx,fy); if( dq_drframe != NULL ) propagate_extrinsics__splined( dq_drframe, dp_drf, (const double*)du_dp, ddeltau_dux, ddeltau_duy, fx,fy); if( dq_dtframe != NULL ) propagate_extrinsics__splined( dq_dtframe, dp_dtf, (const double*)du_dp, ddeltau_dux, ddeltau_duy, fx,fy); } } typedef struct { double* pool; uint16_t run_side_length; uint16_t ivar_stridey; } gradient_sparse_meta_t; // This is internal to project() static void _propagate_extrinsics_one(mrcal_point3_t* dp_dparam, const mrcal_point3_t* pt_ref, const double* drj_dparam, const double* dtj_dparam, const double* d_Rj_rj) { // dRj[row0]/drj is 3x3 matrix at &d_Rj_rj[0] // dRj[row0]/drc = dRj[row0]/drj * drj_drc for(int i=0; i<3; i++) { mul_vec3_gen33_vout( pt_ref->xyz, &d_Rj_rj[9*i], dp_dparam[i].xyz ); mul_vec3_gen33 ( dp_dparam[i].xyz, drj_dparam); add_vec(3, dp_dparam[i].xyz, &dtj_dparam[3*i] ); } } static void _propagate_extrinsics_one_rzero(mrcal_point3_t* dp_dparam, const mrcal_point3_t* pt_ref, const double* dtj_dparam, const double* d_Rj_rj) { // dRj[row0]/drj is 3x3 matrix at &d_Rj_rj[0] // dRj[row0]/drc = dRj[row0]/drj * drj_drc memcpy(dp_dparam->xyz, dtj_dparam, 9*sizeof(double)); } static void _propagate_extrinsics_one_tzero(mrcal_point3_t* dp_dparam, const mrcal_point3_t* pt_ref, const double* drj_dparam, const double* d_Rj_rj) { // dRj[row0]/drj is 3x3 matrix at &d_Rj_rj[0] // dRj[row0]/drc = dRj[row0]/drj * drj_drc for(int i=0; i<3; i++) { mul_vec3_gen33_vout( pt_ref->xyz, &d_Rj_rj[9*i], dp_dparam[i].xyz ); mul_vec3_gen33 ( dp_dparam[i].xyz, drj_dparam); } } static void _propagate_extrinsics_one_rzero_tidentity(mrcal_point3_t* dp_dparam, const mrcal_point3_t* pt_ref, const double* d_Rj_rj) { dp_dparam[0] = (mrcal_point3_t){.x = 1.0}; dp_dparam[1] = (mrcal_point3_t){.y = 1.0}; dp_dparam[2] = (mrcal_point3_t){.z = 1.0}; } static void _propagate_extrinsics_one_cam0(mrcal_point3_t* dp_rf, const mrcal_point3_t* pt_ref, const double* _d_Rf_rf) { // dRj[row0]/drj is 3x3 matrix at &_d_Rf_rf[0] // dRj[row0]/drc = dRj[row0]/drj * drj_drc for(int i=0; i<3; i++) mul_vec3_gen33_vout( pt_ref->xyz, &_d_Rf_rf[9*i], dp_rf[i].xyz ); } static mrcal_point3_t _propagate_extrinsics( // output mrcal_point3_t* _dp_drc, mrcal_point3_t* _dp_dtc, mrcal_point3_t* _dp_drf, mrcal_point3_t* _dp_dtf, mrcal_point3_t** dp_drc, mrcal_point3_t** dp_dtc, mrcal_point3_t** dp_drf, mrcal_point3_t** dp_dtf, // input const mrcal_point3_t* pt_ref, const geometric_gradients_t* gg, const double* Rj, const double* d_Rj_rj, const double* _tj ) { // Rj * pt + tj -> pt mrcal_point3_t p; mul_vec3_gen33t_vout(pt_ref->xyz, Rj, p.xyz); add_vec(3, p.xyz, _tj); if(gg != NULL) { _propagate_extrinsics_one( _dp_drc, pt_ref, gg->_d_rj_rc, gg->_d_tj_rc, d_Rj_rj); _propagate_extrinsics_one_rzero_tidentity(_dp_dtc, pt_ref, d_Rj_rj); _propagate_extrinsics_one_tzero( _dp_drf, pt_ref, gg->_d_rj_rf, d_Rj_rj); _propagate_extrinsics_one_rzero( _dp_dtf, pt_ref, gg->_d_tj_tf, d_Rj_rj); *dp_drc = _dp_drc; *dp_dtc = _dp_dtc; *dp_drf = _dp_drf; *dp_dtf = _dp_dtf; } else { // camera is at the reference. The "joint" coord system is the "frame" // coord system // // p_cam = Rf p_ref + tf // // dp/drc = 0 // dp/dtc = 0 // dp/drf = reshape(dRf_drf p_ref) // dp/dtf = I _propagate_extrinsics_one_cam0(_dp_drf, pt_ref, d_Rj_rj); *dp_drc = NULL; *dp_dtc = NULL; *dp_drf = _dp_drf; *dp_dtf = NULL; // this is I. The user of this MUST know to interpret // it that way } return p; } // This is internal to project() static void _project_point( // outputs mrcal_point2_t* q, mrcal_point2_t* p_dq_dfxy, double* p_dq_dintrinsics_nocore, double* gradient_sparse_meta_pool, int runlen, mrcal_point3_t* restrict dq_drcamera, mrcal_point3_t* restrict dq_dtcamera, mrcal_point3_t* restrict dq_drframe, mrcal_point3_t* restrict dq_dtframe, mrcal_calobject_warp_t* restrict dq_dcalobject_warp, int* restrict * dq_dintrinsics_pool_int, // inputs const mrcal_point3_t* p, const double* restrict intrinsics, const mrcal_lensmodel_t* lensmodel, const mrcal_calobject_warp_t* dpt_refz_dwarp, // if NULL then the camera is at the reference bool camera_at_identity, const double* Rj, const int Nintrinsics, const mrcal_projection_precomputed_t* precomputed, const mrcal_point3_t* dp_drc, const mrcal_point3_t* dp_dtc, const mrcal_point3_t* dp_drf, const mrcal_point3_t* dp_dtf) { if(lensmodel->type == MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC) { // only need 3+3 for quadratic splines double grad_ABCDx_ABCDy[4+4]; int ivar0; _project_point_splined( // outputs q, p_dq_dfxy, grad_ABCDx_ABCDy, &ivar0, dq_drcamera,dq_dtcamera,dq_drframe,dq_dtframe, // inputs p, dp_drc, dp_dtc, dp_drf, dp_dtf, intrinsics, camera_at_identity, lensmodel->LENSMODEL_SPLINED_STEREOGRAPHIC__config.order, lensmodel->LENSMODEL_SPLINED_STEREOGRAPHIC__config.Nx, lensmodel->LENSMODEL_SPLINED_STEREOGRAPHIC__config.Ny, precomputed->LENSMODEL_SPLINED_STEREOGRAPHIC__precomputed.segments_per_u); // WARNING: if I could assume that dq_dintrinsics_pool_double!=NULL then I wouldnt need to copy the context if(*dq_dintrinsics_pool_int != NULL) { *((*dq_dintrinsics_pool_int)++) = ivar0; memcpy(gradient_sparse_meta_pool, grad_ABCDx_ABCDy, sizeof(double)*runlen*2); } } else if(lensmodel->type == MRCAL_LENSMODEL_CAHVOR) { project_cahvor( // outputs q,p_dq_dfxy, p_dq_dintrinsics_nocore, dq_drcamera,dq_dtcamera,dq_drframe,dq_dtframe, // inputs p, dp_drc, dp_dtc, dp_drf, dp_dtf, intrinsics, camera_at_identity, lensmodel); } else if(lensmodel->type == MRCAL_LENSMODEL_CAHVORE) { if(!project_cahvore( // outputs q,p_dq_dfxy, p_dq_dintrinsics_nocore, dq_drcamera,dq_dtcamera,dq_drframe,dq_dtframe, // inputs p, dp_drc, dp_dtc, dp_drf, dp_dtf, intrinsics, camera_at_identity, lensmodel)) { MSG("CAHVORE PROJECTION OF (%f,%f,%f) FAILED. I don't know what to do. Setting result and all gradients to 0", p->x, p->y, p->z); memset(q, 0, sizeof(*q)); if(p_dq_dfxy) memset(p_dq_dfxy, 0, sizeof(*p_dq_dfxy)); if(p_dq_dintrinsics_nocore) memset(p_dq_dintrinsics_nocore, 0, sizeof(*p_dq_dintrinsics_nocore) * 2 * (Nintrinsics-4)); if(dq_drcamera) memset(dq_drcamera, 0, sizeof(*dq_drcamera)); if(dq_dtcamera) memset(dq_dtcamera, 0, sizeof(*dq_dtcamera)); if(dq_drframe) memset(dq_drframe, 0, sizeof(*dq_drframe)); if(dq_dtframe) memset(dq_dtframe, 0, sizeof(*dq_dtframe)); } } else { _project_point_parametric( // outputs q,p_dq_dfxy, p_dq_dintrinsics_nocore, dq_drcamera,dq_dtcamera,dq_drframe,dq_dtframe, // inputs p, dp_drc, dp_dtc, dp_drf, dp_dtf, intrinsics, camera_at_identity, lensmodel); } if( dq_dcalobject_warp != NULL && dpt_refz_dwarp != NULL ) { // p = proj(Rc Rf warp(x) + Rc tf + tc); // dp/dw = dp/dRcRf(warp(x)) dR(warp(x))/dwarp(x) dwarp/dw = // = dp/dtc RcRf dwarp/dw // dp/dtc is dq_dtcamera // R is rodrigues(rj) // dwarp/dw = [0 0 0 ...] // [0 0 0 ...] // [a b c ...] // Let R = [r0 r1 r2] // dp/dw = dp/dt [a r2 b r2] = // [a dp/dt r2 b dp/dt r2 ...] mrcal_point3_t* p_dq_dt; if(!camera_at_identity) p_dq_dt = dq_dtcamera; else p_dq_dt = dq_dtframe; double d[] = { p_dq_dt[0].xyz[0] * Rj[0*3 + 2] + p_dq_dt[0].xyz[1] * Rj[1*3 + 2] + p_dq_dt[0].xyz[2] * Rj[2*3 + 2], p_dq_dt[1].xyz[0] * Rj[0*3 + 2] + p_dq_dt[1].xyz[1] * Rj[1*3 + 2] + p_dq_dt[1].xyz[2] * Rj[2*3 + 2]}; for(int i=0; ivalues[i]; dq_dcalobject_warp[1].values[i] = d[1]*dpt_refz_dwarp->values[i]; } } } // Projects 3D point(s), and reports the projection, and all the gradients. This // is the main internal callback in the optimizer. This operates in one of two modes: // // if(calibration_object_width_n == 0) then we're projecting ONE point. In world // coords this point is at frame_rt->t. frame_rt->r is not referenced. q and the // gradients reference 2 values (x,y in the imager) // // if(calibration_object_width_n > 0) then we're projecting a whole calibration // object. The pose of this object is given in frame_rt. We project ALL // calibration_object_width_n*calibration_object_height_n points. q and the // gradients reference ALL of these points static void project( // out mrcal_point2_t* restrict q, // The intrinsics gradients. These are split among several arrays. // High-parameter-count lens models can return their gradients // sparsely. All the actual gradient values live in // dq_dintrinsics_pool_double, a buffer supplied by the caller. If // dq_dintrinsics_pool_double is not NULL, the rest of the // variables are assumed non-NULL, and we compute all the // intrinsics gradients. Conversely, if dq_dintrinsics_pool_double // is NULL, no intrinsics gradients are computed double* restrict dq_dintrinsics_pool_double, int* restrict dq_dintrinsics_pool_int, double** restrict dq_dfxy, double** restrict dq_dintrinsics_nocore, gradient_sparse_meta_t* gradient_sparse_meta, mrcal_point3_t* restrict dq_drcamera, mrcal_point3_t* restrict dq_dtcamera, mrcal_point3_t* restrict dq_drframe, mrcal_point3_t* restrict dq_dtframe, mrcal_calobject_warp_t* restrict dq_dcalobject_warp, // in // everything; includes the core, if there is one const double* restrict intrinsics, const mrcal_pose_t* restrict camera_rt, const mrcal_pose_t* restrict frame_rt, const mrcal_calobject_warp_t* restrict calobject_warp, bool camera_at_identity, // if true, camera_rt is unused const mrcal_lensmodel_t* lensmodel, const mrcal_projection_precomputed_t* precomputed, double calibration_object_spacing, int calibration_object_width_n, int calibration_object_height_n) { assert(precomputed->ready); // Parametric and non-parametric models do different things: // // parametric models: // u = distort(p, distortions) // q = uxy/uz * fxy + cxy // // extrinsic gradients: // dqx/deee = d( ux/uz * fx + cx)/deee = // = fx d(ux/uz)/deee = // = fx/uz^2 ( uz dux/deee - duz/deee ux ) // // nonparametric (splined) models // u = stereographic(p) // q = (u + deltau(u)) * f + c // // Extrinsics: // dqx/deee = fx (dux/deee + ddeltaux/du du/deee) // = fx ( dux/deee (1 + ddeltaux/dux) + ddeltaux/duy duy/deee) // dqy/deee = fy ( duy/deee (1 + ddeltauy/duy) + ddeltauy/dux dux/deee) // // Intrinsics: // dq/diii = f ddeltau/diii // // So the two kinds of models have completely different expressions for // their gradients, and I implement them separately const int Npoints = calibration_object_width_n ? calibration_object_width_n*calibration_object_height_n : 1; const int Nintrinsics = mrcal_lensmodel_num_params(lensmodel); // I need to compose two transformations // // (object in reference frame) -> [frame transform] -> (object in the reference frame) -> // -> [camera rt] -> (camera frame) // // Note that here the frame transform transforms TO the reference frame and // the camera transform transforms FROM the reference frame. This is how my // data is expected to be set up // // [Rc tc] [Rf tf] = [Rc*Rf Rc*tf + tc] // [0 1 ] [0 1 ] [0 1 ] // // This transformation (and its gradients) is handled by mrcal_compose_rt() // I refer to the camera*frame transform as the "joint" transform, or the // letter j geometric_gradients_t gg; double _joint_rt[6]; double* joint_rt; // The caller has an odd-looking array reference [-3]. This is intended, but // the compiler throws a warning. I silence it here. gcc-10 produces a very // strange-looking warning that was reported to the maintainers: // https://gcc.gnu.org/bugzilla/show_bug.cgi?id=97261 #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Warray-bounds" mrcal_pose_t frame_rt_validr = {.t = frame_rt->t}; #pragma GCC diagnostic pop if(calibration_object_width_n) frame_rt_validr.r = frame_rt->r; if(!camera_at_identity) { // make sure I can pass mrcal_pose_t.r as an rt[] transformation _Static_assert( offsetof(mrcal_pose_t, r) == 0, "mrcal_pose_t has expected structure"); _Static_assert( offsetof(mrcal_pose_t, t) == 3*sizeof(double), "mrcal_pose_t has expected structure"); mrcal_compose_rt( _joint_rt, gg._d_rj_rc, gg._d_rj_rf, gg._d_tj_rc, gg._d_tj_tf, camera_rt ->r.xyz, frame_rt_validr.r.xyz); joint_rt = _joint_rt; } else { // We're looking at the reference frame, so this camera transform is // fixed at the identity. We don't need to compose anything, nor // propagate gradients for the camera extrinsics, since those don't // exist in the parameter vector // Here the "joint" transform is just the "frame" transform joint_rt = frame_rt_validr.r.xyz; } // Not using OpenCV distortions, the distortion and projection are not // coupled double Rj[3*3]; double d_Rj_rj[9*3]; mrcal_R_from_r(Rj, d_Rj_rj, joint_rt); mrcal_point2_t* p_dq_dfxy = NULL; double* p_dq_dintrinsics_nocore = NULL; bool has_core = modelHasCore_fxfycxcy(lensmodel); bool has_dense_intrinsics_grad = (lensmodel->type != MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC); bool has_sparse_intrinsics_grad = (lensmodel->type == MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC); int runlen = (lensmodel->type == MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC) ? (lensmodel->LENSMODEL_SPLINED_STEREOGRAPHIC__config.order + 1) : 0; if(dq_dintrinsics_pool_double != NULL) { // nothing by default *dq_dfxy = NULL; *dq_dintrinsics_nocore = NULL; gradient_sparse_meta->pool = NULL; int ivar_pool = 0; if(has_core) { // Each point produces 2 measurements. Each one depends on ONE fxy // element. So Npoints*2 of these *dq_dfxy = &dq_dintrinsics_pool_double[ivar_pool]; p_dq_dfxy = (mrcal_point2_t*)*dq_dfxy; ivar_pool += Npoints*2; } if(has_dense_intrinsics_grad) { *dq_dintrinsics_nocore = p_dq_dintrinsics_nocore = &dq_dintrinsics_pool_double[ivar_pool]; ivar_pool += Npoints*2 * (Nintrinsics-4); } if(has_sparse_intrinsics_grad) { if(lensmodel->type != MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC) { MSG("Unhandled lens model: %d (%s)", lensmodel->type, mrcal_lensmodel_name_unconfigured(lensmodel)); assert(0); } const mrcal_LENSMODEL_SPLINED_STEREOGRAPHIC__config_t* config = &lensmodel->LENSMODEL_SPLINED_STEREOGRAPHIC__config; *gradient_sparse_meta = (gradient_sparse_meta_t) { .run_side_length = config->order+1, .ivar_stridey = 2*config->Nx, .pool = &dq_dintrinsics_pool_double[ivar_pool] }; ivar_pool += Npoints*2 * runlen; } } // These are produced by _propagate_extrinsics() and consumed by // _project_point() mrcal_point3_t _dp_drc[3]; mrcal_point3_t _dp_dtc[3]; mrcal_point3_t _dp_drf[3]; mrcal_point3_t _dp_dtf[3]; mrcal_point3_t* dp_drc; mrcal_point3_t* dp_dtc; mrcal_point3_t* dp_drf; mrcal_point3_t* dp_dtf; if( calibration_object_width_n == 0 ) { // projecting discrete points mrcal_point3_t p = _propagate_extrinsics( _dp_drc,_dp_dtc,_dp_drf,_dp_dtf, &dp_drc,&dp_dtc,&dp_drf,&dp_dtf, &(mrcal_point3_t){}, camera_at_identity ? NULL : &gg, Rj, d_Rj_rj, &joint_rt[3]); _project_point( q, p_dq_dfxy, p_dq_dintrinsics_nocore, gradient_sparse_meta ? gradient_sparse_meta->pool : NULL, runlen, dq_drcamera, dq_dtcamera, dq_drframe, dq_dtframe, NULL, &dq_dintrinsics_pool_int, &p, intrinsics, lensmodel, NULL, camera_at_identity, Rj, Nintrinsics, precomputed, dp_drc,dp_dtc,dp_drf,dp_dtf); } else { // projecting a chessboard int i_pt = 0; // The calibration object has a simple grid geometry for(int y = 0; yx2 * dx; pt_ref.z += calobject_warp->y2 * dy; dpt_refz_dwarp.x2 = dx; dpt_refz_dwarp.y2 = dy; } mrcal_point3_t p = _propagate_extrinsics( _dp_drc,_dp_dtc,_dp_drf,_dp_dtf, &dp_drc,&dp_dtc,&dp_drf,&dp_dtf, &pt_ref, camera_at_identity ? NULL : &gg, Rj, d_Rj_rj, &joint_rt[3]); mrcal_point3_t* dq_drcamera_here = dq_drcamera ? &dq_drcamera [i_pt*2] : NULL; mrcal_point3_t* dq_dtcamera_here = dq_dtcamera ? &dq_dtcamera [i_pt*2] : NULL; mrcal_point3_t* dq_drframe_here = dq_drframe ? &dq_drframe [i_pt*2] : NULL; mrcal_point3_t* dq_dtframe_here = dq_dtframe ? &dq_dtframe [i_pt*2] : NULL; mrcal_calobject_warp_t* dq_dcalobject_warp_here = dq_dcalobject_warp ? &dq_dcalobject_warp [i_pt*2] : NULL; mrcal_point3_t dq_dtcamera_here_dummy[2]; mrcal_point3_t dq_dtframe_here_dummy [2]; if(dq_dcalobject_warp) { // I need all translation gradients to be available to // compute the calobject_warp gradients (see the end of the // _project_point() function above). So I compute those even // if the caller didn't ask for them if(!dq_dtcamera_here) dq_dtcamera_here = dq_dtcamera_here_dummy; if(!dq_dtframe_here) dq_dtframe_here = dq_dtframe_here_dummy; } _project_point(&q[i_pt], p_dq_dfxy ? &p_dq_dfxy[i_pt] : NULL, p_dq_dintrinsics_nocore ? &p_dq_dintrinsics_nocore[2*(Nintrinsics-4)*i_pt] : NULL, gradient_sparse_meta ? &gradient_sparse_meta->pool[i_pt*runlen*2] : NULL, runlen, dq_drcamera_here, dq_dtcamera_here, dq_drframe_here, dq_dtframe_here, dq_dcalobject_warp_here, &dq_dintrinsics_pool_int, &p, intrinsics, lensmodel, &dpt_refz_dwarp, camera_at_identity, Rj, Nintrinsics, precomputed, dp_drc,dp_dtc,dp_drf,dp_dtf); i_pt++; } } } // NOT A PART OF THE EXTERNAL API. This is exported for the mrcal python wrapper // only bool _mrcal_project_internal( // out mrcal_point2_t* q, // Stored as a row-first array of shape (N,2,3). Each // row lives in a mrcal_point3_t mrcal_point3_t* dq_dp, // core, distortions concatenated. Stored as a row-first // array of shape (N,2,Nintrinsics). This is a DENSE array. // High-parameter-count lens models have very sparse // gradients here, and the internal project() function // returns those sparsely. For now THIS function densifies // all of these double* dq_dintrinsics, // in const mrcal_point3_t* p, int N, const mrcal_lensmodel_t* lensmodel, // core, distortions concatenated const double* intrinsics, int Nintrinsics, const mrcal_projection_precomputed_t* precomputed) { if( dq_dintrinsics == NULL ) { for(int i=0; itype) || lensmodel->type == MRCAL_LENSMODEL_PINHOLE)) { _mrcal_project_internal_opencv( q, NULL,NULL, p, N, intrinsics, Nintrinsics); return true; } mrcal_projection_precomputed_t precomputed; _mrcal_precompute_lensmodel_data(&precomputed, lensmodel); return _mrcal_project_internal(q, dq_dp, dq_dintrinsics, p, N, lensmodel, intrinsics, Nintrinsics, &precomputed); } // Maps a set of distorted 2D imager points q to a 3D vector in camera // coordinates that produced these pixel observations. The 3D vector is defined // up-to-length. The returned vectors v are not normalized, and may have any // length. // // This is the "reverse" direction, so an iterative nonlinear optimization is // performed internally to compute this result. This is much slower than // mrcal_project. For OpenCV distortions specifically, OpenCV has // cvUndistortPoints() (and cv2.undistortPoints()), but these are inaccurate: // https://github.com/opencv/opencv/issues/8811 bool mrcal_unproject( // out mrcal_point3_t* out, // in const mrcal_point2_t* q, int N, const mrcal_lensmodel_t* lensmodel, // core, distortions concatenated const double* intrinsics) { mrcal_lensmodel_metadata_t meta = mrcal_lensmodel_metadata(lensmodel); if(!meta.has_gradients) { MSG("mrcal_unproject(lensmodel='%s') is not yet implemented: we need gradients", mrcal_lensmodel_name_unconfigured(lensmodel)); return false; } mrcal_projection_precomputed_t precomputed; _mrcal_precompute_lensmodel_data(&precomputed, lensmodel); return _mrcal_unproject_internal(out, q, N, lensmodel, intrinsics, &precomputed); } typedef struct { const mrcal_lensmodel_t* lensmodel; // core, distortions concatenated const double* intrinsics; const mrcal_projection_precomputed_t* precomputed; const mrcal_point2_t* q; } _unproject_callback_cookie_t; static void _unproject_callback(const double* u, double* x, double* J, void* _cookie) { _unproject_callback_cookie_t* cookie = (_unproject_callback_cookie_t*)_cookie; // u is the constant-fxy-cxy 2D stereographic // projection of the hypothesis v. I unproject it stereographically, // and project it using the actual model mrcal_point2_t dv_du[3]; mrcal_pose_t frame = {}; mrcal_unproject_stereographic( &frame.t, dv_du, (mrcal_point2_t*)u, 1, cookie->intrinsics ); mrcal_point3_t dq_dtframe[2]; mrcal_point2_t q_hypothesis; project( &q_hypothesis, NULL,NULL,NULL,NULL,NULL, NULL, NULL, NULL, dq_dtframe, NULL, // in cookie->intrinsics, NULL, &frame, NULL, true, cookie->lensmodel, cookie->precomputed, 0.0, 0,0); x[0] = q_hypothesis.x - cookie->q->x; x[1] = q_hypothesis.y - cookie->q->y; J[0*2 + 0] = dq_dtframe[0].x*dv_du[0].x + dq_dtframe[0].y*dv_du[1].x + dq_dtframe[0].z*dv_du[2].x; J[0*2 + 1] = dq_dtframe[0].x*dv_du[0].y + dq_dtframe[0].y*dv_du[1].y + dq_dtframe[0].z*dv_du[2].y; J[1*2 + 0] = dq_dtframe[1].x*dv_du[0].x + dq_dtframe[1].y*dv_du[1].x + dq_dtframe[1].z*dv_du[2].x; J[1*2 + 1] = dq_dtframe[1].x*dv_du[0].y + dq_dtframe[1].y*dv_du[1].y + dq_dtframe[1].z*dv_du[2].y; } // NOT A PART OF THE EXTERNAL API. This is exported for the mrcal python wrapper // only bool _mrcal_unproject_internal( // out mrcal_point3_t* out, // in const mrcal_point2_t* q, int N, const mrcal_lensmodel_t* lensmodel, // core, distortions concatenated const double* intrinsics, const mrcal_projection_precomputed_t* precomputed) { // easy special-cases if( lensmodel->type == MRCAL_LENSMODEL_PINHOLE ) { mrcal_unproject_pinhole(out, NULL, q, N, intrinsics); return true; } if( lensmodel->type == MRCAL_LENSMODEL_STEREOGRAPHIC ) { mrcal_unproject_stereographic(out, NULL, q, N, intrinsics); return true; } if( lensmodel->type == MRCAL_LENSMODEL_LONLAT ) { mrcal_unproject_lonlat(out, NULL, q, N, intrinsics); return true; } if( lensmodel->type == MRCAL_LENSMODEL_LATLON ) { mrcal_unproject_latlon(out, NULL, q, N, intrinsics); return true; } if( lensmodel->type == MRCAL_LENSMODEL_CAHVORE ) { const int Nintrinsics = mrcal_lensmodel_num_params(lensmodel); for(int i = Nintrinsics-3; ixyz, NULL, &(mrcal_point3_t){.x = (q[i].x-cx)/fx, .y = (q[i].y-cy)/fy, .z = 1.}, 1, intrinsics ); // MSG("init. out->xyz[]=(%g,%g)", out->x, out->y); dogleg_parameters2_t dogleg_parameters; dogleg_getDefaultParameters(&dogleg_parameters); dogleg_parameters.dogleg_debug = 0; _unproject_callback_cookie_t cookie = { .lensmodel = lensmodel, .intrinsics = intrinsics, .precomputed = precomputed, .q = &q[i] }; double norm2x = dogleg_optimize_dense2(out->xyz, 2, 2, _unproject_callback, (void*)&cookie, &dogleg_parameters, NULL); //This needs to be precise; if it isn't, I barf. Shouldn't happen //very often static bool already_complained = false; // MSG("norm2x = %g", norm2x); if(norm2x/2.0 > 1e-4) { if(!already_complained) { // MSG("WARNING: I wasn't able to precisely compute some points. norm2x=%f. Returning nan for those. Will complain just once", // norm2x); already_complained = true; } double nan = strtod("NAN", NULL); out->xyz[0] = nan; out->xyz[1] = nan; } else { // out[0,1] is the stereographic representation of the observation // vector using idealized fx,fy,cx,cy. This is already the right // thing if we're reporting in 2d. Otherwise I need to unproject // This is the normal no-error path mrcal_unproject_stereographic((mrcal_point3_t*)out, NULL, (mrcal_point2_t*)out, 1, intrinsics); if(!model_supports_projection_behind_camera(lensmodel) && out->xyz[2] < 0.0) { out->xyz[0] *= -1.0; out->xyz[1] *= -1.0; out->xyz[2] *= -1.0; } } // Advance to the next point. Error or not out++; } return true; } // The following functions define/use the layout of the state vector. In general // I do: // // intrinsics_cam0 // intrinsics_cam1 // intrinsics_cam2 // ... // extrinsics_cam1 // extrinsics_cam2 // extrinsics_cam3 // ... // frame0 // frame1 // frame2 // .... // calobject_warp0 // calobject_warp1 // ... // From real values to unit-scale values. Optimizer sees unit-scale values static int pack_solver_state_intrinsics( // out double* b, // subset based on problem_selections // in const double* intrinsics, // ALL variables. Not a subset const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections, int Ncameras_intrinsics ) { int i_state = 0; const int Nintrinsics = mrcal_lensmodel_num_params(lensmodel); const int Ncore = modelHasCore_fxfycxcy(lensmodel) ? 4 : 0; const int Ndistortions = Nintrinsics - Ncore; for(int icam_intrinsics=0; icam_intrinsics < Ncameras_intrinsics; icam_intrinsics++) { if( problem_selections.do_optimize_intrinsics_core && Ncore ) { const mrcal_intrinsics_core_t* intrinsics_core = (const mrcal_intrinsics_core_t*)intrinsics; b[i_state++] = intrinsics_core->focal_xy [0] / SCALE_INTRINSICS_FOCAL_LENGTH; b[i_state++] = intrinsics_core->focal_xy [1] / SCALE_INTRINSICS_FOCAL_LENGTH; b[i_state++] = intrinsics_core->center_xy[0] / SCALE_INTRINSICS_CENTER_PIXEL; b[i_state++] = intrinsics_core->center_xy[1] / SCALE_INTRINSICS_CENTER_PIXEL; } if( problem_selections.do_optimize_intrinsics_distortions ) for(int i = 0; ix2 / SCALE_CALOBJECT_WARP; b[i_state++] = calobject_warp->y2 / SCALE_CALOBJECT_WARP; } assert(i_state == Nstate_ref); } // Same as above, but packs/unpacks a vector instead of structures void mrcal_pack_solver_state_vector( // out, in double* b, // FULL state on input, unitless // state on output // in int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel) { int Npoints_variable = Npoints - Npoints_fixed; int i_state = 0; i_state += pack_solver_state_intrinsics_subset_to_subset( b, lensmodel, problem_selections, Ncameras_intrinsics ); _Static_assert( offsetof(mrcal_pose_t, r) == 0, "mrcal_pose_t has expected structure"); _Static_assert( offsetof(mrcal_pose_t, t) == 3*sizeof(double), "mrcal_pose_t has expected structure"); if( problem_selections.do_optimize_extrinsics ) for(int icam_extrinsics=0; icam_extrinsics < Ncameras_extrinsics; icam_extrinsics++) { mrcal_pose_t* extrinsics_fromref = (mrcal_pose_t*)(&b[i_state]); b[i_state++] = extrinsics_fromref->r.xyz[0] / SCALE_ROTATION_CAMERA; b[i_state++] = extrinsics_fromref->r.xyz[1] / SCALE_ROTATION_CAMERA; b[i_state++] = extrinsics_fromref->r.xyz[2] / SCALE_ROTATION_CAMERA; b[i_state++] = extrinsics_fromref->t.xyz[0] / SCALE_TRANSLATION_CAMERA; b[i_state++] = extrinsics_fromref->t.xyz[1] / SCALE_TRANSLATION_CAMERA; b[i_state++] = extrinsics_fromref->t.xyz[2] / SCALE_TRANSLATION_CAMERA; } if( problem_selections.do_optimize_frames ) { for(int iframe = 0; iframe < Nframes; iframe++) { mrcal_pose_t* frames_toref = (mrcal_pose_t*)(&b[i_state]); b[i_state++] = frames_toref->r.xyz[0] / SCALE_ROTATION_FRAME; b[i_state++] = frames_toref->r.xyz[1] / SCALE_ROTATION_FRAME; b[i_state++] = frames_toref->r.xyz[2] / SCALE_ROTATION_FRAME; b[i_state++] = frames_toref->t.xyz[0] / SCALE_TRANSLATION_FRAME; b[i_state++] = frames_toref->t.xyz[1] / SCALE_TRANSLATION_FRAME; b[i_state++] = frames_toref->t.xyz[2] / SCALE_TRANSLATION_FRAME; } for(int i_point = 0; i_point < Npoints_variable; i_point++) { mrcal_point3_t* points = (mrcal_point3_t*)(&b[i_state]); b[i_state++] = points->xyz[0] / SCALE_POSITION_POINT; b[i_state++] = points->xyz[1] / SCALE_POSITION_POINT; b[i_state++] = points->xyz[2] / SCALE_POSITION_POINT; } } if( has_calobject_warp(problem_selections,Nobservations_board) ) { mrcal_calobject_warp_t* calobject_warp = (mrcal_calobject_warp_t*)(&b[i_state]); b[i_state++] = calobject_warp->x2 / SCALE_CALOBJECT_WARP; b[i_state++] = calobject_warp->y2 / SCALE_CALOBJECT_WARP; } } static int unpack_solver_state_intrinsics( // out // Ncameras_intrinsics of these double* intrinsics, // ALL variables. Not a subset. // I don't touch the elemnents I'm // not optimizing // in const double* b, // subset based on problem_selections const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections, int intrinsics_stride, int Ncameras_intrinsics ) { if( !problem_selections.do_optimize_intrinsics_core && !problem_selections.do_optimize_intrinsics_distortions ) return 0; const int Nintrinsics = mrcal_lensmodel_num_params(lensmodel); const int Ncore = modelHasCore_fxfycxcy(lensmodel) ? 4 : 0; int i_state = 0; for(int icam_intrinsics=0; icam_intrinsics < Ncameras_intrinsics; icam_intrinsics++) { if( problem_selections.do_optimize_intrinsics_core && Ncore ) { intrinsics[icam_intrinsics*intrinsics_stride + 0] = b[i_state++] * SCALE_INTRINSICS_FOCAL_LENGTH; intrinsics[icam_intrinsics*intrinsics_stride + 1] = b[i_state++] * SCALE_INTRINSICS_FOCAL_LENGTH; intrinsics[icam_intrinsics*intrinsics_stride + 2] = b[i_state++] * SCALE_INTRINSICS_CENTER_PIXEL; intrinsics[icam_intrinsics*intrinsics_stride + 3] = b[i_state++] * SCALE_INTRINSICS_CENTER_PIXEL; } if( problem_selections.do_optimize_intrinsics_distortions ) { for(int i = 0; ir.xyz[0] = b[i_state++] * SCALE_ROTATION_CAMERA; extrinsic->r.xyz[1] = b[i_state++] * SCALE_ROTATION_CAMERA; extrinsic->r.xyz[2] = b[i_state++] * SCALE_ROTATION_CAMERA; extrinsic->t.xyz[0] = b[i_state++] * SCALE_TRANSLATION_CAMERA; extrinsic->t.xyz[1] = b[i_state++] * SCALE_TRANSLATION_CAMERA; extrinsic->t.xyz[2] = b[i_state++] * SCALE_TRANSLATION_CAMERA; return i_state; } static int unpack_solver_state_framert_one(// out mrcal_pose_t* frame, // in const double* b) { int i_state = 0; frame->r.xyz[0] = b[i_state++] * SCALE_ROTATION_FRAME; frame->r.xyz[1] = b[i_state++] * SCALE_ROTATION_FRAME; frame->r.xyz[2] = b[i_state++] * SCALE_ROTATION_FRAME; frame->t.xyz[0] = b[i_state++] * SCALE_TRANSLATION_FRAME; frame->t.xyz[1] = b[i_state++] * SCALE_TRANSLATION_FRAME; frame->t.xyz[2] = b[i_state++] * SCALE_TRANSLATION_FRAME; return i_state; } static int unpack_solver_state_point_one(// out mrcal_point3_t* point, // in const double* b) { int i_state = 0; point->xyz[0] = b[i_state++] * SCALE_POSITION_POINT; point->xyz[1] = b[i_state++] * SCALE_POSITION_POINT; point->xyz[2] = b[i_state++] * SCALE_POSITION_POINT; return i_state; } static int unpack_solver_state_calobject_warp(// out mrcal_calobject_warp_t* calobject_warp, // in const double* b) { int i_state = 0; calobject_warp->x2 = b[i_state++] * SCALE_CALOBJECT_WARP; calobject_warp->y2 = b[i_state++] * SCALE_CALOBJECT_WARP; return i_state; } // From unit-scale values to real values. Optimizer sees unit-scale values static void unpack_solver_state( // out // ALL intrinsics; whether we're optimizing // them or not. Don't touch the parts of this // array we're not optimizing double* intrinsics_all, // Ncameras_intrinsics of these mrcal_pose_t* extrinsics_fromref, // Ncameras_extrinsics of these mrcal_pose_t* frames_toref, // Nframes of these mrcal_point3_t* points, // Npoints of these mrcal_calobject_warp_t* calobject_warp, // 1 of these // in const double* b, const mrcal_lensmodel_t* lensmodel, mrcal_problem_selections_t problem_selections, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints_variable, int Nobservations_board, int Nstate_ref) { int i_state = unpack_solver_state_intrinsics(intrinsics_all, b, lensmodel, problem_selections, mrcal_lensmodel_num_params(lensmodel), Ncameras_intrinsics); if( problem_selections.do_optimize_extrinsics ) for(int icam_extrinsics=0; icam_extrinsics < Ncameras_extrinsics; icam_extrinsics++) i_state += unpack_solver_state_extrinsics_one( &extrinsics_fromref[icam_extrinsics], &b[i_state] ); if( problem_selections.do_optimize_frames ) { for(int iframe = 0; iframe < Nframes; iframe++) i_state += unpack_solver_state_framert_one( &frames_toref[iframe], &b[i_state] ); for(int i_point = 0; i_point < Npoints_variable; i_point++) i_state += unpack_solver_state_point_one( &points[i_point], &b[i_state] ); } if( has_calobject_warp(problem_selections,Nobservations_board) ) i_state += unpack_solver_state_calobject_warp(calobject_warp, &b[i_state]); assert(i_state == Nstate_ref); } // Same as above, but packs/unpacks a vector instead of structures void mrcal_unpack_solver_state_vector( // out, in double* b, // unitless state on input, // scaled, meaningful state on // output // in int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel) { int Npoints_variable = Npoints - Npoints_fixed; int i_state = unpack_solver_state_intrinsics_subset_to_subset(b, lensmodel, problem_selections, Ncameras_intrinsics); if( problem_selections.do_optimize_extrinsics ) { _Static_assert( offsetof(mrcal_pose_t, r) == 0, "mrcal_pose_t has expected structure"); _Static_assert( offsetof(mrcal_pose_t, t) == 3*sizeof(double), "mrcal_pose_t has expected structure"); mrcal_pose_t* extrinsics_fromref = (mrcal_pose_t*)(&b[i_state]); for(int icam_extrinsics=0; icam_extrinsics < Ncameras_extrinsics; icam_extrinsics++) i_state += unpack_solver_state_extrinsics_one( &extrinsics_fromref[icam_extrinsics], &b[i_state] ); } if( problem_selections.do_optimize_frames ) { mrcal_pose_t* frames_toref = (mrcal_pose_t*)(&b[i_state]); for(int iframe = 0; iframe < Nframes; iframe++) i_state += unpack_solver_state_framert_one( &frames_toref[iframe], &b[i_state] ); mrcal_point3_t* points = (mrcal_point3_t*)(&b[i_state]); for(int i_point = 0; i_point < Npoints_variable; i_point++) i_state += unpack_solver_state_point_one( &points[i_point], &b[i_state] ); } if( has_calobject_warp(problem_selections,Nobservations_board) ) { mrcal_calobject_warp_t* calobject_warp = (mrcal_calobject_warp_t*)(&b[i_state]); i_state += unpack_solver_state_calobject_warp(calobject_warp, &b[i_state]); } } int mrcal_state_index_intrinsics(int icam_intrinsics, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel) { if(Ncameras_intrinsics <= 0) return -1; int Nintrinsics = mrcal_num_intrinsics_optimization_params(problem_selections, lensmodel); if(Nintrinsics <= 0) return -1; if(!(0 <= icam_intrinsics && icam_intrinsics < Ncameras_intrinsics)) return -1; return icam_intrinsics * Nintrinsics; } int mrcal_num_states_intrinsics(int Ncameras_intrinsics, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel) { return Ncameras_intrinsics * mrcal_num_intrinsics_optimization_params(problem_selections, lensmodel); } int mrcal_state_index_extrinsics(int icam_extrinsics, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel) { if(Ncameras_extrinsics <= 0) return -1; if(!problem_selections.do_optimize_extrinsics) return -1; if(!(0 <= icam_extrinsics && icam_extrinsics < Ncameras_extrinsics)) return -1; return mrcal_num_states_intrinsics(Ncameras_intrinsics, problem_selections, lensmodel) + (icam_extrinsics*6); } int mrcal_num_states_extrinsics(int Ncameras_extrinsics, mrcal_problem_selections_t problem_selections) { return problem_selections.do_optimize_extrinsics ? (6*Ncameras_extrinsics) : 0; } int mrcal_state_index_frames(int iframe, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel) { if(Nframes <= 0) return -1; if(!problem_selections.do_optimize_frames) return -1; if(!(0 <= iframe && iframe < Nframes)) return -1; return mrcal_num_states_intrinsics(Ncameras_intrinsics, problem_selections, lensmodel) + mrcal_num_states_extrinsics(Ncameras_extrinsics, problem_selections) + (iframe*6); } int mrcal_num_states_frames(int Nframes, mrcal_problem_selections_t problem_selections) { return problem_selections.do_optimize_frames ? (6*Nframes) : 0; } int mrcal_state_index_points(int i_point, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel) { int Npoints_variable = Npoints - Npoints_fixed; if(Npoints_variable <= 0) return -1; if(!problem_selections.do_optimize_frames) return -1; if(!(0 <= i_point && i_point < Npoints_variable)) return -1; return mrcal_num_states_intrinsics(Ncameras_intrinsics, problem_selections, lensmodel) + mrcal_num_states_extrinsics(Ncameras_extrinsics, problem_selections) + mrcal_num_states_frames (Nframes, problem_selections) + (i_point*3); } int mrcal_num_states_points(int Npoints, int Npoints_fixed, mrcal_problem_selections_t problem_selections) { int Npoints_variable = Npoints - Npoints_fixed; return problem_selections.do_optimize_frames ? (Npoints_variable*3) : 0; } int mrcal_state_index_calobject_warp(int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel) { if(!has_calobject_warp(problem_selections,Nobservations_board)) return -1; return mrcal_num_states_intrinsics(Ncameras_intrinsics, problem_selections, lensmodel) + mrcal_num_states_extrinsics(Ncameras_extrinsics, problem_selections) + mrcal_num_states_frames (Nframes, problem_selections) + mrcal_num_states_points (Npoints, Npoints_fixed, problem_selections); } int mrcal_num_states_calobject_warp(mrcal_problem_selections_t problem_selections, int Nobservations_board) { if(has_calobject_warp(problem_selections,Nobservations_board)) return MRCAL_NSTATE_CALOBJECT_WARP; return 0; } // Reports the icam_extrinsics corresponding to a given icam_intrinsics. // // If we're solving a vanilla calibration problem (stationary cameras observing // a moving calibration object), each camera has a unique intrinsics index and a // unique extrinsics index. This function reports the latter, given the former. // // On success, the result is written to *icam_extrinsics, and we return true. If // the given camera is at the reference coordinate system, it has no extrinsics, // and we report -1. // // If we have moving cameras (NOT a vanilla calibration problem), there isn't a // single icam_extrinsics for a given icam_intrinsics, and we report an error by // returning false static bool _corresponding_icam_extrinsics__check( const mrcal_camera_index_t* icam, int i, int* icam_map_to_extrinsics, int* icam_map_to_intrinsics, const char* what) { int icam_intrinsics = icam->intrinsics; int icam_extrinsics = icam->extrinsics; if(icam_extrinsics < 0) icam_extrinsics = -1; if(icam_map_to_intrinsics[icam_extrinsics+1] == -100) icam_map_to_intrinsics[icam_extrinsics+1] = icam_intrinsics; else if(icam_map_to_intrinsics[icam_extrinsics+1] != icam_intrinsics) { MSG("Cannot compute icam_extrinsics. I don't have a vanilla calibration problem: %s observation %d has icam_intrinsics,icam_extrinsics %d,%d while I saw %d,%d previously", what, i, icam_map_to_intrinsics[icam_extrinsics+1], icam_extrinsics, icam_intrinsics, icam_extrinsics); return false; } if(icam_map_to_extrinsics[icam_intrinsics] == -100) icam_map_to_extrinsics[icam_intrinsics] = icam_extrinsics; else if(icam_map_to_extrinsics[icam_intrinsics] != icam_extrinsics) { MSG("Cannot compute icam_extrinsics. I don't have a vanilla calibration problem: %s observation %d has icam_intrinsics,icam_extrinsics %d,%d while I saw %d,%d previously", what, i, icam_intrinsics, icam_map_to_extrinsics[icam_intrinsics], icam_intrinsics, icam_extrinsics); return false; } return true; } bool mrcal_corresponding_icam_extrinsics(// out int* icam_extrinsics, // in int icam_intrinsics, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nobservations_board, const mrcal_observation_board_t* observations_board, int Nobservations_point, const mrcal_observation_point_t* observations_point) { if( !(Ncameras_intrinsics == Ncameras_extrinsics || Ncameras_intrinsics == Ncameras_extrinsics+1 ) ) { MSG("Cannot compute icam_extrinsics. I don't have a vanilla calibration problem"); return false; } int icam_map_to_extrinsics[Ncameras_intrinsics]; int icam_map_to_intrinsics[Ncameras_extrinsics+1]; for(int i=0; i k stdevs past the mean. I make // a broad assumption that the error distribution is normally-distributed, // with mean 0. This is reasonable because this function is applied after // running the optimization. // // The threshold stdev is the stdev of my observed residuals // // I have two separate thresholds. If any measurements are worse than the // higher threshold, then I will need to reoptimize, so I throw out some // extra points: all points worse than the lower threshold. This serves to // reduce the required re-optimizations const double k0 = 4.0; const double k1 = 5.0; *Noutliers = 0; int i_pt,i_feature; #define LOOP_OBSERVATION() \ i_feature = 0; \ for(int i_observation_board=0; \ i_observation_boardicam.intrinsics; \ for(i_pt=0; \ i_pt < calibration_object_width_n*calibration_object_height_n; \ i_pt++, i_feature++) #define LOOP_FEATURE_HEADER() \ const mrcal_point3_t* pt_observed = &observations_board_pool[i_feature]; \ double* weight = &observations_board_pool[i_feature].z; int Ninliers = 0; double var = 0.0; LOOP_OBSERVATION() { LOOP_FEATURE() { LOOP_FEATURE_HEADER(); if(*weight <= 0.0) { (*Noutliers)++; continue; } double dx = x_measurements[2*i_feature + 0]; double dy = x_measurements[2*i_feature + 1]; var += dx*dx + dy*dy; Ninliers++; } } var /= (double)(2*Ninliers); bool markedAny = false; LOOP_OBSERVATION() { LOOP_FEATURE() { LOOP_FEATURE_HEADER(); { if(*weight <= 0.0) continue; double dx = x_measurements[2*i_feature + 0]; double dy = x_measurements[2*i_feature + 1]; // I have sigma = sqrt(var). Outliers have abs(x) > k*sigma // -> x^2 > k^2 var if(dx*dx > k1*k1*var || dy*dy > k1*k1*var ) { *weight *= -1.0; markedAny = true; (*Noutliers)++; // MSG("Feature %d looks like an outlier. x/y are %f/%f stdevs off mean (assumed 0). Observed stdev: %f, limit: %f", // i_feature, // dx/sqrt(var), // dy/sqrt(var), // sqrt(var), // k1); } } } } if(!markedAny) return false; // Some measurements were past the worse threshold, so I throw out a bit // extra to leave some margin so that the next re-optimization would be the // last. Hopefully LOOP_OBSERVATION() { int Npt_inlier = 0; int Npt_outlier = 0; LOOP_FEATURE() { LOOP_FEATURE_HEADER(); if(*weight <= 0.0) { Npt_outlier++; continue; } Npt_inlier++; double dx = x_measurements[2*i_feature + 0]; double dy = x_measurements[2*i_feature + 1]; // I have sigma = sqrt(var). Outliers have abs(x) > k*sigma // -> x^2 > k^2 var if(dx*dx > k0*k0*var || dy*dy > k0*k0*var ) { *weight *= -1.0; (*Noutliers)++; } } if(Npt_inlier < 3) MSG("WARNING: Board observation %d (icam_intrinsics=%d, icam_extrinsics=%d, iframe=%d) had almost all of its points thrown out as outliers: only %d/%d remain. CHOLMOD is about to complain about a non-positive-definite JtJ. Something is wrong with this observation", i_observation_board, observation->icam.intrinsics, observation->icam.extrinsics, observation->iframe, Npt_inlier, Npt_inlier + Npt_outlier); } return true; #undef LOOP_OBSERVATION #undef LOOP_FEATURE #undef LOOP_FEATURE_HEADER } typedef struct { // these are all UNPACKED const double* intrinsics; // Ncameras_intrinsics * NlensParams of these const mrcal_pose_t* extrinsics_fromref; // Ncameras_extrinsics of these. Transform FROM the reference frame const mrcal_pose_t* frames_toref; // Nframes of these. Transform TO the reference frame const mrcal_point3_t* points; // Npoints of these. In the reference frame const mrcal_calobject_warp_t* calobject_warp; // 1 of these. May be NULL if !problem_selections.do_optimize_calobject_warp // in int Ncameras_intrinsics, Ncameras_extrinsics, Nframes; int Npoints, Npoints_fixed; const mrcal_observation_board_t* observations_board; const mrcal_point3_t* observations_board_pool; int Nobservations_board; const mrcal_observation_point_t* observations_point; int Nobservations_point; bool verbose; mrcal_lensmodel_t lensmodel; mrcal_projection_precomputed_t precomputed; const int* imagersizes; // Ncameras_intrinsics*2 of these mrcal_problem_selections_t problem_selections; const mrcal_problem_constants_t* problem_constants; double calibration_object_spacing; int calibration_object_width_n; int calibration_object_height_n; const int Nmeasurements, N_j_nonzero, Nintrinsics; const char* reportFitMsg; } callback_context_t; static void penalty_range_normalization(// out double* penalty, double* dpenalty_ddistsq, // in // SIGNED distance. <0 means "behind the camera" const double distsq, const callback_context_t* ctx, const double weight) { const double maxsq = ctx->problem_constants->point_max_range*ctx->problem_constants->point_max_range; if(distsq > maxsq) { *penalty = weight * (distsq/maxsq - 1.0); *dpenalty_ddistsq = weight*(1. / maxsq); return; } const double minsq = ctx->problem_constants->point_min_range*ctx->problem_constants->point_min_range; if(distsq < minsq) { // too close OR behind the camera *penalty = weight*(1.0 - distsq/minsq); *dpenalty_ddistsq = weight*(-1. / minsq); return; } *penalty = *dpenalty_ddistsq = 0.0; } static void optimizer_callback(// input state const double* packed_state, // output measurements double* x, // Jacobian cholmod_sparse* Jt, const callback_context_t* ctx) { double norm2_error = 0.0; int iJacobian = 0; int iMeasurement = 0; int* Jrowptr = Jt ? (int*) Jt->p : NULL; int* Jcolidx = Jt ? (int*) Jt->i : NULL; double* Jval = Jt ? (double*)Jt->x : NULL; #define STORE_JACOBIAN(col, g) \ do \ { \ if(Jt) { \ Jcolidx[ iJacobian ] = col; \ Jval [ iJacobian ] = g; \ } \ iJacobian++; \ } while(0) #define STORE_JACOBIAN2(col0, g0, g1) \ do \ { \ if(Jt) { \ Jcolidx[ iJacobian+0 ] = col0+0; \ Jval [ iJacobian+0 ] = g0; \ Jcolidx[ iJacobian+1 ] = col0+1; \ Jval [ iJacobian+1 ] = g1; \ } \ iJacobian += 2; \ } while(0) #define STORE_JACOBIAN3(col0, g0, g1, g2) \ do \ { \ if(Jt) { \ Jcolidx[ iJacobian+0 ] = col0+0; \ Jval [ iJacobian+0 ] = g0; \ Jcolidx[ iJacobian+1 ] = col0+1; \ Jval [ iJacobian+1 ] = g1; \ Jcolidx[ iJacobian+2 ] = col0+2; \ Jval [ iJacobian+2 ] = g2; \ } \ iJacobian += 3; \ } while(0) #define STORE_JACOBIAN_N(col0, g0, scale, N) \ do \ { \ if(Jt) { \ for(int i=0; ilensmodel) ? 4 : 0; int Ncore_state = (modelHasCore_fxfycxcy(&ctx->lensmodel) && ctx->problem_selections.do_optimize_intrinsics_core) ? 4 : 0; // If I'm locking down some parameters, then the state vector contains a // subset of my data. I reconstitute the intrinsics and extrinsics here. // I do the frame poses later. This is a good way to do it if I have few // cameras. With many cameras (this will be slow) // WARNING: sparsify this. This is potentially a BIG thing on the stack double intrinsics_all[ctx->Ncameras_intrinsics][ctx->Nintrinsics]; mrcal_pose_t camera_rt[ctx->Ncameras_extrinsics]; mrcal_calobject_warp_t calobject_warp_local = {}; const int i_var_calobject_warp = mrcal_state_index_calobject_warp(ctx->Ncameras_intrinsics, ctx->Ncameras_extrinsics, ctx->Nframes, ctx->Npoints, ctx->Npoints_fixed, ctx->Nobservations_board, ctx->problem_selections, &ctx->lensmodel); if(has_calobject_warp(ctx->problem_selections,ctx->Nobservations_board)) unpack_solver_state_calobject_warp(&calobject_warp_local, &packed_state[i_var_calobject_warp]); else if(ctx->calobject_warp != NULL) calobject_warp_local = *ctx->calobject_warp; for(int icam_intrinsics=0; icam_intrinsicsNcameras_intrinsics; icam_intrinsics++) { // Construct the FULL intrinsics vector, based on either the // optimization vector or the inputs, depending on what we're optimizing double* intrinsics_here = &intrinsics_all[icam_intrinsics][0]; double* distortions_here = &intrinsics_all[icam_intrinsics][Ncore]; int i_var_intrinsics = mrcal_state_index_intrinsics(icam_intrinsics, ctx->Ncameras_intrinsics, ctx->Ncameras_extrinsics, ctx->Nframes, ctx->Npoints, ctx->Npoints_fixed, ctx->Nobservations_board, ctx->problem_selections, &ctx->lensmodel); if(Ncore) { if( ctx->problem_selections.do_optimize_intrinsics_core ) { intrinsics_here[0] = packed_state[i_var_intrinsics++] * SCALE_INTRINSICS_FOCAL_LENGTH; intrinsics_here[1] = packed_state[i_var_intrinsics++] * SCALE_INTRINSICS_FOCAL_LENGTH; intrinsics_here[2] = packed_state[i_var_intrinsics++] * SCALE_INTRINSICS_CENTER_PIXEL; intrinsics_here[3] = packed_state[i_var_intrinsics++] * SCALE_INTRINSICS_CENTER_PIXEL; } else memcpy( intrinsics_here, &ctx->intrinsics[ctx->Nintrinsics*icam_intrinsics], Ncore*sizeof(double) ); } if( ctx->problem_selections.do_optimize_intrinsics_distortions ) { for(int i = 0; iNintrinsics-Ncore; i++) distortions_here[i] = packed_state[i_var_intrinsics++] * SCALE_DISTORTION; } else memcpy( distortions_here, &ctx->intrinsics[ctx->Nintrinsics*icam_intrinsics + Ncore], (ctx->Nintrinsics-Ncore)*sizeof(double) ); } for(int icam_extrinsics=0; icam_extrinsicsNcameras_extrinsics; icam_extrinsics++) { if( icam_extrinsics < 0 ) continue; const int i_var_camera_rt = mrcal_state_index_extrinsics(icam_extrinsics, ctx->Ncameras_intrinsics, ctx->Ncameras_extrinsics, ctx->Nframes, ctx->Npoints, ctx->Npoints_fixed, ctx->Nobservations_board, ctx->problem_selections, &ctx->lensmodel); if(ctx->problem_selections.do_optimize_extrinsics) unpack_solver_state_extrinsics_one(&camera_rt[icam_extrinsics], &packed_state[i_var_camera_rt]); else memcpy(&camera_rt[icam_extrinsics], &ctx->extrinsics_fromref[icam_extrinsics], sizeof(mrcal_pose_t)); } int i_feature = 0; for(int i_observation_board = 0; i_observation_board < ctx->Nobservations_board; i_observation_board++) { const mrcal_observation_board_t* observation = &ctx->observations_board[i_observation_board]; const int icam_intrinsics = observation->icam.intrinsics; const int icam_extrinsics = observation->icam.extrinsics; const int iframe = observation->iframe; // Some of these are bogus if problem_selections says they're inactive const int i_var_frame_rt = mrcal_state_index_frames(iframe, ctx->Ncameras_intrinsics, ctx->Ncameras_extrinsics, ctx->Nframes, ctx->Npoints, ctx->Npoints_fixed, ctx->Nobservations_board, ctx->problem_selections, &ctx->lensmodel); mrcal_pose_t frame_rt; if(ctx->problem_selections.do_optimize_frames) unpack_solver_state_framert_one(&frame_rt, &packed_state[i_var_frame_rt]); else memcpy(&frame_rt, &ctx->frames_toref[iframe], sizeof(mrcal_pose_t)); const int i_var_intrinsics = mrcal_state_index_intrinsics(icam_intrinsics, ctx->Ncameras_intrinsics, ctx->Ncameras_extrinsics, ctx->Nframes, ctx->Npoints, ctx->Npoints_fixed, ctx->Nobservations_board, ctx->problem_selections, &ctx->lensmodel); // invalid if icam_extrinsics < 0, but unused in that case const int i_var_camera_rt = mrcal_state_index_extrinsics(icam_extrinsics, ctx->Ncameras_intrinsics, ctx->Ncameras_extrinsics, ctx->Nframes, ctx->Npoints, ctx->Npoints_fixed, ctx->Nobservations_board, ctx->problem_selections, &ctx->lensmodel); // these are computed in respect to the real-unit parameters, // NOT the unit-scale parameters used by the optimizer mrcal_point3_t dq_drcamera [ctx->calibration_object_width_n*ctx->calibration_object_height_n][2]; mrcal_point3_t dq_dtcamera [ctx->calibration_object_width_n*ctx->calibration_object_height_n][2]; mrcal_point3_t dq_drframe [ctx->calibration_object_width_n*ctx->calibration_object_height_n][2]; mrcal_point3_t dq_dtframe [ctx->calibration_object_width_n*ctx->calibration_object_height_n][2]; mrcal_calobject_warp_t dq_dcalobject_warp[ctx->calibration_object_width_n*ctx->calibration_object_height_n][2]; mrcal_point2_t q_hypothesis [ctx->calibration_object_width_n*ctx->calibration_object_height_n]; // I get the intrinsics gradients in separate arrays, possibly sparsely. // All the data lives in dq_dintrinsics_pool_double[], with the other data // indicating the meaning of the values in the pool. // // dq_dfxy serves a special-case for a perspective core. Such models // are very common, and they have x = fx vx/vz + cx and y = fy vy/vz + // cy. So x depends on fx and NOT on fy, and similarly for y. Similar // for cx,cy, except we know the gradient value beforehand. I support // this case explicitly here. I store dx/dfx and dy/dfy; no cross terms int Ngradients = get_Ngradients(&ctx->lensmodel, ctx->Nintrinsics); double dq_dintrinsics_pool_double[ctx->calibration_object_width_n*ctx->calibration_object_height_n*Ngradients]; int dq_dintrinsics_pool_int [ctx->calibration_object_width_n*ctx->calibration_object_height_n]; double* dq_dfxy = NULL; double* dq_dintrinsics_nocore = NULL; gradient_sparse_meta_t gradient_sparse_meta = {}; int splined_intrinsics_grad_irun = 0; project(q_hypothesis, ctx->problem_selections.do_optimize_intrinsics_core || ctx->problem_selections.do_optimize_intrinsics_distortions ? dq_dintrinsics_pool_double : NULL, ctx->problem_selections.do_optimize_intrinsics_core || ctx->problem_selections.do_optimize_intrinsics_distortions ? dq_dintrinsics_pool_int : NULL, &dq_dfxy, &dq_dintrinsics_nocore, &gradient_sparse_meta, ctx->problem_selections.do_optimize_extrinsics ? (mrcal_point3_t*)dq_drcamera : NULL, ctx->problem_selections.do_optimize_extrinsics ? (mrcal_point3_t*)dq_dtcamera : NULL, ctx->problem_selections.do_optimize_frames ? (mrcal_point3_t*)dq_drframe : NULL, ctx->problem_selections.do_optimize_frames ? (mrcal_point3_t*)dq_dtframe : NULL, has_calobject_warp(ctx->problem_selections,ctx->Nobservations_board) ? (mrcal_calobject_warp_t*)dq_dcalobject_warp : NULL, // input intrinsics_all[icam_intrinsics], &camera_rt[icam_extrinsics], &frame_rt, ctx->calobject_warp == NULL ? NULL : &calobject_warp_local, icam_extrinsics < 0, &ctx->lensmodel, &ctx->precomputed, ctx->calibration_object_spacing, ctx->calibration_object_width_n, ctx->calibration_object_height_n); for(int i_pt=0; i_pt < ctx->calibration_object_width_n*ctx->calibration_object_height_n; i_pt++, i_feature++) { const mrcal_point3_t* qx_qy_w__observed = &ctx->observations_board_pool[i_feature]; double weight = qx_qy_w__observed->z; if(weight >= 0.0) { // I have my two measurements (dx, dy). I propagate their // gradient and store them for( int i_xy=0; i_xy<2; i_xy++ ) { const double err = (q_hypothesis[i_pt].xy[i_xy] - qx_qy_w__observed->xyz[i_xy]) * weight; if( ctx->reportFitMsg ) { MSG("%s: obs/frame/cam_i/cam_e/dot: %d %d %d %d %d err: %g", ctx->reportFitMsg, i_observation_board, iframe, icam_intrinsics, icam_extrinsics, i_pt, err); continue; } if(Jt) Jrowptr[iMeasurement] = iJacobian; x[iMeasurement] = err; norm2_error += err*err; if( ctx->problem_selections.do_optimize_intrinsics_core ) { // fx,fy. x depends on fx only. y depends on fy only STORE_JACOBIAN( i_var_intrinsics + i_xy, dq_dfxy[i_pt*2 + i_xy] * weight * SCALE_INTRINSICS_FOCAL_LENGTH ); // cx,cy. The gradients here are known to be 1. And x depends on cx only. And y depends on cy only STORE_JACOBIAN( i_var_intrinsics + i_xy+2, weight * SCALE_INTRINSICS_CENTER_PIXEL ); } if( ctx->problem_selections.do_optimize_intrinsics_distortions ) { if(gradient_sparse_meta.pool != NULL) { // u = stereographic(p) // q = (u + deltau(u)) * f + c // // Intrinsics: // dq/diii = f ddeltau/diii // // ddeltau/diii = flatten(ABCDx[0..3] * ABCDy[0..3]) const int ivar0 = dq_dintrinsics_pool_int[splined_intrinsics_grad_irun] - ( ctx->problem_selections.do_optimize_intrinsics_core ? 0 : 4 ); const int len = gradient_sparse_meta.run_side_length; const double* ABCDx = &gradient_sparse_meta.pool[len*2*splined_intrinsics_grad_irun + 0]; const double* ABCDy = &gradient_sparse_meta.pool[len*2*splined_intrinsics_grad_irun + len]; const int ivar_stridey = gradient_sparse_meta.ivar_stridey; const double* fxy = &intrinsics_all[icam_intrinsics][0]; for(int iy=0; iyNintrinsics-Ncore; i++) STORE_JACOBIAN( i_var_intrinsics+Ncore_state + i, dq_dintrinsics_nocore[i_pt*2*(ctx->Nintrinsics-Ncore) + i_xy*(ctx->Nintrinsics-Ncore) + i] * weight * SCALE_DISTORTION ); } } if( ctx->problem_selections.do_optimize_extrinsics ) if( icam_extrinsics >= 0 ) { STORE_JACOBIAN3( i_var_camera_rt + 0, dq_drcamera[i_pt][i_xy].xyz[0] * weight * SCALE_ROTATION_CAMERA, dq_drcamera[i_pt][i_xy].xyz[1] * weight * SCALE_ROTATION_CAMERA, dq_drcamera[i_pt][i_xy].xyz[2] * weight * SCALE_ROTATION_CAMERA); STORE_JACOBIAN3( i_var_camera_rt + 3, dq_dtcamera[i_pt][i_xy].xyz[0] * weight * SCALE_TRANSLATION_CAMERA, dq_dtcamera[i_pt][i_xy].xyz[1] * weight * SCALE_TRANSLATION_CAMERA, dq_dtcamera[i_pt][i_xy].xyz[2] * weight * SCALE_TRANSLATION_CAMERA); } if( ctx->problem_selections.do_optimize_frames ) { STORE_JACOBIAN3( i_var_frame_rt + 0, dq_drframe[i_pt][i_xy].xyz[0] * weight * SCALE_ROTATION_FRAME, dq_drframe[i_pt][i_xy].xyz[1] * weight * SCALE_ROTATION_FRAME, dq_drframe[i_pt][i_xy].xyz[2] * weight * SCALE_ROTATION_FRAME); STORE_JACOBIAN3( i_var_frame_rt + 3, dq_dtframe[i_pt][i_xy].xyz[0] * weight * SCALE_TRANSLATION_FRAME, dq_dtframe[i_pt][i_xy].xyz[1] * weight * SCALE_TRANSLATION_FRAME, dq_dtframe[i_pt][i_xy].xyz[2] * weight * SCALE_TRANSLATION_FRAME); } if( has_calobject_warp(ctx->problem_selections,ctx->Nobservations_board) ) { STORE_JACOBIAN_N( i_var_calobject_warp, dq_dcalobject_warp[i_pt][i_xy].values, weight * SCALE_CALOBJECT_WARP, MRCAL_NSTATE_CALOBJECT_WARP); } iMeasurement++; } } else { // Outlier. // This is arbitrary. I'm skipping this observation, so I don't // touch the projection results, and I set the measurement and // all its gradients to 0. I need to have SOME dependency on the // frame parameters to ensure a full-rank Hessian, so if we're // skipping all observations for this frame the system will // become singular. I don't currently handle this. libdogleg // will complain loudly, and add small diagonal L2 // regularization terms for( int i_xy=0; i_xy<2; i_xy++ ) { const double err = 0.0; if( ctx->reportFitMsg ) { MSG( "%s: obs/frame/cam_i/cam_e/dot: %d %d %d %d %d err: %g", ctx->reportFitMsg, i_observation_board, iframe, icam_intrinsics, icam_extrinsics, i_pt, err); continue; } if(Jt) Jrowptr[iMeasurement] = iJacobian; x[iMeasurement] = err; norm2_error += err*err; if( ctx->problem_selections.do_optimize_intrinsics_core ) { STORE_JACOBIAN( i_var_intrinsics + i_xy, 0.0 ); STORE_JACOBIAN( i_var_intrinsics + i_xy+2, 0.0 ); } if( ctx->problem_selections.do_optimize_intrinsics_distortions ) { if(gradient_sparse_meta.pool != NULL) { const int ivar0 = dq_dintrinsics_pool_int[splined_intrinsics_grad_irun] - ( ctx->problem_selections.do_optimize_intrinsics_core ? 0 : 4 ); const int len = gradient_sparse_meta.run_side_length; const int ivar_stridey = gradient_sparse_meta.ivar_stridey; for(int iy=0; iyNintrinsics-Ncore; i++) STORE_JACOBIAN( i_var_intrinsics+Ncore_state + i, 0.0 ); } } if( ctx->problem_selections.do_optimize_extrinsics ) if( icam_extrinsics >= 0 ) { STORE_JACOBIAN3( i_var_camera_rt + 0, 0.0, 0.0, 0.0); STORE_JACOBIAN3( i_var_camera_rt + 3, 0.0, 0.0, 0.0); } if( ctx->problem_selections.do_optimize_frames ) { // Arbitrary differences between the dimensions to keep // my Hessian non-singular. This is 100% arbitrary. I'm // skipping these measurements so these variables // actually don't affect the computation at all STORE_JACOBIAN3( i_var_frame_rt + 0, 0,0,0); STORE_JACOBIAN3( i_var_frame_rt + 3, 0,0,0); } if( has_calobject_warp(ctx->problem_selections,ctx->Nobservations_board) ) STORE_JACOBIAN_N( i_var_calobject_warp, (double*)NULL, 0.0, MRCAL_NSTATE_CALOBJECT_WARP); iMeasurement++; } } if(gradient_sparse_meta.pool != NULL) splined_intrinsics_grad_irun++; } } // Handle all the point observations. This is VERY similar to the // board-observation loop above. Please consolidate for(int i_observation_point = 0; i_observation_point < ctx->Nobservations_point; i_observation_point++) { const mrcal_observation_point_t* observation = &ctx->observations_point[i_observation_point]; const int icam_intrinsics = observation->icam.intrinsics; const int icam_extrinsics = observation->icam.extrinsics; const int i_point = observation->i_point; const bool use_position_from_state = ctx->problem_selections.do_optimize_frames && i_point < ctx->Npoints - ctx->Npoints_fixed; const mrcal_point3_t* qx_qy_w__observed = &observation->px; double weight = qx_qy_w__observed->z; if(weight <= 0.0) { // Outlier. Cost = 0. Jacobians are 0 too, but I must preserve the // structure const int i_var_intrinsics = mrcal_state_index_intrinsics(icam_intrinsics, ctx->Ncameras_intrinsics, ctx->Ncameras_extrinsics, ctx->Nframes, ctx->Npoints, ctx->Npoints_fixed, ctx->Nobservations_board, ctx->problem_selections, &ctx->lensmodel); // invalid if icam_extrinsics < 0, but unused in that case const int i_var_camera_rt = mrcal_state_index_extrinsics(icam_extrinsics, ctx->Ncameras_intrinsics, ctx->Ncameras_extrinsics, ctx->Nframes, ctx->Npoints, ctx->Npoints_fixed, ctx->Nobservations_board, ctx->problem_selections, &ctx->lensmodel); const int i_var_point = mrcal_state_index_points(i_point, ctx->Ncameras_intrinsics, ctx->Ncameras_extrinsics, ctx->Nframes, ctx->Npoints, ctx->Npoints_fixed, ctx->Nobservations_board, ctx->problem_selections, &ctx->lensmodel); // I have my two measurements (dx, dy). I propagate their // gradient and store them for( int i_xy=0; i_xy<2; i_xy++ ) { if(Jt) Jrowptr[iMeasurement] = iJacobian; x[iMeasurement] = 0; if( ctx->problem_selections.do_optimize_intrinsics_core ) { // fx,fy. x depends on fx only. y depends on fy only STORE_JACOBIAN( i_var_intrinsics + i_xy, 0 ); // cx,cy. The gradients here are known to be 1. And x depends on cx only. And y depends on cy only STORE_JACOBIAN( i_var_intrinsics + i_xy+2, 0); } if( ctx->problem_selections.do_optimize_intrinsics_distortions ) { if( (ctx->problem_selections.do_optimize_intrinsics_core || ctx->problem_selections.do_optimize_intrinsics_distortions) && ctx->lensmodel.type == MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC ) { // sparse gradient. This is an outlier, so it doesn't // matter which points I say I depend on, as long as I // pick the right number, and says that j=0. I pick the // control points at the start because why not const mrcal_LENSMODEL_SPLINED_STEREOGRAPHIC__config_t* config = &ctx->lensmodel.LENSMODEL_SPLINED_STEREOGRAPHIC__config; int runlen = config->order+1; for(int i=0; iNintrinsics-Ncore; i++) STORE_JACOBIAN( i_var_intrinsics+Ncore_state + i, 0); } if(icam_extrinsics >= 0 && ctx->problem_selections.do_optimize_extrinsics ) { STORE_JACOBIAN3( i_var_camera_rt + 0, 0,0,0 ); STORE_JACOBIAN3( i_var_camera_rt + 3, 0,0,0 ); } if( use_position_from_state ) STORE_JACOBIAN3( i_var_point, 0,0,0 ); iMeasurement++; } if(Jt) Jrowptr[iMeasurement] = iJacobian; x[iMeasurement] = 0; if(icam_extrinsics >= 0 && ctx->problem_selections.do_optimize_extrinsics ) { STORE_JACOBIAN3( i_var_camera_rt + 0, 0,0,0 ); STORE_JACOBIAN3( i_var_camera_rt + 3, 0,0,0 ); } if( use_position_from_state ) STORE_JACOBIAN3( i_var_point, 0,0,0 ); iMeasurement++; continue; } const int i_var_intrinsics = mrcal_state_index_intrinsics(icam_intrinsics, ctx->Ncameras_intrinsics, ctx->Ncameras_extrinsics, ctx->Nframes, ctx->Npoints, ctx->Npoints_fixed, ctx->Nobservations_board, ctx->problem_selections, &ctx->lensmodel); // invalid if icam_extrinsics < 0, but unused in that case const int i_var_camera_rt = mrcal_state_index_extrinsics(icam_extrinsics, ctx->Ncameras_intrinsics, ctx->Ncameras_extrinsics, ctx->Nframes, ctx->Npoints, ctx->Npoints_fixed, ctx->Nobservations_board, ctx->problem_selections, &ctx->lensmodel); const int i_var_point = mrcal_state_index_points(i_point, ctx->Ncameras_intrinsics, ctx->Ncameras_extrinsics, ctx->Nframes, ctx->Npoints, ctx->Npoints_fixed, ctx->Nobservations_board, ctx->problem_selections, &ctx->lensmodel); mrcal_point3_t point_ref; if(use_position_from_state) unpack_solver_state_point_one(&point_ref, &packed_state[i_var_point]); else point_ref = ctx->points[i_point]; int Ngradients = get_Ngradients(&ctx->lensmodel, ctx->Nintrinsics); // WARNING: "compute size(dq_dintrinsics_pool_double) correctly and maybe bounds-check" double dq_dintrinsics_pool_double[Ngradients]; // used for LENSMODEL_SPLINED_STEREOGRAPHIC only, but getting rid of // this in other cases isn't worth the trouble int dq_dintrinsics_pool_int [1]; double* dq_dfxy = NULL; double* dq_dintrinsics_nocore = NULL; gradient_sparse_meta_t gradient_sparse_meta = {}; mrcal_point3_t dq_drcamera[2]; mrcal_point3_t dq_dtcamera[2]; mrcal_point3_t dq_dpoint [2]; // The array reference [-3] is intended, but the compiler throws a // warning. I silence it here #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Warray-bounds" mrcal_point2_t q_hypothesis; project(&q_hypothesis, ctx->problem_selections.do_optimize_intrinsics_core || ctx->problem_selections.do_optimize_intrinsics_distortions ? dq_dintrinsics_pool_double : NULL, ctx->problem_selections.do_optimize_intrinsics_core || ctx->problem_selections.do_optimize_intrinsics_distortions ? dq_dintrinsics_pool_int : NULL, &dq_dfxy, &dq_dintrinsics_nocore, &gradient_sparse_meta, ctx->problem_selections.do_optimize_extrinsics ? dq_drcamera : NULL, ctx->problem_selections.do_optimize_extrinsics ? dq_dtcamera : NULL, NULL, // frame rotation. I only have a point position use_position_from_state ? dq_dpoint : NULL, NULL, // input intrinsics_all[icam_intrinsics], &camera_rt[icam_extrinsics], // I only have the point position, so the 'rt' memory // points 3 back. The fake "r" here will not be // referenced (mrcal_pose_t*)(&point_ref.xyz[-3]), NULL, icam_extrinsics < 0, &ctx->lensmodel, &ctx->precomputed, 0,0,0); #pragma GCC diagnostic pop // I have my two measurements (dx, dy). I propagate their // gradient and store them for( int i_xy=0; i_xy<2; i_xy++ ) { const double err = (q_hypothesis.xy[i_xy] - qx_qy_w__observed->xyz[i_xy])*weight; if(Jt) Jrowptr[iMeasurement] = iJacobian; x[iMeasurement] = err; norm2_error += err*err; if( ctx->problem_selections.do_optimize_intrinsics_core ) { // fx,fy. x depends on fx only. y depends on fy only STORE_JACOBIAN( i_var_intrinsics + i_xy, dq_dfxy[i_xy] * weight * SCALE_INTRINSICS_FOCAL_LENGTH ); // cx,cy. The gradients here are known to be 1. And x depends on cx only. And y depends on cy only STORE_JACOBIAN( i_var_intrinsics + i_xy+2, weight * SCALE_INTRINSICS_CENTER_PIXEL ); } if( ctx->problem_selections.do_optimize_intrinsics_distortions ) { if(gradient_sparse_meta.pool != NULL) { // u = stereographic(p) // q = (u + deltau(u)) * f + c // // Intrinsics: // dq/diii = f ddeltau/diii // // ddeltau/diii = flatten(ABCDx[0..3] * ABCDy[0..3]) const int ivar0 = dq_dintrinsics_pool_int[0] - ( ctx->problem_selections.do_optimize_intrinsics_core ? 0 : 4 ); const int len = gradient_sparse_meta.run_side_length; const double* ABCDx = &gradient_sparse_meta.pool[0]; const double* ABCDy = &gradient_sparse_meta.pool[len]; const int ivar_stridey = gradient_sparse_meta.ivar_stridey; const double* fxy = &intrinsics_all[icam_intrinsics][0]; for(int iy=0; iyNintrinsics-Ncore; i++) STORE_JACOBIAN( i_var_intrinsics+Ncore_state + i, dq_dintrinsics_nocore[i_xy*(ctx->Nintrinsics-Ncore) + i] * weight * SCALE_DISTORTION ); } } if( ctx->problem_selections.do_optimize_extrinsics ) if( icam_extrinsics >= 0 ) { STORE_JACOBIAN3( i_var_camera_rt + 0, dq_drcamera[i_xy].xyz[0] * weight * SCALE_ROTATION_CAMERA, dq_drcamera[i_xy].xyz[1] * weight * SCALE_ROTATION_CAMERA, dq_drcamera[i_xy].xyz[2] * weight * SCALE_ROTATION_CAMERA); STORE_JACOBIAN3( i_var_camera_rt + 3, dq_dtcamera[i_xy].xyz[0] * weight * SCALE_TRANSLATION_CAMERA, dq_dtcamera[i_xy].xyz[1] * weight * SCALE_TRANSLATION_CAMERA, dq_dtcamera[i_xy].xyz[2] * weight * SCALE_TRANSLATION_CAMERA); } if( use_position_from_state ) STORE_JACOBIAN3( i_var_point, dq_dpoint[i_xy].xyz[0] * weight * SCALE_POSITION_POINT, dq_dpoint[i_xy].xyz[1] * weight * SCALE_POSITION_POINT, dq_dpoint[i_xy].xyz[2] * weight * SCALE_POSITION_POINT); iMeasurement++; } // Now the range normalization (make sure the range isn't // aphysically high or aphysically low) if(icam_extrinsics < 0) { double distsq = point_ref.x*point_ref.x + point_ref.y*point_ref.y + point_ref.z*point_ref.z; double penalty, dpenalty_ddistsq; if(model_supports_projection_behind_camera(&ctx->lensmodel) || point_ref.z > 0.0) penalty_range_normalization(&penalty, &dpenalty_ddistsq, distsq, ctx,weight); else { penalty_range_normalization(&penalty, &dpenalty_ddistsq, -distsq, ctx,weight); dpenalty_ddistsq *= -1.; } if(Jt) Jrowptr[iMeasurement] = iJacobian; x[iMeasurement] = penalty; norm2_error += penalty*penalty; if( use_position_from_state ) { double scale = 2.0 * dpenalty_ddistsq * SCALE_POSITION_POINT; STORE_JACOBIAN3( i_var_point, scale*point_ref.x, scale*point_ref.y, scale*point_ref.z ); } iMeasurement++; } else { // I need to transform the point. I already computed // this stuff in project()... double Rc[3*3]; double d_Rc_rc[9*3]; mrcal_R_from_r(Rc, d_Rc_rc, camera_rt[icam_extrinsics].r.xyz); mrcal_point3_t pcam; mul_vec3_gen33t_vout(point_ref.xyz, Rc, pcam.xyz); add_vec(3, pcam.xyz, camera_rt[icam_extrinsics].t.xyz); double distsq = pcam.x*pcam.x + pcam.y*pcam.y + pcam.z*pcam.z; double penalty, dpenalty_ddistsq; if(model_supports_projection_behind_camera(&ctx->lensmodel) || pcam.z > 0.0) penalty_range_normalization(&penalty, &dpenalty_ddistsq, distsq, ctx,weight); else { penalty_range_normalization(&penalty, &dpenalty_ddistsq, -distsq, ctx,weight); dpenalty_ddistsq *= -1.; } if(Jt) Jrowptr[iMeasurement] = iJacobian; x[iMeasurement] = penalty; norm2_error += penalty*penalty; if( ctx->problem_selections.do_optimize_extrinsics ) { // pcam.x = Rc[row0]*point*SCALE + tc // d(pcam.x)/dr = d(Rc[row0])/drc*point*SCALE // d(Rc[row0])/drc is 3x3 matrix at &d_Rc_rc[0] double d_ptcamx_dr[3]; double d_ptcamy_dr[3]; double d_ptcamz_dr[3]; mul_vec3_gen33_vout( point_ref.xyz, &d_Rc_rc[9*0], d_ptcamx_dr ); mul_vec3_gen33_vout( point_ref.xyz, &d_Rc_rc[9*1], d_ptcamy_dr ); mul_vec3_gen33_vout( point_ref.xyz, &d_Rc_rc[9*2], d_ptcamz_dr ); STORE_JACOBIAN3( i_var_camera_rt + 0, SCALE_ROTATION_CAMERA* 2.0*dpenalty_ddistsq*( pcam.x*d_ptcamx_dr[0] + pcam.y*d_ptcamy_dr[0] + pcam.z*d_ptcamz_dr[0] ), SCALE_ROTATION_CAMERA* 2.0*dpenalty_ddistsq*( pcam.x*d_ptcamx_dr[1] + pcam.y*d_ptcamy_dr[1] + pcam.z*d_ptcamz_dr[1] ), SCALE_ROTATION_CAMERA* 2.0*dpenalty_ddistsq*( pcam.x*d_ptcamx_dr[2] + pcam.y*d_ptcamy_dr[2] + pcam.z*d_ptcamz_dr[2] ) ); STORE_JACOBIAN3( i_var_camera_rt + 3, SCALE_TRANSLATION_CAMERA* 2.0*dpenalty_ddistsq*pcam.x, SCALE_TRANSLATION_CAMERA* 2.0*dpenalty_ddistsq*pcam.y, SCALE_TRANSLATION_CAMERA* 2.0*dpenalty_ddistsq*pcam.z ); } if( use_position_from_state ) STORE_JACOBIAN3( i_var_point, SCALE_POSITION_POINT* 2.0*dpenalty_ddistsq*(pcam.x*Rc[0] + pcam.y*Rc[3] + pcam.z*Rc[6]), SCALE_POSITION_POINT* 2.0*dpenalty_ddistsq*(pcam.x*Rc[1] + pcam.y*Rc[4] + pcam.z*Rc[7]), SCALE_POSITION_POINT* 2.0*dpenalty_ddistsq*(pcam.x*Rc[2] + pcam.y*Rc[5] + pcam.z*Rc[8]) ); iMeasurement++; } } ///////////////// Regularization if(ctx->problem_selections.do_apply_regularization && (ctx->problem_selections.do_optimize_intrinsics_distortions || ctx->problem_selections.do_optimize_intrinsics_core)) { const bool dump_regularizaton_details = false; // I want the total regularization cost to be low relative to the // other contributions to the cost. And I want each set of // regularization terms to weigh roughly the same. Let's say I want // regularization to account for ~ .5% of the other error // contributions: // // Nregularization_types = 2; // Nmeasurements_rest*normal_pixel_error_sq * 0.005/Nregularization_types = // Nmeasurements_regularization_distortion *normal_regularization_distortion_error_sq = // Nmeasurements_regularization_centerpixel*normal_regularization_centerpixel_error_sq = // // normal_regularization_distortion_error_sq = (scale*normal_distortion_offset )^2 // normal_regularization_centerpixel_error_sq = (scale*normal_centerpixel_value )^2 // // Regularization introduces a bias to the solution. The // test-projection-uncertainty test measures it, and barfs if it is too // high. The constants should be adjusted if that test fails. const int Nregularization_types = 2; int Nmeasurements_regularization_distortion = 0; if(ctx->problem_selections.do_optimize_intrinsics_distortions) Nmeasurements_regularization_distortion = ctx->Ncameras_intrinsics*(ctx->Nintrinsics-Ncore); int Nmeasurements_regularization_centerpixel = 0; if(ctx->problem_selections.do_optimize_intrinsics_core) Nmeasurements_regularization_centerpixel = ctx->Ncameras_intrinsics*2; int Nmeasurements_nonregularization = ctx->Nmeasurements - (Nmeasurements_regularization_distortion + Nmeasurements_regularization_centerpixel); double normal_pixel_error = 1.0; double expected_total_pixel_error_sq = (double)Nmeasurements_nonregularization * normal_pixel_error * normal_pixel_error; if(dump_regularizaton_details) MSG("expected_total_pixel_error_sq: %f", expected_total_pixel_error_sq); double scale_regularization_distortion = 0.0; double scale_regularization_centerpixel = 0.0; // compute scales { if(ctx->problem_selections.do_optimize_intrinsics_distortions) { // I need to control this better, but this is sufficient for // now. I need 2.0e-1 for splined models to effectively // eliminate the curl in the splined model vector field. For // other models I use 2.0 because that's what I had for a long // time, and I don't want to change it to not break anything double normal_distortion_value = ctx->lensmodel.type == MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC ? 2.0e-1 : 2.0; double expected_regularization_distortion_error_sq_noscale = (double)Nmeasurements_regularization_distortion * normal_distortion_value * normal_distortion_value; double scale_sq = expected_total_pixel_error_sq * 0.005/(double)Nregularization_types / expected_regularization_distortion_error_sq_noscale; if(dump_regularizaton_details) MSG("expected_regularization_distortion_error_sq: %f", expected_regularization_distortion_error_sq_noscale*scale_sq); scale_regularization_distortion = sqrt(scale_sq); } if(modelHasCore_fxfycxcy(&ctx->lensmodel) && ctx->problem_selections.do_optimize_intrinsics_core) { double normal_centerpixel_offset = 500.0; double expected_regularization_centerpixel_error_sq_noscale = (double)Nmeasurements_regularization_centerpixel * normal_centerpixel_offset * normal_centerpixel_offset; double scale_sq = expected_total_pixel_error_sq * 0.005/(double)Nregularization_types / expected_regularization_centerpixel_error_sq_noscale; if(dump_regularizaton_details) MSG("expected_regularization_centerpixel_error_sq: %f", expected_regularization_centerpixel_error_sq_noscale*scale_sq); scale_regularization_centerpixel = sqrt(scale_sq); } } // compute and store regularization terms { if( ctx->problem_selections.do_optimize_intrinsics_distortions ) for(int icam_intrinsics=0; icam_intrinsicsNcameras_intrinsics; icam_intrinsics++) { const int i_var_intrinsics = mrcal_state_index_intrinsics(icam_intrinsics, ctx->Ncameras_intrinsics, ctx->Ncameras_extrinsics, ctx->Nframes, ctx->Npoints, ctx->Npoints_fixed, ctx->Nobservations_board, ctx->problem_selections, &ctx->lensmodel); if(ctx->lensmodel.type == MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC) { // Splined model regularization. I do directional L2 // regularization. At each knot I penalize contributions in // the tangential direction much more than in the radial // direction. Otherwise noise in the data produces lots of // curl in the vector field. This isn't wrong, but it's much // nicer if "right" in the camera coordinate system // corresponds to "right" in pixel space const int Nx = ctx->lensmodel.LENSMODEL_SPLINED_STEREOGRAPHIC__config.Nx; const int Ny = ctx->lensmodel.LENSMODEL_SPLINED_STEREOGRAPHIC__config.Ny; for(int iy=0; iyNintrinsics-Ncore; j++) { // This maybe should live elsewhere, but I put it here // for now. Various distortion coefficients have // different meanings, and should be regularized in // different ways. Specific logic follows double scale = scale_regularization_distortion; if( MRCAL_LENSMODEL_IS_OPENCV(ctx->lensmodel.type) && ctx->lensmodel.type >= MRCAL_LENSMODEL_OPENCV8 && 5 <= j && j <= 7 ) { // The radial distortion in opencv is x_distorted = // x*scale where r2 = norm2(xy - xyc) and // // scale = (1 + k0 r2 + k1 r4 + k4 r6)/(1 + k5 r2 + k6 r4 + k7 r6) // // Note that k2,k3 are tangential (NOT radial) // distortion components. Note that the r6 factor in // the numerator is only present for // >=MRCAL_LENSMODEL_OPENCV5. Note that the denominator // is only present for >= MRCAL_LENSMODEL_OPENCV8. The // danger with a rational model is that it's // possible to get into a situation where scale ~ // 0/0 ~ 1. This would have very poorly behaved // derivatives. If all the rational coefficients are // ~0, then the denominator is always ~1, and this // problematic case can't happen. I favor that by // regularizing the coefficients in the denominator // more strongly scale *= 5.; } if(Jt) Jrowptr[iMeasurement] = iJacobian; double err = scale*intrinsics_all[icam_intrinsics][j+Ncore]; x[iMeasurement] = err; norm2_error += err*err; STORE_JACOBIAN( i_var_intrinsics + Ncore_state + j, scale * SCALE_DISTORTION ); iMeasurement++; if(dump_regularizaton_details) MSG("regularization distortion: %g; norm2: %g", err, err*err); } } } if( modelHasCore_fxfycxcy(&ctx->lensmodel) && ctx->problem_selections.do_optimize_intrinsics_core ) for(int icam_intrinsics=0; icam_intrinsicsNcameras_intrinsics; icam_intrinsics++) { const int i_var_intrinsics = mrcal_state_index_intrinsics(icam_intrinsics, ctx->Ncameras_intrinsics, ctx->Ncameras_extrinsics, ctx->Nframes, ctx->Npoints, ctx->Npoints_fixed, ctx->Nobservations_board, ctx->problem_selections, &ctx->lensmodel); // And another regularization term: optical center should be // near the middle. This breaks the symmetry between moving the // center pixel coords and pitching/yawing the camera. double cx_target = 0.5 * (double)(ctx->imagersizes[icam_intrinsics*2 + 0] - 1); double cy_target = 0.5 * (double)(ctx->imagersizes[icam_intrinsics*2 + 1] - 1); double err; if(Jt) Jrowptr[iMeasurement] = iJacobian; err = scale_regularization_centerpixel * (intrinsics_all[icam_intrinsics][2] - cx_target); x[iMeasurement] = err; norm2_error += err*err; STORE_JACOBIAN( i_var_intrinsics + 2, scale_regularization_centerpixel * SCALE_INTRINSICS_CENTER_PIXEL ); iMeasurement++; if(dump_regularizaton_details) MSG("regularization center pixel off-center: %g; norm2: %g", err, err*err); if(Jt) Jrowptr[iMeasurement] = iJacobian; err = scale_regularization_centerpixel * (intrinsics_all[icam_intrinsics][3] - cy_target); x[iMeasurement] = err; norm2_error += err*err; STORE_JACOBIAN( i_var_intrinsics + 3, scale_regularization_centerpixel * SCALE_INTRINSICS_CENTER_PIXEL ); iMeasurement++; if(dump_regularizaton_details) MSG("regularization center pixel off-center: %g; norm2: %g", err, err*err); } } } // required to indicate the end of the jacobian matrix if( !ctx->reportFitMsg ) { if(Jt) Jrowptr[iMeasurement] = iJacobian; if(iMeasurement != ctx->Nmeasurements) { MSG("Assertion (iMeasurement == ctx->Nmeasurements) failed: (%d != %d)", iMeasurement, ctx->Nmeasurements); assert(0); } if(iJacobian != ctx->N_j_nonzero ) { MSG("Assertion (iJacobian == ctx->N_j_nonzero ) failed: (%d != %d)", iJacobian, ctx->N_j_nonzero); assert(0); } // MSG_IF_VERBOSE("RMS: %g", sqrt(norm2_error / (double)ctx>Nmeasurements)); } } bool mrcal_optimizer_callback(// out // These output pointers may NOT be NULL, unlike // their analogues in mrcal_optimize() // Shape (Nstate,) double* b_packed, // used only to confirm that the user passed-in the buffer they // should have passed-in. The size must match exactly int buffer_size_b_packed, // Shape (Nmeasurements,) double* x, // used only to confirm that the user passed-in the buffer they // should have passed-in. The size must match exactly int buffer_size_x, // output Jacobian. May be NULL if we don't need // it. This is the unitless Jacobian, used by the // internal optimization routines cholmod_sparse* Jt, // in // intrinsics is a concatenation of the intrinsics core // and the distortion params. The specific distortion // parameters may vary, depending on lensmodel, so // this is a variable-length structure const double* intrinsics, // Ncameras_intrinsics * NlensParams const mrcal_pose_t* extrinsics_fromref, // Ncameras_extrinsics of these. Transform FROM the reference frame const mrcal_pose_t* frames_toref, // Nframes of these. Transform TO the reference frame const mrcal_point3_t* points, // Npoints of these. In the reference frame const mrcal_calobject_warp_t* calobject_warp, // 1 of these. May be NULL if !problem_selections.do_optimize_calobject_warp int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, // at the end of points[] const mrcal_observation_board_t* observations_board, const mrcal_observation_point_t* observations_point, int Nobservations_board, int Nobservations_point, // All the board pixel observations, in order. .x, // .y are the pixel observations .z is the weight // of the observation. Most of the weights are // expected to be 1.0. Less precise observations // have lower weights. // // z<0 indicates that this is an outlier const mrcal_point3_t* observations_board_pool, const mrcal_lensmodel_t* lensmodel, const int* imagersizes, // Ncameras_intrinsics*2 of these mrcal_problem_selections_t problem_selections, const mrcal_problem_constants_t* problem_constants, double calibration_object_spacing, int calibration_object_width_n, int calibration_object_height_n, bool verbose) { bool result = false; if( Nobservations_board > 0 ) { if( problem_selections.do_optimize_calobject_warp && calobject_warp == NULL ) { MSG("ERROR: We're optimizing the calibration object warp, so a buffer with a seed MUST be passed in."); goto done; } } else problem_selections.do_optimize_calobject_warp = false; if(!modelHasCore_fxfycxcy(lensmodel)) problem_selections.do_optimize_intrinsics_core = false; if(!problem_selections.do_optimize_intrinsics_core && !problem_selections.do_optimize_intrinsics_distortions && !problem_selections.do_optimize_extrinsics && !problem_selections.do_optimize_frames && !problem_selections.do_optimize_calobject_warp) { MSG("Not optimizing any of our variables!"); goto done; } const int Nstate = mrcal_num_states(Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, Nobservations_board, problem_selections, lensmodel); if( buffer_size_b_packed != Nstate*(int)sizeof(double) ) { MSG("The buffer passed to fill-in b_packed has the wrong size. Needed exactly %d bytes, but got %d bytes", Nstate*(int)sizeof(double),buffer_size_b_packed); goto done; } int Nmeasurements = mrcal_num_measurements(Nobservations_board, Nobservations_point, calibration_object_width_n, calibration_object_height_n, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, problem_selections, lensmodel); int Nintrinsics = mrcal_lensmodel_num_params(lensmodel); int N_j_nonzero = _mrcal_num_j_nonzero(Nobservations_board, Nobservations_point, calibration_object_width_n, calibration_object_height_n, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, observations_board, observations_point, problem_selections, lensmodel); if( buffer_size_x != Nmeasurements*(int)sizeof(double) ) { MSG("The buffer passed to fill-in x has the wrong size. Needed exactly %d bytes, but got %d bytes", Nmeasurements*(int)sizeof(double),buffer_size_x); goto done; } const int Npoints_fromBoards = Nobservations_board * calibration_object_width_n*calibration_object_height_n; const callback_context_t ctx = { .intrinsics = intrinsics, .extrinsics_fromref = extrinsics_fromref, .frames_toref = frames_toref, .points = points, .calobject_warp = calobject_warp, .Ncameras_intrinsics = Ncameras_intrinsics, .Ncameras_extrinsics = Ncameras_extrinsics, .Nframes = Nframes, .Npoints = Npoints, .Npoints_fixed = Npoints_fixed, .observations_board = observations_board, .observations_board_pool = observations_board_pool, .Nobservations_board = Nobservations_board, .observations_point = observations_point, .Nobservations_point = Nobservations_point, .verbose = verbose, .lensmodel = *lensmodel, .imagersizes = imagersizes, .problem_selections = problem_selections, .problem_constants = problem_constants, .calibration_object_spacing = calibration_object_spacing, .calibration_object_width_n = calibration_object_width_n > 0 ? calibration_object_width_n : 0, .calibration_object_height_n= calibration_object_height_n > 0 ? calibration_object_height_n : 0, .Nmeasurements = Nmeasurements, .N_j_nonzero = N_j_nonzero, .Nintrinsics = Nintrinsics}; _mrcal_precompute_lensmodel_data((mrcal_projection_precomputed_t*)&ctx.precomputed, lensmodel); pack_solver_state(b_packed, lensmodel, intrinsics, extrinsics_fromref, frames_toref, points, calobject_warp, problem_selections, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints-Npoints_fixed, Nobservations_board, Nstate); optimizer_callback(b_packed, x, Jt, &ctx); result = true; done: return result; } mrcal_stats_t mrcal_optimize( // out // Each one of these output pointers may be NULL // Shape (Nstate,) double* b_packed_final, // used only to confirm that the user passed-in the buffer they // should have passed-in. The size must match exactly int buffer_size_b_packed_final, // Shape (Nmeasurements,) double* x_final, // used only to confirm that the user passed-in the buffer they // should have passed-in. The size must match exactly int buffer_size_x_final, // out, in // These are a seed on input, solution on output // intrinsics is a concatenation of the intrinsics core and the // distortion params. The specific distortion parameters may // vary, depending on lensmodel, so this is a variable-length // structure double* intrinsics, // Ncameras_intrinsics * NlensParams mrcal_pose_t* extrinsics_fromref, // Ncameras_extrinsics of these. Transform FROM the reference frame mrcal_pose_t* frames_toref, // Nframes of these. Transform TO the reference frame mrcal_point3_t* points, // Npoints of these. In the reference frame mrcal_calobject_warp_t* calobject_warp, // 1 of these. May be NULL if !problem_selections.do_optimize_calobject_warp // in int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, // at the end of points[] const mrcal_observation_board_t* observations_board, const mrcal_observation_point_t* observations_point, int Nobservations_board, int Nobservations_point, // All the board pixel observations, in order. // .x, .y are the pixel observations // .z is the weight of the observation. Most of the weights are // expected to be 1.0, which implies that the noise on the // observation has standard deviation of // observed_pixel_uncertainty. observed_pixel_uncertainty scales // inversely with the weight. // // z<0 indicates that this is an outlier. This is respected on // input (even if !do_apply_outlier_rejection). New outliers are // marked with z<0 on output, so this isn't const mrcal_point3_t* observations_board_pool, const mrcal_lensmodel_t* lensmodel, const int* imagersizes, // Ncameras_intrinsics*2 of these mrcal_problem_selections_t problem_selections, const mrcal_problem_constants_t* problem_constants, double calibration_object_spacing, int calibration_object_width_n, int calibration_object_height_n, bool verbose, bool check_gradient) { if( Nobservations_board > 0 ) { if( problem_selections.do_optimize_calobject_warp && calobject_warp == NULL ) { MSG("ERROR: We're optimizing the calibration object warp, so a buffer with a seed MUST be passed in."); return (mrcal_stats_t){.rms_reproj_error__pixels = -1.0}; } } else problem_selections.do_optimize_calobject_warp = false; if(!modelHasCore_fxfycxcy(lensmodel)) problem_selections.do_optimize_intrinsics_core = false; if(!problem_selections.do_optimize_intrinsics_core && !problem_selections.do_optimize_intrinsics_distortions && !problem_selections.do_optimize_extrinsics && !problem_selections.do_optimize_frames && !problem_selections.do_optimize_calobject_warp) { MSG("Warning: Not optimizing any of our variables"); } dogleg_parameters2_t dogleg_parameters; dogleg_getDefaultParameters(&dogleg_parameters); dogleg_parameters.dogleg_debug = verbose ? DOGLEG_DEBUG_VNLOG : 0; // These were derived empirically, seeking high accuracy, fast convergence // and without serious concern for performance. I looked only at a single // frame. Tweak them please dogleg_parameters.Jt_x_threshold = 0; dogleg_parameters.update_threshold = 1e-6; dogleg_parameters.trustregion_threshold = 0; dogleg_parameters.max_iterations = 300; // dogleg_parameters.trustregion_decrease_factor = 0.1; // dogleg_parameters.trustregion_decrease_threshold = 0.15; // dogleg_parameters.trustregion_increase_factor = 4.0 // dogleg_parameters.trustregion_increase_threshold = 0.75; const int Npoints_fromBoards = Nobservations_board * calibration_object_width_n*calibration_object_height_n; callback_context_t ctx = { .intrinsics = intrinsics, .extrinsics_fromref = extrinsics_fromref, .frames_toref = frames_toref, .points = points, .calobject_warp = calobject_warp, .Ncameras_intrinsics = Ncameras_intrinsics, .Ncameras_extrinsics = Ncameras_extrinsics, .Nframes = Nframes, .Npoints = Npoints, .Npoints_fixed = Npoints_fixed, .observations_board = observations_board, .observations_board_pool = observations_board_pool, .Nobservations_board = Nobservations_board, .observations_point = observations_point, .Nobservations_point = Nobservations_point, .verbose = verbose, .lensmodel = *lensmodel, .imagersizes = imagersizes, .problem_selections = problem_selections, .problem_constants = problem_constants, .calibration_object_spacing = calibration_object_spacing, .calibration_object_width_n = calibration_object_width_n > 0 ? calibration_object_width_n : 0, .calibration_object_height_n= calibration_object_height_n > 0 ? calibration_object_height_n : 0, .Nmeasurements = mrcal_num_measurements(Nobservations_board, Nobservations_point, calibration_object_width_n, calibration_object_height_n, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, problem_selections, lensmodel), .N_j_nonzero = _mrcal_num_j_nonzero(Nobservations_board, Nobservations_point, calibration_object_width_n, calibration_object_height_n, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, observations_board, observations_point, problem_selections, lensmodel), .Nintrinsics = mrcal_lensmodel_num_params(lensmodel)}; _mrcal_precompute_lensmodel_data((mrcal_projection_precomputed_t*)&ctx.precomputed, lensmodel); const int Nstate = mrcal_num_states(Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, Nobservations_board, problem_selections, lensmodel); if( b_packed_final != NULL && buffer_size_b_packed_final != Nstate*(int)sizeof(double) ) { MSG("The buffer passed to fill-in b_packed_final has the wrong size. Needed exactly %d bytes, but got %d bytes", Nstate*(int)sizeof(double),buffer_size_b_packed_final); return (mrcal_stats_t){.rms_reproj_error__pixels = -1.0}; } if( x_final != NULL && buffer_size_x_final != ctx.Nmeasurements*(int)sizeof(double) ) { MSG("The buffer passed to fill-in x_final has the wrong size. Needed exactly %d bytes, but got %d bytes", ctx.Nmeasurements*(int)sizeof(double),buffer_size_x_final); return (mrcal_stats_t){.rms_reproj_error__pixels = -1.0}; } dogleg_solverContext_t* solver_context = NULL; if(verbose) MSG("## Nmeasurements=%d, Nstate=%d", ctx.Nmeasurements, Nstate); if(ctx.Nmeasurements <= Nstate) { MSG("WARNING: problem isn't overdetermined: Nmeasurements=%d, Nstate=%d. Solver may not converge, and if it does, the results aren't reliable. Add more constraints and/or regularization", ctx.Nmeasurements, Nstate); } // WARNING: is it reasonable to put this on the stack? Can I use // b_packed_final for this? double packed_state[Nstate]; pack_solver_state(packed_state, lensmodel, intrinsics, extrinsics_fromref, frames_toref, points, calobject_warp, problem_selections, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints-Npoints_fixed, Nobservations_board, Nstate); double norm2_error = -1.0; mrcal_stats_t stats = {.rms_reproj_error__pixels = -1.0 }; if( !check_gradient ) { stats.Noutliers = 0; const int Nfeatures_board = Nobservations_board * calibration_object_width_n * calibration_object_height_n; for(int i=0; ibeforeStep, solver_context); #endif } while( problem_selections.do_apply_outlier_rejection && markOutliers(observations_board_pool, &stats.Noutliers, observations_board, Nobservations_board, calibration_object_width_n, calibration_object_height_n, solver_context->beforeStep->x, verbose) && ({MSG("Threw out some outliers. New count = %d/%d (%.1f%%). Going again", stats.Noutliers, Nmeasurements_board, (double)(stats.Noutliers * 100) / (double)Nmeasurements_board); true;})); // Done. I have the final state. I spit it back out unpack_solver_state( intrinsics, // Ncameras_intrinsics of these extrinsics_fromref, // Ncameras_extrinsics of these frames_toref, // Nframes of these points, // Npoints of these calobject_warp, packed_state, lensmodel, problem_selections, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints-Npoints_fixed, Nobservations_board, Nstate); double regularization_ratio_distortion = 0.0; double regularization_ratio_centerpixel = 0.0; int imeas_reg0 = mrcal_measurement_index_regularization(calibration_object_width_n, calibration_object_height_n, Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, Nobservations_board, Nobservations_point, problem_selections, lensmodel); if(problem_selections.do_apply_regularization && imeas_reg0 >= 0) { int Ncore = modelHasCore_fxfycxcy(lensmodel) ? 4 : 0; int Nmeasurements_regularization_distortion = 0; if(problem_selections.do_optimize_intrinsics_distortions) Nmeasurements_regularization_distortion = Ncameras_intrinsics*(ctx.Nintrinsics-Ncore); int Nmeasurements_regularization_centerpixel = 0; if(problem_selections.do_optimize_intrinsics_core) Nmeasurements_regularization_centerpixel = Ncameras_intrinsics*2; double norm2_err_regularization_distortion = 0; double norm2_err_regularization_centerpixel = 0; const double* xreg = &solver_context->beforeStep->x[imeas_reg0]; for(int i=0; ibeforeStep->x[ctx.Nmeasurements]); regularization_ratio_distortion = norm2_err_regularization_distortion / norm2_error; regularization_ratio_centerpixel = norm2_err_regularization_centerpixel / norm2_error; // These are important to the dev, but not to the end user. So I // disable these by default // if(regularization_ratio_distortion > 0.01) // MSG("WARNING: regularization ratio for lens distortion exceeds 1%%. Is the scale factor too high? Ratio = %.3g/%.3g = %.3g", // norm2_err_regularization_distortion, norm2_error, regularization_ratio_distortion); // if(regularization_ratio_centerpixel > 0.01) // MSG("WARNING: regularization ratio for the projection centerpixel exceeds 1%%. Is the scale factor too high? Ratio = %.3g/%.3g = %.3g", // norm2_err_regularization_centerpixel, norm2_error, regularization_ratio_centerpixel); } if(verbose) { if(problem_selections.do_apply_regularization) { // Disable this by default. Splined models have LOTS of // parameters, and I don't want to print them. Usually. // // for(int i=0; ibeforeStep->x[ctx.Nmeasurements - Nmeasurements_regularization + i]; // MSG("regularization %d: %f (squared: %f)", i, x, x*x); // } MSG("Regularization stats:"); MSG("reg err ratio (distortion,centerpixel): %.3g %.3g", regularization_ratio_distortion, regularization_ratio_centerpixel); } } } else for(int ivar=0; ivarbeforeStep->p, Nstate*sizeof(double)); if(x_final) memcpy(x_final, solver_context->beforeStep->x, ctx.Nmeasurements*sizeof(double)); done: if(solver_context != NULL) dogleg_freeContext(&solver_context); return stats; } bool mrcal_write_cameramodel_file(const char* filename, const mrcal_cameramodel_t* cameramodel) { bool result = false; FILE* fp = fopen(filename, "w"); if(fp == NULL) { MSG("Couldn't open('%s')", filename); return false; } char lensmodel_string[1024]; if(!mrcal_lensmodel_name(lensmodel_string, sizeof(lensmodel_string), &cameramodel->lensmodel)) { MSG("Couldn't construct lensmodel string. Unconfigured string: '%s'", mrcal_lensmodel_name_unconfigured(&cameramodel->lensmodel)); goto done; } int Nparams = mrcal_lensmodel_num_params(&cameramodel->lensmodel); if(Nparams<0) { MSG("Couldn't get valid Nparams from lensmodel string '%s'", lensmodel_string); goto done; } fprintf(fp, "{\n"); fprintf(fp, " 'lensmodel': '%s',\n", lensmodel_string); fprintf(fp, " 'intrinsics': [ "); for(int i=0; iintrinsics[i]); fprintf(fp, "],\n"); fprintf(fp, " 'imagersize': [ %u, %u ],\n", cameramodel->imagersize[0], cameramodel->imagersize[1]); fprintf(fp, " 'extrinsics': [ %f, %f, %f, %f, %f, %f ]\n", cameramodel->rt_cam_ref[0], cameramodel->rt_cam_ref[1], cameramodel->rt_cam_ref[2], cameramodel->rt_cam_ref[3], cameramodel->rt_cam_ref[4], cameramodel->rt_cam_ref[5]); fprintf(fp,"}\n"); result = true; done: if(fp != NULL) fclose(fp); return result; } mrcal-2.4.1/mrcal.h000066400000000000000000001124111456301662300140710ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #pragma once #include #include #include "mrcal-types.h" #include "poseutils.h" #include "stereo.h" #include "triangulation.h" #include "mrcal-image.h" //////////////////////////////////////////////////////////////////////////////// //////////////////// Lens models //////////////////////////////////////////////////////////////////////////////// // Return an array of strings listing all the available lens models // // These are all "unconfigured" strings that use "..." placeholders for any // configuration values. Each returned string is a \0-terminated const char*. The // end of the list is signified by a NULL pointer const char* const* mrcal_supported_lensmodel_names( void ); // NULL-terminated array of char* strings // Return true if the given mrcal_lensmodel_type_t specifies a valid lens model __attribute__((unused)) static bool mrcal_lensmodel_type_is_valid(mrcal_lensmodel_type_t t) { return t >= 0; } // Evaluates to true if the given lens model is one of the supported OpenCV // types #define MRCAL_LENSMODEL_IS_OPENCV(d) (MRCAL_LENSMODEL_OPENCV4 <= (d) && (d) <= MRCAL_LENSMODEL_OPENCV12) // Return a string describing a lens model. // // This function returns a static string. For models with no configuration, this // is the FULL string for that model. For models with a configuration, the // configuration values have "..." placeholders. These placeholders mean that // the resulting strings do not define a lens model fully, and cannot be // converted to a mrcal_lensmodel_t with mrcal_lensmodel_from_name() // // This is the inverse of mrcal_lensmodel_type_from_name() const char* mrcal_lensmodel_name_unconfigured( const mrcal_lensmodel_t* lensmodel ); // Return a CONFIGURED string describing a lens model. // // This function generates a fully-configured string describing the given lens // model. For models with no configuration, this is just the static string // returned by mrcal_lensmodel_name_unconfigured(). For models that have a // configuration, however, the configuration values are filled-in. The resulting // string may be converted back into a mrcal_lensmodel_t by calling // mrcal_lensmodel_from_name(). // // This function writes the string into the given buffer "out". The size of the // buffer is passed in the "size" argument. The meaning of "size" is as with // snprintf(), which is used internally. Returns true on success // // This is the inverse of mrcal_lensmodel_from_name() bool mrcal_lensmodel_name( char* out, int size, const mrcal_lensmodel_t* lensmodel ); // Parse the lens model type from a lens model name string // // The configuration is ignored. Thus this function works even if the // configuration is missing or unparseable. Unknown model names return // MRCAL_LENSMODEL_INVALID_TYPE // // This is the inverse of mrcal_lensmodel_name_unconfigured() mrcal_lensmodel_type_t mrcal_lensmodel_type_from_name( const char* name ); // Parse the full configured lens model from a lens model name string // // The lens mode type AND the configuration are read into a mrcal_lensmodel_t // structure, which this function returns. // // On error returns false with lensmodel->type set to MRCAL_LENSMODEL_INVALID_... // // This is the inverse of mrcal_lensmodel_name() bool mrcal_lensmodel_from_name( // output mrcal_lensmodel_t* lensmodel, // input const char* name ); // Return a structure containing a model's metadata // // The available metadata is described in the definition of the // MRCAL_LENSMODEL_META_LIST() macro mrcal_lensmodel_metadata_t mrcal_lensmodel_metadata( const mrcal_lensmodel_t* lensmodel ); // Return the number of parameters required to specify a given lens model // // For models that have a configuration, the parameter count value generally // depends on the configuration. For instance, splined models use the model // parameters as the spline control points, so the spline density (specified in // the configuration) directly affects how many parameters such a model requires int mrcal_lensmodel_num_params( const mrcal_lensmodel_t* lensmodel ); // Return the locations of x and y spline knots // Splined models are defined by the locations of their control points. These // are arranged in a grid, the size and density of which is set by the model // configuration. We fill-in the x knot locations into ux[] and the y locations // into uy[]. ux[] and uy[] must be large-enough to hold configuration->Nx and // configuration->Ny values respectively. // // This function applies to splined models only. Returns true on success bool mrcal_knots_for_splined_models( double* ux, double* uy, const mrcal_lensmodel_t* lensmodel); //////////////////////////////////////////////////////////////////////////////// //////////////////// Projections //////////////////////////////////////////////////////////////////////////////// // Project the given camera-coordinate-system points // // Compute a "projection", a mapping of points defined in the camera coordinate // system to their observed pixel coordinates. If requested, gradients are // computed as well. // // We project N 3D points p to N 2D pixel coordinates q using the given // lensmodel and intrinsics parameter values. // // if (dq_dp != NULL) we report the gradient dq/dp in a dense (N,2,3) array // ((N,2) mrcal_point3_t objects). // // if (dq_dintrinsics != NULL) we report the gradient dq/dintrinsics in a dense // (N,2,Nintrinsics) array. Note that splined models have very high Nintrinsics // and very sparse gradients. THIS function reports the gradients densely, // however, so it is inefficient for splined models. // // This function supports CAHVORE distortions only if we don't ask for any // gradients // // Projecting out-of-bounds points (beyond the field of view) returns undefined // values. Generally things remain continuous even as we move off the imager // domain. Pinhole-like projections will work normally if projecting a point // behind the camera. Splined projections clamp to the nearest spline segment: // the projection will fly off to infinity quickly since we're extrapolating a // polynomial, but the function will remain continuous. bool mrcal_project( // out mrcal_point2_t* q, mrcal_point3_t* dq_dp, double* dq_dintrinsics, // in const mrcal_point3_t* p, int N, const mrcal_lensmodel_t* lensmodel, // core, distortions concatenated const double* intrinsics); // Unproject the given pixel coordinates // // Compute an "unprojection", a mapping of pixel coordinates to the camera // coordinate system. // // We unproject N 2D pixel coordinates q to N 3D direction vectors v using the // given lensmodel and intrinsics parameter values. The returned vectors v are // not normalized, and may have any length. // This is the "reverse" direction, so an iterative nonlinear optimization is // performed internally to compute this result. This is much slower than // mrcal_project(). For OpenCV models specifically, OpenCV has // cvUndistortPoints() (and cv2.undistortPoints()), but these are unreliable: // https://github.com/opencv/opencv/issues/8811 // // This function does NOT support CAHVORE bool mrcal_unproject( // out mrcal_point3_t* v, // in const mrcal_point2_t* q, int N, const mrcal_lensmodel_t* lensmodel, // core, distortions concatenated const double* intrinsics); // Project the given camera-coordinate-system points using a pinhole // model. See the docs for projection details: // http://mrcal.secretsauce.net/lensmodels.html#lensmodel-pinhole // // This is a simplified special case of mrcal_project(). We project N // camera-coordinate-system points p to N pixel coordinates q // // if (dq_dp != NULL) we report the gradient dq/dp in a dense (N,2,3) array // ((N,2) mrcal_point3_t objects). void mrcal_project_pinhole( // output mrcal_point2_t* q, mrcal_point3_t* dq_dp, // input const mrcal_point3_t* p, int N, const double* fxycxy); // Unproject the given pixel coordinates using a pinhole model. // See the docs for projection details: // http://mrcal.secretsauce.net/lensmodels.html#lensmodel-pinhole // // This is a simplified special case of mrcal_unproject(). We unproject N 2D // pixel coordinates q to N camera-coordinate-system vectors v. The returned // vectors v are not normalized, and may have any length. // // if (dv_dq != NULL) we report the gradient dv/dq in a dense (N,3,2) array // ((N,3) mrcal_point2_t objects). void mrcal_unproject_pinhole( // output mrcal_point3_t* v, mrcal_point2_t* dv_dq, // input const mrcal_point2_t* q, int N, const double* fxycxy); // Project the given camera-coordinate-system points using a stereographic // model. See the docs for projection details: // http://mrcal.secretsauce.net/lensmodels.html#lensmodel-stereographic // // This is a simplified special case of mrcal_project(). We project N // camera-coordinate-system points p to N pixel coordinates q // // if (dq_dp != NULL) we report the gradient dq/dp in a dense (N,2,3) array // ((N,2) mrcal_point3_t objects). void mrcal_project_stereographic( // output mrcal_point2_t* q, mrcal_point3_t* dq_dp, // input const mrcal_point3_t* p, int N, const double* fxycxy); // Unproject the given pixel coordinates using a stereographic model. // See the docs for projection details: // http://mrcal.secretsauce.net/lensmodels.html#lensmodel-stereographic // // This is a simplified special case of mrcal_unproject(). We unproject N 2D // pixel coordinates q to N camera-coordinate-system vectors v. The returned // vectors v are not normalized, and may have any length. // // if (dv_dq != NULL) we report the gradient dv/dq in a dense (N,3,2) array // ((N,3) mrcal_point2_t objects). void mrcal_unproject_stereographic( // output mrcal_point3_t* v, mrcal_point2_t* dv_dq, // input const mrcal_point2_t* q, int N, const double* fxycxy); // Project the given camera-coordinate-system points using an equirectangular // projection. See the docs for projection details: // http://mrcal.secretsauce.net/lensmodels.html#lensmodel-lonlat // // This is a simplified special case of mrcal_project(). We project N // camera-coordinate-system points p to N pixel coordinates q // // if (dq_dp != NULL) we report the gradient dq/dp in a dense (N,2,3) array // ((N,2) mrcal_point3_t objects). void mrcal_project_lonlat( // output mrcal_point2_t* q, mrcal_point3_t* dq_dv, // May be NULL. Each point // gets a block of 2 mrcal_point3_t // objects // input const mrcal_point3_t* v, int N, const double* fxycxy); // Unproject the given pixel coordinates using an equirectangular projection. // See the docs for projection details: // http://mrcal.secretsauce.net/lensmodels.html#lensmodel-lonlat // // This is a simplified special case of mrcal_unproject(). We unproject N 2D // pixel coordinates q to N camera-coordinate-system vectors v. The returned // vectors v are normalized. // // if (dv_dq != NULL) we report the gradient dv/dq in a dense (N,3,2) array // ((N,3) mrcal_point2_t objects). void mrcal_unproject_lonlat( // output mrcal_point3_t* v, mrcal_point2_t* dv_dq, // May be NULL. Each point // gets a block of 3 mrcal_point2_t // objects // input const mrcal_point2_t* q, int N, const double* fxycxy); // Project the given camera-coordinate-system points using a transverse // equirectangular projection. See the docs for projection details: // http://mrcal.secretsauce.net/lensmodels.html#lensmodel-latlon // // This is a simplified special case of mrcal_project(). We project N // camera-coordinate-system points p to N pixel coordinates q // // if (dq_dp != NULL) we report the gradient dq/dp in a dense (N,2,3) array // ((N,2) mrcal_point3_t objects). void mrcal_project_latlon( // output mrcal_point2_t* q, mrcal_point3_t* dq_dv, // May be NULL. Each point // gets a block of 2 mrcal_point3_t // objects // input const mrcal_point3_t* v, int N, const double* fxycxy); // Unproject the given pixel coordinates using a transverse equirectangular // projection. See the docs for projection details: // http://mrcal.secretsauce.net/lensmodels.html#lensmodel-latlon // // This is a simplified special case of mrcal_unproject(). We unproject N 2D // pixel coordinates q to N camera-coordinate-system vectors v. The returned // vectors v are normalized. // // if (dv_dq != NULL) we report the gradient dv/dq in a dense (N,3,2) array // ((N,3) mrcal_point2_t objects). void mrcal_unproject_latlon( // output mrcal_point3_t* v, mrcal_point2_t* dv_dq, // May be NULL. Each point // gets a block of 3 mrcal_point2_t // objects // input const mrcal_point2_t* q, int N, const double* fxycxy); //////////////////////////////////////////////////////////////////////////////// //////////////////// Optimization //////////////////////////////////////////////////////////////////////////////// // Return the number of parameters needed in optimizing the given lens model // // This is identical to mrcal_lensmodel_num_params(), but takes into account the // problem selections. Any intrinsics parameters locked down in the // mrcal_problem_selections_t do NOT count towards the optimization parameters int mrcal_num_intrinsics_optimization_params( mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel ); // Scales a state vector to the packed, unitless form used by the optimizer // // In order to make the optimization well-behaved, we scale all the variables in // the state and the gradients before passing them to the optimizer. The internal // optimization library thus works only with unitless (or "packed") data. // // This function takes an (Nstate,) array of full-units values b[], and scales // it to produce packed data. This function applies the scaling directly to the // input array; the input is modified, and nothing is returned. // // This is the inverse of mrcal_unpack_solver_state_vector() void mrcal_pack_solver_state_vector( // out, in double* b, // in int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel); // Scales a state vector from the packed, unitless form used by the optimizer // // In order to make the optimization well-behaved, we scale all the variables in // the state and the gradients before passing them to the optimizer. The internal // optimization library thus works only with unitless (or "packed") data. // // This function takes an (Nstate,) array of unitless values b[], and scales it // to produce full-units data. This function applies the scaling directly to the // input array; the input is modified, and nothing is returned. // // This is the inverse of mrcal_pack_solver_state_vector() void mrcal_unpack_solver_state_vector( // out, in double* b, // unitless state on input, // scaled, meaningful state on // output // in int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel); // Reports the icam_extrinsics corresponding to a given icam_intrinsics. // // If we're solving a vanilla calibration problem (stationary cameras observing // a moving calibration object), each camera has a unique intrinsics index and a // unique extrinsics index. This function reports the latter, given the former. // // On success, the result is written to *icam_extrinsics, and we return true. If // the given camera is at the reference coordinate system, it has no extrinsics, // and we report -1. // // If we have moving cameras (NOT a vanilla calibration problem), there isn't a // single icam_extrinsics for a given icam_intrinsics, and we report an error by // returning false bool mrcal_corresponding_icam_extrinsics(// out int* icam_extrinsics, // in int icam_intrinsics, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nobservations_board, const mrcal_observation_board_t* observations_board, int Nobservations_point, const mrcal_observation_point_t* observations_point); // Solve the given optimization problem // // This is the entry point to the mrcal optimization routine. The argument list // is commented. mrcal_stats_t mrcal_optimize( // out // Each one of these output pointers may be NULL // Shape (Nstate,) double* b_packed, // used only to confirm that the user passed-in the buffer they // should have passed-in. The size must match exactly int buffer_size_b_packed, // Shape (Nmeasurements,) double* x, // used only to confirm that the user passed-in the buffer they // should have passed-in. The size must match exactly int buffer_size_x, // out, in // These are a seed on input, solution on output // intrinsics is a concatenation of the intrinsics core and the // distortion params. The specific distortion parameters may // vary, depending on lensmodel, so this is a variable-length // structure double* intrinsics, // Ncameras_intrinsics * NlensParams mrcal_pose_t* extrinsics_fromref, // Ncameras_extrinsics of these. Transform FROM the reference frame mrcal_pose_t* frames_toref, // Nframes of these. Transform TO the reference frame mrcal_point3_t* points, // Npoints of these. In the reference frame mrcal_calobject_warp_t* calobject_warp, // 1 of these. May be NULL if !problem_selections.do_optimize_calobject_warp // in int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, // at the end of points[] const mrcal_observation_board_t* observations_board, const mrcal_observation_point_t* observations_point, int Nobservations_board, int Nobservations_point, // All the board pixel observations, in an array of shape // // ( Nobservations_board, // calibration_object_height_n, // calibration_object_width_n ) // // .x, .y are the // pixel observations .z is the weight of the observation. Most // of the weights are expected to be 1.0. Less precise // observations have lower weights. // // .z<0 indicates that this is an outlier. This is respected on // input (even if !do_apply_outlier_rejection). New outliers are // marked with .z<0 on output, so this isn't const mrcal_point3_t* observations_board_pool, const mrcal_lensmodel_t* lensmodel, const int* imagersizes, // Ncameras_intrinsics*2 of these mrcal_problem_selections_t problem_selections, const mrcal_problem_constants_t* problem_constants, double calibration_object_spacing, int calibration_object_width_n, int calibration_object_height_n, bool verbose, bool check_gradient); // This is cholmod_sparse. I don't want to include the full header that defines // it in mrcal.h, and I don't need to: mrcal.h just needs to know that it's a // structure struct cholmod_sparse_struct; // Evaluate the value of the callback function at the given operating point // // The main optimization routine in mrcal_optimize() searches for optimal // parameters by repeatedly calling a function to evaluate each hypothethical // parameter set. This evaluation function is available by itself here, // separated from the optimization loop. The arguments are largely the same as // those to mrcal_optimize(), but the inputs are all read-only It is expected // that this will be called from Python only. bool mrcal_optimizer_callback(// out // These output pointers may NOT be NULL, unlike // their analogues in mrcal_optimize() // Shape (Nstate,) double* b_packed, // used only to confirm that the user passed-in the buffer they // should have passed-in. The size must match exactly int buffer_size_b_packed, // Shape (Nmeasurements,) double* x, // used only to confirm that the user passed-in the buffer they // should have passed-in. The size must match exactly int buffer_size_x, // output Jacobian. May be NULL if we don't need // it. This is the unitless Jacobian, used by the // internal optimization routines struct cholmod_sparse_struct* Jt, // in // intrinsics is a concatenation of the intrinsics core // and the distortion params. The specific distortion // parameters may vary, depending on lensmodel, so // this is a variable-length structure const double* intrinsics, // Ncameras_intrinsics * NlensParams const mrcal_pose_t* extrinsics_fromref, // Ncameras_extrinsics of these. Transform FROM the reference frame const mrcal_pose_t* frames_toref, // Nframes of these. Transform TO the reference frame const mrcal_point3_t* points, // Npoints of these. In the reference frame const mrcal_calobject_warp_t* calobject_warp, // 1 of these. May be NULL if !problem_selections.do_optimize_calobject_warp int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, // at the end of points[] const mrcal_observation_board_t* observations_board, const mrcal_observation_point_t* observations_point, int Nobservations_board, int Nobservations_point, // All the board pixel observations, in an array of shape // // ( Nobservations_board, // calibration_object_height_n, // calibration_object_width_n ) // // .x, .y are the pixel observations .z is the // weight of the observation. Most of the weights // are expected to be 1.0. Less precise // observations have lower weights. // // .z<0 indicates that this is an outlier const mrcal_point3_t* observations_board_pool, const mrcal_lensmodel_t* lensmodel, const int* imagersizes, // Ncameras_intrinsics*2 of these mrcal_problem_selections_t problem_selections, const mrcal_problem_constants_t* problem_constants, double calibration_object_spacing, int calibration_object_width_n, int calibration_object_height_n, bool verbose); //////////////////////////////////////////////////////////////////////////////// //////////////////// Layout of the measurement and state vectors //////////////////////////////////////////////////////////////////////////////// // The optimization routine tries to minimize the length of the measurement // vector x by moving around the state vector b. // // Depending on the specific optimization problem being solved and the // mrcal_problem_selections_t, the state vector may contain any of // - The lens parameters // - The geometry of the cameras // - The geometry of the observed chessboards and discrete points // - The chessboard shape // // The measurement vector may contain // - The errors in observations of the chessboards // - The errors in observations of discrete points // - The penalties in the solved point positions // - The regularization terms // // Given the problem selections and a vector b or x it is often useful to know // where specific quantities lie in those vectors. We have 4 sets of functions // to answer such questions: // // int mrcal_measurement_index_THING() // Returns the index in the measurement vector x where the contiguous block of // values describing the THING begins. THING is any of // - boards // - points // - regularization // // int mrcal_num_measurements_THING() // Returns the number of values in the contiguous block in the measurement // vector x that describe the given THING. THING is any of // - boards // - points // - regularization // // int mrcal_state_index_THING() // Returns the index in the state vector b where the contiguous block of // values describing the THING begins. THING is any of // - intrinsics // - extrinsics // - frames // - points // - calobject_warp // If we're not optimizing the THING, return <0 // // int mrcal_num_states_THING() // Returns the number of values in the contiguous block in the state // vector b that describe the given THING. THING is any of // - intrinsics // - extrinsics // - frames // - points // - calobject_warp // If we're not optimizing the THING, return 0 int mrcal_measurement_index_boards(int i_observation_board, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n); int mrcal_num_measurements_boards(int Nobservations_board, int calibration_object_width_n, int calibration_object_height_n); int mrcal_measurement_index_points(int i_observation_point, int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n); int mrcal_num_measurements_points(int Nobservations_point); int mrcal_measurement_index_regularization(int calibration_object_width_n, int calibration_object_height_n, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel); int mrcal_num_measurements_regularization(int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel); int mrcal_num_measurements(int Nobservations_board, int Nobservations_point, int calibration_object_width_n, int calibration_object_height_n, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel); int mrcal_num_states(int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel); int mrcal_state_index_intrinsics(int icam_intrinsics, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel); int mrcal_num_states_intrinsics(int Ncameras_intrinsics, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel); int mrcal_state_index_extrinsics(int icam_extrinsics, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel); int mrcal_num_states_extrinsics(int Ncameras_extrinsics, mrcal_problem_selections_t problem_selections); int mrcal_state_index_frames(int iframe, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel); int mrcal_num_states_frames(int Nframes, mrcal_problem_selections_t problem_selections); int mrcal_state_index_points(int i_point, int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel); int mrcal_num_states_points(int Npoints, int Npoints_fixed, mrcal_problem_selections_t problem_selections); int mrcal_state_index_calobject_warp(int Ncameras_intrinsics, int Ncameras_extrinsics, int Nframes, int Npoints, int Npoints_fixed, int Nobservations_board, mrcal_problem_selections_t problem_selections, const mrcal_lensmodel_t* lensmodel); int mrcal_num_states_calobject_warp(mrcal_problem_selections_t problem_selections, int Nobservations_board); // if len>0, the string doesn't need to be 0-terminated. If len<=0, the end of // the buffer IS indicated by a '\0' byte // // return NULL on error mrcal_cameramodel_t* mrcal_read_cameramodel_string(const char* string, int len); mrcal_cameramodel_t* mrcal_read_cameramodel_file (const char* filename); void mrcal_free_cameramodel(mrcal_cameramodel_t** cameramodel); bool mrcal_write_cameramodel_file(const char* filename, const mrcal_cameramodel_t* cameramodel); #define DECLARE_mrcal_apply_color_map(T,Tname) \ bool mrcal_apply_color_map_##Tname( \ mrcal_image_bgr_t* out, \ const mrcal_image_##Tname##_t* in, \ \ /* If true, I set in_min/in_max from the */ \ /* min/max of the input data */ \ const bool auto_min, \ const bool auto_max, \ \ /* If true, I implement gnuplot's default 7,5,15 mapping. */ \ /* This is a reasonable default choice. */ \ /* function_red/green/blue are ignored if true */ \ const bool auto_function, \ \ /* min/max input values to use if not */ \ /* auto_min/auto_max */ \ T in_min, /* will map to 0 */ \ T in_max, /* will map to 255 */ \ \ /* The color mappings to use. If !auto_function */ \ int function_red, \ int function_green, \ int function_blue) DECLARE_mrcal_apply_color_map(uint8_t, uint8); DECLARE_mrcal_apply_color_map(uint16_t, uint16); DECLARE_mrcal_apply_color_map(uint32_t, uint32); DECLARE_mrcal_apply_color_map(uint64_t, uint64); DECLARE_mrcal_apply_color_map(int8_t, int8); DECLARE_mrcal_apply_color_map(int16_t, int16); DECLARE_mrcal_apply_color_map(int32_t, int32); DECLARE_mrcal_apply_color_map(int64_t, int64); DECLARE_mrcal_apply_color_map(float, float); DECLARE_mrcal_apply_color_map(double, double); #undef DECLARE_mrcal_apply_color_map // Public ABI stuff, that's not for end-user consumption #include "mrcal-internal.h" mrcal-2.4.1/mrcal/000077500000000000000000000000001456301662300137205ustar00rootroot00000000000000mrcal-2.4.1/mrcal/__init__.py000066400000000000000000000025661456301662300160420ustar00rootroot00000000000000#!/usr/bin/python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 '''The main mrcal Python package This package doesn't contain any code itself, but all the mrcal.mmm submodules export their symbols here for convenience. So any function that can be called as mrcal.mmm.fff() can be called as mrcal.fff() instead. The latter is preferred. ''' # The C wrapper is written by us in mrcal-pywrap.c from ._mrcal import * # The C wrapper is generated from mrcal-genpywrap.py from ._mrcal_npsp import * from .projections import * from .cameramodel import * from .poseutils import * # The C wrapper is generated from poseutils-genpywrap.py from ._poseutils_npsp import * from .stereo import * from .visualization import * from .model_analysis import * from .synthetic_data import * from .calibration import * from .image_transforms import * from .utils import * from .triangulation import * # libelas is optional. If we don't have it, I don't complain try: from ._elas_npsp import * except ModuleNotFoundError: pass mrcal-2.4.1/mrcal/_poseutils_scipy.py000066400000000000000000000105661456301662300176770ustar00rootroot00000000000000#!/usr/bin/python3 import sys import numpy as np import numpysane as nps def quat_from_R(R, *, out=None): r"""Convert a rotation defined as a rotation matrix to a unit quaternion SYNOPSIS print(R.shape) ===> (3,3) quat = mrcal.quat_from_R(R) print(quat.shape) ===> (4,) c = quat[0] s = nps.mag(quat[1:]) rotation_magnitude = 2. * np.arctan2(s,c) rotation_axis = quat[1:] / s This is mostly for compatibility with some old stuff. mrcal doesn't use quaternions anywhere. Test this thoroughly before using. This function supports broadcasting fully. ARGUMENTS - R: array of shape (3,3,). The rotation matrix that defines the rotation. - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE We return an array of unit quaternions. Each broadcasted slice has shape (4,). The values in the array are (u,i,j,k) LICENSE AND COPYRIGHT The implementation comes directly from the scipy project, the from_dcm() function in https://github.com/scipy/scipy/blob/master/scipy/spatial/transform/rotation.py Commit: 1169d27ad47a29abafa8a3d2cb5b67ff0df80a8f License: Copyright (c) 2001-2002 Enthought, Inc. 2003-2019, SciPy Developers. All rights reserved. Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. """ # extra broadcasted shape extra_dims = R.shape[:-2] # R.shape = (..., 3,3) with some non-empty ... R = nps.atleast_dims(R, -3) # R.shape = (N,3,3) R = nps.clump(R, n=R.ndim-2) num_rotations = R.shape[0] decision_matrix = np.empty((num_rotations, 4)) decision_matrix[:, :3] = R.diagonal(axis1=1, axis2=2) decision_matrix[:, -1] = decision_matrix[:, :3].sum(axis=1) choices = decision_matrix.argmax(axis=1) s = (num_rotations, 4) if out is not None: quat = out.reshape(s) def base(x): r'''Base function, that returns the self array if it's not a view''' return x if x.base is None else x.base if base(quat) is not base(out): raise Exception("quat_from_R() in-place output isn't yet complete. Please fix") else: quat = np.empty(s) ind = np.nonzero(choices != 3)[0] i = choices[ind] j = (i + 1) % 3 k = (j + 1) % 3 quat[ind, i+1] = 1 - decision_matrix[ind, -1] + 2 * R[ind, i, i] quat[ind, j+1] = R[ind, j, i] + R[ind, i, j] quat[ind, k+1] = R[ind, k, i] + R[ind, i, k] quat[ind, 0 ] = R[ind, k, j] - R[ind, j, k] ind = np.nonzero(choices == 3)[0] quat[ind, 1] = R[ind, 2, 1] - R[ind, 1, 2] quat[ind, 2] = R[ind, 0, 2] - R[ind, 2, 0] quat[ind, 3] = R[ind, 1, 0] - R[ind, 0, 1] quat[ind, 0] = 1 + decision_matrix[ind, -1] quat /= np.linalg.norm(quat, axis=1)[:, None] return quat.reshape(extra_dims + (4,)) mrcal-2.4.1/mrcal/cahvor.py000066400000000000000000000422551456301662300155640ustar00rootroot00000000000000#!/usr/bin/python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Read/write camera models using the legacy .cahvor file format The .cahvor functionality is available via the mrcal.cameramodel class. There's no reason for end users to use the mrcal.cahvor module directly. mrcal supports the .cahvor file format to interoperate with tools that work with that format only. Models stored as .cahvor support a subset of .cameramodel functionality: the optimization_inputs are not included, so uncertainty computations are not possible from .cahvor models. CAHVOR and CAHVORE lens models can be stored in a .cahvor file as one would expect. OPENCV models write a CAHV model, with distortions in a magic comment, and it is up to the parser to interpret that comment. Other lens model types are not supported. Unless you're interfacing with tools that expect .cahvor files, there's no reason to use this module. ''' import sys import re import numpy as np import numpysane as nps import mrcal def _HVs_HVc_HVp(A,H,V): r'''Given a cahvor dict returns a tuple containing (Hs,Vs,Hc,Vc,Hp,Vp)''' Hc = nps.inner(H, A) hshp = H - Hc * A Hs = np.sqrt(nps.inner(hshp,hshp)) Vc = nps.inner(V, A) vsvp = V - Vc * A Vs = np.sqrt(nps.inner(vsvp,vsvp)) Hp = hshp / Hs Vp = vsvp / Vs return Hs,Vs,Hc,Vc,Hp,Vp def _construct_model(C,A,H,V, O = None, R = None, E = None, *, cahvore_linearity, is_cahvor_or_cahvore, is_cahvore, Dimensions, name, VALID_INTRINSICS_REGION = None, lensmodel_fallback = None, distortions_fallback = None, **rest): r'''Construct a mrcal.cameramodel object from cahvor chunks I'm going to be calling this from the outside, but everything about cahvor is a massive hack, so I'm not documenting this ''' # normalize optical axis. Mostly this is here to smooth out ASCII roundoff # errors A /= nps.mag(A) fx,fy,cx,cy,Hp,Vp = _HVs_HVc_HVp(A,H,V) # By construction Hp and Vp will both be orthogonal to A. But CAHVOR allows # non-orthogonal Hp,Vp. MY implementation does not support this, so I check, # and barf if I encounter non-orthogonal Hp,Vp Vp_expected = np.cross(A, Hp) th = np.arccos(np.clip( nps.inner(Vp,Vp_expected), -1, 1)) *180./np.pi if th > 1e-3: print(f"WARNING: parsed .cahvor file has non-orthogonal Hp,Vp. Skew of {th:.3f} degrees. I'm using an orthogonal Vp, so the resulting model will work slightly differently", file=sys.stderr) Vp = Vp_expected R_toref = nps.transpose( nps.cat( Hp, Vp, A )) t_toref = C lensmodel = lensmodel_fallback distortions = distortions_fallback if is_cahvor_or_cahvore: if O is None: alpha = 0 beta = 0 else: o = nps.matmult( O, R_toref ) alpha = np.arctan2(o[0], o[2]) beta = np.arcsin( o[1] ) if is_cahvore: # CAHVORE if E is None: raise Exception('Cahvor file {} LOOKS like a cahvore, but lacks the E'.format(name)) R0,R1,R2 = R.ravel() E0,E1,E2 = E.ravel() distortions = np.array((alpha,beta,R0,R1,R2,E0,E1,E2), dtype=float) lensmodel = f'LENSMODEL_CAHVORE_linearity={cahvore_linearity}' else: # CAHVOR if E is not None: raise Exception('Cahvor file {} LOOKS like a cahvor, but has an E'.format(name)) if R is None or np.linalg.norm(R) < 1e-8: # pinhole distortions = np.array(()) lensmodel = 'LENSMODEL_PINHOLE' else: R0,R1,R2 = R.ravel() distortions = np.array((alpha,beta,R0,R1,R2), dtype=float) lensmodel = 'LENSMODEL_CAHVOR' return mrcal.cameramodel(imagersize = Dimensions[:2].astype(np.int32), intrinsics = (lensmodel, nps.glue( np.array((fx,fy,cx,cy), dtype=float), distortions, axis = -1)), valid_intrinsics_region = VALID_INTRINSICS_REGION, extrinsics_Rt_toref = np.ascontiguousarray(nps.glue(R_toref,t_toref, axis=-2))) def _read(s, name): r'''Reads a .cahvor file into a cameramodel The input is the .cahvor file contents as a string''' re_f = r'[-+]?(?:\d+(?:\.\d*)?|\.\d+)(?:[eE][-+]?\d+)?' re_u = r'\d+' re_d = r'[-+]?\d+' re_s = r'.+' # I parse all key=value lines into my dict as raw text. Further I # post-process some of these raw lines. x = {} for l in s.splitlines(): if re.match(r'^\s*#|^\s*$', l): continue m = re.match(r'\s*(\w+)\s*=\s*(.+?)\s*\n?$', l, flags=re.I) if m: key = m.group(1) value = m.group(2) # for compatibility if re.match('^DISTORTION', key): key = key.replace('DISTORTION', 'LENSMODEL') x[key] = value # Done reading. Any values that look like numbers, I convert to numbers. for i in x: if re.match('{}$'.format(re_f), x[i]): x[i] = float(x[i]) # I parse the fields I know I care about into numpy arrays for i in ('Dimensions','C','A','H','V','O','R','E', 'LENSMODEL_OPENCV4', 'LENSMODEL_OPENCV5', 'LENSMODEL_OPENCV8', 'LENSMODEL_OPENCV12', 'VALID_INTRINSICS_REGION'): if i in x: # Any data that's composed only of digits and whitespaces (no "."), # use integers if re.match(r'[0-9\s]+$', x[i]): totype = int else: totype = float x[i] = np.array( [ totype(v) for v in re.split(r'\s+', x[i])], dtype=totype) # Now I sanity-check the results and call it done for k in ('Dimensions','C','A','H','V'): if not k in x: raise Exception("Cahvor file '{}' incomplete. Missing values for: {}". format(name, k)) is_cahvore = False cahvore_linearity = None is_cahvor_or_cahvore = False if 'LENSMODEL_OPENCV12' in x: distortions = x["LENSMODEL_OPENCV12"] lensmodel = 'LENSMODEL_OPENCV12' elif 'LENSMODEL_OPENCV8' in x: distortions = x["LENSMODEL_OPENCV8"] lensmodel = 'LENSMODEL_OPENCV8' elif 'LENSMODEL_OPENCV5' in x: distortions = x["LENSMODEL_OPENCV5"] lensmodel = 'LENSMODEL_OPENCV5' elif 'LENSMODEL_OPENCV4' in x: distortions = x["LENSMODEL_OPENCV4"] lensmodel = 'LENSMODEL_OPENCV4' elif 'R' not in x: distortions = np.array(()) lensmodel = 'LENSMODEL_PINHOLE' else: is_cahvor_or_cahvore = True lensmodel = None distortions = None if 'VALID_INTRINSICS_REGION' in x: x['VALID_INTRINSICS_REGION'] = \ x['VALID_INTRINSICS_REGION'].reshape( len(x['VALID_INTRINSICS_REGION'])//2, 2) # get extrinsics from cahvor if 'Model' not in x: x['Model'] = '' # One of these: # CAHVORE1 # CAHVORE2 # CAHVORE3,0.44 m = re.match(r'CAHVORE\s*([0-9]+)(\s*,\s*([0-9\.e-]+))?',x['Model']) if m: modelname = x['Model'] is_cahvore = True try: mtype = int(m.group(1)) if m.group(3) is None: cahvore_linearity = None else: cahvore_linearity = float(m.group(3)) except: raise Exception(f"Cahvor file '{name}' looks like CAHVORE, but the CAHVORE declaration is unparseable: '{modelname}'") if mtype == 1: if cahvore_linearity is not None: if cahvore_linearity != 1: raise Exception(f"Cahvor file '{name}' looks like CAHVORE, but has an unexpected linearity defined. mtype=1 so I expected no linearity at all or linearity=1, but got {cahvore_linearity}. CAHVORE declaration: '{modelname}'") cahvore_linearity = 1 elif mtype == 2: if cahvore_linearity is not None: if cahvore_linearity != 0: raise Exception(f"Cahvor file '{name}' looks like CAHVORE, but has an unexpected linearity defined. mtype=2 so I expected no linearity at all or linearity=0, but got {cahvore_linearity}. CAHVORE declaration: '{modelname}'") cahvore_linearity = 0 elif mtype == 3: if cahvore_linearity is None: raise Exception(f"Cahvor file '{name}' looks like CAHVORE, but has a missing linearity. mtype=3 a linearity parameter MUST be defined. CAHVORE declaration: '{modelname}'") else: raise Exception(f"Cahvor file '{name}' looks like CAHVORE, but has mtype={mtype}. I only know about types 1,2,3. CAHVORE declaration: '{modelname}'") else: is_cahvore = False return _construct_model(**x, is_cahvor_or_cahvore = is_cahvor_or_cahvore, is_cahvore = is_cahvore, cahvore_linearity = cahvore_linearity, name = name, distortions_fallback = distortions, lensmodel_fallback = lensmodel) def read(f): r'''Reads a .cahvor file into a cameramodel The input is a filename or an opened file''' if type(f) is mrcal.cameramodel: return f if type(f) is str: with open(f, 'r') as openedfile: return _read(openedfile.read(), f) return _read(f.read(), f.name) def read_from_string(s): return _read(s, "") def _deconstruct_model(model): x = dict() lensmodel,intrinsics = model.intrinsics() m = re.match(r'^LENSMODEL_CAHVORE_linearity=([0-9\.]+)$', lensmodel) if m is not None: x['cahvore_linearity'] = float(m.group(1)) else: x['cahvore_linearity'] = None x['Dimensions'] = model.imagersize() fx,fy,cx,cy = intrinsics[:4] Rt_toref = model.extrinsics_Rt_toref() R_toref = Rt_toref[:3,:] t_toref = Rt_toref[ 3,:] x['C'] = t_toref x['A'] = R_toref[:,2] Hp = R_toref[:,0] Vp = R_toref[:,1] x['H'] = fx*Hp + x['A']*cx x['V'] = fy*Vp + x['A']*cy x['O'] = None x['R'] = None x['E'] = None if re.match('LENSMODEL_CAHVOR', lensmodel): # CAHVOR(E) alpha,beta,R0,R1,R2 = intrinsics[4:9] s_al,c_al,s_be,c_be = np.sin(alpha),np.cos(alpha),np.sin(beta),np.cos(beta) x['O'] = nps.matmult( R_toref, nps.transpose(np.array(( s_al*c_be, s_be, c_al*c_be ), dtype=float)) ).ravel() x['R'] = np.array((R0, R1, R2), dtype=float) if re.match('LENSMODEL_CAHVORE', lensmodel): x['E'] = intrinsics[9:] x['VALID_INTRINSICS_REGION'] = model.valid_intrinsics_region() return x def _write(f, m, note=None): r'''Writes a cameramodel as a .cahvor to a writeable file object''' x = _deconstruct_model(m) if note is not None: for l in note.splitlines(): f.write('# ' + l + '\n') lensmodel,intrinsics = m.intrinsics() if lensmodel == 'LENSMODEL_CAHVOR': f.write("Model = CAHVOR = perspective, distortion\n") elif re.match('LENSMODEL_(OPENCV.*|PINHOLE)', lensmodel): f.write("Model = CAHV = perspective, linear\n") else: if x['cahvore_linearity'] is not None: f.write(f"Model = CAHVORE3,{x['cahvore_linearity']} = general\n") else: raise Exception(f"Don't know how to handle lens model '{lensmodel}'") f.write('Dimensions = {} {}\n'.format(int(x['Dimensions'][0]), int(x['Dimensions'][1]))) f.write(("{} =" + (" {:15.10f}" * 3) + "\n").format('C', *x['C'])) f.write(("{} =" + (" {:15.10f}" * 3) + "\n").format('A', *x['A'])) f.write(("{} =" + (" {:15.10f}" * 3) + "\n").format('H', *x['H'])) f.write(("{} =" + (" {:15.10f}" * 3) + "\n").format('V', *x['V'])) if re.match('LENSMODEL_CAHVOR', lensmodel): # CAHVOR(E) f.write(("{} =" + (" {:15.10f}" * 3) + "\n").format('O', *x['O'])) f.write(("{} =" + (" {:15.10f}" * 3) + "\n").format('R', *x['R'])) if re.match('LENSMODEL_CAHVORE', lensmodel): f.write(("{} =" + (" {:15.10f}" * 3) + "\n").format('E', *x['E'])) elif re.match('LENSMODEL_OPENCV', lensmodel): Ndistortions = mrcal.lensmodel_num_params(lensmodel) - 4 f.write(("{} =" + (" {:15.10f}" * Ndistortions) + "\n").format(lensmodel, *intrinsics[4:])) elif lensmodel == 'LENSMODEL_PINHOLE': # the CAHV values we already wrote are all that's needed pass else: raise Exception(f"Cannot write lens model '{lensmodel}' to a .cahvor file. I only support PINHOLE, CAHVOR(E) and OPENCV model") if x['VALID_INTRINSICS_REGION'] is not None: f.write("VALID_INTRINSICS_REGION = ") np.savetxt(f, x['VALID_INTRINSICS_REGION'].ravel(), fmt='%.2f', newline=' ') f.write('\n') # Write covariance matrix. Old jplv parser requires that this exists, even # if the actual values don't matter S_size = 12 if re.match('LENSMODEL_CAHVORE', lensmodel): S_size = 21 elif re.match('LENSMODEL_CAHVOR', lensmodel): S_size = 18 f.write("S =\n" + ((" 0.0" * S_size) + "\n") * S_size) # Extra spaces before "=" are significant. Old jplv parser gets confused if # they don't exist Hs,Vs,Hc,Vc = intrinsics[:4] f.write("Hs = {}\n".format(Hs)) f.write("Hc = {}\n".format(Hc)) f.write("Vs = {}\n".format(Vs)) f.write("Vc = {}\n".format(Vc)) f.write("# this is hard-coded\nTheta = {} (-90.0 deg)\n".format(-np.pi/2)) # Write internal covariance matrix. Again, the old jplv parser requires that # this exists, even if the actual values don't matter S_internal_size = 5 f.write("S internal =\n" + ((" 0.0" * S_internal_size) + "\n") * S_internal_size) return True def write(f, m, note=None): r'''Writes a cameramodel as a .cahvor to a filename or a writeable file object''' if type(f) is str: with open(f, 'w') as openedfile: return _write(openedfile, m, note) return _write(f, m) def read_transforms(f): r'''Reads a file (a filename string, or a file-like object: an iterable containing lines of text) into a transforms dict, and returns the dict ''' needclose = False if type(f) is str: filename = f f = open(filename, 'r') needclose = True x = { 'veh_from_ins': None, # this is actually "pair" to ins 'ins_from_camera': {} } for l in f: if re.match(r'^\s*#|^\s*$', l): continue re_f = r'[-+]?(?:\d+(?:\.\d*)?|\.\d+)(?:[eE][-+]?\d+)?' re_u = r'\d+' re_d = r'[-+]?\d+' re_s = r'.+' re_pos = r'\(\s*({f})\s+({f})\s+({f})\s*\)' .format(f=re_f) re_quat = r'\(\s*({f})\s+({f})\s+({f})\s+({f})\s*\)'.format(f=re_f) m = re.match(r'\s*ins2veh\s*=\s*{p}\s*{q}\s*\n?$'. format(u=re_u, p=re_pos, q=re_quat), l) if m: if x['veh_from_ins'] is not None: raise("'{}' is corrupt: more than one 'ins2veh'".format(f.name)) x['veh_from_ins'] = mrcal.Rt_from_qt( np.array((float(m.group(4)),float(m.group(5)),float(m.group(6)),float(m.group(7)), float(m.group(1)),float(m.group(2)),float(m.group(3)), ))) continue m = re.match(r'\s*cam2ins\s*\[({u})\]\s*=\s*{p}\s*{q}\s*\n?$'. format(u=re_u, p=re_pos, q=re_quat), l) if m: i = int(m.group(1)) if x['ins_from_camera'].get(i) is not None: raise("'{}' is corrupt: more than one 'cam2ins'[{}]".format(f.name, i)) x['ins_from_camera'][i] = mrcal.Rt_from_qt( np.array((float(m.group(5)),float(m.group(6)),float(m.group(7)),float(m.group(8)), float(m.group(2)),float(m.group(3)),float(m.group(4)), ))) continue raise Exception("'transforms.txt': I only know about 'ins2veh' and 'cam2ins' lines. Got '{}'". format(l)) if not all(e is not None for e in x.values()): raise Exception("Transforms file '{}' incomplete. Missing values for: {}", f.name, [k for k in x.keys() if not x[k]]) if needclose: f.close() return x mrcal-2.4.1/mrcal/calibration.py000066400000000000000000002257731456301662300166010ustar00rootroot00000000000000#!/usr/bin/python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 '''Helper routines for seeding and solving camera calibration problems All functions are exported into the mrcal module. So you can call these via mrcal.calibration.fff() or mrcal.fff(). The latter is preferred. ''' import numpy as np import numpysane as nps import sys import re import mrcal def compute_chessboard_corners(W, H, *, globs_per_camera = ('*',), corners_cache_vnl = None, jobs = 1, exclude_images = set(), weight_column_kind= 'level'): r'''Compute the chessboard observations and returns them in a usable form SYNOPSIS observations, indices_frame_camera, paths = \ mrcal.compute_chessboard_corners(10, 10, globs_per_camera = ('frame*-cam0.jpg','frame*-cam1.jpg'), corners_cache_vnl = "corners.vnl") The input to a calibration problem is a set of images of a calibration object from different angles and positions. This function ingests these images, and outputs the detected chessboard corner coordinates in a form usable by the mrcal optimization routines. The "corners_cache_vnl" argument specifies a file containing cached results of the chessboard detector. If this file already exists, we don't run the detector, but just use the contents of the file. Otherwise, we run the detector, and store the results here. The "corner cache" file is a vnlog 3 or 4 columns. Each row describes a chessboard corner. The first 3 columns are # filename x y If the 4th column is given, it usually is a 'level' or a 'weight'. It encodes the confidence we have in that corner, and the exact interpretation is dependent on the value of the 'weight_column_kind' argument. The output of this function is an array with a weight for each point, so the logic serves to convert the extra column to a weight. if weight_column_kind == 'level': the 4th column is a decimation level of the detected corner. If we needed to cut down the image resolution to detect a corner, its coordinates are known less precisely, and we use that information to weight the errors appropriately later. We set the output weight = 1/2^level. If the 4th column is '-' or <0, the given point was not detected, and should be ignored: we set weight = -1 elif weight_column_kind == 'weight': the 4th column is already represented as a weight, so I just copy it to the output. If the 4th column is '-' or <=0, the given point was not detected, and should be ignored: we set weight = -1 elif weight_column_kind is None: I hard-code the output weight to 1.0. Any data in the extra column is ignored ARGUMENTS - W, H: the width and height of the point grid in the calibration object we're using - globs_per_camera: a list of strings, one per camera, containing globs_per_camera matching the image filenames for that camera. The filenames are expected to encode the instantaneous frame numbers, with identical frame numbers implying synchronized images. A common scheme is to name an image taken by frame C at time T "frameT-camC.jpg". Then images frame10-cam0.jpg and frame10-cam1.jpg are assumed to have been captured at the same moment in time by cameras 0 and 1. With this scheme, if you wanted to calibrate these two cameras together, you'd pass ('frame*-cam0.jpg','frame*-cam1.jpg') in the "globs_per_camera" argument. The "globs_per_camera" argument may be omitted. In this case all images are mapped to the same camera. - corners_cache_vnl: the name of a file to use to read/write the detected corners; or a python file object to read data from. If the given file exists or a python file object is given, we read the detections from it, and do not run the detector. If the given file does NOT exist (which is what happens the first time), mrgingham will be invoked to compute the corners from the images, and the results will be written to that file. So the same function call can be used to both compute the corners initially, and to reuse the pre-computed corners with subsequent calls. This exists to save time where re-analyzing the same data multiple times. - jobs: a GNU-Make style parallelization flag. Indicates how many parallel processes should be invoked when computing the corners. If given, a numerical argument is required. If jobs<0: the corners_cache_vnl MUST already contain valid data; if it doesn't, an exception is thrown instead of the corners being recomputed. - exclude_images: a set of filenames to exclude from reported results - weight_column_kind: an optional argument, defaulting to 'level'. Selects the interpretation of the 4th column describing each corner. Valid options are: - 'level': the 4th column is a decimation level. Level-0 means 'full-resolution', level-1 means 'half-resolution' and so on. I set output weight = 1/2^level. If the 4th column is '-' or <0, the given point was not detected, and should be ignored: we set output weight = -1 - 'weight': the 4th column is already a weight; I copy it to the output. If the 4th column is '-' or <0, the given point was not detected, and should be ignored: we set output weight = -1 - None: the 4th column should be ignored, and I set the output weight to 1.0 RETURNED VALUES This function returns a tuple (observations, indices_frame_camera, files_sorted) - observations: an ordered (N,object_height_n,object_width_n,3) array describing N board observations where the board has dimensions (object_height_n,object_width_n) and each point is an (x,y,weight) pixel observation. A weight<0 means "ignore this point". Incomplete chessboard observations can be specified in this way. - indices_frame_camera is an (N,2) array of contiguous, sorted integers where each observation is (index_frame,index_camera) - files_sorted is a list of paths of images corresponding to the observations Note that this assumes we're solving a calibration problem (stationary cameras) observing a moving object, so this returns indices_frame_camera. It is the caller's job to convert this into indices_frame_camintrinsics_camextrinsics, which mrcal.optimize() expects ''' if not (weight_column_kind == 'level' or weight_column_kind == 'weight' or weight_column_kind is None): raise Exception(f"weight_column_kind must be one of ('level','weight',None); got '{weight_column_kind}'") import os import fnmatch import subprocess import shutil from tempfile import mkstemp import io import copy def get_corner_observations(W, H, globs_per_camera, corners_cache_vnl, exclude_images=set()): r'''Return dot observations, from a cache or from mrgingham Returns a dict mapping from filename to a numpy array with a full grid of dot observations. If no grid was observed in a particular image, the relevant dict entry is empty The corners_cache_vnl argument is for caching corner-finder results. This can be None if we want to ignore this. Otherwise, this is treated as a path to a file on disk or a python file object. If this file exists: The corner coordinates are read from this file instead of being computed. We don't need to actually have the images stored on disk. Any image filenames mentioned in this cache file are matched against the globs_per_camera to decide which camera the image belongs to. If it matches none of the globs_per_camera, that image filename is silently ignored If this file does not exist: We process the images to compute the corner coordinates. Before we compute the calibration off these coordinates, we create the cache file and store this data there. Thus a subsequent identical invocation of mrcal-calibrate-cameras will see this file as existing, and will automatically use the data it contains instead of recomputing the corner coordinates ''' # Expand any ./ and // etc globs_per_camera = [os.path.normpath(g) for g in globs_per_camera] Ncameras = len(globs_per_camera) files_per_camera = [] for i in range(Ncameras): files_per_camera.append([]) # images in corners_cache_vnl have paths relative to where the # corners_cache_vnl lives corners_dir = None fd_already_opened = isinstance(corners_cache_vnl, io.IOBase) if corners_cache_vnl is not None and not fd_already_opened: corners_dir = os.path.dirname( corners_cache_vnl ) pipe_corners_write_fd = None pipe_corners_write_tmpfilename = None if corners_cache_vnl is not None and \ not fd_already_opened and \ os.path.isdir(corners_cache_vnl): raise Exception(f"Given cache path '{corners_cache_vnl}' is a directory. Must be a file or must not exist") if corners_cache_vnl is not None and \ ( fd_already_opened or \ os.path.exists(corners_cache_vnl) ): # Have an existing cache file. Just read it if fd_already_opened: pipe_corners_read = corners_cache_vnl else: pipe_corners_read = open(corners_cache_vnl, 'r', encoding='ascii') corners_output = None else: if jobs < 0: raise Exception("I was asked to use an existing cache file, but it couldn't be read. jobs<0, so I do not recompute") # Need to compute the dot coords. And maybe need to save them into a # cache file too if W != H: if corners_cache_vnl is None: raise Exception(f"No corners cache file given, so we need to run mrgingham to compute them. mrgingham currently accepts ONLY square grids, but we were asked for a {W}x{H} grid") else: raise Exception(f"Requested corners cache file '{corners_cache_vnl}' doesn't exist, so we need to run mrgingham to compute them. mrgingham currently accepts ONLY square grids, but we were asked for a {W}x{H} grid") if weight_column_kind == 'weight': raise Exception("Need to run mrgingham, so I will get a column of decimation levels, but weight_column_kind == 'weight'") args_mrgingham = ['mrgingham', '--jobs', str(jobs), '--gridn', str(W)] args_mrgingham.extend(globs_per_camera) sys.stderr.write("Computing chessboard corners by running:\n {}\n". \ format(' '.join(mrcal.shellquote(s) for s in args_mrgingham))) if corners_cache_vnl is not None: # need to save the corners into a cache. I want to do this # atomically: if the dot-finding is interrupted I don't want to # be writing incomplete results, so I write to a temporary file # and then rename when done pipe_corners_write_fd,pipe_corners_write_tmpfilename = mkstemp('.vnl') sys.stderr.write(f"Will save corners to '{corners_cache_vnl}'\n") corners_output = subprocess.Popen(args_mrgingham, stdout=subprocess.PIPE, stderr=subprocess.PIPE, encoding='ascii') pipe_corners_read = corners_output.stdout mapping = {} context0 = dict(f = '', igrid = 0, Nvalidpoints = 0) # Init the array to -1.0: everything is invalid context0['grid'] = -np.ones( (H*W,3), dtype=float) context = copy.deepcopy(context0) # relative-path globs_per_camera: add explicit "*/" to the start globs_per_camera = [g if g[0]=='/' else '*/'+g for g in globs_per_camera] def finish_chessboard_observation(): nonlocal context def accum_files(f): for icam in range(Ncameras): if fnmatch.fnmatch(os.path.abspath(f), globs_per_camera[icam]): files_per_camera[icam].append(f) return True return False if context['igrid'] > 1: if W*H != context['igrid']: raise Exception("File '{}' expected to have {} points, but got {}". \ format(context['f'], W*H, context['igrid'])) if context['f'] not in exclude_images and \ context['Nvalidpoints'] > 3: # There is a bit of ambiguity here. The image path stored in # the 'corners_cache_vnl' file is relative to what? It could be # relative to the directory the corners_cache_vnl lives in, or it # could be relative to the current directory. The image # doesn't necessarily need to exist. I implement a few # heuristics to figure this out if corners_dir is None or \ context['f'][0] == '/' or \ os.path.exists(context['f']): filename_canonical = os.path.normpath(context['f']) else: filename_canonical = os.path.join(corners_dir, context['f']) if accum_files(filename_canonical): mapping[filename_canonical] = context['grid'].reshape(H,W,3) context = copy.deepcopy(context0) for line in pipe_corners_read: if pipe_corners_write_fd is not None: os.write(pipe_corners_write_fd, line.encode()) if re.match(r'\s*#', line): continue m = re.match(r'\s*(\S+)\s+(.*?)$', line) if m is None: raise Exception(f"Unexpected line in the corners output: '{line}'") if context['f'] != m.group(1): # Got data for the next image. Finish out this one finish_chessboard_observation() context['f'] = m.group(1) # The row may have 2 or 3 values: if 3, it contains a decimation # level of the corner observation (used for the weight). If 2, a # weight of 1.0 is assumed. The weight array is pre-filled with 1.0. # A decimation level of - will be used to set weight <0 which means # "ignore this point" fields = m.group(2).split() if not (len(fields) == 2 or len(fields) == 3): raise Exception(f"'corners.vnl' data rows must contain a filename and 2 or 3 values. Instead got line '{line}'") def parse_point(out, fields): r'''Parse the given split-string fields Write results into out[:]. Return True if the given point is valid. The initial value of out[:] is (-1,-1,-1): "invalid" ''' if fields[0] == '-' or fields[1] == '-': # out[:] already is invalid return False try: out[0] = float(fields[0]) out[1] = float(fields[1]) except: raise Exception(f"'corners.vnl' data rows must lead with 'filename x y' with x and y being numerical or '-'. Instead got line '{line}'") if out[0] < 0 or out[1] < 0: # out[:] already is invalid return False if len(fields) == 2 or weight_column_kind is None: # default weight out[2] = 1.0 return True if fields[2] == '-': # out[:] already is invalid return False try: w = float(fields[2]) except: raise Exception(f"'corners.vnl' data rows expected as 'filename x y {weight_column_kind}' with {weight_column_kind} being numerical or '-'. Instead got line '{line}'") if weight_column_kind == 'weight': if w <= 0.0: # out[:] already is invalid return False out[2] = w else: if w < 0.0: # out[:] already is invalid return False # convert decimation level to weight. The weight is # 2^(-level). I.e. level-0 -> weight=1, level-1 -> # weight=0.5, etc out[2] = 1. / (1 << int(w)) return True if parse_point(context['grid'][context['igrid'],:], fields): context['Nvalidpoints'] += 1 context['igrid'] += 1 finish_chessboard_observation() if corners_output is not None: sys.stderr.write("Done computing chessboard corners\n") if corners_output.wait() != 0: err = corners_output.stderr.read() raise Exception(f"mrgingham failed: {err}") if pipe_corners_write_fd is not None: os.close(pipe_corners_write_fd) shutil.move(pipe_corners_write_tmpfilename, corners_cache_vnl) elif not fd_already_opened: pipe_corners_read.close() # If I have multiple cameras, I use the filenames to figure out what # indexes the frame and what indexes the camera, so I need at least # two images for each camera to figure that out. Example: # # I have two cameras, with one image each: # - frame2-cam0.jpg # - frame3-cam1.jpg # # If this is all I had, it'd be impossible for me to tell whether # the images correspond to the same frame or not. But if cam0 also # had "frame4-cam0.jpg" then I could look at the same-camera cam0 # filenames, find the common prefixes,suffixes, and conclude that # the frame indices are 2 and 4. # # If I only have one camera, however, then the details of the # filenames don't matter, and I just make sure I have at least one # image to look at min_num_images = 2 if len(files_per_camera) > 1 else 1 for icam in range(len(files_per_camera)): N = len(files_per_camera[icam]) if N < min_num_images: raise Exception("Found too few ({}; need at least {}) images containing a calibration pattern in camera {}; glob '{}'". \ format(N, min_num_images, icam, globs_per_camera[icam])) return mapping,files_per_camera indices_frame_camera = np.array((), dtype=np.int32) observations = np.array((), dtype=float) # basic logic is this: # for frames: # for cameras: # if have observation: # push observations # push indices_frame_camera mapping_file_corners,files_per_camera = get_corner_observations(W, H, globs_per_camera, corners_cache_vnl, exclude_images) file_framenocameraindex = mrcal.mapping_file_framenocameraindex(*files_per_camera) # I create a file list sorted by frame and then camera. So my for(frames) # {for(cameras) {}} loop will just end up looking at these files in order files_sorted = sorted(mapping_file_corners.keys(), key=lambda f: file_framenocameraindex[f][1]) files_sorted = sorted(files_sorted, key=lambda f: file_framenocameraindex[f][0]) i_observation = 0 iframe_last = None index_frame = -1 for f in files_sorted: # The frame indices I return are consecutive starting from 0, NOT the # original frame numbers iframe,icam = file_framenocameraindex[f] if iframe_last == None or iframe_last != iframe: index_frame += 1 iframe_last = iframe indices_frame_camera = nps.glue(indices_frame_camera, np.array((index_frame, icam), dtype=np.int32), axis=-2) observations = nps.glue(observations, mapping_file_corners[f], axis=-4) return observations, indices_frame_camera, files_sorted def _estimate_camera_pose_from_fixed_point_observations(lensmodel, intrinsics_data, observation_qxqyw, points_ref, what): r'''Wrapper around solvePnP that tries out different focal lengths This is an ugly hack. The opencv solvePnP() function I'm using here assumes a pinhole model. But this function accepts stereographic data, so observations could be really wide; behind the camera even. I can't do much behind the camera, but I can accept wide observations by using a much smaller pinhole focal length than the stereographic one the user passed. This really shouldn't be hard-coded, and I should only adjust if observations would be thrown away. And REALLY I should be using a flavor of solvePnP that uses observation vectors instead of pinhole pixel observations. Like opengv ''' import cv2 class SolvePnPerror_negz(Exception): def __init__(self, err): self.err = err def __str__(self): return self.err class SolvePnPerror_toofew(Exception): def __init__(self, err): self.err = err def __str__(self): return self.err def solvepnp__try_focal_scale(scale): fx,fy,cx,cy = intrinsics_data[:4] fxy = intrinsics_data[0:2] cxy = intrinsics_data[2:4] camera_matrix = \ np.array(((fx*scale, 0, cx), ( 0, fy*scale, cy), ( 0, 0, 1)), dtype=float) v = mrcal.unproject((observation_qxqyw[..., :2] - cxy) / scale + cxy, lensmodel, intrinsics_data) observation_qxqy_pinhole = \ mrcal.project(v, 'LENSMODEL_PINHOLE', intrinsics_data[:4]) # observation_qxqy_pinhole = (observation_qxqy_pinhole - cxy)*scale + cxy observation_qxqy_pinhole *= scale observation_qxqy_pinhole += cxy*(1. - scale) # I pick off those rows where the point observation is valid i = \ (observation_qxqyw[..., 2] > 0.0) * \ (np.isfinite(v [..., 0])) * \ (np.isfinite(v [..., 1])) * \ (np.isfinite(v [..., 2])) * \ (np.isfinite(observation_qxqy_pinhole[..., 0])) * \ (np.isfinite(observation_qxqy_pinhole[..., 1])) if np.count_nonzero(i) < 4: raise SolvePnPerror_toofew(f"Insufficient observations; need at least 4; got {np.count_nonzero(i)} instead. Cannot estimate initial extrinsics for {what}") observations_local = observation_qxqy_pinhole[i] ref_object = points_ref[i] result,rvec,tvec = cv2.solvePnP(ref_object, observations_local, camera_matrix, None) if not result: raise Exception(f"solvePnP() failed! Cannot estimate initial extrinsics for {what}") if tvec[2] <= 0: # The object ended up behind the camera. I flip it, and try to solve # again result,rvec,tvec = cv2.solvePnP(np.array(ref_object), np.array(observations_local), camera_matrix, None, rvec, -tvec, useExtrinsicGuess = True) if not result: raise Exception(f"Retried solvePnP() failed! Cannot estimate initial extrinsics for {what}") if tvec[2] <= 0: raise SolvePnPerror_negz(f"Retried solvePnP() insists that tvec.z <= 0 (i.e. the chessboard is behind us). Cannot estimate initial extrinsics for {what}") Rt_cam_points = mrcal.Rt_from_rt(nps.glue(rvec.ravel(), tvec.ravel(), axis=-1)) # visualize the fit # x_cam = nps.matmult(Rt_cam_points[:3,:],ref_object)[..., 0] + Rt_cam_points[3,:] # x_imager = x_cam[...,:2]/x_cam[...,(2,)] * focal + (imagersize-1)/2 # import gnuplotlib as gp # gp.plot( (x_imager[:,0],x_imager[:,1], dict(legend='solved')), # (observations_local[:,0,0],observations_local[:,1,0], dict(legend='observed')), # square=1,xrange=(0,4000),yrange=(4000,0), # wait=1) # import IPython # IPython.embed() # sys.exit() return Rt_cam_points # if z<0, try again with bigger f # if too few points: try again with smaller f try: return solvepnp__try_focal_scale(1.) except SolvePnPerror_negz as e: return solvepnp__try_focal_scale(1.5) except SolvePnPerror_toofew as e: return solvepnp__try_focal_scale(0.7) # unreachable raise Exception("This should be unreachable. This is a bug") def estimate_monocular_calobject_poses_Rt_tocam( indices_frame_camera, observations, object_spacing, models_or_intrinsics): r"""Estimate camera-referenced poses of the calibration object from monocular views SYNOPSIS print( indices_frame_camera.shape ) ===> (123, 2) print( observations.shape ) ===> (123, 3) models = [mrcal.cameramodel(f) for f in ("cam0.cameramodel", "cam1.cameramodel")] # Estimated poses of the calibration object from monocular observations Rt_camera_frame = \ mrcal.estimate_monocular_calobject_poses_Rt_tocam( indices_frame_camera, observations, object_spacing, models) print( Rt_camera_frame.shape ) ===> (123, 4, 3) i_observation = 10 icam = indices_frame_camera[i_observation,1] # The calibration object in its reference coordinate system calobject = mrcal.ref_calibration_object(object_width_n, object_height_n, object_spacing) # The estimated calibration object points in the observing camera coordinate # system pcam = mrcal.transform_point_Rt( Rt_camera_frame[i_observation], calobject ) # The pixel observations we would see if the calibration object pose was # where it was estimated to be q = mrcal.project(pcam, *models[icam].intrinsics()) # The reprojection error, comparing these hypothesis pixel observations from # what we actually observed. We estimated the calibration object pose from # the observations, so this should be small err = q - observations[i_observation][:2] print( np.linalg.norm(err) ) ===> [something small] mrcal solves camera calibration problems by iteratively optimizing a nonlinear least squares problem to bring the pixel observation predictions in line with actual pixel observations. This requires an initial "seed", an estimate of the solution. This function is a part of that computation. Since this is just an initial estimate that will be refined, the results of this function do not need to be exact. We have pixel observations of a known calibration object, and we want to estimate the pose of this object in the coordinate system of the camera that produced these observations. This function ingests a number of such observations, and solves this "PnP problem" separately for each one. The observations may come from any lens model; everything is reprojected to a pinhole model first to work with OpenCV. This function is a wrapper around the solvePnP() openCV call, which does all the work. ARGUMENTS - indices_frame_camera: an array of shape (Nobservations,2) and dtype numpy.int32. Each row (iframe,icam) represents an observation of a calibration object by camera icam. iframe is not used by this function - observations: an array of shape (Nobservations,object_height_n,object_width_n,3). Each observation corresponds to a row in indices_frame_camera, and contains a row of shape (3,) for each point in the calibration object. Each row is (x,y,weight) where x,y are the observed pixel coordinates. Any point where x<0 or y<0 or weight<0 is ignored. This is the only use of the weight in this function. - object_spacing: the distance between adjacent points in the calibration object. A square object is assumed, so the vertical and horizontal distances are assumed to be identical. Usually we need the object dimensions in the object_height_n,object_width_n arguments, but here we get those from the shape of the observations array - models_or_intrinsics: either - a list of mrcal.cameramodel objects from which we use the intrinsics - a list of (lensmodel,intrinsics_data) tuples These are indexed by icam from indices_frame_camera RETURNED VALUE An array of shape (Nobservations,4,3). Each slice is an Rt transformation TO the camera coordinate system FROM the calibration object coordinate system. """ # I'm given models. I remove the distortion so that I can pass the data # on to solvePnP() Ncameras = len(models_or_intrinsics) lensmodels_intrinsics_data = [ m.intrinsics() if isinstance(m,mrcal.cameramodel) else m for m in models_or_intrinsics ] lensmodels = [di[0] for di in lensmodels_intrinsics_data] intrinsics_data = np.array([di[1] for di in lensmodels_intrinsics_data]) if not all([mrcal.lensmodel_metadata_and_config(m)['has_core'] for m in lensmodels]): raise Exception("this currently works only with models that have an fxfycxcy core. It might not be required. Take a look at the following code if you want to add support") # We're looking at chessboards. indices_frame_camera is # indices_frame_camintrinsics_camextrinsics[:,:2] object_height_n,object_width_n = observations.shape[-3:-1] # No calobject_warp. Good-enough for the seeding # shape (Npoints,3) points_ref = \ nps.clump(mrcal.ref_calibration_object(object_width_n, object_height_n, object_spacing), n = 2) # observations has shape (Nobservations,Nh,Nw,3). I reshape it into # shape (Nobservations,Nh*Nw,3) observations = nps.mv(nps.clump(nps.mv(observations, -1,0), n = -2), 0, -1) Nobservations = len(observations) # this wastes memory, but makes it easier to keep track of which data goes # with what Rt_cam_points_all = np.zeros( (Nobservations, 4, 3), dtype=float) for i_observation in range(Nobservations): icam_intrinsics = indices_frame_camera[i_observation,1] kwargs = dict( lensmodel = lensmodels [icam_intrinsics], intrinsics_data = intrinsics_data[icam_intrinsics], observation_qxqyw = observations[i_observation], points_ref = points_ref, what = f"observation {i_observation} (camera {icam_intrinsics})" ) Rt_cam_points = _estimate_camera_pose_from_fixed_point_observations(**kwargs) Rt_cam_points_all[i_observation, :, :] = Rt_cam_points return Rt_cam_points_all def _estimate_camera_pose_from_point_observations( indices_point_camintrinsics_camextrinsics, observations_point, models_or_intrinsics, points, icam_intrinsics): r"""Estimate camera poses from monocular views of fixed points SYNOPSIS # I have a monocular solve observing fixed points optimization_inputs = model.optimization_inputs() lensmodel = optimization_inputs['lensmodel'] intrinsics_data = optimization_inputs['intrinsics'] indices_point_camintrinsics_camextrinsics = optimization_inputs['indices_point_camintrinsics_camextrinsics'] observations_point = optimization_inputs['observations_point'] points = optimization_inputs['points'] icam_intrinsics = 0 Rt_camera_ref_estimate = \ mrcal.calibration._estimate_camera_pose_from_point_observations( \ indices_point_camintrinsics_camextrinsics, observations_point, ( (lensmodel, intrinsics_data[0]), ), points, icam_intrinsics = icam_intrinsics) print( Rt_camera_ref_estimate.shape ) ===> (1, 4, 3) i = indices_point_camintrinsics_camextrinsics[:,1] == icam_intrinsics # The estimated calibration object points in the observing camera coordinate # system pcam = mrcal.transform_point_Rt( Rt_camera_ref_estimate[0], points[i] ) # The pixel observations we would see if the calibration object pose was # where it was estimated to be q = mrcal.project(pcam, lensmodel, intrinsics_data) # The reprojection error, comparing these hypothesis pixel observations from # what we actually observed. We estimated the calibration object pose from # the observations, so this should be small err = q - observations_point[i][...,:2] print( np.linalg.norm(err) ) ===> [something small] mrcal solves camera calibration problems by iteratively optimizing a nonlinear least squares problem to bring the pixel observation predictions in line with actual pixel observations. This requires an initial "seed", an estimate of the solution. This function is a part of that computation. Since this is just an initial estimate that will be refined, the results of this function do not need to be exact. We have pixel observations of a known points in space, and we want to estimate the pose of the camera in the coordinate system of these points. This function ingests a number of point observations, and solves this "PnP problem". The observations may come from any lens model; everything is reprojected to a pinhole model first to work with OpenCV. This function is a wrapper around the solvePnP() openCV call, which does all the work. THIS FUNCTION IS A TEMPORARY PLACEHOLDER, AND IS SUBJECT TO CHANGE. IT CURRENTLY WORKS WITH ONLY ONE PHYSICAL CAMERA AT A TIME, AND THIS CAMERA IS ASSUMED STATIONARY ARGUMENTS - indices_point_camintrinsics_camextrinsics: an array of shape (Npoint_observations,3) and dtype numpy.int32. Each row (ipoint,icam_intrinsics,icam_extrinsics) represents a point observation. This is optimization_inputs['indices_point_camintrinsics_camextrinsics'] - observations_point: an array of shape (Npoint_observations,3). Each observation corresponds to a row in indices_point_camintrinsics_camextrinsics, and contains a row of shape (3,) for each point being observed. Each row is (x,y,weight) where x,y are the observed pixel coordinates. Any point where x<0 or y<0 or weight<0 is ignored. This is the only use of the weight in this function. This is optimization_inputs['observations_point'] - models_or_intrinsics: either - a list of mrcal.cameramodel objects from which we use the intrinsics - a list of (lensmodel,intrinsics_data) tuples These are indexed by indices_point_camintrinsics_camextrinsics[...,1] - points: an array of shape (Npoints,3). This is indexed by indices_point_camintrinsics_camextrinsics[...,0]. This is optimization_inputs['points'] - icam_intrinsics: the integer representing the physical camera being evaluated. This is compared against indices_point_camintrinsics_camextrinsics[...,1] RETURNED VALUE An array of shape (1,4,3). Each slice is an Rt transformation TO the camera coordinate system FROM the points coordinate system. """ Nobservations = len(indices_point_camintrinsics_camextrinsics) indices_point = indices_point_camintrinsics_camextrinsics[:,0] indices_cami = indices_point_camintrinsics_camextrinsics[:,1] indices_came = indices_point_camintrinsics_camextrinsics[:,2] if np.any(indices_came != indices_came[0]): raise Exception("For now this function only works with stationary monocular cameras") i = (indices_cami == icam_intrinsics) if np.count_nonzero(i) < 4: raise Exception(f"Requested icam_intrinsics{icam_intrinsics} matched too few observations: {np.count_nonzero(i)}") # I'm given models. I remove the distortion so that I can pass the data # on to solvePnP() Ncameras = len(models_or_intrinsics) if Ncameras != 1: raise Exception(f"For now this function only works with stationary monocular cameras, but given Ncameras={Ncameras}") lensmodels_intrinsics_data = [ m.intrinsics() if isinstance(m,mrcal.cameramodel) else m for m in models_or_intrinsics ] lensmodels = [di[0] for di in lensmodels_intrinsics_data] intrinsics_data = np.array([di[1] for di in lensmodels_intrinsics_data]) if not all([mrcal.lensmodel_metadata_and_config(m)['has_core'] for m in lensmodels]): raise Exception("this currently works only with models that have an fxfycxcy core. It might not be required. Take a look at the following code if you want to add support") Rt_cam_points_all = np.zeros( (1, 4, 3), dtype=float) kwargs = dict( lensmodel = lensmodels [icam_intrinsics], intrinsics_data = intrinsics_data[icam_intrinsics], observation_qxqyw = observations_point[i], points_ref = points[indices_point[i]], what = f"point observations (camera {icam_intrinsics})" ) Rt_cam_points_all[0,...] = _estimate_camera_pose_from_fixed_point_observations(**kwargs) return Rt_cam_points_all def _estimate_camera_poses( calobject_poses_local_Rt_cf, indices_frame_camera, \ object_width_n, object_height_n, object_spacing): r'''Estimate camera poses in respect to each other We are given poses of the calibration object in respect to each observing camera. We also have multiple cameras observing the same calibration object at the same time, and we have local poses for each. We can thus compute the relative camera pose from these observations. We have many frames that have different observations from the same set of fixed-relative-pose cameras, so we compute the relative camera pose to optimize the observations Note that this assumes we're solving a calibration problem (stationary cameras) observing a moving object, so uses indices_frame_camera, not indices_frame_camintrinsics_camextrinsics, which mrcal.optimize() expects ''' import heapq Ncameras = np.max(indices_frame_camera[:,1]) + 1 # I need to compute an estimate of the pose of each camera in the coordinate # system of camera0. This is only possible if there're enough overlapping # observations. For instance if camera1 has overlapping observations with # camera2, but neight overlap with camera0, then I can't relate camera1,2 to # camera0. However if camera2 has overlap with camera2, then I can compute # the relative pose of camera2 from its overlapping observations with # camera0. And I can compute the camera1-camera2 pose from its overlapping # data, and then transform to the camera0 coord system using the # previously-computed camera2-camera0 pose # # I do this by solving a shortest-path problem using Dijkstra's algorithm to # find a set of pair overlaps between cameras that leads to camera0. I favor # edges with large numbers of shared observed frames # list of camera-i to camera-0 transforms. I keep doing stuff until this # list is full of valid data Rt_0c = [None] * (Ncameras-1) def compute_pairwise_Rt(icam_to, icam_from): # I want to assume that icam_from > icam_to. If it's not true, compute the # opposite transform, and invert if icam_to > icam_from: Rt = compute_pairwise_Rt(icam_from, icam_to) return mrcal.invert_Rt(Rt) if icam_to == icam_from: raise Exception(f"Got icam_to == icam_from ( = {icam_to} ). This was probably a mistake") # Now I KNOW that icam_from > icam_to Nobservations = indices_frame_camera.shape[0] # This is a hack. I look at the correspondence of camera0 to camera i for i # in 1:N-1. I ignore all correspondences between cameras i,j if i!=0 and # j!=0. Good enough for now # No calobject_warp. Good-enough for the seeding ref_object = \ nps.clump(mrcal.ref_calibration_object(object_width_n,object_height_n, object_spacing), n = 2) A = np.array(()) B = np.array(()) # I traverse my observation list, and pick out observations from frames # that had data from both my cameras iframe_last = -1 d0 = None d1 = None Rt_cam0_frame = None Rt_cam1_frame = None for i_observation in range(Nobservations): iframe_this,icam_this = indices_frame_camera[i_observation, ...] if iframe_this != iframe_last: d0 = None d1 = None Rt_cam0_frame = None Rt_cam1_frame = None iframe_last = iframe_this # The cameras appear in order. And above I made sure that icam_from > # icam_to, so I take advantage of that here if icam_this == icam_to: if Rt_cam0_frame is not None: raise Exception(f"Saw multiple camera{icam_this} observations in frame {iframe_this}") Rt_cam0_frame = calobject_poses_local_Rt_cf[i_observation, ...] elif icam_this == icam_from: if Rt_cam0_frame is None: # have camera1 observation, but not camera0 continue if Rt_cam1_frame is not None: raise Exception(f"Saw multiple camera{icam_this} observations in frame {iframe_this}") Rt_cam1_frame = calobject_poses_local_Rt_cf[i_observation, ...] A = nps.glue(A, mrcal.transform_point_Rt(Rt_cam0_frame, ref_object), axis = -2) B = nps.glue(B, mrcal.transform_point_Rt(Rt_cam1_frame, ref_object), axis = -2) return mrcal.align_procrustes_points_Rt01(A, B) def compute_connectivity_matrix(): r'''Returns a connectivity matrix of camera observations Returns a symmetric (Ncamera,Ncamera) matrix of integers, where each entry contains the number of frames containing overlapping observations for that pair of cameras ''' camera_connectivity = np.zeros( (Ncameras,Ncameras), dtype=int ) def finish_frame(i0, i1): for ic0 in range(i0, i1): for ic1 in range(ic0+1, i1+1): camera_connectivity[indices_frame_camera[ic0,1], indices_frame_camera[ic1,1]] += 1 camera_connectivity[indices_frame_camera[ic1,1], indices_frame_camera[ic0,1]] += 1 f_current = -1 i_start_current = -1 for i in range(len(indices_frame_camera)): f,c = indices_frame_camera[i] if f < f_current: raise Exception("I'm assuming the frame indices are increasing monotonically") if f > f_current: # first camera in this observation f_current = f if i_start_current >= 0: finish_frame(i_start_current, i-1) i_start_current = i finish_frame(i_start_current, len(indices_frame_camera)-1) return camera_connectivity shared_frames = compute_connectivity_matrix() class Node: def __init__(self, camera_idx): self.camera_idx = camera_idx self.from_idx = -1 self.cost_to_node = None def __lt__(self, other): return self.cost_to_node < other.cost_to_node def visit(self): '''Dijkstra's algorithm''' self.finish() for neighbor_idx in range(Ncameras): if neighbor_idx == self.camera_idx or \ shared_frames[neighbor_idx,self.camera_idx] == 0: continue neighbor = nodes[neighbor_idx] if neighbor.visited(): continue cost_edge = Node.compute_edge_cost(shared_frames[neighbor_idx,self.camera_idx]) cost_to_neighbor_via_node = self.cost_to_node + cost_edge if not neighbor.seen(): neighbor.cost_to_node = cost_to_neighbor_via_node neighbor.from_idx = self.camera_idx heapq.heappush(heap, neighbor) else: if cost_to_neighbor_via_node < neighbor.cost_to_node: neighbor.cost_to_node = cost_to_neighbor_via_node neighbor.from_idx = self.camera_idx heapq.heapify(heap) # is this the most efficient "update" call? def finish(self): '''A shortest path was found''' if self.camera_idx == 0: # This is the reference camera. Nothing to do return Rt_fc = compute_pairwise_Rt(self.from_idx, self.camera_idx) if self.from_idx == 0: Rt_0c[self.camera_idx-1] = Rt_fc return Rt_0f = Rt_0c[self.from_idx-1] Rt_0c[self.camera_idx-1] = mrcal.compose_Rt( Rt_0f, Rt_fc) def visited(self): '''Returns True if this node went through the heap and has then been visited''' return self.camera_idx == 0 or Rt_0c[self.camera_idx-1] is not None def seen(self): '''Returns True if this node has been in the heap''' return self.cost_to_node is not None @staticmethod def compute_edge_cost(shared_frames): # I want to MINIMIZE cost, so I MAXIMIZE the shared frames count and # MINIMIZE the hop count. Furthermore, I really want to minimize the # number of hops, so that's worth many shared frames. cost = 100000 - shared_frames assert(cost > 0) # dijkstra's algorithm requires this to be true return cost nodes = [Node(i) for i in range(Ncameras)] nodes[0].cost_to_node = 0 heap = [] nodes[0].visit() while heap: node_top = heapq.heappop(heap) node_top.visit() if any([x is None for x in Rt_0c]): raise Exception("ERROR: Don't have complete camera observations overlap!\n" + f"Past-camera-0 Rt:\n{Rt_0c}\n" + f"Shared observations matrix:\n{shared_frames}\n") return np.ascontiguousarray(nps.cat(*Rt_0c)) def estimate_joint_frame_poses(calobject_Rt_camera_frame, extrinsics_Rt_fromref, indices_frame_camera, object_width_n, object_height_n, object_spacing): r'''Estimate world-referenced poses of the calibration object SYNOPSIS print( calobject_Rt_camera_frame.shape ) ===> (123, 4,3) print( extrinsics_Rt_fromref.shape ) ===> (2, 4,3) # We have 3 cameras. The first one is at the reference coordinate system, # the pose estimates of the other two are in this array print( indices_frame_camera.shape ) ===> (123, 2) frames_rt_toref = \ mrcal.estimate_joint_frame_poses(calobject_Rt_camera_frame, extrinsics_Rt_fromref, indices_frame_camera, object_width_n, object_height_n, object_spacing) print( frames_rt_toref.shape ) ===> (87, 6) # We have 123 observations of the calibration object by ANY camera. 87 # instances of time when the object was observed. Most of the time it was # observed by multiple cameras simultaneously, hence 123 > 87 i_observation = 10 iframe,icam = indices_frame_camera[i_observation, :] # The calibration object in its reference coordinate system calobject = mrcal.ref_calibration_object(object_width_n, object_height_n, object_spacing) # The estimated calibration object points in the reference coordinate # system, for this one observation pref = mrcal.transform_point_rt( frames_rt_toref[iframe], calobject ) # The estimated calibration object points in the camera coord system. Camera # 0 is at the reference if icam >= 1: pcam = mrcal.transform_point_Rt( extrinsics_Rt_fromref[icam-1], pref ) else: pcam = pref # The pixel observations we would see if the pose estimates were correct q = mrcal.project(pcam, *models[icam].intrinsics()) # The reprojection error, comparing these hypothesis pixel observations from # what we actually observed. This should be small err = q - observations[i_observation][:2] print( np.linalg.norm(err) ) ===> [something small] mrcal solves camera calibration problems by iteratively optimizing a nonlinear least squares problem to bring the pixel observation predictions in line with actual pixel observations. This requires an initial "seed", an initial estimate of the solution. This function is a part of that computation. Since this is just an initial estimate that will be refined, the results of this function do not need to be exact. This function ingests an estimate of the camera poses in respect to each other, and the estimate of the calibration objects in respect to the observing camera. Most of the time we have simultaneous calibration object observations from multiple cameras, so this function consolidates all this information to produce poses of the calibration object in the reference coordinate system, NOT the observing-camera coordinate system poses we already have. By convention, we have a "reference" coordinate system that ties the poses of all the frames (calibration objects) and the cameras together. And by convention, this "reference" coordinate system is the coordinate system of camera 0. Thus the array of camera poses extrinsics_Rt_fromref holds Ncameras-1 transformations: the first camera has an identity transformation, by definition. This function assumes we're observing a moving object from stationary cameras (i.e. a vanilla camera calibration problem). The mrcal solver is more general, and supports moving cameras, hence it uses a more general indices_frame_camintrinsics_camextrinsics array instead of the indices_frame_camera array used here. ARGUMENTS - calobject_Rt_camera_frame: an array of shape (Nobservations,4,3). Each slice is an Rt transformation TO the observing camera coordinate system FROM the calibration object coordinate system. This is returned by estimate_monocular_calobject_poses_Rt_tocam() - extrinsics_Rt_fromref: an array of shape (Ncameras-1,4,3). Each slice is an Rt transformation TO the camera coordinate system FROM the reference coordinate system. By convention camera 0 defines the reference coordinate system, so that camera's extrinsics are the identity, by definition, and we don't store that data in this array - indices_frame_camera: an array of shape (Nobservations,2) and dtype numpy.int32. Each row (iframe,icam) represents an observation at time instant iframe of a calibration object by camera icam - object_width_n: number of horizontal points in the calibration object grid - object_height_n: number of vertical points in the calibration object grid - object_spacing: the distance between adjacent points in the calibration object. A square object is assumed, so the vertical and horizontal distances are assumed to be identical RETURNED VALUE An array of shape (Nframes,6). Each slice represents the pose of the calibration object at one instant in time: an rt transformation TO the reference coordinate system FROM the calibration object coordinate system. ''' Rt_ref_cam = mrcal.invert_Rt( extrinsics_Rt_fromref ) def Rt_ref_frame(i_observation0, i_observation1): R'''Given a range of observations corresponding to the same frame, estimate the pose of that frame ''' def Rt_ref_frame__single_observation(i_observation): r'''Transform from the board coords to the reference coords''' iframe,icam = indices_frame_camera[i_observation, ...] Rt_cam_frame = calobject_Rt_camera_frame[i_observation, :,:] if icam == 0: return Rt_cam_frame return mrcal.compose_Rt( Rt_ref_cam[icam-1, ...], Rt_cam_frame) # frame poses should map FROM the frame coord system TO the ref coord # system (camera 0). # special case: if there's a single observation, I just use it if i_observation1 - i_observation0 == 1: return Rt_ref_frame__single_observation(i_observation0) # Multiple cameras have observed the object for this frame. I have an # estimate of these for each camera. I merge them in a lame way: I # average out the positions of each point, and fit the calibration # object into the mean point cloud # # No calobject_warp. Good-enough for the seeding obj = mrcal.ref_calibration_object(object_width_n, object_height_n, object_spacing) sum_obj_unproj = obj*0 for i_observation in range(i_observation0, i_observation1): Rt = Rt_ref_frame__single_observation(i_observation) sum_obj_unproj += mrcal.transform_point_Rt(Rt, obj) mean_obj_ref = sum_obj_unproj / (i_observation1 - i_observation0) # Got my point cloud. fit # transform both to shape = (N*N, 3) obj = nps.clump(obj, n=2) mean_obj_ref = nps.clump(mean_obj_ref, n=2) return mrcal.align_procrustes_points_Rt01( mean_obj_ref, obj ) frames_rt_toref = np.array(()) iframe_current = -1 i_observation_framestart = -1; for i_observation in range(indices_frame_camera.shape[0]): iframe,icam = indices_frame_camera[i_observation, ...] if iframe != iframe_current: if i_observation_framestart >= 0: Rt = Rt_ref_frame(i_observation_framestart, i_observation) frames_rt_toref = nps.glue(frames_rt_toref, mrcal.rt_from_Rt(Rt), axis=-2) i_observation_framestart = i_observation iframe_current = iframe if i_observation_framestart >= 0: Rt = Rt_ref_frame(i_observation_framestart, indices_frame_camera.shape[0]) frames_rt_toref = nps.glue(frames_rt_toref, mrcal.rt_from_Rt(Rt), axis=-2) return frames_rt_toref def seed_stereographic( imagersizes, focal_estimate, indices_frame_camera, observations, object_spacing): r'''Compute an optimization seed for a camera calibration SYNOPSIS print( imagersizes.shape ) ===> (4, 2) print( indices_frame_camera.shape ) ===> (123, 2) print( observations.shape ) ===> (123, 3) intrinsics_data, \ extrinsics_rt_fromref, \ frames_rt_toref = \ mrcal.seed_stereographic(imagersizes = imagersizes, focal_estimate = 1500, indices_frame_camera = indices_frame_camera, observations = observations, object_spacing = object_spacing) .... mrcal.optimize(intrinsics = intrinsics_data, extrinsics_rt_fromref = extrinsics_rt_fromref, frames_rt_toref = frames_rt_toref, lensmodel = 'LENSMODEL_STEREOGRAPHIC', ...) mrcal solves camera calibration problems by iteratively optimizing a nonlinear least squares problem to bring the pixel observation predictions in line with actual pixel observations. This requires an initial "seed", an initial estimate of the solution. This function computes a usable seed, and its results can be fed to mrcal.optimize(). The output of this function is just an initial estimate that will be refined, so the results of this function do not need to be exact. This function assumes we have stereographic lenses, and the returned intrinsics apply to LENSMODEL_STEREOGRAPHIC. This is usually good-enough to serve as a seed for both long lenses and wide lenses, every ultra-wide fisheyes. The returned intrinsics can be expanded to whatever lens model we actually want to use prior to invoking the optimizer. By convention, we have a "reference" coordinate system that ties the poses of all the frames (calibration objects) and the cameras together. And by convention, this "reference" coordinate system is the coordinate system of camera 0. Thus the array of camera poses extrinsics_rt_fromref holds Ncameras-1 transformations: the first camera has an identity transformation, by definition. This function assumes we're observing a moving object from stationary cameras (i.e. a vanilla camera calibration problem). The mrcal solver is more general, and supports moving cameras, hence it uses a more general indices_frame_camintrinsics_camextrinsics array instead of the indices_frame_camera array used here. See test/test-basic-calibration.py and mrcal-calibrate-cameras for usage examples. ARGUMENTS - imagersizes: an iterable of (imager_width,imager_height) iterables. Defines the imager dimensions for each camera we're calibrating. May be an array of shape (Ncameras,2) or a tuple of tuples or a mix of the two - focal_estimate: an initial estimate of the focal length of the cameras, in pixels. For the purposes of the initial estimate we assume the same focal length value for both the x and y focal length. This argument can be - a scalar: this is applied to all the cameras - an iterable of length 1: this value is applied to all the cameras - an iterable of length Ncameras: each camera uses a different value - indices_frame_camera: an array of shape (Nobservations,2) and dtype numpy.int32. Each row (iframe,icam) represents an observation of a calibration object by camera icam. iframe is not used by this function - observations: an array of shape (Nobservations,object_height_n,object_width_n,3). Each observation corresponds to a row in indices_frame_camera, and contains a row of shape (3,) for each point in the calibration object. Each row is (x,y,weight) where x,y are the observed pixel coordinates. Any point where x<0 or y<0 or weight<0 is ignored. This is the only use of the weight in this function. - object_spacing: the distance between adjacent points in the calibration object. A square object is assumed, so the vertical and horizontal distances are assumed to be identical. Usually we need the object dimensions in the object_height_n,object_width_n arguments, but here we get those from the shape of the observations array RETURNED VALUES We return a tuple: - intrinsics_data: an array of shape (Ncameras,4). Each slice contains the stereographic intrinsics for the given camera. These intrinsics are (focal_x,focal_y,centerpixel_x,centerpixel_y), and define LENSMODEL_STEREOGRAPHIC model. mrcal refers to these 4 values as the "intrinsics core". For models that have such a core (currently, ALL supported models), the core is the first 4 parameters of the intrinsics vector. So to calibrate some cameras, call seed_stereographic(), append to intrinsics_data the proper number of parameters to match whatever lens model we're using, and then invoke the optimizer. - extrinsics_rt_fromref: an array of shape (Ncameras-1,6). Each slice is an rt transformation TO the camera coordinate system FROM the reference coordinate system. By convention camera 0 defines the reference coordinate system, so that camera's extrinsics are the identity, by definition, and we don't store that data in this array - frames_rt_toref: an array of shape (Nframes,6). Each slice represents the pose of the calibration object at one instant in time: an rt transformation TO the reference coordinate system FROM the calibration object coordinate system. ''' Ncameras = len(imagersizes) try: Nfocal = len(focal_estimate) except: # scalar Nfocal = 1 focal_estimate = (focal_estimate,) if Nfocal == 1: focal_estimate = focal_estimate * Ncameras elif Nfocal == Ncameras: # already good pass else: raise Exception(f"Ncameras mismatch: len(imagersizes) = {Ncameras} but len(focal_estimate) = {len(focal_estimate)}") # Done. focal_estimate is now an iterable length Ncameras # I compute an estimate of the poses of the calibration object in the local # coord system of each camera for each frame. This is done for each frame # and for each camera separately. This isn't meant to be precise, and is # only used for seeding. # # I get rotation, translation in a (4,3) array, such that R*calobject + t # produces the calibration object points in the coord system of the camera. # The result has dimensions (N,4,3) intrinsics = [('LENSMODEL_STEREOGRAPHIC', np.array((focal_estimate[icam], focal_estimate[icam], (imagersizes[icam][0]-1.)/2, (imagersizes[icam][1]-1.)/2,))) \ for icam in range(Ncameras)] calobject_poses_local_Rt_cf = \ mrcal.estimate_monocular_calobject_poses_Rt_tocam( indices_frame_camera, observations, object_spacing, intrinsics) # these map FROM the coord system of the calibration object TO the coord # system of this camera object_height_n,object_width_n = observations.shape[-3:-1] # I now have a rough estimate of calobject poses in the coord system of each # camera. One can think of these as two sets of point clouds, each attached # to their camera. I can move around the two sets of point clouds to try to # match them up, and this will give me an estimate of the relative pose of # the two cameras in respect to each other. I need to set up the # correspondences, and mrcal.align_procrustes_points_Rt01() does the rest # # I get transformations that map points in camera-cami coord system to 0th # camera coord system. Rt have dimensions (N-1,4,3) camera_poses_Rt_0_cami = \ _estimate_camera_poses( calobject_poses_local_Rt_cf, indices_frame_camera, object_width_n, object_height_n, object_spacing) if len(camera_poses_Rt_0_cami): # extrinsics should map FROM the ref coord system TO the coord system of the # camera in question. This is backwards from what I have extrinsics_Rt_fromref = \ nps.atleast_dims( mrcal.invert_Rt(camera_poses_Rt_0_cami), -3 ) else: extrinsics_Rt_fromref = np.zeros((0,4,3)) frames_rt_toref = \ mrcal.estimate_joint_frame_poses( calobject_poses_local_Rt_cf, extrinsics_Rt_fromref, indices_frame_camera, object_width_n, object_height_n, object_spacing) return \ nps.cat(*[i[1] for i in intrinsics]), \ nps.atleast_dims(mrcal.rt_from_Rt(extrinsics_Rt_fromref), -2), \ frames_rt_toref def _compute_valid_intrinsics_region(model, threshold_uncertainty, threshold_mean, threshold_stdev, threshold_count, distance, gridn_width = 30, gridn_height = None): r'''Returns the valid-intrinsics region for the camera in the model Internal function use by the mrcal-calibrate-cameras utility. The model is expected to contain the optimization_inputs, which are used for all the work. The thresholds come from the --valid-intrinsics-region-parameters argument to mrcal-calibrate-cameras This is a closed contour, in an (N,2) numpy array. None means "no valid-intrinsics region computed". An empty array of shape (0,2) means "the region was computed and it is empty" The imager of a camera is subdivided into regions (controlled by the gridn_width, gridn_height arguments). The residual statistics are then computed for each bin separately. We can then clearly see areas of insufficient data (observation counts will be low). And we can clearly see lens-model-induced biases (non-zero mean) and we can see heteroscedasticity (uneven standard deviation). The mrcal-calibrate-cameras tool uses these metrics to construct a valid-intrinsics region for the models it computes. This serves as a quick/dirty method of modeling projection reliability, which can be used even if projection uncertainty cannot be computed. ''' import cv2 W,H = model.imagersize() if gridn_height is None: gridn_height = int(round(H/W*gridn_width)) # Each has shape (Nheight,Nwidth) mean,stdev,count,using = \ _report_regional_statistics(model, gridn_width = gridn_width, gridn_height = gridn_height) q = mrcal.sample_imager( gridn_width, gridn_height, *model.imagersize() ) vcam = mrcal.unproject(q, *model.intrinsics(), normalize = True) if distance <= 0: atinfinity = True pcam = vcam else: atinfinity = False pcam = vcam * distance uncertainty = mrcal.projection_uncertainty(pcam, model = model, atinfinity = atinfinity, what = 'worstdirection-stdev' ) # Uncertainty of nan or inf is invalid, so I mark it as very high. This # serves to silence a warning in the next statement where we're comparing # something with nan uncertainty.ravel() [~np.isfinite(uncertainty.ravel())] = 1e9 # shape (Nheight,Nwidth). mask = \ (uncertainty < threshold_uncertainty) if not re.match('LENSMODEL_SPLINED_', model.intrinsics()[0]): mask *= \ (mean < threshold_mean) * \ (stdev < threshold_stdev) * \ (count > threshold_count) # I compute the contour. OpenCV can't process binary images, so I need # to convert to a different image type first. AND findContours() reports # the coordinates in the opposite order as how they're given (image is # given as y,x; returned coords are x,y). This is what I want, but feels # conterintuitive # This is a hoaky mess. I ignore all the topological corner cases, and just # grab the contour with the biggest area contours = \ cv2.findContours(mask.astype(np.uint8), cv2.RETR_EXTERNAL, cv2.CHAIN_APPROX_SIMPLE)[-2] areas = np.array([ cv2.contourArea(c) for c in contours ]) if areas.size == 0: return np.zeros((0,2)) # empty valid-intrinsics region contour = contours[np.argmax(areas)][:,0,:].astype(float) contour = mrcal.close_contour(contour) if contour.ndim != 2 or contour.shape[0] < 4: # I have a closed contour, so the only way for it to not be # degenerate is to include at least 4 points return np.zeros((0,2)) # empty valid-intrinsics region # I convert the contours back to the full-res image coordinate. The grid # mapping is based on the corner pixels W,H = model.imagersize() contour[:,0] *= float(W-1)/(gridn_width -1) contour[:,1] *= float(H-1)/(gridn_height-1) return contour.round().astype(np.int32) def _report_regional_statistics( model, gridn_width = 20, gridn_height = None): r'''Reports fit statistics for regions across the imager SYNOPSIS mean, stdev, count, using = \ mrcal._report_regional_statistics(model, gridn_width = 30) import gnuplotlib as gp W,H = imagersize gp.plot( np.abs(mean), tuplesize = 3, _with = 'image', ascii = True, square = True, using = using) This is an internal function used by mrcal._compute_valid_intrinsics_region() and mrcal.show_residuals_regional(). The mrcal solver optimizes reprojection errors for ALL the observations in ALL cameras at the same time. It is useful to evaluate the optimal solution by examining reprojection errors in subregions of the imager, which is accomplished by this function. All the observations and reprojection errors and subregion gridding are given. The mean and standard derivation of the reprojection errors and a point count are returned for each subregion cell. A "using" expression for plotting is reported as well. After a problem-free solve, the error distributions in each area of the imager should be similar, and should match the error distribution of the pixel observations. If the lens model doesn't fit the data, the statistics will not be consistent across the region: the residuals would be heteroscedastic. The imager of a camera is subdivided into regions (controlled by the gridn_width, gridn_height arguments). The residual statistics are then computed for each bin separately. We can then clearly see areas of insufficient data (observation counts will be low). And we can clearly see lens-model-induced biases (non-zero mean) and we can see heteroscedasticity (uneven standard deviation). The mrcal-calibrate-cameras tool uses these metrics to construct a valid-intrinsics region for the models it computes. This serves as a quick/dirty method of modeling projection reliability, which can be used even if projection uncertainty cannot be computed. ARGUMENTS - model: the model of the camera we're looking at. This model must contain the optimization_inputs. - gridn_width: how many points along the horizontal gridding dimension - gridn_height: how many points along the vertical gridding dimension. If None, we compute an integer gridn_height to maintain a square-ish grid: gridn_height/gridn_width ~ imager_height/imager_width RETURNED VALUES This function returns a tuple - mean: an array of shape (gridn_height,gridn_width). Contains the mean of the residuals in the corresponding cell - stdev: an array of shape (gridn_height,gridn_width). Contains the standard deviation of the residuals in the corresponding cell - count: an array of shape (gridn_height,gridn_width). Contains the count of observations in the corresponding cell - using: is a "using" keyword for plotting the output matrices with gnuplotlib. See the docstring for imagergrid_using() for details ''' W,H=model.imagersize() if gridn_height is None: gridn_height = int(round(H/W*gridn_width)) # shape: (Nheight,Nwidth,2). Contains (x,y) rows q_cell_center = mrcal.sample_imager(gridn_width, gridn_height, W, H) wcell = float(W-1) / (gridn_width -1) hcell = float(H-1) / (gridn_height-1) rcell = np.array((wcell,hcell), dtype=float) / 2. @nps.broadcast_define( (('N',2), ('N',2), (2,)), (3,) ) def stats(q, err, q_cell_center): r'''Compute the residual statistics in a single cell ''' # boolean (x,y separately) map of observations that are within a cell idx = np.abs(q - q_cell_center) < rcell # join x,y: both the x,y must be within a cell for the observation to be # within a cell idx = idx[:,0] * idx[:,1] err = err[idx, ...].ravel() if len(err) <= 5: # we have too little data in this cell return np.array((0.,0.,len(err))) mean = np.mean(err) stdev = np.std(err) return np.array((mean,stdev,len(err))) optimization_inputs = model.optimization_inputs() icam = model.icam_intrinsics() # shape (Nobservations, object_height_n, object_width_n, 3) observations = optimization_inputs['observations_board'] indices_frame_camera = optimization_inputs['indices_frame_camintrinsics_camextrinsics'][...,:2] residuals_shape = observations.shape[:-1] + (2,) # shape (Nobservations,object_height_n,object_width_n,2) residuals = \ mrcal.optimizer_callback(**optimization_inputs, no_jacobian = True, no_factorization = True)[1][:np.product(residuals_shape)]. \ reshape(*residuals_shape) # shape (Nobservations, object_height_n, object_width_n) idx = np.ones( observations.shape[:-1], dtype=bool) # select residuals from THIS camera idx[indices_frame_camera[:,1] != icam, ...] = False # select non-outliers idx[ observations[...,2] <= 0.0 ] = False # shape (N,2) err = residuals [idx, ... ] obs = observations[idx, ..., :2] # Each has shape (Nheight,Nwidth) mean,stdev,count = nps.mv( stats(obs, err, q_cell_center), -1, 0) return \ mean, \ stdev, \ count, \ mrcal.imagergrid_using(model.imagersize(), gridn_width, gridn_height) mrcal-2.4.1/mrcal/cameramodel.py000066400000000000000000002062521456301662300165520ustar00rootroot00000000000000#!/usr/bin/python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 '''A class to read/write/manipulate camera models SYNOPSIS model_for_intrinsics = mrcal.cameramodel('model0.cameramodel') model_for_extrinsics = mrcal.cameramodel('model1.cameramodel') model_joint = mrcal.cameramodel( model_for_intrinsics ) extrinsics = model_for_extrinsics.extrinsics_rt_fromref() model_joint.extrinsics_rt_fromref(extrinsics) # model_joint now has intrinsics from 'model0.cameramodel' and extrinsics # from 'model1.cameramodel'. I write it to disk model_joint.write('model-joint.cameramodel') All functions are exported into the mrcal module. So you can call these via mrcal.cameramodel.fff() or mrcal.fff(). The latter is preferred. ''' import sys import numpy as np import numpysane as nps import numbers import ast import re import warnings import io import base64 import mrcal def _validateExtrinsics(e): r'''Raises an exception if the given extrinsics are invalid''' # Internal extrinsic representation is a 6-long array try: N = len(e) except: raise Exception("Valid extrinsics are an iterable of len 6") if N != 6: raise Exception("Valid extrinsics are an iterable of len 6") for x in e: if not isinstance(x, numbers.Number): raise Exception("All extrinsics elements should be numeric, but '{}' isn't".format(x)) def _validateIntrinsics(imagersize, i, optimization_inputs = None, icam_intrinsics = None): r'''Raises an exception if given components of the intrinsics is invalid''' # need two integers in the imager size try: N = len(imagersize) if N != 2: raise Exception("The imagersize must be an iterable of two positive integers") if imagersize[0] <= 0 or imagersize[1] <= 0: raise Exception("The imagersize must be an iterable of two positive integers") if imagersize[0] != int(imagersize[0]) or imagersize[1] != int(imagersize[1]): raise Exception("The imagersize must be an iterable of two positive integers") except: raise Exception("The imagersize must be an iterable of two positive integers") try: N = len(i) except: raise Exception("Valid intrinsics are an iterable of len 2") if N != 2: raise Exception("Valid intrinsics are an iterable of len 2") lensmodel = i[0] intrinsics = i[1] # If this fails, I keep the exception and let it fall through Nintrinsics_want = mrcal.lensmodel_num_params(lensmodel) try: Nintrinsics_have = len(intrinsics) except: raise Exception("Valid intrinsics are (lensmodel, intrinsics) where 'intrinsics' is an iterable with a length") if Nintrinsics_want != Nintrinsics_have: raise Exception("Mismatched Nintrinsics. Got {}, but model {} must have {}".format(Nintrinsics_have,lensmodel,Nintrinsics_want)) for x in intrinsics: if not isinstance(x, numbers.Number): raise Exception("All intrinsics elements should be numeric, but '{}' isn't".format(x)) if optimization_inputs is not None: # Currently this is only checked when we set the optimization_inputs by # calling intrinsics(). We do NOT check this if reading a file from # disk. This is done as an optimization: we store the unprocessed # _optimization_inputs_string bytes and only decode them as needed. # Perhaps I should expand this if not isinstance(optimization_inputs, dict): raise Exception(f"'optimization_inputs' must be a dict. Instead got type {type(optimization_inputs)}") if icam_intrinsics is None: raise Exception(f"optimization_inputs is given, so icam_intrinsics MUST be given too") if not isinstance(icam_intrinsics, int): raise Exception(f"icam_intrinsics not an int. This must be an int >= 0") if icam_intrinsics < 0: raise Exception(f"icam_intrinsics < 0. This must be an int >= 0") def _validateValidIntrinsicsRegion(valid_intrinsics_region): r'''Raises an exception if the given valid_intrinsics_region is illegal''' if valid_intrinsics_region is None: return try: # valid intrinsics region is a closed contour, so I need at least 4 # points to be valid. Or as a special case, a (0,2) array is legal, and # means "intrinsics are valid nowhere" if not (valid_intrinsics_region.ndim == 2 and \ valid_intrinsics_region.shape[1] == 2 and \ (valid_intrinsics_region.shape[0] >= 4 or \ valid_intrinsics_region.shape[0] == 0)): raise Exception("The valid extrinsics region must be a numpy array of shape (N,2) with N >= 4 or N == 0") except: raise Exception("The valid extrinsics region must be a numpy array of shape (N,2) with N >= 4. Instead got type {} of shape {}". \ format(type(valid_intrinsics_region), valid_intrinsics_region.shape if type(valid_intrinsics_region) is np.ndarray else None)) if valid_intrinsics_region.size > 0 and \ nps.norm2(valid_intrinsics_region[0] - valid_intrinsics_region[-1]) > 1e-6: raise Exception("The valid extrinsics region must be a closed contour: the first and last points must be identical") class CameramodelParseException(Exception): r'''Raised if a .cameramodel file couldn't be parsed successfully This is just a normal "Exception" with a different name, so I can handle this specifically ''' pass def _serialize_optimization_inputs(optimization_inputs): r'''Convert a optimization_inputs dict to an ascii string This is an internal function. I store the optimization inputs as an opaque string in the .cameramodel file. This is a potentially large data blob that has little value in being readable to the user. To serialize I do this: - normalize the data in the dict. The numpy.save...() functions have quirks, so I must work around them: - All non-numpy-array values are read in as scalar numpy arrays, so I must extract them at reading time - Any non-trivial objects are pickled, but pickling is not safe for untrusted data, so I disable pickling, which means that non-trivial objects are not serializable. This includes None. So I store None as ''. This means I can't store '', which I guess is OK - np.savez_compressed() to make a compressed binary data stream - base64.b85encode() to convert to printable ascii This works, but the normalization is ugly, and this thing is inefficient. b85encode() is written in Python for instance. I can replace some of this with tarfile, which doesn't really solve the problems, but it could be a starting point for something better in the future def write(): d = dict( x = np.arange(1000) + 5, y = np.arange(300, dtype=float) / 2, z = None, s = 'abc', bt = True, bf = False) f = io.BytesIO() tar = \ tarfile.open(name = None, mode = 'w|gz', fileobj = f) for k in d.keys(): v = d[k] if v is None: v = '' d_bytes = io.BytesIO() np.save(d_bytes, v, allow_pickle = False) tarinfo = tarfile.TarInfo(name=k) tarinfo.size = d_bytes.tell() d_bytes.seek(0) tar.addfile( tarinfo, fileobj = d_bytes ) tar.close() sys.stdout.buffer.write(f.getvalue()) def read(): with open("/tmp/tst.tar.gz", "rb") as f: tar = \ tarfile.open(name = None, mode = 'r|gz', fileobj = f) for m in tar: b = tar.extractfile(m).read() arr = np.load(io.BytesIO(b), allow_pickle=False, encoding='bytes') if arr.shape == (): arr = arr.item() if type(arr) is str and arr == '': arr = None print(arr) tar.close() ''' data_bytes = io.BytesIO() optimization_inputs_normalized = dict() for k in optimization_inputs.keys(): v = optimization_inputs[k] if v is None: v = '' optimization_inputs_normalized[k] = v np.savez_compressed(data_bytes, **optimization_inputs_normalized) return \ base64.b85encode(data_bytes.getvalue()) def _deserialize_optimization_inputs(data_bytes): r'''Convert an ascii string for the optimization-input to a full dict This is an internal function. This is the inverse of _serialize_optimization_inputs(). See the docstring of that function for details ''' optimization_inputs_bytes = io.BytesIO(base64.b85decode(data_bytes)) _optimization_inputs = np.load(optimization_inputs_bytes, allow_pickle = False) # Now I need to post-process my output array. Numpy converts everything # to numpy arrays for some reason, even things that aren't numpy arrays. # So I find everything that's an array of shape (), and convert it to # the actual thing contained in the array optimization_inputs = dict() for k in _optimization_inputs.keys(): arr = _optimization_inputs[k] if arr.shape == (): arr = arr.item() if type(arr) is str and arr == '': arr = None optimization_inputs[k] = arr # for legacy compatibility def renamed(s0, s1, d): if s0 in d and not s1 in d: d[s1] = d[s0] del d[s0] renamed('do_optimize_intrinsic_core', 'do_optimize_intrinsics_core', optimization_inputs) renamed('do_optimize_intrinsic_distortions', 'do_optimize_intrinsics_distortions', optimization_inputs) # renamed('icam_intrinsics_optimization_inputs', # 'icam_intrinsics', # optimization_inputs) if 'calibration_object_width_n' in optimization_inputs: del optimization_inputs['calibration_object_width_n' ] if 'calibration_object_height_n' in optimization_inputs: del optimization_inputs['calibration_object_height_n'] return optimization_inputs class cameramodel(object): r'''A class that describes the lens parameters and geometry of a single camera SYNOPSIS model = mrcal.cameramodel('xxx.cameramodel') extrinsics_Rt_toref = model.extrinsics_Rt_toref() extrinsics_Rt_toref[3,2] += 10.0 extrinsics_Rt_toref = model.extrinsics_Rt_toref(extrinsics_Rt_toref) model.write('moved.cameramodel') # we read a model from disk, moved it 10 units along the z axis, and wrote # the results back to disk This class represents - The intrinsics: parameters that describe the lens. These do not change as the camera moves around in space. These are represented by a tuple (lensmodel,intrinsics_data) - lensmodel: a string "LENSMODEL_...". The full list of supported models is returned by mrcal.supported_lensmodels() - intrinsics_data: a numpy array of shape (mrcal.lensmodel_num_params(lensmodel),). For lensmodels that have an "intrinsics core" (all of them, currently) the first 4 elements are - fx: the focal-length along the x axis, in pixels - fy: the focal-length along the y axis, in pixels - cx: the projection center along the x axis, in pixels - cy: the projection center along the y axis, in pixels The remaining elements (both their number and their meaning) are dependent on the specific lensmodel being used. Some models (LENSMODEL_PINHOLE for example) do not have any elements other than the core. - The imager size: the dimensions of the imager, in a (width,height) list - The extrinsics: the pose of this camera in respect to some reference coordinate system. The meaning of this "reference" coordinate system is user-defined, and means nothing to mrcal.cameramodel. If we have multiple cameramodels, they generally share this "reference" coordinate system, and it is used as an anchor to position the cameras in respect to one another. Internally this is stored as an rt transformation converting points represented in the reference coordinate TO a representation in the camera coordinate system. These are gettable/settable by these methods: - extrinsics_rt_toref() - extrinsics_rt_fromref() - extrinsics_Rt_toref() - extrinsics_Rt_fromref() These exist for convenience, and handle the necessary conversion internally. These make it simple to use the desired Rt/rt transformation and the desired to/from reference direction. - The valid-intrinsics region: a contour in the imager where the projection behavior is "reliable". The meaning of "reliable" is user-defined. mrcal is able to report the projection uncertainty anywhere in space, and this is a more fine-grained way to measure "reliability", but sometimes it is convenient to define an uncertainty limit, and to compute a region where this limit is met. This region can then be stored in the mrcal.cameramodel object. A missing valid-intrinsics region means "unknown". An empty valid-intrinsics region (array of length 0) means "intrinsics are valid nowhere". Storing this is optional. - The optimization inputs: this is a dict containing all the data that was used to compute the contents of this model. These are optional. These are the kwargs passable to mrcal.optimize() and mrcal.optimizer_callback() that describe the optimization problem at its final optimum. Storing these is optional, but they are very useful for diagnostics, since everything in the model can be re-generated from this data. Some things (most notably the projection uncertainties) are also computed off the optimization_inputs(), making these extra-useful. The optimization_inputs dict can be queried by the optimization_inputs() method. Setting this can be done only together with the intrinsics(), using the intrinsics() method. For the purposes of computing the projection uncertainty it is allowed to move the camera (change the extrinsics), so the extrinsics_...() methods may be called without invalidating the optimization_inputs. This class provides facilities to read/write models on disk, and to get/set the various components. The format of a .cameramodel file is a python dictionary that we (safely) eval. A sample valid .cameramodel file: # generated with ... { 'lensmodel': 'LENSMODEL_OPENCV8', # intrinsics are fx,fy,cx,cy,distortion0,distortion1,.... 'intrinsics': [1766.0712405930, 1765.8925266865, 1944.0664501036, 1064.5231421210, 2.1648025156, -1.1851581377, -0.0000931342, 0.0007782462, -0.2351910903, 2.4460295029, -0.6697132481, -0.6284355415], # extrinsics are rt_fromref 'extrinsics': [0,0,0,0,0,0], 'imagersize': [3840,2160] } ''' def _write(self, f, note=None): r'''Writes out this camera model to an open file''' if note is not None: for l in note.splitlines(): f.write('# ' + l + '\n') # I write this out manually instead of using repr for the whole thing # because I want to preserve key ordering f.write("{\n") f.write(" 'lensmodel': '{}',\n".format(self._intrinsics[0])) f.write("\n") N = len(self._intrinsics[1]) if(mrcal.lensmodel_metadata_and_config(self._intrinsics[0])['has_core']): f.write(" # intrinsics are fx,fy,cx,cy,distortion0,distortion1,....\n") f.write((" 'intrinsics': [" + (" {:.10g}," * N) + "],\n").format(*self._intrinsics[1])) f.write("\n") if self._valid_intrinsics_region is not None: f.write(" 'valid_intrinsics_region': [\n") for row in self._valid_intrinsics_region: f.write((" [ {:.10g}, {:.10g} ],\n").format(*row)) f.write("],\n\n") N = len(self._extrinsics) f.write(" # extrinsics are rt_fromref\n") f.write((" 'extrinsics': [" + (" {:.10g}," * N) + "],\n").format(*self._extrinsics)) f.write("\n") N = 2 f.write((" 'imagersize': [" + (" {:d}," * N) + "],\n").format(*(int(x) for x in self._imagersize))) f.write("\n") if self._icam_intrinsics is not None: f.write((" 'icam_intrinsics': {:d},\n").format(self._icam_intrinsics)) f.write("\n") if self._optimization_inputs_string is not None: f.write(r""" # The optimization inputs contain all the data used to compute this model. # This contains ALL the observations for ALL the cameras in the solve. The uses of # this are to be able to compute projection uncertainties, to visualize the # calibration-time geometry and to re-run the original optimization for # diagnostics. This is a big chunk of data that isn't useful for humans to # interpret, so it's stored in binary, compressed, and encoded to ascii in # base-85. Modifying the intrinsics of the model invalidates the optimization # inputs: the optimum implied by the inputs would no longer match the stored # parameters. Modifying the extrinsics is OK, however: if we move the camera # elsewhere, the original solve can still be used to represent the camera-relative # projection uncertainties """) f.write(f" 'optimization_inputs': {self._optimization_inputs_string},\n\n") f.write("}\n") def _read_into_self(self, f): r'''Reads in a model from an open file, or the model given as a string Note that the string is NOT a filename, it's the model data. This function reads the native .cameramodel format only ''' # workaround for python3 idiocy try: filetype = file except: filetype = io.IOBase if isinstance(f, filetype): s = f.read() try: name = f.name except: name = None else: s = f name = None try: model = ast.literal_eval(s) except: if name is None: raise CameramodelParseException("Failed to parse cameramodel!") else: raise CameramodelParseException(f"Failed to parse cameramodel '{name}'") # for legacy compatibility def renamed(s0, s1, d): if s0 in d and not s1 in d: d[s1] = d[s0] del d[s0] renamed('distortion_model', 'lensmodel', model) renamed('lens_model', 'lensmodel', model) renamed('icam_intrinsics_optimization_inputs', 'icam_intrinsics', model) model['lensmodel'] = model['lensmodel'].replace('DISTORTION', 'LENSMODEL') keys_required = set(('lensmodel', 'intrinsics', 'extrinsics', 'imagersize')) keys_received = set(model.keys()) if keys_received < keys_required: raise Exception("Model must have at least these keys: '{}'. Instead I got '{}'". \ format(keys_required, keys_received)) valid_intrinsics_region = None if 'valid_intrinsics_region' in model: if len(model['valid_intrinsics_region']) > 0: valid_intrinsics_region = np.array(model['valid_intrinsics_region']) else: valid_intrinsics_region = np.zeros((0,2)) intrinsics = (model['lensmodel'], np.array(model['intrinsics'], dtype=float)) _validateIntrinsics(model['imagersize'], intrinsics) try: _validateValidIntrinsicsRegion(valid_intrinsics_region) except Exception as e: warnings.warn("Invalid valid_intrinsics region; skipping: '{}'".format(e)) valid_intrinsics_region = None _validateExtrinsics(model['extrinsics']) self._intrinsics = intrinsics self._valid_intrinsics_region = mrcal.close_contour(valid_intrinsics_region) self._extrinsics = np.array(model['extrinsics'], dtype=float) self._imagersize = np.array(model['imagersize'], dtype=np.int32) if 'optimization_inputs' in model: if not isinstance(model['optimization_inputs'], bytes): raise CameramodelParseException("'optimization_inputs' is given, but it's not a byte string. type(optimization_inputs)={}". \ format(type(model['optimization_inputs']))) self._optimization_inputs_string = model['optimization_inputs'] if 'icam_intrinsics' not in model: raise CameramodelParseException("'optimization_inputs' is given, but icam_intrinsics NOT given") if not isinstance(model['icam_intrinsics'], int): raise CameramodelParseException("'icam_intrinsics' is given, but it's not an int") if model['icam_intrinsics'] < 0: raise CameramodelParseException("'icam_intrinsics' is given, but it's <0. Must be >= 0") self._icam_intrinsics = model['icam_intrinsics'] else: self._optimization_inputs_string = None self._icam_intrinsics = None def __init__(self, file_or_model = None, *, intrinsics = None, imagersize = None, extrinsics_Rt_toref = None, extrinsics_Rt_fromref = None, extrinsics_rt_toref = None, extrinsics_rt_fromref = None, optimization_inputs = None, icam_intrinsics = None, valid_intrinsics_region = None ): r'''Initialize a new camera-model object SYNOPSIS # reading from a file on disk model0 = mrcal.cameramodel('xxx.cameramodel') # using discrete arguments model1 = mrcal.cameramodel( intrinsics = ('LENSMODEL_PINHOLE', np.array((fx,fy,cx,cy))), imagersize = (640,480) ) # using a optimization_inputs dict model2 = mrcal.cameramodel( optimization_inputs = optimization_inputs, icam_intrinsics = 0 ) We can initialize using one of several methods, depending on which arguments are given. The arguments for the methods we're not using MUST all be None. Methods: - Read a file on disk. The filename should be given in the 'file_or_model' argument (possibly as a positional argument) - Read a python 'file' object. Similarly, the opened file should be given in the 'file_or_model' argument (possibly as a poitional argument) - Copy an existing cameramodel object. Pass the object in the 'file_or_model' argument (possibly as a poitional argument) - Read discrete arguments. The components of this model (intrinsics, extrinsics, etc) can be passed-in separetely via separate keyword arguments - optimization_inputs. If we have an optimization_inputs dict to store, this alone may be passed-in, and all the model components can be read from it. ARGUMENTS - file_or_model: we read the camera model from a filename or a pre-opened file object or from an existing cameramodel object to copy. Both .cameramodel and the legacy .cahvor formats are supported. This may be given as a positional argument. Everything else may be given only as keyword arguments. - intrinsics: a tuple (lensmodel, intrinsics_data). If given, 'imagersize' is also required. This may be given only as a keyword argument. - imagersize: tuple (width,height) for the size of the imager. If given, 'intrinsics' is also required. This may be given only as a keyword argument. - extrinsics_Rt_toref: numpy array of shape (4,3) describing the Rt transformation FROM the camera coordinate system TO the reference coordinate system. Exclusive with the other 'extrinsics_...' arguments. If given, 'intrinsics' and 'imagersize' are both required. If no 'extrinsics_...' arguments are given, an identity transformation is set. This may be given only as a keyword argument. - extrinsics_Rt_fromref: numpy array of shape (4,3) describing the Rt transformation FROM the reference coordinate system TO the camera coordinate system. Exclusive with the other 'extrinsics_...' arguments. If given, 'intrinsics' and 'imagersize' are both required. If no 'extrinsics_...' arguments are given, an identity transformation is set. This may be given only as a keyword argument. - extrinsics_rt_toref: numpy array of shape (6,) describing the rt transformation FROM the camera coordinate system TO the reference coordinate system. Exclusive with the other 'extrinsics_...' arguments. If given, 'intrinsics' and 'imagersize' are both required. If no 'extrinsics_...' arguments are given, an identity transformation is set. This may be given only as a keyword argument. - extrinsics_rt_fromref: numpy array of shape (6,) describing the rt transformation FROM the reference coordinate system TO the camera coordinate system. Exclusive with the other 'extrinsics_...' arguments. If given, 'intrinsics' and 'imagersize' are both required. If no 'extrinsics_...' arguments are given, an identity transformation is set. This may be given only as a keyword argument. - optimization_inputs: a dict of arguments to mrcal.optimize() at the optimum. These contain all the information needed to populate the camera model (and more!). If given, 'icam_intrinsics' is also required. This may be given only as a keyword argument. - icam_intrinsics: integer identifying this camera in the solve defined by 'optimization_inputs'. If given, 'optimization_inputs' is required. This may be given only as a keyword argument. - valid_intrinsics_region': numpy array of shape (N,2). Defines a closed contour in the imager pixel space. Points inside this contour are assumed to have 'valid' intrinsics, with the meaning of 'valid' defined by the user. An array of shape (0,2) menas "valid nowhere". This may be given only as a keyword argument. ''' Nargs = dict(file_or_model = 0, discrete = 0, extrinsics = 0, optimization_inputs = 0) if file_or_model is not None: Nargs['file_or_model'] += 1 if intrinsics is not None: Nargs['discrete'] += 1 if imagersize is not None: Nargs['discrete'] += 1 if extrinsics_Rt_toref is not None: Nargs['discrete'] += 1 Nargs['extrinsics'] += 1 if extrinsics_Rt_fromref is not None: Nargs['discrete'] += 1 Nargs['extrinsics'] += 1 if extrinsics_rt_toref is not None: Nargs['discrete'] += 1 Nargs['extrinsics'] += 1 if extrinsics_rt_fromref is not None: Nargs['discrete'] += 1 Nargs['extrinsics'] += 1 if optimization_inputs is not None: Nargs['optimization_inputs'] += 1 if icam_intrinsics is not None: Nargs['optimization_inputs'] += 1 if Nargs['file_or_model']: if Nargs['discrete'] + \ Nargs['optimization_inputs']: raise Exception("'file_or_model' specified, so none of the other inputs should be") if isinstance(file_or_model, cameramodel): self._imagersize = np.array(file_or_model._imagersize, dtype=np.int32) self._extrinsics = np.array(file_or_model._extrinsics, dtype=float) self._intrinsics = (str(file_or_model._intrinsics[0]), np.array(file_or_model._intrinsics[1], dtype=float)) if file_or_model._valid_intrinsics_region is not None: self._valid_intrinsics_region = np.array(mrcal.close_contour(file_or_model._valid_intrinsics_region), dtype=float) else: self._valid_intrinsics_region = None if file_or_model._optimization_inputs_string is not None: self._optimization_inputs_string = str(file_or_model._optimization_inputs_string) else: self._optimization_inputs_string = None if file_or_model._icam_intrinsics is not None: self._icam_intrinsics = int(file_or_model._icam_intrinsics) else: self._icam_intrinsics = None return def parse_as_opencv_or_ros(modelstring): r'''Try to parse model as an opencv/ros string Supports yaml, json. Supports opencv and ros formats. And the output of "rostopic echo" for "sensor_msgs/CameraInfo" messages. This functions tries to be general, and accept everything. This is documented here: https://wiki.ros.org/camera_calibration_parsers A sample file: image_width: 2448 image_height: 2050 camera_name: prosilica camera_matrix: rows: 3 cols: 3 data: [4827.94, 0, 1223.5, 0, 4835.62, 1024.5, 0, 0, 1] distortion_model: plumb_bob distortion_coefficients: rows: 1 cols: 5 data: [-0.41527, 0.31874, -0.00197, 0.00071, 0] rectification_matrix: rows: 3 cols: 3 data: [1, 0, 0, 0, 1, 0, 0, 0, 1] projection_matrix: rows: 3 cols: 4 data: [4827.94, 0, 1223.5, 0, 0, 4835.62, 1024.5, 0, 0, 0, 1, 0] A sample sensor_msgs/CameraInfo message: $ rostopic echo -n1 -b tst.bag /camera/camera_info .... height: 600 width: 960 distortion_model: "rational_polynomial" D: [1.5, 0.4, 0.1, -9.2e-05, 0.1, 1.9, 0.9, 0.2] K: [420.1, 0.1, 479.1, 0.1, 420.1, 295.1, 0.1, 0.1, 1.1] R: [0.9998926520347595, 0.014629560522735119, -0.0007753203972242773, -0.014624223113059998, 0.9998719692230225, 0.006493249908089638, 0.0008702144841663539, -0.006481214426457882, 0.9999786019325256] P: [600.0, 0.0, 480.0, -20.3, 0.0, 600.0, 300.0, 0.0, 0.0, 0.0, 1.0, 0.0] .... These are apparently trying to include rectification in the model, which is silly: I should be able to have a single camera with extrinsics. And there're no clear extrinsics stored here either, and I must figure out what is really intended here. Here the only "extrinsics" relate the camera to its rectified version. Rectification may rotate a camera, but may NOT translate it. - From previous experience, the rotation in R is R_leftrect_cam - P[:,3] are scaled translations: t*fx as described here: https://docs.opencv.org/2.4/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html#stereorectify - From previous experience, the translation in P[:,3]/fx is t_rightrect_leftrect. So for the purposes of extrinsics, the reference is the "left-rectified" camera ''' def load(): try: import yaml return yaml.safe_load(modelstring) except Exception as e: e1 = e pass try: import json return json.loads(modelstring) except Exception as e: e2 = e pass raise CameramodelParseException(f"Couldn't parse yaml (Exception '{e1}') or json (Exception '{e2}')") # output model = dict() # This will raise the exception, as needed model_in = load() def find_array( key_sequences, dtype, shape, model): r'''Search a model dictionary for a given array There are multiple ros/opencv data formats that aren't identical, so this general function is used to find the data. The args are: - key_sequences: a list of key sequences to look for. A key sequence such as ('camera_matrix','data') will find model[...][...][...].....['camera_matrix']['data']. At most one such matching sequence is allowed. If we find more than one, this function will throw an error - dtype: the requested dtype of the array we look for. If the data can't be interpreted in this way, I barf - shape: the shape of array we look for. This function will try to reshape into this shape, and accept any array that may be reshaped in this way. Pass () to interpret this value as a scalar. Pass None to not reshape, and pass the resulting array as is - model: the input dict ''' def find_sequence(s,d, at=''): for k in d.keys(): if isinstance(k,str) and k == s[0]: if len(s) == 1: if isinstance(d[k],dict): return None,None return d[k], f"{at}['{k}']" if not isinstance(d[k], dict): return None,None return \ find_sequence(s[1:], d[k], at=f"{at}['{k}']") return None,None matches = [find_sequence(s,model) for s in key_sequences] matches = [(m,at) for m,at in matches if m is not None] if len(matches) == 0: raise CameramodelParseException(f"None of required key sequences '{key_sequences}' found. Must have exactly one") if len(matches) > 1: raise CameramodelParseException(f"More than one of required key sequences '{key_sequences}' found. Must have exactly one") m,at = matches[0] try: m = np.array(m, dtype=dtype) except: raise CameramodelParseException(f"Could not parse model{at} as dtype = {dtype}") if shape is not None: try: m = m.reshape(shape) except: raise CameramodelParseException(f"Could not parse model{at} with shape {shape}. Input has shape {m.shape}") if len(shape) == 0: m = m.item() # extract the value if we have a scalar return m,at M,M_at = \ find_array( ( ('camera_matrix','data'), ('camera_matrix',), ('K',) ), dtype = float, shape = (3,3), model = model_in ) if M[0,1] != 0 or \ M[1,0] != 0 or \ M[2,0] != 0 or \ M[2,1] != 0 or \ M[2,2] != 1: raise CameramodelParseException(f"model {M_at} should have [fx 0 cx; 0 fy cy; 0 0 1] structure") P,P_at = \ find_array( ( ('projection_matrix','data'), ('projection_matrix',), ('P',) ), dtype = float, shape = (3,4), model = model_in ) if P[1,3] != 0 or \ P[2,3] != 0: raise CameramodelParseException(f"model {P_at} expected to have last column of [x*fx,0,0], but instead have: {P[:,3]}") try: R,R_at = \ find_array( ( ('rotation','data'), ('rotation',), ('R',) ), dtype = float, shape = (3,3), model = model_in ) except: R = mrcal.identity_R() R_at = 'default' # Special-case P=0 or R=0. Sometimes I see this. Set everything to identity if nps.norm2(P.ravel()) == 0: P[:,:3] = np.eye(3) if nps.norm2(R.ravel()) == 0: R = np.eye(3) lensmodel,lensmodel_at = \ find_array( ( ('distortion_model',),), dtype = str, shape = (), model = model_in ) map_lensmodel = \ dict(plumb_bob = 'LENSMODEL_OPENCV5', rational_polynomial = 'LENSMODEL_OPENCV8') try: model['lensmodel'] = map_lensmodel[lensmodel] except: if lensmodel == 'equidistant': raise CameramodelParseException('"equidistant" OpenCV model not supported yet') else: raise CameramodelParseException(f"Unknown OpenCV model \"{lensmodel}\". I only about: {list(map_lensmodel.keys())}") distortion,distortion_at = \ find_array( ( ('distortion_coefficients','data'), ('distortion_coefficients',), ('D',)), dtype = float, shape = None, # Any shape. Do not reshape model = model_in ) try: model['intrinsics'] = \ [M[0,0],M[1,1],M[0,2],M[1,2]] + \ list(distortion) except Exception as e: raise CameramodelParseException(f"No model {distortion_at}") # not checking len(distortion_coefficients); #_read_into_self() will do that image_width,image_width_at = \ find_array( ( ('image_width',), ('width',)), dtype = int, shape = (), model = model_in ) image_height,image_height_at = \ find_array( ( ('image_height',), ('height',)), dtype = int, shape = (), model = model_in ) model['imagersize'] = [image_width,image_height] Rt_ref_cam = np.zeros((4,3), dtype=float) Rt_ref_cam[:3,:] = R if nps.norm2((nps.matmult(R, R.T) - np.eye(3)).ravel()) > 1e-12: raise CameramodelParseException(f"R must be a valid rotation. Instead it is {R}") # In rectified coords ("ref" coords here) I want the camera to # sit at -P[:,3] / P[0,0] Rt_ref_cam[ 3,:] = -P[:,3] / P[0,0] # extrinsics are rt_fromref model['extrinsics'] = list(mrcal.rt_from_Rt(mrcal.invert_Rt(Rt_ref_cam))) return repr(model) # Some readable file. Read it! def tryread(f, what): r'''Try all the formats I support''' modelstring = f.read() errors = dict() try: self._read_into_self(modelstring) return except CameramodelParseException as e: errors['cameramodel'] = e pass try: self._read_into_self(parse_as_opencv_or_ros(modelstring)) return except CameramodelParseException as e: errors['yaml_or_json'] = e pass # Couldn't read the file in any known method. Last try: does a # .cahvor work? # This is more complicated than it looks. I want to read the # .cahvor file into self, but the current cahvor interface # wants to generate a new model object. So I do that, write # it as a .cameramodel-formatted string, and then read that # back into self. Inefficient, but this is far from a hot # path try: from . import cahvor model = cahvor.read_from_string(modelstring) modelfile = io.StringIO() model.write(modelfile) self._read_into_self(modelfile.getvalue()) return except Exception as e: errors['cahvor'] = e raise Exception(f"Couldn't parse {what}. Errors for each attempt: {errors}") if isinstance(file_or_model, str): if file_or_model == '-': if sys.stdin.isatty(): # This isn't an error per-se. But most likely the user # ran something like "mrcal-to-cahvor" without # redirecting any data into it. Without this check the # program will sit there, waiting for input. Which will # look strange to an unsuspecting user raise Exception("Trying to read a model from standard input, but no file is being redirected into it") tryread(sys.stdin, "STDIN") else: with open(file_or_model, 'r') as openedfile: tryread(openedfile, f"file '{file_or_model}'") else: # I assume this is a readable file tryread(file_or_model, "file object") return if Nargs['discrete']: if Nargs['file_or_model'] + \ Nargs['optimization_inputs']: raise Exception("discrete values specified, so none of the other inputs should be") if Nargs['discrete']-Nargs['extrinsics'] != 2: raise Exception("Discrete values given. Must have gotten 'intrinsics' AND 'imagersize' AND optionally ONE of the extrinsics_...") if Nargs['extrinsics'] == 0: # No extrinsics. Use the identity self.extrinsics_rt_fromref(np.zeros((6,),dtype=float)) elif Nargs['extrinsics'] == 1: if extrinsics_Rt_toref is not None: self.extrinsics_Rt_toref (extrinsics_Rt_toref) elif extrinsics_Rt_fromref is not None: self.extrinsics_Rt_fromref(extrinsics_Rt_fromref) elif extrinsics_rt_toref is not None: self.extrinsics_rt_toref (extrinsics_rt_toref) elif extrinsics_rt_fromref is not None: self.extrinsics_rt_fromref(extrinsics_rt_fromref) else: raise Exception("At most one of the extrinsics_... arguments may be given") self.intrinsics(intrinsics, imagersize=imagersize) elif Nargs['optimization_inputs']: if Nargs['file_or_model'] + \ Nargs['discrete']: raise Exception("optimization_inputs specified, so none of the other inputs should be") if Nargs['optimization_inputs'] != 2: raise Exception("optimization_input given. Must have gotten 'optimization_input' AND 'icam_intrinsics'") self.intrinsics( ( optimization_inputs['lensmodel'], optimization_inputs['intrinsics'][icam_intrinsics] ), imagersize = optimization_inputs['imagersizes'][icam_intrinsics], optimization_inputs = optimization_inputs, icam_intrinsics = icam_intrinsics) icam_extrinsics = mrcal.corresponding_icam_extrinsics(icam_intrinsics, **optimization_inputs) if icam_extrinsics < 0: self.extrinsics_rt_fromref(np.zeros((6,), dtype=float)) else: self.extrinsics_rt_fromref(optimization_inputs['extrinsics_rt_fromref'][icam_extrinsics]) else: raise Exception("At least one source of initialization data must have been given. Need a filename or a cameramodel object or discrete arrays or optimization_inputs") self._valid_intrinsics_region = None # default if valid_intrinsics_region is not None: try: self.valid_intrinsics_region(valid_intrinsics_region) except Exception as e: warnings.warn("Invalid valid_intrinsics region; skipping: '{}'".format(e)) def __str__(self): '''Stringification Return what would be written to a .cameramodel file''' f = io.StringIO() self._write(f) return f.getvalue() def __repr__(self): '''Representation Return a string of a constructor function call''' funcs = (self.imagersize, self.intrinsics, self.extrinsics_rt_fromref, self.valid_intrinsics_region) return 'mrcal.cameramodel(' + \ ', '.join( f.__func__.__code__.co_name + '=' + repr(f()) for f in funcs ) + \ ')' def write(self, f, *, note = None, cahvor = False, _opencv = False): r'''Write out this camera model to disk SYNOPSIS model.write('left.cameramodel') We write the contents of the given mrcal.cameramodel object to the given filename or a given pre-opened file. If the filename is 'xxx.cahv' or 'xxx.cahvor' or 'xxx.cahvore' or if cahvor: we use the legacy cahvor file format for output ARGUMENTS - f: a string for the filename or an opened Python 'file' object to use - note: an optional string, defaulting to None. This is a comment that will be written to the top of the output file. This should describe how this model was generated - cahvor: an optional boolean, defaulting to False. If True: we write out the data using the legacy .cahvor file format RETURNED VALUES None ''' # opencv models may be written by setting _opencv=True. But this has no # clear way to specify extrinsics, and requires specifying stereo # rectification, so this is undocumented for now known_format_options = ('cahvor','_opencv') NformatOptions = 0 for o in known_format_options: if locals()[o]: NformatOptions += 1 if NformatOptions > 1: raise Exception(f"At most 1 of {known_format_options} may be given.") _validateIntrinsics(self._imagersize, self._intrinsics) _validateValidIntrinsicsRegion(self._valid_intrinsics_region) _validateExtrinsics(self._extrinsics) def write_cahvor(f): from . import cahvor cahvor.write(f, self, note) def write_opencv(f): r'''Write out an opencv-format file This has no clear way to specify extrinsics, and requires specifying stereo rectification, so this is undone and undocumented for now. This function always sets an identity extrinsics transform and completely made-up projection and rectification matrices This is documented here: https://wiki.ros.org/camera_calibration_parsers A sample file: image_width: 2448 image_height: 2050 camera_name: prosilica camera_matrix: rows: 3 cols: 3 data: [4827.94, 0, 1223.5, 0, 4835.62, 1024.5, 0, 0, 1] distortion_model: plumb_bob distortion_coefficients: rows: 1 cols: 5 data: [-0.41527, 0.31874, -0.00197, 0.00071, 0] rectification_matrix: rows: 3 cols: 3 data: [1, 0, 0, 0, 1, 0, 0, 0, 1] projection_matrix: rows: 3 cols: 4 data: [4827.94, 0, 1223.5, 0, 0, 4835.62, 1024.5, 0, 0, 0, 1, 0] ''' if self._intrinsics[0] == 'LENSMODEL_OPENCV5': distortion_model = 'plumb_bob' distortions = self._intrinsics[1][4:] elif self._intrinsics[0] == 'LENSMODEL_OPENCV4': distortion_model = 'plumb_bob' distortions = nps.glue(self._intrinsics[1][4:], 0, axis = -1) if self._intrinsics[0] == 'LENSMODEL_PINHOLE': distortion_model = 'plumb_bob' distortions = nps.glue(self._intrinsics[1][4:], np.zeros((5,), dtype=float), axis = -1) elif self._intrinsics[0] == 'LENSMODEL_OPENCV8': distortion_model = 'rational_polynomial' distortions = self._intrinsics[1][4:] # I don't support "equidistant" yet else: raise Exception(f"OpenCV yaml can't store the \"{self._intrinsics[0]}\" model") fxycxy = self._intrinsics[1][:4] M = np.array(((fxycxy[0], 0, fxycxy[2]), ( 0, fxycxy[1], fxycxy[3]), ( 0, 0, 1)), dtype=float) f.write(f"image_width: {self._imagersize[0]}\nimage_height: {self._imagersize[1]}\ncamera_name: mrcalmodel\n") f.write(f"camera_matrix:\n rows: 3\n cols: 3\n data: [{fxycxy[0]}, 0, {fxycxy[2]}, 0, {fxycxy[1]}, {fxycxy[3]}, 0, 0, 1]\n") f.write(f"distortion_model: {distortion_model}\n") f.write(f"distortion_coefficients:\n rows: 1\n cols: {len(distortions)}\n data: [") np.savetxt(f, nps.atleast_dims(distortions,-2), delimiter=', ', newline ='', fmt='%.12g') f.write("]\n") f.write('''rectification_matrix: rows: 3 cols: 3 data: [1, 0, 0, 0, 1, 0, 0, 0, 1] projection_matrix: rows: 3 cols: 4 data: [1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1, 0] ''') write_function = None if cahvor: write_function = write_cahvor elif _opencv: write_function = write_opencv if isinstance(f, str): with open(f, 'w') as openedfile: if write_function is not None: write_function(openedfile) elif re.match(r".*\.cahv(or(e)?)?$", f): write_cahvor(openedfile) elif re.match(r".*\.ya?ml$", f): write_opencv(openedfile) else: self._write( openedfile, note ) else: if write_function is not None: write_function(f) else: self._write( f, note ) def intrinsics(self, intrinsics = None, *, imagersize = None, optimization_inputs = None, icam_intrinsics = None): r'''Get or set the intrinsics in this model SYNOPSIS # getter lensmodel,intrinsics_data = model.intrinsics() # setter model.intrinsics( intrinsics = ('LENSMODEL_PINHOLE', fx_fy_cx_cy), imagersize = (640,480), optimization_inputs = optimization_inputs, icam_intrinsics = 0) This function has two modes of operation: a getter and a setter, depending on the arguments. - If no arguments are given: this is a getter. The getter returns the (lensmodel, intrinsics_data) tuple only. - lensmodel: a string "LENSMODEL_...". The full list of supported models is returned by mrcal.supported_lensmodels() - intrinsics_data: a numpy array of shape (mrcal.lensmodel_num_params(lensmodel),). For lensmodels that have an "intrinsics core" (all of them, currently) the first 4 elements are - fx: the focal-length along the x axis, in pixels - fy: the focal-length along the y axis, in pixels - cx: the projection center along the x axis, in pixels - cy: the projection center along the y axis, in pixels The remaining elements (both their number and their meaning) are dependent on the specific lensmodel being used. Some models (LENSMODEL_PINHOLE for example) do not have any elements other than the core. - If any arguments are given, this is a setter. The setter takes in - the (lensmodel, intrinsics_data) tuple - (optionally) the imagersize - (optionally) optimization_inputs - (optionally) icam_intrinsics Changing any of these 4 parameters automatically invalidates the others, and it only makes sense to set them in unison. The getters return a copy of the data, and the setters make a copy of the input: so it's impossible for the caller or callee to modify each other's data. ARGUMENTS - intrinsics: a (lensmodel, intrinsics_data) if we're setting; None if we're getting - imagersize: optional iterable of length 2. The (width,height) for the size of the imager. If omitted, I use the imagersize already stored in this object. This is useful if a valid cameramodel object already exists, and I want to update it with new lens parameters - optimization_inputs: optional dict of arguments to mrcal.optimize() at the optimum. These contain all the information needed to populate the camera model (and more!). If given, 'icam_intrinsics' is also required. If omitted, no optimization_inputs are stored; re-solving and computing of uncertainties is impossible. - icam_intrinsics: optional integer identifying this camera in the solve defined by 'optimization_inputs'. May be omitted if 'optimization_inputs' is omitted RETURNED VALUE If this is a getter (no arguments given), returns a (lensmodel, intrinsics_data) tuple where - lensmodel is a string "LENSMODEL_..." - intrinsics_data is a numpy array of shape (mrcal.lensmodel_num_params(lensmodel),) ''' # This is a getter if \ imagersize is None and \ intrinsics is None and \ optimization_inputs is None and \ icam_intrinsics is None: return (str(self._intrinsics[0]), np.array(self._intrinsics[1], dtype=float)) # This is a setter. The rest of this function does all that work if imagersize is None: imagersize = self._imagersize _validateIntrinsics(imagersize, intrinsics, optimization_inputs, icam_intrinsics) self._imagersize = np.array(imagersize, dtype=np.int32) self._intrinsics = (str(intrinsics[0]), np.array(intrinsics[1], dtype=float)) if optimization_inputs is not None: self._optimization_inputs_string = \ _serialize_optimization_inputs(optimization_inputs) self._icam_intrinsics = icam_intrinsics else: self._optimization_inputs_string = None self._icam_intrinsics = None def _extrinsics_rt(self, toref, rt=None): r'''Get or set the extrinsics in this model This function represents the pose as a 6-long numpy array that contains a 3-long Rodrigues rotation followed by a 3-long translation in the last row: r = rt[:3] t = rt[3:] R = mrcal.R_from_r(r) The transformation is b <-- R*a + t: import numpysane as nps b = nps.matmult(a, nps.transpose(R)) + t if rt is None: this is a getter; otherwise a setter. toref is a boolean. if toref: then rt maps points in the coord system of THIS camera to the reference coord system. Otherwise in the opposite direction ''' # The internal representation is rt_fromref if rt is None: # getter if not toref: return np.array(self._extrinsics) return mrcal.invert_rt(self._extrinsics) # setter if not toref: self._extrinsics = np.array(rt, dtype=float) return True self._extrinsics = mrcal.invert_rt(rt.astype(float)) return True def extrinsics_rt_toref(self, rt=None): r'''Get or set the extrinsics in this model SYNOPSIS # getter rt_rc = model.extrinsics_rt_toref() # setter model.extrinsics_rt_toref( rt_rc ) This function gets/sets rt_toref: a numpy array of shape (6,) describing the rt transformation FROM the camera coordinate system TO the reference coordinate system. if rt is None: this is a getter; otherwise a setter. The getters return a copy of the data, and the setters make a copy of the input: so it's impossible for the caller or callee to modify each other's data. ARGUMENTS - rt: if we're setting, a numpy array of shape (6,). The rt transformation TO the reference coordinate system. If we're getting, None RETURNED VALUE If this is a getter (no arguments given), returns a a numpy array of shape (6,). The rt transformation TO the reference coordinate system. ''' return self._extrinsics_rt(True, rt) def extrinsics_rt_fromref(self, rt=None): r'''Get or set the extrinsics in this model SYNOPSIS # getter rt_cr = model.extrinsics_rt_fromref() # setter model.extrinsics_rt_fromref( rt_cr ) This function gets/sets rt_fromref: a numpy array of shape (6,) describing the rt transformation FROM the reference coordinate system TO the camera coordinate system. if rt is None: this is a getter; otherwise a setter. The getters return a copy of the data, and the setters make a copy of the input: so it's impossible for the caller or callee to modify each other's data. ARGUMENTS - rt: if we're setting, a numpy array of shape (6,). The rt transformation FROM the reference coordinate system. If we're getting, None RETURNED VALUE If this is a getter (no arguments given), returns a a numpy array of shape (6,). The rt transformation FROM the reference coordinate system. ''' return self._extrinsics_rt(False, rt) def _extrinsics_Rt(self, toref, Rt=None): r'''Get or set the extrinsics in this model This function represents the pose as a shape (4,3) numpy array that contains a (3,3) rotation matrix, followed by a (1,3) translation in the last row: R = Rt[:3,:] t = Rt[ 3,:] The transformation is b <-- R*a + t: import numpysane as nps b = nps.matmult(a, nps.transpose(R)) + t if Rt is None: this is a getter; otherwise a setter. toref is a boolean. if toref: then Rt maps points in the coord system of THIS camera to the reference coord system. Otherwise in the opposite direction ''' # The internal representation is rt_fromref if Rt is None: # getter rt_fromref = self._extrinsics Rt_fromref = mrcal.Rt_from_rt(rt_fromref) if not toref: return Rt_fromref return mrcal.invert_Rt(Rt_fromref) # setter if toref: Rt_fromref = mrcal.invert_Rt(Rt.astype(float)) self._extrinsics = mrcal.rt_from_Rt(Rt_fromref) return True self._extrinsics = mrcal.rt_from_Rt(Rt.astype(float)) return True def extrinsics_Rt_toref(self, Rt=None): r'''Get or set the extrinsics in this model SYNOPSIS # getter Rt_rc = model.extrinsics_Rt_toref() # setter model.extrinsics_Rt_toref( Rt_rc ) This function gets/sets Rt_toref: a numpy array of shape (4,3) describing the Rt transformation FROM the camera coordinate system TO the reference coordinate system. if Rt is None: this is a getter; otherwise a setter. The getters return a copy of the data, and the setters make a copy of the input: so it's impossible for the caller or callee to modify each other's data. ARGUMENTS - Rt: if we're setting, a numpy array of shape (4,3). The Rt transformation TO the reference coordinate system. If we're getting, None RETURNED VALUE If this is a getter (no arguments given), returns a a numpy array of shape (4,3). The Rt transformation TO the reference coordinate system. ''' return self._extrinsics_Rt(True, Rt) def extrinsics_Rt_fromref(self, Rt=None): r'''Get or set the extrinsics in this model SYNOPSIS # getter Rt_cr = model.extrinsics_Rt_fromref() # setter model.extrinsics_Rt_fromref( Rt_cr ) This function gets/sets Rt_fromref: a numpy array of shape (4,3) describing the Rt transformation FROM the reference coordinate system TO the camera coordinate system. if Rt is None: this is a getter; otherwise a setter. The getters return a copy of the data, and the setters make a copy of the input: so it's impossible for the caller or callee to modify each other's data. ARGUMENTS - Rt: if we're setting, a numpy array of shape (4,3). The Rt transformation FROM the reference coordinate system. If we're getting, None RETURNED VALUE If this is a getter (no arguments given), returns a a numpy array of shape (4,3). The Rt transformation FROM the reference coordinate system. ''' return self._extrinsics_Rt(False, Rt) def imagersize(self, *args, **kwargs): r'''Get the imagersize in this model SYNOPSIS width,height = model.imagersize() This function retrieves the dimensions of the imager described by this camera model. This function is NOT a setter; use intrinsics() to set all the intrinsics together. ARGUMENTS None RETURNED VALUE A length-2 tuple (width,height) ''' if len(args) or len(kwargs): raise Exception("imagersize() is NOT a setter. Please use intrinsics() to set them all together") return np.array(self._imagersize, dtype=np.int32) def valid_intrinsics_region(self, valid_intrinsics_region=None): r'''Get or set the valid-intrinsics region SYNOPSIS # getter region = model.valid_intrinsics_region() # setter model.valid_intrinsics_region( region ) The valid-intrinsics region is a closed contour in imager space representated as a numpy array of shape (N,2). This is a region where the intrinsics are "reliable", with a user-defined meaning of that term. A region of shape (0,2) means "intrinsics are valid nowhere". if valid_intrinsics_region is None: this is a getter; otherwise a setter. The getters return a copy of the data, and the setters make a copy of the input: so it's impossible for the caller or callee to modify each other's data. ARGUMENTS - valid_intrinsics_region: if we're setting, a numpy array of shape (N,2). If we're getting, None RETURNED VALUE If this is a getter (no arguments given), returns a numpy array of shape (N,2) or None, if no valid-intrinsics region is defined in this model ''' if valid_intrinsics_region is None: # getter if self._valid_intrinsics_region is None: return None return np.array(self._valid_intrinsics_region, dtype=float) # setter if valid_intrinsics_region is None: self._valid_intrinsics_region = None return True valid_intrinsics_region = mrcal.close_contour(valid_intrinsics_region) # raises exception on error _validateValidIntrinsicsRegion(valid_intrinsics_region) self._valid_intrinsics_region = np.array(valid_intrinsics_region, dtype=float) return True def optimization_inputs(self): r'''Get the original optimization inputs SYNOPSIS b,x,j = mrcal.optimizer_callback(**model.optimization_inputs())[:3] This function retrieves the optimization inputs: a dict containing all the data that was used to compute the contents of this model. These are the kwargs passable to mrcal.optimize() and mrcal.optimizer_callback(), that describe the optimization problem at its final optimum. A cameramodel object may not contain this data, in which case we return None. This function is NOT a setter; use intrinsics() to set all the intrinsics together. The optimization inputs aren't a part of the intrinsics per se, but modifying any part of the intrinsics invalidates the optimization inputs, so it makes sense to set them all together ARGUMENTS None RETURNED VALUE The optimization_inputs dict, or None if one isn't stored in this model. ''' if self._optimization_inputs_string is None: return None x = _deserialize_optimization_inputs(self._optimization_inputs_string) if x['extrinsics_rt_fromref'] is None: x['extrinsics_rt_fromref'] = np.zeros((0,6), dtype=float) return x def _optimization_inputs_match(self, other_model): if self. _optimization_inputs_string is None: if other_model._optimization_inputs_string is None: return True else: return False if other_model._optimization_inputs_string is None: return False; # Both non-None return \ self. _optimization_inputs_string == \ other_model._optimization_inputs_string def _extrinsics_moved_since_calibration(self): optimization_inputs = self.optimization_inputs() icam_extrinsics = \ mrcal.corresponding_icam_extrinsics(self.icam_intrinsics(), **optimization_inputs) rt_cam_ref = self.extrinsics_rt_fromref() if icam_extrinsics < 0: # extrinsics WERE at the reference. So I should have an identity # transform return np.max(np.abs(rt_cam_ref)) > 0.0 d = rt_cam_ref - \ optimization_inputs['extrinsics_rt_fromref'][icam_extrinsics] return np.max(np.abs(d)) > 1e-6 def icam_intrinsics(self): r'''Get the camera index indentifying this camera at optimization time SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() icam_intrinsics = m.icam_intrinsics() icam_extrinsics = \ mrcal.corresponding_icam_extrinsics(icam_intrinsics, **optimization_inputs) if icam_extrinsics >= 0: extrinsics_rt_fromref_at_calibration_time = \ optimization_inputs['extrinsics_rt_fromref'][icam_extrinsics] This function retrieves the integer identifying this camera in the solve defined by 'optimization_inputs'. When the optimization happened, we may have been calibrating multiple cameras at the same time, and only one of those cameras is described by this 'cameramodel' object. The 'icam_intrinsics' index returned by this function specifies which camera this is. This function is NOT a setter; use intrinsics() to set all the intrinsics together. The optimization inputs and icam_intrinsics aren't a part of the intrinsics per se, but modifying any part of the intrinsics invalidates the optimization inputs, so it makes sense to set them all together ARGUMENTS None RETURNED VALUE The icam_intrinsics integer, or None if one isn't stored in this model. ''' if self._icam_intrinsics is None: return None return self._icam_intrinsics mrcal-2.4.1/mrcal/image_transforms.py000066400000000000000000000604441456301662300176420ustar00rootroot00000000000000#!/usr/bin/python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 '''Routines for transformation of images All functions are exported into the mrcal module. So you can call these via mrcal.image_transforms.fff() or mrcal.fff(). The latter is preferred. ''' import numpy as np import numpysane as nps import sys import re import mrcal def scale_focal__best_pinhole_fit(model, fit): r'''Compute the optimal focal-length scale for reprojection to a pinhole lens SYNOPSIS model = mrcal.cameramodel('from.cameramodel') lensmodel,intrinsics_data = model.intrinsics() scale_focal = mrcal.scale_focal__best_pinhole_fit(model, 'centers-horizontal') intrinsics_data[:2] *= scale_focal model_pinhole = \ mrcal.cameramodel(intrinsics = ('LENSMODEL_PINHOLE', intrinsics_data[:4]), imagersize = model.imagersize(), extrinsics_rt_fromref = model.extrinsics_rt_fromref() ) Many algorithms work with images assumed to have been captured with a pinhole camera, even though real-world lenses never fit a pinhole model. mrcal provides several functions to remap images captured with non-pinhole lenses into images of the same scene as if they were observed by a pinhole lens. When doing this, we're free to choose all of the parameters of this pinhole lens model, and this function allows us to pick the best scaling on the focal-length parameter. The focal length parameters serve as a "zoom" factor: changing these parameters can increase the resolution of the center of the image, at the expense of cutting off the edges. This function computes the best focal-length scaling, for several possible meanings of "best". I assume an output pinhole model that has pinhole parameters (k*fx, k*fy, cx, cy) where (fx, fy, cx, cy) are the parameters from the input model, and k is the scaling we compute. This function looks at some points on the edge of the input image. I choose k so that all of these points end up inside the pinhole-reprojected image, leaving the worst one at the edge. The set of points I look at are specified in the "fit" argument. ARGUMENTS - model: a mrcal.cameramodel object for the input lens model - fit: which pixel coordinates in the input image must project into the output pinhole-projected image. The 'fit' argument must be one of - a numpy array of shape (N,2) where each row is a pixel coordinate in the input image - "corners": each of the 4 corners of the input image must project into the output image - "centers-horizontal": the two points at the left and right edges of the input image, half-way vertically, must both project into the output image - "centers-vertical": the two points at the top and bottom edges of the input image, half-way horizontally, must both project into the output image RETURNED VALUE A scalar scale_focal that can be passed to pinhole_model_for_reprojection() ''' if fit is None: return 1.0 WH = np.array(model.imagersize(), dtype=float) W,H = WH if type(fit) is np.ndarray: q_edges = fit elif type(fit) is str: if fit == 'corners': q_edges = np.array((( 0., 0.), ( 0., H-1.), (W-1., H-1.), (W-1., 0.))) elif fit == 'centers-horizontal': q_edges = np.array(((0, (H-1.)/2.), (W-1., (H-1.)/2.))) elif fit == 'centers-vertical': q_edges = np.array((((W-1.)/2., 0, ), ((W-1.)/2., H-1.,))) else: raise Exception("fit must be either None or a numpy array or one of ('corners','centers-horizontal','centers-vertical')") else: raise Exception("fit must be either None or a numpy array or one of ('corners','centers-horizontal','centers-vertical')") lensmodel,intrinsics_data = model.intrinsics() v_edges = mrcal.unproject(q_edges, lensmodel, intrinsics_data) if not mrcal.lensmodel_metadata_and_config(lensmodel)['has_core']: raise Exception("This currently works only with models that have an fxfycxcy core") fxy = intrinsics_data[ :2] cxy = intrinsics_data[2:4] # I have points in space now. My scaled pinhole camera would map these to # (k*fx*x/z+cx, k*fy*y/z+cy). I pick a k to make sure that this is in-bounds # for all my points, and that the points occupy as large a chunk of the # imager as possible. I can look at just the normalized x and y. Just one of # the query points should land on the edge; the rest should be in-bounds normxy_edges = v_edges[:,:2] / v_edges[:,(2,)] normxy_min = ( - cxy) / fxy normxy_max = (WH-1. - cxy) / fxy # Each query point will imply a scale to just fit into the imager I take the # most conservative of these. For each point I look at the normalization sign to # decide if I should be looking at the min or max edge. And for each I pick the # more conservative scale # start out at an unreasonably high scale. The data will cut this down scale = 1e6 for p in normxy_edges: for ixy in range(2): if p[ixy] > 0: scale = np.min((scale,normxy_max[ixy]/p[ixy])) else: scale = np.min((scale,normxy_min[ixy]/p[ixy])) return scale def pinhole_model_for_reprojection(model_from, fit = None, *, scale_focal = None, scale_image = None): r'''Generate a pinhole model suitable for reprojecting an image SYNOPSIS model_orig = mrcal.cameramodel("xxx.cameramodel") image_orig = mrcal.load_image("image.jpg") model_pinhole = mrcal.pinhole_model_for_reprojection(model_orig, fit = "corners") mapxy = mrcal.image_transformation_map(model_orig, model_pinhole, intrinsics_only = True) image_undistorted = mrcal.transform_image(image_orig, mapxy) Many algorithms work with images assumed to have been captured with a pinhole camera, even though real-world lenses never fit a pinhole model. mrcal provides several functions to remap images captured with non-pinhole lenses into images of the same scene as if they were observed by a pinhole lens. When doing this, we're free to choose all of the parameters of this pinhole lens model. THIS function produces the pinhole camera model based on some guidance in the arguments, and this model can then be used to "undistort" images. ARGUMENTS - model_from: the mrcal.cameramodel object used to build the pinhole model. We use the intrinsics as the baseline, and we copy the extrinsics to the resulting pinhole model. - fit: optional specification for focal-length scaling. By default we use the focal length values from the input model. This is either a numpy array of shape (...,2) containing pixel coordinates that the resulting pinhole model must represent, or one of ("corners","centers-horizontal","centers-vertical"). See the docstring for scale_focal__best_pinhole_fit() for details. Exclusive with 'scale_focal' - scale_focal: optional specification for focal-length scaling. By default we use the focal length values from the input model. If given, we scale the input focal lengths by the given value. Exclusive with 'fit' - scale_image: optional specification for the scaling of the image size. By default the output model represents an image of the same resolution as the input model. If we want something else, the scaling can be given here. RETURNED VALUE A mrcal.cameramodel object with lensmodel = LENSMODEL_PINHOLE corresponding to the input model. ''' if scale_focal is None: if fit is not None: if isinstance(fit, np.ndarray): if fit.shape[-1] != 2: raise Exception("'fit' is an array, so it must have shape (...,2)") fit = nps.atleast_dims(fit, -2) fit = nps.clump(fit, n=len(fit.shape)-1) # fit now has shape (N,2) elif re.match("^(corners|centers-horizontal|centers-vertical)$", fit): # this is valid. nothing to do pass else: raise Exception("'fit' must be an array of shape (...,2) or one of ('corners','centers-horizontal','centers-vertical')", file=sys.stderr) sys.exit(1) scale_focal = mrcal.scale_focal__best_pinhole_fit(model_from, fit) else: if fit is not None: raise Exception("At most one of 'scale_focal' and 'fit' may be non-None") # I have some scale_focal now. I apply it lensmodel,intrinsics_data = model_from.intrinsics() imagersize = model_from.imagersize() if not mrcal.lensmodel_metadata_and_config(lensmodel)['has_core']: raise Exception("This currently works only with models that have an fxfycxcy core") cx,cy = intrinsics_data[2:4] intrinsics_data[:2] *= scale_focal if scale_image is not None: # Now I apply the imagersize scale. The center of the imager should # unproject to the same point: # # (q0 - cxy0)/fxy0 = v = (q1 - cxy1)/fxy1 # ((WH-1)/2 - cxy) / fxy = (((ki*WH)-1)/2 - kc*cxy) / (kf*fxy) # # The focal lengths scale directly: kf = ki # ((WH-1)/2 - cxy) / fxy = (((ki*WH)-1)/2 - kc*cxy) / (ki*fxy) # (WH-1)/2 - cxy = (((ki*WH)-1)/2 - kc*cxy) / ki # (WH-1)/2 - cxy = (WH-1/ki)/2 - kc/ki*cxy # -1/2 - cxy = (-1/ki)/2 - kc/ki*cxy # 1/2 + cxy = 1/(2ki) + kc/ki*cxy # -> kc = (1/2 + cxy - 1/(2ki)) * ki / cxy # = (ki + 2*cxy*ki - 1) / (2 cxy) # # Sanity check: cxy >> 1: ki+2*cxy*ki = ki*(1+2cxy) ~ 2*cxy*ki # 2*cxy*ki - 1 ~ 2*cxy*ki # -> kc ~ 2*cxy*ki /( 2 cxy ) = ki. Yes. # Looks like I scale cx and cy separately. imagersize[0] = round(imagersize[0]*scale_image) imagersize[1] = round(imagersize[1]*scale_image) kfxy = scale_image kcx = (kfxy + 2.*cx*kfxy - 1.) / (2. * cx) kcy = (kfxy + 2.*cy*kfxy - 1.) / (2. * cy) intrinsics_data[:2] *= kfxy intrinsics_data[2] *= kcx intrinsics_data[3] *= kcy return \ mrcal.cameramodel( intrinsics = ('LENSMODEL_PINHOLE',intrinsics_data[:4]), extrinsics_rt_fromref = model_from.extrinsics_rt_fromref(), imagersize = imagersize ) def image_transformation_map(model_from, model_to, *, intrinsics_only = False, distance = None, plane_n = None, plane_d = None, mask_valid_intrinsics_region_from = False): r'''Compute a reprojection map between two models SYNOPSIS model_orig = mrcal.cameramodel("xxx.cameramodel") image_orig = mrcal.load_image("image.jpg") model_pinhole = mrcal.pinhole_model_for_reprojection(model_orig, fit = "corners") mapxy = mrcal.image_transformation_map(model_orig, model_pinhole, intrinsics_only = True) image_undistorted = mrcal.transform_image(image_orig, mapxy) # image_undistorted is now a pinhole-reprojected version of image_orig Returns the transformation that describes a mapping - from pixel coordinates of an image of a scene observed by model_to - to pixel coordinates of an image of the same scene observed by model_from This transformation can then be applied to a whole image by calling mrcal.transform_image(). This function returns a transformation map in an (Nheight,Nwidth,2) array. The image made by model_to will have shape (Nheight,Nwidth). Each pixel (x,y) in this image corresponds to a pixel mapxy[y,x,:] in the image made by model_from. One application of this function is to validate the models in a stereo pair. For instance, reprojecting one camera's image at distance=infinity should produce exactly the same image that is observed by the other camera when looking at very far objects, IF the intrinsics and rotation are correct. If the images don't line up well, we know that some part of the models is off. Similarly, we can use big planes (such as observations of the ground) and plane_n, plane_d to validate. This function has several modes of operation: - intrinsics, extrinsics Used if not intrinsics_only and \ plane_n is None and \ plane_d is None This is the default. For each pixel in the output, we use the full model to unproject a given distance out, and then use the full model to project back into the other camera. - intrinsics only Used if intrinsics_only and \ plane_n is None and \ plane_d is None Similar, but the extrinsics are ignored. We unproject the pixels in one model, and project the into the other camera. The two camera coordinate systems are assumed to line up perfectly - plane Used if plane_n is not None and plane_d is not None We map observations of a given plane in camera FROM coordinates coordinates to where this plane would be observed by camera TO. We unproject each pixel in one camera, compute the intersection point with the plane, and project that intersection point back to the other camera. This uses ALL the intrinsics, extrinsics and the plane representation. The plane is represented by a normal vector plane_n, and the distance to the normal plane_d. The plane is all points p such that inner(p,plane_n) = plane_d. plane_n does not need to be normalized; any scaling is compensated in plane_d. ARGUMENTS - model_from: the mrcal.cameramodel object describing the camera used to capture the input image. We always use the intrinsics. if not intrinsics_only: we use the extrinsics also - model_to: the mrcal.cameramodel object describing the camera that would have captured the image we're producing. We always use the intrinsics. if not intrinsics_only: we use the extrinsics also - intrinsics_only: optional boolean, defaulting to False. If False: we respect the relative transformation in the extrinsics of the camera models. - distance: optional value, defaulting to None. Used only if not intrinsics_only. We reproject points in space a given distance out. If distance is None (the default), we look out to infinity. This is equivalent to using only the rotation component of the extrinsics, ignoring the translation. - plane_n: optional numpy array of shape (3,); None by default. If given, we produce a transformation to map observations of a given plane to the same pixels in the source and target images. This argument describes the normal vector in the coordinate system of model_from. The plane is all points p such that inner(p,plane_n) = plane_d. plane_n does not need to be normalized; any scaling is compensated in plane_d. If given, plane_d should be given also, and intrinsics_only should be False. if given, we use the full intrinsics and extrinsics of both camera models - plane_d: optional floating-point value; None by default. If given, we produce a transformation to map observations of a given plane to the same pixels in the source and target images. The plane is all points p such that inner(p,plane_n) = plane_d. plane_n does not need to be normalized; any scaling is compensated in plane_d. If given, plane_n should be given also, and intrinsics_only should be False. if given, we use the full intrinsics and extrinsics of both camera models - mask_valid_intrinsics_region_from: optional boolean defaulting to False. If True, points outside the valid-intrinsics region in the FROM image are set to black, and thus do not appear in the output image RETURNED VALUE A numpy array of shape (Nheight,Nwidth,2) where Nheight and Nwidth represent the imager dimensions of model_to. This array contains 32-bit floats, as required by cv2.remap() (the function providing the internals of mrcal.transform_image()). This array can be passed to mrcal.transform_image() ''' if (plane_n is None and plane_d is not None) or \ (plane_n is not None and plane_d is None): raise Exception("plane_n and plane_d should both be None or neither should be None") if plane_n is not None and \ intrinsics_only: raise Exception("We're looking at remapping a plane (plane_d, plane_n are not None), so intrinsics_only should be False") if distance is not None and \ (plane_n is not None or intrinsics_only): raise Exception("'distance' makes sense only without plane_n/plane_d and without intrinsics_only") if intrinsics_only: Rt_to_from = None else: Rt_to_from = mrcal.compose_Rt(model_to. extrinsics_Rt_fromref(), model_from.extrinsics_Rt_toref()) lensmodel_from,intrinsics_data_from = model_from.intrinsics() lensmodel_to, intrinsics_data_to = model_to. intrinsics() if re.match("LENSMODEL_OPENCV",lensmodel_from) and \ lensmodel_to == "LENSMODEL_PINHOLE" and \ plane_n is None and \ not mask_valid_intrinsics_region_from and \ distance is None: # This is a common special case. This branch works identically to the # other path (the other side of this "if" can always be used instead), # but the opencv-specific code is optimized and at one point ran faster # than the code on the other side. # # The mask_valid_intrinsics_region_from isn't implemented in this path. # It COULD be, then this faster path could be used import cv2 fxy_from = intrinsics_data_from[0:2] cxy_from = intrinsics_data_from[2:4] cameraMatrix_from = np.array(((fxy_from[0], 0, cxy_from[0]), ( 0, fxy_from[1], cxy_from[1]), ( 0, 0, 1))) fxy_to = intrinsics_data_to[0:2] cxy_to = intrinsics_data_to[2:4] cameraMatrix_to = np.array(((fxy_to[0], 0, cxy_to[0]), ( 0, fxy_to[1], cxy_to[1]), ( 0, 0, 1))) output_shape = model_to.imagersize() distortion_coeffs = intrinsics_data_from[4: ] if Rt_to_from is not None: R_to_from = Rt_to_from[:3,:] if np.trace(R_to_from) > 3. - 1e-12: R_to_from = None # identity, so I pass None else: R_to_from = None return nps.glue( *[ nps.dummy(arr,-1) for arr in \ cv2.initUndistortRectifyMap(cameraMatrix_from, distortion_coeffs, R_to_from, cameraMatrix_to, tuple(output_shape), cv2.CV_32FC1)], axis = -1) W_from,H_from = model_from.imagersize() W_to, H_to = model_to. imagersize() # shape: (Nheight,Nwidth,2). Contains (x,y) rows grid = np.ascontiguousarray(nps.mv(nps.cat(*np.meshgrid(np.arange(W_to), np.arange(H_to))), 0,-1), dtype = float) v = mrcal.unproject(grid, lensmodel_to, intrinsics_data_to) if plane_n is not None: R_to_from = Rt_to_from[:3,:] t_to_from = Rt_to_from[ 3,:] # The homography definition. Derived in many places. For instance in # "Motion and structure from motion in a piecewise planar environment" # by Olivier Faugeras, F. Lustman. A_to_from = plane_d * R_to_from + nps.outer(t_to_from, plane_n) A_from_to = np.linalg.inv(A_to_from) v = nps.matmult( v, nps.transpose(A_from_to) ) else: if Rt_to_from is not None: if distance is not None: v = mrcal.transform_point_Rt(mrcal.invert_Rt(Rt_to_from), v/nps.dummy(nps.mag(v),-1) * distance) else: R_to_from = Rt_to_from[:3,:] v = nps.matmult(v, R_to_from) mapxy = mrcal.project( v, lensmodel_from, intrinsics_data_from ) if mask_valid_intrinsics_region_from: # Using matplotlib to compute the out-of-bounds points. It doesn't # support broadcasting, so I do that manually with a clump/reshape from matplotlib.path import Path region = Path(model_from.valid_intrinsics_region()) is_inside = region.contains_points(nps.clump(mapxy,n=2)).reshape(mapxy.shape[:2]) mapxy[ ~is_inside, :] = -1 return mapxy.astype(np.float32) def transform_image(image, mapxy, *, out = None, borderMode = None, borderValue = 0, interpolation = None): r'''Transforms a given image using a given map SYNOPSIS model_orig = mrcal.cameramodel("xxx.cameramodel") image_orig = mrcal.load_image("image.jpg") model_pinhole = mrcal.pinhole_model_for_reprojection(model_orig, fit = "corners") mapxy = mrcal.image_transformation_map(model_orig, model_pinhole, intrinsics_only = True) image_undistorted = mrcal.transform_image(image_orig, mapxy) # image_undistorted is now a pinhole-reprojected version of image_orig Given an array of pixel mappings this function can be used to transform one image to another. If we want to convert a scene image observed by one camera model to the image of the same scene using a different model, we can produce a suitable transformation map with mrcal.image_transformation_map(). An example of this common usage appears above in the synopsis. At this time this function is a thin wrapper around cv2.remap() ARGUMENTS - image: a numpy array containing an image we're transforming. May be grayscale: shape (Nheight_input, Nwidth_input) or RGB: shape (Nheight_input, Nwidth_input, 3) - mapxy: a numpy array of shape (Nheight,Nwidth,2) where Nheight and Nwidth represent the dimensions of the target image. This array is expected to have dtype=np.float32, since the internals of this function are provided by cv2.remap() - out: optional numpy array of shape (Nheight,Nwidth) or (Nheight,Nwidth,3) to receive the result. If omitted, a new array is allocated and returned. - borderMode: optional constant defining out-of-bounds behavior. Defaults to cv2.BORDER_TRANSPARENT, and is passed directly to cv2.remap(). Please see the docs for that function for details. This option may disappear if mrcal stops relying on opencv - interpolation: optional constant defining pixel interpolation behavior. Defaults to cv2.INTER_LINEAR, and is passed directly to cv2.remap(). Please see the docs for that function for details. This option may disappear if mrcal stops relying on opencv RETURNED VALUE A numpy array of shape (Nheight, Nwidth) if grayscale or (Nheight, Nwidth, 3) if RGB. Contains the transformed image. ''' # necessary to avoid opencv crashing if not isinstance(image, np.ndarray): raise Exception("'image' must be a numpy array") if not isinstance(mapxy, np.ndarray): raise Exception("'mapxy' must be a numpy array") import cv2 if borderMode is None: borderMode = cv2.BORDER_CONSTANT if interpolation is None: interpolation = cv2.INTER_LINEAR return cv2.remap(image, mapxy, None, borderMode = borderMode, interpolation = interpolation, borderValue = borderValue, dst = out) mrcal-2.4.1/mrcal/model_analysis.py000066400000000000000000002111021456301662300172720ustar00rootroot00000000000000#!/usr/bin/python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 '''Routines for analysis of camera projection This is largely dealing with uncertainty and projection diff operations. All functions are exported into the mrcal module. So you can call these via mrcal.model_analysis.fff() or mrcal.fff(). The latter is preferred. ''' import numpy as np import numpysane as nps import sys import mrcal def implied_Rt10__from_unprojections(q0, p0, v1, *, weights = None, atinfinity = True, focus_center = np.zeros((2,), dtype=float), focus_radius = 1.0e8): r'''Compute the implied-by-the-intrinsics transformation to fit two cameras' projections SYNOPSIS models = ( mrcal.cameramodel('cam0-dance0.cameramodel'), mrcal.cameramodel('cam0-dance1.cameramodel') ) lensmodels = [model.intrinsics()[0] for model in models] intrinsics_data = [model.intrinsics()[1] for model in models] # v shape (...,Ncameras,Nheight,Nwidth,...) # q0 shape (..., Nheight,Nwidth,...) v,q0 = \ mrcal.sample_imager_unproject(60, None, *models[0].imagersize(), lensmodels, intrinsics_data, normalize = True) implied_Rt10 = \ mrcal.implied_Rt10__from_unprojections(q0, v[0,...], v[1,...]) q1 = mrcal.project( mrcal.transform_point_Rt(implied_Rt10, v[0,...]), *models[1].intrinsics()) projection_diff = q1 - q0 When comparing projections from two lens models, it is usually necessary to align the geometry of the two cameras, to cancel out any transformations implied by the intrinsics of the lenses. This transformation is computed by this function, used primarily by mrcal.show_projection_diff() and the mrcal-show-projection-diff tool. What are we comparing? We project the same world point into the two cameras, and report the difference in projection. Usually, the lens intrinsics differ a bit, and the implied origin of the camera coordinate systems and their orientation differ also. These geometric uncertainties are baked into the intrinsics. So when we project "the same world point" we must apply a geometric transformation to compensate for the difference in the geometry of the two cameras. This transformation is unknown, but we can estimate it by fitting projections across the imager: the "right" transformation would result in apparent low projection diffs in a wide area. The primary inputs are unprojected gridded samples of the two imagers, obtained with something like mrcal.sample_imager_unproject(). We grid the two imagers, and produce normalized observation vectors for each grid point. We pass the pixel grid from camera0 in q0, and the two unprojections in p0, v1. This function then tries to find a transformation to minimize norm2( project(camera1, transform(p0)) - q1 ) We return an Rt transformation to map points in the camera0 coordinate system to the camera1 coordinate system. Some details about this general formulation are significant: - The subset of points we use for the optimization - What kind of transformation we use In most practical usages, we would not expect a good fit everywhere in the imager: areas where no chessboards were observed will not fit well, for instance. From the point of view of the fit we perform, those ill-fitting areas should be treated as outliers, and they should NOT be a part of the solve. How do we specify the well-fitting area? The best way is to use the model uncertainties to pass the weights in the "weights" argument (see show_projection_diff() for an implementation). If uncertainties aren't available, or if we want a faster solve, the focus region can be passed in the focus_center, focus_radius arguments. By default, these are set to encompass the whole imager, since the uncertainties would take care of everything, but without uncertainties (weights = None), these should be set more discriminately. It is possible to pass both a focus region and weights, but it's probably not very useful. Unlike the projection operation, the diff operation is NOT invariant under geometric scaling: if we look at the projection difference for two points at different locations along a single observation ray, there will be a variation in the observed diff. This is due to the geometric difference in the two cameras. If the models differed only in their intrinsics parameters, then this would not happen. Thus this function needs to know how far from the camera it should look. By default (atinfinity = True) we look out to infinity. In this case, p0 is expected to contain unit vectors. To use any other distance, pass atinfinity = False, and pass POINTS in p0 instead of just observation directions. v1 should always be normalized. Generally the most confident distance will be where the chessboards were observed at calibration time. Practically, it is very easy for the unprojection operation to produce nan or inf values. And the weights could potentially have some invalid values also. This function explicitly checks for such illegal data in p0, v1 and weights, and ignores those points. ARGUMENTS - q0: an array of shape (Nh,Nw,2). Gridded pixel coordinates covering the imager of both cameras - p0: an array of shape (...,Nh,Nw,3). An unprojection of q0 from camera 0. If atinfinity, this should contain unit vectors, else it should contain points in space at the desired distance from the camera. This array may have leading dimensions that are all used in the fit. These leading dimensions correspond to those in the "weights" array - v1: an array of shape (Nh,Nw,3). An unprojection of q0 from camera 1. This should always contain unit vectors, regardless of the value of atinfinity - weights: optional array of shape (...,Nh,Nw); None by default. If given, these are used to weigh each fitted point differently. Usually we use the projection uncertainties to apply a stronger weight to more confident points. If omitted or None, we weigh each point equally. This array may have leading dimensions that are all used in the fit. These leading dimensions correspond to those in the "p0" array - atinfinity: optional boolean; True by default. If True, we're looking out to infinity, and I compute a rotation-only fit; a full Rt transformation is still returned, but Rt[3,:] is 0; p0 should contain unit vectors. If False, I'm looking out to a finite distance, and p0 should contain 3D points specifying the positions of interest. - focus_center: optional array of shape (2,); (0,0) by default. Used to indicate that we're interested only in a subset of pixels q0, a distance focus_radius from focus_center. By default focus_radius is LARGE, so we use all the points. This is intended to be used if no uncertainties are available, and we need to manually select the focus region. - focus_radius: optional value; LARGE by default. Used to indicate that we're interested only in a subset of pixels q0, a distance focus_radius from focus_center. By default focus_radius is LARGE, so we use all the points. This is intended to be used if no uncertainties are available, and we need to manually select the focus region. RETURNED VALUE An array of shape (4,3), representing an Rt transformation from camera0 to camera1. If atinfinity then we're computing a rotation-fit only, but we still report a full Rt transformation with the t component set to 0 ''' # This is very similar in spirit to what compute_Rcorrected_dq_dintrinsics() did # (removed in commit 4240260), but that function worked analytically, while this # one explicitly computes the rotation by matching up known vectors. import scipy.optimize ### flatten all the input arrays # shape (N,2) q0 = nps.clump(q0, n=q0.ndim-1) # shape (M,N,3) p0 = nps.transpose(nps.clump(nps.mv( nps.atleast_dims(p0, -3), -1,-3), n=-2)) # shape (N,3) v1 = nps.clump(v1, n=v1.ndim-1) if weights is None: weights = np.ones(p0.shape[:-1], dtype=float) else: # shape (..., Nh,Nw) -> (M,N,) where N = Nh*Nw weights = nps.clump( nps.clump(weights, n=-2), n = weights.ndim-2) # Any inf/nan weight or vector are set to 0 weights = weights.copy() weights[ ~np.isfinite(weights) ] = 0.0 p0 = p0.copy() v1 = v1.copy() # p0 had shape (N,3). Collapse all the leading dimensions into one # And do the same for weights i_nan_p0 = ~np.isfinite(p0) p0[i_nan_p0] = 0. weights[i_nan_p0[...,0]] = 0.0 weights[i_nan_p0[...,1]] = 0.0 weights[i_nan_p0[...,2]] = 0.0 i_nan_v1 = ~np.isfinite(v1) v1[i_nan_v1] = 0. weights[..., i_nan_v1[...,0]] = 0.0 weights[..., i_nan_v1[...,1]] = 0.0 weights[..., i_nan_v1[...,2]] = 0.0 # We try to match the geometry in a particular region q_off_center = q0 - focus_center i = nps.norm2(q_off_center) < focus_radius*focus_radius if np.count_nonzero(i)<3: raise Exception("Focus region contained too few points") p0_cut = p0 [..., i, :] v1_cut = v1 [ i, :] weights = weights[..., i ] def residual_jacobian_rt(rt): # rtp0 has shape (M,N,3) # drtp0_drt has shape (M,N,3,6) rtp0, drtp0_drt, _ = \ mrcal.transform_point_rt(rt, p0_cut, get_gradients = True) # inner(a,b)/(mag(a)*mag(b)) = cos(x) ~ 1 - x^2/2 # Each of these has shape (M,N,) mag_rtp0 = nps.mag(rtp0) inner = nps.inner(rtp0, v1_cut) th2 = 2.* (1.0 - inner / mag_rtp0) x = th2 * weights # shape (M,N,6) dmag_rtp0_drt = nps.matmult( nps.dummy(rtp0, -2), # shape (M,N,1,3) drtp0_drt # shape (M,N,3,6) # matmult has shape (M,N,1,6) )[...,0,:] / \ nps.dummy(mag_rtp0, -1) # shape (M,N,1) # shape (M,N,6) dinner_drt = nps.matmult( nps.dummy(v1_cut, -2), # shape (M,N,1,3) drtp0_drt # shape (M,N,3,6) # matmult has shape (M,N,1,6) )[...,0,:] # dth2 = 2 (inner dmag_rtp0 - dinner mag_rtp0)/ mag_rtp0^2 # shape (M,N,6) J = 2. * \ (nps.dummy(inner, -1) * dmag_rtp0_drt - \ nps.dummy(mag_rtp0, -1) * dinner_drt) / \ nps.dummy(mag_rtp0*mag_rtp0, -1) * \ nps.dummy(weights,-1) return x.ravel(), nps.clump(J, n=J.ndim-1) def residual_jacobian_r(r): # rp0 has shape (M,N,3) # drp0_dr has shape (M,N,3,3) rp0, drp0_dr, _ = \ mrcal.rotate_point_r(r, p0_cut, get_gradients = True) # inner(a,b)/(mag(a)*mag(b)) ~ cos(x) ~ 1 - x^2/2 # Each of these has shape (M,N) inner = nps.inner(rp0, v1_cut) th2 = 2.* (1.0 - inner) x = th2 * weights # shape (M,N,3) dinner_dr = nps.matmult( nps.dummy(v1_cut, -2), # shape (M,N,1,3) drp0_dr # shape (M,N,3,3) # matmult has shape (M,N,1,3) )[...,0,:] J = -2. * dinner_dr * nps.dummy(weights,-1) return x.ravel(), nps.clump(J, n=J.ndim-1) cache = {'rt': None} def residual(rt, f): if cache['rt'] is None or not np.array_equal(rt,cache['rt']): cache['rt'] = rt cache['x'],cache['J'] = f(rt) return cache['x'] def jacobian(rt, f): if cache['rt'] is None or not np.array_equal(rt,cache['rt']): cache['rt'] = rt cache['x'],cache['J'] = f(rt) return cache['J'] # # gradient check # import gnuplotlib as gp # rt0 = np.random.random(6)*1e-3 # x0,J0 = residual_jacobian_rt(rt0) # drt = np.random.random(6)*1e-7 # rt1 = rt0+drt # x1,J1 = residual_jacobian_rt(rt1) # dx_theory = nps.matmult(J0, nps.transpose(drt)).ravel() # dx_got = x1-x0 # relerr = (dx_theory-dx_got) / ( (np.abs(dx_theory)+np.abs(dx_got))/2. ) # gp.plot(relerr, wait=1, title='rt') # r0 = np.random.random(3)*1e-3 # x0,J0 = residual_jacobian_r(r0) # dr = np.random.random(3)*1e-7 # r1 = r0+dr # x1,J1 = residual_jacobian_r(r1) # dx_theory = nps.matmult(J0, nps.transpose(dr)).ravel() # dx_got = x1-x0 # relerr = (dx_theory-dx_got) / ( (np.abs(dx_theory)+np.abs(dx_got))/2. ) # gp.plot(relerr, wait=1, title='r') # sys.exit() # I was using loss='soft_l1', but it behaved strangely. For large # f_scale_deg it should be equivalent to loss='linear', but I was seeing # large diffs when comparing a model to itself: # # ./mrcal-show-projection-diff --gridn 50 28 test/data/cam0.splined.cameramodel{,} --distance 3 # # f_scale_deg needs to be > 0.1 to make test-projection-diff.py pass, so # there was an uncomfortably-small usable gap for f_scale_deg. loss='huber' # should work similar-ish to 'soft_l1', and it works even for high # f_scale_deg f_scale_deg = 5 loss = 'huber' if atinfinity: # This is similar to a basic procrustes fit, but here we're using an L1 # cost function r = np.random.random(3) * 1e-5 res = scipy.optimize.least_squares(residual, r, jac=jacobian, method='dogbox', loss=loss, f_scale = (f_scale_deg * np.pi/180.)**2., # max_nfev=1, args=(residual_jacobian_r,), # Without this, the optimization was # ending too quickly, and I was # seeing not-quite-optimal solutions. # Especially for # very-nearly-identical rotations. # This is tested by diffing the same # model in test-projection-diff.py. # I'd like to set this to None to # disable the comparison entirely, # but that requires scipy >= 1.3.0. # So instead I set the threshold so # low that it's effectively disabled gtol = np.finfo(float).eps, verbose=0) Rt = np.zeros((4,3), dtype=float) Rt[:3,:] = mrcal.R_from_r(res.x) return Rt else: rt = np.random.random(6) * 1e-5 res = scipy.optimize.least_squares(residual, rt, jac=jacobian, method='dogbox', loss=loss, f_scale = (f_scale_deg * np.pi/180.)**2., # max_nfev=1, args=(residual_jacobian_rt,), # Without this, the optimization was # ending too quickly, and I was # seeing not-quite-optimal solutions. # Especially for # very-nearly-identical rotations. # This is tested by diffing the same # model in test-projection-diff.py. # I'd like to set this to None to # disable the comparison entirely, # but that requires scipy >= 1.3.0. # So instead I set the threshold so # low that it's effectively disabled gtol = np.finfo(float).eps ) return mrcal.Rt_from_rt(res.x) def worst_direction_stdev(cov): r'''Compute the worst-direction standard deviation from a NxN covariance matrix SYNOPSIS # A covariance matrix print(cov) ===> [[ 1. -0.4] [-0.4 0.5]] # Sample 1000 0-mean points using this covariance x = np.random.multivariate_normal(mean = np.array((0,0)), cov = cov, size = (1000,)) # Compute the worst-direction standard deviation of the sampled data print(np.sqrt(np.max(np.linalg.eig(np.mean(nps.outer(x,x),axis=0))[0]))) ===> 1.1102510878087053 # The predicted worst-direction standard deviation print(mrcal.worst_direction_stdev(cov)) ===> 1.105304960905736 The covariance of a (N,) random vector can be described by a (N,N) positive-definite symmetric matrix. The 1-sigma contour of this random variable is described by an ellipse with its axes aligned with the eigenvectors of the covariance, and the semi-major and semi-minor axis lengths specified as the sqrt of the corresponding eigenvalues. This function returns the worst-case standard deviation of the given covariance: the sqrt of the largest eigenvalue. Given the common case of a 2x2 covariance this function computes the result directly. Otherwise it uses the numpy functions to compute the biggest eigenvalue. This function supports broadcasting fully. DERIVATION I solve this directly for the 2x2 case. Let cov = (a b). If l is an eigenvalue of the covariance then (b c) (a-l)*(c-l) - b^2 = 0 --> l^2 - (a+c) l + ac-b^2 = 0 --> l = (a+c +- sqrt( a^2 + 2ac + c^2 - 4ac + 4b^2)) / 2 = = (a+c +- sqrt( a^2 - 2ac + c^2 + 4b^2)) / 2 = = (a+c)/2 +- sqrt( (a-c)^2/4 + b^2) So the worst-direction standard deviation is sqrt((a+c)/2 + sqrt( (a-c)^2/4 + b^2)) ARGUMENTS - cov: the covariance matrices given as a (..., 2,2) array. Valid covariances are positive-semi-definite (symmetric with eigenvalues >= 0), but this is not checked RETURNED VALUES The worst-direction standard deviation. This is a scalar or an array, if we're broadcasting ''' cov = nps.atleast_dims(cov,-2) if cov.shape[-2:] == (1,1): return np.sqrt(cov[...,0,0]) if cov.shape[-2:] == (2,2): a = cov[..., 0,0] b = cov[..., 1,0] c = cov[..., 1,1] return np.sqrt((a+c)/2 + np.sqrt( (a-c)*(a-c)/4 + b*b)) if cov.shape[-1] != cov.shape[-2]: raise Exception(f"covariance matrices must be square. Got cov.shape = {cov.shape}") import scipy.sparse.linalg @nps.broadcast_define( (('N','N',),), () ) def largest_eigenvalue(V): return \ scipy.sparse.linalg.eigsh(V, 1, which = 'LM', return_eigenvectors = False)[0] return np.sqrt(largest_eigenvalue(cov)) def _observed_pixel_uncertainty_from_inputs(optimization_inputs, x = None): if x is None: x = mrcal.optimizer_callback(**optimization_inputs, no_jacobian = True, no_factorization = True)[1] # mrcal.residuals_point() ignores the range normalization (penalty) sum_of_squares_residuals = 0 Nobservations = 0 # shape (Nobservations*2) residuals = mrcal.residuals_board(optimization_inputs, residuals = x).ravel() if residuals.size: sum_of_squares_residuals += np.var(residuals) * residuals.size Nobservations += residuals.size residuals = mrcal.residuals_point (optimization_inputs, residuals = x).ravel() if residuals.size: sum_of_squares_residuals += np.var(residuals) * residuals.size Nobservations += residuals.size if Nobservations == 0: raise Exception("observed_pixel_uncertainty cannot be computed because we don't have any board or point observations") observed_pixel_uncertainty = np.sqrt(sum_of_squares_residuals / Nobservations) return observed_pixel_uncertainty def _propagate_calibration_uncertainty( what, *, # One of these must be given. If it's # dF_db, then optimization_inputs must # be given too dF_dbpacked = None, dF_db = None, # These are partly optional. I need # everything except optimization_inputs. # If any of the non-optimization_inputs # arguments are missing I need # optimization_inputs to compute them. x = None, factorization = None, Jpacked = None, Nmeasurements_observations_leading = None, observed_pixel_uncertainty = None, # can compute each of the above optimization_inputs = None): r'''Helper for uncertainty propagation functions Propagates the calibration-time uncertainty to compute Var(F) for some arbitrary vector F. The user specifies the gradient dF/db: the sensitivity of F to noise in the calibration state. The vector F can have any length: this is inferred from the dimensions of the given dF/db gradient. The given factorization uses the packed, unitless state: b*. The given Jpacked uses the packed, unitless state: b*. Jpacked applies to all observations. The leading Nmeasurements_observations_leading rows apply to the observations of the calibration object, and we use just those for the input noise propagation. if Nmeasurements_observations_leading==0: assume that ALL the measurements come from the calibration object observations; a simplifed expression can be used in this case The given dF_dbpacked uses the packed, unitless state b*, so it already includes the multiplication by D in the expressions below. It's usually sparse, but stored densely. The uncertainty computation in http://mrcal.secretsauce.net/uncertainty.html concludes that Var(b) = observed_pixel_uncertainty^2 inv(JtJ) J[observations]t J[observations] inv(JtJ) I actually operate with b* and J*: the UNITLESS state and the jacobian respectively. I have b = D b* J = J* inv(D) so Var(b*) = observed_pixel_uncertainty^2 inv(J*tJ*) J*[observations]t J*[observations] inv(J*tJ*) In the special case where all the measurements come from observations, this simplifies to Var(b*) = observed_pixel_uncertainty^2 inv(J*tJ*) My factorization is of packed (scaled, unitless) flavors of J (J*). So Var(b) = D Var(b*) D I want Var(F) = dF/db Var(b) dF/dbt So Var(F) = dF/db D Var(b*) D dF/dbt In the regularized case I have Var(F) = dF/db D inv(J*tJ*) J*[observations]t J*[observations] inv(J*tJ*) D dF/dbt observed_pixel_uncertainty^2 It is far more efficient to compute inv(J*tJ*) D dF/dbt than inv(J*tJ*) J*[observations]t: there's far less to compute, and the matrices are far smaller. Thus I don't compute the covariances directly. In the non-regularized case: Var(F) = dF/db D inv(J*tJ*) D dF/dbt 1. solve( J*tJ*, D dF/dbt) The result has shape (Nstate,2) 2. pre-multiply by dF/db D 3. multiply by observed_pixel_uncertainty^2 In the regularized case: Var(F) = dF/db D inv(J*tJ*) J*[observations]t J*[observations] inv(J*tJ*) D dF/dbt 1. solve( J*tJ*, D dF/dbt) The result has shape (Nstate,2) 2. Pre-multiply by J*[observations] The result has shape (Nmeasurements_observations_leading,2) 3. Compute the sum of the outer products of each row 4. multiply by observed_pixel_uncertainty^2 ''' what_known = set(('covariance', 'worstdirection-stdev', 'rms-stdev')) if not what in what_known: raise Exception(f"'what' kwarg must be in {what_known}, but got '{what}'") if dF_dbpacked is None and \ dF_db is None: raise Exception("Exactly one of dF_dbpacked,dF_db must be given") if dF_dbpacked is not None and \ dF_db is not None: raise Exception("Exactly one of dF_dbpacked,dF_db must be given") if dF_db is not None: if optimization_inputs is None: raise Exception('dF_db is given but optimization_inputs is not. Either pass dF_dbpacked or pass optimization_inputs in as well') # Make dF_db use the packed state. I call "unpack_state" because the # state is in the denominator dF_dbpacked = np.array(dF_db) # make a copy mrcal.unpack_state(dF_dbpacked, **optimization_inputs) dF_dbpacked = nps.atleast_dims(dF_dbpacked, -2) if \ x is None or \ factorization is None or \ Jpacked is None or \ Nmeasurements_observations_leading is None or \ observed_pixel_uncertainty is None: if optimization_inputs is None: raise Exception("At least one of (factorization,Jpacked,Nmeasurements_observations_leading,observed_pixel_uncertainty) are None, so optimization_inputs MUST have been given to compute them") if factorization is None or Jpacked is None or x is None: _,x,Jpacked,factorization = mrcal.optimizer_callback(**optimization_inputs) if factorization is None: raise Exception("Cannot compute the uncertainty: factorization computation failed") if Nmeasurements_observations_leading is None: Nmeasurements_boards = mrcal.num_measurements_boards(**optimization_inputs) Nmeasurements_points = mrcal.num_measurements_points(**optimization_inputs) Nmeasurements_regularization = mrcal.num_measurements_regularization(**optimization_inputs) Nmeasurements_all = mrcal.num_measurements(**optimization_inputs) imeas_regularization = mrcal.measurement_index_regularization(**optimization_inputs) if Nmeasurements_boards + \ Nmeasurements_points + \ Nmeasurements_regularization != \ Nmeasurements_all: raise Exception("Some measurements other than boards, points and regularization are present. Don't know what to do") if imeas_regularization + Nmeasurements_regularization != Nmeasurements_all: raise Exception("Regularization measurements are NOT at the end. Don't know what to do") if Nmeasurements_regularization == 0: # Note the special-case where I'm using all the observations. No other # measurements are present other than the chessboard observations Nmeasurements_observations_leading = 0 else: if Nmeasurements_points > 0: print("WARNING: I'm currently treating the point range normalization (penalty) terms as following the same noise model as other measurements. This will bias the uncertainty estimate", file=sys.stderr) Nmeasurements_observations_leading = \ Nmeasurements_all - Nmeasurements_regularization if Nmeasurements_observations_leading == 0: raise Exception("No non-regularization measurements. Don't know what to do") if observed_pixel_uncertainty is None: observed_pixel_uncertainty = _observed_pixel_uncertainty_from_inputs(optimization_inputs, x = x) # shape (N,Nstate) where N=2 usually A = factorization.solve_xt_JtJ_bt( dF_dbpacked ) if Nmeasurements_observations_leading > 0: # I have regularization. Use the more complicated expression # I see no python way to do matrix multiplication with sparse matrices, # so I have my own routine in C. AND the C routine does the outer # product, so there's no big temporary expression. It's much faster if len(A.shape) == 2 and A.shape[0] == 2: f = mrcal._mrcal_npsp._A_Jt_J_At__2 else: f = mrcal._mrcal_npsp._A_Jt_J_At Var_dF = f(A, Jpacked.indptr, Jpacked.indices, Jpacked.data, Nleading_rows_J = Nmeasurements_observations_leading) else: # No regularization. Use the simplified expression Var_dF = nps.matmult(dF_dbpacked, nps.transpose(A)) if what == 'covariance': return Var_dF * observed_pixel_uncertainty*observed_pixel_uncertainty if what == 'worstdirection-stdev': return worst_direction_stdev(Var_dF) * observed_pixel_uncertainty if what == 'rms-stdev': return np.sqrt(nps.trace(Var_dF)/2.) * observed_pixel_uncertainty else: raise Exception("Shouldn't have gotten here. There's a bug") def _dq_db__projection_uncertainty( p_cam, lensmodel, intrinsics_data, extrinsics_rt_fromref, frames_rt_toref, Nstate, istate_intrinsics, istate_extrinsics, istate_frames, slice_optimized_intrinsics): r'''Helper for projection_uncertainty() See docs for _propagate_calibration_uncertainty() and projection_uncertainty() This function does all the work when observing points with a finite range ''' dq_db = np.zeros(p_cam.shape[:-1] + (2,Nstate), dtype=float) if extrinsics_rt_fromref is not None: p_ref = \ mrcal.transform_point_rt( mrcal.invert_rt(extrinsics_rt_fromref), p_cam ) else: p_ref = p_cam if frames_rt_toref is not None: Nframes = len(frames_rt_toref) # The point in the coord system of all the frames. I index the frames on # axis -2 # shape (..., Nframes, 3) p_frames = mrcal.transform_point_rt( # shape (Nframes,6) mrcal.invert_rt(frames_rt_toref), # shape (...,1,3) nps.dummy(p_ref,-2) ) # I now have the observed point represented in the coordinate system of # the frames. This is independent of any intrinsics-implied rotation, or # anything of the sort. I project this point back to pixels, through # noisy estimates of the frames, extrinsics and intrinsics. # # I transform each frame-represented point back to the reference coordinate # system, and I average out each estimate to get the one p_ref I will use. I # already have p_ref, so I don't actually need to compute the value; I just # need the gradients # dprefallframes_dframes has shape (..., Nframes,3,6) _, \ dprefallframes_dframes, \ _ = mrcal.transform_point_rt( frames_rt_toref, p_frames, get_gradients = True) # shape (..., 3,6*Nframes) # /Nframes because I compute the mean over all the frames dpref_dframes = nps.clump( nps.mv(dprefallframes_dframes, -3, -2), n = -2 ) / Nframes _, dq_dpcam, dq_dintrinsics = \ mrcal.project( p_cam, lensmodel, intrinsics_data, get_gradients = True) if istate_intrinsics is not None: dq_dintrinsics_optimized = dq_dintrinsics[..., slice_optimized_intrinsics] Nintrinsics = dq_dintrinsics_optimized.shape[-1] dq_db[..., istate_intrinsics:istate_intrinsics+Nintrinsics] = \ dq_dintrinsics_optimized if extrinsics_rt_fromref is not None: _, dpcam_drt, dpcam_dpref = \ mrcal.transform_point_rt(extrinsics_rt_fromref, p_ref, get_gradients = True) dq_db[..., istate_extrinsics:istate_extrinsics+6] = \ nps.matmult(dq_dpcam, dpcam_drt) if frames_rt_toref is not None: dq_db[..., istate_frames:istate_frames+Nframes*6] = \ nps.matmult(dq_dpcam, dpcam_dpref, dpref_dframes) else: if frames_rt_toref is not None: dq_db[..., istate_frames:istate_frames+Nframes*6] = \ nps.matmult(dq_dpcam, dpref_dframes) return dq_db def _dq_db__projection_uncertainty_rotationonly( p_cam, lensmodel, intrinsics_data, extrinsics_rt_fromref, frames_rt_toref, Nstate, istate_intrinsics, istate_extrinsics, istate_frames, slice_optimized_intrinsics): r'''Helper for projection_uncertainty() See docs for _propagate_calibration_uncertainty() and projection_uncertainty() This function does all the work when observing points at infinity ''' dq_db = np.zeros(p_cam.shape[:-1] + (2,Nstate), dtype=float) if extrinsics_rt_fromref is not None: p_ref = \ mrcal.rotate_point_r( -extrinsics_rt_fromref[..., :3], p_cam ) else: p_ref = p_cam if frames_rt_toref is not None: Nframes = len(frames_rt_toref) # The point in the coord system of all the frames. I index the frames on # axis -2 # shape (..., Nframes, 3) p_frames = mrcal.rotate_point_r( # shape (Nframes,3) -frames_rt_toref[...,:3], # shape (...,1,3) nps.dummy(p_ref,-2) ) # I now have the observed point represented in the coordinate system of # the frames. This is independent of any intrinsics-implied rotation, or # anything of the sort. I project this point back to pixels, through # noisy estimates of the frames, extrinsics and intrinsics. # # I transform each frame-represented point back to the reference coordinate # system, and I average out each estimate to get the one p_ref I will use. I # already have p_ref, so I don't actually need to compute the value; I just # need the gradients # dprefallframes_dframesr has shape (..., Nframes,3,3) _, \ dprefallframes_dframesr, \ _ = mrcal.rotate_point_r( frames_rt_toref[...,:3], p_frames, get_gradients = True) _, dq_dpcam, dq_dintrinsics = \ mrcal.project( p_cam, lensmodel, intrinsics_data, get_gradients = True) if istate_intrinsics is not None: dq_dintrinsics_optimized = dq_dintrinsics[..., slice_optimized_intrinsics] Nintrinsics = dq_dintrinsics_optimized.shape[-1] dq_db[..., istate_intrinsics:istate_intrinsics+Nintrinsics] = \ dq_dintrinsics_optimized if extrinsics_rt_fromref is not None: _, dpcam_dr, dpcam_dpref = \ mrcal.rotate_point_r(extrinsics_rt_fromref[...,:3], p_ref, get_gradients = True) dq_db[..., istate_extrinsics:istate_extrinsics+3] = \ nps.matmult(dq_dpcam, dpcam_dr) if frames_rt_toref is not None: dq_dpref = nps.matmult(dq_dpcam, dpcam_dpref) # dprefallframes_dframesr has shape (..., Nframes,3,3) for i in range(Nframes): dq_db[..., istate_frames+6*i:istate_frames+6*i+3] = \ nps.matmult(dq_dpref, dprefallframes_dframesr[...,i,:,:]) / Nframes else: if frames_rt_toref is not None: # dprefallframes_dframesr has shape (..., Nframes,3,3) for i in range(Nframes): dq_db[..., istate_frames+6*i:istate_frames+6*i+3] = \ nps.matmult(dq_dpcam, dprefallframes_dframesr[...,i,:,:]) / Nframes return dq_db def projection_uncertainty( p_cam, model, *, atinfinity = False, # what we're reporting what = 'covariance', observed_pixel_uncertainty = None): r'''Compute the projection uncertainty of a camera-referenced point This is the interface to the uncertainty computations described in http://mrcal.secretsauce.net/uncertainty.html SYNOPSIS model = mrcal.cameramodel("xxx.cameramodel") q = np.array((123., 443.)) distance = 10.0 pcam = distance * mrcal.unproject(q, *model.intrinsics(), normalize=True) print(mrcal.projection_uncertainty(pcam, model = model, what = 'worstdirection-stdev')) ===> 0.5 # So if we have observed a world point at pixel coordinates q, and we know # it's 10m out, then we know that the standard deviation of the noise of the # pixel obsevation is 0.5 pixels, in the worst direction After a camera model is computed via a calibration process, the model is ultimately used in projection/unprojection operations to map between 3D camera-referenced coordinates and projected pixel coordinates. We never know the parameters of the model perfectly, and it is VERY useful to have the resulting uncertainty of projection. This can be used, among other things, to - propagate the projection noise down to whatever is using the observed pixels to do stuff - evaluate the quality of calibrations, to know whether a given calibration should be accepted, or rejected - evaluate the stability of a computed model I quantify uncertainty by propagating the expected pixel observation noise through the optimization problem. This gives us the uncertainty of the solved optimization parameters. And then we propagate this parameter noise through projection to produce the projected pixel uncertainty. As noted in the docs (http://mrcal.secretsauce.net/uncertainty.html), this measures the SAMPLING error, which is a direct function of the quality of the gathered calibration data. It does NOT measure model errors, which arise from inappropriate lens models, for instance. The uncertainties can be visualized with the mrcal-show-projection-uncertainty tool. ARGUMENTS This function accepts an array of camera-referenced points p_cam, a model and a few meta-parameters that describe details of the behavior. This function broadcasts on p_cam only. We accept - p_cam: a numpy array of shape (..., 3). This is the set of camera-coordinate points where we're querying uncertainty. if not atinfinity: then the full 3D coordinates of p_cam are significant, even distance to the camera. if atinfinity: the distance to the camera is ignored. - model: a mrcal.cameramodel object that contains optimization_inputs, which are used to propagate the uncertainty - atinfinity: optional boolean, defaults to False. If True, we want to know the projection uncertainty, looking at a point infinitely-far away. We propagate all the uncertainties, ignoring the translation components of the poses - what: optional string, defaults to 'covariance'. This chooses what kind of output we want. Known options are: - 'covariance': return a full (2,2) covariance matrix Var(q) for each p_cam - 'worstdirection-stdev': return the worst-direction standard deviation for each p_cam - 'rms-stdev': return the RMS of the worst and best direction standard deviations - observed_pixel_uncertainty: optional value, defaulting to None. The uncertainty of the pixel observations being propagated through the solve and through projection. If omitted or None, this input uncertainty is inferred from the residuals at the optimum. Most people should omit this RETURN VALUE A numpy array of uncertainties. If p_cam has shape (..., 3) then: if what == 'covariance': we return an array of shape (..., 2,2) else: we return an array of shape (...) ''' # This is a summary of the full derivation in the docs: # # http://mrcal.secretsauce.net/uncertainty.html # # I computed Var(b) earlier, which contains the variance of ALL the optimization # parameters together. The noise on the chessboard poses is coupled to the noise # on the extrinsics and to the noise on the intrinsics. And we can apply all these # together to propagate the uncertainty. # Let's define some variables (these are all subsets of the big optimization # vector): # - b_i: the intrinsics of a camera # - b_e: the extrinsics of that camera (T_cr) # - b_f: ALL the chessboard poses (T_fr) # - b_ief: the concatenation of b_i, b_e and b_f # I have # dq = q0 + dq/db_ief db_ief # Var(q) = dq/db_ief Var(b_ief) (dq/db_ief)t # Var(b_ief) is a subset of Var(b), computed above. # dq/db_ief = [dq/db_i dq/db_e dq/db_f] # dq/db_e = dq/dpcam dpcam/db_e # dq/db_f = dq/dpcam dpcam/dpref dpref/db_f / Nframes # dq/db_i and all the constituent expressions comes directly from the # project() and transform calls above. Depending on the details of the # optimization problem, some of these may not exist. For instance, if we're # looking at a camera that is sitting at the reference coordinate system, # then there is no b_e, and Var_ief is smaller: it's just Var_if. If we # somehow know the poses of the frames, then there's no Var_f. In this case # both fixed frames and fixed discrete points can be processed with the same # code. If we want to know the uncertainty at distance=infinity, then we # ignore all the translation components of b_e and b_f. # Alright, so we have Var(q). We could claim victory at that point. But it'd be # nice to convert Var(q) into a single number that describes my projection # uncertainty at q. Empirically I see that Var(dq) often describes an eccentric # ellipse, so I want to look at the length of the major axis of the 1-sigma # ellipse: # eig (a b) --> (a-l)*(c-l)-b^2 = 0 --> l^2 - (a+c) l + ac-b^2 = 0 # (b c) # --> l = (a+c +- sqrt( a^2+2ac+c^2 - 4ac + 4b^2)) / 2 = # = (a+c +- sqrt( a^2-2ac+c^2 + 4b^2)) / 2 = # = (a+c)/2 +- sqrt( (a-c)^2/4 + b^2) # So the worst-case stdev(q) is # sqrt((a+c)/2 + sqrt( (a-c)^2/4 + b^2)) # which calibration-time camera we're looking at icam_intrinsics = model.icam_intrinsics() optimization_inputs = model.optimization_inputs() if optimization_inputs is None: raise Exception("optimization_inputs are unavailable in this model. Uncertainty cannot be computed") if not optimization_inputs.get('do_optimize_extrinsics'): raise Exception("Computing uncertainty if !do_optimize_extrinsics not supported currently. This is possible, but not implemented. _projection_uncertainty...() would need a path for fixed extrinsics like they already do for fixed frames") frames_rt_toref = None istate_frames = None if optimization_inputs.get('do_optimize_frames'): frames_rt_toref = optimization_inputs.get('frames_rt_toref') points = optimization_inputs.get('points') if frames_rt_toref is not None and frames_rt_toref.size == 0: frames_rt_toref = None if points is not None and points .size == 0: points = None if points is not None: raise Exception("Uncertainty computation not yet implemented if I have non-fixed points") if frames_rt_toref is not None: # None if we're not optimizing chessboard poses, but I just checked, # and we ARE istate_frames = mrcal.state_index_frames(0, **optimization_inputs) # The intrinsics,extrinsics,frames MUST come from the solve when # evaluating the uncertainties. The user is allowed to update the # extrinsics in the model after the solve, as long as I use the # solve-time ones for the uncertainty computation. Updating the # intrinsics invalidates the uncertainty stuff so I COULD grab those # from the model. But for good hygiene I get them from the solve as # well # This will raise an exception if the cameras are not stationary icam_extrinsics = mrcal.corresponding_icam_extrinsics(icam_intrinsics, **optimization_inputs) lensmodel = optimization_inputs['lensmodel'] intrinsics_data = optimization_inputs['intrinsics'][icam_intrinsics] if not optimization_inputs.get('do_optimize_intrinsics_core') and \ not optimization_inputs.get('do_optimize_intrinsics_distortions'): # Not optimizing ANY of the intrinsics istate_intrinsics = None slice_optimized_intrinsics = None else: # Optimizing SOME of the intrinsics istate_intrinsics = mrcal.state_index_intrinsics(icam_intrinsics, **optimization_inputs) i0,i1 = None,None # everything by default has_core = mrcal.lensmodel_metadata_and_config(lensmodel)['has_core'] Ncore = 4 if has_core else 0 Ndistortions = mrcal.lensmodel_num_params(lensmodel) - Ncore if not optimization_inputs.get('do_optimize_intrinsics_core'): i0 = Ncore if not optimization_inputs.get('do_optimize_intrinsics_distortions'): i1 = -Ndistortions slice_optimized_intrinsics = slice(i0,i1) if icam_extrinsics < 0: extrinsics_rt_fromref = None istate_extrinsics = None else: extrinsics_rt_fromref = optimization_inputs['extrinsics_rt_fromref'][icam_extrinsics] istate_extrinsics = mrcal.state_index_extrinsics (icam_extrinsics, **optimization_inputs) Nstate = mrcal.num_states(**optimization_inputs) # Two distinct paths here that are very similar, but different-enough to not # share any code. If atinfinity, I ignore all translations args = ( p_cam, lensmodel, intrinsics_data, extrinsics_rt_fromref, frames_rt_toref, Nstate, istate_intrinsics, istate_extrinsics, istate_frames, slice_optimized_intrinsics ) if not atinfinity: f = _dq_db__projection_uncertainty else: f = _dq_db__projection_uncertainty_rotationonly dq_db = f(*args) return _propagate_calibration_uncertainty(what, dF_db = dq_db, observed_pixel_uncertainty = observed_pixel_uncertainty, optimization_inputs = optimization_inputs) def projection_diff(models, *, implied_Rt10 = None, gridn_width = 60, gridn_height = None, intrinsics_only = False, distance = None, use_uncertainties = True, focus_center = None, focus_radius = -1.): r'''Compute the difference in projection between N models SYNOPSIS models = ( mrcal.cameramodel('cam0-dance0.cameramodel'), mrcal.cameramodel('cam0-dance1.cameramodel') ) difference,_,q0,_ = mrcal.projection_diff(models) print(q0.shape) ==> (40,60) print(difference.shape) ==> (40,60) # The differences are computed across a grid. 'q0' is the pixel centers of # each grid cell. 'difference' is the projection variation between the two # models at each cell The operation of this tool is documented at http://mrcal.secretsauce.net/differencing.html It is often useful to compare the projection behavior of two camera models. For instance, one may want to validate a calibration by comparing the results of two different chessboard dances. Or one may want to evaluate the stability of the intrinsics in response to mechanical or thermal stresses. This function makes these comparisons, and returns the results. A visualization wrapper is available: mrcal.show_projection_diff() and the mrcal-show-projection-diff tool. In the most common case we're given exactly 2 models to compare, and we compute the differences in projection of each point. If we're given more than 2 models, we instead compute the standard deviation of the differences between models 1..N and model0. The top-level operation of this function: - Grid the imager - Unproject each point in the grid using one camera model - Apply a transformation to map this point from one camera's coord system to the other. How we obtain this transformation is described below - Project the transformed points to the other camera - Look at the resulting pixel difference in the reprojection If implied_Rt10 is given, we simply use that as the transformation (this is currently supported ONLY for diffing exactly 2 cameras). If implied_Rt10 is not given, we estimate it. Several variables control this. Top-level logic: if intrinsics_only: Rt10 = identity_Rt() else: if focus_radius == 0: Rt10 = relative_extrinsics(models) else: Rt10 = implied_Rt10__from_unprojections() Sometimes we want to look at the intrinsics differences in isolation (if intrinsics_only), and sometimes we want to use the known geometry in the given models (not intrinsics_only and focus_radius == 0). If neither of these apply, we estimate the transformation: this is needed if we're comparing different calibration results from the same lens. Given different camera models, we have a different set of intrinsics for each. Extrinsics differ also, even if we're looking at different calibration of the same stationary lens: the position and orientation of the camera coordinate system in respect to the physical camera housing shift with each calibration. This geometric variation is baked into the intrinsics. So when we project "the same world point" into both cameras (as is desired when comparing repeated calibrations), we must apply a geometric transformation because we want to be comparing projections of world points (relative to the camera housing), not projections relative to the (floating) camera coordinate systems. This transformation is unknown, but we can estimate it by fitting projections across the imager: the "right" transformation would result in apparent low projection differences in a wide area. This transformation is computed by implied_Rt10__from_unprojections(), and some details of its operation are significant: - The imager area we use for the fit - Which world points we're looking at In most practical usages, we would not expect a good fit everywhere in the imager: areas where no chessboards were observed will not fit well, for instance. From the point of view of the fit we perform, those ill-fitting areas should be treated as outliers, and they should NOT be a part of the solve. How do we specify the well-fitting area? The best way is to use the model uncertainties: these can be used to emphasize the confident regions of the imager. This behavior is selected with use_uncertainties=True, which is the default. If uncertainties aren't available, or if we want a faster solve, pass use_uncertainties=False. The well-fitting region can then be passed using the focus_center,focus_radius arguments to indicate the circle in the imager we care about. If use_uncertainties then the defaults for focus_center,focus_radius are set to utilize all the data in the imager. If not use_uncertainties, then the defaults are to use a more reasonable circle of radius min(width,height)/6 at the center of the imager. Usually this is sufficiently correct, and we don't need to mess with it. If we aren't guided to the correct focus region, the implied-by-the-intrinsics solve will try to fit lots of outliers, which would result in an incorrect transformation, which in turn would produce overly-high reported diffs. A common case when this happens is if the chessboard observations used in the calibration were concentrated to the side of the image (off-center), no uncertainties were used, and the focus_center was not pointed to that area. Unlike the projection operation, the diff operation is NOT invariant under geometric scaling: if we look at the projection difference for two points at different locations along a single observation ray, there will be a variation in the observed diff. This is due to the geometric difference in the two cameras. If the models differed only in their intrinsics parameters, then this variation would not appear. Thus we need to know how far from the camera to look, and this is specified by the "distance" argument. By default (distance = None) we look out to infinity. If we care about the projection difference at some other distance, pass that here. Multiple distances can be passed in an iterable. We'll then fit the implied-by-the-intrinsics transformation using all the distances, and we'll return the differences for each given distance. Generally the most confident distance will be where the chessboards were observed at calibration time. ARGUMENTS - models: iterable of mrcal.cameramodel objects we're comparing. Usually there will be 2 of these, but more than 2 is allowed. The intrinsics are always used; the extrinsics are used only if not intrinsics_only and focus_radius==0 - implied_Rt10: optional transformation to use to line up the camera coordinate systems. Most of the time we want to estimate this transformation, so this should be omitted or None. Currently this is supported only if exactly two models are being compared. - gridn_width: optional value, defaulting to 60. How many points along the horizontal gridding dimension - gridn_height: how many points along the vertical gridding dimension. If None, we compute an integer gridn_height to maintain a square-ish grid: gridn_height/gridn_width ~ imager_height/imager_width - intrinsics_only: optional boolean, defaulting to False. If True: we evaluate the intrinsics of each lens in isolation by assuming that the coordinate systems of each camera line up exactly - distance: optional value, defaulting to None. Has an effect only if not intrinsics_only. The projection difference varies depending on the range to the observed world points, with the queried range set in this 'distance' argument. If None (the default) we look out to infinity. We can compute the implied-by-the-intrinsics transformation off multiple distances if they're given here as an iterable. This is especially useful if we have uncertainties, since then we'll emphasize the best-fitting distances. - use_uncertainties: optional boolean, defaulting to True. Used only if not intrinsics_only and focus_radius!=0. If True we use the whole imager to fit the implied-by-the-intrinsics transformation, using the uncertainties to emphasize the confident regions. If False, it is important to select the confident region using the focus_center and focus_radius arguments. If use_uncertainties is True, but that data isn't available, we report a warning, and try to proceed without. - focus_center: optional array of shape (2,); the imager center by default. Used only if not intrinsics_only and focus_radius!=0. Used to indicate that the implied-by-the-intrinsics transformation should use only those pixels a distance focus_radius from focus_center. This is intended to be used if no uncertainties are available, and we need to manually select the focus region. - focus_radius: optional value. If use_uncertainties then the default is LARGE, to use the whole imager. Else the default is min(width,height)/6. Used to indicate that the implied-by-the-intrinsics transformation should use only those pixels a distance focus_radius from focus_center. This is intended to be used if no uncertainties are available, and we need to manually select the focus region. To avoid computing the transformation, either pass focus_radius=0 (to use the extrinsics in the given models) or pass intrinsics_only=True (to use the identity transform). RETURNED VALUE A tuple - difflen: a numpy array of shape (...,gridn_height,gridn_width) containing the magnitude of differences at each cell, or the standard deviation of the differences between models 1..N and model0 if len(models)>2. if len(models)==2: this is nps.mag(diff). If the given 'distance' argument was an iterable, the shape is (len(distance),...). Otherwise the shape is (...) - diff: a numpy array of shape (...,gridn_height,gridn_width,2) containing the vector of differences at each cell. If len(models)>2 this isn't defined, so None is returned. If the given 'distance' argument was an iterable, the shape is (len(distance),...). Otherwise the shape is (...) - q0: a numpy array of shape (gridn_height,gridn_width,2) containing the pixel coordinates of each grid cell - Rt10: the geometric Rt transformation in an array of shape (...,4,3). This is the relative transformation we ended up using, which is computed using the logic above (using intrinsics_only and focus_radius). if len(models)>2: this is an array of shape (len(models)-1,4,3), with slice i representing the transformation between camera 0 and camera i+1. ''' if len(models) < 2: raise Exception("At least 2 models are required to compute the diff") if len(models) > 2 and implied_Rt10 is not None: raise Exception("A given implied_Rt10 is currently supported ONLY if exactly 2 models are being compared") # If the distance is iterable, the shape of the output is (len(distance), # ...). Otherwise it is just (...). In the intermediate computations, the # quantities ALWAYS have shape (len(distance), ...). I select the desired # shape at the end distance_is_iterable = True try: len(distance) except: distance_is_iterable = False if distance is None: atinfinity = True distance = np.ones((1,), dtype=float) else: atinfinity = False distance = nps.atleast_dims(np.array(distance), -1) distance = nps.mv(distance.ravel(), -1,-4) imagersizes = np.array([model.imagersize() for model in models]) if np.linalg.norm(np.std(imagersizes, axis=-2)) != 0: raise Exception("The diff function needs all the imager dimensions to match. Instead got {}". \ format(imagersizes)) W,H=imagersizes[0] lensmodels = [model.intrinsics()[0] for model in models] intrinsics_data = [model.intrinsics()[1] for model in models] for i in range(len(models)): if mrcal.lensmodel_metadata_and_config(lensmodels[i])['noncentral']: if not atinfinity: raise Exception(f"Model {i} are noncentral, so I can only evaluate the diff at infinity") import re if re.match("LENSMODEL_CAHVORE_",lensmodels[i]): if use_uncertainties: raise Exception("I have a noncentral model. No usable uncertainties for those yet") # Special-case to centralize CAHVORE. This path will need to be # redone when I do noncentral models "properly", but this will # do in the meantime intrinsics_data[i][-3:] = 0 else: raise Exception("I have a non-CAHVORE noncentral model. This isn't supported yet") # v shape (Ncameras,Nheight,Nwidth,3) # q0 shape ( Nheight,Nwidth,2) v,q0 = mrcal.sample_imager_unproject(gridn_width, gridn_height, W, H, lensmodels, intrinsics_data, normalize = True) uncertainties = None if use_uncertainties and \ not intrinsics_only and focus_radius != 0 and \ implied_Rt10 is None: try: # len(uncertainties) = Ncameras. Each has shape (len(distance),Nh,Nw) uncertainties = \ [ mrcal.projection_uncertainty(# shape (len(distance),Nheight,Nwidth,3) v[i] * distance, models[i], atinfinity = atinfinity, what = 'worstdirection-stdev') \ for i in range(len(models)) ] except Exception as e: print(f"WARNING: projection_diff() was asked to use uncertainties, but they aren't available/couldn't be computed. Falling back on the region-based-only logic. Caught exception: {e}", file = sys.stderr) if focus_center is None: focus_center = ((W-1.)/2., (H-1.)/2.) if focus_radius < 0: if uncertainties is not None: focus_radius = max(W,H) * 100 # whole imager else: focus_radius = min(W,H)/6. if len(models) == 2: # Two models. Take the difference and call it good if implied_Rt10 is not None: Rt10 = implied_Rt10 else: if intrinsics_only: Rt10 = mrcal.identity_Rt() else: if focus_radius == 0: Rt10 = mrcal.compose_Rt(models[1].extrinsics_Rt_fromref(), models[0].extrinsics_Rt_toref()) else: # weights has shape (len(distance),Nh,Nw)) if uncertainties is not None: weights = 1.0 / (uncertainties[0]*uncertainties[1]) # It appears to work better if I discount the uncertain regions # even more. This isn't a principled decision, and is supported # only by a little bit of data. The differencing.org I'm writing # now will contain a weighted diff of culled and not-culled # splined model data. That diff computation requires this. weights *= weights else: weights = None # weight may be inf or nan. implied_Rt10__from_unprojections() will # clean those up, as well as any inf/nan in v (from failed # unprojections) Rt10 = \ implied_Rt10__from_unprojections(q0, # shape (len(distance),Nheight,Nwidth,3) v[0,...] * distance, v[1,...], weights = weights, atinfinity = atinfinity, focus_center = focus_center, focus_radius = focus_radius) q1 = mrcal.project( mrcal.transform_point_Rt(Rt10, # shape (len(distance),Nheight,Nwidth,3) v[0,...] * distance), lensmodels[1], intrinsics_data[1]) # shape (len(distance),Nheight,Nwidth,2) q1 = nps.atleast_dims(q1, -4) diff = q1 - q0 difflen = nps.mag(diff) else: # Many models. Look at the stdev def get_Rt10( i0, i1 ): if intrinsics_only: return mrcal.identity_Rt() if focus_radius == 0: return mrcal.compose_Rt(models[i1].extrinsics_Rt_fromref(), models[i0].extrinsics_Rt_toref()) # weights has shape (len(distance),Nh,Nw)) if uncertainties is not None: weights = 1.0 / (uncertainties[i0]*uncertainties[i1]) # It appears to work better if I discount the uncertain regions # even more. This isn't a principled decision, and is supported # only by a little bit of data. The differencing.org I'm writing # now will contain a weighted diff of culled and not-culled # splined model data. That diff computation requires this. weights *= weights else: weights = None v0 = v[i0,...] v1 = v[i1,...] return \ implied_Rt10__from_unprojections(q0, # shape (len(distance),Nheight,Nwidth,3) v0*distance, v1, weights = weights, atinfinity = atinfinity, focus_center = focus_center, focus_radius = focus_radius) def get_reprojections(q0, Rt10, lensmodel, intrinsics_data): q1 = mrcal.project(mrcal.transform_point_Rt(Rt10, # shape (len(distance),Nheight,Nwidth,3) v[0,...]*distance), lensmodel, intrinsics_data) # returning shape (len(distance),Nheight,Nwidth,2) return nps.atleast_dims(q1, -4) Ncameras = len(v) # shape (Ncameras-1, 4,3) Rt10 = nps.cat(*[ get_Rt10(0,i) for i in range(1,Ncameras)]) # shape (Ncameras-1,len(distance),Nheight,Nwidth,2) grids = nps.cat(*[get_reprojections(q0, Rt10[i-1], lensmodels[i], intrinsics_data[i]) \ for i in range(1,Ncameras)]) diff = None # shape (len(distance),Nheight,Nwidth) difflen = np.sqrt(np.mean(nps.norm2(grids-q0),axis=0)) # difflen, diff, q0 currently all have shape (len(distance), ...). If the # given distance was NOT an iterable, I strip out that leading dimension if not distance_is_iterable: if difflen.shape[0] != 1: raise Exception(f"distance_is_iterable is False, but leading shape of difflen is not 1 (difflen.shape = {difflen.shape}). This is a bug. Giving up") difflen = difflen[0,...] if diff is not None: if diff.shape[0] != 1: raise Exception(f"distance_is_iterable is False, but leading shape of diff is not 1 (diff.shape = {diff.shape}). This is a bug. Giving up") diff = diff[0,...] return difflen, diff, q0, Rt10 def is_within_valid_intrinsics_region(q, model): r'''Which of the pixel coordinates fall within the valid-intrinsics region? SYNOPSIS mask = mrcal.is_within_valid_intrinsics_region(q, model) q_trustworthy = q[mask] mrcal camera models may have an estimate of the region of the imager where the intrinsics are trustworthy (originally computed with a low-enough error and uncertainty). When using a model, we may want to process points that fall outside of this region differently from points that fall within this region. This function returns a mask that indicates whether each point is within the region or not. If no valid-intrinsics region is defined in the model, returns None. ARGUMENTS - q: an array of shape (..., 2) of pixel coordinates - model: the model we're interrogating RETURNED VALUE The mask that indicates whether each point is within the region ''' r = model.valid_intrinsics_region() if r is None: return None from shapely.geometry import Polygon,Point r = Polygon(r) mask = np.zeros(q.shape[:-1], dtype=bool) mask_flat = mask.ravel() q_flat = q.reshape(q.size//2, 2) for i in range(q.size // 2): if r.contains(Point(q_flat[i])): mask_flat[i] = True return mask mrcal-2.4.1/mrcal/poseutils.py000066400000000000000000001331631456301662300163300ustar00rootroot00000000000000#!/usr/bin/python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 '''Routines to manipulate poses, transformations and points Most of these are Python wrappers around the written-in-C Python extension module mrcal._poseutils_npsp. Most of the time you want to use this module instead of touching mrcal._poseutils_npsp directly. All functions are exported into the mrcal module. So you can call these via mrcal.poseutils.fff() or mrcal.fff(). The latter is preferred. ''' import numpy as np import numpysane as nps # for python3 from functools import reduce from . import _poseutils_npsp from . import _poseutils_scipy def r_from_R(R, *, get_gradients=False, out=None): r"""Compute a Rodrigues vector from a rotation matrix SYNOPSIS r = mrcal.r_from_R(R) rotation_magnitude = nps.mag(r) rotation_axis = r / rotation_magnitude Given a rotation specified as a (3,3) rotation matrix, converts it to a Rodrigues vector, a unit rotation axis scaled by the rotation magnitude, in radians. By default this function returns the Rodrigues vector(s) only. If we also want gradients, pass get_gradients=True. Logic: if not get_gradients: return r else: return (r, dr/dR) This function supports broadcasting fully. ARGUMENTS - R: array of shape (3,3). This matrix defines the rotation. It is assumed that this is a valid rotation (matmult(R,transpose(R)) = I, det(R) = 1), but that is not checked - get_gradients: optional boolean. By default (get_gradients=False) we return an array of Rodrigues vectors. Otherwise we return a tuple of arrays of Rodrigues vectors and their gradients. - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE If not get_gradients: we return an array of Rodrigues vector(s). Each broadcasted slice has shape (3,) If get_gradients: we return a tuple of arrays containing the Rodrigues vector(s) and the gradients (r, dr/dR) 1. The Rodrigues vector. Each broadcasted slice has shape (3,) 2. The gradient dr/dR. Each broadcasted slice has shape (3,3,3). The first dimension selects the element of r, and the last two dimensions select the element of R """ if get_gradients: return _poseutils_npsp._r_from_R_withgrad(R, out=out) return _poseutils_npsp._r_from_R(R, out=out) def R_from_r(r, *, get_gradients=False, out=None): r"""Compute a rotation matrix from a Rodrigues vector SYNOPSIS r = rotation_axis * rotation_magnitude R = mrcal.R_from_r(r) Given a rotation specified as a Rodrigues vector (a unit rotation axis scaled by the rotation magnitude, in radians.), converts it to a rotation matrix. By default this function returns the rotation matrices only. If we also want gradients, pass get_gradients=True. Logic: if not get_gradients: return R else: return (R, dR/dr) This function supports broadcasting fully. ARGUMENTS - r: array of shape (3,). The Rodrigues vector that defines the rotation. This is a unit rotation axis scaled by the rotation magnitude, in radians - get_gradients: optional boolean. By default (get_gradients=False) we return an array of rotation matrices. Otherwise we return a tuple of arrays of rotation matrices and their gradients. - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE If not get_gradients: we return an array of rotation matrices. Each broadcasted slice has shape (3,3) If get_gradients: we return a tuple of arrays containing the rotation matrices and the gradient (R, dR/dr): 1. The rotation matrix. Each broadcasted slice has shape (3,3). This is a valid rotation: matmult(R,transpose(R)) = I, det(R) = 1 2. The gradient dR/dr. Each broadcasted slice has shape (3,3,3). The first two dimensions select the element of R, and the last dimension selects the element of r """ if get_gradients: return _poseutils_npsp._R_from_r_withgrad(r, out=out) return _poseutils_npsp._R_from_r(r, out=out) def invert_R(R, *, out=None): r"""Invert a rotation matrix SYNOPSIS print(R.shape) ===> (3,3) R10 = mrcal.invert_R(R01) print(x1.shape) ===> (3,) x0 = mrcal.rotate_point_R(R01, x1) print( nps.norm2( x1 - \ mrcal.rotate_point_R(R10, x0) )) ===> 0 Given a rotation specified as a (3,3) rotation matrix outputs another rotation matrix that has the opposite effect. This is simply a matrix transpose. This function supports broadcasting fully. In-place operation is supported; the output array may be the same as the input array to overwrite the input. ARGUMENTS - R: array of shape (3,3), a rotation matrix. It is assumed that this is a valid rotation (matmult(R,transpose(R)) = I, det(R) = 1), but that is not checked - out: optional argument specifying the destination. By default, a new numpy array is created and returned. To write the results into an existing (and possibly non-contiguous) array, specify it with the 'out' kwarg. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE The inverse rotation matrix in an array of shape (3,3). """ return _poseutils_npsp._invert_R(R, out=out) def rt_from_Rt(Rt, *, get_gradients=False, out=None): r"""Compute an rt transformation from a Rt transformation SYNOPSIS Rt = nps.glue(rotation_matrix,translation, axis=-2) print(Rt.shape) ===> (4,3) rt = mrcal.rt_from_Rt(Rt) print(rt.shape) ===> (6,) translation = rt[3:] rotation_magnitude = nps.mag(rt[:3]) rotation_axis = rt[:3] / rotation_magnitude Converts an Rt transformation to an rt transformation. Both specify a rotation and translation. An Rt transformation is a (4,3) array formed by nps.glue(R,t, axis=-2) where R is a (3,3) rotation matrix and t is a (3,) translation vector. An rt transformation is a (6,) array formed by nps.glue(r,t, axis=-1) where r is a (3,) Rodrigues vector and t is a (3,) translation vector. Applied to a point x the transformed result is rotate(x)+t. Given a matrix R, the rotation is defined by a matrix multiplication. x and t are stored as a row vector (that's how numpy stores 1-dimensional arrays), but the multiplication works as if x was a column vector (to match linear algebra conventions). See the docs for mrcal._transform_point_Rt() for more detail. By default this function returns the rt transformations only. If we also want gradients, pass get_gradients=True. Logic: if not get_gradients: return rt else: return (rt, dr/dR) Note that the translation gradient isn't returned: it is always the identity This function supports broadcasting fully. ARGUMENTS - Rt: array of shape (4,3). This matrix defines the transformation. Rt[:3,:] is a rotation matrix; Rt[3,:] is a translation. It is assumed that the rotation matrix is a valid rotation (matmult(R,transpose(R)) = I, det(R) = 1), but that is not checked - get_gradients: optional boolean. By default (get_gradients=False) we return an array of rt transformations. Otherwise we return a tuple of arrays of rt transformations and their gradients. - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE If not get_gradients: we return the rt transformation. Each broadcasted slice has shape (6,). rt[:3] is a rotation defined as a Rodrigues vector; rt[3:] is a translation. If get_gradients: we return a tuple of arrays containing the rt transformation and the gradient (rt, dr/dR): 1. The rt transformation. Each broadcasted slice has shape (6,) 2. The gradient dr/dR. Each broadcasted slice has shape (3,3,3). The first dimension selects the element of r, and the last two dimension select the element of R """ if get_gradients: return _poseutils_npsp._rt_from_Rt_withgrad(Rt, out=out) return _poseutils_npsp._rt_from_Rt(Rt, out=out) def Rt_from_rt(rt, *, get_gradients=False, out=None): r"""Compute an Rt transformation from a rt transformation SYNOPSIS r = rotation_axis * rotation_magnitude rt = nps.glue(r,t, axis=-1) print(rt.shape) ===> (6,) Rt = mrcal.Rt_from_rt(rt) print(Rt.shape) ===> (4,3) translation = Rt[3,:] rotation_matrix = Rt[:3,:] Converts an rt transformation to an Rt transformation. Both specify a rotation and translation. An Rt transformation is a (4,3) array formed by nps.glue(R,t, axis=-2) where R is a (3,3) rotation matrix and t is a (3,) translation vector. An rt transformation is a (6,) array formed by nps.glue(r,t, axis=-1) where r is a (3,) Rodrigues vector and t is a (3,) translation vector. Applied to a point x the transformed result is rotate(x)+t. Given a matrix R, the rotation is defined by a matrix multiplication. x and t are stored as a row vector (that's how numpy stores 1-dimensional arrays), but the multiplication works as if x was a column vector (to match linear algebra conventions). See the docs for mrcal._transform_point_Rt() for more detail. By default this function returns the Rt transformations only. If we also want gradients, pass get_gradients=True. Logic: if not get_gradients: return Rt else: return (Rt, dR/dr) Note that the translation gradient isn't returned: it is always the identity This function supports broadcasting fully. ARGUMENTS - rt: array of shape (6,). This vector defines the input transformation. rt[:3] is a rotation defined as a Rodrigues vector; rt[3:] is a translation. - get_gradients: optional boolean. By default (get_gradients=False) we return an array of Rt transformations. Otherwise we return a tuple of arrays of Rt transformations and their gradients. - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE If not get_gradients: we return the Rt transformation. Each broadcasted slice has shape (4,3). Rt[:3,:] is a rotation matrix; Rt[3,:] is a translation. The matrix R is a valid rotation: matmult(R,transpose(R)) = I and det(R) = 1 If get_gradients: we return a tuple of arrays containing the Rt transformation and the gradient (Rt, dR/dr): 1. The Rt transformation. Each broadcasted slice has shape (4,3,) 2. The gradient dR/dr. Each broadcasted slice has shape (3,3,3). The first two dimensions select the element of R, and the last dimension selects the element of r """ if get_gradients: return _poseutils_npsp._Rt_from_rt_withgrad(rt, out=out) return _poseutils_npsp._Rt_from_rt(rt, out=out) def invert_Rt(Rt, *, out=None): r"""Invert an Rt transformation SYNOPSIS Rt01 = nps.glue(rotation_matrix,translation, axis=-2) print(Rt01.shape) ===> (4,3) Rt10 = mrcal.invert_Rt(Rt01) print(x1.shape) ===> (3,) x0 = mrcal.transform_point_Rt(Rt01, x1) print( nps.norm2( x1 - \ mrcal.transform_point_Rt(Rt10, x0) )) ===> 0 Given an Rt transformation to convert a point representated in coordinate system 1 to coordinate system 0 (let's call it Rt01), returns a transformation that does the reverse: converts a representation in coordinate system 0 to coordinate system 1 (let's call it Rt10). Thus if you have a point in coordinate system 1 (let's call it x1), we can convert it to a representation in system 0, and then back. And we'll get the same thing out: x1 == mrcal.transform_point_Rt( mrcal.invert_Rt(Rt01), mrcal.transform_point_Rt( Rt01, x1 )) An Rt transformation represents a rotation and a translation. It is a (4,3) array formed by nps.glue(R,t, axis=-2) where R is a (3,3) rotation matrix and t is a (3,) translation vector. Applied to a point x the transformed result is rotate(x)+t. Given a matrix R, the rotation is defined by a matrix multiplication. x and t are stored as a row vector (that's how numpy stores 1-dimensional arrays), but the multiplication works as if x was a column vector (to match linear algebra conventions). See the docs for mrcal._transform_point_Rt() for more detail. This function supports broadcasting fully. In-place operation is supported; the output array may be the same as the input array to overwrite the input. ARGUMENTS - Rt: array of shape (4,3). This matrix defines the transformation. Rt[:3,:] is a rotation matrix; Rt[3,:] is a translation. It is assumed that the rotation matrix is a valid rotation (matmult(R,transpose(R)) = I, det(R) = 1), but that is not checked - out: optional argument specifying the destination. By default, a new numpy array is created and returned. To write the results into an existing (and possibly non-contiguous) array, specify it with the 'out' kwarg. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE The inverse Rt transformation in an array of shape (4,3). """ return _poseutils_npsp._invert_Rt(Rt, out=out) def invert_rt(rt, *, get_gradients=False, out=None): r"""Invert an rt transformation SYNOPSIS r = rotation_axis * rotation_magnitude rt01 = nps.glue(r,t, axis=-1) print(rt01.shape) ===> (6,) rt10 = mrcal.invert_rt(rt01) print(x1.shape) ===> (3,) x0 = mrcal.transform_point_rt(rt01, x1) print( nps.norm2( x1 - mrcal.transform_point_rt(rt10, x0) )) ===> 0 Given an rt transformation to convert a point representated in coordinate system 1 to coordinate system 0 (let's call it rt01), returns a transformation that does the reverse: converts a representation in coordinate system 0 to coordinate system 1 (let's call it rt10). Thus if you have a point in coordinate system 1 (let's call it x1), we can convert it to a representation in system 0, and then back. And we'll get the same thing out: x1 == mrcal.transform_point_rt( mrcal.invert_rt(rt01), mrcal.transform_point_rt( rt01, x1 )) An rt transformation represents a rotation and a translation. It is a (6,) array formed by nps.glue(r,t, axis=-1) where r is a (3,) Rodrigues vector and t is a (3,) translation vector. Applied to a point x the transformed result is rotate(x)+t. x and t are stored as a row vector (that's how numpy stores 1-dimensional arrays). See the docs for mrcal._transform_point_rt() for more detail. By default this function returns the rt transformation only. If we also want gradients, pass get_gradients=True. Logic: if not get_gradients: return rt else: return (rt, drtout_drtin) Note that the poseutils C API returns only - dtout_drin - dtout_dtin because - drout_drin is always -I - drout_dtin is always 0 This Python function, however fills in those constants to return the full (and more convenient) arrays. This function supports broadcasting fully. In-place operation is supported; the output array may be the same as the input array to overwrite the input. ARGUMENTS - rt: array of shape (6,). This vector defines the input transformation. rt[:3] is a rotation defined as a Rodrigues vector; rt[3:] is a translation. - get_gradients: optional boolean. By default (get_gradients=False) we return an array of rt translation. Otherwise we return a tuple of arrays of rt translations and their gradients. - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE If not get_gradients: we return an array of rt transformation(s). Each broadcasted slice has shape (6,) If get_gradients: we return a tuple of arrays containing the rt transformation(s) and the gradients (rt, drtout/drtin) 1. The rt transformation. Each broadcasted slice has shape (6,) 2. The gradient drtout/drtin. Each broadcasted slice has shape (6,6). The first dimension selects elements of rtout, and the last dimension selects elements of rtin """ if get_gradients: return _poseutils_npsp._invert_rt_withgrad(rt, out=out) return _poseutils_npsp._invert_rt(rt, out=out) def compose_Rt(*Rt, out=None): r"""Compose Rt transformations SYNOPSIS Rt10 = nps.glue(rotation_matrix10,translation10, axis=-2) Rt21 = nps.glue(rotation_matrix21,translation21, axis=-2) Rt32 = nps.glue(rotation_matrix32,translation32, axis=-2) print(Rt10.shape) ===> (4,3) Rt30 = mrcal.compose_Rt( Rt32, Rt21, Rt10 ) print(x0.shape) ===> (3,) print( nps.norm2( mrcal.transform_point_Rt(Rt30, x0) - mrcal.transform_point_Rt(Rt32, mrcal.transform_point_Rt(Rt21, mrcal.transform_point_Rt(Rt10, x0))))) ===> 0 Given 2 or more Rt transformations, returns their composition. An Rt transformation is a (4,3) array formed by nps.glue(R,t, axis=-2) where R is a (3,3) rotation matrix and t is a (3,) translation vector. This transformation is defined by a matrix multiplication and an addition. x and t are stored as a row vector (that's how numpy stores 1-dimensional arrays), but the multiplication works as if x was a column vector (to match linear algebra conventions): transform_point_Rt(Rt, x) = transpose( matmult(Rt[:3,:], transpose(x)) + transpose(Rt[3,:]) ) = = matmult(x, transpose(Rt[:3,:])) + Rt[3,:] This function supports broadcasting fully, so we can compose lots of transformations at the same time. In-place operation is supported; the output array may be the same as either of the input arrays to overwrite the input. ARGUMENTS - *Rt: a list of transformations to compose. Usually we'll be composing two transformations, but any number could be given here. Each broadcasted slice has shape (4,3). - out: optional argument specifying the destination. By default, a new numpy array is created and returned. To write the results into an existing (and possibly non-contiguous) array, specify it with the 'out' kwarg. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE An array of composed Rt transformations. Each broadcasted slice has shape (4,3) """ Rt1onwards = reduce( _poseutils_npsp._compose_Rt, Rt[1:] ) return _poseutils_npsp._compose_Rt(Rt[0], Rt1onwards, out=out) def compose_r(*r, get_gradients=False, out=None): r"""Compose angle-axis rotations SYNOPSIS r10 = rotation_axis10 * rotation_magnitude10 r21 = rotation_axis21 * rotation_magnitude21 r32 = rotation_axis32 * rotation_magnitude32 print(r10.shape) ===> (3,) r30 = mrcal.compose_r( r32, r21, r10 ) print(x0.shape) ===> (3,) print( nps.norm2( mrcal.rotate_point_r(r30, x0) - mrcal.rotate_point_r(r32, mrcal.rotate_point_r(r21, mrcal.rotate_point_r(r10, x0))))) ===> 0 print( [arr.shape for arr in mrcal.compose_r(r21,r10, get_gradients = True)] ) ===> [(3,), (3,3), (3,3)] Given 2 or more axis-angle rotations, returns their composition. By default this function returns the composed rotation only. If we also want gradients, pass get_gradients=True. This is supported ONLY if we have EXACTLY 2 rotations to compose. Logic: if not get_gradients: return r=compose(r0,r1) else: return (r=compose(r0,r1), dr/dr0, dr/dr1) This function supports broadcasting fully, so we can compose lots of rotations at the same time. In-place operation is supported; the output array may be the same as either of the input arrays to overwrite the input. ARGUMENTS - *r: a list of rotations to compose. Usually we'll be composing two rotations, but any number could be given here. Each broadcasted slice has shape (3,) - get_gradients: optional boolean. By default (get_gradients=False) we return an array of composed rotations. Otherwise we return a tuple of arrays of composed rotations and their gradients. Gradient reporting is only supported when exactly two rotations are given - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE If not get_gradients: we return an array of composed rotations. Each broadcasted slice has shape (3,) If get_gradients: we return a tuple of arrays containing the composed rotations and the gradients (r=compose(r0,r1), dr/dr0, dr/dr1): 1. The composed rotation. Each broadcasted slice has shape (3,) 2. The gradient dr/dr0. Each broadcasted slice has shape (3,3). The first dimension selects the element of r, and the last dimension selects the element of r0 3. The gradient dr/dr1. Each broadcasted slice has shape (3,3). The first dimension selects the element of r, and the last dimension selects the element of r1 """ if get_gradients: if len(r) != 2: raise Exception("compose_r(..., get_gradients=True) is supported only if exactly 2 inputs are given") return _poseutils_npsp._compose_r_withgrad(*r, out=out) r1onwards = reduce( _poseutils_npsp._compose_r, r[1:] ) return _poseutils_npsp._compose_r(r[0], r1onwards, out=out) def compose_rt(*rt, get_gradients=False, out=None): r"""Compose rt transformations SYNOPSIS r10 = rotation_axis10 * rotation_magnitude10 r21 = rotation_axis21 * rotation_magnitude21 r32 = rotation_axis32 * rotation_magnitude32 rt10 = nps.glue(r10,t10, axis=-1) rt21 = nps.glue(r21,t21, axis=-1) rt32 = nps.glue(r32,t32, axis=-1) print(rt10.shape) ===> (6,) rt30 = mrcal.compose_rt( rt32, rt21, rt10 ) print(x0.shape) ===> (3,) print( nps.norm2( mrcal.transform_point_rt(rt30, x0) - mrcal.transform_point_rt(rt32, mrcal.transform_point_rt(rt21, mrcal.transform_point_rt(rt10, x0))))) ===> 0 print( [arr.shape for arr in mrcal.compose_rt(rt21,rt10, get_gradients = True)] ) ===> [(6,), (6,6), (6,6)] Given 2 or more rt transformations, returns their composition. An rt transformation is a (6,) array formed by nps.glue(r,t, axis=-1) where r is a (3,) Rodrigues vector and t is a (3,) translation vector. This transformation is defined by a matrix multiplication and an addition. x and t are stored as a row vector (that's how numpy stores 1-dimensional arrays), but the multiplication works as if x was a column vector (to match linear algebra conventions): transform_point_rt(rt, x) = transpose( matmult(R_from_r(rt[:3]), transpose(x)) + transpose(rt[3,:]) ) = = matmult(x, transpose(R_from_r(rt[:3]))) + rt[3:] By default this function returns the composed transformation only. If we also want gradients, pass get_gradients=True. This is supported ONLY if we have EXACTLY 2 transformations to compose. Logic: if not get_gradients: return rt=compose(rt0,rt1) else: return (rt=compose(rt0,rt1), dr/drt0, dr/drt1) Note that the poseutils C API returns only - dr_dr0 - dr_dr1 - dt_dr0 - dt_dt1 because - dr/dt0 is always 0 - dr/dt1 is always 0 - dt/dr1 is always 0 - dt/dt0 is always the identity matrix This Python function, however fills in those constants to return the full (and more convenient) arrays. This function supports broadcasting fully, so we can compose lots of transformations at the same time. In-place operation is supported; the output array may be the same as either of the input arrays to overwrite the input. ARGUMENTS - *rt: a list of transformations to compose. Usually we'll be composing two transformations, but any number could be given here. Each broadcasted slice has shape (6,) - get_gradients: optional boolean. By default (get_gradients=False) we return an array of composed transformations. Otherwise we return a tuple of arrays of composed transformations and their gradients. Gradient reporting is only supported when exactly two transformations are given - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE If not get_gradients: we return an array of composed rt transformations. Each broadcasted slice has shape (6,) If get_gradients: we return a tuple of arrays containing the composed transformations and the gradients (rt=compose(rt0,rt1), drt/drt0,drt/drt1): 1. The composed transformation. Each broadcasted slice has shape (6,) 2. The gradient drt/dr0. Each broadcasted slice has shape (6,6). The first dimension selects the element of rt, and the last dimension selects the element of rt0 3. The gradient drt/drt1. Each broadcasted slice has shape (6,6). The first dimension selects the element of rt, and the last dimension selects the element of rt1 """ if get_gradients: if len(rt) != 2: raise Exception("compose_rt(..., get_gradients=True) is supported only if exactly 2 inputs are given") return _poseutils_npsp._compose_rt_withgrad(*rt, out=out) rt1onwards = reduce( _poseutils_npsp._compose_rt, rt[1:] ) return _poseutils_npsp._compose_rt(rt[0], rt1onwards, out=out) def rotate_point_r(r, x, *, get_gradients=False, out=None, inverted=False): r"""Rotate point(s) using a Rodrigues vector SYNOPSIS r = rotation_axis * rotation_magnitude print(r.shape) ===> (3,) print(x.shape) ===> (10,3) print(mrcal.rotate_point_r(r, x).shape) ===> (10,3) print( [arr.shape for arr in mrcal.rotate_point_r(r, x, get_gradients = True)] ) ===> [(10,3), (10,3,3), (10,3,3)] Rotate point(s) by a rotation matrix. The Rodrigues vector is converted to a rotation matrix internally, and then this function is a matrix multiplication. x is stored as a row vector (that's how numpy stores 1-dimensional arrays), but the multiplication works as if x was a column vector (to match linear algebra conventions): rotate_point_r(r,x) = transpose( matmult(R(r), transpose(x))) = = matmult(x, transpose(R(r))) By default this function returns the rotated points only. If we also want gradients, pass get_gradients=True. Logic: if not get_gradients: return u=r(x) else: return (u=r(x),du/dr,du/dx) This function supports broadcasting fully, so we can rotate lots of points at the same time and/or apply lots of different rotations at the same time In-place operation is supported; the output array may be the same as the input arrays to overwrite the input. ARGUMENTS - r: array of shape (3,). The Rodrigues vector that defines the rotation. This is a unit rotation axis scaled by the rotation magnitude, in radians - x: array of shape (3,). The point being rotated - get_gradients: optional boolean. By default (get_gradients=False) we return an array of rotated points. Otherwise we return a tuple of arrays of rotated points and their gradients. - inverted: optional boolean, defaulting to False. If True, the opposite rotation is computed. The gradient du/dr is returned in respect to the input r - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE If not get_gradients: we return an array of rotated point(s). Each broadcasted slice has shape (3,) If get_gradients: we return a tuple of arrays containing the rotated points and the gradients (u=r(x),du/dr,du/dx): A tuple (u=r(x),du/dr,du/dx): 1. The rotated point(s). Each broadcasted slice has shape (3,) 2. The gradient du/dr. Each broadcasted slice has shape (3,3). The first dimension selects the element of u, and the last dimension selects the element of r 3. The gradient du/dx. Each broadcasted slice has shape (3,3). The first dimension selects the element of u, and the last dimension selects the element of x """ if not get_gradients: return _poseutils_npsp._rotate_point_r(r,x, out=out, inverted=inverted) return _poseutils_npsp._rotate_point_r_withgrad(r,x, out=out, inverted=inverted) def rotate_point_R(R, x, *, get_gradients=False, out=None, inverted=False): r"""Rotate point(s) using a rotation matrix SYNOPSIS r = rotation_axis * rotation_magnitude R = mrcal.R_from_r(r) print(R.shape) ===> (3,3) print(x.shape) ===> (10,3) print( mrcal.rotate_point_R(R, x).shape ) ===> (10,3) print( [arr.shape for arr in mrcal.rotate_point_R(R, x, get_gradients = True)] ) ===> [(10,3), (10,3,3,3), (10,3,3)] Rotate point(s) by a rotation matrix. This is a matrix multiplication. x is stored as a row vector (that's how numpy stores 1-dimensional arrays), but the multiplication works as if x was a column vector (to match linear algebra conventions): rotate_point_R(R,x) = transpose( matmult(R, transpose(x))) = = matmult(x, transpose(R)) By default this function returns the rotated points only. If we also want gradients, pass get_gradients=True. Logic: if not get_gradients: return u=R(x) else: return (u=R(x),du/dR,du/dx) This function supports broadcasting fully, so we can rotate lots of points at the same time and/or apply lots of different rotations at the same time In-place operation is supported; the output array may be the same as the input arrays to overwrite the input. ARGUMENTS - R: array of shape (3,3). This matrix defines the rotation. It is assumed that this is a valid rotation (matmult(R,transpose(R)) = I, det(R) = 1), but that is not checked - x: array of shape (3,). The point being rotated - get_gradients: optional boolean. By default (get_gradients=False) we return an array of rotated points. Otherwise we return a tuple of arrays of rotated points and their gradients. - inverted: optional boolean, defaulting to False. If True, the opposite rotation is computed. The gradient du/dR is returned in respect to the input R - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE If not get_gradients: we return an array of rotated point(s). Each broadcasted slice has shape (3,) If get_gradients: we return a tuple of arrays containing the rotated points and the gradients (u=R(x),du/dR,du/dx): 1. The rotated point(s). Each broadcasted slice has shape (3,) 2. The gradient du/dR. Each broadcasted slice has shape (3,3,3). The first dimension selects the element of u, and the last 2 dimensions select the element of R 3. The gradient du/dx. Each broadcasted slice has shape (3,3). The first dimension selects the element of u, and the last dimension selects the element of x """ if not get_gradients: return _poseutils_npsp._rotate_point_R(R,x, out=out, inverted=inverted) return _poseutils_npsp._rotate_point_R_withgrad(R,x, out=out, inverted=inverted) def transform_point_rt(rt, x, *, get_gradients=False, out=None, inverted=False): r"""Transform point(s) using an rt transformation SYNOPSIS r = rotation_axis * rotation_magnitude rt = nps.glue(r,t, axis=-1) print(rt.shape) ===> (6,) print(x.shape) ===> (10,3) print( mrcal.transform_point_rt(rt, x).shape ) ===> (10,3) print( [arr.shape for arr in mrcal.transform_point_rt(rt, x, get_gradients = True)] ) ===> [(10,3), (10,3,6), (10,3,3)] Transform point(s) by an rt transformation: a (6,) array formed by nps.glue(r,t, axis=-1) where r is a (3,) Rodrigues vector and t is a (3,) translation vector. This transformation is defined by a matrix multiplication and an addition. x and t are stored as a row vector (that's how numpy stores 1-dimensional arrays), but the multiplication works as if x was a column vector (to match linear algebra conventions): transform_point_rt(rt, x) = transpose( matmult(R_from_r(rt[:3]), transpose(x)) + transpose(rt[3,:]) ) = = matmult(x, transpose(R_from_r(rt[:3]))) + rt[3:] By default this function returns the transformed points only. If we also want gradients, pass get_gradients=True. Logic: if not get_gradients: return u=rt(x) else: return (u=rt(x),du/drt,du/dx) This function supports broadcasting fully, so we can transform lots of points at the same time and/or apply lots of different transformations at the same time In-place operation is supported; the output array may be the same as the input arrays to overwrite the input. ARGUMENTS - rt: array of shape (6,). This vector defines the transformation. rt[:3] is a rotation defined as a Rodrigues vector; rt[3:] is a translation. - x: array of shape (3,). The point being transformed - get_gradients: optional boolean. By default (get_gradients=False) we return an array of transformed points. Otherwise we return a tuple of arrays of transformed points and their gradients. - inverted: optional boolean, defaulting to False. If True, the opposite transformation is computed. The gradient du/drt is returned in respect to the input rt - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE If not get_gradients: we return an array of transformed point(s). Each broadcasted slice has shape (3,) If get_gradients: we return a tuple of arrays of transformed points and the gradients (u=rt(x),du/drt,du/dx): 1. The transformed point(s). Each broadcasted slice has shape (3,) 2. The gradient du/drt. Each broadcasted slice has shape (3,6). The first dimension selects the element of u, and the last dimension selects the element of rt 3. The gradient du/dx. Each broadcasted slice has shape (3,3). The first dimension selects the element of u, and the last dimension selects the element of x """ if not get_gradients: return _poseutils_npsp._transform_point_rt(rt,x, out=out, inverted=inverted) return _poseutils_npsp._transform_point_rt_withgrad(rt,x, out=out, inverted=inverted) def transform_point_Rt(Rt, x, *, get_gradients=False, out=None, inverted=False): r"""Transform point(s) using an Rt transformation SYNOPSIS Rt = nps.glue(rotation_matrix,translation, axis=-2) print(Rt.shape) ===> (4,3) print(x.shape) ===> (10,3) print( mrcal.transform_point_Rt(Rt, x).shape ) ===> (10,3) print( [arr.shape for arr in mrcal.transform_point_Rt(Rt, x, get_gradients = True)] ) ===> [(10,3), (10,3,4,3), (10,3,3)] Transform point(s) by an Rt transformation: a (4,3) array formed by nps.glue(R,t, axis=-2) where R is a (3,3) rotation matrix and t is a (3,) translation vector. This transformation is defined by a matrix multiplication and an addition. x and t are stored as a row vector (that's how numpy stores 1-dimensional arrays), but the multiplication works as if x was a column vector (to match linear algebra conventions): transform_point_Rt(Rt, x) = transpose( matmult(Rt[:3,:], transpose(x)) + transpose(Rt[3,:]) ) = = matmult(x, transpose(Rt[:3,:])) + Rt[3,:] By default this function returns the transformed points only. If we also want gradients, pass get_gradients=True. Logic: if not get_gradients: return u=Rt(x) else: return (u=Rt(x),du/dRt,du/dx) This function supports broadcasting fully, so we can transform lots of points at the same time and/or apply lots of different transformations at the same time In-place operation is supported; the output array may be the same as the input arrays to overwrite the input. ARGUMENTS - Rt: array of shape (4,3). This matrix defines the transformation. Rt[:3,:] is a rotation matrix; Rt[3,:] is a translation. It is assumed that the rotation matrix is a valid rotation (matmult(R,transpose(R)) = I, det(R) = 1), but that is not checked - x: array of shape (3,). The point being transformed - get_gradients: optional boolean. By default (get_gradients=False) we return an array of transformed points. Otherwise we return a tuple of arrays of transformed points and their gradients. - inverted: optional boolean, defaulting to False. If True, the opposite transformation is computed. The gradient du/dRt is returned in respect to the input Rt - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE If not get_gradients: we return an array of transformed point(s). Each broadcasted slice has shape (3,) If get_gradients: we return a tuple of arrays of transformed points and the gradients (u=Rt(x),du/dRt,du/dx): 1. The transformed point(s). Each broadcasted slice has shape (3,) 2. The gradient du/dRt. Each broadcasted slice has shape (3,4,3). The first dimension selects the element of u, and the last 2 dimensions select the element of Rt 3. The gradient du/dx. Each broadcasted slice has shape (3,3). The first dimension selects the element of u, and the last dimension selects the element of x """ if not get_gradients: return _poseutils_npsp._transform_point_Rt(Rt,x, out=out, inverted=inverted) return _poseutils_npsp._transform_point_Rt_withgrad(Rt,x, out=out, inverted=inverted) from . import _poseutils_scipy quat_from_R = _poseutils_scipy.quat_from_R def qt_from_Rt(Rt, *, out=None): r"""Compute a qt transformation from a Rt transformation SYNOPSIS Rt = nps.glue(rotation_matrix,translation, axis=-2) print(Rt.shape) ===> (4,3) qt = mrcal.qt_from_Rt(Rt) print(qt.shape) ===> (7,) quat = qt[:4] translation = qt[4:] Converts an Rt transformation to a qt transformation. Both specify a rotation and translation. An Rt transformation is a (4,3) array formed by nps.glue(R,t, axis=-2) where R is a (3,3) rotation matrix and t is a (3,) translation vector. A qt transformation is a (7,) array formed by nps.glue(q,t, axis=-1) where q is a (4,) unit quaternion and t is a (3,) translation vector. Applied to a point x the transformed result is rotate(x)+t. Given a matrix R, the rotation is defined by a matrix multiplication. x and t are stored as a row vector (that's how numpy stores 1-dimensional arrays), but the multiplication works as if x was a column vector (to match linear algebra conventions). See the docs for mrcal._transform_point_Rt() for more detail. This function supports broadcasting fully. Note: mrcal does not use unit quaternions anywhere to represent rotations. This function is provided for convenience, but isn't thoroughly tested. ARGUMENTS - Rt: array of shape (4,3). This matrix defines the transformation. Rt[:3,:] is a rotation matrix; Rt[3,:] is a translation. It is assumed that the rotation matrix is a valid rotation (matmult(R,transpose(R)) = I, det(R) = 1), but that is not checked - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. RETURNED VALUE We return the qt transformation. Each broadcasted slice has shape (7,). qt[:4] is a rotation defined as a unit quaternion; qt[4:] is a translation. """ if out is not None: qt = out else: qt = np.zeros(Rt.shape[:-2] + (7,), dtype=float) _poseutils_scipy.quat_from_R(Rt[..., :3, :], out=qt[..., :4]) qt[..., 4:] = Rt[..., 3, :] return qt def Rt_from_qt(qt, *, out=None): r"""Compute an Rt transformation from a qt transformation SYNOPSIS qt = nps.glue(q,t, axis=-1) print(qt.shape) ===> (7,) Rt = mrcal.Rt_from_qt(qt) print(Rt.shape) ===> (4,3) translation = Rt[3,:] rotation_matrix = Rt[:3,:] Converts a qt transformation to an Rt transformation. Both specify a rotation and translation. An Rt transformation is a (4,3) array formed by nps.glue(R,t, axis=-2) where R is a (3,3) rotation matrix and t is a (3,) translation vector. A qt transformation is a (7,) array formed by nps.glue(q,t, axis=-1) where q is a (4,) unit quaternion and t is a (3,) translation vector. Applied to a point x the transformed result is rotate(x)+t. Given a matrix R, the rotation is defined by a matrix multiplication. x and t are stored as a row vector (that's how numpy stores 1-dimensional arrays), but the multiplication works as if x was a column vector (to match linear algebra conventions). See the docs for mrcal._transform_point_Rt() for more detail. This function supports broadcasting fully. Note: mrcal does not use unit quaternions anywhere to represent rotations. This function is provided for convenience, but isn't thoroughly tested. ARGUMENTS - qt: array of shape (7,). This vector defines the input transformation. qt[:4] is a rotation defined as a unit quaternion; qt[4:] is a translation. - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. RETURNED VALUE We return the Rt transformation. Each broadcasted slice has shape (4,3). Rt[:3,:] is a rotation matrix; Rt[3,:] is a translation. The matrix R is a valid rotation: matmult(R,transpose(R)) = I and det(R) = 1 """ if out is not None: Rt = out else: Rt = np.zeros(qt.shape[:-1] + (4,3), dtype=float) _poseutils_npsp.R_from_quat(qt[..., :4], out=Rt[..., :3, :]) Rt[..., 3, :] = qt[..., 4:] return Rt mrcal-2.4.1/mrcal/projections.py000066400000000000000000001177701456301662300166460ustar00rootroot00000000000000#!/usr/bin/python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 '''Routines to (un)project points using any camera model Most of these are Python wrappers around the written-in-C Python extension module mrcal._mrcal_npsp. Most of the time you want to use this module instead of touching mrcal._mrcal_npsp directly. All functions are exported into the mrcal module. So you can call these via mrcal.projections.fff() or mrcal.fff(). The latter is preferred. ''' import numpy as np import numpysane as nps import sys import mrcal def project(v, lensmodel, intrinsics_data, *, get_gradients = False, out = None): r'''Projects a set of 3D camera-frame points to the imager SYNOPSIS # v is a (...,3) array of 3D points we're projecting points = mrcal.project( v, lensmodel, intrinsics_data ) ### OR ### m = mrcal.cameramodel(...) points = mrcal.project( v, *m.intrinsics() ) # points is a (...,2) array of pixel coordinates Given a shape-(...,3) array of points in the camera frame (x,y aligned with the imager coords, z 'forward') and an intrinsic model, this function computes the projection, optionally with gradients. Projecting out-of-bounds points (beyond the field of view) returns undefined values. Generally things remain continuous even as we move off the imager domain. Pinhole-like projections will work normally if projecting a point behind the camera. Splined projections clamp to the nearest spline segment: the projection will fly off to infinity quickly since we're extrapolating a polynomial, but the function will remain continuous. Broadcasting is fully supported across v and intrinsics_data ARGUMENTS - points: array of dims (...,3); the points we're projecting - lensmodel: a string such as LENSMODEL_PINHOLE LENSMODEL_OPENCV4 LENSMODEL_CAHVOR LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=16_Ny=12_fov_x_deg=100 - intrinsics: array of dims (Nintrinsics): (focal_x, focal_y, center_pixel_x, center_pixel_y, distortion0, distortion1, ...) The focal lengths are given in pixels. - get_gradients: optional boolean that defaults to False. Whether we should compute and report the gradients. This affects what we return - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the same arrays passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE if not get_gradients: we return an (...,2) array of projected pixel coordinates if get_gradients: we return a tuple: - (...,2) array of projected pixel coordinates - (...,2,3) array of gradients of the pixel coordinates in respect to the input 3D point positions - (...,2,Nintrinsics) array of the gradients of the pixel coordinates in respect to the intrinsics ''' # Internal function must have a different argument order so # that all the broadcasting stuff is in the leading arguments if not get_gradients: return mrcal._mrcal_npsp._project(v, intrinsics_data, lensmodel=lensmodel, out=out) return mrcal._mrcal_npsp._project_withgrad(v, intrinsics_data, lensmodel=lensmodel, out=out) def unproject(q, lensmodel, intrinsics_data, *, normalize = False, get_gradients = False, out = None): r'''Unprojects pixel coordinates to observation vectors SYNOPSIS # q is a (...,2) array of pixel observations v = mrcal.unproject( q, lensmodel, intrinsics_data ) ### OR ### m = mrcal.cameramodel(...) v = mrcal.unproject( q, *m.intrinsics() ) Maps a set of 2D imager points q to a set of 3D vectors in camera coordinates that produced these pixel observations. Each 3D vector is unique only up-to-length, and the returned vectors aren't normalized by default. The default length of the returned vector is arbitrary, and selected for the convenience of the implementation. Pass normalize=True to always return unit vectors. This is the "reverse" direction, so an iterative nonlinear optimization is performed internally to compute this result. This is much slower than mrcal_project. For OpenCV distortions specifically, OpenCV has cvUndistortPoints() (and cv2.undistortPoints()), but these are inaccurate and we do not use them: https://github.com/opencv/opencv/issues/8811 Gradients are available by passing get_gradients=True. Since unproject() is implemented as an iterative solve around project(), the unproject() gradients are computed by manipulating the gradients reported by project() at the solution. The reported gradients are relative to whatever unproject() is reporting; the unprojection is unique only up-to-length, and the magnitude isn't fixed. So the gradients may include a component in the direction of the returned observation vector: this follows the arbitrary scaling used by unproject(). It is possible to pass normalize=True; we then return NORMALIZED observation vectors and the gradients of those NORMALIZED vectors. In that case, those gradients are guaranteed to be orthogonal to the observation vector. The vector normalization involves a bit more computation, so it isn't the default. NOTE: THE MAGNITUDE OF THE RETURNED VECTOR CHANGES IF get_gradients CHANGES. The reported gradients are correct relative to the output returned with get_gradients=True. Passing normalize=True can be used to smooth this out: unproject(..., normalize=True) returns the same vectors as unproject(..., normalize=True, get_gradients=True)[0] Broadcasting is fully supported across q and intrinsics_data. Models that have no gradients available cannot use mrcal_unproject() in C, but CAN still use this mrcal.unproject() Python routine: a slower routine is employed that uses numerical differences instead of analytical gradients. ARGUMENTS - q: array of dims (...,2); the pixel coordinates we're unprojecting - lensmodel: a string such as LENSMODEL_PINHOLE LENSMODEL_OPENCV4 LENSMODEL_CAHVOR LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=16_Ny=12_fov_x_deg=100 - intrinsics_data: array of dims (Nintrinsics): (focal_x, focal_y, center_pixel_x, center_pixel_y, distortion0, distortion1, ...) The focal lengths are given in pixels. - normalize: optional boolean defaults to False. If True: normalize the output vectors - get_gradients: optional boolean that defaults to False. Whether we should compute and report the gradients. This affects what we return (see below). If not normalize, the magnitude of the reported vectors changes if get_gradients is turned on/off (see above) - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the same arrays passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE if not get_gradients: we return an (...,3) array of unprojected observation vectors. Not normalized by default; see description above if get_gradients: we return a tuple: - (...,3) array of unprojected observation vectors - (...,3,2) array of gradients of unprojected observation vectors in respect to pixel coordinates - (...,3,Nintrinsics) array of gradients of unprojected observation vectors in respect to the intrinsics ''' def apply_normalization_to_output_with_gradients(v,dv_dq,dv_di): # vn = v/mag(v) # dvn = dv (1/mag(v)) + v d(1/mag(v)) # = dv( 1/mag(v) - v vt / mag^3(v) ) # = dv( 1/mag(v) - vn vnt / mag(v) ) # = dv/mag(v) ( 1 - vn vnt ) # v has shape (...,3) # dv_dq has shape (...,3,2) # dv_di has shape (...,3,N) # shape (...,1) magv_recip = 1. / nps.dummy(nps.mag(v), -1) v *= magv_recip # shape (...,1,1) magv_recip = nps.dummy(magv_recip,-1) dv_dq *= magv_recip dv_dq -= nps.xchg( nps.matmult( nps.dummy(nps.xchg(dv_dq, -1,-2), -2), nps.dummy(nps.outer(v,v),-3) )[...,0,:], -1, -2) dv_di *= magv_recip dv_di -= nps.xchg( nps.matmult( nps.dummy(nps.xchg(dv_di, -1,-2), -2), nps.dummy(nps.outer(v,v),-3) )[...,0,:], -1, -2) # First, handle some trivial cases. I don't want to run the # optimization-based unproject() if I don't have to if lensmodel == 'LENSMODEL_PINHOLE' or \ lensmodel == 'LENSMODEL_LONLAT' or \ lensmodel == 'LENSMODEL_LATLON' or \ lensmodel == 'LENSMODEL_STEREOGRAPHIC': if lensmodel == 'LENSMODEL_PINHOLE': func = mrcal.unproject_pinhole always_normalized = False elif lensmodel == 'LENSMODEL_LONLAT': func = mrcal.unproject_lonlat always_normalized = True elif lensmodel == 'LENSMODEL_LATLON': func = mrcal.unproject_latlon always_normalized = True elif lensmodel == 'LENSMODEL_STEREOGRAPHIC': func = mrcal.unproject_stereographic always_normalized = False if not get_gradients: v = func(q, intrinsics_data, out = out) if normalize and not always_normalized: v /= nps.dummy(nps.mag(v), axis=-1) return v # shapes (...,2) fxy = intrinsics_data[..., :2] cxy = intrinsics_data[..., 2:] # shapes (...,3) and (...,3,2) v, dv_dq = \ func(q, intrinsics_data, get_gradients = True, out = None if out is None else (out[0],out[1])) # q = f l(v) + c # l(v) = (q-c)/f # # dl/dv dv/df = (c-q) / f^2 # dl/dv dv/dq = 1/f # -> dl/dv = 1 / ( f dv/dq ) # -> dv/df = (c-q) / (f^2 dl/dv) = (c-q) dv/dq / f # # dl/dv dv/dc = -1/f # -> dv/dc = -1 / (f dl/dv) = -1 / (f /( f dv/dq )) = -dv/dq dv_di_shape = dv_dq.shape[:-1] + (4,) if out is None: dv_di = np.zeros( dv_di_shape, dtype=float) else: if not (out[2].shape[-len(dv_di_shape):] == dv_di_shape and \ not any(np.array(out[2].shape[:-len(dv_di_shape)]) - 1)): raise Exception(f"Shape of out[2] doesn't match broadcasted shape for dv_di. Wanted {dv_di_shape}, but got {out[2].shape}") dv_di = out[2] dv_di *= 0 # dv/df dv_di[..., :2] += nps.dummy((cxy - q)/fxy, -2) * dv_dq # dv/dc dv_di[..., 2:] -= dv_dq if normalize and not always_normalized: apply_normalization_to_output_with_gradients(v,dv_dq,dv_di) return v,dv_dq,dv_di try: meta = mrcal.lensmodel_metadata_and_config(lensmodel) except: raise Exception(f"Invalid lens model '{lensmodel}': couldn't get the metadata") if meta['has_gradients']: # Main path. We have gradients. # # Internal function must have a different argument order so # that all the broadcasting stuff is in the leading arguments if not get_gradients: v = mrcal._mrcal_npsp._unproject(q, intrinsics_data, lensmodel=lensmodel, out=out) if normalize: # Explicitly handle nan and inf to set their normalized values # to 0. Otherwise I get a scary-looking warning from numpy i_vgood = \ np.isfinite(v[...,0]) * \ np.isfinite(v[...,1]) * \ np.isfinite(v[...,2]) v[~i_vgood] = np.array((0.,0.,1.)) v /= nps.dummy(nps.mag(v), -1) v[~i_vgood] = np.array((0.,0.,0.)) return v # We need to report gradients vs = mrcal._mrcal_npsp._unproject(q, intrinsics_data, lensmodel=lensmodel) # I have no gradients available for unproject(), and I need to invert a # non-square matrix to use the gradients from project(). I deal with this # with a stereographic mapping # # With a simple unprojection I have q -> v # Instead I now do q -> vs -> u -> v # I reproject vs, to produce a scaled v = k*vs. I'm assuming all # projections are central, so vs represents q just as well as v does. u # is a 2-vector, so dq_du is (2x2), and I can invert it u = mrcal.project_stereographic(vs) dv_du = np.zeros( vs.shape + (2,), dtype=float) v, dv_du = \ mrcal.unproject_stereographic(u, get_gradients = True, out = (vs if out is None else out[0], dv_du)) _,dq_dv,dq_di = mrcal.project(v, lensmodel, intrinsics_data, get_gradients = True) # shape (..., 2,2). Square. Invertible! dq_du = nps.matmult( dq_dv, dv_du ) # dv/dq = dv/du du/dq = # = dv/du inv(dq/du) # = transpose(inv(transpose(dq/du)) transpose(dv/du)) dv_dq = nps.transpose(np.linalg.solve( nps.transpose(dq_du), nps.transpose(dv_du) )) if out is not None: out[1] *= 0. out[1] += dv_dq dv_dq = out[1] # dv/di is a bit different. I have (q,i) -> v. I want to find out # how moving i affects v while keeping q constant. Taylor expansion # of projection: q = q0 + dq/dv dv + dq/di di. q is constant so # dq/dv dv + dq/di di = 0 -> dv/di = - dv/dq dq/di dv_di = nps.matmult(dv_dq, dq_di, out = None if out is None else out[2]) dv_di *= -1. if normalize: apply_normalization_to_output_with_gradients(v,dv_dq,dv_di) return v, dv_dq, dv_di # No projection gradients implemented in C. We should get here approximately # never. At this time, there are no longer any projection functions that # have no gradients implemented. If another such model is defined, this path # will be used. If these see use, real gradients should be implemented # # We compute the gradients numerically. This is a reimplementation of the C # code. It's barely maintained, and here for legacy compatibility only raise("should never get here") if get_gradients: raise Exception(f"unproject(..., get_gradients=True) is unsupported for models with no gradients, such as '{lensmodel}'") if q is None: return q if q.size == 0: s = q.shape return np.zeros(s[:-1] + (3,)) if out is not None: raise Exception(f"unproject(..., out) is unsupported if out is not None and we're using a model with no gradients, such as '{lensmodel}'") fxy = intrinsics_data[..., :2] cxy = intrinsics_data[..., 2:4] # undistort the q, by running an optimizer import scipy.optimize # I optimize each point separately because the internal optimization # algorithm doesn't know that each point is independent, so if I optimized # it all together, it would solve a dense linear system whose size is linear # in Npoints. The computation time thus would be much slower than # linear(Npoints) @nps.broadcast_define( ((2,),), ) def undistort_this(q0): def cost_no_gradients(vxy, *args, **kwargs): '''Optimization functions''' return \ mrcal.project(np.array((vxy[0],vxy[1],1.)), lensmodel, intrinsics_data) - \ q0 # seed assuming distortions aren't there vxy_seed = (q0 - cxy) / fxy # no gradients available result = scipy.optimize.least_squares(cost_no_gradients, vxy_seed, '3-point') vxy = result.x # This needs to be precise; if it isn't, I barf. Shouldn't happen # very often if np.sqrt(result.cost/2.) > 1e-3: if not unproject.__dict__.get('already_complained'): sys.stderr.write("WARNING: unproject() wasn't able to precisely compute some points. Returning nan for those. Will complain just once\n") unproject.already_complained = True return np.array((np.nan,np.nan)) return vxy vxy = undistort_this(q) # I append a 1. shape = (..., 3) v = nps.glue(vxy, np.ones( vxy.shape[:-1] + (1,) ), axis=-1) if normalize: v /= nps.dummy(nps.mag(v), -1) return v def project_pinhole(points, fxycxy = np.array((1.0, 1.0, 0.0, 0.0), dtype=float), *, get_gradients = False, out = None): r'''Projects 3D camera-frame points using a pinhole projection SYNOPSIS # points is a (N,3) array of camera-coordinate-system points q = mrcal.project_pinhole( points, fxycxy ) # q is now a (N,2) array of pinhole coordinates This is a special case of mrcal.project(). Useful to represent a very simple, very perfect lens. Wide lenses do not follow this model. Long lenses usually more-or-less DO follow this model. See the lensmodel documentation for details: http://mrcal.secretsauce.net/lensmodels.html#lensmodel-pinhole Given a (N,3) array of points in the camera frame (x,y aligned with the imager coords, z 'forward') and the parameters fxycxy, this function computes the projection, optionally with gradients. ARGUMENTS - points: array of dims (...,3); the points we're projecting. This supports broadcasting fully, and any leading dimensions are allowed, including none - fxycxy: optional intrinsics core. This is a shape (4,) array (fx,fy,cx,cy), with all elements given in units of pixels. fx and fy are the horizontal and vertical focal lengths, respectively. (cx,cy) are pixel coordinates corresponding to the projection of p = [0,0,1]. If omitted, default values are used: fx=fy=1.0 and cx=cy=0.0. - get_gradients: optional boolean, defaults to False. This affects what we return (see below) - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the same arrays passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE if not get_gradients: we return an (...,2) array of projected transverse equirectangular coordinates if get_gradients: we return a tuple: - (...,2) array of projected pinhole coordinates - (...,2,3) array of the gradients of the transverse equirectangular coordinates in respect to the input 3D point positions ''' # Internal function must have a different argument order so # that all the broadcasting stuff is in the leading arguments if not get_gradients: return mrcal._mrcal_npsp._project_pinhole(points, fxycxy, out=out) return mrcal._mrcal_npsp._project_pinhole_withgrad(points, fxycxy, out=out) def unproject_pinhole(points, fxycxy = np.array((1.0, 1.0, 0.0, 0.0), dtype=float), *, get_gradients = False, out = None): r'''Unprojects 2D pixel coordinates using a pinhole projection SYNOPSIS # points is a (N,2) array of imager points v = mrcal.unproject_pinhole( points, fxycxy ) # v is now a (N,3) array of observation directions in the camera coordinate # system. v are NOT normalized This is a special case of mrcal.unproject(). Useful to represent a very simple, very perfect lens. Wide lenses do not follow this model. Long lenses usually more-or-less DO follow this model. See the lensmodel documentation for details: http://mrcal.secretsauce.net/lensmodels.html#lensmodel-pinhole Given a (N,2) array of pinhole coordinates and the parameters fxycxy, this function computes the inverse projection, optionally with gradients. The vectors returned by this function are NOT normalized. ARGUMENTS - points: array of dims (...,2); the pinhole coordinates we're unprojecting. This supports broadcasting fully, and any leading dimensions are allowed, including none - fxycxy: optional intrinsics core. This is a shape (4,) array (fx,fy,cx,cy), with all elements given in units of pixels. fx and fy are the horizontal and vertical focal lengths, respectively. (cx,cy) are pixel coordinates corresponding to the projection of p = [0,0,1]. If omitted, default values are used: fx=fy=1.0 and cx=cy=0.0. - get_gradients: optional boolean, defaults to False. This affects what we return (see below) - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the same arrays passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE if not get_gradients: we return an (...,3) array of unprojected observation vectors. These are NOT normalized. if get_gradients: we return a tuple: - (...,3) array of unprojected observation vectors. These are NOT normalized. - (...,3,2) array of the gradients of the observation vectors in respect to the input 2D pinhole coordinates ''' if not get_gradients: return mrcal._mrcal_npsp._unproject_pinhole(points, fxycxy, out=out) return mrcal._mrcal_npsp._unproject_pinhole_withgrad(points, fxycxy, out=out) def project_stereographic(points, fxycxy = np.array((1.0, 1.0, 0.0, 0.0), dtype=float), *, get_gradients = False, out = None): r'''Projects a set of 3D camera-frame points using a stereographic model SYNOPSIS # points is a (N,3) array of camera-coordinate-system points q = mrcal.project_stereographic( points ) # q is now a (N,2) array of normalized stereographic coordinates This is a special case of mrcal.project(). No actual lens ever follows this model exactly, but this is useful as a baseline for other models. See the lensmodel documentation for details: http://mrcal.secretsauce.net/lensmodels.html#lensmodel-stereographic Given a (N,3) array of points in the camera frame (x,y aligned with the imager coords, z 'forward') and parameters of a perfect stereographic camera, this function computes the projection, optionally with gradients. The user can pass in focal length and center-pixel values. Or they can be omitted to compute a "normalized" stereographic projection (fx = fy = 1, cx = cy = 0). The stereographic projection is able to represent points behind the camera, and has only one singular observation direction: directly behind the camera, along the optical axis. This projection acts radially. If the observation vector v makes an angle theta with the optical axis, then the projected point q is 2 tan(theta/2) f from the image center. ARGUMENTS - points: array of dims (...,3); the points we're projecting. This supports broadcasting fully, and any leading dimensions are allowed, including none - fxycxy: optional intrinsics core. This is a shape (4,) array (fx,fy,cx,cy), with all elements given in units of pixels. fx and fy are the horizontal and vertical focal lengths, respectively. (cx,cy) are pixel coordinates corresponding to the projection of p = [0,0,1]. If omitted, default values are used to specify a normalized stereographic projection : fx=fy=1.0 and cx=cy=0.0. - get_gradients: optional boolean, defaults to False. This affects what we return (see below) - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the same arrays passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE if not get_gradients: we return an (...,2) array of projected stereographic coordinates if get_gradients: we return a tuple: - (...,2) array of projected stereographic coordinates - (...,2,3) array of the gradients of the stereographic coordinates in respect to the input 3D point positions ''' if not get_gradients: return mrcal._mrcal_npsp._project_stereographic(points, fxycxy, out=out) return mrcal._mrcal_npsp._project_stereographic_withgrad(points, fxycxy, out=out) def unproject_stereographic(points, fxycxy = np.array((1.0, 1.0, 0.0, 0.0), dtype=float), *, get_gradients = False, out = None): r'''Unprojects a set of 2D pixel coordinates using a stereographic model SYNOPSIS # points is a (N,2) array of pixel coordinates v = mrcal.unproject_stereographic( points, fxycxy) # v is now a (N,3) array of observation directions in the camera coordinate # system. v are NOT normalized This is a special case of mrcal.unproject(). No actual lens ever follows this model exactly, but this is useful as a baseline for other models. See the lensmodel documentation for details: http://mrcal.secretsauce.net/lensmodels.html#lensmodel-stereographic Given a (N,2) array of stereographic coordinates and parameters of a perfect stereographic camera, this function computes the inverse projection, optionally with gradients. The user can pass in focal length and center-pixel values. Or they can be omitted to compute a "normalized" stereographic projection (fx = fy = 1, cx = cy = 0). The stereographic projection is able to represent points behind the camera, and has only one singular observation direction: directly behind the camera, along the optical axis. This projection acts radially. If the observation vector v makes an angle theta with the optical axis, then the projected point q is 2 tan(theta/2) f from the image center. ARGUMENTS - points: array of dims (...,2); the stereographic coordinates we're unprojecting. This supports broadcasting fully, and any leading dimensions are allowed, including none - fxycxy: optional intrinsics core. This is a shape (4,) array (fx,fy,cx,cy), with all elements given in units of pixels. fx and fy are the horizontal and vertical focal lengths, respectively. (cx,cy) are pixel coordinates corresponding to the projection of p = [0,0,1]. If omitted, default values are used to specify a normalized stereographic projection : fx=fy=1.0 and cx=cy=0.0. - get_gradients: optional boolean, defaults to False. This affects what we return (see below) - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the same arrays passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE if not get_gradients: we return an (...,3) array of unprojected observation vectors. These are NOT normalized. if get_gradients: we return a tuple: - (...,3) array of unprojected observation vectors. These are NOT normalized. - (...,3,2) array of the gradients of the observation vectors in respect to the input 2D stereographic coordinates ''' if not get_gradients: return mrcal._mrcal_npsp._unproject_stereographic(points, fxycxy, out=out) return mrcal._mrcal_npsp._unproject_stereographic_withgrad(points, fxycxy, out=out) def project_lonlat(points, fxycxy = np.array((1.0, 1.0, 0.0, 0.0), dtype=float), *, get_gradients = False, out = None): r'''Projects a set of 3D camera-frame points using an equirectangular projection SYNOPSIS # points is a (N,3) array of camera-coordinate-system points q = mrcal.project_lonlat( points, fxycxy ) # q is now a (N,2) array of equirectangular coordinates This is a special case of mrcal.project(). Useful not for representing lenses, but for describing the projection function of wide panoramic images. Lenses do not follow this model. See the lensmodel documentation for details: http://mrcal.secretsauce.net/lensmodels.html#lensmodel-lonlat Given a (N,3) array of points in the camera frame (x,y aligned with the imager coords, z 'forward') and the parameters fxycxy, this function computes the projection, optionally with gradients. ARGUMENTS - points: array of dims (...,3); the points we're projecting. This supports broadcasting fully, and any leading dimensions are allowed, including none - fxycxy: optional intrinsics core. This is a shape (4,) array (fx,fy,cx,cy). fx and fy are the "focal lengths": they specify the angular resolution of the image, in pixels/radian. (cx,cy) are pixel coordinates corresponding to the projection of p = [0,0,1]. If omitted, default values are used to specify a normalized equirectangular projection : fx=fy=1.0 and cx=cy=0.0. This produces q = (lon,lat) - get_gradients: optional boolean, defaults to False. This affects what we return (see below) - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the same arrays passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE if not get_gradients: we return an (...,2) array of projected equirectangular coordinates if get_gradients: we return a tuple: - (...,2) array of projected equirectangular coordinates - (...,2,3) array of the gradients of the equirectangular coordinates in respect to the input 3D point positions ''' # Internal function must have a different argument order so # that all the broadcasting stuff is in the leading arguments if not get_gradients: return mrcal._mrcal_npsp._project_lonlat(points, fxycxy, out=out) return mrcal._mrcal_npsp._project_lonlat_withgrad(points, fxycxy, out=out) def unproject_lonlat(points, fxycxy = np.array((1.0, 1.0, 0.0, 0.0), dtype=float), *, get_gradients = False, out = None): r'''Unprojects a set of 2D pixel coordinates using an equirectangular projection SYNOPSIS # points is a (N,2) array of imager points v = mrcal.unproject_lonlat( points, fxycxy ) # v is now a (N,3) array of observation directions in the camera coordinate # system. v are normalized This is a special case of mrcal.unproject(). Useful not for representing lenses, but for describing the projection function of wide panoramic images. Lenses do not follow this model. See the lensmodel documentation for details: http://mrcal.secretsauce.net/lensmodels.html#lensmodel-lonlat Given a (N,2) array of equirectangular coordinates and the parameters fxycxy, this function computes the inverse projection, optionally with gradients. The vectors returned by this function are normalized. ARGUMENTS - points: array of dims (...,2); the equirectangular coordinates we're unprojecting. This supports broadcasting fully, and any leading dimensions are allowed, including none - fxycxy: optional intrinsics core. This is a shape (4,) array (fx,fy,cx,cy). fx and fy are the "focal lengths": they specify the angular resolution of the image, in pixels/radian. (cx,cy) are pixel coordinates corresponding to the projection of p = [0,0,1]. If omitted, default values are used to specify a normalized equirectangular projection : fx=fy=1.0 and cx=cy=0.0. This produces q = (lon,lat) - get_gradients: optional boolean, defaults to False. This affects what we return (see below) - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the same arrays passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE if not get_gradients: we return an (...,3) array of unprojected observation vectors. These are normalized. if get_gradients: we return a tuple: - (...,3) array of unprojected observation vectors. These are normalized. - (...,3,2) array of the gradients of the observation vectors in respect to the input 2D equirectangular coordinates ''' if not get_gradients: return mrcal._mrcal_npsp._unproject_lonlat(points, fxycxy, out=out) return mrcal._mrcal_npsp._unproject_lonlat_withgrad(points, fxycxy, out=out) def project_latlon(points, fxycxy = np.array((1.0, 1.0, 0.0, 0.0), dtype=float), *, get_gradients = False, out = None): r'''Projects 3D camera-frame points using a transverse equirectangular projection SYNOPSIS # points is a (N,3) array of camera-coordinate-system points q = mrcal.project_latlon( points, fxycxy ) # q is now a (N,2) array of transverse equirectangular coordinates This is a special case of mrcal.project(). Useful not for representing lenses, but for performing stereo rectification. Lenses do not follow this model. See the lensmodel documentation for details: http://mrcal.secretsauce.net/lensmodels.html#lensmodel-latlon Given a (N,3) array of points in the camera frame (x,y aligned with the imager coords, z 'forward') and the parameters fxycxy, this function computes the projection, optionally with gradients. ARGUMENTS - points: array of dims (...,3); the points we're projecting. This supports broadcasting fully, and any leading dimensions are allowed, including none - fxycxy: optional intrinsics core. This is a shape (4,) array (fx,fy,cx,cy). fx and fy are the "focal lengths": they specify the angular resolution of the image, in pixels/radian. (cx,cy) are pixel coordinates corresponding to the projection of p = [0,0,1]. If omitted, default values are used to specify a normalized transverse equirectangular projection : fx=fy=1.0 and cx=cy=0.0. This produces q = (lat,lon) - get_gradients: optional boolean, defaults to False. This affects what we return (see below) - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the same arrays passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE if not get_gradients: we return an (...,2) array of projected transverse equirectangular coordinates if get_gradients: we return a tuple: - (...,2) array of projected transverse equirectangular coordinates - (...,2,3) array of the gradients of the transverse equirectangular coordinates in respect to the input 3D point positions ''' # Internal function must have a different argument order so # that all the broadcasting stuff is in the leading arguments if not get_gradients: return mrcal._mrcal_npsp._project_latlon(points, fxycxy, out=out) return mrcal._mrcal_npsp._project_latlon_withgrad(points, fxycxy, out=out) def unproject_latlon(points, fxycxy = np.array((1.0, 1.0, 0.0, 0.0), dtype=float), *, get_gradients = False, out = None): r'''Unprojects 2D pixel coordinates using a transverse equirectangular projection SYNOPSIS # points is a (N,2) array of imager points v = mrcal.unproject_latlon( points, fxycxy ) # v is now a (N,3) array of observation directions in the camera coordinate # system. v are normalized This is a special case of mrcal.unproject(). Useful not for representing lenses, but for performing stereo rectification. Lenses do not follow this model. See the lensmodel documentation for details: http://mrcal.secretsauce.net/lensmodels.html#lensmodel-latlon Given a (N,2) array of transverse equirectangular coordinates and the parameters fxycxy, this function computes the inverse projection, optionally with gradients. The vectors returned by this function are normalized. ARGUMENTS - points: array of dims (...,2); the transverse equirectangular coordinates we're unprojecting. This supports broadcasting fully, and any leading dimensions are allowed, including none - fxycxy: optional intrinsics core. This is a shape (4,) array (fx,fy,cx,cy), with all elements given in units of pixels. fx and fy are the horizontal and vertical focal lengths, respectively. (cx,cy) are pixel coordinates corresponding to the projection of p = [0,0,1]. If omitted, default values are used to specify a normalized transverse equirectangular projection : fx=fy=1.0 and cx=cy=0.0. This produces q = (lat,lon) - get_gradients: optional boolean, defaults to False. This affects what we return (see below) - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the same arrays passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE if not get_gradients: we return an (...,3) array of unprojected observation vectors. These are normalized. if get_gradients: we return a tuple: - (...,3) array of unprojected observation vectors. These are normalized. - (...,3,2) array of the gradients of the observation vectors in respect to the input 2D transverse equirectangular coordinates ''' if not get_gradients: return mrcal._mrcal_npsp._unproject_latlon(points, fxycxy, out=out) return mrcal._mrcal_npsp._unproject_latlon_withgrad(points, fxycxy, out=out) mrcal-2.4.1/mrcal/stereo.py000066400000000000000000002470471456301662300156110ustar00rootroot00000000000000#!/usr/bin/python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 '''Routines for stereo processing: rectification and ranging All functions are exported into the mrcal module. So you can call these via mrcal.stereo.fff() or mrcal.fff(). The latter is preferred. ''' import sys import numpy as np import numpysane as nps import mrcal import re def rectified_resolution(model, *, az_fov_deg, el_fov_deg, az0_deg, el0_deg, R_cam0_rect0, pixels_per_deg_az = -1., pixels_per_deg_el = -1., rectification_model = 'LENSMODEL_LATLON'): r'''Compute the resolution to be used for the rectified system SYNOPSIS pixels_per_deg_az, \ pixels_per_deg_el = \ mrcal.rectified_resolution(model, az_fov_deg = 120, el_fov_deg = 100, az0_deg = 0, el0_deg = 0 R_cam0_rect0) This is usually called from inside mrcal.rectified_system() only, and usually there's no reason for the end-user to call this function. If the final resolution used in the rectification is needed, call mrcal.rectified_system(return_metadata = True) This function also supports LENSMODEL_LONLAT (not for stereo rectification, but for a 360deg around-the-horizon view), and is useful to compute the image resolution in those applications. Similar to mrcal.rectified_system(), this functions takes in rectified-image pan,zoom values and a desired resolution in pixels_per_deg_.... If pixels_per_deg_... < 0: we compute and return a scaled factor of the input image resolution at the center of the rectified field of view. pixels_per_deg_... = -1 means "full resolution", pixels_per_deg_... = -0.5 means "half resolution" and so on. If pixels_per_deg_... > 0: then we use the intended value as is. In either case, we adjust the returned pixels_per_deg_... to evenly fit into the requested field of view, to match the integer pixel count in the rectified image. This is only possible for LENSMODEL_LATLON and LENSMODEL_LONLAT. ARGUMENTS - model: the model of the camera that captured the image that will be reprojected. In a stereo pair this is the FIRST camera. Used to determine the angular resolution of the input image. Only the intrinsics are used. - az_fov_deg: required value for the azimuth (along-the-baseline) field-of-view of the desired rectified system, in degrees - el_fov_deg: required value for the elevation (across-the-baseline) field-of-view of the desired rectified system, in degrees - az0_deg: required value for the azimuth center of the rectified images. - el0_deg: required value for the elevation center of the rectified system. - pixels_per_deg_az: optional value for the azimuth resolution of the rectified image. If a resolution of >0 is requested, the value is used as is. If a resolution of <0 is requested, we use this as a scale factor on the resolution of the first input image. For instance, to downsample by a factor of 2, pass pixels_per_deg_az = -0.5. By default, we use -1: the resolution of the input image at the center of the rectified system. - pixels_per_deg_el: same as pixels_per_deg_az but in the elevation direction - rectification_model: optional string that selects the projection function to use in the resulting rectified system. This is a string selecting the mrcal lens model. Currently supported are "LENSMODEL_LATLON" (the default) and "LENSMODEL_LONLAT" and "LENSMODEL_PINHOLE" RETURNED VALUES A tuple (pixels_per_deg_az,pixels_per_deg_el) ''' # The guts of this function are implemented in C. Call that return mrcal._mrcal._rectified_resolution(*model.intrinsics(), R_cam0_rect0 = np.ascontiguousarray(R_cam0_rect0), az_fov_deg = az_fov_deg, el_fov_deg = el_fov_deg, az0_deg = az0_deg, el0_deg = el0_deg, pixels_per_deg_az = pixels_per_deg_az, pixels_per_deg_el = pixels_per_deg_el, rectification_model = rectification_model) def _rectified_resolution_python(model, *, az_fov_deg, el_fov_deg, az0_deg, el0_deg, R_cam0_rect0, pixels_per_deg_az = -1., pixels_per_deg_el = -1., rectification_model = 'LENSMODEL_LATLON'): r'''Reference implementation of mrcal_rectified_resolution() in python The main implementation is written in C in stereo.c: mrcal_rectified_resolution() This should be identical to the rectified_resolution() function above. There's no explicit test to compare the two implementations, but test/test-stereo.py should catch any differences. ''' if pixels_per_deg_az < 0 or \ pixels_per_deg_el < 0: azel0 = np.array((az0_deg,el0_deg)) * np.pi/180. # I need to compute the resolution of the rectified images. I try to # match the resolution of the cameras. I just look at camera0. If your # two cameras are different, pass in the pixels_per_deg yourself # # I look at the center of the stereo field of view. There I have q = # project(v) where v is a unit projection vector. I compute dq/dth where # th is an angular perturbation applied to v. if rectification_model == 'LENSMODEL_LATLON': q0_normalized = azel0 v,dv_dazel = \ mrcal.unproject_latlon( q0_normalized, get_gradients = True ) elif rectification_model == 'LENSMODEL_LONLAT': q0_normalized = azel0 v,dv_dazel = \ mrcal.unproject_lonlat( q0_normalized, get_gradients = True ) elif rectification_model == 'LENSMODEL_PINHOLE': q0_normalized = np.tan(azel0) v,dv_dq0normalized = \ mrcal.unproject_pinhole( q0_normalized, get_gradients = True ) # dq/dth = dtanth/dth = 1/cos^2(th) dv_dazel = dv_dq0normalized cos_azel0 = np.cos(azel0) dv_dazel /= cos_azel0*cos_azel0 else: raise Exception("Unsupported rectification model") v0 = mrcal.rotate_point_R(R_cam0_rect0, v) dv0_dazel = nps.matmult(R_cam0_rect0, dv_dazel) _,dq_dv0,_ = mrcal.project(v0, *model.intrinsics(), get_gradients = True) # More complex method that's probably not any better # # if False: # # I rotate my v to a coordinate system where u = rotate(v) is [0,0,1]. # # Then u = [a,b,0] are all orthogonal to v. So du/dth = [cos, sin, 0]. # # I then have dq/dth = dq/dv dv/du [cos, sin, 0]t # # ---> dq/dth = dq/dv dv/du[:,:2] [cos, sin]t = M [cos,sin]t # # # # norm2(dq/dth) = [cos,sin] MtM [cos,sin]t is then an ellipse with the # # eigenvalues of MtM giving me the best and worst sensitivities. I can # # use mrcal.worst_direction_stdev() to find the densest direction. But I # # actually know the directions I care about, so I evaluate them # # independently for the az and el directions # Ruv = mrcal.R_aligned_to_vector(v0) # M = nps.matmult(dq_dv0, nps.transpose(Ruv[:2,:])) # # I pick the densest direction: highest |dq/dth| # pixels_per_rad = mrcal.worst_direction_stdev( nps.matmult( nps.transpose(M),M) ) dq_dazel = nps.matmult(dq_dv0, dv0_dazel) if pixels_per_deg_az < 0: pixels_per_deg_az_have = nps.mag(dq_dazel[:,0])*np.pi/180. pixels_per_deg_az *= -pixels_per_deg_az_have if pixels_per_deg_el < 0: pixels_per_deg_el_have = nps.mag(dq_dazel[:,1])*np.pi/180. pixels_per_deg_el *= -pixels_per_deg_el_have # I now have the desired pixels_per_deg # # With LENSMODEL_LATLON or LENSMODEL_LONLAT we have even angular spacing, so # q = f th + c -> dq/dth = f everywhere. I can thus compute the rectified # image size and adjust the resolution accordingly # # With LENSMODEL_PINHOLE this is much more complex, so this function just # leaves the desired pixels_per_deg as it is if rectification_model == 'LENSMODEL_LATLON' or \ rectification_model == 'LENSMODEL_LONLAT': Naz = round(az_fov_deg*pixels_per_deg_az) Nel = round(el_fov_deg*pixels_per_deg_el) pixels_per_deg_az = Naz/az_fov_deg pixels_per_deg_el = Nel/el_fov_deg return \ pixels_per_deg_az, \ pixels_per_deg_el def rectified_system(models, *, az_fov_deg, el_fov_deg, az0_deg = None, el0_deg = 0, pixels_per_deg_az = -1., pixels_per_deg_el = -1., rectification_model = 'LENSMODEL_LATLON', return_metadata = False): r'''Build rectified models for stereo rectification SYNOPSIS import sys import mrcal import cv2 import numpy as np import numpysane as nps models = [ mrcal.cameramodel(f) \ for f in ('left.cameramodel', 'right.cameramodel') ] images = [ mrcal.load_image(f) \ for f in ('left.jpg', 'right.jpg') ] models_rectified = \ mrcal.rectified_system(models, az_fov_deg = 120, el_fov_deg = 100) rectification_maps = mrcal.rectification_maps(models, models_rectified) images_rectified = [ mrcal.transform_image(images[i], rectification_maps[i]) \ for i in range(2) ] # Find stereo correspondences using OpenCV block_size = 3 max_disp = 160 # in pixels matcher = \ cv2.StereoSGBM_create(minDisparity = 0, numDisparities = max_disp, blockSize = block_size, P1 = 8 *3*block_size*block_size, P2 = 32*3*block_size*block_size, uniquenessRatio = 5, disp12MaxDiff = 1, speckleWindowSize = 50, speckleRange = 1) disparity16 = matcher.compute(*images_rectified) # in pixels*16 # Point cloud in rectified camera-0 coordinates # shape (H,W,3) p_rect0 = mrcal.stereo_unproject( disparity16, models_rectified, disparity_scale = 16 ) Rt_cam0_rect0 = mrcal.compose_Rt( models [0].extrinsics_Rt_fromref(), models_rectified[0].extrinsics_Rt_toref() ) # Point cloud in camera-0 coordinates # shape (H,W,3) p_cam0 = mrcal.transform_point_Rt(Rt_cam0_rect0, p_rect0) This function computes the parameters of a rectified system from two cameramodels in a stereo pair. The output is a pair of "rectified" models. Each of these is a normal mrcal.cameramodel object describing a "camera" somewhere in space, with some particular projection behavior. The pair of models returned here have the desired property that each row of pixels represents a plane in space AND each corresponding row in the pair of rectified images represents the SAME plane: the epipolar lines are aligned. We can use the rectified models returned by this function to transform the input images into "rectified" images, and then we can perform stereo matching efficiently, by treating each row independently. This function is generic: the two input cameras may use any lens models, any resolution and any geometry. They don't even have to match. As long as there's some non-zero baseline and some overlapping views, we can run stereo processing. The two rectified models describe the poses of the rectified cameras. Each rectified camera sits at the same position as the input camera, but with a different orientation. The orientations of the two cameras in the rectified system are identical. The only difference between the poses of the two rectified cameras is a translation of the second camera along the x axis. The axes of the rectified coordinate system: - x: from the origin of the first camera to the origin of the second camera (the baseline direction) - y: completes the system from x,z - z: the mean "forward" direction of the two input cameras, with the component parallel to the baseline subtracted off In a nominal geometry (the two cameras are square with each other, the second camera strictly to the right of the first camera), the geometry of the rectified models exactly matches the geometry of the input models. The above formulation supports any geometry, however, including vertical and/or forward/backward shifts. Vertical stereo is supported: we still run stereo matching on ROWS of the rectified images, but the rectification transformation will rotate the images by 90 degrees. Several projection functions may be used in the rectified system. These are selectable using the "rectification_model" keyword argument; they're a string representing the lensmodel that will be used in the cameramodel objects we return. Two projections are currently supported: - "LENSMODEL_LATLON": the default projection that utilizes a transverse equirectangular map. This projection has even angular spacing between pixels, so it works well even with wide lenses. The documentation has more information: http://mrcal.secretsauce.net/lensmodels.html#lensmodel-latlon - "LENSMODEL_PINHOLE": the traditional projection function that utilizes a pinhole camera. This works badly with wide lenses, and is recommended if compatibility with other stereo processes is desired ARGUMENTS - models: an iterable of two mrcal.cameramodel objects representing the cameras in the stereo pair. Any sane combination of lens models and resolutions and geometries is valid - az_fov_deg: required value for the azimuth (along-the-baseline) field-of-view of the desired rectified system, in degrees - el_fov_deg: required value for the elevation (across-the-baseline) field-of-view of the desired rectified system, in degrees. Note that this applies at the center of the rectified system: az = 0. With a skewed stereo system (if we have a forward/backward shift or if a nonzero az0_deg is given), this rectification center will not be at the horizontal center of the image, and may not be in-bounds of the image at all. - az0_deg: optional value for the azimuth center of the rectified images. This is especially significant in a camera system with some forward/backward shift. That causes the baseline to no longer be perpendicular with the view axis of the cameras, and thus the azimuth=0 vector no longer points "forward". If omitted, we compute az0_deg to align the center of the rectified system with the center of the two cameras' views. This computed value can be retrieved in the metadata dict by passing return_metadata = True - el0_deg: optional value for the elevation center of the rectified system. Defaults to 0. - pixels_per_deg_az: optional value for the azimuth resolution of the rectified image. If a resolution of >0 is requested, the value is used as is. If a resolution of <0 is requested, we use this as a scale factor on the resolution of the first input image. For instance, to downsample by a factor of 2, pass pixels_per_deg_az = -0.5. By default, we use -1: the resolution of the input image at the center of the rectified system. The value we end up with can be retrieved in the metadata dict by passing return_metadata = True - pixels_per_deg_el: same as pixels_per_deg_az but in the elevation direction - rectification_model: optional string that selects the projection function to use in the resulting rectified system. This is a string selecting the mrcal lens model. Currently supported are "LENSMODEL_LATLON" (the default) and "LENSMODEL_PINHOLE" - return_metadata: optional boolean, defaulting to False. If True, we return a dict of metadata describing the rectified system in addition to the rectified models. This is useful to retrieve any of the autodetected values. At this time, the metadata dict contains keys: - az_fov_deg - el_fov_deg - az0_deg - el0_deg - pixels_per_deg_az - pixels_per_deg_el - baseline RETURNED VALUES We compute a tuple of mrcal.cameramodels describing the two rectified cameras. These two models are identical, except for a baseline translation in the +x direction in rectified coordinates. if not return_metadata: we return this tuple of models else: we return this tuple of models, dict of metadata ''' for m in models: lensmodel = m.intrinsics()[0] meta = mrcal.lensmodel_metadata_and_config(lensmodel) if meta['noncentral']: if re.match("^LENSMODEL_CAHVORE", lensmodel): if nps.norm2(m.intrinsics()[1][-3:]) > 0: raise Exception("Stereo rectification is only possible with a central projection. Please centralize your models. This is CAHVORE, so set E=0 to centralize. This will ignore all noncentral effects near the lens") else: raise Exception("Stereo rectification is only possible with a central projection. Please centralize your models") if rectification_model == 'LENSMODEL_PINHOLE': # The pinhole rectification path is not implemented in C yet. Call the # Python return _rectified_system_python(models, az_fov_deg = az_fov_deg, el_fov_deg = el_fov_deg, az0_deg = az0_deg, el0_deg = el0_deg, pixels_per_deg_az = pixels_per_deg_az, pixels_per_deg_el = pixels_per_deg_el, rectification_model = rectification_model, return_metadata = return_metadata) # The guts of this function are implemented in C. Call that pixels_per_deg_az, \ pixels_per_deg_el, \ Naz, Nel, \ fxycxy_rectified, \ rt_rect0_ref, \ baseline, \ az_fov_deg, \ el_fov_deg, \ az0_deg, \ el0_deg = \ mrcal._mrcal._rectified_system(*models[0].intrinsics(), models[0].extrinsics_rt_fromref(), models[1].extrinsics_rt_fromref(), az_fov_deg = az_fov_deg, el_fov_deg = el_fov_deg, az0_deg = az0_deg if az0_deg is not None else 1e7, el0_deg = el0_deg, pixels_per_deg_az = pixels_per_deg_az, pixels_per_deg_el = pixels_per_deg_el, rectification_model = rectification_model) ######## The geometry # rect1 coord system has the same orientation as rect0, but translated by # baseline in the x direction (its origin is at the origin of cam1) # rt_rect0_rect1 = (0,0,0, baseline,0,0) # rt_rect1_ref = rt_rect1_rect0 rt_rect0_ref rt_rect1_ref = rt_rect0_ref.copy() rt_rect1_ref[3] -= baseline models_rectified = \ ( mrcal.cameramodel( intrinsics = (rectification_model, fxycxy_rectified), imagersize = (Naz, Nel), extrinsics_rt_fromref = rt_rect0_ref), mrcal.cameramodel( intrinsics = (rectification_model, fxycxy_rectified), imagersize = (Naz, Nel), extrinsics_rt_fromref = rt_rect1_ref) ) if not return_metadata: return models_rectified metadata = \ dict( az_fov_deg = az_fov_deg, el_fov_deg = el_fov_deg, az0_deg = az0_deg, el0_deg = el0_deg, pixels_per_deg_az = pixels_per_deg_az, pixels_per_deg_el = pixels_per_deg_el, baseline = baseline ) return models_rectified, metadata def _rectified_system_python(models, *, az_fov_deg, el_fov_deg, az0_deg = None, el0_deg = 0, pixels_per_deg_az = -1., pixels_per_deg_el = -1., rectification_model = 'LENSMODEL_LATLON', return_metadata = False): r'''Reference implementation of mrcal_rectified_system() in python The main implementation is written in C in stereo.c: mrcal_rectified_system() This should be identical to the rectified_system() function above. There's no explicit test to compare the two implementations, but test/test-stereo.py should catch any differences. NOTE: THE C IMPLEMENTATION HANDLES LENSMODEL_LATLON only. The mrcal.rectified_system() wrapper above calls THIS function in that case ''' if not (rectification_model == 'LENSMODEL_LATLON' or \ rectification_model == 'LENSMODEL_PINHOLE'): raise(f"Unsupported rectification model '{rectification_model}'. Only LENSMODEL_LATLON and LENSMODEL_PINHOLE are supported.") if len(models) != 2: raise Exception("I need exactly 2 camera models") if pixels_per_deg_az == 0: raise Exception("pixels_per_deg_az == 0 is illegal. Must be >0 if we're trying to specify a value, or <0 to autodetect") if pixels_per_deg_el == 0: raise Exception("pixels_per_deg_el == 0 is illegal. Must be >0 if we're trying to specify a value, or <0 to autodetect") if az_fov_deg is None or el_fov_deg is None or \ az_fov_deg <= 0. or el_fov_deg <= 0.: raise Exception("az_fov_deg, el_fov_deg must be > 0. No auto-detection implemented yet") ######## Compute the geometry of the rectified stereo system. This is a ######## rotation, centered at camera0. More or less we have axes: ######## ######## x: from camera0 to camera1 ######## y: completes the system from x,z ######## z: component of the cameras' viewing direction ######## normal to the baseline Rt01 = mrcal.compose_Rt( models[0].extrinsics_Rt_fromref(), models[1].extrinsics_Rt_toref()) # Rotation relating camera0 coords to the rectified camera coords. I fill in # each row separately Rt_rect0_cam0 = np.zeros((4,3), dtype=float) R_rect0_cam0 = Rt_rect0_cam0[:3,:] # Axes of the rectified system, in the cam0 coord system right = R_rect0_cam0[0,:] down = R_rect0_cam0[1,:] forward = R_rect0_cam0[2,:] # "right" of the rectified coord system: towards the origin of camera1 from # camera0, in camera0 coords right[:] = Rt01[3,:] baseline = nps.mag(right) right /= baseline # "forward" for each of the two cameras, in the cam0 coord system forward0 = np.array((0,0,1.)) forward1 = Rt01[:3,2] # "forward" of the rectified coord system, in camera0 coords. The mean # optical-axis direction of the two cameras: component orthogonal to "right" forward01 = forward0 + forward1 forward01_proj_right = nps.inner(forward01,right) forward[:] = forward01 - forward01_proj_right*right forward /= nps.mag(forward) # "down" of the rectified coord system, in camera0 coords. Completes the # right,down,forward coordinate system down[:] = np.cross(forward,right) ######## Done with the geometry! Now to get the az/el grid. I need to figure ######## out the resolution and the extents if az0_deg is not None: az0 = az0_deg * np.pi/180. else: # In the rectified system az=0 sits perpendicular to the baseline. # Normally the cameras are looking out perpendicular to the baseline # also, so I center my azimuth samples around 0 to match the cameras' # field of view. But what if the geometry isn't square, and one camera # is behind the other? Like this: # # camera # view # ^ # | # \ | / # \_/ # . / # . /az=0 # ./ # . # baseline . # . # \ / # \_/ # # Here the center-of-view axis of each camera is not at all # perpendicular to the baseline. Thus I compute the mean "forward" # direction of the cameras in the rectified system, and set that as the # center azimuth az0. az0 = np.arcsin( forward01_proj_right / nps.mag(forward01) ) az0_deg = az0 * 180./np.pi el0 = el0_deg * np.pi/180. pixels_per_deg_az, \ pixels_per_deg_el = \ mrcal.rectified_resolution(models[0], az_fov_deg = az_fov_deg, el_fov_deg = el_fov_deg, az0_deg = az0_deg, el0_deg = el0_deg, R_cam0_rect0 = nps.transpose(R_rect0_cam0), pixels_per_deg_az = pixels_per_deg_az, pixels_per_deg_el = pixels_per_deg_el, rectification_model = rectification_model) # How do we apply the desired pixels_per_deg? # # With LENSMODEL_LATLON we have even angular spacing, so q = f th + c -> # dq/dth = f everywhere. # # With LENSMODEL_PINHOLE the angular resolution changes across the image: q # = f tan(th) + c -> dq/dth = f/cos^2(th). So at the center, th=0 and we # have the maximum resolution fxycxy = np.array((pixels_per_deg_az / np.pi*180., pixels_per_deg_el / np.pi*180., 0., 0.), dtype=float) if rectification_model == 'LENSMODEL_LATLON': # The angular resolution is consistent everywhere, so fx,fy are already # set. Let's set cx,cy such that # (az0,el0) = unproject(imager center) Naz = round(az_fov_deg*pixels_per_deg_az) Nel = round(el_fov_deg*pixels_per_deg_el) fxycxy[2:] = \ np.array(((Naz-1.)/2.,(Nel-1.)/2.)) - \ np.array((az0,el0)) * fxycxy[:2] elif rectification_model == 'LENSMODEL_PINHOLE': cos_az0 = np.cos(az0) cos_el0 = np.cos(el0) fxycxy[0] *= cos_az0*cos_az0 fxycxy[1] *= cos_el0*cos_el0 # fx,fy are set. Let's set cx,cy. Unlike the LENSMODEL_LATLON case, this # is asymmetric, so I explicitly solve for (cx,Naz). cy,Nel work the # same way. I want # # tan(az0)*fx + cx = (Naz-1)/2 # # inner( normalized(unproject(x=0)), # normalized(unproject(x=Naz-1)) ) = cos(fov) # # unproject(x=0 ) = [ (0 - cx)/fx, 0, 1] # unproject(x=Naz-1) = [ (Naz-1 - cx)/fx, 0, 1] # # -> v0 ~ [ -cx/fx, 0, 1] # -> v1 ~ [ 2*tanaz0 + cx/fx, 0, 1] # # Let K = 2*tanaz0 (we have K). Let C = cx/fx (we want to find C) # -> v0 ~ [-C,1], v1 ~ [K+C,1] # -> cosfov = (1 - K*C - C^2) / sqrt( (1+C^2)*(1+C^2+K^2+2*K*C)) # -> cos2fov*(1+C^2)*(1+C^2+K^2+2*K*C) - (1 - K*C - C^2)^2 = 0 # -> 0 = # C^4 * (cos2fov - 1) + # C^3 * 2 K (cos2fov - 1 ) + # C^2 * (cos2fov K^2 + 2 cos2fov - K^2 + 2) + # C * 2 K ( cos2fov + 1 ) + # cos2fov ( K^2 + 1 ) - 1 # # I can solve this numerically def cxy(fxy, tanazel0, fov_deg): cosfov = np.cos(fov_deg*np.pi/180.) cos2fov = cosfov*cosfov K = 2.*tanazel0 C = np.roots( [ (cos2fov - 1), 2.* K * (cos2fov - 1 ), cos2fov * K*K + 2.*cos2fov - K*K + 2, 2.* K * (cos2fov + 1 ), cos2fov * (K*K + 1.) - 1 ] ) # Some numerical fuzz (if fov ~ 90deg) may give me slightly # imaginary numbers, so I just look at the real component. # Similarly, I allow a bit of numerical fuzz in the logic below C = np.real(C) # I solve my quadratic polynomial numerically. I get 4 solutions, # and I need to throw out the invalid ones. # # fov may be > 90deg, so cos(fov) may be <0. The solution will make # sure that cos^2(fov) matches up, but the solution may assume the # wrong sign for cos(fov). From above: # # cosfov = (1 - K*C - C^2) / sqrt( (1+C^2)*(1+C^2+K^2+2*K*C)) # # So I must have cosfov*(1 - K*C - C^2) > 0 C = C[cosfov*(1 - K*C - C*C) >= -1e-9] # And the implied imager size MUST be positive C = C[(tanazel0*fxy + C*fxy)*2. + 1 > 0] if len(C) == 0: raise Exception("Couldn't compute the rectified pinhole center pixel. Something is wrong.") # I should have exactly one solution let. Due to some numerical # fuzz, I might have more, and I pick the most positive one in the # condition above return C[np.argmax(cosfov*(1 - K*C - C*C))] * fxy tanaz0 = np.tan(az0) tanel0 = np.tan(el0) fxycxy[2] = cxy(fxycxy[0], tanaz0, az_fov_deg) fxycxy[3] = cxy(fxycxy[1], tanel0, el_fov_deg) Naz = round((tanaz0*fxycxy[0] + fxycxy[2])*2.) + 1 Nel = round((tanel0*fxycxy[1] + fxycxy[3])*2.) + 1 else: raise Exception("Shouldn't get here; This case was checked above") if Nel <= 0: raise Exception(f"Resulting stereo geometry has Nel={Nel}. This is nonsensical. You should examine the geometry or adjust the elevation bounds or pixels-per-deg") ######## The geometry Rt_rect0_ref = mrcal.compose_Rt( Rt_rect0_cam0, models[0].extrinsics_Rt_fromref()) # rect1 coord system has the same orientation as rect0, but is translated so # that its origin is at the origin of cam1 R_rect1_cam0 = R_rect0_cam0 R_rect1_cam1 = nps.matmult(R_rect1_cam0, Rt01[:3,:]) Rt_rect1_cam1 = nps.glue(R_rect1_cam1, np.zeros((3,),), axis=-2) Rt_rect1_ref = mrcal.compose_Rt( Rt_rect1_cam1, models[1].extrinsics_Rt_fromref()) models_rectified = \ ( mrcal.cameramodel( intrinsics = (rectification_model, fxycxy), imagersize = (Naz, Nel), extrinsics_Rt_fromref = Rt_rect0_ref), mrcal.cameramodel( intrinsics = (rectification_model, fxycxy), imagersize = (Naz, Nel), extrinsics_Rt_fromref = Rt_rect1_ref) ) if not return_metadata: return models_rectified metadata = \ dict( az_fov_deg = az_fov_deg, el_fov_deg = el_fov_deg, az0_deg = az0 * 180./np.pi, el0_deg = el0_deg, pixels_per_deg_az = pixels_per_deg_az, pixels_per_deg_el = pixels_per_deg_el, baseline = baseline ) return models_rectified, metadata def _validate_models_rectified(models_rectified): r'''Internal function to validate a rectified system These should have been returned by rectified_system(). Should have two LENSMODEL_LATLON or LENSMODEL_PINHOLE cameras with identical intrinsics. extrinsics should be identical too EXCEPT for a baseline translation in the x rectified direction ''' if len(models_rectified) != 2: raise Exception(f"Must have received exactly two models. Got {len(models_rectified)} instead") intrinsics = [m.intrinsics() for m in models_rectified] Rt01 = mrcal.compose_Rt( models_rectified[0].extrinsics_Rt_fromref(), models_rectified[1].extrinsics_Rt_toref()) if not ( (intrinsics[0][0] == 'LENSMODEL_LATLON' and intrinsics[1][0] == 'LENSMODEL_LATLON' ) or \ (intrinsics[0][0] == 'LENSMODEL_PINHOLE' and intrinsics[1][0] == 'LENSMODEL_PINHOLE') ): raise Exception(f"Expected two models with the same 'LENSMODEL_LATLON' or 'LENSMODEL_PINHOLE' but got {intrinsics[0][0]} and {intrinsics[1][0]}") if nps.norm2(intrinsics[0][1] - intrinsics[1][1]) > 1e-6: raise Exception("The two rectified models MUST have the same intrinsics values") imagersize_diff = \ np.array(models_rectified[0].imagersize()) - \ np.array(models_rectified[1].imagersize()) if imagersize_diff[0] != 0 or imagersize_diff[1] != 0: raise Exceptions("The two rectified models MUST have the same imager size") costh = (np.trace(Rt01[:3,:]) - 1.) / 2. if costh < 0.999999: raise Exception("The two rectified models MUST have the same relative rotation") if nps.norm2(Rt01[3,1:]) > 1e-9: raise Exception("The two rectified models MUST have a translation ONLY in the +x rectified direction") def rectification_maps(models, models_rectified): r'''Construct image transformation maps to make rectified images SYNOPSIS import sys import mrcal import cv2 import numpy as np import numpysane as nps models = [ mrcal.cameramodel(f) \ for f in ('left.cameramodel', 'right.cameramodel') ] images = [ mrcal.load_image(f) \ for f in ('left.jpg', 'right.jpg') ] models_rectified = \ mrcal.rectified_system(models, az_fov_deg = 120, el_fov_deg = 100) rectification_maps = mrcal.rectification_maps(models, models_rectified) images_rectified = [ mrcal.transform_image(images[i], rectification_maps[i]) \ for i in range(2) ] # Find stereo correspondences using OpenCV block_size = 3 max_disp = 160 # in pixels matcher = \ cv2.StereoSGBM_create(minDisparity = 0, numDisparities = max_disp, blockSize = block_size, P1 = 8 *3*block_size*block_size, P2 = 32*3*block_size*block_size, uniquenessRatio = 5, disp12MaxDiff = 1, speckleWindowSize = 50, speckleRange = 1) disparity16 = matcher.compute(*images_rectified) # in pixels*16 # Point cloud in rectified camera-0 coordinates # shape (H,W,3) p_rect0 = mrcal.stereo_unproject( disparity16, models_rectified, disparity_scale = 16 ) Rt_cam0_rect0 = mrcal.compose_Rt( models [0].extrinsics_Rt_fromref(), models_rectified[0].extrinsics_Rt_toref() ) # Point cloud in camera-0 coordinates # shape (H,W,3) p_cam0 = mrcal.transform_point_Rt(Rt_cam0_rect0, p_rect0) After the pair of rectified models has been built by mrcal.rectified_system(), this function can be called to compute the rectification maps. These can be passed to mrcal.transform_image() to remap input images into the rectified space. The documentation for mrcal.rectified_system() applies here. This function is implemented in C in the mrcal_rectification_maps() function. An equivalent Python implementation is available: mrcal.stereo._rectification_maps_python() ARGUMENTS - models: an iterable of two mrcal.cameramodel objects representing the cameras in the stereo pair - models_rectified: the pair of rectified models, corresponding to the input images. Usually this is returned by mrcal.rectified_system() RETURNED VALUES We return a length-2 tuple of numpy arrays containing transformation maps for each camera. Each map can be used to mrcal.transform_image() images into rectified space. Each array contains 32-bit floats (as expected by mrcal.transform_image() and cv2.remap()). Each array has shape (Nel,Naz,2), where (Nel,Naz) is the shape of each rectified image. Each shape-(2,) row contains corresponding pixel coordinates in the input image ''' _validate_models_rectified(models_rectified) Naz,Nel = models_rectified[0].imagersize() # shape (Ncameras=2, Nel, Naz, Nxy=2) rectification_maps = np.zeros((2, Nel, Naz, 2), dtype = np.float32) mrcal._mrcal._rectification_maps(*models[0].intrinsics(), *models[1].intrinsics(), *models_rectified[0].intrinsics(), r_cam0_ref = models[0].extrinsics_rt_fromref()[:3], r_cam1_ref = models[1].extrinsics_rt_fromref()[:3], r_rect0_ref = models_rectified[0].extrinsics_rt_fromref()[:3], rectification_maps = rectification_maps) return rectification_maps def _rectification_maps_python(models, models_rectified): r'''Reference implementation of mrcal.rectification_maps() in python The main implementation is written in C in stereo.c: mrcal_rectification_maps() This should be identical to the rectification_maps() function above. This is checked by the test-rectification-maps.py test. ''' Naz,Nel = models_rectified[0].imagersize() fxycxy = models_rectified[0].intrinsics()[1] R_cam_rect = [ nps.matmult(models [i].extrinsics_Rt_fromref()[:3,:], models_rectified[i].extrinsics_Rt_toref ()[:3,:]) \ for i in range(2) ] # This is massively inefficient. I should # # - Not generate any intermediate ARRAYS, but loop through each pixel, and # perform the full transformation on each pixel. All the way through the # project(v0, ...) below # # - Not compute full sin/cos separately for each pixel, but take advantage # of my even angle steps to compute the sin/cos once, and take # multiplication/addition steps from there # shape (Nel,Naz,3) if models_rectified[0].intrinsics()[0] == 'LENSMODEL_LATLON': unproject = mrcal.unproject_latlon else: unproject = mrcal.unproject_pinhole az, el = \ np.meshgrid(np.arange(Naz,dtype=float), np.arange(Nel,dtype=float)) v = unproject( np.ascontiguousarray( \ nps.mv( nps.cat(az,el), 0, -1)), fxycxy) v0 = mrcal.rotate_point_R(R_cam_rect[0], v) v1 = mrcal.rotate_point_R(R_cam_rect[1], v) return \ (mrcal.project( v0, *models[0].intrinsics()).astype(np.float32), \ mrcal.project( v1, *models[1].intrinsics()).astype(np.float32)) def stereo_range(disparity, models_rectified, *, disparity_scale = 1, disparity_min = None, disparity_scaled_min = None, disparity_max = None, disparity_scaled_max = None, qrect0 = None): r'''Compute ranges from observed disparities SYNOPSIS import sys import mrcal import cv2 import numpy as np import numpysane as nps models = [ mrcal.cameramodel(f) \ for f in ('left.cameramodel', 'right.cameramodel') ] images = [ mrcal.load_image(f) \ for f in ('left.jpg', 'right.jpg') ] models_rectified = \ mrcal.rectified_system(models, az_fov_deg = 120, el_fov_deg = 100) rectification_maps = mrcal.rectification_maps(models, models_rectified) images_rectified = [ mrcal.transform_image(images[i], rectification_maps[i]) \ for i in range(2) ] # Find stereo correspondences using OpenCV block_size = 3 max_disp = 160 # in pixels matcher = \ cv2.StereoSGBM_create(minDisparity = 0, numDisparities = max_disp, blockSize = block_size, P1 = 8 *3*block_size*block_size, P2 = 32*3*block_size*block_size, uniquenessRatio = 5, disp12MaxDiff = 1, speckleWindowSize = 50, speckleRange = 1) disparity16 = matcher.compute(*images_rectified) # in pixels*16 # Convert the disparities to range-to-camera0 ranges = mrcal.stereo_range( disparity16, models_rectified, disparity_scale = 16 ) H,W = disparity16.shape # shape (H,W,2) q = np.ascontiguousarray( \ nps.mv( nps.cat( *np.meshgrid(np.arange(W,dtype=float), np.arange(H,dtype=float))), 0, -1)) # Point cloud in rectified camera-0 coordinates # shape (H,W,3) p_rect0 = \ mrcal.unproject_latlon(q, models_rectified[0].intrinsics()[1]) * \ nps.dummy(ranges, axis=-1) Rt_cam0_rect0 = mrcal.compose_Rt( models [0].extrinsics_Rt_fromref(), models_rectified[0].extrinsics_Rt_toref() ) # Point cloud in camera-0 coordinates # shape (H,W,3) p_cam0 = mrcal.transform_point_Rt(Rt_cam0_rect0, p_rect0) As shown in the example above, we can perform stereo processing by building rectified models and transformation maps, rectifying our images, and then doing stereo matching to get pixel disparities. The disparities can be converted to usable geometry by calling one of two functions: - stereo_range() to convert pixel disparities to ranges - stereo_unproject() to convert pixel disparities to a point cloud. This is a superset of stereo_range() In the most common usage of stereo_range() we take a full disparity IMAGE, and then convert it to a range IMAGE. In this common case we call range_image = mrcal.stereo_range(disparity_image, models_rectified) If we aren't processing the full disparity image, we can pass in an array of rectified pixel coordinates (in the first rectified camera) in the "qrect0" argument. These must be broadcastable with the disparity argument. So we can pass in a scalar for disparity and a single (2,) array for qrect0. Or we can pass in full arrays for both. Or we can pass in a shape (H,W) image for disparity, but only a shape (W,2) array for qrect0: this would use the same qrect0 value for a whole column of disparity, as dictated by the broadcasting rules. Such identical-az-in-a-column behavior is valid for LENSMODEL_LATLON stereo, but not for LENSMODEL_PINHOLE stereo. It's the user's responsibility to know when to omit data like this. When in doubt, pass a separate qrect0 for each disparity value. Each epipolar plane looks like this: camera0 + . . . . \ az0 |---------------- | \-------------------- | range \----------------------- | \-------- p | a -----/ | -----/ | -----/ |baseline -----/ | -----/ | -----/ | -----/ | -----/ | -----/ | -----/ | -----/ ---/ az1 +. . . . . camera1 The cameras are at the top-left and bottom-left of the figure, looking out to the right at a point p in space. The observation ray from camera0 makes an angle az0 with the "forward" direction (here az0 > 0), while the observation ray from camera1 makes an angle az1 (here az1 < 0). A LENSMODEL_LATLON disparity is a difference of azimuth angles: disparity ~ az0-az1. A LENSMODEL_PINHOLE disparity is a scaled difference of tangents: disparity ~ tan(az0)-tan(az1) The law of sines tells us that baseline / sin(a) = range / sin(90 + az1) Thus range = baseline cos(az1) / sin(a) = = baseline cos(az1) / sin( 180 - (90-az0 + 90+az1) ) = = baseline cos(az1) / sin(az0-az1) = = baseline cos(az0 - az0-az1) / sin(az0-az1) az0-az1 is the angular disparity. If using LENSMODEL_LATLON, this is what we have, and this is a usable expression. Otherwise we keep going: range = baseline cos(az0 - az0-az1) / sin(az0-az1) = baseline (cos(az0)cos(az0-az1) + sin(az0)sin(az0-az1)) / sin(az0-az1) = baseline cos(az0)/tan(az0-az1) + sin(az0) = baseline cos(az0)* (1 + tan(az0)tan(az1))/(tan(az0) - tan(az1)) + sin(az0) = baseline cos(az0)*((1 + tan(az0)tan(az1))/(tan(az0) - tan(az1)) + tan(az0)) A scaled tan(az0)-tan(az1) is the disparity when using LENSMODEL_PINHOLE, so this is the final expression we use. When using LENSMODEL_LATLON, the azimuth values in the projection ARE the azimuth values inside each epipolar plane, so there's nothing extra to do. When using LENSMODEL_PINHOLE however, there's an extra step. We need to convert pixel disparity values to az0 and az1. Let's say we're looking two rectified pinhole points on the same epipolar plane, a "forward" point and a "query" point: q0 = [0, qy] and q1 = [qx1, qy] We convert these to normalized coords: tanxy = (q-cxy)/fxy t0 = [0, ty] and t1 = [tx1, ty] These unproject to v0 = [0, ty, 1] and v1 = [tx1, ty, 1] These lie on an epipolar plane with normal [0, -1, ty]. I define a coordinate system basis using the normal as one axis. The other two axes are b0 = [1, 0, 0 ] b1 = [0, ty/L, 1/L] where L = sqrt(ty^2 + 1) Projecting my two vectors to (b0,b1) I get [0, ty^2/L + 1/L] [tx1, ty^2/L + 1/L] Thus the the angle this query point makes with the "forward" vector is tan(az_in_epipolar_plane) = tx1 / ( (ty^2 + 1)/L ) = tx1 / sqrt(ty^2 + 1) Thus to get tan(az) expressions we use to compute ranges, we need to scale our (qx1-cx)/fx values by 1./sqrt(ty^2 + 1). This is one reason to use LENSMODEL_LATLON for stereo processing instead of LENSMODEL_PINHOLE: the az angular scale stays constant across different el, which produces better stereo matches. ARGUMENTS - disparity: a numpy array of disparities being processed. If disparity_scale is omitted, this array contains floating-point disparity values in PIXELS. Many stereo-matching algorithms produce integer disparities, in units of some constant number of pixels (the OpenCV StereoSGBM and StereoBM routines use 16). In this common case, you can pass the integer scaled disparities here, with the scale factor in disparity_scale. Any array shape is supported. In the common case of a disparity IMAGE, this is an array of shape (Nel, Naz) - models_rectified: the pair of rectified models, corresponding to the input images. Usually this is returned by mrcal.rectified_system() - disparity_scale: optional scale factor for the "disparity" array. If omitted, the "disparity" array is assumed to contain the disparities, in pixels. Otherwise it contains data in the units of 1/disparity_scale pixels. - disparity_min: optional minimum-expected disparity value. If omitted, disparity_min = 0 is assumed. disparity below this limit is interpreted as an invalid value: range=0 is reported. This has units of "pixels", so we scale by disparity_scale before comparing to the dense stereo correlator result - disparity_max: optional maximum-expected disparity value. If omitted, no maximum exists. Works the same as disparity_min - disparity_scaled_min disparity_scaled_max: optional disparity values with the disparity_scaled already applied. These can be compared directly against the scaled disparity values. Both the scaled and unscaled flavors of these may NOT be given - qrect0: optional array of rectified camera0 pixel coordinates corresponding to the given disparities. By default, a full disparity image is assumed. Otherwise we use the given rectified coordinates. The shape of this array must be broadcasting-compatible with the disparity array. See the description above. RETURNED VALUES - An array of ranges of the same dimensionality as the input disparity array. Contains floating-point data. Invalid or missing ranges are represented as 0. ''' _validate_models_rectified(models_rectified) if disparity_min is not None and disparity_scaled_min is not None and \ disparity_min != disparity_scaled_min: raise Exception("disparity_min and disparity_scaled_min may not both be given") if disparity_max is not None and disparity_scaled_max is not None and \ disparity_max != disparity_scaled_max: raise Exception("disparity_max and disparity_scaled_max may not both be given") if qrect0 is None: if disparity_scaled_min is None: if disparity_min is None: disparity_scaled_min = 0 else: disparity_scaled_min = disparity_min * disparity_scale if disparity_scaled_max is None: if disparity_max is None: disparity_scaled_max = np.uint16(np.iinfo(np.uint16).max) else: disparity_scaled_max = disparity_max * disparity_scale else: if disparity_min is None: if disparity_scaled_min is None: disparity_min = 0 else: disparity_min = disparity_scaled_min / disparity_scale if disparity_max is None: if disparity_scaled_max is None: disparity_max = np.finfo(float).max else: disparity_max = disparity_scaled_max / disparity_scale # I want to support scalar disparities. If one is given, I convert it into # an array of shape (1,), and then pull it out at the end is_scalar = False try: s = disparity.shape except: is_scalar = True if not is_scalar: if len(s) == 0: is_scalar = True if is_scalar: disparity = np.array((disparity,),) Rt01 = mrcal.compose_Rt( models_rectified[0].extrinsics_Rt_fromref(), models_rectified[1].extrinsics_Rt_toref()) baseline = nps.mag(Rt01[3,:]) if qrect0 is None: W,H = models_rectified[0].imagersize() if np.any(disparity.shape - np.array((H,W),dtype=int)): raise Exception(f"qrect0 is None, so the disparity image must have the full dimensions of a rectified image") r = \ mrcal._mrcal_npsp._stereo_range_dense \ ( disparity_scaled = disparity.astype(np.uint16), disparity_scale = np.uint16(disparity_scale), disparity_scaled_min = np.uint16(disparity_scaled_min), disparity_scaled_max = np.uint16(disparity_scaled_max), rectification_model_type = models_rectified[0].intrinsics()[0], fxycxy_rectified = models_rectified[0].intrinsics()[1].astype(float), baseline = baseline ) else: r = \ mrcal._mrcal_npsp._stereo_range_sparse \ ( disparity = disparity.astype(float) / disparity_scale, qrect0 = qrect0.astype(float), disparity_min = float(disparity_min), disparity_max = float(disparity_max), rectification_model_type = models_rectified[0].intrinsics()[0], fxycxy_rectified = models_rectified[0].intrinsics()[1].astype(float), baseline = baseline ) if is_scalar: r = r[0] return r def _stereo_range_python(disparity, models_rectified, *, disparity_scale = 1, disparity_min = None, disparity_scaled_min = None, disparity_max = None, disparity_scaled_max = None, qrect0 = None): r'''Reference implementation of mrcal.stereo_range() in python The main implementation is written in C in stereo.c: mrcal_stereo_range_sparse() and mrcal_stereo_range_dense() This should be identical to the stereo_range() function above. This is checked by the test-stereo-range.py test. ''' _validate_models_rectified(models_rectified) if disparity_min is not None and disparity_scaled_min is not None and \ disparity_min != disparity_scaled_min: raise Exception("disparity_min and disparity_scaled_min may not both be given") if disparity_max is not None and disparity_scaled_max is not None and \ disparity_max != disparity_scaled_max: raise Exception("disparity_max and disparity_scaled_max may not both be given") if qrect0 is None: if disparity_scaled_min is None: if disparity_min is None: disparity_scaled_min = 0 else: disparity_scaled_min = disparity_min * disparity_scale if disparity_scaled_max is None: if disparity_max is None: disparity_scaled_max = np.uint16(np.iinfo(np.uint16).max) else: disparity_scaled_max = disparity_max * disparity_scale else: if disparity_min is None: if disparity_scaled_min is None: disparity_min = 0 else: disparity_min = disparity_scaled_min / disparity_scale if disparity_max is None: if disparity_scaled_max is None: disparity_max = np.finfo(float).max else: disparity_max = disparity_scaled_max / disparity_scale # I want to support scalar disparities. If one is given, I convert it into # an array of shape (1,), and then pull it out at the end is_scalar = False try: s = disparity.shape except: is_scalar = True if not is_scalar: if len(s) == 0: is_scalar = True if is_scalar: disparity = np.array((disparity,),) W,H = models_rectified[0].imagersize() if qrect0 is None and np.any(disparity.shape - np.array((H,W),dtype=int)): raise Exception(f"qrect0 is None, so the disparity image must have the full dimensions of a rectified image") intrinsics = models_rectified[0].intrinsics() fx = intrinsics[1][0] cx = intrinsics[1][2] Rt01 = mrcal.compose_Rt( models_rectified[0].extrinsics_Rt_fromref(), models_rectified[1].extrinsics_Rt_toref()) baseline = nps.mag(Rt01[3,:]) if qrect0 is None: mask_invalid = \ (disparity < disparity_scaled_min) + \ (disparity > disparity_scaled_max) + \ (disparity <= 0) else: mask_invalid = \ (disparity / disparity_scale < disparity_min) + \ (disparity / disparity_scale > disparity_max) + \ (disparity <= 0) if intrinsics[0] == 'LENSMODEL_LATLON': if qrect0 is None: az0 = (np.arange(W, dtype=float) - cx)/fx else: az0 = (qrect0[...,0] - cx)/fx disparity_rad = disparity.astype(np.float32) / (fx * disparity_scale) s = np.sin(disparity_rad) s[mask_invalid] = 1 # to prevent division by 0 r = baseline * np.cos(az0 - disparity_rad) / s else: # pinhole fy = intrinsics[1][1] cy = intrinsics[1][3] if qrect0 is None: # shape (W,) tanaz0 = (np.arange(W, dtype=float) - cx)/fx # shape (H,1) tanel = (np.arange(H, dtype=float) - cy)/fy tanel = nps.dummy(tanel, -1) else: tanaz0 = (qrect0[...,0] - cx) / fx tanel = (qrect0[...,1] - cy) / fy s_sq_recip = tanel*tanel + 1. tanaz0_tanaz1 = disparity.astype(np.float32) / (fx * disparity_scale) tanaz0_tanaz1[mask_invalid] = 1 # to prevent division by 0 tanaz1 = tanaz0 - tanaz0_tanaz1 r = baseline / \ np.sqrt(s_sq_recip + tanaz0*tanaz0) * \ ((s_sq_recip + tanaz0*tanaz1) / tanaz0_tanaz1 + \ tanaz0) mask_invalid += ~np.isfinite(r) r[mask_invalid] = 0 if is_scalar: r = r[0] return r def stereo_unproject(disparity, models_rectified, *, ranges = None, disparity_scale = 1, qrect0 = None): r'''Compute a point cloud from observed disparities SYNOPSIS import sys import mrcal import cv2 import numpy as np import numpysane as nps models = [ mrcal.cameramodel(f) \ for f in ('left.cameramodel', 'right.cameramodel') ] images = [ mrcal.load_image(f) \ for f in ('left.jpg', 'right.jpg') ] models_rectified = \ mrcal.rectified_system(models, az_fov_deg = 120, el_fov_deg = 100) rectification_maps = mrcal.rectification_maps(models, models_rectified) images_rectified = [ mrcal.transform_image(images[i], rectification_maps[i]) \ for i in range(2) ] # Find stereo correspondences using OpenCV block_size = 3 max_disp = 160 # in pixels matcher = \ cv2.StereoSGBM_create(minDisparity = 0, numDisparities = max_disp, blockSize = block_size, P1 = 8 *3*block_size*block_size, P2 = 32*3*block_size*block_size, uniquenessRatio = 5, disp12MaxDiff = 1, speckleWindowSize = 50, speckleRange = 1) disparity16 = matcher.compute(*images_rectified) # in pixels*16 # Point cloud in rectified camera-0 coordinates # shape (H,W,3) p_rect0 = mrcal.stereo_unproject( disparity16, models_rectified, disparity_scale = 16 ) Rt_cam0_rect0 = mrcal.compose_Rt( models [0].extrinsics_Rt_fromref(), models_rectified[0].extrinsics_Rt_toref() ) # Point cloud in camera-0 coordinates # shape (H,W,3) p_cam0 = mrcal.transform_point_Rt(Rt_cam0_rect0, p_rect0) As shown in the example above, we can perform stereo processing by building rectified models and transformation maps, rectifying our images, and then doing stereo matching to get pixel disparities. The disparities can be converted to usable geometry by calling one of two functions: - stereo_range() to convert pixel disparities to ranges - stereo_unproject() to convert pixel disparities to a point cloud, each point in the rectified-camera-0 coordinates. This is a superset of stereo_range() In the most common usage of stereo_unproject() we take a full disparity IMAGE, and then convert it to a dense point cloud: one point per pixel. In this common case we call p_rect0 = mrcal.stereo_unproject(disparity_image, models_rectified) If we aren't processing the full disparity image, we can pass in an array of rectified pixel coordinates (in the first rectified camera) in the "qrect0" argument. These must be broadcastable with the disparity argument. The arguments are identical to those accepted by stereo_range(), except an optional "ranges" argument is accepted. This can be given in lieu of the "disparity" argument, if we already have ranges returned by stereo_range(). Exactly one of (disparity,ranges) must be given as non-None. "ranges" is a keyword-only argument, while "disparity" is positional. So if passing ranges, the disparity must be explicitly given as None: p_rect0 = mrcal.stereo_unproject( disparity = None, models_rectified = models_rectified, ranges = ranges ) ARGUMENTS - disparity: a numpy array of disparities being processed. If disparity_scale is omitted, this array contains floating-point disparity values in PIXELS. Many stereo-matching algorithms produce integer disparities, in units of some constant number of pixels (the OpenCV StereoSGBM and StereoBM routines use 16). In this common case, you can pass the integer scaled disparities here, with the scale factor in disparity_scale. Any array shape is supported. In the common case of a disparity IMAGE, this is an array of shape (Nel, Naz) - models_rectified: the pair of rectified models, corresponding to the input images. Usually this is returned by mrcal.rectified_system() - ranges: optional numpy array with the ranges returned by stereo_range(). Exactly one of (disparity,ranges) should be given as non-None. - disparity_scale: optional scale factor for the "disparity" array. If omitted, the "disparity" array is assumed to contain the disparities, in pixels. Otherwise it contains data in the units of 1/disparity_scale pixels. - qrect0: optional array of rectified camera0 pixel coordinates corresponding to the given disparities. By default, a full disparity image is assumed. Otherwise we use the given rectified coordinates. The shape of this array must be broadcasting-compatible with the disparity array. See the description above. RETURNED VALUES - An array of points of the same dimensionality as the input disparity (or ranges) array. Contains floating-point data. Invalid or missing points are represented as (0,0,0). ''' if (ranges is None and disparity is None) or \ (ranges is not None and disparity is not None): raise Exception("Exactly one of (disparity,ranges) must be non-None") if ranges is None: ranges = stereo_range(disparity, models_rectified, disparity_scale = disparity_scale, qrect0 = qrect0) if qrect0 is None: W,H = models_rectified[0].imagersize() # shape (H,W,2) qrect0 = np.ascontiguousarray( \ nps.mv( nps.cat( *np.meshgrid(np.arange(W,dtype=float), np.arange(H,dtype=float))), 0, -1)) # shape (..., 3) vrect0 = mrcal.unproject(qrect0, *models_rectified[0].intrinsics(), normalize = True) # shape (..., 3) p_rect0 = vrect0 * nps.dummy(ranges, axis = -1) return p_rect0 def match_feature( image0, image1, q0, *, search_radius1, template_size1, q1_estimate = None, H10 = None, method = None, visualize = False, extratitle = None, return_plot_args = False, **kwargs): r'''Find a pixel correspondence in a pair of images SYNOPSIS # Let's assume that the two cameras are roughly observing the plane defined # by z=0 in the ref coordinate system. We also have an estimate of the # camera extrinsics and intrinsics, so we can construct the homography that # defines the relationship between the pixel observations in the vicinity of # the q0 estimate. We use this homography to estimate the corresponding # pixel coordinate q1, and we use it to transform the search template def xy_from_q(model, q): v, dv_dq, _ = mrcal.unproject(q, *model.intrinsics(), get_gradients = True) t_ref_cam = model.extrinsics_Rt_toref()[ 3,:] R_ref_cam = model.extrinsics_Rt_toref()[:3,:] vref = mrcal.rotate_point_R(R_ref_cam, v) # We're looking at the plane z=0, so z = 0 = t_ref_cam[2] + k*vref[2] k = -t_ref_cam[2]/vref[2] xy = t_ref_cam[:2] + k*vref[:2] H_xy_vref = np.array((( -t_ref_cam[2], 0, xy[0] - k*vref[0]), ( 0, -t_ref_cam[2], xy[1] - k*vref[1]), ( 0, 0, 1))) H_v_q = nps.glue( dv_dq, nps.transpose(v - nps.inner(dv_dq,q)), axis = -1) H_xy_q = nps.matmult(H_xy_vref, R_ref_cam, H_v_q) return xy, H_xy_q xy, H_xy_q0 = xy_from_q(model0, q0) v1 = mrcal.transform_point_Rt(model1.extrinsics_Rt_fromref(), np.array((*xy, 0.))) q1 = mrcal.project(v1, *model1.intrinsics()) _, H_xy_q1 = xy_from_q(model1, q1) H10 = np.linalg.solve( H_xy_q1, H_xy_q0) q1, diagnostics = \ mrcal.match_feature( image0, image1, q0, H10 = H10, search_radius1 = 200, template_size1 = 17 ) This function wraps the OpenCV cv2.matchTemplate() function to provide additional functionality. The big differences are 1. The mrcal.match_feature() interface reports a matching pixel coordinate, NOT a matching template. The conversions between templates and pixel coordinates at their center are tedious and error-prone, and they're handled by this function. 2. mrcal.match_feature() can take into account a homography that is applied to the two images to match their appearance. The caller can estimate this from the relative geometry of the two cameras and the geometry of the observed object. If two pinhole cameras are observing a plane in space, a homography exists to perfectly represent the observed images everywhere in view. The homography can include a scaling (if the two cameras are looking at the same object from different distances) and/or a rotation (if the two cameras are oriented differently) and/or a skewing (if the object is being observed from different angles) 3. mrcal.match_feature() performs simple sub-pixel interpolation to increase the resolution of the reported pixel match 4. Visualization capabilities are included to allow the user to evaluate the results It is usually required to pre-filter the images being matched to get good results. This function does not do this, and it is the caller's job to apply the appropriate filters. All inputs and outputs use the (x,y) convention normally utilized when talking about images; NOT the (y,x) convention numpy uses to talk about matrices. So template_size1 is specified as (width,height). The H10 homography estimate is used in two separate ways: 1. To define the image transformation we apply to the template before matching 2. To compute the initial estimate of q1. This becomes the center of the search window. We have q1_estimate = mrcal.apply_homography(H10, q0) A common use case is a translation-only homography. This avoids any image transformation, but does select a q1_estimate. This special case is supported by this function accepting a q1_estimate argument instead of H10. Equivalently, a full translation-only homography may be passed in: H10 = np.array((( 1., 0., q1_estimate[0]-q0[0]), ( 0., 1., q1_estimate[1]-q0[1]), ( 0., 0., 1.))) The top-level logic of this function: 1. q1_estimate = mrcal.apply_homography(H10, q0) 2. Select a region in image1, centered at q1_estimate, with dimensions given in template_size1 3. Transform this region to image0, using H10. The resulting transformed image patch in image0 is used as the template 4. Select a region in image1, centered at q1_estimate, that fits the template search_radius1 pixels off center in each dimension 5. cv2.matchTemplate() to search for the template in this region of image1 If the template being matched is out-of-bounds in either image, this function raises an exception. If the search_radius1 pushes the search outside of the search image, the search bounds are reduced to fit into the given image, and the function works as expected. If the match fails in some data-dependent way, we return q1 = None instead of raising an Exception. This can happen if the optimum cannot be found or if subpixel interpolation fails. if visualize: we produce a visualization of the best-fitting match. if not return_plot_args: we display this visualization; else: we return the plot data, so that we can create the plot later. The diagnostic plot contains 3 overlaid images: - The image being searched - The homography-transformed template placed at the best-fitting location - The correlation (or difference) image, placed at the best-fitting location In an interactive gnuplotlib window, each image can be shown/hidden by clicking on the relevant legend entry at the top-right of the image. Repeatedly toggling the visibility of the template image is useful to communicate the fit accuracy. The correlation image is guaranteed to appear at the end of plot_data_tuples, so it can be omitted by plotting plot_data_tuples[:-1]. Skipping this image is often most useful for quick human evaluation. ARGUMENTS - image0: the first image to use in the matching. This image is cropped, and transformed using the H10 homography to produce the matching template. This is interpreted as a grayscale image: 2-dimensional numpy array - image1: the second image to use in the matching. This image is not transformed, but cropped to accomodate the given template size and search radius. We use this image as the base to compare the template against. The same dimensionality, dtype logic applies as with image0 - q0: a numpy array of shape (2,) representing the pixel coordinate in image0 for which we seek a correspondence in image1 - search_radius1: integer selecting the search window size, in image1 pixels - template_size1: an integer width or an iterable (width,height) describing the size of the template used for matching. If an integer width is given, we use (width,width). This is given in image1 coordinates, even though the template itself comes from image0 - q1_estimate: optional numpy array of shape (2,) representing the pixel coordinate in image1, which is our rough estimate for the camera1 observation of the q0 observation in image0. If omitted, H10 specifies the initial estimate. Exactly one of (q1_estimate,H10) must be given - H10: optional numpy array of shape (3,3) containing the homography mapping q0 to q1 in the vicinity of the match. If omitted, we assume a translation-only homography mapping q0 to q1_estimate. Exactly one of (q1_estimate,H10) must be given - method: optional constant, selecting the correlation function used in the template comparison. If omitted or None, we default to normalized cross-correlation: cv2.TM_CCORR_NORMED. For a description of available methods see: https://docs.opencv.org/master/df/dfb/group__imgproc__object.html - visualize: optional boolean, defaulting to False. If True, we generate a plot that describes the matching results. This overlays the search image, the template, and the matching-output image, shifted to their optimized positions. All 3 images are plotted direclty on top of one another. Clicking on the legend in the resulting gnuplot window toggles that image on/off, which allows the user to see how well things line up. if visualize and not return_plot_args: we generate an interactive plot, and this function blocks until the interactive plot is closed. if visualize and return_plot_args: we generate the plot data and commands, but instead of creating the plot, we return these data and commands, for the caller to post-process - extratitle: optional string to include in the title of the resulting plot. Used to extend the default title string. If kwargs['title'] is given, it is used directly, and the extratitle is ignored. Used only if visualize - return_plot_args: boolean defaulting to False. if return_plot_args: we return data_tuples, plot_options objects instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot. Used only if visualize - **kwargs: optional arguments passed verbatim as plot options to gnuplotlib. Useful to make hardcopies, etc. Used only if visualize RETURNED VALUES We return a tuple: - q1: a numpy array of shape (2,): the pixel coordinate in image1 corresponding to the given q0. If the computation fails in some data-dependent way, this value is None - diagnostics: a dict containing diagnostics that describe the match. keys: - matchoutput_image: the matchoutput array computed by cv2.matchTemplate() - matchoutput_optimum_subpixel_at: the subpixel-refined coordinate of the optimum in the matchoutput image - matchoutput_optimum_subpixel: the value of the subpixel-refined optimum in the matchoutput_image - qshift_image1_matchoutput: the shift between matchoutput image coords and image1 coords. We have q1 = diagnostics['matchoutput_optimum_subpixel_at'] + diagnostics['qshift_image1_matchoutput'] If visualize and return_plot_args: we return two more elements in the tuple: data_tuples, plot_options. The plot can then be made with gp.plot(*data_tuples, **plot_options). ''' try: N = len(template_size1) except: N = 2 template_size1 = (template_size1, template_size1) if N != 2: raise Exception(f"template_size1 must be an interable of length 2 OR a scalar. Got an iterable of length {N}") for i in range(2): if not (isinstance(template_size1[i], int) and template_size1[i] > 0): raise Exception(f"Each element of template_size1 must be an integer > 0. Got {template_size1[i]}") template_size1 = np.array(template_size1, dtype=int) if image0.ndim != 2: raise Exception("match_feature() accepts ONLY grayscale images of shape (H,W)") if image1.ndim != 2: raise Exception("match_feature() accepts ONLY grayscale images of shape (H,W)") if (H10 is None and q1_estimate is None) or \ (H10 is not None and q1_estimate is not None): raise Exception("Exactly one of (q1_estimate,H10) must be given") q0 = q0.astype(np.float32) if H10 is None: H10 = np.array((( 1., 0., q1_estimate[0]-q0[0]), ( 0., 1., q1_estimate[1]-q0[1]), ( 0., 0., 1.)), dtype=np.float32) q1_estimate = q1_estimate.astype(np.float32) else: H10 = H10.astype(np.float32) q1_estimate = mrcal.apply_homography(H10, q0) # I default to normalized cross-correlation. The method arg defaults to None # instead of cv2.TM_CCORR_NORMED so that I don't need to import cv2, unless # the user actually calls this function import cv2 if method is None: method = cv2.TM_CCORR_NORMED ################### BUILD TEMPLATE # I construct the template I'm searching for. This is a slice of image0 that # is # - centered at the given q0 # - remapped using the homography to correct for the geometric # differences in the two images q1_template_min = np.round(q1_estimate - (template_size1-1.)/2.).astype(int) q1_template_max = q1_template_min + template_size1 - 1 # last pixel def checkdims(image_shape, what, *qall): for q in qall: if q[0] < 0: raise Exception(f"Too close to the left edge in {what}") if q[1] < 0: raise Exception(f"Too close to the top edge in {what} ") if q[0] >= image_shape[1]: raise Exception(f"Too close to the right edge in {what} ") if q[1] >= image_shape[0]: raise Exception(f"Too close to the bottom edge in {what} ") checkdims( image1.shape, "image1", q1_template_min, q1_template_max) # shape (H,W,2) q1 = nps.glue(*[ nps.dummy(arr, -1) for arr in \ np.meshgrid( np.arange(q1_template_min[0], q1_template_max[0]+1), np.arange(q1_template_min[1], q1_template_max[1]+1))], axis=-1).astype(np.float32) q0 = mrcal.apply_homography(np.linalg.inv(H10), q1) checkdims( image0.shape, "image0", q0[ 0, 0], q0[-1, 0], q0[ 0,-1], q0[-1,-1] ) image0_template = mrcal.transform_image(image0, q0) ################### MATCH TEMPLATE q1_min = q1_template_min - search_radius1 q1_max = q1_template_min + search_radius1 + template_size1 - 1 # last pixel # Adjust the bounds in case the search radius pushes us past the bounds of # image1 if q1_min[0] < 0: q1_min[0] = 0 if q1_min[1] < 0: q1_min[1] = 0 if q1_max[0] > image1.shape[-1] - 1: q1_max[0] = image1.shape[-1] - 1 if q1_max[1] > image1.shape[-2] - 1: q1_max[1] = image1.shape[-2] - 1 # q1_min, q1_max are now corners of image1 we should search image1_cut = image1[ q1_min[1]:q1_max[1]+1, q1_min[0]:q1_max[0]+1 ] template_size1_hw = np.array((template_size1[-1],template_size1[-2])) matchoutput = np.zeros( image1_cut.shape - template_size1_hw+1, dtype=np.float32 ) cv2.matchTemplate(image1_cut, image0_template, method, matchoutput) if method == cv2.TM_SQDIFF or method == cv2.TM_SQDIFF_NORMED: matchoutput_optimum_flatindex = np.argmin( matchoutput.ravel() ) else: matchoutput_optimum_flatindex = np.argmax( matchoutput.ravel() ) matchoutput_optimum = matchoutput.ravel()[matchoutput_optimum_flatindex] # optimal, discrete-pixel q1 in image1_cut coords q1_cut = \ np.array( np.unravel_index(matchoutput_optimum_flatindex, matchoutput.shape) )[(-1,-2),] diagnostics = \ dict(matchoutput_image = matchoutput) ###################### SUBPIXEL INTERPOLATION # I fit a simple quadratic surface to the 3x3 points around the discrete # max, and report the max of that fitted surface # c = (c00, c10, c01, c20, c11, c02) # z = c00 + c10*x + c01*y + c20*x*x + c11*x*y + c02*y*y # z ~ M c # dz/dx = c10 + 2 c20 x + c11 y = 0 # dz/dy = c01 + 2 c02 y + c11 x = 0 # -> [ 2 c20 c11 ] [x] = [-c10] # [ c11 2 c02 ] [y] = [-c01] # # -> xy = -1/(4 c20 c02 - c11^2) [ 2 c02 -c11 ] [c10] # [ -c11 2 c20 ] [c01] default_plot_args = (None,None) if visualize and return_plot_args else () if q1_cut[0] <= 0 or \ q1_cut[1] <= 0 or \ q1_cut[0] >= matchoutput.shape[-1]-1 or \ q1_cut[1] >= matchoutput.shape[-2]-1: # discrete matchoutput peak at the edge. Cannot compute subpixel # interpolation return (None, diagnostics) + default_plot_args x,y = np.meshgrid( np.arange(3) - 1, np.arange(3) - 1 ) x = x.ravel().astype(float) y = y.ravel().astype(float) M = nps.transpose( nps.cat( np.ones(9,), x, y, x*x, x*y, y*y )) z = matchoutput[ q1_cut[1]-1:q1_cut[1]+2, q1_cut[0]-1:q1_cut[0]+2 ].ravel() # I try rcond = -1 to work in an old numpy lsqsq_result = None if True: try: lsqsq_result = np.linalg.lstsq( M, z, rcond = None) except: pass if lsqsq_result is None: try: lsqsq_result = np.linalg.lstsq( M, z, rcond = -1) except: pass if lsqsq_result is None: return (None, diagnostics) + default_plot_args c = lsqsq_result[0] (c00, c10, c01, c20, c11, c02) = c det = 4.*c20*c02 - c11*c11 xy_subpixel = -np.array((2.*c10*c02 - c01*c11, 2.*c01*c20 - c10*c11)) / det x,y = xy_subpixel matchoutput_optimum_subpixel = c00 + c10*x + c01*y + c20*x*x + c11*x*y + c02*y*y q1_cut = q1_cut.astype(float) + xy_subpixel diagnostics['matchoutput_optimum_subpixel_at'] = q1_cut diagnostics['matchoutput_optimum_subpixel'] = matchoutput_optimum_subpixel # The translation to pixel coordinates # Top-left pixel of the template, in image1 coordinates q1_aligned_template_topleft = q1_min + q1_cut # Shift for the best-fitting pixel of image1 of the template center qshift_image1_matchoutput = \ q1_min + \ q1_estimate - \ q1_template_min diagnostics['qshift_image1_matchoutput'] = qshift_image1_matchoutput # the best-fitting pixel of image1 of the template center q1 = q1_cut + qshift_image1_matchoutput matchoutput_min = np.min(matchoutput) matchoutput_max = np.max(matchoutput) if not visualize: return q1, diagnostics import gnuplotlib as gp plot_options = dict(kwargs) if 'title' not in plot_options: title = 'Feature-matching results' if extratitle is not None: title += ": " + extratitle plot_options['title'] = title gp.add_plot_option(plot_options, _with = 'image', ascii = True, overwrite = True) gp.add_plot_option(plot_options, square = True, yinv = True, _set = 'palette gray', overwrite = False) data_tuples = \ ( ( image1_cut, dict(legend='image', using = f'($1 + {q1_min[0]}):($2 + {q1_min[1]}):3', tuplesize = 3)), ( image0_template, dict(legend='template', using = \ f'($1 + {q1_aligned_template_topleft[0]}):' + \ f'($2 + {q1_aligned_template_topleft[1]}):3', tuplesize = 3)), ( (matchoutput - matchoutput_min) / (matchoutput_max - matchoutput_min) * 255, dict(legend='matchoutput', using = \ f'($1 + {qshift_image1_matchoutput[0]}):' + \ f'($2 + {qshift_image1_matchoutput[1]}):3', tuplesize = 3)) ) if return_plot_args: return q1, diagnostics, data_tuples, plot_options gp.plot( *data_tuples, **plot_options, wait=True) return q1, diagnostics mrcal-2.4.1/mrcal/synthetic_data.py000066400000000000000000000735011456301662300173030ustar00rootroot00000000000000#!/usr/bin/python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 '''Routines useful in generation and processing of synthetic data These are very useful in analyzing the behavior or cameras and lenses. All functions are exported into the mrcal module. So you can call these via mrcal.synthetic_data.fff() or mrcal.fff(). The latter is preferred. ''' import numpy as np import numpysane as nps import sys import mrcal def ref_calibration_object(W = None, H = None, object_spacing = None, *, optimization_inputs = None, calobject_warp = None, x_corner0 = 0, x_corner1 = None, Nx = None, y_corner0 = 0, y_corner1 = None, Ny = None): r'''Return the geometry of the calibration object SYNOPSIS import gnuplotlib as gp import numpysane as nps obj = mrcal.ref_calibration_object( 10,6, 0.1 ) print(obj.shape) ===> (6, 10, 3) gp.plot( nps.clump( obj[...,:2], n=2), tuplesize = -2, _with = 'points', _xrange = (-0.1,1.0), _yrange = (-0.1,0.6), unset = 'grid', square = True, terminal = 'dumb 74,45') 0.6 +---------------------------------------------------------------+ | + + + + + | | | 0.5 |-+ A A A A A A A A A A +-| | | | | 0.4 |-+ A A A A A A A A A A +-| | | | | 0.3 |-+ A A A A A A A A A A +-| | | | | 0.2 |-+ A A A A A A A A A A +-| | | | | 0.1 |-+ A A A A A A A A A A +-| | | | | 0 |-+ A A A A A A A A A A +-| | | | + + + + + | -0.1 +---------------------------------------------------------------+ 0 0.2 0.4 0.6 0.8 1 Returns the geometry of a calibration object in its own reference coordinate system in a (H,W,3) array. Only a grid-of-points calibration object is supported, possibly with some deformation (i.e. what the internal mrcal solver supports). Each row of the output is an (x,y,z) point. The origin is at the corner of the grid, so ref_calibration_object(...)[0,0,:] is np.array((0,0,0)). The grid spans x and y, with z representing the depth: z=0 for a flat calibration object. A simple parabolic board warping model is supported by passing a (2,) array in calobject_warp. These 2 values describe additive flex along the x axis and along the y axis, in that order. In each direction the flex is a parabola, with the parameter k describing the max deflection at the center. If the edges were at +-1 we'd have z = k*(1 - x^2) The edges we DO have are at (0,N-1), so the equivalent expression is xr = x / (N-1) z = k*( 1 - 4*xr^2 + 4*xr - 1 ) = 4*k*(xr - xr^2) = 4*k*xr*(1 - xr) By default we return the coordinates of the chessboard CORNERS only, but this function can return the position of ANY point on the chessboard. This can be controlled by passing the x_corner0,x_corner1,Nx arguments (and/or their y-axis versions). This selects the grid of points we return, in chessboard-corner coordinates (0 is the first corner, 1 is the second corner, etc). We use np.linspace(x_corner0, x_corner1, Nx). By default we have - x_corner0 = 0 - x_corner1 = W-1 - Nx = W So we only return the coordinates of the corners by default. The points returned along the y axis work similarly, using their variables. If optimization_inputs is given, we get H,W,object_spacing and calobject_warp from the inputs. In this case, (H,W,object_spacing) must all be None. Otherwise all of (H,W,object_spacing) must be given. Thus it's possible to call this function like this: model = mrcal.cameramodel('calibration.cameramodel') obj = mrcal.ref_calibration_object(optimization_inputs = optimization_inputs) ARGUMENTS - W: how many chessboard corners we have in the horizontal direction - H: how many chessboard corners we have in the vertical direction - object_spacing: the distance between adjacent points in the calibration object. If a scalar is given, a square object is assumed, and the vertical and horizontal distances are assumed to be identical. An array of shape (..., 2) can be given: the last dimension is (spacing_h, spacing_w), and the preceding dimensions are used for broadcasting - calobject_warp: optional array of shape (2,) defaults to None. Describes the warping of the calibration object. If None, the object is flat. If an array is given, the values describe the maximum additive deflection along the x and y axes. Extended array can be given for broadcasting - optimization_inputs: the input from a calibrated model. Usually the output of mrcal.cameramodel.optimization_inputs() call. If given, (H,W,object_spacing,calobject_warp) are all read from these inputs, and must not be given separately. - x_corner0: optional value, defaulting to 0. Selects the first point in the linear horizontal grid we're returning. This indexes the chessboard corners, and we start with the first corner by default - x_corner1: optional value, defaulting to W-1. Selects the last point in the linear horizontal grid we're returning. This indexes the chessboard corners, and we end with the last corner by default - Nx: optional value, defaulting to W. Selects the number of points we return in the horizontal direction, between x_corner0 and x_corner1 inclusive. - y_corner0,y_corner1,Ny: same as x_corner0,x_corner1,Nx but acting in the vertical direction This function supports broadcasting across object_spacing and calobject_warp RETURNED VALUES The calibration object geometry in a (..., Ny,Nx,3) array, with the leading dimensions set by the broadcasting rules. Usually Ny = H and Nx = W ''' Noptions_base = 0 options_base = ('W', 'H', 'object_spacing') for o in options_base: if locals()[o] is not None: Noptions_base += 1 if not (Noptions_base == 0 or \ Noptions_base == len(options_base)): raise Exception(f"Options '{options_base}': ALL must be given, or NONE must be given") if Noptions_base > 0 and optimization_inputs is not None: raise Exception(f"Options '{options_base}' and 'optimization_inputs' cannot both be given") if Noptions_base == 0 and optimization_inputs is None: raise Exception(f"One of options '{options_base}' and 'optimization_inputs' MUST be given") if optimization_inputs is not None: H,W = optimization_inputs['observations_board'].shape[-3:-1] object_spacing = optimization_inputs['calibration_object_spacing'] calobject_warp = optimization_inputs['calobject_warp'] if Nx is None: Nx = W if Ny is None: Ny = H if x_corner1 is None: x_corner1 = W-1 if y_corner1 is None: y_corner1 = H-1 # shape (Ny,Nx) xx,yy = np.meshgrid( np.linspace(x_corner0, x_corner1, Nx), np.linspace(y_corner0, y_corner1, Ny)) # shape (Ny,Nx,3) full_object = nps.glue(nps.mv( nps.cat(xx,yy), 0, -1), np.zeros(xx.shape + (1,)), axis=-1) # object_spacing has shape (..., 2) object_spacing = np.array(object_spacing) if object_spacing.ndim == 0: object_spacing = np.array((1,1))*object_spacing object_spacing = nps.dummy(object_spacing, -2,-2) # object_spacing now has shape (..., 1,1,2) if object_spacing.ndim > 3: # extend full_object to the output shape I want full_object = full_object * np.ones( object_spacing.shape[:-3] + (1,1,1) ) full_object[..., :2] *= object_spacing if calobject_warp is not None: xr = xx / (W-1) yr = yy / (H-1) dx = 4. * xr * (1. - xr) dy = 4. * yr * (1. - yr) # To allow broadcasting over calobject_warp if calobject_warp.ndim > 1: # shape (..., 1,1,2) calobject_warp = nps.dummy(calobject_warp, -2,-2) # extend full_object to the output shape I want full_object = full_object * np.ones( calobject_warp.shape[:-3] + (1,1,1) ) full_object[..., 2] += calobject_warp[...,0] * dx full_object[..., 2] += calobject_warp[...,1] * dy return full_object def synthesize_board_observations(models, *, object_width_n, object_height_n, object_spacing, calobject_warp, rt_ref_boardcenter, rt_ref_boardcenter__noiseradius, Nframes, which = 'all-cameras-must-see-full-board'): r'''Produce synthetic chessboard observations SYNOPSIS models = [mrcal.cameramodel("0.cameramodel"), mrcal.cameramodel("1.cameramodel"),] # shapes (Nframes, Ncameras, object_height_n, object_width_n, 2) and # (Nframes, 4, 3) q,Rt_ref_boardref = \ mrcal.synthesize_board_observations( \ models, # board geometry object_width_n = 10, object_height_n = 12, object_spacing = 0.1, calobject_warp = None, # mean board pose and the radius of the added uniform noise rt_ref_boardcenter = rt_ref_boardcenter rt_ref_boardcenter__noiseradius = rt_ref_boardcenter__noiseradius, # How many frames we want Nframes = 100 which = 'some-cameras-must-see-half-board') # q now contains the synthetic pixel observations, but some of them will be # out of view. I construct an (x,y,weight) observations array, as expected # by the optimizer, and I set the weight for the out-of-view points to -1 to # tell the optimizer to ignore those points # Set the weights to 1 initially # shape (Nframes, Ncameras, object_height_n, object_width_n, 3) observations = nps.glue(q, np.ones( q.shape[:-1] + (1,) ), axis = -1) # shape (Ncameras, 1, 1, 2) imagersizes = nps.mv( nps.cat(*[ m.imagersize() for m in models ]), -2, -4 ) observations[ np.any( q < 0, axis=-1 ), 2 ] = -1. observations[ np.any( q-imagersizes >= 0, axis=-1 ), 2 ] = -1. Given a description of a calibration object and of the cameras observing it, produces perfect pixel observations of the objects by those cameras. We return a dense observation array: every corner observation from every chessboard pose will be reported for every camera. Some of these observations MAY be out-of-view, depending on the value of the 'which' argument; see description below. The example above demonstrates how to mark such out-of-bounds observations as outliers to tell the optimization to ignore these. The "models" provides the intrinsics and extrinsics. The calibration objects are nominally have pose rt_ref_boardcenter in the reference coordinate system, with each pose perturbed uniformly with radius rt_ref_boardcenter__noiseradius. This is nonstandard since here I'm placing the board origin at its center instead of the corner (as mrcal.ref_calibration_object() does). But this is more appropriate to the usage of this function. The returned Rt_ref_boardref transformation DOES use the normal corner-referenced board geometry Returns the point observations and the chessboard poses that produced these observations. ARGUMENTS - models: an array of mrcal.cameramodel objects, one for each camera we're simulating. This is the intrinsics and the extrinsics. Ncameras = len(models) - object_width_n: the number of horizontal points in the calibration object grid - object_height_n: the number of vertical points in the calibration object grid - object_spacing: the distance between adjacent points in the calibration object. A square object is assumed, so the vertical and horizontal distances are assumed to be identical. - calobject_warp: a description of the calibration board warping. None means "no warping": the object is flat. Otherwise this is an array of shape (2,). See the docs for ref_calibration_object() for the meaning of the values in this array. - rt_ref_boardcenter: the nominal pose of the calibration object, in the reference coordinate system. This is an rt transformation from a center-referenced calibration object to the reference coordinate system - rt_ref_boardcenter__noiseradius: the deviation-from-nominal for the chessboard pose for each frame. I add uniform noise to rt_ref_boardcenter, with each element sampled independently, with the radius given here. - Nframes: how many frames of observations to return - which: a string, defaulting to 'all-cameras-must-see-full-board'. Controls the requirements on the visibility of the returned points. Valid values: - 'all-cameras-must-see-full-board': We return only those chessboard poses that produce observations that are FULLY visible by ALL the cameras. - 'some-cameras-must-see-full-board': We return only those chessboard poses that produce observations that are FULLY visible by AT LEAST ONE camera. - 'all-cameras-must-see-half-board': We return only those chessboard poses that produce observations that are AT LEAST HALF visible by ALL the cameras. - 'some-cameras-must-see-half-board': We return only those chessboard poses that produce observations that are AT LEAST HALF visible by AT LEAST ONE camera. RETURNED VALUES We return a tuple: - q: an array of shape (Nframes, Ncameras, object_height, object_width, 2) containing the pixel coordinates of the generated observations - Rt_ref_boardref: an array of shape (Nframes, 4,3) containing the poses of the chessboards. This transforms the object returned by ref_calibration_object() to the pose that was projected, in the ref coord system ''' # Can visualize results with this script: r''' r = np.array((30, 0, 0,), dtype=float) * np.pi/180. model = mrcal.cameramodel( intrinsics = ('LENSMODEL_PINHOLE', np.array((1000., 1000., 1000., 1000.,))), imagersize = np.array((2000,2000)) ) Rt_ref_boardref = \ mrcal.synthesize_board_observations([model], object_width_n = 5, object_height_n = 20, object_spacing = 0.1, calobject_warp = None, rt_ref_boardcenter = nps.glue(r, np.array((0,0,3.)), axis=-1), rt_ref_boardcenter__noiseradius = np.array((0,0,0., 0,0,0)), Nframes = 1) [1] mrcal.show_geometry( models_or_extrinsics_rt_fromref = np.zeros((1,1,6), dtype=float), frames_rt_toref = mrcal.rt_from_Rt(Rt_ref_boardref), object_width_n = 20, object_height_n = 5, object_spacing = 0.1, _set = 'xyplane 0', wait = 1 ) ''' which_valid = ( 'all-cameras-must-see-full-board', 'some-cameras-must-see-full-board', 'all-cameras-must-see-half-board', 'some-cameras-must-see-half-board', ) if not which in which_valid: raise Exception(f"'which' argument must be one of {which_valid}") Ncameras = len(models) # I move the board, and keep the cameras stationary. # # Camera coords: x,y with pixels, z forward # Board coords: x,y in-plane. z forward (i.e. back towards the camera) # The center of the board is at the origin (ignoring warping) board_center = \ np.array(( (object_width_n -1)*object_spacing/2., (object_height_n-1)*object_spacing/2., 0 )) # shape: (Nh,Nw,3) board_reference = \ mrcal.ref_calibration_object(object_width_n,object_height_n, object_spacing, calobject_warp = calobject_warp) - \ board_center # Transformation from the board returned by ref_calibration_object() to # the one I use here. It's a shift to move the origin to the center of the # board Rt_boardref_origboardref = mrcal.identity_Rt() Rt_boardref_origboardref[3,:] = -board_center def get_observation_chunk(): '''Make Nframes observations, and return them all, even the out-of-view ones''' # I compute the full random block in one shot. This is useful for # simulations that want to see identical poses when asking for N-1 # random poses and when asking for the first N-1 of a set of N random # poses # shape (Nframes,6) randomblock = np.random.uniform(low=-1.0, high=1.0, size=(Nframes,6)) # shape(Nframes,4,3) Rt_ref_boardref = \ mrcal.Rt_from_rt( rt_ref_boardcenter + randomblock * rt_ref_boardcenter__noiseradius ) # shape = (Nframes, Nh,Nw,3) boards_ref = mrcal.transform_point_Rt( # shape (Nframes, 1,1,4,3) nps.mv(Rt_ref_boardref, 0, -5), # shape ( Nh,Nw,3) board_reference ) # I project full_board. Shape: (Nframes,Ncameras,Nh,Nw,2) q = \ nps.mv( \ nps.cat( \ *[ mrcal.project( mrcal.transform_point_Rt(models[i].extrinsics_Rt_fromref(), boards_ref), *models[i].intrinsics()) \ for i in range(Ncameras) ]), 0,1 ) return q,Rt_ref_boardref def cull_out_of_view(q,Rt_ref_boardref, which): # q has shape (Nframes,Ncameras,Nh,Nw,2) # Rt_ref_boardref has shape (Nframes,4,3) # I pick only those frames where at least one cameras sees the whole # board # shape (Nframes,Ncameras,Nh,Nw) mask_visible = (q[..., 0] >= 0) * (q[..., 1] >= 0) for i in range(Ncameras): W,H = models[i].imagersize() mask_visible[:,i,...] *= \ (q[:,i,:,:,0] <= W-1) * \ (q[:,i,:,:,1] <= H-1) # shape (Nframes, Ncameras) Nvisible = np.count_nonzero(mask_visible, axis=(-1,-2) ) Nh,Nw = q.shape[2:4] if which == 'all-cameras-must-see-full-board': iframe = np.all(Nvisible == Nh*Nw, axis=-1) elif which == 'some-cameras-must-see-full-board': iframe = np.any(Nvisible == Nh*Nw, axis=-1) elif which == 'all-cameras-must-see-half-board': iframe = np.all(Nvisible > Nh*Nw//2, axis=-1) elif which == 'some-cameras-must-see-half-board': iframe = np.any(Nvisible > Nh*Nw//2, axis=-1) else: raise Exception("Unknown 'which' argument. This is a bug. I checked for the valid options at the top of this function") # q has shape (Nframes_inview,Ncameras,Nh*Nw,2) # Rt_ref_boardref has shape (Nframes_inview,4,3) return q[iframe, ...], Rt_ref_boardref[iframe, ...] # shape (Nframes_sofar,Ncameras,Nh,Nw,2) q = np.zeros((0, Ncameras, object_height_n,object_width_n, 2), dtype=float) # shape (Nframes_sofar,4,3) Rt_ref_boardref = np.zeros((0,4,3), dtype=float) # I keep creating data, until I get Nframes-worth of in-view observations while True: q_here, Rt_ref_boardref_here = get_observation_chunk() q_here, Rt_ref_boardref_here = \ cull_out_of_view(q_here, Rt_ref_boardref_here, which) q = nps.glue(q, q_here, axis=-5) Rt_ref_boardref = nps.glue(Rt_ref_boardref, Rt_ref_boardref_here, axis=-3) if q.shape[0] >= Nframes: q = q [:Nframes,...] Rt_ref_boardref = Rt_ref_boardref[:Nframes,...] break return q, mrcal.compose_Rt(Rt_ref_boardref, Rt_boardref_origboardref) def _noisy_observation_vectors_for_triangulation(p, Rt01, intrinsics0, intrinsics1, Nsamples, sigma): # p has shape (...,3) # shape (..., 2) q0 = mrcal.project( p, *intrinsics0 ) q1 = mrcal.project( mrcal.transform_point_Rt( mrcal.invert_Rt(Rt01), p), *intrinsics1 ) # shape (..., 1,2). Each has x,y q0 = nps.dummy(q0,-2) q1 = nps.dummy(q1,-2) q_noise = np.random.randn(*p.shape[:-1], Nsamples,2,2) * sigma # shape (..., Nsamples,2). Each has x,y q0_noise = q_noise[...,:,0,:] q1_noise = q_noise[...,:,1,:] q0_noisy = q0 + q0_noise q1_noisy = q1 + q1_noise # shape (..., Nsamples, 3) v0local_noisy = mrcal.unproject( q0_noisy, *intrinsics0 ) v1local_noisy = mrcal.unproject( q1_noisy, *intrinsics1 ) v0_noisy = v0local_noisy v1_noisy = mrcal.rotate_point_R(Rt01[:3,:], v1local_noisy) # All have shape (..., Nsamples,3) return \ v0local_noisy, v1local_noisy, v0_noisy,v1_noisy, \ q0,q1, q0_noisy, q1_noisy def make_perfect_observations(optimization_inputs, *, observed_pixel_uncertainty = None): r'''Write perfect observations with perfect noise into the optimization_inputs SYNOPSIS model = mrcal.cameramodel("0.cameramodel") optimization_inputs = model.optimization_inputs() optimization_inputs['calobject_warp'] = np.array((1e-3, -1e-3)) mrcal.make_perfect_observations(optimization_inputs) # We now have perfect data assuming a slightly WARPED chessboard. Let's use # this data to compute a calibration assuming a FLAT chessboard optimization_inputs['calobject_warp'] *= 0. optimization_inputs['do_optimize_calobject_warp'] = False mrcal.optimize(**optimization_inputs) model = mrcal.cameramodel(optimization_inputs = optimization_inputs, icam_intrinsics = model.icam_intrinsics()) model.write("reoptimized.cameramodel") # We can now look at the residuals and diffs to see how much a small # chessboard deformation affects our results Tracking down all the sources of error in real-world models computed by mrcal is challenging: the models never fit perfectly, and the noise never follows the assumed distribution exactly. It is thus really useful to be able to run idealized experiments where both the models and the noise are perfect. We can then vary only one variable to judge its effects. Since everything else is perfect, we can be sure that any imperfections in the results are due only to the variable we tweaked. In the sample above we evaluated the effect of a small chessboard deformation. This function ingests optimization_inputs from a completed calibration. It then assumes that all the geometry and intrinsics are perfect, and sets the observations to projections of that perfect geometry. If requested, perfect gaussian noise is then added to the observations. THIS FUNCTION MODIES THE INPUT OPTIMIZATION_INPUTS ARGUMENTS - optimization_inputs: the input from a calibrated model. Usually the output of mrcal.cameramodel.optimization_inputs() call. The output is written into optimization_inputs['observations_board'] and optimization_inputs['observations_point'] - observed_pixel_uncertainty: optional standard deviation of the noise to apply. By default the noise applied has same variance as the noise in the input optimization_inputs. If we want to omit the noise, pass observed_pixel_uncertainty = 0 RETURNED VALUES None ''' import mrcal.model_analysis x = mrcal.optimizer_callback(**optimization_inputs, no_jacobian = True, no_factorization = True)[1] if observed_pixel_uncertainty is None: observed_pixel_uncertainty = \ mrcal.model_analysis._observed_pixel_uncertainty_from_inputs(optimization_inputs, x = x) if 'indices_frame_camintrinsics_camextrinsics' in optimization_inputs and \ optimization_inputs['indices_frame_camintrinsics_camextrinsics'] is not None and \ optimization_inputs['indices_frame_camintrinsics_camextrinsics'].size: # shape (Nobservations, Nheight, Nwidth, 3) pcam = mrcal.hypothesis_board_corner_positions(**optimization_inputs)[0] i_intrinsics = optimization_inputs['indices_frame_camintrinsics_camextrinsics'][:,1] # shape (Nobservations,1,1,Nintrinsics) intrinsics = nps.mv(optimization_inputs['intrinsics'][i_intrinsics],-2,-4) optimization_inputs['observations_board'][...,:2] = \ mrcal.project( pcam, optimization_inputs['lensmodel'], intrinsics ) if 'indices_point_camintrinsics_camextrinsics' in optimization_inputs and \ optimization_inputs['indices_point_camintrinsics_camextrinsics'] is not None and \ optimization_inputs['indices_point_camintrinsics_camextrinsics'].size: indices_point_camintrinsics_camextrinsics = \ optimization_inputs['indices_point_camintrinsics_camextrinsics'] # shape (Nobservations,3) pref = optimization_inputs['points'][ indices_point_camintrinsics_camextrinsics[:,0] ] # shape (Nobservations,4,3) Rt_cam_ref = \ nps.glue( mrcal.identity_Rt(), mrcal.Rt_from_rt(optimization_inputs['extrinsics_rt_fromref']), axis = -3 ) \ [ indices_point_camintrinsics_camextrinsics[:,2]+1 ] # shape (Nobservations,3) pcam = mrcal.transform_point_Rt(Rt_cam_ref, pref) # shape (Nobservations,Nintrinsics) intrinsics = optimization_inputs['intrinsics'][ indices_point_camintrinsics_camextrinsics[:,1] ] optimization_inputs['observations_point'][...,:2] = \ mrcal.project( pcam, optimization_inputs['lensmodel'], intrinsics ) ########### The perfect observations have been written. Make sure we get ########### perfect residuals # I don't actually do that here, and rely on the tests to make sure it works properly if False: x = mrcal.optimizer_callback(**optimization_inputs, no_jacobian = True, no_factorization = True)[1] Nmeas = mrcal.num_measurements_boards(**optimization_inputs) if Nmeas > 0: i_meas0 = mrcal.measurement_index_boards(0, **optimization_inputs) err = nps.norm2(x[i_meas0:i_meas0+Nmeas]) if err > 1e-16: raise Exception("Perfect observations produced nonzero error for boards. This is a bug") Nmeas = mrcal.num_measurements_points(**optimization_inputs) if Nmeas > 0: i_meas0 = mrcal.measurement_index_points(0, **optimization_inputs) err = nps.norm2(x[i_meas0:i_meas0+Nmeas]) if err > 1e-16: raise Exception("Perfect observations produced nonzero error for points. This is a bug") ########### I have perfect data. Now add perfect noise if observed_pixel_uncertainty == 0: return for what in ('observations_board','observations_point'): if what in optimization_inputs and \ optimization_inputs[what] is not None and \ optimization_inputs[what].size: noise_nominal = \ observed_pixel_uncertainty * \ np.random.randn(*optimization_inputs[what][...,:2].shape) weight = nps.dummy( optimization_inputs[what][...,2], axis = -1 ) weight[ weight<=0 ] = 1. # to avoid dividing by 0 optimization_inputs[what][...,:2] += \ noise_nominal / weight mrcal-2.4.1/mrcal/triangulation.py000066400000000000000000002303361456301662300171610ustar00rootroot00000000000000#!/usr/bin/python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 '''Triangulation routines Various ways to convert two rays in 3D into a 3D point those rays represent All functions are exported into the mrcal module. So you can call these via mrcal.triangulation.fff() or mrcal.fff(). The latter is preferred. ''' import numpy as np import numpysane as nps import sys import mrcal import mrcal._triangulation_npsp import mrcal.model_analysis def _parse_args(v1, t01, get_gradients, v_are_local, Rt01): r'''Parse arguments to triangulation functions that take camera-0-referenced v AND t01''' if Rt01 is not None and t01 is not None: raise Exception("Exactly one of Rt01 and t01 must be None. Both were non-None") if Rt01 is None and t01 is None: raise Exception("Exactly one of Rt01 and t01 must be None. Both were None") if v_are_local: if get_gradients: raise Exception("get_gradients is True, so v_are_local MUST be the default: False") if Rt01 is None: raise Exception("v_are_local is True, so Rt01 MUST have been given") v1 = mrcal.rotate_point_R(Rt01[:3,:], v1) t01 = Rt01[3,:] else: # Normal path if t01 is None: t01 = Rt01[3,:] if get_gradients: raise Exception("get_gradients is True, so t01 MUST have been given") else: # Normal path pass return v1, t01 def triangulate_geometric(v0, v1, t01 = None, *, get_gradients = False, v_are_local = False, Rt01 = None, out = None): r'''Simple geometric triangulation SYNOPSIS models = ( mrcal.cameramodel('cam0.cameramodel'), mrcal.cameramodel('cam1.cameramodel') ) images = (mrcal.load_image('image0.jpg', bits_per_pixel=8, channels=1), mrcal.load_image('image1.jpg', bits_per_pixel=8, channels=1)) Rt01 = mrcal.compose_Rt( models[0].extrinsics_Rt_fromref(), models[1].extrinsics_Rt_toref() ) R01 = Rt01[:3,:] t01 = Rt01[ 3,:] # pixel observation in camera0 q0 = np.array((1233, 2433), dtype=np.float32) # corresponding pixel observation in camera1 q1, _ = \ mrcal.match_feature( *images, q0 = q0, template_size = (17,17), method = cv2.TM_CCORR_NORMED, search_radius = 20, H10 = H10, # homography mapping q0 to q1 ) v0 = mrcal.unproject(q0, *models[0].intrinsics()) v1 = mrcal.rotate_point_R(R01, mrcal.unproject(q1, *models[1].intrinsics())) # Estimated 3D position in camera-0 coordinates of the feature observed in # the two cameras p = mrcal.triangulate_geometric( v0, v1, t01 ) This is the lower-level triangulation routine. For a richer function that can be used to propagate uncertainties, see mrcal.triangulate() This function implements a very simple closest-approach-in-3D routine. It finds the point on each ray that's nearest to the other ray, and returns the mean of these two points. This is the "Mid" method in the paper "Triangulation: Why Optimize?", Seong Hun Lee and Javier Civera. https://arxiv.org/abs/1907.11917 This paper compares many methods. This routine is simplest and fastest, but it has the highest errors. If the triangulated point lies behind either camera (i.e. if the observation rays are parallel or divergent), (0,0,0) is returned. This function supports broadcasting fully. By default, this function takes a translation t01 instead of a full transformation Rt01. This is consistent with most, but not all of the triangulation routines. For API compatibility with ALL triangulation routines, the full Rt01 may be passed as a kwarg. Also, by default this function takes v1 in the camera-0-local coordinate system like most, but not all the other triangulation routines. If v_are_local: then v1 is interpreted in the camera-1 coordinate system instead. This makes it simple to compare the triangulation routines against one another. The invocation compatible across all the triangulation routines omits t01, and passes Rt01 and v_are_local: triangulate_...( v0, v1, Rt01 = Rt01, v_are_local = False ) Gradient reporting is possible in the default case of Rt01 is None and not v_are_local. ARGUMENTS - v0: (3,) numpy array containing a not-necessarily-normalized observation vector of a feature observed in camera-0, described in the camera-0 coordinate system - v1: (3,) numpy array containing a not-necessarily-normalized observation vector of a feature observed in camera-1, described in the camera-0 coordinate system. Note that this vector is represented in the SAME coordinate system as v0 in the default case (v_are_local is False) - t01: (3,) numpy array containing the position of the camera-1 origin in the camera-0 coordinate system. Exclusive with Rt01. - get_gradients: optional boolean that defaults to False. Whether we should compute and report the gradients. This affects what we return. If get_gradients: v_are_local must have the default value - v_are_local: optional boolean that defaults to False. If True: v1 is represented in the local coordinate system of camera-1. The default is consistent with most, but not all of the triangulation routines. Must have the default value if get_gradients - Rt01: optional (4,3) numpy array, defaulting to None. Exclusive with t01. If given, we use this transformation from camera-1 coordinates to camera-0 coordinates instead of t01. If v_are_local: then Rt01 MUST be given instead of t01. This exists for API compatibility with the other triangulation routines. - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE if not get_gradients: we return an (...,3) array of triangulated point positions in the camera-0 coordinate system if get_gradients: we return a tuple: - (...,3) array of triangulated point positions - (...,3,3) array of the gradients of the triangulated positions in respect to v0 - (...,3,3) array of the gradients of the triangulated positions in respect to v1 - (...,3,3) array of the gradients of the triangulated positions in respect to t01 ''' v1, t01 = _parse_args(v1, t01, get_gradients, v_are_local, Rt01) if not get_gradients: return mrcal._triangulation_npsp._triangulate_geometric(v0, v1, t01, out=out) else: return mrcal._triangulation_npsp._triangulate_geometric_withgrad(v0, v1, t01, out=out) def triangulate_leecivera_l1(v0, v1, t01 = None, *, get_gradients = False, v_are_local = False, Rt01 = None, out = None): r'''Triangulation minimizing the L1-norm of angle differences SYNOPSIS models = ( mrcal.cameramodel('cam0.cameramodel'), mrcal.cameramodel('cam1.cameramodel') ) images = (mrcal.load_image('image0.jpg', bits_per_pixel=8, channels=1), mrcal.load_image('image1.jpg', bits_per_pixel=8, channels=1)) Rt01 = mrcal.compose_Rt( models[0].extrinsics_Rt_fromref(), models[1].extrinsics_Rt_toref() ) R01 = Rt01[:3,:] t01 = Rt01[ 3,:] # pixel observation in camera0 q0 = np.array((1233, 2433), dtype=np.float32) # corresponding pixel observation in camera1 q1, _ = \ mrcal.match_feature( *images, q0 = q0, template_size = (17,17), method = cv2.TM_CCORR_NORMED, search_radius = 20, H10 = H10, # homography mapping q0 to q1 ) v0 = mrcal.unproject(q0, *models[0].intrinsics()) v1 = mrcal.rotate_point_R(R01, mrcal.unproject(q1, *models[1].intrinsics())) # Estimated 3D position in camera-0 coordinates of the feature observed in # the two cameras p = mrcal.triangulate_leecivera_l1( v0, v1, t01 ) This is the lower-level triangulation routine. For a richer function that can be used to propagate uncertainties, see mrcal.triangulate() This function implements a triangulation routine minimizing the L1 norm of angular errors. This is described in "Closed-Form Optimal Two-View Triangulation Based on Angular Errors", Seong Hun Lee and Javier Civera. ICCV 2019. This is the "L1 ang" method in the paper "Triangulation: Why Optimize?", Seong Hun Lee and Javier Civera. https://arxiv.org/abs/1907.11917 This paper compares many methods. This routine works decently well, but it isn't the best. triangulate_leecivera_mid2() (or triangulate_leecivera_wmid2() if we're near the cameras) are preferred, according to the paper. If the triangulated point lies behind either camera (i.e. if the observation rays are parallel or divergent), (0,0,0) is returned. This function supports broadcasting fully. By default, this function takes a translation t01 instead of a full transformation Rt01. This is consistent with most, but not all of the triangulation routines. For API compatibility with ALL triangulation routines, the full Rt01 may be passed as a kwarg. Also, by default this function takes v1 in the camera-0-local coordinate system like most, but not all the other triangulation routines. If v_are_local: then v1 is interpreted in the camera-1 coordinate system instead. This makes it simple to compare the triangulation routines against one another. The invocation compatible across all the triangulation routines omits t01, and passes Rt01 and v_are_local: triangulate_...( v0, v1, Rt01 = Rt01, v_are_local = False ) Gradient reporting is possible in the default case of Rt01 is None and not v_are_local. ARGUMENTS - v0: (3,) numpy array containing a not-necessarily-normalized observation vector of a feature observed in camera-0, described in the camera-0 coordinate system - v1: (3,) numpy array containing a not-necessarily-normalized observation vector of a feature observed in camera-1, described in the camera-0 coordinate system. Note that this vector is represented in the SAME coordinate system as v0 in the default case (v_are_local is False) - t01: (3,) numpy array containing the position of the camera-1 origin in the camera-0 coordinate system. Exclusive with Rt01. - get_gradients: optional boolean that defaults to False. Whether we should compute and report the gradients. This affects what we return. If get_gradients: v_are_local must have the default value - v_are_local: optional boolean that defaults to False. If True: v1 is represented in the local coordinate system of camera-1. The default is consistent with most, but not all of the triangulation routines. Must have the default value if get_gradients - Rt01: optional (4,3) numpy array, defaulting to None. Exclusive with t01. If given, we use this transformation from camera-1 coordinates to camera-0 coordinates instead of t01. If v_are_local: then Rt01 MUST be given instead of t01. This exists for API compatibility with the other triangulation routines. - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE if not get_gradients: we return an (...,3) array of triangulated point positions in the camera-0 coordinate system if get_gradients: we return a tuple: - (...,3) array of triangulated point positions - (...,3,3) array of the gradients of the triangulated positions in respect to v0 - (...,3,3) array of the gradients of the triangulated positions in respect to v1 - (...,3,3) array of the gradients of the triangulated positions in respect to t01 ''' v1, t01 = _parse_args(v1, t01, get_gradients, v_are_local, Rt01) if not get_gradients: return mrcal._triangulation_npsp._triangulate_leecivera_l1(v0, v1, t01, out=out) else: return mrcal._triangulation_npsp._triangulate_leecivera_l1_withgrad(v0, v1, t01, out=out) def triangulate_leecivera_linf(v0, v1, t01 = None, *, get_gradients = False, v_are_local = False, Rt01 = None, out = None): r'''Triangulation minimizing the infinity-norm of angle differences SYNOPSIS models = ( mrcal.cameramodel('cam0.cameramodel'), mrcal.cameramodel('cam1.cameramodel') ) images = (mrcal.load_image('image0.jpg', bits_per_pixel=8, channels=1), mrcal.load_image('image1.jpg', bits_per_pixel=8, channels=1)) Rt01 = mrcal.compose_Rt( models[0].extrinsics_Rt_fromref(), models[1].extrinsics_Rt_toref() ) R01 = Rt01[:3,:] t01 = Rt01[ 3,:] # pixel observation in camera0 q0 = np.array((1233, 2433), dtype=np.float32) # corresponding pixel observation in camera1 q1, _ = \ mrcal.match_feature( *images, q0 = q0, template_size = (17,17), method = cv2.TM_CCORR_NORMED, search_radius = 20, H10 = H10, # homography mapping q0 to q1 ) v0 = mrcal.unproject(q0, *models[0].intrinsics()) v1 = mrcal.rotate_point_R(R01, mrcal.unproject(q1, *models[1].intrinsics())) # Estimated 3D position in camera-0 coordinates of the feature observed in # the two cameras p = mrcal.triangulate_leecivera_linf( v0, v1, t01 ) This is the lower-level triangulation routine. For a richer function that can be used to propagate uncertainties, see mrcal.triangulate() This function implements a triangulation routine minimizing the infinity norm of angular errors (it minimizes the larger of the two angle errors). This is described in "Closed-Form Optimal Two-View Triangulation Based on Angular Errors", Seong Hun Lee and Javier Civera. ICCV 2019. This is the "L-infinity ang" method in the paper "Triangulation: Why Optimize?", Seong Hun Lee and Javier Civera. https://arxiv.org/abs/1907.11917 This paper compares many methods. This routine works decently well, but it isn't the best. triangulate_leecivera_mid2() (or triangulate_leecivera_wmid2() if we're near the cameras) are preferred, according to the paper. If the triangulated point lies behind either camera (i.e. if the observation rays are parallel or divergent), (0,0,0) is returned. This function supports broadcasting fully. By default, this function takes a translation t01 instead of a full transformation Rt01. This is consistent with most, but not all of the triangulation routines. For API compatibility with ALL triangulation routines, the full Rt01 may be passed as a kwarg. Also, by default this function takes v1 in the camera-0-local coordinate system like most, but not all the other triangulation routines. If v_are_local: then v1 is interpreted in the camera-1 coordinate system instead. This makes it simple to compare the triangulation routines against one another. The invocation compatible across all the triangulation routines omits t01, and passes Rt01 and v_are_local: triangulate_...( v0, v1, Rt01 = Rt01, v_are_local = False ) Gradient reporting is possible in the default case of Rt01 is None and not v_are_local. ARGUMENTS - v0: (3,) numpy array containing a not-necessarily-normalized observation vector of a feature observed in camera-0, described in the camera-0 coordinate system - v1: (3,) numpy array containing a not-necessarily-normalized observation vector of a feature observed in camera-1, described in the camera-0 coordinate system. Note that this vector is represented in the SAME coordinate system as v0 in the default case (v_are_local is False) - t01: (3,) numpy array containing the position of the camera-1 origin in the camera-0 coordinate system. Exclusive with Rt01. - get_gradients: optional boolean that defaults to False. Whether we should compute and report the gradients. This affects what we return. If get_gradients: v_are_local must have the default value - v_are_local: optional boolean that defaults to False. If True: v1 is represented in the local coordinate system of camera-1. The default is consistent with most, but not all of the triangulation routines. Must have the default value if get_gradients - Rt01: optional (4,3) numpy array, defaulting to None. Exclusive with t01. If given, we use this transformation from camera-1 coordinates to camera-0 coordinates instead of t01. If v_are_local: then Rt01 MUST be given instead of t01. This exists for API compatibility with the other triangulation routines. - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE if not get_gradients: we return an (...,3) array of triangulated point positions in the camera-0 coordinate system if get_gradients: we return a tuple: - (...,3) array of triangulated point positions - (...,3,3) array of the gradients of the triangulated positions in respect to v0 - (...,3,3) array of the gradients of the triangulated positions in respect to v1 - (...,3,3) array of the gradients of the triangulated positions in respect to t01 ''' v1, t01 = _parse_args(v1, t01, get_gradients, v_are_local, Rt01) if not get_gradients: return mrcal._triangulation_npsp._triangulate_leecivera_linf(v0, v1, t01, out=out) else: return mrcal._triangulation_npsp._triangulate_leecivera_linf_withgrad(v0, v1, t01, out=out) def triangulate_leecivera_mid2(v0, v1, t01 = None, *, get_gradients = False, v_are_local = False, Rt01 = None, out = None): r'''Triangulation using Lee and Civera's alternative midpoint method SYNOPSIS models = ( mrcal.cameramodel('cam0.cameramodel'), mrcal.cameramodel('cam1.cameramodel') ) images = (mrcal.load_image('image0.jpg', bits_per_pixel=8, channels=1), mrcal.load_image('image1.jpg', bits_per_pixel=8, channels=1)) Rt01 = mrcal.compose_Rt( models[0].extrinsics_Rt_fromref(), models[1].extrinsics_Rt_toref() ) R01 = Rt01[:3,:] t01 = Rt01[ 3,:] # pixel observation in camera0 q0 = np.array((1233, 2433), dtype=np.float32) # corresponding pixel observation in camera1 q1, _ = \ mrcal.match_feature( *images, q0 = q0, template_size = (17,17), method = cv2.TM_CCORR_NORMED, search_radius = 20, H10 = H10, # homography mapping q0 to q1 ) v0 = mrcal.unproject(q0, *models[0].intrinsics()) v1 = mrcal.rotate_point_R(R01, mrcal.unproject(q1, *models[1].intrinsics())) # Estimated 3D position in camera-0 coordinates of the feature observed in # the two cameras p = mrcal.triangulate_leecivera_mid2( v0, v1, t01 ) This is the lower-level triangulation routine. For a richer function that can be used to propagate uncertainties, see mrcal.triangulate() This function implements the "Mid2" triangulation routine in "Triangulation: Why Optimize?", Seong Hun Lee and Javier Civera. https://arxiv.org/abs/1907.11917 This paper compares many methods. This routine works decently well, but it isn't the best. The method in this function should be a good tradeoff between accuracy (in 3D and 2D) and performance. If we're looking at objects very close to the cameras, where the distances to the two cameras are significantly different, use triangulate_leecivera_wmid2() instead. If the triangulated point lies behind either camera (i.e. if the observation rays are parallel or divergent), (0,0,0) is returned. This function supports broadcasting fully. By default, this function takes a translation t01 instead of a full transformation Rt01. This is consistent with most, but not all of the triangulation routines. For API compatibility with ALL triangulation routines, the full Rt01 may be passed as a kwarg. Also, by default this function takes v1 in the camera-0-local coordinate system like most, but not all the other triangulation routines. If v_are_local: then v1 is interpreted in the camera-1 coordinate system instead. This makes it simple to compare the triangulation routines against one another. The invocation compatible across all the triangulation routines omits t01, and passes Rt01 and v_are_local: triangulate_...( v0, v1, Rt01 = Rt01, v_are_local = False ) Gradient reporting is possible in the default case of Rt01 is None and not v_are_local. ARGUMENTS - v0: (3,) numpy array containing a not-necessarily-normalized observation vector of a feature observed in camera-0, described in the camera-0 coordinate system - v1: (3,) numpy array containing a not-necessarily-normalized observation vector of a feature observed in camera-1, described in the camera-0 coordinate system. Note that this vector is represented in the SAME coordinate system as v0 in the default case (v_are_local is False) - t01: (3,) numpy array containing the position of the camera-1 origin in the camera-0 coordinate system. Exclusive with Rt01. - get_gradients: optional boolean that defaults to False. Whether we should compute and report the gradients. This affects what we return. If get_gradients: v_are_local must have the default value - v_are_local: optional boolean that defaults to False. If True: v1 is represented in the local coordinate system of camera-1. The default is consistent with most, but not all of the triangulation routines. Must have the default value if get_gradients - Rt01: optional (4,3) numpy array, defaulting to None. Exclusive with t01. If given, we use this transformation from camera-1 coordinates to camera-0 coordinates instead of t01. If v_are_local: then Rt01 MUST be given instead of t01. This exists for API compatibility with the other triangulation routines. - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE if not get_gradients: we return an (...,3) array of triangulated point positions in the camera-0 coordinate system if get_gradients: we return a tuple: - (...,3) array of triangulated point positions - (...,3,3) array of the gradients of the triangulated positions in respect to v0 - (...,3,3) array of the gradients of the triangulated positions in respect to v1 - (...,3,3) array of the gradients of the triangulated positions in respect to t01 ''' v1, t01 = _parse_args(v1, t01, get_gradients, v_are_local, Rt01) if not get_gradients: return mrcal._triangulation_npsp._triangulate_leecivera_mid2(v0, v1, t01, out=out) else: return mrcal._triangulation_npsp._triangulate_leecivera_mid2_withgrad(v0, v1, t01, out=out) def triangulate_leecivera_wmid2(v0, v1, t01 = None, *, get_gradients = False, v_are_local = False, Rt01 = None, out = None): r'''Triangulation using Lee and Civera's weighted alternative midpoint method SYNOPSIS models = ( mrcal.cameramodel('cam0.cameramodel'), mrcal.cameramodel('cam1.cameramodel') ) images = (mrcal.load_image('image0.jpg', bits_per_pixel=8, channels=1), mrcal.load_image('image1.jpg', bits_per_pixel=8, channels=1)) Rt01 = mrcal.compose_Rt( models[0].extrinsics_Rt_fromref(), models[1].extrinsics_Rt_toref() ) R01 = Rt01[:3,:] t01 = Rt01[ 3,:] # pixel observation in camera0 q0 = np.array((1233, 2433), dtype=np.float32) # corresponding pixel observation in camera1 q1, _ = \ mrcal.match_feature( *images, q0 = q0, template_size = (17,17), method = cv2.TM_CCORR_NORMED, search_radius = 20, H10 = H10, # homography mapping q0 to q1 ) v0 = mrcal.unproject(q0, *models[0].intrinsics()) v1 = mrcal.rotate_point_R(R01, mrcal.unproject(q1, *models[1].intrinsics())) # Estimated 3D position in camera-0 coordinates of the feature observed in # the two cameras p = mrcal.triangulate_leecivera_wmid2( v0, v1, t01 ) This is the lower-level triangulation routine. For a richer function that can be used to propagate uncertainties, see mrcal.triangulate() This function implements the "wMid2" triangulation routine in "Triangulation: Why Optimize?", Seong Hun Lee and Javier Civera. https://arxiv.org/abs/1907.11917 This paper compares many methods. This routine works decently well, but it isn't the best. The preferred method, according to the paper, is triangulate_leecivera_mid2. THIS method (wMid2) is better if we're looking at objects very close to the cameras, where the distances to the two cameras are significantly different. If the triangulated point lies behind either camera (i.e. if the observation rays are parallel or divergent), (0,0,0) is returned. This function supports broadcasting fully. By default, this function takes a translation t01 instead of a full transformation Rt01. This is consistent with most, but not all of the triangulation routines. For API compatibility with ALL triangulation routines, the full Rt01 may be passed as a kwarg. Also, by default this function takes v1 in the camera-0-local coordinate system like most, but not all the other triangulation routines. If v_are_local: then v1 is interpreted in the camera-1 coordinate system instead. This makes it simple to compare the triangulation routines against one another. The invocation compatible across all the triangulation routines omits t01, and passes Rt01 and v_are_local: triangulate_...( v0, v1, Rt01 = Rt01, v_are_local = False ) Gradient reporting is possible in the default case of Rt01 is None and not v_are_local. ARGUMENTS - v0: (3,) numpy array containing a not-necessarily-normalized observation vector of a feature observed in camera-0, described in the camera-0 coordinate system - v1: (3,) numpy array containing a not-necessarily-normalized observation vector of a feature observed in camera-1, described in the camera-0 coordinate system. Note that this vector is represented in the SAME coordinate system as v0 in the default case (v_are_local is False) - t01: (3,) numpy array containing the position of the camera-1 origin in the camera-0 coordinate system. Exclusive with Rt01. - get_gradients: optional boolean that defaults to False. Whether we should compute and report the gradients. This affects what we return. If get_gradients: v_are_local must have the default value - v_are_local: optional boolean that defaults to False. If True: v1 is represented in the local coordinate system of camera-1. The default is consistent with most, but not all of the triangulation routines. Must have the default value if get_gradients - Rt01: optional (4,3) numpy array, defaulting to None. Exclusive with t01. If given, we use this transformation from camera-1 coordinates to camera-0 coordinates instead of t01. If v_are_local: then Rt01 MUST be given instead of t01. This exists for API compatibility with the other triangulation routines. - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE if not get_gradients: we return an (...,3) array of triangulated point positions in the camera-0 coordinate system if get_gradients: we return a tuple: - (...,3) array of triangulated point positions - (...,3,3) array of the gradients of the triangulated positions in respect to v0 - (...,3,3) array of the gradients of the triangulated positions in respect to v1 - (...,3,3) array of the gradients of the triangulated positions in respect to t01 ''' v1, t01 = _parse_args(v1, t01, get_gradients, v_are_local, Rt01) if not get_gradients: return mrcal._triangulation_npsp._triangulate_leecivera_wmid2(v0, v1, t01, out=out) else: return mrcal._triangulation_npsp._triangulate_leecivera_wmid2_withgrad(v0, v1, t01, out=out) def triangulate_lindstrom(v0, v1, # The other routines take t01 here Rt01, *, get_gradients = False, v_are_local = True, out = None): r'''Triangulation minimizing the 2-norm of pinhole reprojection errors SYNOPSIS models = ( mrcal.cameramodel('cam0.cameramodel'), mrcal.cameramodel('cam1.cameramodel') ) images = (mrcal.load_image('image0.jpg', bits_per_pixel=8, channels=1), mrcal.load_image('image1.jpg', bits_per_pixel=8, channels=1)) Rt01 = mrcal.compose_Rt( models[0].extrinsics_Rt_fromref(), models[1].extrinsics_Rt_toref() ) R01 = Rt01[:3,:] t01 = Rt01[ 3,:] # pixel observation in camera0 q0 = np.array((1233, 2433), dtype=np.float32) # corresponding pixel observation in camera1 q1, _ = \ mrcal.match_feature( *images, q0 = q0, template_size = (17,17), method = cv2.TM_CCORR_NORMED, search_radius = 20, H10 = H10, # homography mapping q0 to q1 ) # observation vectors in the LOCAL coordinate system of the two cameras v0 = mrcal.unproject(q0, *models[0].intrinsics()) v1 = mrcal.unproject(q1, *models[1].intrinsics()) # Estimated 3D position in camera-0 coordinates of the feature observed in # the two cameras p = mrcal.triangulate_lindstrom( v0, v1, Rt01 = Rt01 ) This is the lower-level triangulation routine. For a richer function that can be used to propagate uncertainties, see mrcal.triangulate() This function implements a triangulation routine minimizing the 2-norm of reprojection errors, ASSUMING a pinhole projection. This is described in "Triangulation Made Easy", Peter Lindstrom, IEEE Conference on Computer Vision and Pattern Recognition, 2010. This is the "L2 img 5-iteration" method in the paper "Triangulation: Why Optimize?", Seong Hun Lee and Javier Civera. https://arxiv.org/abs/1907.11917 but with only 2 iterations (Lindstrom's paper recommends 2 iterations). This Lee, Civera paper compares many methods. This routine works decently well, but it isn't the best. The angular methods should work better than this one for wide lenses. triangulate_leecivera_mid2() (or triangulate_leecivera_wmid2() if we're near the cameras) are preferred, according to the paper. The assumption of a pinhole projection is a poor one when using a wide lens, and looking away from the optical center. The Lee-Civera triangulation functions don't have this problem, and are generally faster. See the Lee, Civera paper for details. If the triangulated point lies behind either camera (i.e. if the observation rays are parallel or divergent), (0,0,0) is returned. This function supports broadcasting fully. This function takes a full transformation Rt01, instead of t01 like most of the other triangulation functions do by default. The other function may take Rt01, for API compatibility. Also, by default this function takes v1 in the camera-1-local coordinate system unlike most of the other triangulation routines. If not v_are_local: then v1 is interpreted in the camera-0 coordinate system instead. This makes it simple to compare the routines against one another. The invocation compatible across all the triangulation routines omits t01, and passes Rt01 and v_are_local: triangulate_...( v0, v1, Rt01 = Rt01, v_are_local = False ) Gradient reporting is possible in the default case of v_are_local is True ARGUMENTS - v0: (3,) numpy array containing a not-necessarily-normalized observation vector of a feature observed in camera-0, described in the camera-0 coordinate system - v1: (3,) numpy array containing a not-necessarily-normalized observation vector of a feature observed in camera-1, described in the camera-1 coordinate system by default (v_are_local is True). Note that this vector is represented in the camera-local coordinate system, unlike the representation in all the other triangulation routines - Rt01: (4,3) numpy array describing the transformation from camera-1 coordinates to camera-0 coordinates - get_gradients: optional boolean that defaults to False. Whether we should compute and report the gradients. This affects what we return. If get_gradients: v_are_local must have the default value - v_are_local: optional boolean that defaults to True. If True: v1 is represented in the local coordinate system of camera-1. This is different from the other triangulation routines. Set v_are_local to False to make this function interpret v1 similarly to the other triangulation routines. Must have the default value if get_gradients - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If not get_gradients: 'out' is the one numpy array we will write into. Else: 'out' is a tuple of all the output numpy arrays. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE if not get_gradients: we return an (...,3) array of triangulated point positions in the camera-0 coordinate system if get_gradients: we return a tuple: - (...,3) array of triangulated point positions - (...,3,3) array of the gradients of the triangulated positions in respect to v0 - (...,3,3) array of the gradients of the triangulated positions in respect to v1 - (...,3,4,3) array of the gradients of the triangulated positions in respect to Rt01 ''' if not v_are_local: if get_gradients: raise Exception("get_gradients is True, so v_are_local MUST be True") v1 = mrcal.rotate_point_R(nps.transpose(Rt01[:3,:]), v1) if not get_gradients: return mrcal._triangulation_npsp._triangulate_lindstrom(v0, v1, Rt01, out=out) else: return mrcal._triangulation_npsp._triangulate_lindstrom_withgrad(v0, v1, Rt01, out=out) def _compute_Var_q_triangulation(sigma, stdev_cross_camera_correlation): r'''Compute triangulation variance due to observation noise This is an internal piece of mrcal.triangulate(). It's available separately for the benefit of the test ''' # For each triangulation we ingest one pixel observation per camera. # This is 4 numbers: 2 cameras, with (x,y) for each one Ncameras = 2 Nxy = 2 var_q = np.eye(Ncameras*Nxy) * sigma*sigma # When computing dense stereo we generally assume that q0 is fixed, and we # only think about the effects of Var(q1): Var(q0) = 0, sigma_cross = 0 # var_q[0,0] = 0 # var_q[1,1] = 0 # sigma_cross = 0 var_q_reshaped = var_q.reshape( Ncameras, Nxy, Ncameras, Nxy ) sigma_cross = sigma*stdev_cross_camera_correlation var_cross = sigma_cross*sigma_cross # cam0-cam1 correlations var_q_reshaped[0,0, 1,0] = var_cross var_q_reshaped[0,1, 1,1] = var_cross # cam1-cam0 correlations var_q_reshaped[1,0, 0,0] = var_cross var_q_reshaped[1,1, 0,1] = var_cross return var_q def _triangulate_grad_simple(q, models, out, method = triangulate_leecivera_mid2): r'''Compute a single triangulation, reporting a single gradient This is an internal piece of mrcal.triangulate(). It's available separately for the benefit of the test ''' # Simplified path. We don't need most of the gradients rt01 = \ mrcal.compose_rt(models[0].extrinsics_rt_fromref(), models[1].extrinsics_rt_toref()) # all the v have shape (3,) vlocal0, dvlocal0_dq0, _ = \ mrcal.unproject(q[0,:], *models[0].intrinsics(), get_gradients = True) vlocal1, dvlocal1_dq1, _ = \ mrcal.unproject(q[1,:], *models[1].intrinsics(), get_gradients = True) v0 = vlocal0 v1, _, dv1_dvlocal1 = \ mrcal.rotate_point_r(rt01[:3], vlocal1, get_gradients=True) dp_triangulated_dv0 = np.zeros( out.shape + (3,), dtype=float) dp_triangulated_dv1 = np.zeros( out.shape + (3,), dtype=float) dp_triangulated_dt01 = np.zeros( out.shape + (3,), dtype=float) if method is mrcal.triangulate_lindstrom: raise Exception("Triangulation gradients not supported (yet?) with method=triangulate_lindstrom. It has slightly different inputs and slightly different gradients") method(v0, v1, rt01[3:], out = (out, dp_triangulated_dv0, dp_triangulated_dv1, dp_triangulated_dt01), get_gradients = True) dp_triangulated_dq = np.zeros((3,) + q.shape[-2:], dtype=float) nps.matmult( dp_triangulated_dv0, dvlocal0_dq0, out = dp_triangulated_dq[..., 0, :]) nps.matmult( dp_triangulated_dv1, dv1_dvlocal1, dvlocal1_dq1, out = dp_triangulated_dq[..., 1, :]) # shape (3,4) return nps.clump(dp_triangulated_dq, n=-2) def _triangulation_uncertainty_internal(slices, optimization_inputs, # if None: we're not propagating calibration-time noise q_observation_stdev, q_observation_stdev_correlation, method = triangulate_leecivera_mid2, stabilize_coords = True): r'''Compute most of the triangulation uncertainty logic This is an internal piece of mrcal.triangulate(). It's available separately to allow the test suite to validate some of the internals. if optimization_inputs is None and q_observation_stdev is None: We're not propagating any noise. Just return the triangulated point ''' def _triangulate_grad(models, q, out, method): # Full path. Compute and return the gradients for most things rt_ref1,drt_ref1_drt_1ref = \ mrcal.invert_rt(models[1].extrinsics_rt_fromref(), get_gradients=True) rt01,drt01_drt_0ref,drt01_drt_ref1 = \ mrcal.compose_rt(models[0].extrinsics_rt_fromref(), rt_ref1, get_gradients=True) # all the v have shape (3,) vlocal0, dvlocal0_dq0, dvlocal0_dintrinsics0 = \ mrcal.unproject(q[0,:], *models[0].intrinsics(), get_gradients = True) vlocal1, dvlocal1_dq1, dvlocal1_dintrinsics1 = \ mrcal.unproject(q[1,:], *models[1].intrinsics(), get_gradients = True) v0 = vlocal0 v1, dv1_dr01, dv1_dvlocal1 = \ mrcal.rotate_point_r(rt01[:3], vlocal1, get_gradients=True) dp_triangulated_dv0 = np.zeros(out.shape + (3,), dtype=float) dp_triangulated_dv1 = np.zeros(out.shape + (3,), dtype=float) dp_triangulated_dt01 = np.zeros(out.shape + (3,), dtype=float) if method is mrcal.triangulate_lindstrom: raise Exception("Triangulation gradients not supported (yet?) with method=triangulate_lindstrom. It has slightly different inputs and slightly different gradients") method(v0, v1, rt01[3:], out = (out, dp_triangulated_dv0, dp_triangulated_dv1, dp_triangulated_dt01), get_gradients = True) dp_triangulated_dq = np.zeros((3,) + q.shape[-2:], dtype=float) nps.matmult( dp_triangulated_dv0, dvlocal0_dq0, out = dp_triangulated_dq[..., 0, :]) nps.matmult( dp_triangulated_dv1, dv1_dvlocal1, dvlocal1_dq1, out = dp_triangulated_dq[..., 1, :]) # shape (3,4) dp_triangulated_dq = nps.clump(dp_triangulated_dq, n=-2) return \ dp_triangulated_dq, \ drt_ref1_drt_1ref, \ drt01_drt_0ref, \ drt01_drt_ref1, \ dvlocal0_dintrinsics0, \ dvlocal1_dintrinsics1, \ dv1_dr01, \ dv1_dvlocal1, \ dp_triangulated_dv0, \ dp_triangulated_dv1, \ dp_triangulated_dt01 def stabilize(p_cam0, rt_cam0_ref, rt_ref_frame): # The triangulated point is reported in the coordinate system of # camera0. If we perturb the calibration inputs, the coordinate # system itself moves, and without extra effort, the reported # triangulation uncertainty incorporates this extra coordinate # system motion. Here, the stabilization logic is available to try # to compensate for the effects of the shifting coordinate system. # This is done very similarly to how we do this when computing the # projection uncertainty. # # Let's say I have a triangulated point collected after a # perturbation. I transform it to the coordinate systems of the # frames. Those represent fixed objects in space, so THESE # coordinate systems do not shift after a calibration-time # perturbation. I then project the point in the coordinate systems # of the frames back, using the unperturbed geometry. This gives me # the triangulation in the UNPERTURBED (baseline) camera0 frame. # # The data flow: # point_cam_perturbed -> point_ref_perturbed -> point_frames # point_frames -> point_ref_baseline -> point_cam_baseline # # The final quantity point_cam_baseline depends on calibration # parameters in two ways: # # 1. Indirectly, via point_cam_perturbed # 2. Directly, via each of the transformations in the above data flow # # For the indirect dependencies, we have the unstabilized # dpoint_cam_perturbed/dparam for a number of parameters, and we # want to propagate that to the stabilized quantity: # # dpoint_cam_baseline/dparam = # dpoint_cam_baseline/dpoint_ref_baseline # dpoint_ref_baseline/dpoint_frames # dpoint_frames/dpoint_ref_perturbed # dpoint_ref_perturbed/dpoint_cam_perturbed # dpoint_cam_perturbed/dparam # # We only consider small perturbations, and we assume that # everything is locally linear. Thus the gradients in this # expression all cancel out, and we get simply # # dpoint_cam_baseline/dparam = dpoint_cam_perturbed/dparam # # Thus there's nothing for this function to do to handle these indirect # dependencies. # # For the direct dependencies, we consider point_frames to be the # nominal representation of the point. So for the purpose of # computing gradients we don't look at the baseline parameter # gradients: # # dpoint_cam_baseline/dparam = # dpoint_cam_baseline/dpoint_frames # dpoint_frames/dparam = # # Simplifying notation: # # dpc/dparam = dpc/dpf dpf/dparam # # Thus we have exactly two transformations whose parameters should # be propagated: # # 1. rt_cam_ref # 2. rt_ref_frame # # Propagating rt_cam_ref: # # dpc/drt_cr = dpc/dpf dpf/drt_cr # = dpc/dpr dpr/dpf dpf/dpr dpr/drt_cr # = dpc/dpr dpr/drt_cr # # Propagating rt_ref_frame: # # dpc/drt_rf = dpc/dpf dpf/drt_rf # = dpc/dpr dpr/dpf dpf/drt_rf # # If the frames are fixed, the same logic applies, with some # simplifications. The cameras move in respect to the ref frame, but the # frames are fixed in the ref frame. So the ref frame is the nominal # representation # # dpoint_cam_baseline/dparam = # dpoint_cam_baseline/dpoint_ref # dpoint_ref/dparam # triangulated point in the perturbed reference coordinate system p_ref, \ dp_ref_drt_0ref, \ dp_ref_dp_cam0 = \ mrcal.transform_point_rt(rt_cam0_ref, p_cam0, get_gradients = True, inverted = True) dp_triangulated_drt_0ref = \ np.linalg.solve( dp_ref_dp_cam0, dp_ref_drt_0ref) if rt_ref_frame is not None: # we're optimizing the frames # dp_frames_drtrf has shape (..., Nframes, 3,6) # dp_frames_dp_ref has shape (..., Nframes, 3,3) _, \ dp_frames_drtrf, \ dp_frames_dp_ref = \ mrcal.transform_point_rt(rt_ref_frame, nps.dummy(p_ref,-2), get_gradients = True, inverted = True) dp_frames_dp_cam0 = \ nps.matmult( dp_frames_dp_ref, nps.dummy(dp_ref_dp_cam0, -3)) Nframes = len(rt_ref_frame) # shape (..., 3,6) dp_triangulated_drtrf = np.linalg.solve(dp_frames_dp_cam0, dp_frames_drtrf) / Nframes else: # the frames are fixed; not subject to optimization dp_triangulated_drtrf = None return \ dp_triangulated_drtrf, \ dp_triangulated_drt_0ref Npoints = len(slices) # Output goes here. This function fills in the observation-time stuff. # Otherwise this function just returns the array of 0s, which the callers # will fill using the dp_triangulated_db data this function returns p = np.zeros((Npoints,3), dtype=float) if optimization_inputs is not None: Nintrinsics = mrcal.num_intrinsics_optimization_params(**optimization_inputs) Nstate = mrcal.num_states(**optimization_inputs) # I store dp_triangulated_db initially, without worrying about the # "packed" part. I'll scale the thing when done to pack it dp_triangulated_db = np.zeros((Npoints,3,Nstate), dtype=float) if stabilize_coords and optimization_inputs.get('do_optimize_frames'): # We're re-optimizing (looking at calibration uncertainty) AND we # are optimizing the frames AND we have stabilization enabled. # Without stabilization, there's no dependence on rt_ref_frame rt_ref_frame = optimization_inputs['frames_rt_toref'] istate_f0 = mrcal.state_index_frames(0, **optimization_inputs) Nstate_frames = mrcal.num_states_frames( **optimization_inputs) else: rt_ref_frame = None istate_f0 = None Nstate_frames = None else: # We don't need to evaluate the calibration-time noise. dp_triangulated_db = None istate_i0 = None istate_i1 = None icam_extrinsics0 = None icam_extrinsics1 = None istate_e1 = None istate_e0 = None if q_observation_stdev is not None: # observation-time variance of each observed pair of points # shape (Ncameras*Nxy, Ncameras*Nxy) = (4,4) Var_q_observation_flat = \ _compute_Var_q_triangulation(q_observation_stdev, q_observation_stdev_correlation) Var_p_observation = np.zeros((Npoints,3,3), dtype=float) else: Var_p_observation = None for ipt in range(Npoints): q,models01 = slices[ipt] if optimization_inputs is None: # shape (3,Ncameras*Nxy=4) dp_triangulated_dq = \ _triangulate_grad_simple(q, models01, out = p[ipt], method = method) else: dp_triangulated_dq, \ drt_ref1_drt_1ref, \ drt01_drt_0ref, \ drt01_drt_ref1, \ dvlocal0_dintrinsics0, \ dvlocal1_dintrinsics1, \ dv1_dr01, \ dv1_dvlocal1, \ dp_triangulated_dv0, \ dp_triangulated_dv1, \ dp_triangulated_dt01 = \ _triangulate_grad(models01, q, out = p[ipt], method = method) # triangulation-time uncertainty if q_observation_stdev is not None: nps.matmult( dp_triangulated_dq, Var_q_observation_flat, nps.transpose(dp_triangulated_dq), out = Var_p_observation[ipt,...]) if optimization_inputs is None: # Not evaluating calibration-time uncertainty. Nothing else to do. continue # calibration-time uncertainty if stabilize_coords: dp_triangulated_drtrf, \ dp_triangulated_drt_0ref = \ stabilize(p[ipt], models01[0].extrinsics_rt_fromref(), rt_ref_frame) else: dp_triangulated_drtrf = None dp_triangulated_drt_0ref = None # Do the right thing is we're optimizing partial intrinsics only i0,i1 = None,None # everything by default has_core = mrcal.lensmodel_metadata_and_config(optimization_inputs['lensmodel'])['has_core'] Ncore = 4 if has_core else 0 Ndistortions = mrcal.lensmodel_num_params(optimization_inputs['lensmodel']) - Ncore if not optimization_inputs.get('do_optimize_intrinsics_core'): i0 = Ncore if not optimization_inputs.get('do_optimize_intrinsics_distortions'): i1 = -Ndistortions slice_optimized_intrinsics = slice(i0,i1) dvlocal0_dintrinsics0 = dvlocal0_dintrinsics0[...,slice_optimized_intrinsics] dvlocal1_dintrinsics1 = dvlocal1_dintrinsics1[...,slice_optimized_intrinsics] ### Sensitivities # The data flow: # q0,i0 -> v0 (same as vlocal0; I'm working in the cam0 coord system) # q1,i1 -> vlocal1 # r_0ref,r_1ref -> r01 # r_0ref,r_1ref,t_0ref,t_1ref -> t01 # vlocal1,r01 -> v1 # v0,v1,t01 -> p_triangulated icam_intrinsics0 = models01[0].icam_intrinsics() icam_intrinsics1 = models01[1].icam_intrinsics() istate_i0 = mrcal.state_index_intrinsics(icam_intrinsics0, **optimization_inputs) istate_i1 = mrcal.state_index_intrinsics(icam_intrinsics1, **optimization_inputs) if istate_i0 is not None: # dp_triangulated_di0 = dp_triangulated_dv0 dvlocal0_di0 # dp_triangulated_di1 = dp_triangulated_dv1 dv1_dvlocal1 dvlocal1_di1 nps.matmult( dp_triangulated_dv0, dvlocal0_dintrinsics0, out = dp_triangulated_db[ipt, :, istate_i0:istate_i0+Nintrinsics]) if istate_i1 is not None: nps.matmult( dp_triangulated_dv1, dv1_dvlocal1, dvlocal1_dintrinsics1, out = dp_triangulated_db[ipt, :, istate_i1:istate_i1+Nintrinsics]) icam_extrinsics0 = mrcal.corresponding_icam_extrinsics(icam_intrinsics0, **optimization_inputs) icam_extrinsics1 = mrcal.corresponding_icam_extrinsics(icam_intrinsics1, **optimization_inputs) if icam_extrinsics0 >= 0: istate_e0 = mrcal.state_index_extrinsics(icam_extrinsics0, **optimization_inputs) else: istate_e0 = None if icam_extrinsics1 >= 0: istate_e1 = mrcal.state_index_extrinsics(icam_extrinsics1, **optimization_inputs) else: istate_e1 = None if istate_e1 is not None: # dp_triangulated_dr_0ref = dp_triangulated_dv1 dv1_dr01 dr01_dr_0ref + # dp_triangulated_dt01 dt01_dr_0ref # dp_triangulated_dr_1ref = dp_triangulated_dv1 dv1_dr01 dr01_dr_1ref + # dp_triangulated_dt01 dt01_dr_1ref # dp_triangulated_dt_0ref = dp_triangulated_dt01 dt01_dt_0ref # dp_triangulated_dt_1ref = dp_triangulated_dt01 dt01_dt_1ref dr01_dr_ref1 = drt01_drt_ref1[:3,:3] dr_ref1_dr_1ref = drt_ref1_drt_1ref[:3,:3] dr01_dr_1ref = nps.matmult(dr01_dr_ref1, dr_ref1_dr_1ref) dt01_drt_ref1 = drt01_drt_ref1[3:,:] dt01_dr_1ref = nps.matmult(dt01_drt_ref1, drt_ref1_drt_1ref[:,:3]) dt01_dt_1ref = nps.matmult(dt01_drt_ref1, drt_ref1_drt_1ref[:,3:]) nps.matmult( dp_triangulated_dv1, dv1_dr01, dr01_dr_1ref, out = dp_triangulated_db[ipt, :, istate_e1:istate_e1+3]) dp_triangulated_db[ipt, :, istate_e1:istate_e1+3] += \ nps.matmult(dp_triangulated_dt01, dt01_dr_1ref) nps.matmult( dp_triangulated_dt01, dt01_dt_1ref, out = dp_triangulated_db[ipt, :, istate_e1+3:istate_e1+6]) if istate_e0 is not None: dr01_dr_0ref = drt01_drt_0ref[:3,:3] dt01_dr_0ref = drt01_drt_0ref[3:,:3] dt01_dt_0ref = drt01_drt_0ref[3:,3:] nps.matmult( dp_triangulated_dv1, dv1_dr01, dr01_dr_0ref, out = dp_triangulated_db[ipt, :, istate_e0:istate_e0+3]) dp_triangulated_db[ipt, :, istate_e0:istate_e0+3] += \ nps.matmult(dp_triangulated_dt01, dt01_dr_0ref) nps.matmult( dp_triangulated_dt01, dt01_dt_0ref, out = dp_triangulated_db[ipt, :, istate_e0+3:istate_e0+6]) if dp_triangulated_drt_0ref is not None: dp_triangulated_db[ipt, :, istate_e0:istate_e0+6] += dp_triangulated_drt_0ref if dp_triangulated_drtrf is not None: # We're re-optimizing (looking at calibration uncertainty) AND we # are optimizing the frames AND we have stabilization enabled. # Without stabilization, there's no dependence on rt_ref_frame # dp_triangulated_drtrf has shape (Npoints,Nframes,3,6). I reshape to (Npoints,3,Nframes*6) dp_triangulated_db[ipt, :, istate_f0:istate_f0+Nstate_frames] = \ nps.clump(nps.xchg(dp_triangulated_drtrf,-2,-3), n=-2) # Returning the istate stuff for the test suite. These are the istate_... # and icam_... for the last slice only. This is good-enough for the test # suite return p, Var_p_observation, dp_triangulated_db, \ istate_i0, \ istate_i1, \ icam_extrinsics0, \ icam_extrinsics1, \ istate_e1, \ istate_e0 def triangulate( q, models, *, q_calibration_stdev = None, q_observation_stdev = None, q_observation_stdev_correlation = 0, method = triangulate_leecivera_mid2, stabilize_coords = True): r'''Triangulate N points with uncertainty propagation SYNOPSIS p, \ Var_p_calibration, \ Var_p_observation, \ Var_p_joint = \ mrcal.triangulate( nps.cat(q0, q), (model0, model1), q_calibration_stdev = q_calibration_stdev, q_observation_stdev = q_observation_stdev, q_observation_stdev_correlation = q_observation_stdev_correlation ) # p is now the triangulated point, in camera0 coordinates. The uncertainties # of p from different sources are returned in the Var_p_... arrays DESCRIPTION This is the interface to the triangulation computations described in http://mrcal.secretsauce.net/triangulation.html Let's say two cameras observe a point p in space. The pixel observations of this point in the two cameras are q0 and q1 respectively. If the two cameras are calibrated (both intrinsics and extrinsics), I can reconstruct the observed point p from the calibration and the two pixel observations. This is the "triangulation" operation implemented by this function. If the calibration and the pixel observations q0,q1 were perfect, computing the corresponding point p would be trivial: unproject q0 and q1, and find the intersection of the resulting rays. Since everything is perfect, the rays will intersect exactly at p. But in reality, both the calibration and the pixel observations are noisy. This function propagates these sources of noise through the triangulation, to produce covariance matrices of p. Two kinds of noise are propagated: - Calibration-time noise. This is the noise in the pixel observations of the chessboard corners, propagated through the calibration to the triangulation result. The normal use case is to calibrate once, and then use the same calibration result many times. So each time we use a given calibration, we have the same calibration-time noise, resulting in correlated errors between each such triangulation operation. This is a source of bias: averaging many different triangulation results will NOT push the errors to 0. Here, only the calibration-time input noise is taken into account. Other sources of calibration-time errors (bad input data, outliers, non-fitting model) are ignored. Furthermore, currently a vanilla calibration is assumed: both cameras in the camera pair must have been calibrated together, and the cameras were not moved in respect to each other after the calibration. - Observation-time noise. This is the noise in the pixel observations of the point being propagated: q0, q1. Unlike the calibration-time noise, each sample of observations (q0,q1) IS independent from every other sample. So if we observe the same point p many times, this observation noise will average out. Both sources of noise are assumed normal with the noise on the x and y components of the observation being independent. The standard deviation of the noise is given by the q_calibration_stdev and q_observation_stdev arguments. Since q0 and q1 often arise from an image correlation operation, they are usually correlated with each other. It's not yet clear to me how to estimate this correlation, but it can be specified in this function with the q_observation_stdev_correlation argument: - q_observation_stdev_correlation = 0: the noise on q0 and q1 is independent - q_observation_stdev_correlation = 1: the noise on q0 and q1 is 100% correlated The (q0x,q1x) and (q0y,q1y) cross terms of the covariance matrix are (q_observation_stdev_correlation*q_observation_stdev)^2 Since the distribution of the calibration-time input noise is given at calibration time, we can just use that distribution instead of specifying it again: pass q_calibration_stdev<0 to do that. COORDINATE STABILIZATION We're analyzing the effects of calibration-time noise. As with projection uncertainty, varying calibration-time noise affects the pose of the camera coordinate system in respect to the physical camera housing. So Var(p) in the camera coord system includes this coordinate-system fuzz, which is usually not something we want to include. To compensate for this fuzz pass stabilize_coords=True to return Var(p) in the physical camera housing coords. The underlying method is exactly the same as how this is done with projection uncertainty: http://mrcal.secretsauce.net/uncertainty.html#propagating-through-projection In the usual case, the translation component of this extra transformation is negligible, but the rotation (even a small one) produces lateral uncertainty that isn't really there. Enabling stabilization usually reduces the size of the uncertainty ellipse in the lateral direction. BROADCASTING Broadcasting is fully supported on models and q. Each slice has 2 models and 2 pixel observations (q0,q1). If multiple models and/or observation pairs are given, we compute the covariances with all the cross terms, so Var_p_calibration.size grows quadratically with the number of broadcasted slices. ARGUMENTS - q: (..., 2,2) numpy array of pixel observations. Each broadcasted slice describes a pixel observation from each of the two cameras - models: iterable of shape (..., 2). Complex shapes may be represented in a numpy array of dtype=np.object. Each row is two mrcal.cameramodel objects describing the left and right cameras - q_calibration_stdev: optional value describing the calibration-time noise. If omitted or None, we do not compute or return the uncertainty resulting from this noise. The noise in the observations of chessboard corners is assumed to be normal and independent for each corner and for the x and y components. To use the optimization residuals, pass any q_calibration_stdev < 0 - q_observation_stdev: optional value describing the observation-time noise. If omitted or None, we do not compute or return the uncertainty resulting from this noise. The noise in the observations is assumed to be normal and independent for the x and y components - q_observation_stdev_correlation: optional value, describing the correlation between the pair of pixel coordinates observing the same point in space. Since q0 and q1 often arise from an image correlation operation, they are usually correlated with each other. This argument linearly scales q_observation_stdev: 0 = "independent", 1 = "100% correlated". The default is 0 - method: optional value selecting the triangulation method. This is one of the mrcal.triangulate_... functions. If omitted, we select mrcal.triangulate_leecivera_mid2. At this time, mrcal.triangulate_lindstrom is usable only if we do not propagate any uncertainties - stabilize_coords: optional boolean, defaulting to True. We always return the triangulated point in camera-0 coordinates. If we're propagating calibration-time noise, then the origin of those coordinates moves around inside the housing of the camera. Characterizing this extra motion is generally not desired in Var_p_calibration. To compensate for this motion, and return Var_p_calibration in the coordinate system of the HOUSING of camera-0, pass stabilize_coords = True. RETURN VALUES We always return p: the coordinates of the triangulated point(s) in the camera-0 coordinate system. Depending on the input arguments, we may also return uncertainties. The general logic is: if q_xxx_stdev is None: don't propagate or return that source of uncertainty if q_xxx_stdev == 0: don't propagate that source of uncertainty, but return Var_p_xxx = np.zeros(...) if both q_xxx_stdev are not None: we compute and report the two separate uncertainty components AND a joint covariance combining the two If we need to return Var_p_calibration, it has shape (...,3, ...,3) where ... is the broadcasting shape. If a single triangulation is being performed, there's no broadcasting, and Var_p_calibration.shape = (3,3). This representation allows us to represent the correlated covariances (non-zero cross terms) that arise due to calibration-time uncertainty. If we need to return Var_p_observation, it has shape (...,3,3) where ... is the broadcasting shape. If a single triangulation is being performed, there's no broadcasting, and Var_p_observation.shape = (3,3). This representation is more compact than that for Var_p_calibration because it assumes independent covariances (zero cross terms) that result when propagating observation-time uncertainty. If we need to return Var_p_joint, it has shape (...,3, ...,3) where ... is the broadcasting shape. If a single triangulation is being performed, there's no broadcasting, and Var_p_joint.shape = (3,3). This representation allows us to represent the correlated covariances (non-zero cross terms) that arise due to calibration-time uncertainty. Complete logic: if q_calibration_stdev is None and q_observation_stdev is None: # p.shape = (...,3) return p if q_calibration_stdev is not None and q_observation_stdev is None: # p.shape = (...,3) # Var_p_calibration.shape = (...,3,...,3) return p, Var_p_calibration if q_calibration_stdev is None and q_observation_stdev is not None: # p.shape = (...,3) # Var_p_observation.shape = (...,3,3) return p, Var_p_observation if q_calibration_stdev is not None and q_observation_stdev is not None: # p.shape = (...,3) # Var_p_calibration.shape = (...,3,...,3) # Var_p_observation.shape = (...,3, 3) # Var_p_joint.shape = (...,3,...,3) return p, Var_p_calibration, Var_p_observation, Var_p_joint ''' # I'm propagating noise in the input vector # # x = [q_cal q_obs0 q_obs1 q_obs2 ...] # # This is the noise in the pixel observations at calibration-time and at # triangulation time. All the triangulated points are assumed to originate # from cameras calibrated using this one calibration run (using observations # q_cal). For each triangulation we want to compute, we have a separate set # of observations. I want to propagate the noise in x to some function f(x). # As usual # # Var(f) = df/dx Var(x) (df/dx)T. # # The noise on all the triangulation-time points is independent, as is the # calibration-time noise. Thus Var(x) is block-diagonal and # # Var(f) = df/dq_cal Var(q_cal) (df/dq_cal)T + # df/dq_obs0 Var(q_obs0) (df/dq_obs0)T + # df/dq_obs1 Var(q_obs1) (df/dq_obs1)T + ... if q_observation_stdev is not None and \ q_observation_stdev < 0: raise Exception("q_observation_stdev MUST be None or >= 0") if not isinstance(models, np.ndarray): models = np.array(models, dtype=object) slices = tuple(nps.broadcast_generate( ((2,2),(2,)), (q, models) ) ) broadcasted_shape = tuple(nps.broadcast_extra_dims( ((2,2),(2,)), (q, models) )) if (q_calibration_stdev is None or q_calibration_stdev == 0) and \ (q_observation_stdev is None or q_observation_stdev == 0): # I don't need to propagate any noise @nps.broadcast_define(((2,2),(2,)), (3,)) def triangulate_slice(q01, m01): Rt01 = \ mrcal.compose_Rt(m01[0].extrinsics_Rt_fromref(), m01[1].extrinsics_Rt_toref()) # all the v have shape (3,) vlocal0 = mrcal.unproject(q01[0,:], *m01[0].intrinsics()) vlocal1 = mrcal.unproject(q01[1,:], *m01[1].intrinsics()) return method(vlocal0, vlocal1, v_are_local = True, Rt01 = Rt01) p = triangulate_slice(q, models) if q_calibration_stdev is None and \ q_observation_stdev is None: return p if q_calibration_stdev is not None: Var_p_calibration = np.zeros(broadcasted_shape + (3,) + broadcasted_shape + (3,), dtype=float) if q_observation_stdev is not None: Var_p_observation = np.zeros(broadcasted_shape + (3,3), dtype=float) if q_calibration_stdev is not None: if q_observation_stdev is not None: return p, Var_p_calibration, Var_p_observation, Var_p_calibration else: return p, Var_p_calibration else: return p, Var_p_observation # SOMETHING is non-zero, so we need to do noise propagation if q_calibration_stdev is not None and \ q_calibration_stdev != 0: # we're propagating calibration-time noise models_flat = models.ravel() optimization_inputs = models_flat[0].optimization_inputs() if optimization_inputs is None: raise Exception("optimization_inputs are not available, so I cannot propagate calibration-time noise") for i0 in range(len(models_flat)): for i1 in range(i0): if not models_flat[i0]._optimization_inputs_match(models_flat[i1]): raise Exception("The optimization_inputs for all of the given models must be identical") if models_flat[i0]._extrinsics_moved_since_calibration(): raise Exception(f"The given models must have been fixed inside the initial calibration. Model {i0} has been moved") else: optimization_inputs = None # p has shape (Npoints + (3,)) # Var_p_observation_flat has shape (Npoints + (3,3)) # dp_triangulated_db has shape (Npoints*3 + (Nstate,)) p, \ Var_p_observation_flat, \ dp_triangulated_db = \ _triangulation_uncertainty_internal( slices, optimization_inputs, q_observation_stdev, q_observation_stdev_correlation, method = method, stabilize_coords = stabilize_coords)[:3] # Done looping through all the triangulated points. I have computed the # observation-time noise contributions in Var_p_observation. And I have all # the gradients in dp_triangulated_db if optimization_inputs is not None: # reshape dp_triangulated_db to (Npoints*3, Nstate) # So the Var(p) will end up with shape (Npoints*3, Npoints*3) dp_triangulated_db = nps.clump(dp_triangulated_db,n=2) if q_calibration_stdev > 0: # Calibration-time noise is given. Use it. observed_pixel_uncertainty = q_calibration_stdev else: # Infer the expected calibration-time noise from the calibration data observed_pixel_uncertainty = None # Var_p_calibration_flat has shape (Npoints*3,Npoints*3) Var_p_calibration_flat = \ mrcal.model_analysis._propagate_calibration_uncertainty( 'covariance', dF_db = dp_triangulated_db, observed_pixel_uncertainty = observed_pixel_uncertainty, optimization_inputs = optimization_inputs) else: Var_p_calibration_flat = None # I used broadcast_generate() to implement the broadcasting logic. This # function flattened the broadcasted output, so at this time I have # p.shape = (Npoints,3) # Var_p_calibration_flat.shape = (Npoints*3, Npoints*3) # Var_p_observation_flat.shape = (Npoints,3,3) # # I now reshape the output into its proper shape. I have the leading shape I # want in broadcasted_shape (I know that reduce(broadcast_extra_dims, *) = # Npoints) p = p.reshape(broadcasted_shape + (3,)) if Var_p_calibration_flat is not None: Var_p_calibration = \ Var_p_calibration_flat.reshape(broadcasted_shape + (3,) + broadcasted_shape + (3,)) elif q_calibration_stdev is not None and \ q_calibration_stdev == 0: Var_p_calibration = \ np.zeros(broadcasted_shape + (3,) + broadcasted_shape + (3,)) else: Var_p_calibration = None if Var_p_observation_flat is not None: Var_p_observation = \ Var_p_observation_flat.reshape(broadcasted_shape + (3,3)) else: Var_p_observation = None if Var_p_observation is None: return p, Var_p_calibration if Var_p_calibration is None: return p, Var_p_observation # Propagating both types of noise. I create a joint covariance matrix if Var_p_calibration is not None: Var_p_joint = Var_p_calibration.copy() else: Var_p_joint = np.zeros((broadcasted_shape + (3,) + broadcasted_shape + (3,)), dtype=float) if Var_p_observation is not None: Var_p_joint_flat = Var_p_joint.reshape(len(slices)*3, len(slices)*3) for ipt in range(len(slices)): Var_p_joint_flat[ipt*3:(ipt+1)*3,ipt*3:(ipt+1)*3] += \ Var_p_observation_flat[ipt,...] return p, Var_p_calibration, Var_p_observation, Var_p_joint mrcal-2.4.1/mrcal/utils.py000066400000000000000000001653511456301662300154450ustar00rootroot00000000000000#!/usr/bin/python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 '''General utility functions used throughout mrcal All functions are exported into the mrcal module. So you can call these via mrcal.utils.fff() or mrcal.fff(). The latter is preferred. ''' import numpy as np import numpysane as nps import sys import re import mrcal def align_procrustes_points_Rt01(p0, p1, weights=None): r"""Compute a rigid transformation to align two point clouds SYNOPSIS print(points0.shape) ===> (100,3) print(points1.shape) ===> (100,3) Rt01 = mrcal.align_procrustes_points_Rt01(points0, points1) print( np.sum(nps.norm2(mrcal.transform_point_Rt(Rt01, points1) - points0)) ) ===> [The fit error from applying the optimal transformation. If the two point clouds match up, this will be small] Given two sets of 3D points in numpy arrays of shape (N,3), we find the optimal rotation, translation to align these sets of points. This is done with a well-known direct method. See: - https://en.wikipedia.org/wiki/Orthogonal_Procrustes_problem - https://en.wikipedia.org/wiki/Kabsch_algorithm We return a transformation that minimizes the sum 2-norm of the misalignment: cost = sum( norm2( w[i] (a[i] - transform(b[i])) )) We return an Rt transformation to map points in set 1 to points in set 0. At least 3 sets of points must be passed-in to produce a non-singular result. If a set of inputs produces a singular result, a (4,3) array of 0 is returned. This is not a valid Rt transform, and is used to signal an error. A similar computation can be performed to instead align a set of UNIT VECTORS to compute an optimal rotation matrix R by calling align_procrustes_vectors_R01(). ARGUMENTS - p0: an array of shape (..., N, 3). Each row is a point in the coordinate system we're transforming TO - p1: an array of shape (..., N, 3). Each row is a point in the coordinate system we're transforming FROM - weights: optional array of shape (..., N). Specifies the relative weight of each point. If omitted, all the given points are weighted equally RETURNED VALUES The Rt transformation in an array of shape (4,3). We return the optimal transformation to align the given point clouds. The transformation maps points TO coord system 0 FROM coord system 1. If the inputs were singular or insufficient, a (4,3) array of 0 is returned. This is not a valid Rt transform, and is used to signal an error. """ if weights is None: weights = np.ones(p0.shape[:-1], dtype=float) return _align_procrustes_points_Rt01(p0,p1,weights) @nps.broadcast_define( (('N',3,), ('N',3,), ('N',)), (4,3), ) def _align_procrustes_points_Rt01(p0, p1, weights): p0 = nps.transpose(p0) p1 = nps.transpose(p1) # I process Mt instead of M to not need to transpose anything later, and to # end up with contiguous-memory results Mt = nps.matmult( (p0 - np.mean(p0, axis=-1)[..., np.newaxis])*weights, nps.transpose(p1 - np.mean(p1, axis=-1)[..., np.newaxis])) V,S,Ut = np.linalg.svd(Mt) # I look at the second-lowest singular value. One 0 singular value is OK; # two isn't if S[-2] < 1e-12: # Poorly-defined problem. Return error return np.zeros((4,3), dtype=float) R = nps.matmult(V, Ut) # det(R) is now +1 or -1. If it's -1, then this contains a mirror, and thus # is not a physical rotation. I compensate by negating the least-important # pair of singular vectors if np.linalg.det(R) < 0: V[:,2] *= -1 R = nps.matmult(V, Ut) # Now that I have my optimal R, I compute the optimal t. From before: # # t = mean(a) - R mean(b) t = np.mean(p0, axis=-1)[..., np.newaxis] - nps.matmult( R, np.mean(p1, axis=-1)[..., np.newaxis] ) return nps.glue( R, t.ravel(), axis=-2) def align_procrustes_vectors_R01(v0, v1, weights=None): r"""Compute a rotation to align two sets of direction vectors SYNOPSIS print(vectors0.shape) ===> (100,3) print(vectors1.shape) ===> (100,3) R01 = mrcal.align_procrustes_vectors_R01(vectors0, vectors1) print( np.mean(1. - nps.inner(mrcal.rotate_point_R(R01, vectors1), vectors0)) ) ===> [The fit error from applying the optimal rotation. If the two sets of vectors match up, this will be small] Given two sets of normalized direction vectors in 3D (stored in numpy arrays of shape (N,3)), we find the optimal rotation to align them. This is done with a well-known direct method. See: - https://en.wikipedia.org/wiki/Orthogonal_Procrustes_problem - https://en.wikipedia.org/wiki/Kabsch_algorithm We return a rotation that minimizes the weighted sum of the cosine of the misalignment: cost = -sum( w[i] inner(a[i], rotate(b[i])) ) We return a rotation to map vectors in set 1 to vectors in set 0. At least 2 sets of vectors must be passed-in to produce a non-singular result. If a set of inputs produces a singular result, a (3,3) array of 0 is returned. This is not a valid rotation, and is used to signal an error. A similar computation can be performed to instead align a set of POINTS to compute an optimal transformation Rt by calling align_procrustes_points_Rt01(). ARGUMENTS - v0: an array of shape (..., N, 3). Each row is a vector in the coordinate system we're transforming TO. These are assumed normalized. - v1: an array of shape (..., N, 3). Each row is a vector in the coordinate system we're transforming FROM. These are assumed normalized. - weights: optional array of shape (..., N). Specifies the relative weight of each vector. If omitted, everything is weighted equally RETURNED VALUES The rotation matrix in an array of shape (3,3). We return the optimal rotation to align the given vector sets. The rotation maps vectors TO coord system 0 FROM coord system 1. If the inputs were singular or insufficient, a (3,3) array of 0 is returned. This is not a valid rotation, and is used to signal an error. """ if weights is None: weights = np.ones(v0.shape[:-1], dtype=float) return _align_procrustes_vectors_R01(v0,v1,weights) @nps.broadcast_define( (('N',3,), ('N',3,), ('N',)), (3,3), ) def _align_procrustes_vectors_R01(v0, v1, weights): v0 = nps.transpose(v0) v1 = nps.transpose(v1) # I process Mt instead of M to not need to transpose anything later, and to # end up with contiguous-memory results Mt = nps.matmult( v0*weights, nps.transpose(v1) ) V,S,Ut = np.linalg.svd(Mt) # I look at the second-lowest singular value. One 0 singular value is OK; # two isn't if S[-2] < 1e-12: # Poorly-defined problem. Return error return np.zeros((3,3), dtype=float) R = nps.matmult(V, Ut) # det(R) is now +1 or -1. If it's -1, then this contains a mirror, and thus # is not a physical rotation. I compensate by negating the least-important # pair of singular vectors if np.linalg.det(R) < 0: V[:,2] *= -1 R = nps.matmult(V, Ut) return R def sample_imager(gridn_width, gridn_height, imager_width, imager_height): r'''Returns regularly-sampled, gridded pixels coordinates across the imager SYNOPSIS q = sample_imager( 60, 40, *model.imagersize() ) print(q.shape) ===> (40,60,2) Note that the arguments are given in width,height order, as is customary when generally talking about images and indexing. However, the output is in height,width order, as is customary when talking about matrices and numpy arrays. If we ask for gridding dimensions (gridn_width, gridn_height), the output has shape (gridn_height,gridn_width,2) where each row is an (x,y) pixel coordinate. The top-left corner is at [0,0,:]: sample_imager(...)[0,0] = [0,0] The the bottom-right corner is at [-1,-1,:]: sample_imager(...)[ -1, -1,:] = sample_imager(...)[gridn_height-1,gridn_width-1,:] = (imager_width-1,imager_height-1) When making plots you probably want to call mrcal.imagergrid_using(). See the that docstring for details. ARGUMENTS - gridn_width: how many points along the horizontal gridding dimension - gridn_height: how many points along the vertical gridding dimension. If None, we compute an integer gridn_height to maintain a square-ish grid: gridn_height/gridn_width ~ imager_height/imager_width - imager_width,imager_height: the width, height of the imager. With a mrcal.cameramodel object this is *model.imagersize() RETURNED VALUES We return an array of shape (gridn_height,gridn_width,2). Each row is an (x,y) pixel coordinate. ''' if gridn_height is None: gridn_height = int(round(imager_height/imager_width*gridn_width)) w = np.linspace(0,imager_width -1,gridn_width) h = np.linspace(0,imager_height-1,gridn_height) return np.ascontiguousarray(nps.mv(nps.cat(*np.meshgrid(w,h)), 0,-1)) def sample_imager_unproject(gridn_width, gridn_height, imager_width, imager_height, lensmodel, intrinsics_data, normalize = False): r'''Reports 3D observation vectors that regularly sample the imager SYNOPSIS import gnuplotlib as gp import mrcal ... Nwidth = 60 Nheight = 40 # shape (Nheight,Nwidth,3) v,q = \ mrcal.sample_imager_unproject(Nw, Nh, *model.imagersize(), *model.intrinsics()) # shape (Nheight,Nwidth) f = interesting_quantity(v) gp.plot(f, tuplesize = 3, ascii = True, using = mrcal.imagergrid_using(model.imagersize, Nw, Nh), square = True, _with = 'image') This is a utility function used by functions that evalute some interesting quantity for various locations across the imager. Grid dimensions and lens parameters are passed in, and the grid points and corresponding unprojected vectors are returned. The unprojected vectors are unique only up-to-length, and the returned vectors aren't normalized by default. If we want them to be normalized, pass normalize=True. This function has two modes of operation: - One camera. lensmodel is a string, and intrinsics_data is a 1-dimensions numpy array. With a mrcal.cameramodel object together these are *model.intrinsics(). We return (v,q) where v is a shape (Nheight,Nwidth,3) array of observation vectors, and q is a (Nheight,Nwidth,2) array of corresponding pixel coordinates (the grid returned by sample_imager()) - Multiple cameras. lensmodel is a list or tuple of strings; intrinsics_data is an iterable of 1-dimensional numpy arrays (a list/tuple or a 2D array). We return the same q as before (only one camera is gridded), but the unprojected array v has shape (Ncameras,Nheight,Nwidth,3) where Ncameras is the leading dimension of lensmodel. The gridded imager appears in camera0: v[0,...] = unproject(q) ARGUMENTS - gridn_width: how many points along the horizontal gridding dimension - gridn_height: how many points along the vertical gridding dimension. If None, we compute an integer gridn_height to maintain a square-ish grid: gridn_height/gridn_width ~ imager_height/imager_width - imager_width,imager_height: the width, height of the imager. With a mrcal.cameramodel object this is *model.imagersize() - lensmodel, intrinsics_data: the lens parameters. With a single camera, lensmodel is a string, and intrinsics_data is a 1-dimensions numpy array; with a mrcal.cameramodel object together these are *model.intrinsics(). With multiple cameras, lensmodel is a list/tuple of strings. And intrinsics_data is an iterable of 1-dimensional numpy arrays (a list/tuple or a 2D array). - normalize: optional boolean defaults to False. If True: normalize the output vectors RETURNED VALUES We return a tuple: - v: the unprojected vectors. If we have a single camera this has shape (Nheight,Nwidth,3). With multiple cameras this has shape (Ncameras,Nheight,Nwidth,3). These are NOT normalized by default. To get normalized vectors, pass normalize=True - q: the imager-sampling grid. This has shape (Nheight,Nwidth,2) regardless of how many cameras were given (we always sample just one camera). This is what sample_imager() returns ''' def is_list_or_tuple(l): return isinstance(l,list) or isinstance(l,tuple) # shape: (Nheight,Nwidth,2). Contains (x,y) rows grid = sample_imager(gridn_width, gridn_height, imager_width, imager_height) if is_list_or_tuple(lensmodel): # shape: Ncameras,Nwidth,Nheight,3 return np.array([mrcal.unproject(np.ascontiguousarray(grid), lensmodel[i], intrinsics_data[i], normalize = normalize) \ for i in range(len(lensmodel))]), \ grid else: # shape: Nheight,Nwidth,3 return \ mrcal.unproject(np.ascontiguousarray(grid), lensmodel, intrinsics_data, normalize = normalize), \ grid def hypothesis_board_corner_positions(icam_intrinsics = None, idx_inliers = None, **optimization_inputs): r'''Reports the 3D chessboard points observed by a camera at calibration time SYNOPSIS model = mrcal.cameramodel("xxx.cameramodel") optimization_inputs = model.optimization_inputs() # shape (Nobservations, Nheight, Nwidth, 3) pcam = mrcal.hypothesis_board_corner_positions(**optimization_inputs)[0] i_intrinsics = \ optimization_inputs['indices_frame_camintrinsics_camextrinsics'][:,1] # shape (Nobservations,1,1,Nintrinsics) intrinsics = nps.mv(optimization_inputs['intrinsics'][i_intrinsics],-2,-4) optimization_inputs['observations_board'][...,:2] = \ mrcal.project( pcam, optimization_inputs['lensmodel'], intrinsics ) # optimization_inputs now contains perfect, noiseless board observations x = mrcal.optimizer_callback(**optimization_inputs)[1] print(nps.norm2(x[:mrcal.num_measurements_boards(**optimization_inputs)])) ==> 0 The optimization routine generates hypothetical observations from a set of parameters being evaluated, trying to match these hypothetical observations to real observations. To facilitate analysis, this routine returns these hypothetical coordinates of the chessboard corners being observed. This routine reports the 3D points in the coordinate system of the observing camera. The hypothetical points are constructed from - The calibration object geometry - The calibration object-reference transformation in optimization_inputs['frames_rt_toref'] - The camera extrinsics (reference-camera transformation) in optimization_inputs['extrinsics_rt_fromref'] - The table selecting the camera and calibration object frame for each observation in optimization_inputs['indices_frame_camintrinsics_camextrinsics'] ARGUMENTS - icam_intrinsics: optional integer specifying which intrinsic camera in the optimization_inputs we're looking at. If omitted (or None), we report camera-coordinate points for all the cameras - idx_inliers: optional numpy array of booleans of shape (Nobservations,object_height,object_width) to select the outliers manually. If omitted (or None), the outliers are selected automatically: idx_inliers = observations_board[...,2] > 0. This argument is available to pick common inliers from two separate solves. - **optimization_inputs: a dict() of arguments passable to mrcal.optimize() and mrcal.optimizer_callback(). We use the geometric data. This dict is obtainable from a cameramodel object by calling cameramodel.optimization_inputs() RETURNED VALUE - An array of shape (Nobservations, Nheight, Nwidth, 3) containing the coordinates (in the coordinate system of each camera) of the chessboard corners, for ALL the cameras. These correspond to the observations in optimization_inputs['observations_board'], which also have shape (Nobservations, Nheight, Nwidth, 3) - An array of shape (Nobservations_thiscamera, Nheight, Nwidth, 3) containing the coordinates (in the camera coordinate system) of the chessboard corners, for the particular camera requested in icam_intrinsics. If icam_intrinsics is None: this is the same array as the previous returned value - an (N,3) array containing camera-frame 3D points observed at calibration time, and accepted by the solver as inliers. This is a subset of the 2nd returned array. - an (N,3) array containing camera-frame 3D points observed at calibration time, but rejected by the solver as outliers. This is a subset of the 2nd returned array. ''' observations_board = optimization_inputs.get('observations_board') if observations_board is None: raise Exception("No board observations available") indices_frame_camintrinsics_camextrinsics = \ optimization_inputs['indices_frame_camintrinsics_camextrinsics'] object_width_n = observations_board.shape[-2] object_height_n = observations_board.shape[-3] object_spacing = optimization_inputs['calibration_object_spacing'] calobject_warp = optimization_inputs.get('calobject_warp') # shape (Nh,Nw,3) full_object = mrcal.ref_calibration_object(object_width_n, object_height_n, object_spacing, calobject_warp = calobject_warp) frames_Rt_toref = \ mrcal.Rt_from_rt( optimization_inputs['frames_rt_toref'] )\ [ indices_frame_camintrinsics_camextrinsics[:,0] ] extrinsics_Rt_fromref = \ nps.glue( mrcal.identity_Rt(), mrcal.Rt_from_rt(optimization_inputs['extrinsics_rt_fromref']), axis = -3 ) \ [ indices_frame_camintrinsics_camextrinsics[:,2]+1 ] Rt_cam_frame = mrcal.compose_Rt( extrinsics_Rt_fromref, frames_Rt_toref ) p_cam_calobjects = \ mrcal.transform_point_Rt(nps.mv(Rt_cam_frame,-3,-5), full_object) # shape (Nobservations,Nheight,Nwidth) if idx_inliers is None: idx_inliers = observations_board[...,2] > 0 idx_outliers = ~idx_inliers if icam_intrinsics is None: return \ p_cam_calobjects, \ p_cam_calobjects, \ p_cam_calobjects[idx_inliers, ...], \ p_cam_calobjects[idx_outliers, ...] # The user asked for a specific camera. Separate out its data # shape (Nobservations,) idx_observations = indices_frame_camintrinsics_camextrinsics[:,1]==icam_intrinsics idx_inliers [~idx_observations] = False idx_outliers[~idx_observations] = False return \ p_cam_calobjects, \ p_cam_calobjects[idx_observations, ...], \ p_cam_calobjects[idx_inliers, ...], \ p_cam_calobjects[idx_outliers, ...] def _splined_stereographic_domain(lensmodel): r'''Return the stereographic domain for splined-stereographic lens models SYNOPSIS model = mrcal.cameramodel(model_filename) lensmodel = model.intrinsics()[0] domain_contour = mrcal._splined_stereographic_domain(lensmodel) Splined stereographic models are defined by a splined surface. This surface is indexed by normalized stereographic-projected points. This surface is defined in some finite area, and this function reports a piecewise linear contour reporting this region. This function only makes sense for splined stereographic models. RETURNED VALUE An array of shape (N,2) containing a contour representing the projection domain. ''' if not re.match('LENSMODEL_SPLINED_STEREOGRAPHIC', lensmodel): raise Exception(f"This only makes sense with splined models. Input uses {lensmodel}") ux,uy = mrcal.knots_for_splined_models(lensmodel) # shape (Ny,Nx,2) u = np.ascontiguousarray(nps.mv(nps.cat(*np.meshgrid(ux,uy)), 0, -1)) meta = mrcal.lensmodel_metadata_and_config(lensmodel) if meta['order'] == 2: # spline order is 3. The valid region is 1/2 segments inwards from the # outer contour return \ nps.glue( (u[0,1:-2] + u[1,1:-2]) / 2., (u[0,-2] + u[1,-2] + u[0,-1] + u[1,-1]) / 4., (u[1:-2, -2] + u[1:-2, -1]) / 2., (u[-2,-2] + u[-1,-2] + u[-2,-1] + u[-1,-1]) / 4., (u[-2, -2:1:-1] + u[-1, -2:1:-1]) / 2., (u[-2, 1] + u[-1, 1] + u[-2, 0] + u[-1, 0]) / 4., (u[-2:0:-1, 0] +u[-2:0:-1, 1]) / 2., (u[0, 0] +u[0, 1] + u[1, 0] +u[1, 1]) / 4., (u[0,1] + u[1,1]) / 2., axis = -2 ) elif meta['order'] == 3: # spline order is 3. The valid region is the outer contour, leaving one # knot out return \ nps.glue( u[1,1:-2], u[1:-2, -2], u[-2, -2:1:-1], u[-2:0:-1, 1], axis=-2 ) else: raise Exception("I only support cubic (order==3) and quadratic (order==2) models") def polygon_difference(positive, negative): r'''Return the difference of two closed polygons SYNOPSIS import numpy as np import numpysane as nps import gnuplotlib as gp A = np.array(((-1,-1),( 1,-1),( 1, 1),(-1, 1),(-1,-1))) B = np.array(((-.1,-1.1),( .1,-1.1),( .1, 1.1),(-.1, 1.1),(-.1,-1.1))) diff = mrcal.polygon_difference(A, B) gp.plot( (A, dict(legend = 'A', _with = 'lines')), (B, dict(legend = 'B', _with = 'lines')), *[ ( r, dict( _with = 'filledcurves closed fillcolor "red"', legend = 'difference')) for r in diff], tuplesize = -2, square = True, wait = True) Given two polygons specified as a point sequence in arrays of shape (N,2) this function computes the topological difference: all the regions contained in the positive polygon, but missing in the negative polygon. The result could be empty, or it could contain any number of disconnected polygons, so a list of polygons is returned. Each of the constituent resulting polygons is guaranteed to not have holes. If any holes are found when computing the difference, we cut apart the resulting shape until no holes remain. ARGUMENTS - positive: a polygon specified by a sequence of points in an array of shape (N,2). The resulting difference describes regions contained inside the positive polygon - negative: a polygon specified by a sequence of points in an array of shape (N,2). The resulting difference describes regions outside the negative polygon RETURNED VALUE A list of arrays of shape (N,2). Each array in the list describes a hole-free polygon as a sequence of points. The difference is a union of all these constituent polygons. This list could have 0 elements (empty difference) or N element (difference consists of N separate polygons) ''' from shapely.geometry import Polygon,MultiPolygon,GeometryCollection,LineString import shapely.ops diff = Polygon(positive).difference(Polygon(negative)) if isinstance(diff, (MultiPolygon,GeometryCollection)): diff = list(diff.geoms) elif isinstance(diff, Polygon): diff = [diff] else: raise Exception(f"I only know how to deal with MultiPolygon or Polygon, but instead got type '{type(diff)}") def split_polygon_to_remove_holes(p): if not isinstance(p, Polygon): raise Exception(f"Expected a 'Polygon' type, but got {type(p)}") if not (p.interiors and len(p.interiors)): # No hole. Return the coords, if they exist try: coords = p.exterior.coords if len(coords) == 0: return [] return [np.array(coords)] except: return [] # There's a hole! We need to split this polygon. I cut the polygon by a # line between the centroid and some vertex. Which one doesn't matter; I # keep trying until some cut works hole = p.interiors[0] for i in range(0,len(hole.coords)): l0 = np.array((hole.centroid)) l1 = np.array((hole.coords[i])) l0,l1 = (l1 + 100*(l0-l1)),(l0 + 100*(l1-l0)) line = LineString( (l0,l1) ) s = shapely.ops.split(p, line) if len(s) > 1: # success. split into multiple pieces. I process each one # recursively, and I'm done. I return a flattened list return [subpiece for piece in s for subpiece in split_polygon_to_remove_holes(piece)] # Split didn't work. Try the next vertex print("WARNING: Couldn't split the region. Ignoring", file = sys.stderr) return [] return \ [subpiece for p in diff for subpiece in split_polygon_to_remove_holes(p)] def _densify_polyline(p, spacing): r'''Returns the input polyline, but resampled more densely The input and output polylines are a numpy array of shape (N,2). The output is resampled such that each input point is hit, but each linear segment is also sampled with at least the given spacing ''' if p is None or p.size == 0: return p p1 = np.array(p[0,:], dtype=p.dtype) for i in range(1,len(p)): a = p[i-1,:] b = p[i, :] d = b-a l = nps.mag(d) # A hacky method of rounding up N = int(l/spacing - 1e-6 + 1.) for j in range(N): p1 = nps.glue(p1, float(j+1) / N * d + a, axis=-2) return p1 # mrcal.shellquote is either pipes.quote or shlex.quote, depending on # python2/python3 try: import pipes shellquote = pipes.quote except: # python3 puts this into a different module import shlex shellquote = shlex.quote def mapping_file_framenocameraindex(*files_per_camera): r'''Parse image filenames to get the frame numbers SYNOPSIS mapping = \ mapping_file_framenocameraindex( ('img5-cam2.jpg', 'img6-cam2.jpg'), ('img6-cam3.jpg', 'img7-cam3.jpg'),) print(mapping) ===> { 'frame5-cam2.jpg': (5, 0), 'frame6-cam2.jpg': (6, 0), 'frame6-cam3.jpg': (6, 1), 'frame7-cam3.jpg': (7, 1) } Prior to this call we already applied a glob to some images, so we already know which images belong to which camera. This function further classifies the images to find the frame number of each image. This is done by looking at the filenames of images in each camera, removing common prefixes and suffixes, and using the central varying filename component as the frame number. This varying component should be numeric. If it isn't and we have multiple cameras, then we barf. If it isn't, but we only have one camera, we fallback on sequential frame numbers. If we have just one image for a camera, I can't tell what is constant in the filenames, so I return framenumber=0. ARGUMENTS - *files_per_camera: one argument per camera. Each argument is a list of strings of filenames of images observed by that camera RETURNED VALUES We return a dict from filenames to (framenumber, cameraindex) tuples. The "cameraindex" is a sequential index counting up from 0. cameraindex==0 corresponds to files_per_camera[0] and so on. The "framenumber" may not be sequential OR starting from 0: this comes directly from the filename. ''' i_empty = [i for i in range(len(files_per_camera)) if len(files_per_camera[i]) == 0] if len(i_empty) > 0: raise Exception("These camera globs matched no files: {}".format(i_empty)) def get_longest_leading_trailing_substrings(strings): r'''Given a list of strings, returns the length of the longest leading and trailing substring common to all the strings Main use case is to take in strings such as a/b/c/frame001.png a/b/c/frame002.png a/b/c/frame003.png and return ("a/b/c/frame00", ".png") ''' # These feel inefficient, especially being written in python. There's # probably some built-in primitive I'm not seeing def longest_leading_substring(a,b): for i in range(len(a)): if i >= len(b) or a[i] != b[i]: return a[:i] return a def longest_trailing_substring(a,b): for i in range(len(a)): if i >= len(b) or a[-i-1] != b[-i-1]: if i == 0: return '' return a[-i:] return a if not strings: return (None,None) leading = strings[0] trailing = strings[0] for s in strings[1:]: leading = longest_leading_substring (leading,s) trailing = longest_trailing_substring(trailing,s) return leading,trailing def pull_framenumbers(files): if len(files) == 1: # special case where only one file is given. In this case I can't # tell where the frame number is, but I don't really care. I just # say that the frame number is 0 return [0] leading,trailing = get_longest_leading_trailing_substrings(files) Nleading = len(leading) Ntrailing = len(trailing) # I now have leading and trailing substrings. I make sure that all the stuff # between the leading and trailing strings is numeric # needed because I want s[i:-0] to mean s[i:], but that doesn't work, but # s[i:None] does Itrailing = -Ntrailing if Ntrailing > 0 else None for f in files: if not re.match("^[0-9]+$", f[Nleading:Itrailing]): raise Exception(("Image filenames MUST be of the form 'something..number..something'\n" + \ "where the somethings are common to all the filenames. File '{}'\n" + \ "has a non-numeric middle: '{}'. The somethings are: '{}' and '{}'\n" + \ "Did you forget to pass globs for each camera separately?"). \ format(f, f[Nleading:Itrailing], leading, trailing)) # Alrighty. The centers are all numeric. I gather all the digits around the # centers, and I'm done m = re.match("^(.*?)([0-9]*)$", leading) if m: pre_numeric = m.group(2) else: pre_numeric = '' m = re.match("^([0-9]*)(.*?)$", trailing) if m: post_numeric = m.group(1) else: post_numeric = '' return [int(pre_numeric + f[Nleading:Itrailing] + post_numeric) for f in files] Ncameras = len(files_per_camera) mapping = {} for icamera in range(Ncameras): try: framenumbers = pull_framenumbers(files_per_camera[icamera]) except: # If we couldn't parse out the frame numbers, but there's only one # camera, then I just use a sequential list of integers. Since it # doesn't matter if Ncameras == 1: framenumbers = range(len(files_per_camera[icamera])) else: raise if framenumbers is not None: mapping.update(zip(files_per_camera[icamera], [(iframe,icamera) for iframe in framenumbers])) return mapping def close_contour(c): r'''Close a polyline, if it isn't already closed SYNOPSIS print( a.shape ) ===> (5, 2) print( a[0] ) ===> [844 204] print( a[-1] ) ===> [886 198] b = mrcal.close_contour(a) print( b.shape ) ===> (6, 2) print( b[0] ) ===> [844 204] print( b[-2:] ) ===> [[886 198] [844 204]] This function works with polylines represented as arrays of shape (N,2). The polygon represented by such a polyline is "closed" if its first and last points sit at the same location. This function ingests a polyline, and returns the corresponding, closed polygon. If the first and last points of the input match, the input is returned. Otherwise, the first point is appended to the end, and this extended polyline is returned. None is accepted as an empty polygon: we return None. ARGUMENTS - c: an array of shape (N,2) representing the polyline to be closed. None and arrays of shape (0,2) are accepted as special cases ("unknown" and "empty" regions, respectively) RETURNED VALUE An array of shape (N,2) representing the closed polygon. The input is returned if the input was None or has shape (0,2) ''' if c is None or c.size == 0: return c if np.linalg.norm( c[0,:] - c[-1,:]) < 1e-6: return c return nps.glue(c, c[0,:], axis=-2) def plotoptions_state_boundaries(**optimization_inputs): r'''Return the 'set' plot options for gnuplotlib to show the state boundaries SYNOPSIS import numpy as np import gnuplotlib as gp import mrcal model = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = model.optimization_inputs() J = mrcal.optimizer_callback(**optimization_inputs)[2] gp.plot( np.sum(np.abs(J.toarray()), axis=-2), _set = mrcal.plotoptions_state_boundaries(**optimization_inputs) ) # a plot pops up showing the magnitude of the effects of each element of the # packed state (as seen by the optimizer), with boundaries between the # different state variables denoted When plotting the state vector (or anything relating to it, such as rows of the Jacobian), it is usually very useful to infer at a glance the meaning of each part of the plot. This function returns a list of 'set' directives passable to gnuplotlib that show the boundaries inside the state vector. ARGUMENTS **optimization_inputs: a dict() of arguments passable to mrcal.optimize() and mrcal.optimizer_callback(). These define the full optimization problem, and can be obtained from the optimization_inputs() method of mrcal.cameramodel RETURNED VALUE A list of 'set' directives passable as plot options to gnuplotlib ''' istate0 = [] try: istate0.append(int(mrcal.state_index_intrinsics (0, **optimization_inputs))) except: pass try: istate0.append(int(mrcal.state_index_extrinsics (0, **optimization_inputs))) except: pass try: istate0.append(int(mrcal.state_index_frames (0, **optimization_inputs))) except: pass try: istate0.append(int(mrcal.state_index_points (0, **optimization_inputs))) except: pass try: istate0.append(int(mrcal.state_index_calobject_warp( **optimization_inputs))) except: pass return [f"arrow nohead from {x},graph 0 to {x},graph 1" for x in istate0] def plotoptions_measurement_boundaries(**optimization_inputs): r'''Return the 'set' plot options for gnuplotlib to show the measurement boundaries SYNOPSIS import numpy as np import gnuplotlib as gp import mrcal model = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = model.optimization_inputs() x = mrcal.optimizer_callback(**optimization_inputs)[1] gp.plot( np.abs(x), _set = mrcal.plotoptions_measurement_boundaries(**optimization_inputs) ) # a plot pops up showing the magnitude of each measurement, with boundaries # between the different measurements denoted When plotting the measurement vector (or anything relating to it, such as columns of the Jacobian), it is usually very useful to infer at a glance the meaning of each part of the plot. This function returns a list of 'set' directives passable to gnuplotlib that show the boundaries inside the measurement vector. ARGUMENTS **optimization_inputs: a dict() of arguments passable to mrcal.optimize() and mrcal.optimizer_callback(). These define the full optimization problem, and can be obtained from the optimization_inputs() method of mrcal.cameramodel RETURNED VALUE A list of 'set' directives passable as plot options to gnuplotlib ''' imeas0 = [] try: imeas0.append(mrcal.measurement_index_boards (0, **optimization_inputs)) except: pass try: imeas0.append(mrcal.measurement_index_points (0, **optimization_inputs)) except: pass try: imeas0.append(mrcal.measurement_index_regularization(**optimization_inputs)) except: pass return [f"arrow nohead from {x},graph 0 to {x},graph 1" for x in imeas0] def ingest_packed_state(b_packed, **optimization_inputs): r'''Read a given packed state into optimization_inputs SYNOPSIS # A simple gradient check model = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = model.optimization_inputs() b0,x0,J = mrcal.optimizer_callback(no_factorization = True, **optimization_inputs)[:3] db = np.random.randn(len(b0)) * 1e-9 mrcal.ingest_packed_state(b0 + db, **optimization_inputs) x1 = mrcal.optimizer_callback(no_factorization = True, no_jacobian = True, **optimization_inputs)[1] dx_observed = x1 - x0 dx_predicted = nps.inner(J, db_packed) This is the converse of mrcal.optimizer_callback(). One thing mrcal.optimizer_callback() does is to convert the expanded (intrinsics, extrinsics, ...) arrays into a 1-dimensional scaled optimization vector b_packed. mrcal.ingest_packed_state() allows updates to b_packed to be absorbed back into the (intrinsics, extrinsics, ...) arrays for further evaluation with mrcal.optimizer_callback() and others. ARGUMENTS - b_packed: a numpy array of shape (Nstate,) containing the input packed state - **optimization_inputs: a dict() of arguments passable to mrcal.optimize() and mrcal.optimizer_callback(). The arrays in this dict are updated RETURNED VALUE None ''' intrinsics = optimization_inputs.get("intrinsics") extrinsics = optimization_inputs.get("extrinsics_rt_fromref") frames = optimization_inputs.get("frames_rt_toref") points = optimization_inputs.get("points") calobject_warp = optimization_inputs.get("calobject_warp") Npoints_fixed = optimization_inputs.get('Npoints_fixed', 0) Nvars_intrinsics = mrcal.num_states_intrinsics (**optimization_inputs) Nvars_extrinsics = mrcal.num_states_extrinsics (**optimization_inputs) Nvars_frames = mrcal.num_states_frames (**optimization_inputs) Nvars_points = mrcal.num_states_points (**optimization_inputs) Nvars_calobject_warp = mrcal.num_states_calobject_warp(**optimization_inputs) Nvars_expected = \ Nvars_intrinsics + \ Nvars_extrinsics + \ Nvars_frames + \ Nvars_points + \ Nvars_calobject_warp # Defaults MUST match those in OPTIMIZER_ARGUMENTS_OPTIONAL in # mrcal-pywrap.c. Or better yet, this whole function should # come from the C code instead of being reimplemented here in Python do_optimize_intrinsics_core = optimization_inputs.get('do_optimize_intrinsics_core', True) do_optimize_intrinsics_distortions = optimization_inputs.get('do_optimize_intrinsics_distortions', True) do_optimize_extrinsics = optimization_inputs.get('do_optimize_extrinsics', True) do_optimize_frames = optimization_inputs.get('do_optimize_frames', True) do_optimize_calobject_warp = optimization_inputs.get('do_optimize_calobject_warp', True) if b_packed.ravel().size != Nvars_expected: raise Exception(f"Mismatched array size: b_packed.size={b_packed.ravel().size} while the optimization problem expects {Nvars_expected}") b = b_packed.copy() mrcal.unpack_state(b, **optimization_inputs) if do_optimize_intrinsics_core or \ do_optimize_intrinsics_distortions: ivar0 = mrcal.state_index_intrinsics(0, **optimization_inputs) if ivar0 is not None: iunpacked0,iunpacked1 = None,None # everything by default lensmodel = optimization_inputs['lensmodel'] has_core = mrcal.lensmodel_metadata_and_config(lensmodel)['has_core'] Ncore = 4 if has_core else 0 Ndistortions = mrcal.lensmodel_num_params(lensmodel) - Ncore if not do_optimize_intrinsics_core: iunpacked0 = Ncore if not do_optimize_intrinsics_distortions: iunpacked1 = -Ndistortions intrinsics[:, iunpacked0:iunpacked1].ravel()[:] = \ b[ ivar0:Nvars_intrinsics ] if do_optimize_extrinsics: ivar0 = mrcal.state_index_extrinsics(0, **optimization_inputs) if ivar0 is not None: extrinsics.ravel()[:] = b[ivar0:ivar0+Nvars_extrinsics] if do_optimize_frames: ivar0 = mrcal.state_index_frames(0, **optimization_inputs) if ivar0 is not None: frames.ravel()[:] = b[ivar0:ivar0+Nvars_frames] if do_optimize_frames: ivar0 = mrcal.state_index_points(0, **optimization_inputs) if ivar0 is not None: points.ravel()[:-Npoints_fixed*3] = b[ivar0:ivar0+Nvars_points] if do_optimize_calobject_warp: ivar0 = mrcal.state_index_calobject_warp(**optimization_inputs) if ivar0 is not None: calobject_warp.ravel()[:] = b[ivar0:ivar0+Nvars_calobject_warp] def sorted_eig(M): r'''Compute eigenvalues, eigenvectors; sorted results returned SYNOPSIS # p is an array of shape (N,3): a point cloud. I find a normal to a fitted # plane p -= np.mean(p, axis=-2) l,v = mrcal.sorted_eig(nps.matmult(nps.transpose(p),p)) n = v[:,0] # n is the eigenvector corresponding to the smallest eigenvalue This function calls numpy.linalg.eig(), and sorts the output by eigenvalue, in ascending order ARGUMENTS - M: the matrix to eigendecompose RETURNED VALUE Same as that of numpy.linalg.eig(). A tuple: - Eigenvalues, sorted in ascending order - Eigenvectors, sorted by the corresponding eigenvalue. Each eigenvector is stored in a COLUMN of this array ''' l,v = np.linalg.eig(M) i = np.argsort(l) return l[i], v[:,i] def _plot_arg_covariance_ellipse(q_mean, Var, what): # if the variance is 0, the ellipse is infinitely small, and I don't even # try to plot it. Gnuplot has the arguably-buggy behavior where drawing an # ellipse with major_diam = minor_diam = 0 plots a nominally-sized ellipse. if np.max(np.abs(Var)) == 0: return None l,v = _sorted_eig(Var) l0,l1 = l v0,v1 = nps.transpose(v) major = np.sqrt(l0) minor = np.sqrt(l1) return \ (q_mean[0], q_mean[1], 2*major, 2*minor, 180./np.pi*np.arctan2(v0[1],v0[0]), dict(_with='ellipses', tuplesize=5, legend=what)) def _plot_args_points_and_covariance_ellipse(q, what): q_mean = np.mean(q,axis=-2) q_mean0 = q - q_mean Var = np.mean( nps.outer(q_mean0,q_mean0), axis=0 ) # Some functions assume that we're plotting _with = "dots". Look for the # callers if changing this return ( _plot_arg_covariance_ellipse(q_mean,Var, what), ( q, dict(_with = 'dots', tuplesize = -2)) ) def residuals_board(optimization_inputs, *, icam_intrinsics = None, residuals = None, return_observations = False, # for backwards-compatibility only; same as # icam_intrinsics i_cam = None): r'''Compute and return the chessboard residuals SYNOPSIS model = mrcal.cameramodel(model_filename) gp.plot( mrcal.residuals_board( optimization_inputs = model.optimization_inputs(), icam_intrinsics = icam_intrinsics ).ravel(), histogram = True, binwidth = 0.02 ) ... A plot pops up showing the empirical distribution of chessboard fit ... errors in this solve. For the given camera only Given a calibration solve, returns the residuals of chessboard observations, throwing out outliers and, optionally, selecting the residuals from a specific camera. These are the weighted reprojection errors present in the measurement vector. ARGUMENTS - optimization_inputs: the optimization inputs dict passed into and returned from mrcal.optimize(). This describes the solved optimization problem that we're visualizing - icam_intrinsics: optional integer to select the camera whose residuals we're visualizing If omitted or None, we report the residuals for ALL the cameras together. - residuals: optional numpy array of shape (Nmeasurements,) containing the optimization residuals. If omitted or None, this will be recomputed. To use a cached value, pass the result of mrcal.optimize(**optimization_inputs)['x'] or mrcal.optimizer_callback(**optimization_inputs)[1] - return_observations: optional boolean, defaulting to False. if return_observations: we return a tuple (residuals,observations) instead of just residuals If no chessboards are present in the solve I return arrays of appropriate shape with N = 0 RETURNED VALUES if not return_observations: we return a numpy array of shape (N,2) of all the residuals. N is the number of pixel observations remaining after outliers and other cameras are thrown out else: we return a tuple: - The same residuals array as before - The corresponding observation points in a numpy array of shape (N,2). These are a slice of observations_board[] corresponding to each residual ''' # shape (Nobservations, object_height_n, object_width_n, 3) observations_board = optimization_inputs.get('observations_board') if observations_board is None or observations_board.size == 0: # no board observations if not return_observations: # shape (N,2) return \ np.zeros((0,2), dtype=float) else: # shape (N,2), (N,2) return \ np.zeros((0,2), dtype=float), \ np.zeros((0,2), dtype=float) # for backwards compatibility if i_cam is not None: icam_intrinsics = i_cam if residuals is None: # Flattened residuals. This is ALL the measurements: chessboard, point, # regularization... residuals = \ mrcal.optimizer_callback(**optimization_inputs, no_jacobian = True, no_factorization = True)[1] residuals_shape = observations_board.shape[:-1] + (2,) # shape (Nobservations, object_height_n, object_width_n, 2) imeas0 = mrcal.measurement_index_boards(0, **optimization_inputs) Nmeas = mrcal.num_measurements_boards(**optimization_inputs) residuals_board = residuals[imeas0:imeas0+Nmeas].reshape(*residuals_shape) # shape (Nobservations, object_height_n, object_width_n, 3) indices_frame_camera = optimization_inputs['indices_frame_camintrinsics_camextrinsics'][...,:2] # shape (Nobservations, object_height_n, object_width_n) idx = np.ones( observations_board.shape[:-1], dtype=bool) if icam_intrinsics is not None: # select residuals from THIS camera idx[indices_frame_camera[:,1] != icam_intrinsics, ...] = False # select non-outliers idx[ observations_board[...,2] <= 0.0 ] = False if not return_observations: # shape (N,2) return \ residuals_board [idx, ... ] else: # shape (N,2), (N,2) return \ residuals_board [idx, ... ], \ observations_board[idx, ..., :2] # For backwards compatibility residuals_chessboard = residuals_board def residuals_point(optimization_inputs, *, icam_intrinsics = None, residuals = None, return_observations = False): r'''Compute and return the point observation residuals SYNOPSIS model = mrcal.cameramodel(model_filename) gp.plot( mrcal.residuals_point( optimization_inputs = model.optimization_inputs(), icam_intrinsics = icam_intrinsics ).ravel(), histogram = True, binwidth = 0.02 ) ... A plot pops up showing the empirical distribution of point fit ... errors in this solve. For the given camera only Given a calibration solve, returns the residuals of point observations, throwing out outliers and, optionally, selecting the residuals from a specific camera. These are the weighted reprojection errors present in the measurement vector. If no points are present in the solve I return arrays of appropriate shape with N = 0 ARGUMENTS - optimization_inputs: the optimization inputs dict passed into and returned from mrcal.optimize(). This describes the solved optimization problem that we're visualizing - icam_intrinsics: optional integer to select the camera whose residuals we're visualizing If omitted or None, we report the residuals for ALL the cameras together. - residuals: optional numpy array of shape (Nmeasurements,) containing the optimization residuals. If omitted or None, this will be recomputed. To use a cached value, pass the result of mrcal.optimize(**optimization_inputs)['x'] or mrcal.optimizer_callback(**optimization_inputs)[1] - return_observations: optional boolean, defaulting to False. if return_observations: we return a tuple (residuals,observations) instead of just residuals RETURNED VALUES if not return_observations: we return a numpy array of shape (N,2) of all the residuals. N is the number of pixel observations remaining after outliers and other cameras are thrown out else: we return a tuple: - The same residuals array as before - The corresponding observation points in a numpy array of shape (N,2). These are a slice of observations_point[] corresponding to each residual ''' # shape (Nobservations, 3) observations_point = optimization_inputs.get('observations_point') if observations_point is None or observations_point.size == 0: # no point observations if not return_observations: # shape (N,2) return \ np.zeros((0,2), dtype=float) else: # shape (N,2), (N,2) return \ np.zeros((0,2), dtype=float), \ np.zeros((0,2), dtype=float) if residuals is None: # Flattened residuals. This is ALL the measurements: chessboard, point, # regularization... residuals = \ mrcal.optimizer_callback(**optimization_inputs, no_jacobian = True, no_factorization = True)[1] Nobservations = len(observations_point) imeas0 = mrcal.measurement_index_points(0, **optimization_inputs) Nmeas = mrcal.num_measurements_points(**optimization_inputs) # shape (Nobservations, 2) # # Each observation row is (err_x, err_y, range_penalty). I ignore the # range_penalty here residuals_point = residuals[imeas0:imeas0+Nmeas].reshape(Nobservations,3)[:,:2] indices_point_camera = optimization_inputs['indices_point_camintrinsics_camextrinsics'][...,:2] # shape (Nobservations,) idx = np.ones( (Nobservations,), dtype=bool) if icam_intrinsics is not None: # select residuals from THIS camera idx[indices_point_camera[:,1] != icam_intrinsics, ...] = False # select non-outliers idx[ observations_point[...,2] <= 0.0 ] = False if not return_observations: # shape (N,2) return \ residuals_point [idx, ... ] else: # shape (N,2), (N,2) return \ residuals_point [idx, ... ], \ observations_point[idx, ..., :2] def R_aligned_to_vector(v): r'''Compute a rotation to map a given vector to [0,0,1] SYNOPSIS # I have a plane that passes through a point p, and has a normal n. I # compute a transformation from the world to a coord system aligned to the # plane, with p at the origin. R_plane_world p + t_plane_world = 0: Rt_plane_world = np.zeros((4,3), dtype=float) Rt_plane_world[:3,:] = mrcal.R_aligned_to_vector(n) Rt_plane_world[ 3,:] = -mrcal.rotate_point_R(Rt_plane_world[:3,:],p) This rotation is not unique: adding any rotation around v still maps v to [0,0,1]. An arbitrary acceptable rotation is returned. ARGUMENTS - v: a numpy array of shape (3,). The vector that the computed rotation maps to [0,0,1]. Does not need to be normalized. Must be non-0 RETURNED VALUES The rotation in a (3,3) array ''' z = v/nps.mag(v) if np.abs(z[0]) < .9: x = np.array((1,0,0.)) else: x = np.array((0,1,0.)) x -= nps.inner(x,z)*z x /= nps.mag(x) y = np.cross(z,x) return nps.cat(x,y,z) def write_point_cloud_as_ply(filename, points, *, color = None, binary = True): r'''Write a point cloud to a .ply file SYNOPSIS print( points.shape ) ===> (1000, 3) write_point_cloud_as_ply( "points.ply", points ) The point cloud to visualize may contain colors for each point: either as a BGR triplet or as a single intensity value. The colors may be given either in the trailing columns of the "points" array or in a separate "color" array. Both binary and ascii .ply formats are supported, with the binary format the default. ARGUMENTS - filename: the filename of the .ply file being written - points: the numpy array of points being visualized. Required. One of 3 shapes is allowed: - shape (N,3) if no color information is given here; may be given in the separate "color" array - shape (N,4) if a grayscale intensity is given in the last column - shape (N,6) if a BGR color is given in the last 3 columns If color is given here, the separate "color" array must be None - color: the numpy array of colors corresponding to each point in "points". Optional. If the colors are given here, they must NOT be given in "points": points.shape MUST be (N,3). If not None, 2 shapes are allowed: - shape (N,) if we have a grayscale intensity - shape (N,3) if we have BGR colors - binary: optional boolean, defaulting to True. Selects the binary or ascii .ply format. RETURNED VALUE None ''' if points.ndim != 2: raise Exception(f"points.shape must be (N,3) or (N,4) or (N,6), but points.ndim={points.ndim}") N,Ntrailing = points.shape if not (Ntrailing == 3 or \ Ntrailing == 4 or \ Ntrailing == 6): raise Exception(f"points.shape[-1] must be one of (3,4,6) to indicate no-color or grayscale or bgr colors respectively. Instead got points.shape[-1] = {points.shape[-1]}") if color is not None: if Ntrailing != 3: raise Exception("Both 'points' and 'color' are specifying color information. At most one of those should provide it") if color.ndim > 2: raise Exception(f"color.shape must be (N,) or (N,3), but color.ndim={color.ndim}") if N != color.shape[0]: raise Exception(f"Inconsistent point counts: len(points)={len(points)} but len(color)={len(color)}") if not (color.shape == (N,) or \ color.shape == (N,3) ): raise Exception(f"color.shape must be (N,) or (N,3), but color.shape={color.shape}") else: # No "color" specified if Ntrailing == 4: # But it exists as grayscale in the points. Separate it into the # "color" array color = points[:,3] points = points[:,:3] elif Ntrailing == 6: # But it exists as bgr in the points. Separate it into the # "color" array color = points[:,3:] points = points[:,:3] # I now have points.shape = (N,3) and color is None or (N,) or (N,3) if binary: ply_type = 'binary_little_endian' else: ply_type = 'ascii' if color is not None and color.ndim == 1: # grayscale dtype = np.dtype([ ('xyz',np.float32,3), ('i', np.uint8) ]) header_color = '''property uchar intensity ''' elif color is not None and color.ndim == 2: # bgr dtype = np.dtype([ ('xyz',np.float32,3), ('rgb', np.uint8, 3) ]) header_color = '''property uchar red property uchar green property uchar blue ''' else: dtype = np.dtype([ ('xyz',np.float32,3), ]) header_color = '' ply_header = f'''ply format {ply_type} 1.0 element vertex {N} property float x property float y property float z {header_color}end_header '''.encode() with open(filename, 'wb') as f: f.write(ply_header) if binary: binary_ply = np.empty( (N,), dtype = dtype) binary_ply['xyz'] = points.astype(np.float32) if color is not None and color.ndim == 1: # grayscale binary_ply['i' ] = color .astype(np.uint8) elif color is not None and color.ndim == 2: # bgr binary_ply['rgb'][:,0] = color[:,2] binary_ply['rgb'][:,1] = color[:,1] binary_ply['rgb'][:,2] = color[:,0] binary_ply.tofile(f) else: if color is not None and color.ndim == 1: # grayscale pbgr = nps.glue(points, nps.dummy(color, -1), axis = -1) np.savetxt(f, pbgr, fmt = ('%.1f','%.1f','%.1f','%d'), comments = '', header = '') elif color is not None and color.ndim == 2: # bgr pbgr = nps.glue(points, color[:,(2,)], color[:,(1,)], color[:,(0,)], 255*np.ones((N,1)), axis = -1) np.savetxt(f, pbgr, fmt = ('%.1f','%.1f','%.1f','%d','%d','%d','%d'), comments = '', header = '') else: np.savetxt(f, points, fmt = ('%.1f','%.1f','%.1f',), comments = '', header = '') mrcal-2.4.1/mrcal/visualization.py000066400000000000000000004651471456301662300172140ustar00rootroot00000000000000#!/usr/bin/python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 '''Visualization routines All functions are exported into the mrcal module. So you can call these via mrcal.visualization.fff() or mrcal.fff(). The latter is preferred. ''' import numpy as np import numpysane as nps import sys import re import os import mrcal def show_geometry(models_or_extrinsics_rt_fromref, *, cameranames = None, cameras_Rt_plot_ref = None, frames_rt_toref = None, points = None, show_calobjects = 'all', show_points = 'all', axis_scale = None, object_width_n = None, object_height_n = None, object_spacing = None, calobject_warp = None, point_labels = None, extratitle = None, return_plot_args = False, **kwargs): r'''Visualize the world resulting from a calibration run SYNOPSIS # Visualize the geometry from some models on disk models = [mrcal.cameramodel(m) for m in model_filenames] plot1 = mrcal.show_geometry(models) # Solve a calibration problem. Visualize the resulting geometry AND the # observed calibration objects and points ... mrcal.optimize(intrinsics = intrinsics, extrinsics_rt_fromref = extrinsics_rt_fromref, frames_rt_toref = frames_rt_toref, points = points, ...) plot2 = \ mrcal.show_geometry(extrinsics_rt_fromref, frames_rt_toref = frames_rt_toref, points = points, xlabel = 'Northing (m)', ylabel = 'Easting (m)', zlabel = 'Down (m)') This function visualizes the world described by a set of camera models. It shows - The geometry of the cameras themselves. Each one is represented by the axes of its coordinate system - The geometry of the observed objects used to compute these models (calibration boards and/or points). The geometry is shown only if requested and available - Requested: we show the calibration boards if show_calobjects, and the points if show_points. If the data comes from model.optimization_inputs(), then we can have a bit more control. if show_calobjects == 'all': we show ALL the calibration objects, observed by ANY camera. elif show_calobjects == 'thiscamera': we only show the calibration objects that were observed by the given camera at calibration time. Similarly with show_points. - Available: The data comes either from the frames_rt_toref and/or points arguments or from the first model.optimization_inputs() that is given. If we have both, we use the frames_rt_toref/points This function can also be used to visualize the output (or input) of mrcal.optimize(); the relevant parameters are all identical to those mrcal.optimize() takes. This function is the core of the mrcal-show-geometry tool. All arguments except models_or_extrinsics_rt_fromref are optional. Extra **kwargs are passed directly to gnuplotlib to control the plot. ARGUMENTS - models_or_extrinsics_rt_fromref: an iterable of mrcal.cameramodel objects or (6,) rt arrays. A array of shape (N,6) works to represent N cameras. If mrcal.cameramodel objects are given here and frames_rt_toref (or points) are omitted, we get the frames_rt_toref (or points) from the first model that provides optimization_inputs(). - cameranames: optional array of strings of labels for the cameras. If omitted, we use generic labels. If given, the array must have the same length as models_or_extrinsics_rt_fromref - cameras_Rt_plot_ref: optional transformation(s). If omitted or None, we plot everything in the reference coordinate system. If given, we use a "plot" coordinate system with the transformation TO plot coordinates FROM the reference coordinates given in this argument. This argument can be given as single Rt transformation to apply to ALL the cameras, or an iterable of Rt transformations to use a different one for each camera (the number of transforms must match the number of cameras exactly) - frames_rt_toref: optional array of shape (N,6). If given, each row of shape (6,) is an rt transformation representing the transformation TO the reference coordinate system FROM the calibration object coordinate system. The calibration object then MUST be defined by passing in valid object_width_n, object_height_n, object_spacing parameters. If frames_rt_toref is omitted or None, we look for this data in the given camera models. I look at the given models in order, and grab the frames from the first model that has them. If none of the models have this data and frames_rt_toref is omitted or NULL, then I don't plot any frames at all - object_width_n: the number of horizontal points in the calibration object grid. Required only if frames_rt_toref is not None - object_height_n: the number of vertical points in the calibration object grid. Required only if frames_rt_toref is not None - object_spacing: the distance between adjacent points in the calibration object. A square object is assumed, so the vertical and horizontal distances are assumed to be identical. Required only if frames_rt_toref is not None - calobject_warp: optional (2,) array describing the calibration board warping. None means "no warping": the object is flat. Used only if frames_rt_toref is not None. See the docs for mrcal.ref_calibration_object() for a description. - points: optional array of shape (N,3). If omitted, we don't plot the observed points. If given, each row of shape (3,) is a point in the reference coordinate system. - point_labels: optional dict from a point index to a string describing it. Points in this dict are plotted with this legend; all other points are plotted under a generic "points" legend. As many or as few of the points may be labelled in this way. If omitted, none of the points will be labelled specially. This is used only if points is not None - show_calobjects: optional string defaults to 'all'. if show_calobjects: we render the observed calibration objects (if they are available in frames_rt_toref or model.optimization_inputs()['frames_rt_toref']; we look at the FIRST model that provides this data). If we have optimization_inputs and show_calobjects == 'all': we display the objects observed by ANY camera. elif show_calobjects == 'thiscamera': we only show those observed by THIS camera. - show_points: same as show_calobjects, but applying to discrete points, not chessboard poses - axis_scale: optional scale factor for the size of the axes used to represent the cameras. Can be omitted to use some reasonable default size, but tweaking it might be necessary to make the plot look right. If 1 or fewer cameras are given, this defaults to 1.0 - extratitle: optional string to include in the title of the resulting plot. Used to extend the default title string. If kwargs['title'] is given, it is used directly, and the extratitle is ignored - return_plot_args: boolean defaulting to False. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot - **kwargs: optional arguments passed verbatim as plot options to gnuplotlib. Useful to make hardcopies, set the plot title, etc. RETURNED VALUES if not return_plot_args (the usual path): we return the gnuplotlib plot object. The plot disappears when this object is destroyed (by the garbage collection, for instance), so save this returned plot object into a variable, even if you're not going to be doing anything with this object. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot ''' import gnuplotlib as gp # First one with optimization_inputs. If we're not given frames and/or # points, we get them from the optimization inputs in this model i_model_with_optimization_inputs = \ next((i for i in range(len(models_or_extrinsics_rt_fromref)) \ if isinstance(models_or_extrinsics_rt_fromref[i], mrcal.cameramodel) and \ models_or_extrinsics_rt_fromref[i].optimization_inputs() is not None), None) Ncameras = len(models_or_extrinsics_rt_fromref) if cameras_Rt_plot_ref is not None: # have cameras_Rt_plot_ref. It can be # - a list of transforms # - a single transform # If we're given frames_rt_toref or points, then a different transform # per camera doesn't make sense, and I barf if not isinstance(cameras_Rt_plot_ref, np.ndarray): # cameras_Rt_plot_ref must be an iterable with each slice being an # array of shape (4,3) try: cameras_Rt_plot_ref = np.array(cameras_Rt_plot_ref, dtype=float) except: raise Exception("cameras_Rt_plot_ref must be a transform or a list of transforms") # cameras_Rt_plot_ref is now an array. Does it have the right shape? if cameras_Rt_plot_ref.shape[-2:] != (4,3): raise Exception("cameras_Rt_plot_ref must be a transform or a list of Rt transforms. Got an array that looks like neither") # shape is (....,4,3) if cameras_Rt_plot_ref.ndim == 2: # shape is (4,3). I extend it to # shape (N,4,3) cameras_Rt_plot_ref = \ np.repeat(nps.atleast_dims(cameras_Rt_plot_ref,-3), Ncameras, axis=-3) elif cameras_Rt_plot_ref.ndim == 3: # shape is (N,4,3). if len(cameras_Rt_plot_ref) != Ncameras: raise Exception("cameras_Rt_plot_ref must be a transform or a list of transforms, exactly one per camera. Got mismatched number of transforms") # have an array of transforms with the right shape if frames_rt_toref is not None or points is not None: raise Exception("Got multiple transforms in cameras_Rt_plot_ref AND frames_rt_toref or points. This makes no sense: I can't tell which transform to use") pass else: raise Exception("cameras_Rt_plot_ref must be a transform or a list of transforms, exactly one per camera. Got mismatched number of transforms") # cameras_Rt_plot_ref is now either None or an array of shape (N,4,3) if frames_rt_toref is not None: if object_width_n is None or \ object_height_n is None or \ object_spacing is None: raise Exception("frames_rt_toref is given, so object_width_n and object_height_n and object_spacing must be given as well") def get_extrinsics_Rt_toref_one(m): if isinstance(m, mrcal.cameramodel): return m.extrinsics_Rt_toref() else: return mrcal.invert_Rt(mrcal.Rt_from_rt(m)) extrinsics_Rt_toref = \ nps.cat(*[get_extrinsics_Rt_toref_one(m) \ for m in models_or_extrinsics_rt_fromref]) # reshape extrinsics_Rt_toref to exactly (N,4,3) extrinsics_Rt_toref = nps.atleast_dims(extrinsics_Rt_toref, -3) extrinsics_Rt_toref = nps.clump( extrinsics_Rt_toref, n = extrinsics_Rt_toref.ndim-3 ) if axis_scale is None: # This is intended to work with the behavior in the mrcal-stereo # tool. That tool sets the fov-indicating hair lengths to # baseline/4. Here I default to a bit more: baseline/3 # I want this routine to work with any N cameras. I need to compute a # "characteristic distance" for them to serve as a "baseline". I do this # by first computing a "geometric median" that minimizes the mean # of the distances from each point to this median. Then the # characteristic radius is this constant-ish distance. # shape (N,3); the position of each camera in the ref coord system p = extrinsics_Rt_toref[:,3,:] if len(p) <= 1: axis_scale = 1.0 else: import scipy.optimize res = scipy.optimize.least_squares(# cost function lambda c: np.sum(nps.mag(p-c)), # seed np.mean(p,axis=-2), method='trf', verbose=False) center = res.x baseline = np.mean(nps.mag(p-center)) * 2. axis_scale = baseline/3. if axis_scale == 0.: # All the cameras are at exactly the same spot axis_scale = 1.0 def get_boards_to_plot(): r'''get the chessboard poses to plot''' if not show_calobjects: # Not requested return None if frames_rt_toref is not None: # We have explicit poses given. Use them return \ nps.atleast_dims(frames_rt_toref, -2), \ object_width_n, \ object_height_n, \ object_spacing, \ calobject_warp # Poses aren't given. Grab them from the model if not (show_calobjects is True or show_calobjects == 'all' or show_calobjects == 'thiscamera'): raise Exception("show_calobjects must be 'all' or 'thiscamera' or True or False") if i_model_with_optimization_inputs is None: return None m = models_or_extrinsics_rt_fromref[i_model_with_optimization_inputs] optimization_inputs = m.optimization_inputs() if not ('observations_board' in optimization_inputs and \ optimization_inputs['observations_board'] is not None and \ optimization_inputs['observations_board'].size ): return None; _frames_rt_toref = optimization_inputs['frames_rt_toref'] _object_spacing = optimization_inputs['calibration_object_spacing'] _object_width_n = optimization_inputs['observations_board'].shape[-2] _object_height_n = optimization_inputs['observations_board'].shape[-3] _calobject_warp = optimization_inputs['calobject_warp'] icam_intrinsics = m.icam_intrinsics() if show_calobjects == 'thiscamera': indices_frame_camintrinsics_camextrinsics = \ optimization_inputs['indices_frame_camintrinsics_camextrinsics'] mask_observations = \ indices_frame_camintrinsics_camextrinsics[:,1] == icam_intrinsics idx_frames = indices_frame_camintrinsics_camextrinsics[mask_observations,0] _frames_rt_toref = _frames_rt_toref[idx_frames] # The current frames_rt_toref uses the calibration-time ref, NOT # the current ref. I transform. frames_rt_toref = T_rcal_f # I want T_rnow_rcal T_rcal_f icam_extrinsics = \ mrcal.corresponding_icam_extrinsics(icam_intrinsics, **optimization_inputs) if icam_extrinsics >= 0: _frames_rt_toref = \ mrcal.compose_rt( mrcal.rt_from_Rt(extrinsics_Rt_toref[i_model_with_optimization_inputs]), optimization_inputs['extrinsics_rt_fromref'][icam_extrinsics], _frames_rt_toref ) else: _frames_rt_toref = \ mrcal.compose_rt( mrcal.rt_from_Rt(extrinsics_Rt_toref[i_model_with_optimization_inputs]), _frames_rt_toref ) # All good. Done return \ nps.atleast_dims(_frames_rt_toref, -2), \ _object_width_n, \ _object_height_n, \ _object_spacing, \ _calobject_warp def get_points_to_plot(): r'''get the discrete points to plot''' if not show_points: # Not requested return None if points is not None: # We have explicit points given. Use them return \ nps.atleast_dims(points, -2) # Points aren't given. Grab them from the model if not (show_points is True or show_points == 'all' or show_points == 'thiscamera'): raise Exception("show_points must be 'all' or 'thiscamera' or True or False") if i_model_with_optimization_inputs is None: return None m = models_or_extrinsics_rt_fromref[i_model_with_optimization_inputs] optimization_inputs = m.optimization_inputs() if not ('points' in optimization_inputs and \ optimization_inputs['points'] is not None and \ optimization_inputs['points'].size ): return None; _points = optimization_inputs['points'] icam_intrinsics = m.icam_intrinsics() if show_points == 'thiscamera': indices_point_camintrinsics_camextrinsics = \ optimization_inputs['indices_point_camintrinsics_camextrinsics'] mask_observations = \ indices_point_camintrinsics_camextrinsics[:,1] == icam_intrinsics idx_points = indices_point_camintrinsics_camextrinsics[mask_observations,0] _points = _points[idx_points] # The current points uses the calibration-time ref, NOT # the current ref. I transform. icam_extrinsics = \ mrcal.corresponding_icam_extrinsics(icam_intrinsics, **optimization_inputs) if icam_extrinsics >= 0: _points = \ mrcal.transform_point_rt( optimization_inputs['extrinsics_rt_fromref'][icam_extrinsics], _points ) _points = \ mrcal.transform_point_Rt( extrinsics_Rt_toref[i_model_with_optimization_inputs], _points ) else: _points = \ mrcal.transform_point_Rt( extrinsics_Rt_toref[i_model_with_optimization_inputs], _points ) # All good. Done return \ nps.atleast_dims(_points, -2) boards_to_plot_list = get_boards_to_plot() if boards_to_plot_list is not None: frames_rt_toref, \ object_width_n, \ object_height_n, \ object_spacing, \ calobject_warp = boards_to_plot_list else: frames_rt_toref = None # the others will not be referenced if frames_rt_toref is None points = get_points_to_plot() def extend_axes_for_plotting(axes): r'''Input is a 4x3 axes array: center, center+x, center+y, center+z. I transform this into a 3x6 array that can be gnuplotted "with vectors" ''' # first, copy the center 3 times out = nps.cat( axes[0,:], axes[0,:], axes[0,:] ) # then append just the deviations to each row containing the center out = nps.glue( out, axes[1:,:] - axes[0,:], axis=-1) return out def gen_plot_axes(transforms, legend, scale = 1.0): r'''Given a list of transforms (applied to the reference set of axes in reverse order) and a legend, return a list of plotting directives gnuplotlib understands. Each transform is an Rt (4,3) matrix Transforms are in reverse order so a point x being transformed as A*B*C*x can be represented as a transforms list (A,B,C). if legend is not None: plot ONLY the axis vectors. If legend is None: plot ONLY the axis labels ''' axes = np.array( ((0,0,0), (1,0,0), (0,1,0), (0,0,2),), dtype=float ) * scale transform = mrcal.identity_Rt() for x in transforms: transform = mrcal.compose_Rt(transform, x) if legend is not None: return \ (extend_axes_for_plotting(mrcal.transform_point_Rt(transform, axes)), dict(_with = 'vectors', tuplesize = -6, legend = legend), ) return tuple(nps.transpose(mrcal.transform_point_Rt(transform, axes[1:,:]*1.01))) + \ (np.array(('x', 'y', 'z')), dict(_with = 'labels', tuplesize = 4, legend = None),) # I need to plot 3 things: # # - Cameras # - Calibration object poses # - Observed points def gen_curves_cameras(): def camera_Rt_toplotcoords(i): Rt_ref_cam = extrinsics_Rt_toref[i] if cameras_Rt_plot_ref is None: return Rt_ref_cam return mrcal.compose_Rt(cameras_Rt_plot_ref[i], Rt_ref_cam) def camera_name(i): try: return cameranames[i] except: return f'cam{i}' cam_axes = \ [gen_plot_axes( ( camera_Rt_toplotcoords(i), ), legend = camera_name(i), scale=axis_scale) for i in range(0,Ncameras)] cam_axes_labels = \ [gen_plot_axes( ( camera_Rt_toplotcoords(i), ), legend = None, scale=axis_scale) for i in range(0,Ncameras)] # I collapse all the labels into one gnuplotlib dataset. Thus I'll be # able to turn them all on/off together return cam_axes + [(np.ravel(nps.cat(*[l[0] for l in cam_axes_labels])), np.ravel(nps.cat(*[l[1] for l in cam_axes_labels])), np.ravel(nps.cat(*[l[2] for l in cam_axes_labels])), np.tile(cam_axes_labels[0][3], Ncameras)) + \ cam_axes_labels[0][4:]] def gen_curves_calobjects(): if frames_rt_toref is None or len(frames_rt_toref) == 0: return [] if object_spacing <= 0 or \ object_width_n is None or \ object_height_n is None: raise Exception("We're observing calibration boards, so object_spacing and object_width_n and object_height_n must be valid") # if observations_board is None or \ # indices_frame_camera_board is None or \ # len(observations_board) == 0 or \ # len(indices_frame_camera_board) == 0: # return [] # Nobservations = len(indices_frame_camera_board) # if icam_highlight is not None: # i_observations_frames = [(i_observation,indices_frame_camera_board[i_observation,0]) \ # for i_observation in range(Nobservations) \ # if indices_frame_camera_board[i_observation,1] == icam_highlight] # i_observations, iframes = nps.transpose(np.array(i_observations_frames)) # frames_rt_toref = frames_rt_toref[iframes, ...] calobject_ref = mrcal.ref_calibration_object(object_width_n, object_height_n, object_spacing, calobject_warp = calobject_warp) # object in the ref coord system. # shape (Nframes, object_height_n, object_width_n, 3) calobject_ref = mrcal.transform_point_rt(nps.mv(frames_rt_toref, -2, -4), calobject_ref) if cameras_Rt_plot_ref is not None: # I checked earlier that if separate frames_rt_toref or points are # given, then only a single cameras_Rt_plot_ref may be given. # They're all the same, so I use 0 here arbitrarily calobject_ref = \ mrcal.transform_point_Rt(cameras_Rt_plot_ref[i_model_with_optimization_inputs if i_model_with_optimization_inputs is not None else 0], calobject_ref) # if icam_highlight is not None: # # shape=(Nobservations, object_height_n, object_width_n, 2) # calobject_cam = nps.transform_point_Rt( models[icam_highlight].extrinsics_Rt_fromref(), calobject_ref ) # print("double-check this. I don't broadcast over the intrinsics anymore") # err = observations[i_observations, ...] - mrcal.project(calobject_cam, *models[icam_highlight].intrinsics()) # err = nps.clump(err, n=-3) # rms = np.mag(err) / (object_height_n*object_width_n)) # # igood = rms < 0.4 # # ibad = rms >= 0.4 # # rms[igood] = 0 # # rms[ibad] = 1 # calobject_ref = nps.glue( calobject_ref, # nps.dummy( nps.mv(rms, -1, -3) * np.ones((object_height_n,object_width_n)), # -1 ), # axis = -1) # calobject_ref shape: (3, Nframes, object_height_n*object_width_n). # This will broadcast nicely calobject_ref = nps.clump( nps.mv(calobject_ref, -1, -4), n=-2) # if icam_highlight is not None: # calobject_curveopts = {'with':'lines palette', 'tuplesize': 4} # else: calobject_curveopts = {'with':'lines', 'tuplesize': 3} return [tuple(list(calobject_ref) + [calobject_curveopts,])] def gen_curves_points(points): if points is None or len(points) == 0: return [] if cameras_Rt_plot_ref is not None: # I checked earlier that if separate frames_rt_toref or points are # given, then only a single cameras_Rt_plot_ref may be given. # They're all the same, so I use 0 here arbitrarily points = \ mrcal.transform_point_Rt(cameras_Rt_plot_ref[i_model_with_optimization_inputs if i_model_with_optimization_inputs is not None else 0], points) if point_labels is not None: # all the non-fixed point indices ipoint_not_labeled = np.ones( (len(points),), dtype=bool) ipoint_not_labeled[np.array(list(point_labels.keys()))] = False return \ [ (points[ipoint_not_labeled], dict(tuplesize = -3, _with = 'points', legend = 'points')) ] + \ [ (points[ipoint], dict(tuplesize = -3, _with = 'points', legend = point_labels[ipoint])) \ for ipoint in point_labels.keys() ] else: return [ (points, dict(tuplesize = -3, _with = 'points', legend = 'points')) ] curves_cameras = gen_curves_cameras() curves_calobjects = gen_curves_calobjects() curves_points = gen_curves_points(points) kwargs = dict(kwargs) gp.add_plot_option(kwargs, xlabel = 'x', ylabel = 'y', zlabel = 'z', overwrite = False) plot_options = \ dict(_3d=1, square=1, **kwargs) if 'title' not in plot_options: title = 'Camera geometry' if extratitle is not None: title += ": " + extratitle plot_options['title'] = title data_tuples = curves_points + curves_cameras + curves_calobjects if not return_plot_args: plot = gp.gnuplotlib(**plot_options) plot.plot(*data_tuples) return plot return (data_tuples, plot_options) def _options_heatmap_with_contours( plotoptions, # we update this on output *, contour_min = 0, contour_max, contour_increment = None, imagersize, gridn_width, gridn_height, do_contours = True, contour_labels_styles = 'boxed', contour_labels_font = None): r'''Update plotoptions, return curveoptions for a contoured heat map''' import gnuplotlib as gp gp.add_plot_option(plotoptions, 'set', ('view equal xy', 'view map')) if do_contours: if contour_increment is None: # Compute a "nice" contour increment. I pick a round number that gives # me a reasonable number of contours Nwant = 10 increment = (contour_max - contour_min)/Nwant # I find the nearest 1eX or 2eX or 5eX base10_floor = np.power(10., np.floor(np.log10(increment))) # Look through the options, and pick the best one m = np.array((1., 2., 5., 10.)) err = np.abs(m * base10_floor - increment) contour_increment = -m[ np.argmin(err) ] * base10_floor gp.add_plot_option(plotoptions, 'set', ('key box opaque', 'style textbox opaque', 'contour base', f'cntrparam levels incremental {contour_max},{contour_increment},{contour_min}')) if contour_labels_font is not None: gp.add_plot_option(plotoptions, 'set', f'cntrlabel font "{contour_labels_font}"' ) plotoptions['cbrange'] = [contour_min, contour_max] # I plot 3 times: # - to make the heat map # - to make the contours # - to make the contour labels _with = np.array(('image', 'lines nosurface', f'labels {contour_labels_styles} nosurface')) else: gp.add_plot_option(plotoptions, 'unset', 'key') _with = 'image' plotoptions['_3d'] = True plotoptions['_xrange'] = [0, imagersize[0]] plotoptions['_yrange'] = [imagersize[1], 0] plotoptions['ascii'] = True # needed for imagergrid_using to work gp.add_plot_option(plotoptions, 'unset', 'grid') return \ dict( tuplesize=3, legend = "", # needed to force contour labels using = imagergrid_using(imagersize, gridn_width, gridn_height), _with=_with) def fitted_gaussian_equation(*, binwidth, x = None, mean = None, sigma = None, N = None, legend = None): r'''Get an 'equation' gnuplotlib expression for a gaussian curve fitting some data SYNOPSIS import gnuplotlib as gp import numpy as np ... # x is a one-dimensional array with samples that we want to compare to a # normal distribution. For instance: # x = np.random.randn(10000) * 0.1 + 10 binwidth = 0.01 equation = \ mrcal.fitted_gaussian_equation(x = x, binwidth = binwidth) gp.plot(x, histogram = True, binwidth = binwidth, equation_above = equation) # A plot pops ups displaying a histogram of the array x overlaid by an ideal # gaussian probability density function. This PDF corresponds to the mean # and standard deviation of the data, and takes into account the histogram # parameters to overlay nicely on top of it Overlaying a ideal PDF on top of an empirical histogram requires a bit of math to figure out the proper vertical scaling of the plotted PDF that would line up with the histogram. This is evaluated by this function. This function can be called in one of two ways: - Passing the data in the 'x' argument. The statistics are computed from the data, and there's no reason to pass 'mean', 'sigma', 'N' - Passing the statistics 'mean', 'sigma', 'N' instead of the data 'x'. This is useful to compare an empirical histogram with idealized distributions that are expected to match the data, but do not. For instance, we may want to plot the expected standard deviation that differs from the observed standard deviation ARGUMENTS - binwidth: the width of each bin in the histogram we will plot. This is the only required argument - x: one-dimensional numpy array containing the data that will be used to construct the histogram. If given, (mean, sigma, N) must all NOT be given: they will be computed from x. If omitted, then all those must be given instead - mean: mean the gaussian to plot. Must be given if and only if x is not given - sigma: standard deviation of the gaussian to plot. Must be given if and only if x is not given - N: the number of values in the dataset in the histogram. Must be given if and only if x is not given - legend: string containing the legend of the curve in the plot. May be omitted or None to leave the curve unlabelled RETURNED VALUES String passable to gnuplotlib in the 'equation' or 'equation_above' plot option ''' # I want to plot a PDF of a normal distribution together with the # histogram to get a visual comparison. This requires a scaling on # either the PDF or the histogram. I plot a scaled pdf: # # f = k*pdf = k * exp(-x^2 / (2 s^2)) / sqrt(2*pi*s^2) # # I match up the size of the central bin of the histogram (-binwidth/2, # binwidth/2): # # bin(0) ~ k*pdf(0) ~ pdf(0) * N * binwidth # # So k = N*binwdith should work. I can do this more precisely: # # bin(0) ~ k*pdf(0) ~ # = N * integral( pdf(x) dx, -binwidth/2, binwidth/2) # = N * integral( exp(-x^2 / (2 s^2)) / sqrt( 2*pi*s^2) dx, -binwidth/2, binwidth/2) # ->k = N * integral( exp(-x^2 / (2 s^2)) / sqrt( 2*pi*s^2) dx, -binwidth/2, binwidth/2) / pdf(0) # = N * integral( exp(-x^2 / (2 s^2)) dx, -binwidth/2, binwidth/2) # = N * integral( exp(-(x/(sqrt(2) s))^2) dx ) # # Let u = x/(sqrt(2) s) # du = dx/(sqrt(2) s) # u(x = binwidth/2) = binwidth/(s 2sqrt(2)) -> # # k = N * sqrt(2) s * integral( exp(-u^2) du ) # = N*sqrt(2pi) s * erf(binwidth / (s 2*sqrt(2))) # # for low x erf(x) ~ 2x/sqrt(pi). So if binwidth << sigma # k = N*sqrt(2pi) s * erf(binwidth / (s 2*sqrt(2))) # ~ N*sqrt(2pi) s * (binwidth/(s 2*sqrt(2))) *2 / sqrt(pi) # ~ N binwidth from scipy.special import erf if x is not None: if mean is not None or sigma is not None or N is not None: raise Exception("x was given. So none of (mean,sigma,N) should have been given") sigma = np.std(x) mean = np.mean(x) N = len(x) else: if mean is None or sigma is None or N is None: raise Exception("x was not given. So all of (mean,sigma,N) should have been given") var = sigma*sigma k = N * np.sqrt(2.*np.pi) * sigma * erf(binwidth/(2.*np.sqrt(2)*sigma)) if legend is None: title = 'notitle' else: title = f'title "{legend}"' return \ f'{k}*exp(-(x-{mean})*(x-{mean})/(2.*{var})) / sqrt(2.*pi*{var}) {title} with lines lw 2' def _append_observation_visualizations(plot_data_args, model, legend_prefix, pointtype, _2d, # for splined models reproject_to_stereographic = False): optimization_inputs = model.optimization_inputs() if optimization_inputs is None: raise Exception("mrcal.show_...(observations=True) requires optimization_inputs to be available") q_cam_boards_inliers = None q_cam_boards_outliers = None observations_board = optimization_inputs.get('observations_board') if observations_board is not None: mask_observation = \ optimization_inputs['indices_frame_camintrinsics_camextrinsics'][:,1] == \ model.icam_intrinsics() observations_board = observations_board[mask_observation] # shape (N,3) observations_board = nps.clump(observations_board, n=3) mask_inliers = observations_board[...,2] > 0 q_cam_boards_inliers = observations_board[ mask_inliers,:2] q_cam_boards_outliers = observations_board[~mask_inliers,:2] q_cam_points_inliers = None q_cam_points_outliers = None observations_point = optimization_inputs.get('observations_point') if observations_point is not None: mask_observation = \ optimization_inputs['indices_point_camintrinsics_camextrinsics'][:,1] == \ model.icam_intrinsics() # shape (N,3) observations_point = observations_point[mask_observation] mask_inliers = observations_point[...,2] > 0 q_cam_points_inliers = observations_point[ mask_inliers,:2] q_cam_points_outliers = observations_point[~mask_inliers,:2] # Disabled for now. I see a legend entry for each broadcasted slice, # which isn't what I want # # if len(q_cam_calobjects): # plot_data_args.append( ( nps.clump(q_cam_calobjects[...,0], n=-2), # nps.clump(q_cam_calobjects[...,1], n=-2) ) + # ( () if _2d else # (np.zeros((q_cam_calobjects.shape[-2]* # q_cam_calobjects.shape[-3],)),)) + # ( dict( tuplesize = 2 if _2d else 3, # _with = f'lines lc "black"' + ("" if _2d else ' nocontour'), # legend = f"{legend_prefix} board sequences"),)) for q,color,what in ( (q_cam_boards_inliers, "black", "board inliers"), (q_cam_points_inliers, "black", "point inliers"), (q_cam_boards_outliers, "red", "board outliers"), (q_cam_points_outliers, "red", "point outliers"), ): if q is not None and len(q) > 0: if reproject_to_stereographic: q = mrcal.project_stereographic( \ mrcal.unproject(q, *model.intrinsics())) if pointtype < 0: _with = f'dots lc "{color}"' else: _with = f'points lc "{color}" pt {pointtype}' if not _2d: _with += ' nocontour' plot_data_args.append( ( q[...,0], q[...,1] ) + ( () if _2d else ( np.zeros(q.shape[:-1]), )) + ( dict( tuplesize = 2 if _2d else 3, _with = _with, legend = f'{legend_prefix}{what}'), )) def show_projection_diff(models, *, implied_Rt10 = None, gridn_width = 60, gridn_height = None, observations = False, valid_intrinsics_region = False, intrinsics_only = False, distance = None, use_uncertainties= True, focus_center = None, focus_radius = -1., vectorfield = False, vectorscale = 1.0, directions = False, cbmax = 4, contour_increment = None, contour_labels_styles = 'boxed', contour_labels_font = None, extratitle = None, return_plot_args = False, **kwargs): r'''Visualize the difference in projection between N models SYNOPSIS models = ( mrcal.cameramodel('cam0-dance0.cameramodel'), mrcal.cameramodel('cam0-dance1.cameramodel') ) mrcal.show_projection_diff(models) # A plot pops up displaying the projection difference between the two models The operation of this tool is documented at http://mrcal.secretsauce.net/differencing.html This function visualizes the results of mrcal.projection_diff() It is often useful to compare the projection behavior of two camera models. For instance, one may want to validate a calibration by comparing the results of two different chessboard dances. Or one may want to evaluate the stability of the intrinsics in response to mechanical or thermal stresses. In the most common case we're given exactly 2 models to compare. We then display the projection difference as either a vector field or a heat map. If we're given more than 2 models, then a vector field isn't possible and we instead display as a heatmap the standard deviation of the differences between models 1..N and model0. The top-level operation of this function: - Grid the imager - Unproject each point in the grid using one camera model - Apply a transformation to map this point from one camera's coord system to the other. How we obtain this transformation is described below - Project the transformed points to the other camera - Look at the resulting pixel difference in the reprojection If implied_Rt10 is given, we simply use that as the transformation (this is currently supported ONLY for diffing exactly 2 cameras). If implied_Rt10 is not given, we estimate it. Several variables control this. Top-level logic: if intrinsics_only: Rt10 = identity_Rt() else: if focus_radius == 0: Rt10 = relative_extrinsics(models) else: Rt10 = implied_Rt10__from_unprojections() The details of how the comparison is computed, and the meaning of the arguments controlling this, are in the docstring of mrcal.projection_diff(). ARGUMENTS - models: iterable of mrcal.cameramodel objects we're comparing. Usually there will be 2 of these, but more than 2 is possible. The intrinsics are used; the extrinsics are NOT. - implied_Rt10: optional transformation to use to line up the camera coordinate systems. Most of the time we want to estimate this transformation, so this should be omitted or None. Currently this is supported only if exactly two models are being compared. - gridn_width: optional value, defaulting to 60. How many points along the horizontal gridding dimension - gridn_height: how many points along the vertical gridding dimension. If None, we compute an integer gridn_height to maintain a square-ish grid: gridn_height/gridn_width ~ imager_height/imager_width - observations: optional value, defaulting to False. If observations: we overlay calibration-time observations on top of the difference plot. We should then see that more data produces more consistent results. If a special value of 'dots' is passed, the observations are plotted as dots instead of points - valid_intrinsics_region: optional boolean, defaulting to False. If True, we overlay the valid-intrinsics regions onto the plot. If the valid-intrinsics regions aren't available, we will silently omit them - intrinsics_only: optional boolean, defaulting to False. If True: we evaluate the intrinsics of each lens in isolation by assuming that the coordinate systems of each camera line up exactly - distance: optional value, defaulting to None. Has an effect only if not intrinsics_only. The projection difference varies depending on the range to the observed world points, with the queried range set in this 'distance' argument. If None (the default) we look out to infinity. We can compute the implied-by-the-intrinsics transformation off multiple distances if they're given here as an iterable. This is especially useful if we have uncertainties, since then we'll emphasize the best-fitting distances. If multiple distances are given, the generated plot displays the difference using the FIRST distance in the list - use_uncertainties: optional boolean, defaulting to True. Used only if not intrinsics_only and focus_radius!=0. If True we use the whole imager to fit the implied-by-the-intrinsics transformation, using the uncertainties to emphasize the confident regions. If False, it is important to select the confident region using the focus_center and focus_radius arguments. If use_uncertainties is True, but that data isn't available, we report a warning, and try to proceed without. - focus_center: optional array of shape (2,); the imager center by default. Used only if not intrinsics_only and focus_radius!=0. Used to indicate that the implied-by-the-intrinsics transformation should use only those pixels a distance focus_radius from focus_center. This is intended to be used if no uncertainties are available, and we need to manually select the focus region. - focus_radius: optional value. If use_uncertainties then the default is LARGE, to use the whole imager. Else the default is min(width,height)/6. Used to indicate that the implied-by-the-intrinsics transformation should use only those pixels a distance focus_radius from focus_center. This is intended to be used if no uncertainties are available, and we need to manually select the focus region. To avoid computing the transformation, either pass focus_radius=0 (to use the extrinsics in the given models) or pass intrinsics_only=True (to use the identity transform). - vectorfield: optional boolean, defaulting to False. By default we produce a heat map of the projection differences. If vectorfield: we produce a vector field instead. This is more busy, and is often less clear at first glance, but unlike a heat map, this shows the directions of the differences in addition to the magnitude. This is only valid if we're given exactly two models to compare - vectorscale: optional value, defaulting to 1.0. Applicable only if vectorfield. The magnitude of the errors displayed in the vector field is often very small, and impossible to make out when looking at the whole imager. This argument can be used to scale all the displayed vectors to improve legibility. - directions: optional boolean, defaulting to False. By default the plot is color-coded by the magnitude of the difference vectors. If directions: we color-code by the direction instead. This is especially useful if we're plotting a vector field. This is only valid if we're given exactly two models to compare - cbmax: optional value, defaulting to 4.0. Sets the maximum range of the color map - contour_increment: optional value, defaulting to None. If given, this will be used as the distance between adjacent contours. If omitted of None, a reasonable value will be estimated - contour_labels_styles: optional string, defaulting to 'boxed'. The style of the contour labels. This will be passed to gnuplot as f"with labels {contour_labels_styles} nosurface". Can be used to box/unbox the label, set the color, etc. To change the font use contour_labels_font. - contour_labels_font: optional string, defaulting to None, If given, this is the font string for the contour labels. Will be passed to gnuplot as f'set cntrlabel font "{contour_labels_font}"' - extratitle: optional string to include in the title of the resulting plot. Used to extend the default title string. If kwargs['title'] is given, it is used directly, and the extratitle is ignored - return_plot_args: boolean defaulting to False. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot - **kwargs: optional arguments passed verbatim as plot options to gnuplotlib. Useful to make hardcopies, etc RETURNED VALUE A tuple: - if not return_plot_args (the usual path): the gnuplotlib plot object. The plot disappears when this object is destroyed (by the garbage collection, for instance), so save this returned plot object into a variable, even if you're not going to be doing anything with this object. if return_plot_args: a (data_tuples, plot_options) tuple. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot - Rt10: the geometric Rt transformation in an array of shape (...,4,3). This is the relative transformation we ended up using, which is computed using the logic above (using intrinsics_only and focus_radius). if len(models)>2: this is an array of shape (len(models)-1,4,3), with slice i representing the transformation between camera 0 and camera i+1. ''' if len(models) < 2: raise Exception("At least 2 models are required to compute the diff") import gnuplotlib as gp if 'title' not in kwargs: if intrinsics_only: title_note = "using an identity extrinsics transform" elif focus_radius == 0: title_note = "using given extrinsics transform" else: distance_string = "infinity" if distance is None else f"distance={distance}" using_uncertainties_string = f"{'' if use_uncertainties else 'not '}using uncertainties" title_note = f"computing the extrinsics transform {using_uncertainties_string} from data at {distance_string}" # should say something about the focus too, but it's already too long # elif focus_radius > 2*(W+H): # where = "extrinsics transform fitted everywhere" # else: # where = "extrinsics transform fit looking at {} with radius {}". \ # format('the imager center' if focus_center is None else focus_center, # focus_radius) title = f"Diff looking at {len(models)} models, {title_note}" if extratitle is not None: title += ": " + extratitle kwargs['title'] = title if vectorfield: if len(models) > 2: raise Exception("I can only plot a vectorfield when looking at exactly 2 models. Instead I have {}". \ format(len(models))) if directions and len(models) > 2: raise Exception("I can only color-code by directions when looking at exactly 2 models. Instead I have {}". \ format(len(models))) # Now do all the actual work difflen,diff,q0,Rt10 = mrcal.projection_diff(models, implied_Rt10 = implied_Rt10, gridn_width = gridn_width, gridn_height = gridn_height, intrinsics_only = intrinsics_only, distance = distance, use_uncertainties = use_uncertainties, focus_center = focus_center, focus_radius = focus_radius) # difflen,diff have shape (len(distance), ...) if multiple distances are # given. In this case I display the difference using the FIRST distance in # the list # shape (Nheight, Nwidth) if difflen is not None and difflen.ndim > 2: difflen = nps.clump(difflen, n=difflen.ndim-2)[0] # shape (Nheight, Nwidth,2) if diff is not None and diff.ndim > 3: diff = nps.clump(diff, n=diff.ndim-3)[0] plot_options = kwargs if vectorfield: # Not plotting a matrix image. I collapse (Nheight, Nwidth, ...) to (Nheight*Nwidth, ...) if q0 is not None: q0 = nps.clump(q0, n=2) if difflen is not None: difflen = nps.clump(difflen, n=2) if diff is not None: diff = nps.clump(diff, n=2) if directions: gp.add_plot_option(plot_options, cbrange = [-180.,180.], _set = 'palette defined ( 0 "#00ffff", 0.5 "#80ffff", 1 "#ffffff") model HSV') color = 180./np.pi * np.arctan2(diff[...,1], diff[...,0]) else: gp.add_plot_option(plot_options, cbrange = [0,cbmax]) color = difflen # Any invalid values (nan or inf) are set to an effectively infinite # difference color[~np.isfinite(color)] = 1e6 if vectorfield: # The mrcal.projection_diff() call made sure they're the same for all # the models W,H=models[0].imagersize() gp.add_plot_option(plot_options, square = 1, _xrange = [0,W], _yrange = [H,0]) curve_options = dict(_with='vectors filled palette', tuplesize=5) plot_data_args = \ [ (q0 [:,0], q0 [:,1], diff[:,0] * vectorscale, diff[:,1] * vectorscale, color, curve_options) ] else: curve_options = \ _options_heatmap_with_contours( # update these plot options kwargs, contour_max = cbmax, contour_increment = contour_increment, imagersize = models[0].imagersize(), gridn_width = gridn_width, gridn_height = gridn_height, contour_labels_styles = contour_labels_styles, contour_labels_font = contour_labels_font, do_contours = not directions) plot_data_args = [ (color, curve_options) ] if valid_intrinsics_region: valid_region0 = models[0].valid_intrinsics_region() if valid_region0 is not None: if vectorfield: # 2d plot plot_data_args.append( (valid_region0[:,0], valid_region0[:,1], dict(_with = 'lines lw 4 lc "green"', legend = "valid region of 1st camera")) ) else: # 3d plot plot_data_args.append( (valid_region0[:,0], valid_region0[:,1], valid_region0[:,0]*0, dict(_with = 'lines lw 4 lc "green" nocontour', legend = "valid region of 1st camera")) ) valid_region1 = models[1].valid_intrinsics_region() else: valid_region0 = None valid_region1 = None if len(models) == 2 and valid_region1 is not None: # The second camera has a valid region, and I should plot it. This has # more complexity: each point on the contour of the valid region of the # second camera needs to be transformed to the coordinate system of the # first camera to make sense. The transformation is complex, and # straight lines will not remain straight. I thus resample the polyline # more densely. if not intrinsics_only: v1 = mrcal.unproject(mrcal.utils._densify_polyline(valid_region1, spacing = 50), *models[1].intrinsics(), normalize = True) if distance is not None: try: v1 *= distance except: v1 *= distance[0] valid_region1 = mrcal.project( mrcal.transform_point_Rt( mrcal.invert_Rt(Rt10), v1 ), *models[0].intrinsics() ) if vectorfield: # 2d plot plot_data_args.append( (valid_region1[:,0], valid_region1[:,1], dict(_with = 'lines lw 3 lc "gray80"', legend = "valid region of 2nd camera")) ) else: # 3d plot plot_data_args.append( (valid_region1[:,0], valid_region1[:,1], valid_region1[:,0]*0, dict(_with = 'lines lw 3 lc "gray80" nocontour', legend = "valid region of 2nd camera")) ) if observations: for i in range(len(models)): _2d = bool(vectorfield) _append_observation_visualizations(plot_data_args, models[i], f"Camera {i} ", -1 if observations == 'dots' else (1+i), _2d) data_tuples = plot_data_args if not return_plot_args: plot = gp.gnuplotlib(**plot_options) plot.plot(*data_tuples) return plot, Rt10 return (data_tuples, plot_options), Rt10 def show_projection_uncertainty(model, *, gridn_width = 60, gridn_height = None, observed_pixel_uncertainty = None, observations = False, valid_intrinsics_region = False, distance = None, isotropic = False, cbmax = 3, contour_increment = None, contour_labels_styles = 'boxed', contour_labels_font = None, extratitle = None, return_plot_args = False, **kwargs): r'''Visualize the uncertainty in camera projection SYNOPSIS model = mrcal.cameramodel('xxx.cameramodel') mrcal.show_projection_uncertainty(model) ... A plot pops up displaying the expected projection uncertainty across the ... imager This function uses the expected noise of the calibration-time observations to estimate the uncertainty of projection of the final model. At calibration time we estimate - The intrinsics (lens paramaters) of a number of cameras - The extrinsics (geometry) of a number of cameras in respect to some reference coordinate system - The poses of observed chessboards and/or the coordinates of the discrete points, also in respect to some reference coordinate system All the coordinate systems move around, and all 3 of these sets of data have some uncertainty. This tool takes into account all the uncertainties to report an estimated uncertainty metric. See http://mrcal.secretsauce.net/uncertainty.html for a detailed description of the computation. This function grids the imager, and reports an uncertainty for each point on the grid. The resulting plot contains a heatmap of the uncertainties for each cell in the grid, and corresponding contours. Since the projection uncertainty is based on calibration-time observation uncertainty, it is sometimes useful to see where the calibration-time observations were. Pass observations=True to do that. Since the projection uncertainty is based partly on the uncertainty of the camera pose, points at different distance from the camera will have different reported uncertainties EVEN IF THEY PROJECT TO THE SAME PIXEL. The queried distance is passed in the distance argument. If distance is None (the default) then we look out to infinity. For each cell we compute the covariance matrix of the projected (x,y) coords, and by default we report the worst-direction standard deviation. If isotropic: we report the RMS standard deviation instead. ARGUMENTS - model: the mrcal.cameramodel object being evaluated - gridn_width: optional value, defaulting to 60. How many points along the horizontal gridding dimension - gridn_height: how many points along the vertical gridding dimension. If None, we compute an integer gridn_height to maintain a square-ish grid: gridn_height/gridn_width ~ imager_height/imager_width - observed_pixel_uncertainty: optional value, defaulting to None. The uncertainty of the pixel observations being propagated through the solve and projection. If omitted or None, this input uncertainty is inferred from the residuals at the optimum. Most people should omit this - observations: optional value, defaulting to False. If observatoins:, we overlay calibration-time observations on top of the uncertainty plot. We should then see that more data produces more confident results. If a special value of 'dots' is passed, the observations are plotted as dots instead of points - valid_intrinsics_region: optional boolean, defaulting to False. If True, we overlay the valid-intrinsics region onto the plot. If the valid-intrinsics region isn't available, we will silently omit it - distance: optional value, defaulting to None. The projection uncertainty varies depending on the range to the observed point, with the queried range set in this 'distance' argument. If None (the default) we look out to infinity. - isotropic: optional boolean, defaulting to False. We compute the full 2x2 covariance matrix of the projection. The 1-sigma contour implied by this matrix is an ellipse, and we use the worst-case direction by default. If we want the RMS size of the ellipse instead of the worst-direction size, pass isotropic=True. - cbmax: optional value, defaulting to 3.0. Sets the maximum range of the color map - contour_increment: optional value, defaulting to None. If given, this will be used as the distance between adjacent contours. If omitted of None, a reasonable value will be estimated - contour_labels_styles: optional string, defaulting to 'boxed'. The style of the contour labels. This will be passed to gnuplot as f"with labels {contour_labels_styles} nosurface". Can be used to box/unbox the label, set the color, etc. To change the font use contour_labels_font. - contour_labels_font: optional string, defaulting to None, If given, this is the font string for the contour labels. Will be passed to gnuplot as f'set cntrlabel font "{contour_labels_font}"' - extratitle: optional string to include in the title of the resulting plot. Used to extend the default title string. If kwargs['title'] is given, it is used directly, and the extratitle is ignored - return_plot_args: boolean defaulting to False. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot - **kwargs: optional arguments passed verbatim as plot options to gnuplotlib. Useful to make hardcopies, etc RETURNED VALUE if not return_plot_args (the usual path): we return the gnuplotlib plot object. The plot disappears when this object is destroyed (by the garbage collection, for instance), so save this returned plot object into a variable, even if you're not going to be doing anything with this object. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot ''' import gnuplotlib as gp W,H=model.imagersize() if gridn_height is None: gridn_height = int(round(H/W*gridn_width)) lensmodel, intrinsics_data = model.intrinsics() q = mrcal.sample_imager( gridn_width, gridn_height, *model.imagersize() ) pcam = mrcal.unproject(q, *model.intrinsics(), normalize = True) err = mrcal.projection_uncertainty(pcam * (distance if distance is not None else 1.0), model = model, atinfinity = distance is None, what = 'rms-stdev' if isotropic else 'worstdirection-stdev', observed_pixel_uncertainty = observed_pixel_uncertainty) # Any nan or inf uncertainty is set to a very high value. This usually # happens if the unproject() call failed, resulting in pcam == 0 err[~np.isfinite(err)] = 1e6 if 'title' not in kwargs: if distance is None: distance_description = ". Looking out to infinity" else: distance_description = f". Looking out to {distance}m" if not isotropic: what_description = "Projection" else: what_description = "Isotropic projection" title = f"{what_description} uncertainty (in pixels) based on calibration input noise{distance_description}" if extratitle is not None: title += ": " + extratitle kwargs['title'] = title curveoptions = \ _options_heatmap_with_contours( # update these plot options kwargs, contour_max = cbmax, contour_increment = contour_increment, imagersize = model.imagersize(), gridn_width = gridn_width, gridn_height = gridn_height, contour_labels_styles = contour_labels_styles, contour_labels_font = contour_labels_font) plot_data_args = [(err, curveoptions)] if valid_intrinsics_region: valid_intrinsics_region = model.valid_intrinsics_region() else: valid_intrinsics_region = None if valid_intrinsics_region is not None: plot_data_args.append( (valid_intrinsics_region[:,0], valid_intrinsics_region[:,1], np.zeros(valid_intrinsics_region.shape[-2]), dict(_with = 'lines lw 4 lc "green" nocontour', legend = "Valid-intrinsics region")) ) if observations: _append_observation_visualizations(plot_data_args, model, '', -1 if observations == 'dots' else 1, False) plot_options = kwargs data_tuples = plot_data_args if not return_plot_args: plot = gp.gnuplotlib(**plot_options) plot.plot(*data_tuples) return plot return (data_tuples, plot_options) def _observed_hypothesis_points_and_boards_at_calibration_time(model): optimization_inputs = model.optimization_inputs() p_cam_observed_at_calibration_time = np.zeros((0,3), dtype=float) try: # [-2] means "inliers" p_cam_observed_at_calibration_time = \ mrcal.hypothesis_board_corner_positions(model.icam_intrinsics(), **optimization_inputs)[-2] except: # no chessboards perhaps pass points = optimization_inputs.get('points') if points is not None: indices_point_camintrinsics_camextrinsics = \ optimization_inputs['indices_point_camintrinsics_camextrinsics'] mask_thiscam = \ indices_point_camintrinsics_camextrinsics[...,1] == model.icam_intrinsics() ipoint = indices_point_camintrinsics_camextrinsics[mask_thiscam,0] icame = indices_point_camintrinsics_camextrinsics[mask_thiscam,2] observations_point = optimization_inputs['observations_point'][mask_thiscam] mask_inliers = observations_point[...,2] > 0 ipoint = ipoint[mask_inliers] icame = icame [mask_inliers] icame[icame<0] = -1 rt_cam_ref = \ nps.glue( mrcal.identity_rt(), optimization_inputs['extrinsics_rt_fromref'], axis = -2 ) \ [ icame+1 ] rt_cam_ref = optimization_inputs['extrinsics_rt_fromref'][icame] p_ref_points = points[ipoint] p_cam_points = mrcal.transform_point_rt(rt_cam_ref, p_ref_points) p_cam_observed_at_calibration_time = \ nps.glue(p_cam_observed_at_calibration_time, p_cam_points, axis = -2) return p_cam_observed_at_calibration_time def show_projection_uncertainty_vs_distance(model, *, where = "centroid", observed_pixel_uncertainty = None, isotropic = False, distance_min = None, distance_max = None, extratitle = None, return_plot_args = False, **kwargs): r'''Visualize the uncertainty in camera projection along one observation ray SYNOPSIS model = mrcal.cameramodel('xxx.cameramodel') mrcal.show_projection_uncertainty_vs_distance(model) ... A plot pops up displaying the expected projection uncertainty along an ... observation ray at different distances from the camera This function is similar to show_projection_uncertainty(). That function displays the uncertainty at different locations along the imager, for one observation distance. Conversely, THIS function displays it in one location on the imager, but at different distances. This function uses the expected noise of the calibration-time observations to estimate the uncertainty of projection of the final model. At calibration time we estimate - The intrinsics (lens paramaters) of a number of cameras - The extrinsics (geometry) of a number of cameras in respect to some reference coordinate system - The poses of observed chessboards and/or the coordinates of the discrete points, also in respect to some reference coordinate system All the coordinate systems move around, and all 3 of these sets of data have some uncertainty. This tool takes into account all the uncertainties to report an estimated uncertainty metric. See http://mrcal.secretsauce.net/uncertainty.html for a detailed description of the computation. The curve produced by this function has a characteristic shape: - At low ranges, the camera translation dominates, and the uncertainty increases to infinity, as the distance to the camera goes to 0 - As we move away from the camera, the uncertainty drops to a minimum, at around the distance where the chessboards were observed - Past the minimum, the uncertainty climbs to asymptotically approach the uncertainty at infinity ARGUMENTS - model: the mrcal.cameramodel object being evaluated - where: optional value, defaulting to "centroid". Indicates the point on the imager we're examining. May be one of - "center": the center of the imager - "centroid": the midpoint of all the points observed at calibration time - A numpy array (x,y) indicating the pixel - observed_pixel_uncertainty: optional value, defaulting to None. The uncertainty of the pixel observations being propagated through the solve and projection. If omitted or None, this input uncertainty is inferred from the residuals at the optimum. Most people should omit this - isotropic: optional boolean, defaulting to False. We compute the full 2x2 covariance matrix of the projection. The 1-sigma contour implied by this matrix is an ellipse, and we use the worst-case direction by default. If we want the RMS size of the ellipse instead of the worst-direction size, pass isotropic=True. - extratitle: optional string to include in the title of the resulting plot. Used to extend the default title string. If kwargs['title'] is given, it is used directly, and the extratitle is ignored - return_plot_args: boolean defaulting to False. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot - **kwargs: optional arguments passed verbatim as plot options to gnuplotlib. Useful to make hardcopies, etc RETURNED VALUE if not return_plot_args (the usual path): we return the gnuplotlib plot object. The plot disappears when this object is destroyed (by the garbage collection, for instance), so save this returned plot object into a variable, even if you're not going to be doing anything with this object. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot ''' import gnuplotlib as gp p_cam_observed_at_calibration_time = \ _observed_hypothesis_points_and_boards_at_calibration_time(model) if p_cam_observed_at_calibration_time.size == 0: raise Exception("No inlier chessboards or points observed at calibration time") if isinstance(where, str): if where == 'center': q = (model.imagersize() - 1.) / 2. vcam = mrcal.unproject(q, *model.intrinsics(), normalize = True) elif where == 'centroid': p = np.mean(p_cam_observed_at_calibration_time, axis=-2) vcam = p / nps.mag(p) else: raise Exception("'where' should be 'center' or an array specifying a pixel") elif isinstance(where, np.ndarray): q = where vcam = mrcal.unproject(q, *model.intrinsics(), normalize = True) else: raise Exception("'where' should be 'center' or an array specifying a pixel") # shape (Ndistances) if distance_min is None or distance_max is None: distance_observed_at_calibration_time = \ nps.mag(p_cam_observed_at_calibration_time) if distance_min is None: # / 5 for a bit of extra margin distance_min = np.min(distance_observed_at_calibration_time) / 5. if distance_max is None: # * 10 for a bit of extra margin distance_max = np.max(distance_observed_at_calibration_time) * 10. distances = np.logspace( np.log10(distance_min), np.log10(distance_max), 80 ) # shape (Ndistances, 3) pcam = vcam * nps.dummy(distances, -1) # shape (Ndistances) uncertainty = \ mrcal.projection_uncertainty( pcam, model = model, what = 'rms-stdev' if isotropic else 'worstdirection-stdev', observed_pixel_uncertainty = observed_pixel_uncertainty) if 'title' not in kwargs: if not isotropic: what_description = "Projection" else: what_description = "Isotropic projection" title = f"{what_description} uncertainty (in pixels) based on calibration input noise at q = {where}" if extratitle is not None: title += ": " + extratitle kwargs['title'] = title plot_options = \ dict( xlabel = 'Observation distance', ylabel = 'Projection uncertainty (pixels)', _with = 'lines', **kwargs ) data_tuples = ( distances, uncertainty ) if not return_plot_args: plot = gp.gnuplotlib(**plot_options) plot.plot(*data_tuples) return plot return (data_tuples, plot_options) def show_distortion_off_pinhole_radial(model, *, show_fisheye_projections = False, extratitle = None, return_plot_args = False, **kwargs): r'''Visualize a lens's deviation from a pinhole projection SYNOPSIS model = mrcal.cameramodel('xxx.cameramodel') mrcal.show_distortion_off_pinhole_radial(model) ... A plot pops up displaying how much this model deviates from a pinhole ... model across the imager in the radial direction This function treats a pinhole projection as a baseline, and visualizes deviations from this baseline. So wide lenses will have a lot of reported "distortion". This function looks at radial distortion only. Plots a curve showing the magnitude of the radial distortion as a function of the distance to the center ARGUMENTS - model: the mrcal.cameramodel object being evaluated - show_fisheye_projections: optional boolean defaulting to False. If show_fisheye_projections: the radial plots include the behavior of common fisheye projections, in addition to the behavior of THIS lens - extratitle: optional string to include in the title of the resulting plot. Used to extend the default title string. If kwargs['title'] is given, it is used directly, and the extratitle is ignored - return_plot_args: boolean defaulting to False. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot - **kwargs: optional arguments passed verbatim as plot options to gnuplotlib. Useful to make hardcopies, etc RETURNED VALUE if not return_plot_args (the usual path): we return the gnuplotlib plot object. The plot disappears when this object is destroyed (by the garbage collection, for instance), so save this returned plot object into a variable, even if you're not going to be doing anything with this object. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot ''' import gnuplotlib as gp lensmodel, intrinsics_data = model.intrinsics() # plot the radial distortion. For now I only deal with opencv here m = re.search("OPENCV([0-9]+)", lensmodel) if not m: raise Exception("Radial distortion visualization implemented only for OpenCV distortions; for now") N = int(m.group(1)) # OpenCV does this: # # This is the opencv distortion code in cvProjectPoints2 in # calibration.cpp Here x,y are x/z and y/z. OpenCV applies distortion to # x/z, y/z and THEN does the ...*f + c thing. The distortion factor is # based on r, which is ~ x/z ~ tan(th) where th is the deviation off # center # # z = z ? 1./z : 1; # x *= z; y *= z; # r2 = x*x + y*y; # r4 = r2*r2; # r6 = r4*r2; # a1 = 2*x*y; # a2 = r2 + 2*x*x; # a3 = r2 + 2*y*y; # cdist = 1 + k[0]*r2 + k[1]*r4 + k[4]*r6; # icdist2 = 1./(1 + k[5]*r2 + k[6]*r4 + k[7]*r6); # xd = x*cdist*icdist2 + k[2]*a1 + k[3]*a2 + k[8]*r2+k[9]*r4; # yd = y*cdist*icdist2 + k[2]*a3 + k[3]*a1 + k[10]*r2+k[11]*r4; # ... # m[i].x = xd*fx + cx; # m[i].y = yd*fy + cy; cxy = intrinsics_data[2:4] distortions = intrinsics_data[4:] k2 = distortions[0] k4 = distortions[1] k6 = 0 if N >= 5: k6 = distortions[4] numerator = '1. + r*r * ({} + r*r * ({} + r*r * {}))'.format(k2,k4,k6) numerator = numerator.replace('r', 'tan(x*pi/180.)') if N >= 8: denominator = '1. + r*r * ({} + r*r * ({} + r*r * {}))'.format(*distortions[5:8]) denominator = denominator.replace('r', 'tan(x*pi/180.)') scale = '({})/({})'.format(numerator,denominator) else: scale = numerator W,H = model.imagersize() x0,x1 = 0, W-1 y0,y1 = 0, H-1 q_corners = np.array(((x0,y0), (x0,y1), (x1,y0), (x1,y1)), dtype=float) q_centersx = np.array(((cxy[0],y0), (cxy[0],y1)), dtype=float) q_centersy = np.array(((x0,cxy[1]), (x1,cxy[1])), dtype=float) v_corners = mrcal.unproject( q_corners, lensmodel, intrinsics_data) v_centersx = mrcal.unproject( q_centersx, lensmodel, intrinsics_data) v_centersy = mrcal.unproject( q_centersy, lensmodel, intrinsics_data) # some unprojections may be nan (we're looking beyond where the projection # is valid), so I explicitly ignore those v_corners = v_corners [np.all(np.isfinite(v_corners), axis=-1)] v_centersx = v_centersx[np.all(np.isfinite(v_centersx), axis=-1)] v_centersy = v_centersy[np.all(np.isfinite(v_centersy), axis=-1)] th_corners = 180./np.pi * np.arctan2(nps.mag(v_corners [..., :2]), v_corners [..., 2]) th_centersx = 180./np.pi * np.arctan2(nps.mag(v_centersx[..., :2]), v_centersx[..., 2]) th_centersy = 180./np.pi * np.arctan2(nps.mag(v_centersy[..., :2]), v_centersy[..., 2]) # Now the equations. The 'x' value here is "pinhole pixels off center", # which is f*tan(th). I plot this model's radial relationship, and that # from other common fisheye projections (formulas mostly from # https://en.wikipedia.org/wiki/Fisheye_lens) equations = [f'180./pi*atan(tan(x*pi/180.) * ({scale})) with lines lw 2 title "THIS model"', 'x title "pinhole"'] if show_fisheye_projections: equations += [f'180./pi*atan(2. * tan( x*pi/180. / 2.)) title "stereographic"', f'180./pi*atan(x*pi/180.) title "equidistant"', f'180./pi*atan(2. * sin( x*pi/180. / 2.)) title "equisolid angle"', f'180./pi*atan( sin( x*pi/180. )) title "orthogonal"'] gp.add_plot_option(kwargs, 'set', ['arrow from {th}, graph 0 to {th}, graph 1 nohead lc "red"' . \ format(th=th) for th in th_centersy] + \ ['arrow from {th}, graph 0 to {th}, graph 1 nohead lc "green"'. \ format(th=th) for th in th_centersx] + \ ['arrow from {th}, graph 0 to {th}, graph 1 nohead lc "blue"' . \ format(th=th) for th in th_corners ]) if N >= 8: equations.extend( [numerator + ' axis x1y2 title "numerator (y2)"', denominator + ' axis x1y2 title "denominator (y2)"', '0 axis x1y2 notitle with lines lw 2' ] ) gp.add_plot_option(kwargs, 'set', 'y2tics') kwargs['y2label'] = 'Rational correction numerator, denominator' if 'title' not in kwargs: title = 'Radial distortion. Red: x edges. Green: y edges. Blue: corners' if extratitle is not None: title += ": " + extratitle kwargs['title'] = title plot_options = \ dict(equation = equations, # any of the unprojections could be nan, so I do the best I can _xrange = [0,np.max(np.nan_to_num(nps.glue(th_corners, th_centersx, th_centersy, axis=-1))) * 1.01], xlabel = 'Angle off the projection center (deg)', ylabel = 'Distorted angle off the projection center', **kwargs) data_tuples = () if not return_plot_args: plot = gp.gnuplotlib(**plot_options) plot.plot(*data_tuples) return plot return (data_tuples, plot_options) def show_distortion_off_pinhole(model, *, vectorfield = False, vectorscale = 1.0, cbmax = 25.0, gridn_width = 60, gridn_height = None, extratitle = None, return_plot_args = False, **kwargs): r'''Visualize a lens's deviation from a pinhole projection SYNOPSIS model = mrcal.cameramodel('xxx.cameramodel') mrcal.show_distortion_off_pinhole( model ) ... A plot pops up displaying how much this model deviates from a pinhole ... model across the imager This function treats a pinhole projection as a baseline, and visualizes deviations from this baseline. So wide lenses will have a lot of reported "distortion". ARGUMENTS - model: the mrcal.cameramodel object being evaluated - vectorfield: optional boolean, defaulting to False. By default we produce a heat map of the differences. If vectorfield: we produce a vector field instead - vectorscale: optional value, defaulting to 1.0. Applicable only if vectorfield. The magnitude of the errors displayed in the vector field could be small, and difficult to see. This argument can be used to scale all the displayed vectors to improve legibility. - cbmax: optional value, defaulting to 25.0. Sets the maximum range of the color map and of the contours if plotting a heat map - gridn_width: how many points along the horizontal gridding dimension - gridn_height: how many points along the vertical gridding dimension. If None, we compute an integer gridn_height to maintain a square-ish grid: gridn_height/gridn_width ~ imager_height/imager_width - extratitle: optional string to include in the title of the resulting plot. Used to extend the default title string. If kwargs['title'] is given, it is used directly, and the extratitle is ignored - return_plot_args: boolean defaulting to False. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot - **kwargs: optional arguments passed verbatim as plot options to gnuplotlib. Useful to make hardcopies, etc RETURNED VALUE if not return_plot_args (the usual path): we return the gnuplotlib plot object. The plot disappears when this object is destroyed (by the garbage collection, for instance), so save this returned plot object into a variable, even if you're not going to be doing anything with this object. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot ''' import gnuplotlib as gp lensmodel, intrinsics_data = model.intrinsics() imagersize = model.imagersize() if 'title' not in kwargs: title = "Off-pinhole effects of {}".format(lensmodel) if extratitle is not None: title += ": " + extratitle kwargs['title'] = title W,H = imagersize if gridn_height is None: gridn_height = int(round(H/W*gridn_width)) if not mrcal.lensmodel_metadata_and_config(lensmodel)['has_core']: raise Exception("This currently works only with models that have an fxfycxcy core. It might not be required. Take a look at the following code if you want to add support") fxy = intrinsics_data[ :2] cxy = intrinsics_data[2:4] # shape: (Nheight,Nwidth,2). Contains (x,y) rows grid = np.ascontiguousarray(nps.mv(nps.cat(*np.meshgrid(np.linspace(0,W-1,gridn_width), np.linspace(0,H-1,gridn_height))), 0,-1), dtype = float) dgrid = mrcal.project( nps.glue( (grid-cxy)/fxy, np.ones(grid.shape[:-1] + (1,), dtype=float), axis = -1 ), lensmodel, intrinsics_data ) if not vectorfield: curveoptions = \ _options_heatmap_with_contours( # update these plot options kwargs, contour_max = cbmax, imagersize = imagersize, gridn_width = gridn_width, gridn_height = gridn_height) delta = dgrid-grid # shape: gridn_height,gridn_width. Because numpy (and thus gnuplotlib) want it that # way distortion = nps.mag(delta) data_tuples = ((distortion, curveoptions), ) else: # vectorfield # shape: gridn_height*gridn_width,2 grid = nps.clump(grid, n=2) dgrid = nps.clump(dgrid, n=2) delta = dgrid-grid delta *= vectorscale kwargs['_xrange']=(-50,W+50) kwargs['_yrange']=(H+50, -50) kwargs['_set' ]=['object 1 rectangle from 0,0 to {},{} fillstyle empty'.format(W,H)] kwargs['square' ]=True if '_set' in kwargs: if type(kwargs['_set']) is list: kwargs['_set'].extend(kwargs['_set']) else: kwargs['_set'].append(kwargs['_set']) del kwargs['_set'] data_tuples = \ ( (grid[:,0], grid[:,1], delta[:,0], delta[:,1], {'with': 'vectors filled', 'tuplesize': 4, }), (grid[:,0], grid[:,1], {'with': 'points', 'tuplesize': 2, })) plot_options = kwargs if not return_plot_args: plot = gp.gnuplotlib(**plot_options) plot.plot(*data_tuples) return plot return (data_tuples, plot_options) def show_valid_intrinsics_region(models, *, cameranames = None, image = None, points = None, extratitle = None, return_plot_args = False, **kwargs): r'''Visualize a model's valid-intrinsics region SYNOPSIS filenames = ('cam0-dance0.cameramodel', 'cam0-dance1.cameramodel') models = [ mrcal.cameramodel(f) for f in filenames ] mrcal.show_valid_intrinsics_region( models, cameranames = filenames, image = 'image.jpg' ) This function displays the valid-intrinsics region in the given camera models. Multiple models can be passed-in to see their valid-intrinsics regions together. This is useful to evaluate different calibrations of the same lens. A captured image can be passed-in to see the regions overlaid on an actual image produced by the camera. All given models MUST have a valid-intrinsics region defined. A model may have an empty region. This cannot be plotted (there's no contour to plot), but the plot legend will still contain an entry for this model, with a note indicating its emptiness This tool produces a gnuplotlib plot. To annotate an image array, call annotate_image__valid_intrinsics_region() instead ARGUMENTS - models: an iterable of mrcal.cameramodel objects we're visualizing. If we're looking at just a single model, it can be passed directly in this argument, instead of wrapping it into a list. - cameranames: optional an iterable of labels, one for each model. These will appear as the legend in the plot. If omitted, we will simply enumerate the models. - image: optional image to annotate. May be given as an image filename or an array of image data. If omitted, we plot the valid-intrinsics region only. - points: optional array of shape (N,2) of pixel coordinates to plot. If given, we show these arbitrary points in our plot. Useful to visualize the feature points used in a vision algorithm to see how reliable they are expected to be - extratitle: optional string to include in the title of the resulting plot. Used to extend the default title string. If kwargs['title'] is given, it is used directly, and the extratitle is ignored - return_plot_args: boolean defaulting to False. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot - **kwargs: optional arguments passed verbatim as plot options to gnuplotlib. Useful to make hardcopies, etc RETURNED VALUE A tuple: - if not return_plot_args (the usual path): the gnuplotlib plot object. The plot disappears when this object is destroyed (by the garbage collection, for instance), so save this returned plot object into a variable, even if you're not going to be doing anything with this object. if return_plot_args: a (data_tuples, plot_options) tuple. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot ''' if isinstance(models, mrcal.cameramodel): models = (models,) if cameranames is None: cameranames = ['Model {}'.format(i) for i in range(len(models))] else: if len(models) != len(cameranames): raise Exception("Must get the same number of models and cameranames") W,H = models[0].imagersize() for m in models[1:]: WH1 = m.imagersize() if W != WH1[0] or H != WH1[1]: raise Exception("All given models MUST have the same imagersize. Got {} and {}".format((W,H), WH1)) valid_regions = [ m.valid_intrinsics_region() for m in models ] if any(r is None for r in valid_regions): raise Exception("Some given models have no valid-intrinsics region defined") # I want to render empty regions, to at least indicate this in the legend for i in range(len(models)): if valid_regions[i].size == 0: valid_regions[i] = np.zeros((1,2)) cameranames[i] += ": empty" import gnuplotlib as gp gp.add_plot_option(kwargs, 'set', 'key opaque') plot_data_args = [] if image is not None: if isinstance(image, np.ndarray): plot_data_args.append( (image, dict(_with='image', tuplesize = 3))) else: kwargs['rgbimage'] = image plot_data_args.extend( (r[:,0], r[:,1], dict(_with = 'lines lw 4 lc "green"', legend = cameranames[i])) \ for i,r in enumerate(valid_regions) ) if points is not None: plot_data_args.append( (points, dict(tuplesize = -2, _with = 'points pt 7 ps 1'))) plot_options = dict(square=1, _xrange=[0,W], _yrange=[H,0], **kwargs) if 'title' not in plot_options: title = 'Valid-intrinsics region' if extratitle is not None: title += ": " + extratitle plot_options['title'] = title data_tuples = plot_data_args if not return_plot_args: plot = gp.gnuplotlib(**plot_options) plot.plot(*data_tuples) return plot return (data_tuples, plot_options) def show_splined_model_correction(model, *, vectorfield = False, xy = None, imager_domain = False, vectorscale = 1.0, valid_intrinsics_region = True, observations = False, gridn_width = 60, gridn_height = None, extratitle = None, return_plot_args = False, **kwargs): r'''Visualize the projection corrections defined by a splined model SYNOPSIS model = mrcal.cameramodel(model_filename) mrcal.show_splined_model_correction(model) # A plot pops up displaying the spline knots, the magnitude of the # corrections defined by the spline surfaces, the spline-in-bounds # regions and the valid-intrinsics region Splined models are parametrized by flexible surfaces that define the projection corrections (off some baseline model), and visualizing these corrections is useful for understanding the projection behavior. Details of these models are described in the documentation: http://mrcal.secretsauce.net/lensmodels.html#splined-stereographic-lens-model At this time LENSMODEL_SPLINED_STEREOGRAPHIC is the only splined model mrcal has, so the baseline model is always LENSMODEL_STEREOGRAPHIC. In spots, the below documentation assumes a stereographic baseline model. This function can produce a plot in the domain either of the input or the output of the spline functions. if not imager_domain: The default. The plot is presented based on the spline index. With LENSMODEL_SPLINED_STEREOGRAPHIC, this is the stereographic projection u. This is the "forward" direction, what the projection operation actually computes. In this view the knots form a regular grid, and the edge of the imager forms a (possibly very irregular) curve if imager_domain: The plot is presented based on the pixels in the imager. This is the backward direction: the domain is the OUTPUT of the splined functions. In this view the knot layout is (possibly highly) irregular. The edge of the imager is a perfect rectangle. Separate from the domain, the data can be presented in 3 different ways: - Magnitude heatmap. This is the default. Selected by "not vectorfield and xy is None". We plot mag(deltauxy). This displays the deviation from the baseline model as a heat map. - Individual heatmap. Selected by "not vectorfield and xy is not None". We plot deltaux or deltauy, depending on the value of xy. This displays the value of one of the two splined surfaces individually, as a heat map. - Vector field. Selected by "bool(vectorfield) is True". Displays the correction (deltaux, deltauy) as a vector field. The splined surfaces are defined by control points we call "knots". These knots are arranged in a fixed grid (defined by the model configuration) with the value at each knot set in the intrinsics vector. The configuration selects the control point density and the expected field of view of the lens. If the fov_x_deg configuration value is too big, many of the knots will lie well outside the visible area, and will not be used. This is wasteful. If fov_x_deg is too small, then some parts of the imager will lie outside of the spline-in-bounds region, resulting in less-flexible projection behavior at the edges of the imager. So the field of view should roughly match the actual lens+camera we're using, and we can evaluate that with this function. This function displays the spline-in-bounds region together with the usable projection region (either the valid-intrinsics region or the imager bounds). Ideally, the spline-in-bounds region is slightly bigger than the usable projection region. The usable projection region visualized by this function is controlled by the valid_intrinsics_region argument. If True (the default), we display the valid-intrinsics region. This is recommended, but keep in mind that this region is smaller than the full imager, so a fov_x_deg that aligns well for one calibration may be too small in a subsequent calibration of the same lens. If the subsequent calibration has better coverage, and thus a bigger valid-intrinsics region. If not valid_intrinsics_region: we use the imager bounds instead. The issue here is that the projection near the edges of the imager is usually poorly-defined because usually there isn't a lot of calibration data there. This makes the projection behavior at the imager edges unknowable. Consequently, plotting the projection at the imager edges is usually too alarming or not alarming enough. Passing valid_intrinsics_region=False is thus recommended only if we have very good calibration coverage at the edge of the imager. ARGUMENTS - model: the mrcal.cameramodel object being evaluated - vectorfield: optional boolean defaults to False. if vectorfield: we plot the stereographic correction deltau as vectors. if not vectorfield (the default): we plot either deltaux or deltauy or mag(deltauxy) as a heat map. if vectorfield: xy must be None - xy: optional string. Must be either 'x' or 'y' or None. Selects the surface we're looking at. We have a separate surface for the x and y coordinates, with the two sharing the knot positions. We can display one of the surfaces individually, or if xy is None: we display the magnitude of the (deltaux, deltauy) vector. if xy is not None: vectorfield MUST be false - imager_domain: optional boolean defaults to False. If False: we plot everything against normalized stereographic coordinates; in this representation the knots form a regular grid, and the surface domain is a rectangle, but the imager boundary is curved. If True: we plot everything against the rendered pixel coordinates; the imager boundary is a rectangle, while the knots and domain become curved - vectorscale: optional value defaulting to 1.0. if vectorfield: this is a scale factor on the length of the vectors. If we have small deltau, longer vectors increase legibility of the plot. - valid_intrinsics_region: optional boolean defaults to True. If True: we communicate the usable projection region to the user by displaying the valid-intrinsics region. This isn't available in all models. To fall back on the boundary of the full imager, pass False here. In the usual case of incomplete calibration-time coverage at the edges, this results in a very unrealistic representation of reality. Passing True here is strongly recommended - observations: optional value, defaulting to False. If observations: we plot the calibration-time point observations on top of the surface and the knots. These make it more clear if the unprojectable regions in the model really are a problem. If a special value of 'dots' is passed, the observations are plotted as dots instead of points - gridn_width: optional value, defaulting to 60. How many points along the horizontal gridding dimension - gridn_height: how many points along the vertical gridding dimension. If None, we compute an integer gridn_height to maintain a square-ish grid: gridn_height/gridn_width ~ imager_height/imager_width - extratitle: optional string to include in the title of the resulting plot. Used to extend the default title string. If kwargs['title'] is given, it is used directly, and the extratitle is ignored - return_plot_args: boolean defaulting to False. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot - **kwargs: optional arguments passed verbatim as plot options to gnuplotlib. Useful to make hardcopies, etc RETURNED VALUES If not return_plot_args (the usual path): we return the gnuplotlib plot object. The plot disappears when this object is destroyed (by the garbage collection, for instance), so save this returned plot object into a variable, even if you're not going to be doing anything with this object. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot ''' if xy is not None: if vectorfield: raise Exception("Plotting a vectorfield, so xy should be None") if not (xy == 'x' or xy == 'y'): raise Exception("If given, xy should be either 'x' or 'y'") lensmodel,intrinsics_data = model.intrinsics() W,H = model.imagersize() if not re.match('LENSMODEL_SPLINED_STEREOGRAPHIC', lensmodel): raise Exception(f"This only makes sense with splined models. Input uses {lensmodel}") if gridn_height is None: gridn_height = int(round(H/W*gridn_width)) import gnuplotlib as gp if 'title' not in kwargs: title = f"Correction for {lensmodel}" if xy is not None: title += ". Looking at deltau{xy}" if extratitle is not None: title += ": " + extratitle kwargs['title'] = title ux_knots,uy_knots = mrcal.knots_for_splined_models(lensmodel) if imager_domain: # Shape (Ny,Nx,2); contains (x,y) rows q = \ nps.mv( nps.cat(*np.meshgrid( np.linspace(0, W-1, gridn_width), np.linspace(0, H-1, gridn_height) )), 0,-1) v = mrcal.unproject(np.ascontiguousarray(q), lensmodel, intrinsics_data) u = mrcal.project_stereographic(v) else: # Shape (gridn_height,gridn_width,2); contains (x,y) rows u = \ nps.mv( nps.cat(*np.meshgrid( np.linspace(ux_knots[0], ux_knots[-1],gridn_width), np.linspace(uy_knots[0], uy_knots[-1],gridn_height) )), 0,-1) # My projection is q = (u + deltau) * fxy + cxy. deltau is queried from the # spline surface v = mrcal.unproject_stereographic(np.ascontiguousarray(u)) q = mrcal.project(v, lensmodel, intrinsics_data) fxy = intrinsics_data[0:2] cxy = intrinsics_data[2:4] deltau = (q - cxy) / fxy - u if valid_intrinsics_region: imager_boundary_sparse = model.valid_intrinsics_region() if imager_boundary_sparse is None: raise Exception("No valid-intrinsics region is available in this model. Pass valid_intrinsics_region=False") else: # the imager boundary imager_boundary_sparse = \ np.array(((0, 0), (W-1, 0), (W-1, H-1), (0, H-1), (0, 0)), dtype=float) if imager_domain: imager_boundary = imager_boundary_sparse else: imager_boundary = \ mrcal.project_stereographic( mrcal.unproject( mrcal.utils._densify_polyline(imager_boundary_sparse, spacing = 50), lensmodel, intrinsics_data )) plot_options = dict(kwargs, square = True, yinv = True, ascii = True) if imager_domain: plot_options['xlabel'] = 'X pixel coord' plot_options['ylabel'] = 'Y pixel coord' else: plot_options['xlabel'] = 'Stereographic ux' plot_options['ylabel'] = 'Stereographic uy' if not vectorfield: gp.add_plot_option(plot_options, _set = 'cblabel "u correction (unitless)"') surface_curveoptions = dict( _with = 'image', tuplesize = 3 ) if imager_domain: surface_curveoptions['using'] = \ f'($1/({deltau.shape[1]-1})*({W-1})):' + \ f'($2/({deltau.shape[0]-1})*({H-1})):' + \ '3' else: surface_curveoptions['using'] = \ f'({(ux_knots[0])}+$1/({deltau.shape[1]-1})*({(ux_knots[-1])-(ux_knots[0])})):' + \ f'({(uy_knots[0])}+$2/({deltau.shape[0]-1})*({(uy_knots[-1])-(uy_knots[0])})):' + \ '3' if xy is not None: plot_data_tuples_surface = \ ( ( deltau[..., 0 if xy == 'x' else 1], surface_curveoptions ), ) else: plot_data_tuples_surface = \ ( ( nps.mag(deltau), surface_curveoptions ), ) else: if imager_domain: # Vector field in the imager domain. I have q = f (u+du) + cx. So I # render the vectors dq = f du plot_data_tuples_surface = \ ( ( *(x.ravel() for x in (q[...,0], q[...,1], vectorscale * fxy[0] * deltau[..., 0], vectorscale * fxy[1] * deltau[..., 1])), dict( _with = 'vectors filled', tuplesize = 4) ), ) else: plot_data_tuples_surface = \ ( ( *(x.ravel() for x in (u[...,0], u[...,1], vectorscale * deltau[..., 0], vectorscale * deltau[..., 1])), dict( _with = 'vectors filled', tuplesize = 4) ), ) domain_contour_u = mrcal.utils._splined_stereographic_domain(lensmodel) knots_u = nps.clump(nps.mv(nps.cat(*np.meshgrid(ux_knots,uy_knots)), 0, -1), n = 2) if imager_domain: domain_contour = \ mrcal.project( mrcal.unproject_stereographic( domain_contour_u), lensmodel, intrinsics_data) knots = \ mrcal.project( mrcal.unproject_stereographic( np.ascontiguousarray(knots_u)), lensmodel, intrinsics_data) else: domain_contour = domain_contour_u knots = knots_u plot_data_tuples_boundaries = \ ( ( imager_boundary, dict(_with = 'lines lw 2 lc "green"', tuplesize = -2, legend = 'Valid-intrinsics region' if valid_intrinsics_region else 'Imager boundary')), ( domain_contour, dict(_with = 'lines lw 1', tuplesize = -2, legend = 'Spline-in-bounds')), ) plot_data_tuples_knots = \ ( ( knots, dict(_with = 'points pt 2 ps 2 lc "green"', tuplesize = -2, legend = 'knots')), ) plot_data_tuples_observations = [] if observations: _append_observation_visualizations(plot_data_tuples_observations, model, '', -1 if observations == 'dots' else 1, True, reproject_to_stereographic = not imager_domain) # Anything outside the valid region contour but inside the imager is an # invalid area: the field-of-view of the camera needs to be increased. I # plot this area imager_boundary_nonan = \ imager_boundary[ np.isfinite(imager_boundary[:,0]) * np.isfinite(imager_boundary[:,1]),:] try: invalid_regions = mrcal.polygon_difference(imager_boundary_nonan, domain_contour) except Exception as e: # sometimes the domain_contour self-intersects, and this makes us # barf # print(f"WARNING: Couldn't compute invalid projection region. Exception: {e}") invalid_regions = [] if len(invalid_regions) > 0: print("WARNING: some parts of the imager cannot be projected from a region covered by the spline surface! You should increase the field-of-view of the model") plot_data_tuples_invalid_regions = \ tuple( ( r, dict( tuplesize = -2, _with = 'filledcurves fill transparent pattern 1 lc "royalblue"', legend = 'Visible spline-out-of-bounds region')) for r in invalid_regions ) else: plot_data_tuples_invalid_regions = () data_tuples = \ plot_data_tuples_surface + \ plot_data_tuples_boundaries + \ plot_data_tuples_invalid_regions + \ tuple(plot_data_tuples_observations) + \ plot_data_tuples_knots if not return_plot_args: plot = gp.gnuplotlib(**plot_options) plot.plot(*data_tuples) return plot return (data_tuples, plot_options) def annotate_image__valid_intrinsics_region(image, model, *, color=(0,255,0)): r'''Annotate an image with a model's valid-intrinsics region SYNOPSIS model = mrcal.cameramodel('cam0.cameramodel') image = mrcal.load_image('image.jpg') mrcal.annotate_image__valid_intrinsics_region(image, model) mrcal.save_image('image-annotated.jpg', image) This function reads a valid-intrinsics region from a given camera model, and draws it on top of a given image. This is useful to see what parts of a captured image have reliable intrinsics. This function modifies the input image. If the given model has no valid-intrinsics region defined, an exception is thrown. If the valid-intrinsics region is empty, a solid circle is drawn at the center. If we want an interactive plot instead of an annotated image, call mrcal.show_valid_intrinsics_region() instead. ARGUMENTS - model: the mrcal.cameramodel object that contains the valid-intrinsics region contour - image: the numpy array containing the image we're annotating. This is both an input and an output - color: optional tuple of length 3 indicating the BGR color of the annotation. Green by default RETURNED VALUES None. The input image array is modified ''' valid_intrinsics_region = model.valid_intrinsics_region() if valid_intrinsics_region is None: raise Exception("The given model has no valid-intrinsics region defined") import cv2 if valid_intrinsics_region.size == 0: cv2.circle( image, tuple((model.imagersize() - 1)//2), 10, color, -1) print("WARNING: annotate_image__valid_intrinsics_region(): valid-intrinsics region is empty. Drawing a circle") else: cv2.polylines(image, [valid_intrinsics_region.astype(np.int32)], True, color, 3) def imagergrid_using(imagersize, gridn_width, gridn_height = None): r'''Get a 'using' gnuplotlib expression for imager colormap plots SYNOPSIS import gnuplotlib as gp import numpy as np import mrcal ... Nwidth = 60 Nheight = 40 # shape (Nheight,Nwidth,3) v,_ = \ mrcal.sample_imager_unproject(Nw, Nh, *model.imagersize(), *model.intrinsics()) # shape (Nheight,Nwidth) f = interesting_quantity(v) gp.plot(f, tuplesize = 3, ascii = True, using = mrcal.imagergrid_using(model.imagersize, Nw, Nh), square = True, _with = 'image') We often want to plot some quantity at every location on the imager (intrinsics uncertainties for instance). This is done by gridding the imager, computing the quantity at each grid point, and sending this to gnuplot. This involves a few non-obvious plotting idioms, with the full usage summarized in the above example. Due to peculiarities of gnuplot, the 'using' expression produced by this function can only be used in plots using ascii data commands (i.e. pass 'ascii=True' to gnuplotlib). ARGUMENTS - imagersize: a (width,height) tuple for the size of the imager. With a mrcal.cameramodel object this is model.imagersize() - gridn_width: how many points along the horizontal gridding dimension - gridn_height: how many points along the vertical gridding dimension. If omitted or None, we compute an integer gridn_height to maintain a square-ish grid: gridn_height/gridn_width ~ imager_height/imager_width RETURNED VALUE The 'using' string. ''' W,H = imagersize if gridn_height is None: gridn_height = int(round(H/W*gridn_width)) return '($1*{}):($2*{}):3'.format(float(W-1)/(gridn_width-1), float(H-1)/(gridn_height-1)) def show_residuals_board_observation(optimization_inputs, i_observation, *, from_worst = False, i_observations_sorted_from_worst = None, residuals = None, paths = None, image_path_prefix = None, image_directory = None, circlescale = 1.0, vectorscale = 1.0, cbmax = None, showimage = True, extratitle = None, return_plot_args = False, **kwargs): r'''Visualize calibration residuals for a single observation SYNOPSIS model = mrcal.cameramodel(model_filename) mrcal.show_residuals_board_observation( model.optimization_inputs(), 0, from_worst = True ) ... A plot pops up showing the worst-fitting chessboard observation from ... the calibration run that produced the model in model_filename Given a calibration solve, visualizes the fit for a single observation. Plots the chessboard image overlaid with its residuals. Each residual is plotted as a circle and a vector. The circles are color-coded by the residual error. The size of the circle indicates the weight. Bigger means higher weight. The vector shows the weighted residual from the observation to the prediction. ARGUMENTS - optimization_inputs: the optimization inputs dict passed into and returned from mrcal.optimize(). This describes the solved optimization problem that we're visualizing - i_observation: integer that selects the chessboard observation. If not from_worst (the default), this indexes sequential observations, in the order in which they appear in the optimization problem. If from_worst: the observations are indexed in order from the worst-fitting to the best-fitting: i_observation=0 refers to the worst-fitting observation. This is very useful to investigate issues in the calibration - from_worst: optional boolean, defaulting to False. If not from_worst (the default), i_observation indexes sequential observations, in the order in which they appear in the optimization problem. If from_worst: the observations are indexed in order from the worst-fitting to the best-fitting: i_observation=0 refers to the worst-fitting observation. This is very useful to investigate issues in the calibration - i_observations_sorted_from_worst: optional iterable of integers used to convert sorted-from-worst observation indices to as-specified observation indices. If omitted or None, this will be recomputed. To use a cached value, pass in a precomputed value. See the sources for an example of how to compute it - residuals: optional numpy array of shape (Nmeasurements,) containing the optimization residuals. If omitted or None, this will be recomputed. To use a cached value, pass the result of mrcal.optimize(**optimization_inputs)['x'] or mrcal.optimizer_callback(**optimization_inputs)[1] - paths: optional iterable of strings, containing image filenames corresponding to each observation. If omitted or None or if the image couldn't be found, the residuals will be plotted without the source image. The path we search is controlled by the image_path_prefix and image_directory options - image_path_prefix: optional argument, defaulting to None, exclusive with "image_directory". If given, the image paths in the "paths" argument are prefixed with the given string. - image_directory: optional argument, defaulting to None, exclusive with "image_path_prefix". If given, we extract the filename from the image path in the "paths" argument, and look for the images in the directory given here instead - circlescale: optional scale factor to adjust the size of the plotted circles. If omitted, a unit scale (1.0) is used. This exists to improve the legibility of the generated plot - vectorscale: optional scale factor to adjust the length of the plotted vectors. If omitted, a unit scale (1.0) is used: this results in the vectors representing pixel errors directly. This exists to improve the legibility of the generated plot - cbmax: optional value, defaulting to None. If given, sets the maximum range of the color map - showimage: optional boolean, defaulting to True. If False, we do NOT plot the image beneath the residuals. - extratitle: optional string to include in the title of the resulting plot. Used to extend the default title string. If kwargs['title'] is given, it is used directly, and the extratitle is ignored - return_plot_args: boolean defaulting to False. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot - **kwargs: optional arguments passed verbatim as plot options to gnuplotlib. Useful to make hardcopies, etc RETURNED VALUES if not return_plot_args (the usual path): we return the gnuplotlib plot object. The plot disappears when this object is destroyed (by the garbage collection, for instance), so save this returned plot object into a variable, even if you're not going to be doing anything with this object. If return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot ''' import gnuplotlib as gp if image_path_prefix is not None and \ image_directory is not None: raise Exception("image_path_prefix and image_directory are mutually exclusive") if residuals is None: # Flattened residuals. The board measurements are at the start of the # array residuals = \ mrcal.optimizer_callback(**optimization_inputs, no_jacobian = True, no_factorization = True)[1] # shape (Nobservations, object_height_n, object_width_n, 3) observations = optimization_inputs['observations_board'] residuals_shape = observations.shape[:-1] + (2,) # shape (Nobservations, object_height_n, object_width_n, 2) residuals = residuals[:np.product(residuals_shape)].reshape(*residuals_shape) if from_worst: if i_observations_sorted_from_worst is None: # shape (Nobservations,) err_per_observation = nps.norm2(nps.clump(residuals, n=-3)) i_observations_sorted_from_worst = \ list(reversed(np.argsort(err_per_observation))) i_observation_from_worst = i_observation i_observation = i_observations_sorted_from_worst[i_observation_from_worst] # shape (Nh*Nw,2) residuals = nps.clump(residuals [i_observation ], n=2) # shape (Nh*Nw,2) obs = nps.clump(observations[i_observation, ..., :2], n=2) # shape (Nh*Nw) weight = nps.clump(observations[i_observation, ..., 2], n=2) # take non-outliers i_inliers = weight > 0. residuals = residuals[i_inliers] # shape (Ninliers,2) weight = weight [i_inliers] # shape (Ninliers,) obs = obs [i_inliers] # shape (Ninliers,2) plot_options = dict(kwargs) if 'title' not in plot_options: title = \ '{}: i_observation={}{}, iframe={}, icam={}, {}RMS_error={:.2f}'. \ format( optimization_inputs['lensmodel'], i_observation, f'({i_observation_from_worst} from worst)' if from_worst else '', *optimization_inputs['indices_frame_camintrinsics_camextrinsics'][i_observation, :2], "" if paths is None else f"path={paths[i_observation]}, ", np.sqrt(np.mean(nps.norm2(residuals)))) if extratitle is not None: title += ": " + extratitle plot_options['title'] = title gp.add_plot_option(plot_options, square = True, cbmin = 0, overwrite = False) if paths is not None and showimage: imagepath = paths[i_observation] if image_path_prefix is not None: imagepath = f"{image_path_prefix}/{imagepath}" elif image_directory is not None: imagepath = f"{image_directory}/{os.path.basename(imagepath)}" if not os.path.exists(imagepath): print(f"WARNING: Couldn't read image at '{imagepath}'", file=sys.stderr) imagepath = None else: imagepath = None if imagepath is not None: # only plot an image overlay if the image exists gp.add_plot_option(plot_options, rgbimage = imagepath, overwrite = True) gp.add_plot_option(plot_options, 'set', 'autoscale noextend') else: icam = optimization_inputs['indices_frame_camintrinsics_camextrinsics'][i_observation, 1] W,H=optimization_inputs['imagersizes'][icam] gp.add_plot_option(plot_options, xrange = [0,W-1], yrange = [H-1,0], overwrite = False) gp.add_plot_option(plot_options, 'unset', 'key') if cbmax is not None: gp.add_plot_option(plot_options, cbmax = cbmax) data_tuples = \ ( # Points. Color indicates error. Size indicates level. Bigger = # more confident = higher weight (obs[:,0], obs[:,1], 3. * weight * circlescale, # size nps.mag(residuals), # color dict(_with = 'points pt 7 ps variable palette', tuplesize = 4)), # Vectors. From observation to prediction. Scaled by the weight. # Vector points AT the prediction only if weight = 1 (obs[:,0], obs[:,1], vectorscale*residuals[:,0], vectorscale*residuals[:,1], dict(_with = 'vectors filled lw 2', tuplesize = 4)) ) if not return_plot_args: plot = gp.gnuplotlib(**plot_options) plot.plot(*data_tuples) return plot return (data_tuples, plot_options) def show_residuals_histogram(optimization_inputs, icam_intrinsics = None, residuals = None, *, binwidth = 0.02, extratitle = None, return_plot_args = False, **kwargs): r'''Visualize the distribution of the optimized residuals SYNOPSIS model = mrcal.cameramodel(model_filename) mrcal.show_residuals_histogram( model.optimization_inputs() ) ... A plot pops up showing the empirical distribution of fit errors ... in this solve. For ALL the cameras Given a calibration solve, visualizes the distribution of errors at the optimal solution. We display a histogram of residuals and overlay it with an idealized gaussian distribution. ARGUMENTS - optimization_inputs: the optimization inputs dict passed into and returned from mrcal.optimize(). This describes the solved optimization problem that we're visualizing - icam_intrinsics: optional integer to select the camera whose residuals we're visualizing If omitted or None, we display the residuals for ALL the cameras together. - residuals: optional numpy array of shape (Nmeasurements,) containing the optimization residuals. If omitted or None, this will be recomputed. To use a cached value, pass the result of mrcal.optimize(**optimization_inputs)['x'] or mrcal.optimizer_callback(**optimization_inputs)[1] - binwidth: optional floating-point value selecting the width of each bin in the computed histogram. A default of 0.02 pixels is used if this value is omitted. - extratitle: optional string to include in the title of the resulting plot. Used to extend the default title string. If kwargs['title'] is given, it is used directly, and the extratitle is ignored - return_plot_args: boolean defaulting to False. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot - **kwargs: optional arguments passed verbatim as plot options to gnuplotlib. Useful to make hardcopies, etc RETURNED VALUES if not return_plot_args (the usual path): we return the gnuplotlib plot object. The plot disappears when this object is destroyed (by the garbage collection, for instance), so save this returned plot object into a variable, even if you're not going to be doing anything with this object. If return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot ''' import gnuplotlib as gp if 'observations_board' in optimization_inputs and \ optimization_inputs['observations_board'] is not None: x_chessboard = \ mrcal.residuals_board(optimization_inputs = optimization_inputs, icam_intrinsics = icam_intrinsics, residuals = residuals).ravel() else: x_chessboard = np.array(()) if 'observations_point' in optimization_inputs and \ optimization_inputs['observations_point'] is not None: x_point = \ mrcal.residuals_point(optimization_inputs = optimization_inputs, icam_intrinsics = icam_intrinsics, residuals = residuals).ravel() else: x_point = np.array(()) # I just pool all the observations together for now. I could display them # separately... x = nps.glue(x_chessboard, x_point, axis=-1) if x.size == 0: raise Exception("No board or point observations in this solve!") sigma_observed = np.std(x) equation = fitted_gaussian_equation(sigma = sigma_observed, mean = np.mean(x), N = len(x), binwidth = binwidth, legend = f'Normal distribution of residuals with observed stdev: {sigma_observed:.02f} pixels') if icam_intrinsics is None: what = 'all the cameras' else: what = f"camera {icam_intrinsics}" plot_options = dict(kwargs) if 'title' not in plot_options: title = f'Distribution of fitted residuals and a gaussian fit for {what}' if extratitle is not None: title += ": " + extratitle plot_options['title'] = title gp.add_plot_option(plot_options, equation_above = equation, overwrite = True) gp.add_plot_option(plot_options, xlabel = 'Residuals (pixels). x and y components of error are counted separately', ylabel = 'Observed frequency', overwrite = False) data_tuples = [ (x, dict(histogram = True, binwidth = binwidth)) ] if not return_plot_args: plot = gp.gnuplotlib(**plot_options) plot.plot(*data_tuples) return plot return (data_tuples, plot_options) def _get_show_residuals_data_onecam(model, # shape (Nobservations,object_height_n,object_width_n,2) residuals, valid_intrinsics_region): r'''Return the data used by the various show_residuals_...() functions icam is the camera in question, or None for ALL the cameras''' optimization_inputs = model.optimization_inputs() icam_intrinsics = model.icam_intrinsics() if 'observations_board' in optimization_inputs and \ optimization_inputs['observations_board'] is not None: # shape (N,2), (N,2) err_chessboard,obs_chessboard = \ mrcal.residuals_board(optimization_inputs = optimization_inputs, icam_intrinsics = icam_intrinsics, residuals = residuals, return_observations = True) else: err_chessboard,obs_chessboard = \ np.array(()),np.array(()) if 'observations_point' in optimization_inputs and \ optimization_inputs['observations_point'] is not None: # shape (N,2), (N,2) err_point,obs_point = \ mrcal.residuals_point(optimization_inputs = optimization_inputs, icam_intrinsics = icam_intrinsics, residuals = residuals, return_observations = True) else: err_point,obs_point = \ np.array(()),np.array(()) # I just pool all the observations together for now. I could display them # separately... err = nps.glue(err_chessboard, err_point, axis=-1) obs = nps.glue(obs_chessboard, obs_point, axis=-1) if valid_intrinsics_region and icam_intrinsics is not None: legend = "Valid-intrinsics region" valid_region = model.valid_intrinsics_region() if valid_region.size == 0: valid_region = np.zeros((1,2)) legend += ": empty" valid_intrinsics_region_plotarg_3d = \ (valid_region[:,0], valid_region[:,1], np.zeros(valid_region.shape[-2]), dict(_with = 'lines lw 4 lc "green"', legend = legend)) valid_intrinsics_region_plotarg_2d = \ (valid_region[:,0], valid_region[:,1], dict(_with = 'lines lw 4 lc "green"', legend = legend)) else: valid_intrinsics_region_plotarg_2d = None valid_intrinsics_region_plotarg_3d = None return \ err, \ obs, \ valid_intrinsics_region_plotarg_2d, \ valid_intrinsics_region_plotarg_3d def show_residuals_vectorfield(model, residuals = None, *, vectorscale = 1.0, cbmax = None, valid_intrinsics_region = True, extratitle = None, return_plot_args = False, **kwargs): r'''Visualize the optimized residuals as a vector field SYNOPSIS model = mrcal.cameramodel(model_filename) mrcal.show_residuals_vectorfield( model ) ... A plot pops up showing each observation from this camera used to ... compute this calibration as a vector field. Each vector shows the ... observed and predicted location of each chessboard corner Given a calibration solve, visualizes the errors at the optimal solution as a vector field. Each vector runs from the observed chessboard corner to its prediction at the optimal solution. ARGUMENTS - model: the mrcal.cameramodel object representing the camera model we're investigating. This cameramodel MUST contain the optimization_inputs data - residuals: optional numpy array of shape (Nmeasurements,) containing the optimization residuals. If omitted or None, this will be recomputed. To use a cached value, pass the result of mrcal.optimize(**optimization_inputs)['x'] or mrcal.optimizer_callback(**optimization_inputs)[1] - vectorscale: optional scale factor to adjust the length of the plotted vectors. If omitted, a unit scale (1.0) is used. Any other scale factor makes the tip of each vector run past (or short) of the predicted corner position. This exists to improve the legibility of the generated plot - cbmax: optional value, defaulting to None. If given, sets the maximum range of the color map - valid_intrinsics_region: optional boolean, defaulting to True. If valid_intrinsics_region: the valid-intrinsics region present in the model is shown in the plot. This is usually interesting to compare to the set of observations plotted by the rest of this function - extratitle: optional string to include in the title of the resulting plot. Used to extend the default title string. If kwargs['title'] is given, it is used directly, and the extratitle is ignored - return_plot_args: boolean defaulting to False. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot - **kwargs: optional arguments passed verbatim as plot options to gnuplotlib. Useful to make hardcopies, etc RETURNED VALUES if not return_plot_args (the usual path): we return the gnuplotlib plot object. The plot disappears when this object is destroyed (by the garbage collection, for instance), so save this returned plot object into a variable, even if you're not going to be doing anything with this object. If return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot ''' import gnuplotlib as gp err,obs, \ valid_intrinsics_region_plotarg_2d, \ valid_intrinsics_region_plotarg_3d = \ _get_show_residuals_data_onecam(model, residuals, valid_intrinsics_region) W,H = model.imagersize() plot_options = dict(kwargs) if 'title' not in plot_options: title = 'Fitted residuals. Errors shown as vectors and colors' if extratitle is not None: title += ": " + extratitle plot_options['title'] = title gp.add_plot_option(plot_options, square = True, _xrange = [0,W], yrange=[H,0], xlabel = 'Imager x', ylabel = 'Imager y', overwrite = False) if cbmax is not None: gp.add_plot_option(plot_options, cbrange = [0,cbmax]) data_tuples = [(obs[:,0], obs[:,1], vectorscale*err[:,0], vectorscale*err[:,1], np.sqrt(nps.norm2(err)), dict(_with='vectors filled palette', tuplesize=5))] if valid_intrinsics_region_plotarg_2d is not None: data_tuples.append(valid_intrinsics_region_plotarg_2d) if not return_plot_args: plot = gp.gnuplotlib(**plot_options) plot.plot(*data_tuples) return plot return (data_tuples, plot_options) def show_residuals_magnitudes(model, residuals = None, *, cbmax = None, valid_intrinsics_region = True, extratitle = None, return_plot_args = False, **kwargs): r'''Visualize the optimized residual magnitudes as color-coded points SYNOPSIS model = mrcal.cameramodel(model_filename) mrcal.show_residuals_magnitudes( model ) ... A plot pops up showing each observation from this camera used to ... compute this calibration. Each displayed point represents an ... observation and its fit error coded as a color Given a calibration solve, visualizes the errors at the optimal solution. Each point sits at the observed chessboard corner, with its color representing how well the solved model fits the observation ARGUMENTS - model: the mrcal.cameramodel object representing the camera model we're investigating. This cameramodel MUST contain the optimization_inputs data - residuals: optional numpy array of shape (Nmeasurements,) containing the optimization residuals. If omitted or None, this will be recomputed. To use a cached value, pass the result of mrcal.optimize(**optimization_inputs)['x'] or mrcal.optimizer_callback(**optimization_inputs)[1] - cbmax: optional value, defaulting to None. If given, sets the maximum range of the color map - valid_intrinsics_region: optional boolean, defaulting to True. If valid_intrinsics_region: the valid-intrinsics region present in the model is shown in the plot. This is usually interesting to compare to the set of observations plotted by the rest of this function - extratitle: optional string to include in the title of the resulting plot. Used to extend the default title string. If kwargs['title'] is given, it is used directly, and the extratitle is ignored - return_plot_args: boolean defaulting to False. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot - **kwargs: optional arguments passed verbatim as plot options to gnuplotlib. Useful to make hardcopies, etc RETURNED VALUES if not return_plot_args (the usual path): we return the gnuplotlib plot object. The plot disappears when this object is destroyed (by the garbage collection, for instance), so save this returned plot object into a variable, even if you're not going to be doing anything with this object. If return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot ''' import gnuplotlib as gp err,obs, \ valid_intrinsics_region_plotarg_2d, \ valid_intrinsics_region_plotarg_3d = \ _get_show_residuals_data_onecam(model, residuals, valid_intrinsics_region) W,H = model.imagersize() plot_options = dict(kwargs) if 'title' not in plot_options: title = 'Fitted residuals. Errors shown as colors' if extratitle is not None: title += ": " + extratitle plot_options['title'] = title gp.add_plot_option(plot_options, square = True, _xrange = [0,W], yrange=[H,0], xlabel = 'Imager x', ylabel = 'Imager y', overwrite = False) if cbmax is not None: gp.add_plot_option(plot_options, cbrange = [0,cbmax]) data_tuples = [( obs[:,0], obs[:,1], np.sqrt(nps.norm2(err)), dict(_with='points pt 7 palette', tuplesize=3))] if valid_intrinsics_region_plotarg_2d is not None: data_tuples.append(valid_intrinsics_region_plotarg_2d) if not return_plot_args: plot = gp.gnuplotlib(**plot_options) plot.plot(*data_tuples) return plot return (data_tuples, plot_options) def show_residuals_directions(model, residuals = None, *, valid_intrinsics_region = True, extratitle = None, return_plot_args = False, **kwargs): r'''Visualize the optimized residual directions as color-coded points SYNOPSIS model = mrcal.cameramodel(model_filename) mrcal.show_residuals_directions( model ) ... A plot pops up showing each observation from this camera used to ... compute this calibration. Each displayed point represents an ... observation and the direction of its fit error coded as a color Given a calibration solve, visualizes the errors at the optimal solution. Each point sits at the observed chessboard corner, with its color representing the direction of the fit error. Magnitudes are ignored: large errors and small errors are displayed identically as long as they're off in the same direction. This is very useful to detect systematic errors in a solve due to an insufficiently-flexible camera model. ARGUMENTS - model: the mrcal.cameramodel object representing the camera model we're investigating. This cameramodel MUST contain the optimization_inputs data - residuals: optional numpy array of shape (Nmeasurements,) containing the optimization residuals. If omitted or None, this will be recomputed. To use a cached value, pass the result of mrcal.optimize(**optimization_inputs)['x'] or mrcal.optimizer_callback(**optimization_inputs)[1] - valid_intrinsics_region: optional boolean, defaulting to True. If valid_intrinsics_region: the valid-intrinsics region present in the model is shown in the plot. This is usually interesting to compare to the set of observations plotted by the rest of this function - extratitle: optional string to include in the title of the resulting plot. Used to extend the default title string. If kwargs['title'] is given, it is used directly, and the extratitle is ignored - return_plot_args: boolean defaulting to False. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot - **kwargs: optional arguments passed verbatim as plot options to gnuplotlib. Useful to make hardcopies, etc RETURNED VALUES if not return_plot_args (the usual path): we return the gnuplotlib plot object. The plot disappears when this object is destroyed (by the garbage collection, for instance), so save this returned plot object into a variable, even if you're not going to be doing anything with this object. If return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot ''' import gnuplotlib as gp err,obs, \ valid_intrinsics_region_plotarg_2d, \ valid_intrinsics_region_plotarg_3d = \ _get_show_residuals_data_onecam(model, residuals, valid_intrinsics_region) W,H = model.imagersize() plot_options = dict(kwargs) if 'title' not in plot_options: title = 'Fitted residuals. Directions shown as colors. Magnitudes ignored' if extratitle is not None: title += ": " + extratitle plot_options['title'] = title # Use an maximum-saturation, maximum-value HSV # palette where the hue encodes the error direction. # The direction is periodic, as is the hue gp.add_plot_option(plot_options, 'set', 'palette defined ( 0 "#00ffff", 0.5 "#80ffff", 1 "#ffffff") model HSV') gp.add_plot_option(plot_options, square = True, _xrange = [0,W], yrange=[H,0], xlabel = 'Imager x', ylabel = 'Imager y', cbrange = [-180., 180.], overwrite = False) data_tuples = [( obs[:,0], obs[:,1], 180./np.pi * np.arctan2(err[...,1], err[...,0]), dict(_with='points pt 7 palette', tuplesize=3))] if valid_intrinsics_region_plotarg_2d is not None: data_tuples.append(valid_intrinsics_region_plotarg_2d) if not return_plot_args: plot = gp.gnuplotlib(**plot_options) plot.plot(*data_tuples) return plot return (data_tuples, plot_options) def show_residuals_regional(model, residuals = None, *, gridn_width = 20, gridn_height = None, valid_intrinsics_region = True, extratitle = None, return_plot_args = False, **kwargs): r'''Visualize the optimized residuals, broken up by region SYNOPSIS model = mrcal.cameramodel(model_filename) mrcal.show_residuals_regional( model ) ... Three plots pop up, showing the mean, standard deviation and the count ... of residuals in each region in the imager This serves as a simple method of estimating calibration reliability, without computing the projection uncertainty. The imager of a camera is subdivided into bins (controlled by the gridn_width, gridn_height arguments). The residual statistics are then computed for each bin separately. We can then clearly see areas of insufficient data (observation counts will be low). And we can clearly see lens-model-induced biases (non-zero mean) and we can see heteroscedasticity (uneven standard deviation). The mrcal-calibrate-cameras tool uses these metrics to construct a valid-intrinsics region for the models it computes. This serves as a quick/dirty method of modeling projection reliability, which can be used even if projection uncertainty cannot be computed. ARGUMENTS - model: the mrcal.cameramodel object representing the camera model we're investigating. This cameramodel MUST contain the optimization_inputs data - gridn_width: optional value, defaulting to 20. How many bins along the horizontal gridding dimension - gridn_height: how many bins along the vertical gridding dimension. If None, we compute an integer gridn_height to maintain a square-ish grid: gridn_height/gridn_width ~ imager_height/imager_width - residuals: optional numpy array of shape (Nmeasurements,) containing the optimization residuals. If omitted or None, this will be recomputed. To use a cached value, pass the result of mrcal.optimize(**optimization_inputs)['x'] or mrcal.optimizer_callback(**optimization_inputs)[1] - valid_intrinsics_region: optional boolean, defaulting to True. If valid_intrinsics_region: the valid-intrinsics region present in the model is shown in the plot. This is usually interesting to compare to the set of observations plotted by the rest of this function - extratitle: optional string to include in the title of the resulting plot. Used to extend the default title string. If kwargs['title'] is given, it is used directly, and the extratitle is ignored - return_plot_args: boolean defaulting to False. if return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot - **kwargs: optional arguments passed verbatim as plot options to gnuplotlib. Useful to make hardcopies, etc. A "hardcopy" here is a base name: kwargs['hardcopy']="/a/b/c/d.pdf" will produce plots in "/a/b/c/d.XXX.pdf" where XXX is the type of plot being made RETURNED VALUES if not return_plot_args (the usual path): we return the gnuplotlib plot object. The plot disappears when this object is destroyed (by the garbage collection, for instance), so save this returned plot object into a variable, even if you're not going to be doing anything with this object. If return_plot_args: we return a (data_tuples, plot_options) tuple instead of making the plot. The plot can then be made with gp.plot(*data_tuples, **plot_options). Useful if we want to include this as a part of a more complex plot ''' import gnuplotlib as gp err,obs, \ valid_intrinsics_region_plotarg_2d, \ valid_intrinsics_region_plotarg_3d = \ _get_show_residuals_data_onecam(model, residuals, valid_intrinsics_region) # Each has shape (Nheight,Nwidth) mean,stdev,count,using = \ mrcal.calibration._report_regional_statistics(model) def mkplot(x, title, **plot_options): plot_options.update(kwargs) if 'hardcopy' in plot_options and plot_options['hardcopy'] is not None: # hardcopy "/a/b/c/d.pdf" -> "/a/b/c/d.stdev.pdf" where "stdev" is # the "what" without special characters what = re.sub('[^a-zA-Z0-9_-]+', '_', title) plot_options['hardcopy'] = re.sub(r'(\.[^\.]+$)', '.' + what + r'\1', plot_options['hardcopy']) print(f"Writing '{plot_options['hardcopy']}'") if 'title' not in plot_options: if extratitle is not None: title += ": " + extratitle plot_options['title'] = title gp.add_plot_option(plot_options, 'set', ('xrange [:] noextend', 'yrange [:] noextend reverse', 'view equal xy', 'view map')) gp.add_plot_option(plot_options, 'unset', 'grid') gp.add_plot_option(plot_options, _3d = True, ascii = True, overwrite = True) W,H = model.imagersize() gp.add_plot_option(plot_options, _xrange = [0,W], _yrange = [H,0], overwrite = False) data_tuples = [( x, dict(tuplesize=3, _with='image', using=using))] if valid_intrinsics_region_plotarg_3d is not None: data_tuples.append(valid_intrinsics_region_plotarg_3d) if not return_plot_args: plot = gp.gnuplotlib(**plot_options) plot.plot(*data_tuples) return plot return (data_tuples, plot_options) return \ [ mkplot(np.abs(mean), 'abs(mean)'), mkplot(stdev, 'stdev'), mkplot(count, 'count', cbrange = (0, 20)) ] mrcal-2.4.1/num_intrinsics_optimization_params.docstring000066400000000000000000000047411456301662300237630ustar00rootroot00000000000000Get the number of optimization parameters for a single camera's intrinsics SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') f( m.optimization_inputs() ) ... def f(optimization_inputs): Nstates = mrcal.num_intrinsics_optimization_params(**optimization_inputs) ... Return the number of parameters used in the optimization of the intrinsics of a camera. The optimization algorithm sees its world described in one, big vector of state. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. This function reports how many optimization parameters are used to represent the intrinsics of a single camera. This is very similar to mrcal.lensmodel_num_params(), except THIS function takes into account the do_optimize_intrinsics_... variables used to lock down some parts of the intrinsics vector. Similarly, we have mrcal.num_states_intrinsics(), which takes into account the optimization details also, but reports the number of variables needed to describe ALL the cameras instead of just one. In order to determine the variable mapping, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_calobject_warp do_optimize_frames optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting the number of optimization parameters used to describe the intrinsics of a single camera mrcal-2.4.1/num_measurements.docstring000066400000000000000000000051001456301662300201230ustar00rootroot00000000000000Return how many measurements we have in the full optimization problem SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() x,J = mrcal.optimizer_callback(**optimization_inputs)[1:3] Nmeas = mrcal.num_measurements(**optimization_inputs) print(x.shape[0] - Nmeas) ===> 0 print(J.shape[0] - Nmeas) ===> 0 The optimization algorithm tries to minimize the norm of a "measurements" vector x. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. The mrcal.num_measurements_...() functions report where particular items end up in the vector of measurements. THIS function reports the total number of measurements we have. This corresponds to the number of elements in the vector x and to the number of rows in the jacobian matrix J. In order to determine the mapping, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_frames do_optimize_calobject_warp do_apply_regularization optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed Nobservations_board Nobservations_point calibration_object_width_n calibration_object_height_n optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting the size of the measurement vector x mrcal-2.4.1/num_measurements_boards.docstring000066400000000000000000000053201456301662300214610ustar00rootroot00000000000000Return how many measurements we have from calibration object observations SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() x = mrcal.optimizer_callback(**optimization_inputs)[1] Nmeas = mrcal.num_measurements_boards ( **optimization_inputs) i_meas0 = mrcal.measurement_index_boards(0, **optimization_inputs) x_boards_all = x[i_meas0:i_meas0+Nmeas] The optimization algorithm tries to minimize the norm of a "measurements" vector x. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. The mrcal.num_measurements_...() functions report how many measurements are produced by particular items. THIS function reports how many measurements come from the observations of the calibration object. When solving calibration problems, most if not all of the measurements will come from these observations. These are stored contiguously. In order to determine the layout, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_frames do_optimize_calobject_warp do_apply_regularization optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed Nobservations_board Nobservations_point calibration_object_width_n calibration_object_height_n optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting how many elements of the measurement vector x come from the calibration object observations mrcal-2.4.1/num_measurements_points.docstring000066400000000000000000000053021456301662300215230ustar00rootroot00000000000000Return how many measurements we have from point observations SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() x = mrcal.optimizer_callback(**optimization_inputs)[1] Nmeas = mrcal.num_measurements_points( **optimization_inputs) i_meas0 = mrcal.measurement_index_points(0, **optimization_inputs) x_points_all = x[i_meas0:i_meas0+Nmeas] The optimization algorithm tries to minimize the norm of a "measurements" vector x. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. The mrcal.num_measurements_...() functions report how many measurements are produced by particular items. THIS function reports how many measurements come from the observations of discrete points. When solving structure-from-motion problems, most if not all of the measurements will come from these observations. These are stored contiguously. In order to determine the layout, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_frames do_optimize_calobject_warp do_apply_regularization optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed Nobservations_board Nobservations_point calibration_object_width_n calibration_object_height_n optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting how many elements of the measurement vector x come from observations of discrete points mrcal-2.4.1/num_measurements_regularization.docstring000066400000000000000000000053761456301662300232610ustar00rootroot00000000000000Return how many measurements we have from regularization SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() x = mrcal.optimizer_callback(**optimization_inputs)[1] Nmeas = mrcal.num_measurements_regularization( **optimization_inputs) i_meas0 = mrcal.measurement_index_regularization(**optimization_inputs) x_regularization = x[i_meas0:i_meas0+Nmeas] The optimization algorithm tries to minimize the norm of a "measurements" vector x. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. The mrcal.num_measurements_...() functions report where particular items end up in the vector of measurements. THIS function reports how many measurements come from the regularization terms of the optimization problem. These don't model physical effects, but guide the solver away from obviously-incorrect solutions, and resolve ambiguities. This helps the solver converge to the right solution, quickly. In order to determine the layout, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_frames do_optimize_calobject_warp do_apply_regularization optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed Nobservations_board Nobservations_point calibration_object_width_n calibration_object_height_n optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting how many elements of the measurement vector x come from regularization terms mrcal-2.4.1/num_states.docstring000066400000000000000000000044251456301662300167270ustar00rootroot00000000000000Get the total number of parameters in the optimization vector SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') f( m.optimization_inputs() ) ... def f(optimization_inputs): Nstates = mrcal.num_states (**optimization_inputs) ... The optimization algorithm sees its world described in one, big vector of state. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. The mrcal.num_states_...() functions report how many variables in the optimization vector are taken up by each particular kind of measurement. THIS function reports how many variables are used to represent the FULL state vector. In order to determine the variable mapping, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_calobject_warp do_optimize_frames optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting the total variable count in the state vector mrcal-2.4.1/num_states_calobject_warp.docstring000066400000000000000000000054521456301662300217670ustar00rootroot00000000000000Get the number of parameters in the optimization vector for the board warp SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() b = mrcal.optimizer_callback(**optimization_inputs)[0] mrcal.unpack_state(b, **optimization_inputs) i_state0 = mrcal.state_index_calobject_warp(**optimization_inputs) Nstates = mrcal.num_states_calobject_warp (**optimization_inputs) calobject_warp = b[i_state0:i_state0+Nstates] The optimization algorithm sees its world described in one, big vector of state. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. The mrcal.num_states_...() functions report how many variables in the optimization vector are taken up by each particular kind of measurement. THIS function reports how many variables are used to represent the calibration-object warping. This is stored contiguously as in memory. These warping parameters describe how the observed calibration object differs from the expected calibration object. There will always be some difference due to manufacturing tolerances and temperature and humidity effects. In order to determine the variable mapping, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_calobject_warp do_optimize_frames optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed Nobservations_board optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting the variable count of the calibration object warping parameters mrcal-2.4.1/num_states_extrinsics.docstring000066400000000000000000000060221456301662300211750ustar00rootroot00000000000000Get the number of extrinsics parameters in the optimization vector SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() b = mrcal.optimizer_callback(**optimization_inputs)[0] mrcal.unpack_state(b, **optimization_inputs) i_state0 = mrcal.state_index_extrinsics(0, **optimization_inputs) Nstates = mrcal.num_states_extrinsics ( **optimization_inputs) extrinsics_rt_fromref_all = b[i_state0:i_state0+Nstates] The optimization algorithm sees its world described in one, big vector of state. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. The mrcal.num_states_...() functions report how many variables in the optimization vector are taken up by each particular kind of measurement. THIS function reports how many variables are used to represent ALL the camera extrinsics. The extrinsics are stored contiguously as an "rt transformation": a 3-element rotation represented as a Rodrigues vector followed by a 3-element translation. These transform points represented in the reference coordinate system to the coordinate system of the specific camera. Note that mrcal allows the reference coordinate system to be tied to a particular camera. In this case the extrinsics of that camera do not appear in the state vector at all, and icam_extrinsics == -1 in the indices_frame_camintrinsics_camextrinsics array. In order to determine the variable mapping, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_calobject_warp do_optimize_frames optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting the variable count of extrinsics in the state vector mrcal-2.4.1/num_states_frames.docstring000066400000000000000000000055341456301662300202660ustar00rootroot00000000000000Get the number of calibration object pose parameters in the optimization vector SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() b = mrcal.optimizer_callback(**optimization_inputs)[0] mrcal.unpack_state(b, **optimization_inputs) i_state0 = mrcal.state_index_frames(0, **optimization_inputs) Nstates = mrcal.num_states_frames ( **optimization_inputs) frames_rt_toref_all = b[i_state0:i_state0+Nstates] The optimization algorithm sees its world described in one, big vector of state. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. The mrcal.num_states_...() functions report how many variables in the optimization vector are taken up by each particular kind of measurement. THIS function reports how many variables are used to represent ALL the frame poses. Here a "frame" is a pose of the observed calibration object at some instant in time. The frames are stored contiguously as an "rt transformation": a 3-element rotation represented as a Rodrigues vector followed by a 3-element translation. These transform points represented in the internal calibration object coordinate system to the reference coordinate system. In order to determine the variable mapping, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_calobject_warp do_optimize_frames optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting the variable count of frames in the state vector mrcal-2.4.1/num_states_intrinsics.docstring000066400000000000000000000064671456301662300212040ustar00rootroot00000000000000Get the number of intrinsics parameters in the optimization vector SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() b = mrcal.optimizer_callback(**optimization_inputs)[0] mrcal.unpack_state(b, **optimization_inputs) i_state0 = mrcal.state_index_intrinsics(0, **optimization_inputs) Nstates = mrcal.num_states_intrinsics ( **optimization_inputs) intrinsics_all = b[i_state0:i_state0+Nstates] The optimization algorithm sees its world described in one, big vector of state. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. The mrcal.num_states_...() functions report how many variables in the optimization vector are taken up by each particular kind of measurement. THIS function reports how many optimization variables are used to represent ALL the camera intrinsics. The intrinsics are stored contiguously. They consist of a 4-element "intrinsics core" (focallength-x, focallength-y, centerpixel-x, centerpixel-y) followed by a lensmodel-specific vector of "distortions". A similar function mrcal.num_intrinsics_optimization_params() is available to report the number of optimization variables used for just ONE camera. If all the intrinsics are being optimized, then the mrcal.lensmodel_num_params() returns the same value: the number of values needed to describe the intrinsics of a single camera. It is possible to lock down some of the intrinsics during optimization (by setting the do_optimize_intrinsics_... variables appropriately). These variables control what mrcal.num_intrinsics_optimization_params() and mrcal.num_states_intrinsics() return, but not mrcal.lensmodel_num_params(). In order to determine the variable mapping, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_calobject_warp do_optimize_frames optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting the variable count of intrinsics in the state vector mrcal-2.4.1/num_states_points.docstring000066400000000000000000000050601456301662300203170ustar00rootroot00000000000000Get the number of point-position parameters in the optimization vector SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() b = mrcal.optimizer_callback(**optimization_inputs)[0] mrcal.unpack_state(b, **optimization_inputs) i_state0 = mrcal.state_index_points(0, **optimization_inputs) Nstates = mrcal.num_states_points ( **optimization_inputs) points_all = b[i_state0:i_state0+Nstates] The optimization algorithm sees its world described in one, big vector of state. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. The mrcal.num_states_...() functions report how many variables in the optimization vector are taken up by each particular kind of measurement. THIS function reports how many variables are used to represent ALL the points. The points are stored contiguously as a 3-element coordinates in the reference frame. In order to determine the variable mapping, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_calobject_warp do_optimize_frames optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting the variable count of points in the state vector mrcal-2.4.1/optimize.docstring000066400000000000000000000244331456301662300164060ustar00rootroot00000000000000Invoke the calibration routine SYNOPSIS stats = mrcal.optimize( intrinsics_data, extrinsics_rt_fromref, frames_rt_toref, points, observations_board, indices_frame_camintrinsics_camextrinsics, observations_point, indices_point_camintrinsics_camextrinsics, lensmodel, imagersizes = imagersizes, do_optimize_intrinsics_core = True, do_optimize_intrinsics_distortions= True, calibration_object_spacing = object_spacing, point_min_range = 0.1, point_max_range = 100.0, do_apply_outlier_rejection = True, do_apply_regularization = True, verbose = False) Please see the mrcal documentation at http://mrcal.secretsauce.net/formulation.html for details. This is a flexible implementation of a calibration system core that uses sparse Jacobians, performs outlier rejection and reports some metrics back to the user. Measurements from any number of cameras can beat used simultaneously, and this routine is flexible-enough to solve structure-from-motion problems. The input is a combination of observations of a calibration board and observations of discrete points. The point observations MAY have a known range. The cameras and what they're observing is given in the arrays - intrinsics_data - extrinsics_rt_fromref - frames_rt_toref - points - indices_frame_camintrinsics_camextrinsics - indices_point_camintrinsics_camextrinsics intrinsics_data contains the intrinsics for all the physical cameras present in the problem. len(intrinsics_data) = Ncameras_intrinsics extrinsics_rt_fromref contains all the camera poses present in the problem, omitting any cameras that sit at the reference coordinate system. len(extrinsics_rt_fromref) = Ncameras_extrinsics. frames_rt_toref is all the poses of the calibration board in the problem, and points is all the discrete points being observed in the problem. indices_frame_camintrinsics_camextrinsics describes which board observations were made by which camera, and where this camera was. Each board observation is described by a tuple (iframe,icam_intrinsics,icam_extrinsics). The board at frames_rt_toref[iframe] was observed by camera intrinsics_data[icam_intrinsics], which was at extrinsics_rt_fromref[icam_extrinsics] indices_point_camintrinsics_camextrinsics is the same thing for discrete points. If we're solving a vanilla calibration problem, we have stationary cameras observing a moving target. By convention, camera 0 is at the reference coordinate system. So - Ncameras_intrinsics = Ncameras_extrinsics+1 - All entries in indices_frame_camintrinsics_camextrinsics have icam_intrinsics = icam_extrinsics+1 - frames_rt_toref, points describes the motion of the moving target we're observing Conversely, in a structure-from-motion problem we have some small number of moving cameras (often just 1) observing stationary target(s). We would have - Ncameras_intrinsics is small: it's how many physical cameras we have - Ncameras_extrinsics is large: it describes the motion of the cameras - frames_rt_toref, points is small: it describes the non-moving world we're observing Any combination of these extreme cases is allowed. REQUIRED ARGUMENTS - intrinsics: array of dims (Ncameras_intrinsics, Nintrinsics). The intrinsics of each physical camera. Each intrinsic vector is given as (focal_x, focal_y, center_pixel_x, center_pixel_y, distortion0, distortion1, ...) The focal lengths are given in pixels. On input this is a seed. On output the optimal data is returned. THIS ARRAY IS MODIFIED BY THIS CALL. - extrinsics_rt_fromref: array of dims (Ncameras_extrinsics, 6). The pose of each camera observation. Each pose is given as 6 values: a Rodrigues rotation vector followed by a translation. This represents a transformation FROM the reference coord system TO the coord system of each camera. On input this is a seed. On output the optimal data is returned. THIS ARRAY IS MODIFIED BY THIS CALL. If we only have one camera, pass either None or np.zeros((0,6)) - frames_rt_toref: array of dims (Nframes, 6). The poses of the calibration object over time. Each pose is given as 6 values: a rodrigues rotation vector followed by a translation. This represents a transformation FROM the coord system of the calibration object TO the reference coord system. THIS IS DIFFERENT FROM THE CAMERA EXTRINSICS. On input this is a seed. On output the optimal data is returned. THIS ARRAY IS MODIFIED BY THIS CALL. If we don't have any frames, pass either None or np.zeros((0,6)) - points: array of dims (Npoints, 3). The estimated positions of discrete points we're observing. These positions are represented in the reference coord system. The initial Npoints-Npoints_fixed points are optimized by this routine. The final Npoints_fixed points are fixed. By default Npoints_fixed==0, and we optimize all the points. On input this is a seed. On output the optimal data is returned. THIS ARRAY IS MODIFIED BY THIS CALL. - observations_board: array of dims (Nobservations_board, calibration_object_height_n, calibration_object_width_n, 3). Each slice is an (x,y,weight) tuple where (x,y) are the observed pixel coordinates of the corners in the calibration object, and "weight" is the relative weight of this point observation. Most of the weights are expected to be 1.0, which implies that the noise on that observation has the nominal standard deviation of observed_pixel_uncertainty (in addition to the overall assumption of gaussian noise, independent on x,y). weight<0 indicates that this is an outlier. This is respected on input (even if !do_apply_outlier_rejection). New outliers are marked with weight<0 on output. Subpixel interpolation is assumed, so these contain 64-bit floating point values, like all the other data. The frame and camera that produced these observations are given in the indices_frame_camintrinsics_camextrinsics THIS ARRAY IS MODIFIED BY THIS CALL (to mark outliers) - indices_frame_camintrinsics_camextrinsics: array of dims (Nobservations_board, 3). For each observation these are an (iframe,icam_intrinsics,icam_extrinsics) tuple. icam_extrinsics == -1 means this observation came from a camera in the reference coordinate system. iframe indexes the "frames_rt_toref" array, icam_intrinsics indexes the "intrinsics_data" array, icam_extrinsics indexes the "extrinsics_rt_fromref" array All of the indices are guaranteed to be monotonic. This array contains 32-bit integers. - observations_point: array of dims (Nobservations_point, 3). Each slice is an (x,y,weight) tuple where (x,y) are the pixel coordinates of the observed point, and "weight" is the relative weight of this point observation. Most of the weights are expected to be 1.0, which implies that the noise on the observation is gaussian, independent on x,y, and has the nominal standard deviation of observed_pixel_uncertainty. weight<0 indicates that this is an outlier. This is respected on input (even if !do_apply_outlier_rejection). At this time, no new outliers are detected for point observations. Subpixel interpolation is assumed, so these contain 64-bit floating point values, like all the other data. The point index and camera that produced these observations are given in the indices_point_camera_points array. - indices_point_camintrinsics_camextrinsics: array of dims (Nobservations_point, 3). For each observation these are an (i_point,icam_intrinsics,icam_extrinsics) tuple. Analogous to indices_frame_camintrinsics_camextrinsics, but for observations of discrete points. The indices can appear in any order. No monotonicity is required. This array contains 32-bit integers. - lensmodel: a string such as LENSMODEL_PINHOLE LENSMODEL_OPENCV4 LENSMODEL_CAHVOR LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=16_Ny=12_fov_x_deg=100 LENSMODEL_CAHVORE is explicitly NOT supported at this time since gradients are required - imagersizes: integer array of dims (Ncameras_intrinsics,2) OPTIONAL ARGUMENTS - calobject_warp A numpy array of shape (2,) describing the non-flatness of the calibration board. If omitted or None, the board is assumed to be perfectly flat. And if do_optimize_calobject_warp then we optimize these parameters to find the best-fitting board shape. - Npoints_fixed Specifies how many points at the end of the points array are fixed, and remain unaffected by the optimization. This is 0 by default, and we optimize all the points. - do_optimize_intrinsics_core - do_optimize_intrinsics_distortions - do_optimize_extrinsics - do_optimize_frames - do_optimize_calobject_warp Indicate whether to optimize a specific set of variables. The intrinsics core is fx,fy,cx,cy. These all default to True so if we specify none of these, we will optimize ALL the variables. - calibration_object_spacing: the width of each square in a calibration board. Can be omitted if we have no board observations, just points. The calibration object has shape (calibration_object_height_n,calibration_object_width_n), given by the dimensions of "observations_board" - verbose: if True, write out all sorts of diagnostic data to STDERR. Defaults to False - do_apply_outlier_rejection: if False, don't bother with detecting or rejecting outliers. The outliers we get on input (observations_board[...,2] < 0) are honered regardless. Defaults to True - do_apply_regularization: if False, don't include regularization terms in the solver. Defaults to True - point_min_range, point_max_range: Required ONLY if point observations are given. These are lower, upper bounds for the distance of a point observation to its observing camera. Each observation outside of this range is penalized. This helps the solver by guiding it away from unreasonable solutions. We return a dict with various metrics describing the computation we just performed mrcal-2.4.1/optimizer_callback.docstring000066400000000000000000000076351456301662300204110ustar00rootroot00000000000000Call the optimization callback function SYNOPSIS model = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = model.optimization_inputs() b_packed,x,J_packed,factorization = \ mrcal.optimizer_callback( **optimization_inputs ) Please see the mrcal documentation at http://mrcal.secretsauce.net/formulation.html for details. The main optimization routine in mrcal.optimize() searches for optimal parameters by repeatedly calling a function to evaluate each hypothethical parameter set. This evaluation function is available by itself here, separated from the optimization loop. The arguments are largely the same as those to mrcal.optimize(), but the inputs are all read-only. Some arguments that have meaning in calls to optimize() have no meaning in calls to optimizer_callback(). These are accepted, and effectively ignored. Currently these are: - do_apply_outlier_rejection ARGUMENTS This function accepts lots of arguments, but they're the same as the arguments to mrcal.optimize() so please see that documentation for details. Arguments accepted by optimizer_callback() on top of those in optimize(): - no_jacobian: optional boolean defaulting to False. If True, we do not compute a jacobian, which would speed up this function. We then return None in its place. if no_jacobian and not no_factorization then we still compute and return a jacobian, since it's needed for the factorization - no_factorization: optional boolean defaulting to False. If True, we do not compute a cholesky factorization of JtJ, which would speed up this function. We then return None in its place. if no_jacobian and not no_factorization then we still compute and return a jacobian, since it's needed for the factorization RETURNED VALUES The output is returned in a tuple: - b_packed: a numpy array of shape (Nstate,). This is the packed (unitless) state vector that represents the inputs, as seen by the optimizer. If the optimization routine was running, it would use this as a starting point in the search for different parameters, trying to find those that minimize norm2(x). This packed state can be converted to the expanded representation like this: b = mrcal.optimizer_callback(**optimization_inputs)[0 mrcal.unpack_state(b, **optimization_inputs) - x: a numpy array of shape (Nmeasurements,). This is the error vector. If the optimization routine was running, it would be testing different parameters, trying to find those that minimize norm2(x) - J: a sparse matrix of shape (Nmeasurements,Nstate). These are the gradients of the measurements in respect to the packed parameters. This is a SPARSE array of type scipy.sparse.csr_matrix. This object can be converted to a numpy array like this: b,x,J_sparse = mrcal.optimizer_callback(...)[:3] J_numpy = J_sparse.toarray() Note that the numpy array is dense, so it is very inefficient for sparse data, and working with it could be very memory-intensive and slow. This jacobian matrix comes directly from the optimization callback function, which uses packed, unitless state. To convert a densified packed jacobian to full units, one can do this: J_sparse = mrcal.optimizer_callback(**optimization_inputs)[2] J_numpy = J_sparse.toarray() mrcal.pack_state(J_numpy, **optimization_inputs) Note that we're calling pack_state() instead of unpack_state() because the packed variables are in the denominator - factorization: a Cholesky factorization of JtJ in a mrcal.CHOLMOD_factorization object. The core of the optimization algorithm is solving a linear system JtJ x = b. J is a large, sparse matrix, so we do this with a Cholesky factorization of J using the CHOLMOD library. This factorization is also useful in other contexts, such as uncertainty quantification, so we make it available here. If the factorization could not be computed (because JtJ isn't full-rank for instance), this is set to None mrcal-2.4.1/pack_state.docstring000066400000000000000000000055321456301662300166630ustar00rootroot00000000000000Scales a state vector to the packed, unitless form used by the optimizer SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() Jpacked = mrcal.optimizer_callback(**optimization_inputs)[2].toarray() J = Jpacked.copy() mrcal.pack_state(J, **optimization_inputs) In order to make the optimization well-behaved, we scale all the variables in the state and the gradients before passing them to the optimizer. The internal optimization library thus works only with unitless (or "packed") data. This function takes a full numpy array of shape (...., Nstate), and scales it to produce packed data. This function applies the scaling directly to the input array; the input is modified, and nothing is returned. To unpack a state vector, you naturally call unpack_state(). To unpack a jacobian matrix, you would call pack_state() because in a jacobian, the state is in the denominator. This is shown in the example above. Broadcasting is supported: any leading dimensions will be processed correctly, as long as the given array has shape (..., Nstate). In order to know what the scale factors should be, and how they should map to each variable in the state vector, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - b: a numpy array of shape (..., Nstate). This is the full state on input, and the packed state on output. The input array is modified. - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_calobject_warp do_optimize_frames optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE None. The scaling is applied to the input array mrcal-2.4.1/packaging/000077500000000000000000000000001456301662300145465ustar00rootroot00000000000000mrcal-2.4.1/packaging/README000066400000000000000000000004251456301662300154270ustar00rootroot00000000000000These are sample package definitions for Redhat-based OSs. Debian-based OSs already have mrcal in their repositories; the mrcal Debian git repo is here: https://salsa.debian.org/science-team/mrcal See the documentation for details: http://mrcal.secretsauce.net/install.html mrcal-2.4.1/packaging/rpmpackage.spec000066400000000000000000000040471456301662300175410ustar00rootroot00000000000000Name: mrcal Version: 2.2 Release: 1%{?dist} Summary: Calibration tools License: Apache-2.0 URL: https://www.github.com/dkogan/mrcal/ Source0: https://www.github.com/dkogan/mrcal/archive/%{version}.tar.gz#/%{name}-%{version}.tar.gz BuildRequires: python36-numpy # For the non-global parameters BuildRequires: libdogleg-devel >= 0.15.4 BuildRequires: suitesparse-devel >= 5.4.0 BuildRequires: re2c >= 2 # I want suitesparse >= 5 at runtime. I'm using CHOLMOD_FUNCTION_DEFAULTS, which # makes a reference to SuiteSparse_divcomplex Requires: suitesparse >= 5.4.0 BuildRequires: lapack-devel BuildRequires: python36-devel BuildRequires: python36-libs # I need to run the python stuff in order to build the manpages and to generate # the npsp wrappers BuildRequires: numpysane >= 0.35 BuildRequires: gnuplotlib >= 0.38 BuildRequires: opencv-python36 BuildRequires: python36-scipy BuildRequires: python36 # some tests shell out to vnl-filter BuildRequires: vnlog # for minimath BuildRequires: perl-List-MoreUtils # for mrbuild BuildRequires: chrpath # for the parser BuildRequires: re2c >= 2.0.3 Requires: numpysane >= 0.35 Requires: gnuplotlib >= 0.38 Requires: opencv-python36 Requires: python36-numpy >= 1.14.5 Requires: python36-scipy >= 0.18.1 Requires: python36-shapely Requires: python36 Requires: python36-ipython-console # for image_transformation_map(), not for plotting Requires: python36-matplotlib # for mrcal-stereo --viz stereo Requires: python36-gl-image-display %description Calibration library This is the C library and the python tools %package devel Summary: Development files for %{name} Requires: %{name}%{?_isa} = %{version}-%{release} %description devel This is the headers and DSOs for other C applications to use this library %prep %setup -q %build make %{?_smp_mflags} %install rm -rf $RPM_BUILD_ROOT %make_install %check make test-nosampling %files %doc %{_bindir}/* %{_mandir}/* %{_libdir}/*.so.* %{python3_sitelib}/* %files devel %{_includedir}/* %{_libdir}/*.so mrcal-2.4.1/poseutils-genpywrap.py000077500000000000000000001050131456301662300172400ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Python-wrap the mrcal geometry routines ''' import sys import os import numpy as np import numpysane as nps import numpysane_pywrap as npsp docstring_module = '''Low-level routines to manipulate poses, transformations and points This is the written-in-C Python extension module. Most of the time you want to use the mrcal.poseutils wrapper module instead of this module directly. Any functions not prefixed with "_" are meant to be called directly, without the wrapper. All functions are exported into the mrcal module. So you can call these via mrcal._poseutils.fff() or mrcal.fff(). The latter is preferred. ''' m = npsp.module( name = "_poseutils_npsp", docstring = docstring_module, header = r''' #include "poseutils.h" #include ''') m.function( "identity_R", """Return an identity rotation matrix SYNOPSIS print( mrcal.identity_R() ) ===> [[1. 0. 0.] [0. 1. 0.] [0. 0. 1.]] As with all the poseutils functions, the output can be written directly into a (possibly-non-contiguous) array, by specifying the destination in the 'out' kwarg """, args_input = (), prototype_input = (), prototype_output = (3,3), Ccode_slice_eval = \ {np.float64: r''' mrcal_identity_R_full( (double*)data_slice__output, strides_slice__output[0], strides_slice__output[1] ); return true; '''}) m.function( "identity_r", """Return an identity Rodrigues rotation SYNOPSIS print( mrcal.identity_r() ) ===> [0. 0. 0.] As with all the poseutils functions, the output can be written directly into a (possibly-non-contiguous) array, by specifying the destination in the 'out' kwarg""", args_input = (), prototype_input = (), prototype_output = (3,), Ccode_slice_eval = \ {np.float64: r''' mrcal_identity_r_full( (double*)data_slice__output, strides_slice__output[0] ); return true; '''}) m.function( "identity_Rt", """Return an identity Rt transformation SYNOPSIS print( mrcal.identity_Rt() ) ===> [[1. 0. 0.] [0. 1. 0.] [0. 0. 1.] [0. 0. 0.]] As with all the poseutils functions, the output can be written directly into a (possibly-non-contiguous) array, by specifying the destination in the 'out' kwarg""", args_input = (), prototype_input = (), prototype_output = (4,3), Ccode_slice_eval = \ {np.float64: r''' mrcal_identity_Rt_full( (double*)data_slice__output, strides_slice__output[0], strides_slice__output[1] ); return true; '''}) m.function( "identity_rt", """Return an identity rt transformation SYNOPSIS print( mrcal.identity_rt() ) ===> [0. 0. 0. 0. 0. 0.] As with all the poseutils functions, the output can be written directly into a (possibly-non-contiguous) array, by specifying the destination in the 'out' kwarg""", args_input = (), prototype_input = (), prototype_output = (6,), Ccode_slice_eval = \ {np.float64: r''' mrcal_identity_rt_full( (double*)data_slice__output, strides_slice__output[0] ); return true; '''}) m.function( "_rotate_point_R", """Rotate a point using a rotation matrix This is an internal function. You probably want mrcal.rotate_point_R(). See the docs for that function for details. """, args_input = ('R', 'x'), prototype_input = ((3,3), (3,)), prototype_output = (3,), extra_args = (("int", "inverted", "false", "p"),), Ccode_slice_eval = \ {np.float64: r''' mrcal_rotate_point_R_full( (double*)data_slice__output, strides_slice__output[0], NULL,0,0,0, NULL,0,0, (const double*)data_slice__R, strides_slice__R[0], strides_slice__R[1], (const double*)data_slice__x, strides_slice__x[0], *inverted ); return true; '''}, ) m.function( "_rotate_point_R_withgrad", """Rotate a point using a rotation matrix; report the result and gradients This is an internal function. You probably want mrcal.rotate_point_R(). See the docs for that function for details. """, args_input = ('R', 'x'), prototype_input = ((3,3), (3,)), prototype_output = ((3,), (3,3,3), (3,3)), extra_args = (("int", "inverted", "false", "p"),), Ccode_slice_eval = \ {np.float64: r''' mrcal_rotate_point_R_full( (double*)data_slice__output0, strides_slice__output0[0], (double*)data_slice__output1, strides_slice__output1[0], strides_slice__output1[1], strides_slice__output1[2], (double*)data_slice__output2, strides_slice__output2[0], strides_slice__output2[1], (const double*)data_slice__R, strides_slice__R[0], strides_slice__R[1], (const double*)data_slice__x, strides_slice__x[0], *inverted ); return true; '''}, ) m.function( "_rotate_point_r", """Rotate a point using a Rodrigues vector This is an internal function. You probably want mrcal.rotate_point_r(). See the docs for that function for details. """, args_input = ('r', 'x'), prototype_input = ((3,), (3,)), prototype_output = (3,), extra_args = (("int", "inverted", "false", "p"),), Ccode_slice_eval = \ {np.float64: r''' mrcal_rotate_point_r_full( (double*)data_slice__output, strides_slice__output[0], NULL,0,0, NULL,0,0, (const double*)data_slice__r, strides_slice__r[0], (const double*)data_slice__x, strides_slice__x[0], *inverted); return true; '''}, ) m.function( "_rotate_point_r_withgrad", """Rotate a point using a Rodrigues vector; report the result and gradients This is an internal function. You probably want mrcal.rotate_point_r(). See the docs for that function for details. """, args_input = ('r', 'x'), prototype_input = ((3,), (3,)), prototype_output = ((3,), (3,3), (3,3)), extra_args = (("int", "inverted", "false", "p"),), Ccode_slice_eval = \ {np.float64: r''' mrcal_rotate_point_r_full( (double*)data_slice__output0, strides_slice__output0[0], (double*)data_slice__output1, strides_slice__output1[0], strides_slice__output1[1], (double*)data_slice__output2, strides_slice__output2[0], strides_slice__output2[1], (const double*)data_slice__r, strides_slice__r[0], (const double*)data_slice__x, strides_slice__x[0], *inverted); return true; '''}, ) m.function( "_transform_point_Rt", """Transform a point using an Rt transformation This is an internal function. You probably want mrcal.transform_point_Rt(). See the docs for that function for details. """, args_input = ('Rt', 'x'), prototype_input = ((4,3), (3,)), prototype_output = (3,), extra_args = (("int", "inverted", "false", "p"),), Ccode_slice_eval = \ {np.float64: r''' mrcal_transform_point_Rt_full( (double*)data_slice__output, strides_slice__output[0], NULL,0,0,0, NULL,0,0, (const double*)data_slice__Rt, strides_slice__Rt[0], strides_slice__Rt[1], (const double*)data_slice__x, strides_slice__x[0], *inverted ); return true; '''}, ) m.function( "_transform_point_Rt_withgrad", """Transform a point using an Rt transformation; report the result and gradients This is an internal function. You probably want mrcal.transform_point_Rt(). See the docs for that function for details. """, args_input = ('Rt', 'x'), prototype_input = ((4,3), (3,)), prototype_output = ((3,), (3,4,3), (3,3)), extra_args = (("int", "inverted", "false", "p"),), Ccode_slice_eval = \ {np.float64: r''' mrcal_transform_point_Rt_full( (double*)data_slice__output0, strides_slice__output0[0], (double*)data_slice__output1, strides_slice__output1[0], strides_slice__output1[1], strides_slice__output1[2], (double*)data_slice__output2, strides_slice__output2[0], strides_slice__output2[1], (const double*)data_slice__Rt, strides_slice__Rt[0], strides_slice__Rt[1], (const double*)data_slice__x, strides_slice__x[0], *inverted ); return true; '''}, ) m.function( "_transform_point_rt", """Transform a point using an rt transformation This is an internal function. You probably want mrcal.transform_point_rt(). See the docs for that function for details. """, args_input = ('rt', 'x'), prototype_input = ((6,), (3,)), prototype_output = (3,), extra_args = (("int", "inverted", "false", "p"),), Ccode_slice_eval = \ {np.float64: r''' mrcal_transform_point_rt_full( (double*)data_slice__output, strides_slice__output[0], NULL,0,0, NULL,0,0, (const double*)data_slice__rt, strides_slice__rt[0], (const double*)data_slice__x, strides_slice__x[0], *inverted ); return true; '''}, ) m.function( "_transform_point_rt_withgrad", """Transform a point using an rt transformation; report the result and gradients This is an internal function. You probably want mrcal.transform_point_rt(). See the docs for that function for details. """, args_input = ('rt', 'x'), prototype_input = ((6,), (3,)), prototype_output = ((3,), (3,6), (3,3)), extra_args = (("int", "inverted", "false", "p"),), Ccode_slice_eval = \ {np.float64: r''' mrcal_transform_point_rt_full( (double*)data_slice__output0, strides_slice__output0[0], (double*)data_slice__output1, strides_slice__output1[0], strides_slice__output1[1], (double*)data_slice__output2, strides_slice__output2[0], strides_slice__output2[1], (const double*)data_slice__rt, strides_slice__rt[0], (const double*)data_slice__x, strides_slice__x[0], *inverted ); return true; '''}, ) m.function( "_r_from_R", """Compute a Rodrigues vector from a rotation matrix This is an internal function. You probably want mrcal.r_from_R(). See the docs for that function for details. """, args_input = ('R',), prototype_input = ((3,3),), prototype_output = (3,), Ccode_slice_eval = \ {np.float64: r''' mrcal_r_from_R_full( (double*)data_slice__output,strides_slice__output[0], NULL,0,0,0, (const double*)data_slice__R,strides_slice__R[0], strides_slice__R[1] ); return true; '''} ) m.function( "_r_from_R_withgrad", """Compute a Rodrigues vector from a rotation matrix This is an internal function. You probably want mrcal.r_from_R(). See the docs for that function for details. """, args_input = ('R',), prototype_input = ((3,3),), prototype_output = ((3,),(3,3,3)), Ccode_slice_eval = \ {np.float64: r''' mrcal_r_from_R_full( (double*)data_slice__output0,strides_slice__output0[0], (double*)data_slice__output1,strides_slice__output1[0], strides_slice__output1[1],strides_slice__output1[2], (const double*)data_slice__R,strides_slice__R[0], strides_slice__R[1] ); return true; '''} ) m.function( "_R_from_r", """Compute a rotation matrix from a Rodrigues vector This is an internal function. You probably want mrcal.R_from_r(). See the docs for that function for details. """, args_input = ('r',), prototype_input = ((3,),), prototype_output = (3,3), Ccode_slice_eval = \ {np.float64: r''' mrcal_R_from_r_full( (double*)data_slice__output, strides_slice__output[0], strides_slice__output[1], NULL,0,0,0, (const double*)data_slice__r, strides_slice__r[0] ); return true; '''} ) m.function( "_R_from_r_withgrad", """Compute a rotation matrix from a Rodrigues vector This is an internal function. You probably want mrcal.R_from_r(). See the docs for that function for details. """, args_input = ('r',), prototype_input = ((3,),), prototype_output = ((3,3), (3,3,3)), Ccode_slice_eval = \ {np.float64: r''' mrcal_R_from_r_full( (double*)data_slice__output0,strides_slice__output0[0], strides_slice__output0[1], (double*)data_slice__output1,strides_slice__output1[0], strides_slice__output1[1],strides_slice__output1[2], (const double*)data_slice__r, strides_slice__r[0] ); return true; '''} ) m.function( "_invert_R", """Invert a rotation matrix This is an internal function. You probably want mrcal.invert_R(). See the docs for that function for details. """, args_input = ('R',), prototype_input = ((3,3),), prototype_output = (3,3), Ccode_slice_eval = \ {np.float64: r''' mrcal_invert_R_full( (double*)data_slice__output, strides_slice__output[0], strides_slice__output[1], (const double*)data_slice__R, strides_slice__R[0], strides_slice__R[1] ); return true; '''}, ) m.function( "_rt_from_Rt", """Compute an rt transformation from a Rt transformation This is an internal function. You probably want mrcal.rt_from_Rt(). See the docs for that function for details. """, args_input = ('Rt',), prototype_input = ((4,3),), prototype_output = (6,), Ccode_slice_eval = \ {np.float64: r''' mrcal_rt_from_Rt_full( (double*)data_slice__output,strides_slice__output[0], NULL,0,0,0, (const double*)data_slice__Rt,strides_slice__Rt[0], strides_slice__Rt[1] ); return true; '''} ) m.function( "_rt_from_Rt_withgrad", """Compute an rt transformation from a Rt transformation This is an internal function. You probably want mrcal.rt_from_Rt(). See the docs for that function for details. """, args_input = ('Rt',), prototype_input = ((4,3),), prototype_output = ((6,), (3,3,3)), Ccode_slice_eval = \ {np.float64: r''' mrcal_rt_from_Rt_full( (double*)data_slice__output0,strides_slice__output0[0], (double*)data_slice__output1,strides_slice__output1[0], strides_slice__output1[1],strides_slice__output1[2], (const double*)data_slice__Rt,strides_slice__Rt[0], strides_slice__Rt[1] ); return true; '''} ) m.function( "_Rt_from_rt", """Compute an Rt transformation from a rt transformation This is an internal function. You probably want mrcal.Rt_from_rt(). See the docs for that function for details. """, args_input = ('rt',), prototype_input = ((6,),), prototype_output = (4,3), Ccode_slice_eval = \ {np.float64: r''' mrcal_Rt_from_rt_full( (double*)data_slice__output, strides_slice__output[0],strides_slice__output[1], NULL,0,0,0, (const double*)data_slice__rt, strides_slice__rt[0] ); return true; '''} ) m.function( "_Rt_from_rt_withgrad", """Compute an Rt transformation from a rt transformation This is an internal function. You probably want mrcal.Rt_from_rt(). See the docs for that function for details. """, args_input = ('rt',), prototype_input = ((6,),), prototype_output = ((4,3), (3,3,3)), Ccode_slice_eval = \ {np.float64: r''' mrcal_Rt_from_rt_full( (double*)data_slice__output0, strides_slice__output0[0],strides_slice__output0[1], (double*)data_slice__output1,strides_slice__output1[0], strides_slice__output1[1],strides_slice__output1[2], (const double*)data_slice__rt, strides_slice__rt[0] ); return true; '''} ) m.function( "_invert_Rt", """Invert an Rt transformation This is an internal function. You probably want mrcal.invert_Rt(). See the docs for that function for details. """, args_input = ('Rt',), prototype_input = ((4,3),), prototype_output = (4,3), Ccode_slice_eval = \ {np.float64: r''' mrcal_invert_Rt_full( (double*)data_slice__output, strides_slice__output[0], strides_slice__output[1], (const double*)data_slice__Rt, strides_slice__Rt[0], strides_slice__Rt[1] ); return true; '''}, ) m.function( "_invert_rt", """Invert an rt transformation This is an internal function. You probably want mrcal.invert_rt(). See the docs for that function for details. """, args_input = ('rt',), prototype_input = ((6,),), prototype_output = (6,), Ccode_slice_eval = \ {np.float64: r''' mrcal_invert_rt_full( (double*)data_slice__output, strides_slice__output[0], NULL,0,0, NULL,0,0, (const double*)data_slice__rt, strides_slice__rt[0] ); return true; '''}, ) m.function( "_invert_rt_withgrad", """Invert an rt transformation This is an internal function. You probably want mrcal.invert_rt(). See the docs for that function for details. Note that the C library returns limited gradients: - It returns dtout_drin,dtout_dtin only because - drout_drin always -I - drout_dtin always 0 THIS function combines these into a full drtout_drtin array """, args_input = ('rt',), prototype_input = ((6,),), prototype_output = ((6,), (6,6)), # output1 is drtout/drtin = [ drout/drin drout/dtin ] # [ dtout/drin dtout/dtin ] # # = [ -I 0 ] # [ dtout/drin dtout/dtin ] Ccode_slice_eval = \ {np.float64: r''' mrcal_invert_rt_full( (double*)data_slice__output0, strides_slice__output0[0], &item__output1(3,0), strides_slice__output1[0], strides_slice__output1[1], &item__output1(3,3), strides_slice__output1[0], strides_slice__output1[1], (const double*)data_slice__rt, strides_slice__rt[0] ); for(int i=0; i<3; i++) for(int j=0; j<6; j++) item__output1(i,j) = 0; item__output1(0,0) = -1.; item__output1(1,1) = -1.; item__output1(2,2) = -1.; return true; '''}, ) m.function( "_compose_Rt", """Composes two Rt transformations This is an internal function. You probably want mrcal.compose_Rt(). See the docs for that function for details. This internal function differs from compose_Rt(): - It supports exactly two arguments, while compose_Rt() can compose N transformations """, args_input = ('Rt0', 'Rt1'), prototype_input = ((4,3,), (4,3,)), prototype_output = (4,3), Ccode_slice_eval = \ {np.float64: r''' mrcal_compose_Rt_full( (double*)data_slice__output, strides_slice__output[0], strides_slice__output[1], (const double*)data_slice__Rt0, strides_slice__Rt0[0], strides_slice__Rt0[1], (const double*)data_slice__Rt1, strides_slice__Rt1[0], strides_slice__Rt1[1] ); return true; '''}, ) m.function( "_compose_r", """Compose two angle-axis rotations This is an internal function. You probably want mrcal.compose_r(). See the docs for that function for details. This internal function differs from compose_r(): - It supports exactly two arguments, while compose_r() can compose N rotations - It never reports gradients """, args_input = ('r0', 'r1'), prototype_input = ((3,), (3,)), prototype_output = (3,), Ccode_slice_eval = \ {np.float64: r''' mrcal_compose_r_full( (double*)data_slice__output, strides_slice__output[0], NULL,0,0, NULL,0,0, (const double*)data_slice__r0, strides_slice__r0[0], (const double*)data_slice__r1, strides_slice__r1[0] ); return true; '''}, ) m.function( "_compose_r_withgrad", """Compose two angle-axis rotations; return (r,dr/dr0,dr/dr1) This is an internal function. You probably want mrcal.compose_r(). See the docs for that function for details. This internal function differs from compose_r(): - It supports exactly two arguments, while compose_r() can compose N rotations - It always reports gradients """, args_input = ('r0', 'r1'), prototype_input = ((3,), (3,)), prototype_output = ((3,), (3,3),(3,3)), Ccode_slice_eval = \ {np.float64: r''' mrcal_compose_r_full( (double*)data_slice__output0, strides_slice__output0[0], // dr/dr0 &item__output1(0,0), strides_slice__output1[0], strides_slice__output1[1], // dr/dr1 &item__output2(0,0), strides_slice__output2[0], strides_slice__output2[1], (const double*)data_slice__r0, strides_slice__r0[0], (const double*)data_slice__r1, strides_slice__r1[0] ); return true; '''}, ) m.function( "compose_r_tinyr0_gradientr0", r"""Special-case rotation composition for the uncertainty computation SYNOPSIS r1 = rotation_axis1 * rotation_magnitude1 dr01_dr0 = compose_r_tinyr0_gradientr0(r1) ### Another way to get the same thing (but possibly less efficiently) _,dr01_dr0,_ = compose_r(np.zeros((3,),), r1, get_gradients=True) This is a special-case subset of compose_r(). It is the same, except: - r0 is assumed to be 0, so we don't ingest it, and we don't report the composition result - we ONLY report the dr01/dr0 gradient This special-case function is a part of the projection uncertainty computation, so it exists by itself. See the documentation for compose_r() for all the details. ARGUMENTS - r1: the second of the two rotations being composed. The first rotation is an identity, so it's not given - out: optional argument specifying the destination. By default, a new numpy array(s) is created and returned. To write the results into an existing (and possibly non-contiguous) array, specify it with the 'out' kwarg. 'out' is the one numpy array we will write into RETURNED VALUE We return a single array: dr01/dr0 """, args_input = ('r1',), prototype_input = ((3,),), prototype_output = (3,3), Ccode_slice_eval = \ {np.float64: r''' mrcal_compose_r_tinyr0_gradientr0_full( // dr/dr0 &item__output(0,0), strides_slice__output[0], strides_slice__output[1], (const double*)data_slice__r1, strides_slice__r1[0] ); return true; '''}, ) m.function( "_compose_rt", """Compose two rt transformations This is an internal function. You probably want mrcal.compose_rt(). See the docs for that function for details. This internal function differs from compose_rt(): - It supports exactly two arguments, while compose_rt() can compose N transformations - It never reports gradients """, args_input = ('rt0', 'rt1'), prototype_input = ((6,), (6,)), prototype_output = (6,), Ccode_slice_eval = \ {np.float64: r''' mrcal_compose_rt_full( (double*)data_slice__output, strides_slice__output[0], NULL,0,0, NULL,0,0, NULL,0,0, NULL,0,0, (const double*)data_slice__rt0, strides_slice__rt0[0], (const double*)data_slice__rt1, strides_slice__rt1[0] ); return true; '''}, ) m.function( "_compose_rt_withgrad", """Compose two rt transformations; return (rt,drt/drt0,drt/drt1) This is an internal function. You probably want mrcal.compose_rt(). See the docs for that function for details. This internal function differs from compose_rt(): - It supports exactly two arguments, while compose_rt() can compose N transformations - It always reports gradients Note that the C library returns limited gradients: - dr/dt0 is not returned: it is always 0 - dr/dt1 is not returned: it is always 0 - dt/dr1 is not returned: it is always 0 - dt/dt0 is not returned: it is always the identity matrix THIS function combines these into the full drtout_drt0,drtout_drt1 arrays """, args_input = ('rt0', 'rt1'), prototype_input = ((6,), (6,)), prototype_output = ((6,), (6,6),(6,6)), # output1 is drt/drt0 = [ dr/dr0 dr/dt0 ] # [ dt/dr0 dt/dt0 ] # # = [ dr/dr0 0 ] # [ dt/dr0 I ] # # output2 is drt/drt1 = [ dr/dr1 dr/dt1 ] # [ dt/dr1 dt/dt1 ] # # = [ dr/dr1 0 ] # [ 0 dt/dt1 ] Ccode_slice_eval = \ {np.float64: r''' mrcal_compose_rt_full( (double*)data_slice__output0, strides_slice__output0[0], // dr/dr0 &item__output1(0,0), strides_slice__output1[0], strides_slice__output1[1], // dr/dr1 &item__output2(0,0), strides_slice__output2[0], strides_slice__output2[1], // dt/dr0 &item__output1(3,0), strides_slice__output1[0], strides_slice__output1[1], // dt/dt1 &item__output2(3,3), strides_slice__output2[0], strides_slice__output2[1], (const double*)data_slice__rt0, strides_slice__rt0[0], (const double*)data_slice__rt1, strides_slice__rt1[0] ); for(int i=0; i<3; i++) for(int j=0; j<3; j++) { item__output1(i, j+3) = 0; item__output1(i+3,j+3) = 0; item__output2(i, j+3) = 0; item__output2(i+3,j ) = 0; } item__output1(3,3) = 1.; item__output1(4,4) = 1.; item__output1(5,5) = 1.; return true; '''}, ) m.function( "R_from_quat", r"""Convert a rotation defined as a unit quaternion rotation to a rotation matrix SYNOPSIS s = np.sin(rotation_magnitude/2.) c = np.cos(rotation_magnitude/2.) quat = nps.glue( c, s*rotation_axis, axis = -1) print(quat.shape) ===> (4,) R = mrcal.R_from_quat(quat) print(R.shape) ===> (3,3) This is mostly for compatibility with some old stuff. mrcal doesn't use quaternions anywhere. Test this thoroughly before using. This function supports broadcasting fully. ARGUMENTS - quat: array of shape (4,). The unit quaternion that defines the rotation. The values in the array are (u,i,j,k) - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE We return an array of rotation matrices. Each broadcasted slice has shape (3,3) """, args_input = ('q',), prototype_input = ((4,),), prototype_output = (3,3), Ccode_slice_eval = \ {np.float64: r''' // From the expression in wikipedia const double r = item__q(0); const double i = item__q(1); const double j = item__q(2); const double k = item__q(3); const double ii = i*i; const double ij = i*j; const double ik = i*k; const double ir = i*r; const double jj = j*j; const double jk = j*k; const double jr = j*r; const double kk = k*k; const double kr = k*r; item__output(0,0) = 1. - 2.*(jj+kk); item__output(0,1) = 2.*(ij-kr); item__output(0,2) = 2.*(ik+jr); item__output(1,0) = 2.*(ij+kr); item__output(1,1) = 1. - 2.*(ii+kk); item__output(1,2) = 2.*(jk-ir); item__output(2,0) = 2.*(ik-jr); item__output(2,1) = 2.*(jk+ir); item__output(2,2) = 1. - 2.*(ii+jj); return true; '''} ) m.function( "skew_symmetric", r"""Return the skew-symmetric matrix used in a cross product SYNOPSIS a = np.array(( 1., 5., 7.)) b = np.array(( 3., -.1, -10.)) A = mrcal.skew_symmetric(a) print( nps.inner(A,b) ) ===> [-49.3 31. -15.1] print( np.cross(a,b) ) ===> [-49.3 31. -15.1] A vector cross-product a x b can be represented as a matrix multiplication A*b where A is a skew-symmetric matrix based on the vector a. This function computes this matrix A from the vector a. This function supports broadcasting fully. ARGUMENTS - a: array of shape (3,) - out: optional argument specifying the destination. By default, new numpy array(s) are created and returned. To write the results into existing (and possibly non-contiguous) arrays, specify them with the 'out' kwarg. If 'out' is given, we return the 'out' that was passed in. This is the standard behavior provided by numpysane_pywrap. RETURNED VALUE We return the matrix A in a (3,3) numpy array """, args_input = ('a',), prototype_input = ((3,),), prototype_output = (3,3), Ccode_slice_eval = \ {np.float64: r''' // diagonal is zero item__output(0,0) = 0.0; item__output(1,1) = 0.0; item__output(2,2) = 0.0; item__output(0,1) = -item__a(2); item__output(0,2) = item__a(1); item__output(1,0) = item__a(2); item__output(1,2) = -item__a(0); item__output(2,0) = -item__a(1); item__output(2,1) = item__a(0); return true; '''} ) m.write() mrcal-2.4.1/poseutils-opencv.c000066400000000000000000000152661456301662300163170ustar00rootroot00000000000000// The implementation of mrcal_R_from_r is based on opencv. // The sources have been heavily modified, but the opencv logic remains. // // from opencv-4.1.2+dfsg/modules/calib3d/src/calibration.cpp // // Copyright (C) 2000-2008, Intel Corporation, all rights reserved. // Copyright (C) 2009, Willow Garage Inc., all rights reserved. // Third party copyrights are property of their respective owners. // // Redistribution and use in source and binary forms, with or without modification, // are permitted provided that the following conditions are met: // // * Redistribution's of source code must retain the above copyright notice, // this list of conditions and the following disclaimer. // // * Redistribution's in binary form must reproduce the above copyright notice, // this list of conditions and the following disclaimer in the documentation // and/or other materials provided with the distribution. // // * The name of the copyright holders may not be used to endorse or promote products // derived from this software without specific prior written permission. // // This software is provided by the copyright holders and contributors "as is" and // any express or implied warranties, including, but not limited to, the implied // warranties of merchantability and fitness for a particular purpose are disclaimed. // In no event shall the Intel Corporation or contributors be liable for any direct, // indirect, incidental, special, exemplary, or consequential damages // (including, but not limited to, procurement of substitute goods or services; // loss of use, data, or profits; or business interruption) however caused // and on any theory of liability, whether in contract, strict liability, // or tort (including negligence or otherwise) arising in any way out of // Apparently I need this in MSVC to get constants #define _USE_MATH_DEFINES #include #include #include "poseutils.h" #include "strides.h" void mrcal_R_from_r_full( // outputs double* R, // (3,3) array int R_stride0, // in bytes. <= 0 means "contiguous" int R_stride1, // in bytes. <= 0 means "contiguous" double* J, // (3,3,3) array. Gradient. May be NULL int J_stride0, // in bytes. <= 0 means "contiguous" int J_stride1, // in bytes. <= 0 means "contiguous" int J_stride2, // in bytes. <= 0 means "contiguous" // input const double* r, // (3,) vector int r_stride0 // in bytes. <= 0 means "contiguous" ) { init_stride_2D(R, 3,3); init_stride_3D(J, 3,3,3 ); init_stride_1D(r, 3 ); double norm2r = 0.0; for(int i=0; i<3; i++) norm2r += P1(r,i)*P1(r,i); if( norm2r < DBL_EPSILON*DBL_EPSILON ) { mrcal_identity_R_full(R, R_stride0, R_stride1); if( J ) { for(int i=0; i<3; i++) for(int j=0; j<3; j++) for(int k=0; k<3; k++) P3(J,i,j,k) = 0.; P3(J,1,2,0) = -1.; P3(J,2,0,1) = -1.; P3(J,0,1,2) = -1.; P3(J,2,1,0) = 1.; P3(J,0,2,1) = 1.; P3(J,1,0,2) = 1.; } return; } double theta = sqrt(norm2r); double s = sin(theta); double c = cos(theta); double c1 = 1. - c; double itheta = 1./theta; double r_unit[3]; for(int i=0; i<3; i++) r_unit[i] = P1(r,i) * itheta; // R = cos(theta)*I + (1 - cos(theta))*r*rT + sin(theta)*[r_x] P2(R, 0,0) = c + c1*r_unit[0]*r_unit[0]; P2(R, 0,1) = c1*r_unit[0]*r_unit[1] - s*r_unit[2]; P2(R, 0,2) = c1*r_unit[0]*r_unit[2] + s*r_unit[1]; P2(R, 1,0) = c1*r_unit[0]*r_unit[1] + s*r_unit[2]; P2(R, 1,1) = c + c1*r_unit[1]*r_unit[1]; P2(R, 1,2) = c1*r_unit[1]*r_unit[2] - s*r_unit[0]; P2(R, 2,0) = c1*r_unit[0]*r_unit[2] - s*r_unit[1]; P2(R, 2,1) = c1*r_unit[1]*r_unit[2] + s*r_unit[0]; P2(R, 2,2) = c + c1*r_unit[2]*r_unit[2]; if( J ) { // opencv had some logic with lots of 0s. I unrolled all of the // loops, and removed all the resulting 0 terms double a0, a1, a3; double a2 = itheta * c1; double a4 = itheta * s; a0 = -s *r_unit[0]; a1 = (s - 2*a2)*r_unit[0]; a3 = (c - a4)*r_unit[0]; P3(J,0,0,0) = a0 + a1*r_unit[0]*r_unit[0] + a2*(r_unit[0]+r_unit[0]); P3(J,0,1,0) = a1*r_unit[0]*r_unit[1] + a2*r_unit[1] - a3*r_unit[2]; P3(J,0,2,0) = a1*r_unit[0]*r_unit[2] + a2*r_unit[2] + a3*r_unit[1]; P3(J,1,0,0) = a1*r_unit[0]*r_unit[1] + a2*r_unit[1] + a3*r_unit[2]; P3(J,1,1,0) = a0 + a1*r_unit[1]*r_unit[1]; P3(J,1,2,0) = a1*r_unit[1]*r_unit[2] - a3*r_unit[0] - a4; P3(J,2,0,0) = a1*r_unit[0]*r_unit[2] + a2*r_unit[2] - a3*r_unit[1]; P3(J,2,1,0) = a1*r_unit[1]*r_unit[2] + a3*r_unit[0] + a4; P3(J,2,2,0) = a0 + a1*r_unit[2]*r_unit[2]; a0 = -s *r_unit[1]; a1 = (s - 2*a2)*r_unit[1]; a3 = (c - a4)*r_unit[1]; P3(J,0,0,1) = a0 + a1*r_unit[0]*r_unit[0]; P3(J,0,1,1) = a1*r_unit[0]*r_unit[1] + a2*r_unit[0] - a3*r_unit[2]; P3(J,0,2,1) = a1*r_unit[0]*r_unit[2] + a3*r_unit[1] + a4; P3(J,1,0,1) = a1*r_unit[0]*r_unit[1] + a2*r_unit[0] + a3*r_unit[2]; P3(J,1,1,1) = a0 + a1*r_unit[1]*r_unit[1] + a2*(r_unit[1]+r_unit[1]); P3(J,1,2,1) = a1*r_unit[1]*r_unit[2] + a2*r_unit[2] - a3*r_unit[0]; P3(J,2,0,1) = a1*r_unit[0]*r_unit[2] - a3*r_unit[1] - a4; P3(J,2,1,1) = a1*r_unit[1]*r_unit[2] + a2*r_unit[2] + a3*r_unit[0]; P3(J,2,2,1) = a0 + a1*r_unit[2]*r_unit[2]; a0 = -s *r_unit[2]; a1 = (s - 2*a2)*r_unit[2]; a3 = (c - a4)*r_unit[2]; P3(J,0,0,2) = a0 + a1*r_unit[0]*r_unit[0]; P3(J,0,1,2) = a1*r_unit[0]*r_unit[1] - a3*r_unit[2] - a4; P3(J,0,2,2) = a1*r_unit[0]*r_unit[2] + a2*r_unit[0] + a3*r_unit[1]; P3(J,1,0,2) = a1*r_unit[0]*r_unit[1] + a3*r_unit[2] + a4; P3(J,1,1,2) = a0 + a1*r_unit[1]*r_unit[1]; P3(J,1,2,2) = a1*r_unit[1]*r_unit[2] + a2*r_unit[1] - a3*r_unit[0]; P3(J,2,0,2) = a1*r_unit[0]*r_unit[2] + a2*r_unit[0] - a3*r_unit[1]; P3(J,2,1,2) = a1*r_unit[1]*r_unit[2] + a2*r_unit[1] + a3*r_unit[0]; P3(J,2,2,2) = a0 + a1*r_unit[2]*r_unit[2] + a2*(r_unit[2]+r_unit[2]); } } mrcal-2.4.1/poseutils-uses-autodiff.cc000066400000000000000000000666361456301662300177550ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #include "autodiff.hh" #include "strides.h" extern "C" { #include "poseutils.h" } template static void rotate_point_r_core(// output val_withgrad_t* x_outg, // inputs const val_withgrad_t* rg, const val_withgrad_t* x_ing, bool inverted) { // Rodrigues rotation formula: // xrot = x cos(th) + cross(axis, x) sin(th) + axis axist x (1 - cos(th)) // // I have r = axis*th -> th = norm(r) -> // xrot = x cos(th) + cross(r, x) sin(th)/th + r rt x (1 - cos(th)) / (th*th) // an inversion would flip the sign on: // - rg // - cross // - inner // But inner is always multiplied by rg, making the sign irrelevant. So an // inversion only flips the sign on the cross double sign = inverted ? -1.0 : 1.0; const val_withgrad_t th2 = rg[0]*rg[0] + rg[1]*rg[1] + rg[2]*rg[2]; const val_withgrad_t cross[3] = { (rg[1]*x_ing[2] - rg[2]*x_ing[1])*sign, (rg[2]*x_ing[0] - rg[0]*x_ing[2])*sign, (rg[0]*x_ing[1] - rg[1]*x_ing[0])*sign }; const val_withgrad_t inner = rg[0]*x_ing[0] + rg[1]*x_ing[1] + rg[2]*x_ing[2]; if(th2.x < 1e-10) { // Small rotation. I don't want to divide by 0, so I take the limit // lim(th->0, xrot) = // = x + cross(r, x) + r rt x lim(th->0, (1 - cos(th)) / (th*th)) // = x + cross(r, x) + r rt x lim(th->0, sin(th) / (2*th)) // = x + cross(r, x) + r rt x/2 for(int i=0; i<3; i++) x_outg[i] = x_ing[i] + cross[i] + rg[i]*inner / 2.; } else { // Non-small rotation. This is the normal path const val_withgrad_t th = th2.sqrt(); const vec_withgrad_t sc = th.sincos(); for(int i=0; i<3; i++) x_outg[i] = x_ing[i]*sc.v[1] + cross[i] * sc.v[0]/th + rg[i] * inner * (val_withgrad_t(1.) - sc.v[1]) / th2; } } template static void r_from_R_core(// output val_withgrad_t* rg, // inputs const val_withgrad_t* Rg) { val_withgrad_t tr = Rg[0] + Rg[4] + Rg[8]; val_withgrad_t axis[3] = { Rg[2*3 + 1] - Rg[1*3 + 2], Rg[0*3 + 2] - Rg[2*3 + 0], Rg[1*3 + 0] - Rg[0*3 + 1] }; val_withgrad_t costh = (tr - 1.) / 2.; if( (fabs(axis[0].x) > 1e-10 || fabs(axis[1].x) > 1e-10 || fabs(axis[2].x) > 1e-10) && fabs(costh.x) < (1. - 1e-10) ) { // normal path val_withgrad_t th = costh.acos(); val_withgrad_t mag_axis_recip = val_withgrad_t(1.) / ((axis[0]*axis[0] + axis[1]*axis[1] + axis[2]*axis[2]).sqrt()); for(int i=0; i<3; i++) rg[i] = axis[i] * mag_axis_recip * th; } else { // small th. Can't divide by it. But I can look at the limit. // // axis / (2 sinth)*th = axis/2 *th/sinth ~ axis/2 for(int i=0; i<3; i++) rg[i] = axis[i] / 2.; } } extern "C" void mrcal_rotate_point_r_full( // output double* x_out, // (3,) array int x_out_stride0, // in bytes. <= 0 means "contiguous" double* J_r, // (3,3) array. May be NULL int J_r_stride0, // in bytes. <= 0 means "contiguous" int J_r_stride1, // in bytes. <= 0 means "contiguous" double* J_x, // (3,3) array. May be NULL int J_x_stride0, // in bytes. <= 0 means "contiguous" int J_x_stride1, // in bytes. <= 0 means "contiguous" // input const double* r, // (3,) array. May be NULL int r_stride0, // in bytes. <= 0 means "contiguous" const double* x_in, // (3,) array. May be NULL int x_in_stride0, // in bytes. <= 0 means "contiguous" bool inverted // if true, I apply a // rotation in the opposite // direction. J_r corresponds // to the input r ) { init_stride_1D(x_out, 3); init_stride_2D(J_r, 3,3); init_stride_2D(J_x, 3,3); init_stride_1D(r, 3); init_stride_1D(x_in, 3); if(J_r == NULL && J_x == NULL) { vec_withgrad_t<0, 3> rg (r, -1, r_stride0); vec_withgrad_t<0, 3> x_ing(x_in, -1, x_in_stride0); vec_withgrad_t<0, 3> x_outg; rotate_point_r_core<0>(x_outg.v, rg.v, x_ing.v, inverted); x_outg.extract_value(x_out, x_out_stride0); } else if(J_r != NULL && J_x == NULL) { vec_withgrad_t<3, 3> rg (r, 0, r_stride0); vec_withgrad_t<3, 3> x_ing(x_in, -1, x_in_stride0); vec_withgrad_t<3, 3> x_outg; rotate_point_r_core<3>(x_outg.v, rg.v, x_ing.v, inverted); x_outg.extract_value(x_out, x_out_stride0); x_outg.extract_grad (J_r, 0, 3, 0, J_r_stride0, J_r_stride1); } else if(J_r == NULL && J_x != NULL) { vec_withgrad_t<3, 3> rg (r, -1, r_stride0); vec_withgrad_t<3, 3> x_ing(x_in, 0, x_in_stride0); vec_withgrad_t<3, 3> x_outg; rotate_point_r_core<3>(x_outg.v, rg.v, x_ing.v, inverted); x_outg.extract_value(x_out, x_out_stride0); x_outg.extract_grad (J_x, 0, 3, 0, J_x_stride0,J_x_stride1); } else { vec_withgrad_t<6, 3> rg (r, 0, r_stride0); vec_withgrad_t<6, 3> x_ing(x_in, 3, x_in_stride0); vec_withgrad_t<6, 3> x_outg; rotate_point_r_core<6>(x_outg.v, rg.v, x_ing.v, inverted); x_outg.extract_value(x_out, x_out_stride0); x_outg.extract_grad (J_r, 0, 3, 0, J_r_stride0, J_r_stride1); x_outg.extract_grad (J_x, 3, 3, 0, J_x_stride0, J_x_stride1); } } extern "C" void mrcal_transform_point_rt_full( // output double* x_out, // (3,) array int x_out_stride0, // in bytes. <= 0 means "contiguous" double* J_rt, // (3,6) array. May be NULL int J_rt_stride0, // in bytes. <= 0 means "contiguous" int J_rt_stride1, // in bytes. <= 0 means "contiguous" double* J_x, // (3,3) array. May be NULL int J_x_stride0, // in bytes. <= 0 means "contiguous" int J_x_stride1, // in bytes. <= 0 means "contiguous" // input const double* rt, // (6,) array. May be NULL int rt_stride0, // in bytes. <= 0 means "contiguous" const double* x_in, // (3,) array. May be NULL int x_in_stride0, // in bytes. <= 0 means "contiguous" bool inverted // if true, I apply the // transformation in the // opposite direction. // J_rt corresponds to // the input rt ) { if(!inverted) { init_stride_1D(x_out, 3); init_stride_2D(J_rt, 3,6); // init_stride_2D(J_x, 3,3 ); init_stride_1D(rt, 6 ); // init_stride_1D(x_in, 3 ); // to make in-place operations work double t[3] = { P1(rt, 3), P1(rt, 4), P1(rt, 5) }; // I want rotate(x) + t // First rotate(x) mrcal_rotate_point_r_full(x_out, x_out_stride0, J_rt, J_rt_stride0, J_rt_stride1, J_x, J_x_stride0, J_x_stride1, rt, rt_stride0, x_in, x_in_stride0, false); // And now +t. The J_r, J_x gradients are unaffected. J_t is identity for(int i=0; i<3; i++) P1(x_out,i) += t[i]; if(J_rt) mrcal_identity_R_full(&P2(J_rt,0,3), J_rt_stride0, J_rt_stride1); } else { // I use the special-case rx_minus_rt() to efficiently rotate both x and // t by the same r init_stride_1D(x_out, 3); init_stride_2D(J_rt, 3,6); init_stride_2D(J_x, 3,3 ); init_stride_1D(rt, 6 ); init_stride_1D(x_in, 3 ); if(J_rt == NULL && J_x == NULL) { vec_withgrad_t<0, 3> x_minus_t(x_in, -1, x_in_stride0); x_minus_t -= vec_withgrad_t<0, 3>(&P1(rt,3), -1, rt_stride0); vec_withgrad_t<0, 3> rg (&rt[0], -1, rt_stride0); vec_withgrad_t<0, 3> x_outg; rotate_point_r_core<0>(x_outg.v, rg.v, x_minus_t.v, true); x_outg.extract_value(x_out, x_out_stride0); } else if(J_rt != NULL && J_x == NULL) { vec_withgrad_t<6, 3> x_minus_t(x_in, -1, x_in_stride0); x_minus_t -= vec_withgrad_t<6, 3>(&P1(rt,3), 3, rt_stride0); vec_withgrad_t<6, 3> rg (&rt[0], 0, rt_stride0); vec_withgrad_t<6, 3> x_outg; rotate_point_r_core<6>(x_outg.v, rg.v, x_minus_t.v, true); x_outg.extract_value(x_out, x_out_stride0); x_outg.extract_grad (J_rt, 0, 3, 0, J_rt_stride0, J_rt_stride1); x_outg.extract_grad (&P2(J_rt,0,3), 3, 3, 0, J_rt_stride0, J_rt_stride1); } else if(J_rt == NULL && J_x != NULL) { vec_withgrad_t<3, 3> x_minus_t(x_in, 0, x_in_stride0); x_minus_t -= vec_withgrad_t<3, 3>(&P1(rt,3),-1, rt_stride0); vec_withgrad_t<3, 3> rg (&rt[0], -1, rt_stride0); vec_withgrad_t<3, 3> x_outg; rotate_point_r_core<3>(x_outg.v, rg.v, x_minus_t.v, true); x_outg.extract_value(x_out, x_out_stride0); x_outg.extract_grad (J_x, 0, 3, 0, J_x_stride0, J_x_stride1); } else { vec_withgrad_t<9, 3> x_minus_t(x_in, 3, x_in_stride0); x_minus_t -= vec_withgrad_t<9, 3>(&P1(rt,3), 6, rt_stride0); vec_withgrad_t<9, 3> rg (&rt[0], 0, rt_stride0); vec_withgrad_t<9, 3> x_outg; rotate_point_r_core<9>(x_outg.v, rg.v, x_minus_t.v, true); x_outg.extract_value(x_out, x_out_stride0); x_outg.extract_grad (J_rt, 0, 3, 0, J_rt_stride0, J_rt_stride1); x_outg.extract_grad (&P2(J_rt,0,3), 6, 3, 0, J_rt_stride0, J_rt_stride1); x_outg.extract_grad (J_x, 3, 3, 0, J_x_stride0, J_x_stride1); } } } extern "C" void mrcal_r_from_R_full( // output double* r, // (3,) vector int r_stride0, // in bytes. <= 0 means "contiguous" double* J, // (3,3,3) array. Gradient. May be NULL int J_stride0, // in bytes. <= 0 means "contiguous" int J_stride1, // in bytes. <= 0 means "contiguous" int J_stride2, // in bytes. <= 0 means "contiguous" // input const double* R, // (3,3) array int R_stride0, // in bytes. <= 0 means "contiguous" int R_stride1 // in bytes. <= 0 means "contiguous" ) { init_stride_1D(r, 3); init_stride_3D(J, 3,3,3); init_stride_2D(R, 3,3); if(J == NULL) { vec_withgrad_t<0, 3> rg; vec_withgrad_t<0, 9> Rg; Rg.init_vars(&P2(R,0,0), 0,3, -1, R_stride1); Rg.init_vars(&P2(R,1,0), 3,3, -1, R_stride1); Rg.init_vars(&P2(R,2,0), 6,3, -1, R_stride1); r_from_R_core<0>(rg.v, Rg.v); rg.extract_value(r, r_stride0); } else { vec_withgrad_t<9, 3> rg; vec_withgrad_t<9, 9> Rg; Rg.init_vars(&P2(R,0,0), 0,3, 0, R_stride1); Rg.init_vars(&P2(R,1,0), 3,3, 3, R_stride1); Rg.init_vars(&P2(R,2,0), 6,3, 6, R_stride1); r_from_R_core<9>(rg.v, Rg.v); rg.extract_value(r, r_stride0); // J is dr/dR of shape (3,3,3). autodiff.h has a gradient of shape // (3,9): the /dR part is flattened. I pull it out in 3 chunks that scan // the middle dimension. So I fill in J[:,0,:] then J[:,1,:] then J[:,2,:] rg.extract_grad(&P3(J,0,0,0), 0,3, 0,J_stride0,J_stride2,3); rg.extract_grad(&P3(J,0,1,0), 3,3, 0,J_stride0,J_stride2,3); rg.extract_grad(&P3(J,0,2,0), 6,3, 0,J_stride0,J_stride2,3); } } template static void compose_r_core(// output vec_withgrad_t* r, // inputs const vec_withgrad_t* r0, const vec_withgrad_t* r1) { // Described here: // // Altmann, Simon L. "Hamilton, Rodrigues, and the Quaternion Scandal." // Mathematics Magazine, vol. 62, no. 5, 1989, pp. 291–308 // // Available here: // // https://www.jstor.org/stable/2689481 // // I use Equations (19) and (20) on page 302 of this paper. These equations say // that // // R(angle=gamma, axis=n) = // compose( R(angle=alpha, axis=l), R(angle=beta, axis=m) ) // // I need to compute gamma*n, and these are given as solutions to: // // cos(gamma/2) = // cos(alpha/2)*cos(beta/2) - // sin(alpha/2)*sin(beta/2) * inner(l,m) // sin(gamma/2) n = // sin(alpha/2)*cos(beta/2)*l + // cos(alpha/2)*sin(beta/2)*m + // sin(alpha/2)*sin(beta/2) * cross(l,m) // // For nicer notation, I define // // A = alpha/2 // B = beta /2 // C = gamma/2 // // l = r0 /(2A) // m = r1 /(2B) // n = r01/(2C) // // I rewrite: // // cos(C) = // cos(A)*cos(B) - // sin(A)*sin(B) * inner(r0,r1) / 4AB // sin(C) r01 / 2C = // sin(A)*cos(B)*r0 / 2A + // cos(A)*sin(B)*r1 / 2B + // sin(A)*sin(B) * cross(r0,r1) / 4AB const val_withgrad_t A = r0->mag() / 2.; const val_withgrad_t B = r1->mag() / 2.; const val_withgrad_t inner = r0->dot(*r1); const vec_withgrad_t cross = r0->cross(*r1); if(A.x < 1e-8) { // A ~ 0. I simplify // // cosC ~ // + cosB // - A*sinB * inner(r0,r1) / 4AB // sinC r01 / 2C ~ // + A*cosB* r0 / 2A // + sinB * r1 / 2B // + A*sinB * cross(r0,r1) / 4AB // // I have C = B + dB where dB ~ 0, so // // cosC ~ cos(B + dB) ~ cosB - dB sinB // -> dB = A * inner(r0,r1) / 4AB = // inner(r0,r1) / 4B // -> C = B + inner(r0,r1) / 4B // // Now let's look at the axis expression. Assuming A ~ 0 // // sinC r01 / 2C ~ // + A*cosB r0 / 2A // + sinB r1 / 2B // + A*sinB * cross(r0,r1) / 4AB // -> // sinC/C * r01 ~ // + cosB r0 // + sinB r1 / B // + sinB * cross(r0,r1) / 2B // // I linearize the left-hand side: // // sinC/C = sin(B+dB)/(B+dB) ~ // sinB/B + d( sinB/B )/dB dB = // sinB/B + dB (B cosB - sinB) / B^2 // // So // // (sinB/B + dB (B cosB - sinB) / B^2) r01 ~ // + cosB r0 // + sinB r1 / B // + sinB * cross(r0,r1) / 2B // -> // (sinB + dB (B cosB - sinB) / B) r01 ~ // + cosB*B r0 // + sinB r1 // + sinB * cross(r0,r1) / 2 // -> // sinB (r01 - r1) + dB (B cosB - sinB) / B r01 ~ // + cosB*B r0 // + sinB * cross(r0,r1) / 2 // // I want to find the perturbation to give me r01 ~ r1 + deltar -> // // sinB deltar + dB (B cosB - sinB) / B (r1 + deltar) ~ // + cosB*B r0 // + sinB * cross(r0,r1) / 2 // // All terms here are linear or quadratic in r0. For tiny r0, I can // ignore the quadratic terms: // // sinB deltar + dB (B cosB - sinB) / B r1 ~ // + cosB*B r0 // + sinB * cross(r0,r1) / 2 // -> // deltar ~ // - dB (B/tanB - 1) / B r1 // + B/tanB r0 // + cross(r0,r1) / 2 // // I substitute in the dB from above, and I simplify: // // deltar ~ // - inner(r0,r1) / 4B (B/tanB - 1) / B r1 // + B/tanB r0 // + cross(r0,r1) / 2 // = // - inner(r0,r1) (B/tanB - 1) / 4B^2 r1 // + B/tanB r0 // + cross(r0,r1) / 2 // // So // // r01 = r1 // - inner(r0,r1) (B/tanB - 1) / 4B^2 r1 // + B/tanB r0 // + cross(r0,r1) / 2 if(B.x < 1e-8) { // what if B is ALSO near 0? I simplify further // // lim(B->0) (B/tanB) = lim( 1 / sec^2 B) = 1. // lim(B->0) d(B/tanB)/dB = 0 // // (B/tanB - 1) / 4B^2 = // (B - tanB) / (4 B^2 tanB) // lim(B->0) = 0 // lim(B->0) d/dB = 0 // // So // r01 = r1 // + r0 // + cross(r0,r1) / 2 // // Here I have linear and quadratic terms. With my tiny numbers, the // quadratic terms can be ignored, so simply // // r01 = r0 + r1 *r = *r0 + *r1; return; } const val_withgrad_t& B_over_tanB = B / B.tan(); for(int i=0; i<3; i++) (*r)[i] = (*r1)[i] * (val_withgrad_t(1.0) - inner * (B_over_tanB - 1.) / (B*B*4.)) + (*r0)[i] * B_over_tanB + cross[i] / 2.; return; } else if(B.x < 1e-8) { // B ~ 0. I simplify // // cosC = // cosA - // sinA*B * inner(r0,r1) / 4AB // sinC r01 / 2C = // sinA*r0 / 2A + // cosA*B*r1 / 2B + // sinA*B * cross(r0,r1) / 4AB // // I have C = A + dA where dA ~ 0, so // // cosC ~ cos(A + dA) ~ cosA - dA sinA // -> dA = B * inner(r0,r1) / 4AB = // = inner(r0,r1) / 4A // -> C = A + inner(r0,r1) / 4A // // Now let's look at the axis expression. Assuming B ~ 0 // // sinC r01 / 2C = // + sinA*r0 / 2A // + cosA*B*r1 / 2B // + sinA*B * cross(r0,r1) / 4AB // -> // sinC/C r01 = // + sinA*r0 / A // + cosA*r1 // + sinA * cross(r0,r1) / 2A // // I linearize the left-hand side: // // sinC/C = sin(A+dA)/(A+dA) ~ // sinA/A + d( sinA/A )/dA dA = // sinA/A + dA (A cosA - sinA) / A^2 // // So // // (sinA/A + dA (A cosA - sinA) / A^2) r01 ~ // + sinA*r0 / A // + cosA*r1 // + sinA * cross(r0,r1) / 2A // -> // (sinA + dA (A cosA - sinA) / A) r01 ~ // + sinA*r0 // + cosA*r1*A // + sinA * cross(r0,r1) / 2 // -> // sinA (r01 - r0) + dA (A cosA - sinA) / A r01 ~ // + cosA*A r1 // + sinA * cross(r0,r1) / 2 // // // I want to find the perturbation to give me r01 ~ r0 + deltar -> // // sinA deltar + dA (A cosA - sinA) / A (r0 + deltar) ~ // + cosA*A r1 // + sinA * cross(r0,r1) / 2 // // All terms here are linear or quadratic in r1. For tiny r1, I can // ignore the quadratic terms: // // sinA deltar + dA (A cosA - sinA) / A r0 ~ // + cosA*A r1 // + sinA * cross(r0,r1) / 2 // -> // deltar ~ // - dA (A/tanA - 1) / A r0 // + A/tanA r1 // + cross(r0,r1) / 2 // // I substitute in the dA from above, and I simplify: // // deltar ~ // - inner(r0,r1) / 4A (A/tanA - 1) / A r0 // + A/tanA r1 // + cross(r0,r1) / 2 // = // - inner(r0,r1) (A/tanA - 1) / 4A^2 r0 // + A/tanA r1 // + cross(r0,r1) / 2 // // So // // r01 = r0 // - inner(r0,r1) (A/tanA - 1) / 4A^2 r0 // + A/tanA r1 // + cross(r0,r1) / 2 // I don't have an if(A.x < 1e-8){} case here; this is handled in // the above if() branch const val_withgrad_t& A_over_tanA = A / A.tan(); for(int i=0; i<3; i++) (*r)[i] = (*r0)[i] * (val_withgrad_t(1.0) - inner * (A_over_tanA - 1.) / (A*A*4.)) + (*r1)[i] * A_over_tanA + cross[i] / 2.; return; } const vec_withgrad_t sincosA = A.sincos(); const vec_withgrad_t sincosB = B.sincos(); const val_withgrad_t& sinA = sincosA.v[0]; const val_withgrad_t& cosA = sincosA.v[1]; const val_withgrad_t& sinB = sincosB.v[0]; const val_withgrad_t& cosB = sincosB.v[1]; const val_withgrad_t& sinA_over_A = A.sinx_over_x(sinA); const val_withgrad_t& sinB_over_B = B.sinx_over_x(sinB); val_withgrad_t cosC = cosA*cosB - sinA_over_A*sinB_over_B*inner/4.; // To handle numerical fuzz if (cosC.x > 1.0) cosC.x = 1.0; else if(cosC.x < -1.0) cosC.x = -1.0; const val_withgrad_t C = cosC.acos(); const val_withgrad_t sinC = (val_withgrad_t(1.) - cosC*cosC).sqrt(); const val_withgrad_t sinC_over_C_recip = val_withgrad_t(1.) / C.sinx_over_x(sinC); for(int i=0; i<3; i++) (*r)[i] = ( sinA_over_A*cosB*(*r0)[i] + sinB_over_B*cosA*(*r1)[i] + sinA_over_A*sinB_over_B*cross[i]/2. ) * sinC_over_C_recip; } extern "C" void mrcal_compose_r_full( // output double* r_out, // (3,) array int r_out_stride0, // in bytes. <= 0 means "contiguous" double* dr_dr0, // (3,3) array; may be NULL int dr_dr0_stride0, // in bytes. <= 0 means "contiguous" int dr_dr0_stride1, // in bytes. <= 0 means "contiguous" double* dr_dr1, // (3,3) array; may be NULL int dr_dr1_stride0, // in bytes. <= 0 means "contiguous" int dr_dr1_stride1, // in bytes. <= 0 means "contiguous" // input const double* r_0, // (3,) array int r_0_stride0, // in bytes. <= 0 means "contiguous" const double* r_1, // (3,) array int r_1_stride0 // in bytes. <= 0 means "contiguous" ) { init_stride_1D(r_out, 3); init_stride_2D(dr_dr0, 3,3); init_stride_2D(dr_dr1, 3,3); init_stride_1D(r_0, 3); init_stride_1D(r_1, 3); if(dr_dr0 == NULL && dr_dr1 == NULL) { // no gradients vec_withgrad_t<0, 3> r0g, r1g; r0g.init_vars(r_0, 0, 3, -1, r_0_stride0); r1g.init_vars(r_1, 0, 3, -1, r_1_stride0); vec_withgrad_t<0, 3> r01g; compose_r_core<0>( &r01g, &r0g, &r1g ); r01g.extract_value(r_out, r_out_stride0, 0, 3); } else if(dr_dr0 != NULL && dr_dr1 == NULL) { // r0 gradient only vec_withgrad_t<3, 3> r0g, r1g; r0g.init_vars(r_0, 0, 3, 0, r_0_stride0); r1g.init_vars(r_1, 0, 3, -1, r_1_stride0); vec_withgrad_t<3, 3> r01g; compose_r_core<3>( &r01g, &r0g, &r1g ); r01g.extract_value(r_out, r_out_stride0, 0, 3); r01g.extract_grad(dr_dr0, 0,3, 0, dr_dr0_stride0, dr_dr0_stride1, 3); } else if(dr_dr0 == NULL && dr_dr1 != NULL) { // r1 gradient only vec_withgrad_t<3, 3> r0g, r1g; r0g.init_vars(r_0, 0, 3, -1, r_0_stride0); r1g.init_vars(r_1, 0, 3, 0, r_1_stride0); vec_withgrad_t<3, 3> r01g; compose_r_core<3>( &r01g, &r0g, &r1g ); r01g.extract_value(r_out, r_out_stride0, 0, 3); r01g.extract_grad(dr_dr1, 0,3, 0, dr_dr1_stride0, dr_dr1_stride1, 3); } else { // r0 AND r1 gradients vec_withgrad_t<6, 3> r0g, r1g; r0g.init_vars(r_0, 0, 3, 0, r_0_stride0); r1g.init_vars(r_1, 0, 3, 3, r_1_stride0); vec_withgrad_t<6, 3> r01g; compose_r_core<6>( &r01g, &r0g, &r1g ); r01g.extract_value(r_out, r_out_stride0, 0, 3); r01g.extract_grad(dr_dr0, 0,3, 0, dr_dr0_stride0, dr_dr0_stride1, 3); r01g.extract_grad(dr_dr1, 3,3, 0, dr_dr1_stride0, dr_dr1_stride1, 3); } } mrcal-2.4.1/poseutils.c000066400000000000000000000752731456301662300150330ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // Apparently I need this in MSVC to get constants #define _USE_MATH_DEFINES #include #include #include #include "poseutils.h" #include "strides.h" // All arrays stored in row-major order // // I have two different representations of pose transformations: // // - Rt is a concatenated (4,3) array: Rt = nps.glue(R,t, axis=-2). The // transformation is R*x+t // // - rt is a concatenated (6) array: rt = nps.glue(r,t, axis=-1). The // transformation is R*x+t where R = R_from_r(r) // row vectors: vout = matmult(v,Mt) // equivalent col vector expression: vout = matmult(M,v) #define mul_vec3_gen33t_vout_scaled_full(vout, vout_stride0, \ v, v_stride0, \ Mt, Mt_stride0, Mt_stride1, \ scale) \ do { \ /* needed for in-place operations */ \ double outcopy[3] = { \ scale * \ (_P2(Mt,Mt_stride0,Mt_stride1,0,0)*_P1(v,v_stride0,0) + \ _P2(Mt,Mt_stride0,Mt_stride1,0,1)*_P1(v,v_stride0,1) + \ _P2(Mt,Mt_stride0,Mt_stride1,0,2)*_P1(v,v_stride0,2) ), \ scale * \ (_P2(Mt,Mt_stride0,Mt_stride1,1,0)*_P1(v,v_stride0,0) + \ _P2(Mt,Mt_stride0,Mt_stride1,1,1)*_P1(v,v_stride0,1) + \ _P2(Mt,Mt_stride0,Mt_stride1,1,2)*_P1(v,v_stride0,2) ), \ scale * \ (_P2(Mt,Mt_stride0,Mt_stride1,2,0)*_P1(v,v_stride0,0) + \ _P2(Mt,Mt_stride0,Mt_stride1,2,1)*_P1(v,v_stride0,1) + \ _P2(Mt,Mt_stride0,Mt_stride1,2,2)*_P1(v,v_stride0,2) ) }; \ _P1(vout,vout_stride0,0) = outcopy[0]; \ _P1(vout,vout_stride0,1) = outcopy[1]; \ _P1(vout,vout_stride0,2) = outcopy[2]; \ } while(0) #define mul_vec3_gen33t_vout_full(vout, vout_stride0, \ v, v_stride0, \ Mt, Mt_stride0, Mt_stride1) \ mul_vec3_gen33t_vout_scaled_full(vout, vout_stride0, \ v, v_stride0, \ Mt, Mt_stride0, Mt_stride1, 1.0) // row vectors: vout = scale*matmult(v,M) #define mul_vec3_gen33_vout_scaled_full(vout, vout_stride0, \ v, v_stride0, \ M, M_stride0, M_stride1, \ scale) \ do { \ /* needed for in-place operations */ \ double outcopy[3] = { \ scale * \ (_P2(M,M_stride0,M_stride1,0,0)*_P1(v,v_stride0,0) + \ _P2(M,M_stride0,M_stride1,1,0)*_P1(v,v_stride0,1) + \ _P2(M,M_stride0,M_stride1,2,0)*_P1(v,v_stride0,2)), \ scale * \ (_P2(M,M_stride0,M_stride1,0,1)*_P1(v,v_stride0,0) + \ _P2(M,M_stride0,M_stride1,1,1)*_P1(v,v_stride0,1) + \ _P2(M,M_stride0,M_stride1,2,1)*_P1(v,v_stride0,2)), \ scale * \ (_P2(M,M_stride0,M_stride1,0,2)*_P1(v,v_stride0,0) + \ _P2(M,M_stride0,M_stride1,1,2)*_P1(v,v_stride0,1) + \ _P2(M,M_stride0,M_stride1,2,2)*_P1(v,v_stride0,2)) }; \ _P1(vout,vout_stride0,0) = outcopy[0]; \ _P1(vout,vout_stride0,1) = outcopy[1]; \ _P1(vout,vout_stride0,2) = outcopy[2]; \ } while(0) #define mul_vec3_gen33_vout_full(vout, vout_stride0, \ v, v_stride0, \ Mt, Mt_stride0, Mt_stride1) \ mul_vec3_gen33_vout_scaled_full(vout, vout_stride0, \ v, v_stride0, \ Mt, Mt_stride0, Mt_stride1, 1.0) // row vectors: vout = matmult(v,Mt) // equivalent col vector expression: vout = matmult(M,v) #define mul_vec3_gen33t_vaccum_full(vout, vout_stride0, \ v, v_stride0, \ Mt, Mt_stride0, Mt_stride1) \ do { \ /* needed for in-place operations */ \ double outcopy[3] = { \ _P1(vout,vout_stride0,0) + \ _P2(Mt,Mt_stride0,Mt_stride1,0,0)*_P1(v,v_stride0,0) + \ _P2(Mt,Mt_stride0,Mt_stride1,0,1)*_P1(v,v_stride0,1) + \ _P2(Mt,Mt_stride0,Mt_stride1,0,2)*_P1(v,v_stride0,2), \ _P1(vout,vout_stride0,1) + \ _P2(Mt,Mt_stride0,Mt_stride1,1,0)*_P1(v,v_stride0,0) + \ _P2(Mt,Mt_stride0,Mt_stride1,1,1)*_P1(v,v_stride0,1) + \ _P2(Mt,Mt_stride0,Mt_stride1,1,2)*_P1(v,v_stride0,2), \ _P1(vout,vout_stride0,2) + \ _P2(Mt,Mt_stride0,Mt_stride1,2,0)*_P1(v,v_stride0,0) + \ _P2(Mt,Mt_stride0,Mt_stride1,2,1)*_P1(v,v_stride0,1) + \ _P2(Mt,Mt_stride0,Mt_stride1,2,2)*_P1(v,v_stride0,2) }; \ _P1(vout,vout_stride0,0) = outcopy[0]; \ _P1(vout,vout_stride0,1) = outcopy[1]; \ _P1(vout,vout_stride0,2) = outcopy[2]; \ } while(0) // row vectors: vout = scale*matmult(v,M) #define mul_vec3_gen33_vaccum_scaled_full(vout, vout_stride0, \ v, v_stride0, \ M, M_stride0, M_stride1, \ scale) \ do { \ /* needed for in-place operations */ \ double outcopy[3] = { \ _P1(vout,vout_stride0,0) + scale * \ (_P2(M,M_stride0,M_stride1,0,0)*_P1(v,v_stride0,0) + \ _P2(M,M_stride0,M_stride1,1,0)*_P1(v,v_stride0,1) + \ _P2(M,M_stride0,M_stride1,2,0)*_P1(v,v_stride0,2)), \ _P1(vout,vout_stride0,1) + scale * \ (_P2(M,M_stride0,M_stride1,0,1)*_P1(v,v_stride0,0) + \ _P2(M,M_stride0,M_stride1,1,1)*_P1(v,v_stride0,1) + \ _P2(M,M_stride0,M_stride1,2,1)*_P1(v,v_stride0,2)), \ _P1(vout,vout_stride0,2) + scale * \ (_P2(M,M_stride0,M_stride1,0,2)*_P1(v,v_stride0,0) + \ _P2(M,M_stride0,M_stride1,1,2)*_P1(v,v_stride0,1) + \ _P2(M,M_stride0,M_stride1,2,2)*_P1(v,v_stride0,2)) }; \ _P1(vout,vout_stride0,0) = outcopy[0]; \ _P1(vout,vout_stride0,1) = outcopy[1]; \ _P1(vout,vout_stride0,2) = outcopy[2]; \ } while(0) // multiply two (3,3) matrices static inline void mul_gen33_gen33_vout_full(// output double* m0m1, int m0m1_stride0, int m0m1_stride1, // input const double* m0, int m0_stride0, int m0_stride1, const double* m1, int m1_stride0, int m1_stride1) { /* needed for in-place operations */ double outcopy2[9]; for(int i=0; i<3; i++) // one row at a time mul_vec3_gen33_vout_scaled_full(&outcopy2[i*3], sizeof(outcopy2[0]), &_P2(m0 , m0_stride0, m0_stride1, i,0), m0_stride1, m1, m1_stride0, m1_stride1, 1.0); for(int i=0; i<3; i++) for(int j=0; j<3; j++) P2(m0m1, i,j) = outcopy2[3*i+j]; } static inline double inner3(const double* restrict a, const double* restrict b) { double s = 0.0; for (int i=0; i<3; i++) s += a[i]*b[i]; return s; } // Make an identity rotation or transformation void mrcal_identity_R_full(double* R, // (3,3) array int R_stride0, // in bytes. <= 0 means "contiguous" int R_stride1 // in bytes. <= 0 means "contiguous" ) { init_stride_2D(R, 3,3); P2(R, 0,0) = 1.0; P2(R, 0,1) = 0.0; P2(R, 0,2) = 0.0; P2(R, 1,0) = 0.0; P2(R, 1,1) = 1.0; P2(R, 1,2) = 0.0; P2(R, 2,0) = 0.0; P2(R, 2,1) = 0.0; P2(R, 2,2) = 1.0; } void mrcal_identity_r_full(double* r, // (3,) array int r_stride0 // in bytes. <= 0 means "contiguous" ) { init_stride_1D(r, 3); P1(r, 0) = 0.0; P1(r, 1) = 0.0; P1(r, 2) = 0.0; } void mrcal_identity_Rt_full(double* Rt, // (4,3) array int Rt_stride0, // in bytes. <= 0 means "contiguous" int Rt_stride1 // in bytes. <= 0 means "contiguous" ) { init_stride_2D(Rt, 4,3); mrcal_identity_R_full(Rt, Rt_stride0, Rt_stride1); for(int i=0; i<3; i++) P2(Rt, 3, i) = 0.0; } void mrcal_identity_rt_full(double* rt, // (6,) array int rt_stride0 // in bytes. <= 0 means "contiguous" ) { init_stride_1D(rt, 6); mrcal_identity_r_full(rt, rt_stride0); for(int i=0; i<3; i++) P1(rt, i+3) = 0.0; } void mrcal_rotate_point_R_full( // output double* x_out, // (3,) array int x_out_stride0, // in bytes. <= 0 means "contiguous" double* J_R, // (3,3,3) array. May be NULL int J_R_stride0, // in bytes. <= 0 means "contiguous" int J_R_stride1, // in bytes. <= 0 means "contiguous" int J_R_stride2, // in bytes. <= 0 means "contiguous" double* J_x, // (3,3) array. May be NULL int J_x_stride0, // in bytes. <= 0 means "contiguous" int J_x_stride1, // in bytes. <= 0 means "contiguous" // input const double* R, // (3,3) array. May be NULL int R_stride0, // in bytes. <= 0 means "contiguous" int R_stride1, // in bytes. <= 0 means "contiguous" const double* x_in, // (3,) array. May be NULL int x_in_stride0, // in bytes. <= 0 means "contiguous" bool inverted // if true, I apply a // rotation in the opposite // direction. J_R corresponds // to the input R ) { init_stride_1D(x_out, 3); init_stride_3D(J_R, 3,3,3 ); init_stride_2D(J_x, 3,3 ); init_stride_2D(R, 3,3 ); init_stride_1D(x_in, 3 ); if(inverted) { // transpose R int tmp; tmp = R_stride0; R_stride0 = R_stride1; R_stride1 = tmp; tmp = J_R_stride1; J_R_stride1 = J_R_stride2; J_R_stride2 = tmp; } if(J_R) { // out[i] = inner(R[i,:],in) for(int i=0; i<3; i++) { int j=0; for(; j a = R'b - R't void mrcal_invert_Rt_full( // output double* Rt_out, // (4,3) array int Rt_out_stride0, // in bytes. <= 0 means "contiguous" int Rt_out_stride1, // in bytes. <= 0 means "contiguous" // input const double* Rt_in, // (4,3) array int Rt_in_stride0, // in bytes. <= 0 means "contiguous" int Rt_in_stride1 // in bytes. <= 0 means "contiguous" ) { init_stride_2D(Rt_out, 4,3); init_stride_2D(Rt_in, 4,3); // transpose(R). Extra stuff to make in-place operations work for(int i=0; i<3; i++) P2(Rt_out,i,i) = P2(Rt_in,i,i); for(int i=0; i<3; i++) for(int j=i+1; j<3; j++) { double tmp = P2(Rt_in,i,j); P2(Rt_out,i,j) = P2(Rt_in,j,i); P2(Rt_out,j,i) = tmp; } // -transpose(R)*t mul_vec3_gen33t_vout_scaled_full(&P2(Rt_out,3,0), Rt_out_stride1, &P2(Rt_in, 3,0), Rt_in_stride1, Rt_out, Rt_out_stride0, Rt_out_stride1, -1.0); } // Invert an rt transformation // // b = rotate(a) + t -> a = invrotate(b) - invrotate(t) // // drout_drin is not returned: it is always -I // drout_dtin is not returned: it is always 0 void mrcal_invert_rt_full( // output double* rt_out, // (6,) array int rt_out_stride0, // in bytes. <= 0 means "contiguous" double* dtout_drin, // (3,3) array int dtout_drin_stride0, // in bytes. <= 0 means "contiguous" int dtout_drin_stride1, // in bytes. <= 0 means "contiguous" double* dtout_dtin, // (3,3) array int dtout_dtin_stride0, // in bytes. <= 0 means "contiguous" int dtout_dtin_stride1, // in bytes. <= 0 means "contiguous" // input const double* rt_in, // (6,) array int rt_in_stride0 // in bytes. <= 0 means "contiguous" ) { init_stride_1D(rt_out, 6); // init_stride_2D(dtout_drin, 3,3); init_stride_2D(dtout_dtin, 3,3); init_stride_1D(rt_in, 6); // r uses an angle-axis representation, so to undo a rotation r, I can apply // a rotation -r (same axis, equal and opposite angle) for(int i=0; i<3; i++) P1(rt_out,i) = -P1(rt_in,i); mrcal_rotate_point_r_full( &P1(rt_out,3), rt_out_stride0, dtout_drin, dtout_drin_stride0, dtout_drin_stride1, dtout_dtin, dtout_dtin_stride0, dtout_dtin_stride1, // input rt_out, rt_out_stride0, &P1(rt_in,3), rt_in_stride0, false); for(int i=0; i<3; i++) P1(rt_out,3+i) *= -1.; if(dtout_dtin) for(int i=0; i<3; i++) for(int j=0; j<3; j++) P2(dtout_dtin,i,j) *= -1.; } // Compose two Rt transformations // R0*(R1*x + t1) + t0 = // (R0*R1)*x + R0*t1+t0 void mrcal_compose_Rt_full( // output double* Rt_out, // (4,3) array int Rt_out_stride0, // in bytes. <= 0 means "contiguous" int Rt_out_stride1, // in bytes. <= 0 means "contiguous" // input const double* Rt_0, // (4,3) array int Rt_0_stride0, // in bytes. <= 0 means "contiguous" int Rt_0_stride1, // in bytes. <= 0 means "contiguous" const double* Rt_1, // (4,3) array int Rt_1_stride0, // in bytes. <= 0 means "contiguous" int Rt_1_stride1 // in bytes. <= 0 means "contiguous" ) { init_stride_2D(Rt_out, 4,3); init_stride_2D(Rt_0, 4,3); init_stride_2D(Rt_1, 4,3); // for in-place operation double t0[] = { P2(Rt_0,3,0), P2(Rt_0,3,1), P2(Rt_0,3,2) }; // t <- R0*t1 mul_vec3_gen33t_vout_full(&P2(Rt_out,3,0), Rt_out_stride1, &P2(Rt_1, 3,0), Rt_1_stride1, Rt_0, Rt_0_stride0, Rt_0_stride1); // R <- R0*R1 mul_gen33_gen33_vout_full( Rt_out, Rt_out_stride0, Rt_out_stride1, Rt_0, Rt_0_stride0, Rt_0_stride1, Rt_1, Rt_1_stride0, Rt_1_stride1 ); // t <- R0*t1+t0 for(int i=0; i<3; i++) P2(Rt_out,3,i) += t0[i]; } // Compose two rt transformations. It is assumed that we're getting no gradients // at all or we're getting ALL the gradients: only dr_r0 is checked for NULL // // dr_dt0 is not returned: it is always 0 // dr_dt1 is not returned: it is always 0 // dt_dr1 is not returned: it is always 0 // dt_dt0 is not returned: it is always the identity matrix void mrcal_compose_rt_full( // output double* rt_out, // (6,) array int rt_out_stride0, // in bytes. <= 0 means "contiguous" double* dr_r0, // (3,3) array; may be NULL int dr_r0_stride0, // in bytes. <= 0 means "contiguous" int dr_r0_stride1, // in bytes. <= 0 means "contiguous" double* dr_r1, // (3,3) array; may be NULL int dr_r1_stride0, // in bytes. <= 0 means "contiguous" int dr_r1_stride1, // in bytes. <= 0 means "contiguous" double* dt_r0, // (3,3) array; may be NULL int dt_r0_stride0, // in bytes. <= 0 means "contiguous" int dt_r0_stride1, // in bytes. <= 0 means "contiguous" double* dt_t1, // (3,3) array; may be NULL int dt_t1_stride0, // in bytes. <= 0 means "contiguous" int dt_t1_stride1, // in bytes. <= 0 means "contiguous" // input const double* rt_0, // (6,) array int rt_0_stride0, // in bytes. <= 0 means "contiguous" const double* rt_1, // (6,) array int rt_1_stride0 // in bytes. <= 0 means "contiguous" ) { init_stride_1D(rt_out, 6); init_stride_2D(dr_r0, 3,3); init_stride_2D(dr_r1, 3,3); init_stride_2D(dt_r0, 3,3); init_stride_2D(dt_t1, 3,3); init_stride_1D(rt_0, 6); init_stride_1D(rt_1, 6); // r0 (r1 x + t1) + t0 = r0 r1 x + r0 t1 + t0 // -> I want (r0 r1, r0 t1 + t0) // to make in-place operation work double rt0[6]; for(int i=0; i<6; i++) rt0[i] = P1(rt_0, i); // Compute r01 mrcal_compose_r_full( rt_out, rt_out_stride0, dr_r0, dr_r0_stride0, dr_r0_stride1, dr_r1, dr_r1_stride0, dr_r1_stride1, rt_0, rt_0_stride0, rt_1, rt_1_stride0); // t01 <- r0 t1 mrcal_rotate_point_r_full( &P1(rt_out,3), rt_out_stride0, dt_r0, dt_r0_stride0, dt_r0_stride1, dt_t1, dt_t1_stride0, dt_t1_stride1, rt0, -1, &P1(rt_1,3), rt_1_stride0, false ); // t01 <- r0 t1 + t0 for(int i=0; i<3; i++) P1(rt_out,3+i) += rt0[3+i]; } void mrcal_compose_r_tinyr0_gradientr0_full( // output double* dr_dr0, // (3,3) array; may be NULL int dr_dr0_stride0, // in bytes. <= 0 means "contiguous" int dr_dr0_stride1, // in bytes. <= 0 means "contiguous" // input const double* r_1, // (3,) array int r_1_stride0 // in bytes. <= 0 means "contiguous" ) { init_stride_2D(dr_dr0, 3, 3); init_stride_1D(r_1, 3); // All the comments and logic appear in compose_r_core() in // poseutils-uses-autodiff.cc. This is a special-case function with // manually-computed gradients (because I want to make sure they're fast) double norm2_r1 = 0.0; for(int i=0; i<3; i++) norm2_r1 += P1(r_1,i)*P1(r_1,i); if(norm2_r1 < 2e-8*2e-8) { // Both vectors are tiny, so I have r01 = r0 + r1, and the gradient is // an identity matrix for(int i=0; i<3; i++) for(int j=0; j<3; j++) P2(dr_dr0,i,j) = i==j ? 1.0 : 0.0; return; } // I have // r01 = r1 // - inner(r0,r1) (B/tanB - 1) / 4B^2 r1 // + B/tanB r0 // + cross(r0,r1) / 2 // // I differentiate: // // dr01/dr0 = // - outer(r1,r1) (B/tanB - 1) / 4B^2 // + B/tanB I // - skew_symmetric(r1) / 2 double B = sqrt(norm2_r1) / 2.; double B_over_tanB = B / tan(B); for(int i=0; i<3; i++) for(int j=0; j<3; j++) P2(dr_dr0,i,j) = - P1(r_1,i)*P1(r_1,j) * (B_over_tanB - 1.) / (4.*B*B); for(int i=0; i<3; i++) P2(dr_dr0,i,i) += B_over_tanB; P2(dr_dr0,0,1) -= -P1(r_1,2)/2.; P2(dr_dr0,0,2) -= P1(r_1,1)/2.; P2(dr_dr0,1,0) -= P1(r_1,2)/2.; P2(dr_dr0,1,2) -= -P1(r_1,0)/2.; P2(dr_dr0,2,0) -= -P1(r_1,1)/2.; P2(dr_dr0,2,1) -= P1(r_1,0)/2.; } mrcal-2.4.1/poseutils.h000066400000000000000000000650071456301662300150320ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #pragma once #include // Unless specified all arrays stored in contiguous matrices in row-major order. // // All functions are defined using the mrcal_..._full() form, which supports // non-contiguous input and output arrays, and some optional arguments. Strides // are used to specify the array layout. // // All functions have a convenience wrapper macro that is a simpler way to call // the function, usable with contiguous arrays and defaults. // // All the functions use double-precision floating point to store the data, and // C ints to store strides. The strides are given in bytes. In the // mrcal_..._full() functions, each array is followed by the strides, one per // dimension. // // I have two different representations of pose transformations: // // - Rt is a concatenated (4,3) array: Rt = nps.glue(R,t, axis=-2). The // transformation is R*x+t // // - rt is a concatenated (6,) array: rt = nps.glue(r,t, axis=-1). The // transformation is R*x+t where R = R_from_r(r) // // I treat all vectors as column vectors, so matrix multiplication works from // the left: to rotate a vector x by a rotation matrix R I have // // x_rotated = R * x // Store an identity rotation matrix into the given (3,3) array // // This is simply an identity matrix #define mrcal_identity_R(R) mrcal_identity_R_full(R,0,0) void mrcal_identity_R_full(double* R, // (3,3) array int R_stride0, // in bytes. <= 0 means "contiguous" int R_stride1 // in bytes. <= 0 means "contiguous" ); // Store an identity rodrigues rotation into the given (3,) array // // This is simply an array of zeros #define mrcal_identity_r(r) mrcal_identity_r_full(r,0) void mrcal_identity_r_full(double* r, // (3,) array int r_stride0 // in bytes. <= 0 means "contiguous" ); // Store an identity Rt transformation into the given (4,3) array #define mrcal_identity_Rt(Rt) mrcal_identity_Rt_full(Rt,0,0) void mrcal_identity_Rt_full(double* Rt, // (4,3) array int Rt_stride0, // in bytes. <= 0 means "contiguous" int Rt_stride1 // in bytes. <= 0 means "contiguous" ); // Store an identity rt transformation into the given (6,) array #define mrcal_identity_rt(rt) mrcal_identity_rt_full(rt,0) void mrcal_identity_rt_full(double* rt, // (6,) array int rt_stride0 // in bytes. <= 0 means "contiguous" ); // Rotate the point x_in in a (3,) array by the rotation matrix R in a (3,3) // array. This is simply the matrix-vector multiplication R x_in // // The result is returned in a (3,) array x_out. // // The gradient dx_out/dR is returned in a (3, 3,3) array J_R. Set to NULL if // this is not wanted // // The gradient dx_out/dx_in is returned in a (3,3) array J_x. This is simply // the matrix R. Set to NULL if this is not wanted // // In-place operation is supported; the output array may be the same as the // input arrays to overwrite the input. #define mrcal_rotate_point_R( x_out,J_R,J_x,R,x_in) mrcal_rotate_point_R_full(x_out,0,J_R,0,0,0,J_x,0,0,R,0,0,x_in,0, false) #define mrcal_rotate_point_R_inverted(x_out,J_R,J_x,R,x_in) mrcal_rotate_point_R_full(x_out,0,J_R,0,0,0,J_x,0,0,R,0,0,x_in,0, true) void mrcal_rotate_point_R_full( // output double* x_out, // (3,) array int x_out_stride0, // in bytes. <= 0 means "contiguous" double* J_R, // (3,3,3) array. May be NULL int J_R_stride0, // in bytes. <= 0 means "contiguous" int J_R_stride1, // in bytes. <= 0 means "contiguous" int J_R_stride2, // in bytes. <= 0 means "contiguous" double* J_x, // (3,3) array. May be NULL int J_x_stride0, // in bytes. <= 0 means "contiguous" int J_x_stride1, // in bytes. <= 0 means "contiguous" // input const double* R, // (3,3) array. May be NULL int R_stride0, // in bytes. <= 0 means "contiguous" int R_stride1, // in bytes. <= 0 means "contiguous" const double* x_in, // (3,) array. May be NULL int x_in_stride0, // in bytes. <= 0 means "contiguous" bool inverted // if true, I apply a // rotation in the opposite // direction. J_R corresponds // to the input R ); // Rotate the point x_in in a (3,) array by the rodrigues rotation in a (3,) // array. // // The result is returned in a (3,) array x_out. // // The gradient dx_out/dr is returned in a (3,3) array J_r. Set to NULL if this // is not wanted // // The gradient dx_out/dx_in is returned in a (3,3) array J_x. Set to NULL if // this is not wanted // // In-place operation is supported; the output array may be the same as the // input arrays to overwrite the input. #define mrcal_rotate_point_r( x_out,J_r,J_x,r,x_in) mrcal_rotate_point_r_full(x_out,0,J_r,0,0,J_x,0,0,r,0,x_in,0, false) #define mrcal_rotate_point_r_inverted(x_out,J_r,J_x,r,x_in) mrcal_rotate_point_r_full(x_out,0,J_r,0,0,J_x,0,0,r,0,x_in,0, true) void mrcal_rotate_point_r_full( // output double* x_out, // (3,) array int x_out_stride0, // in bytes. <= 0 means "contiguous" double* J_r, // (3,3) array. May be NULL int J_r_stride0, // in bytes. <= 0 means "contiguous" int J_r_stride1, // in bytes. <= 0 means "contiguous" double* J_x, // (3,3) array. May be NULL int J_x_stride0, // in bytes. <= 0 means "contiguous" int J_x_stride1, // in bytes. <= 0 means "contiguous" // input const double* r, // (3,) array. May be NULL int r_stride0, // in bytes. <= 0 means "contiguous" const double* x_in, // (3,) array. May be NULL int x_in_stride0, // in bytes. <= 0 means "contiguous" bool inverted // if true, I apply a // rotation in the opposite // direction. J_r corresponds // to the input r ); // Transform the point x_in in a (3,) array by the Rt transformation in a (4,3) // array. // // The result is returned in a (3,) array x_out. // // The gradient dx_out/dRt is returned in a (3, 4,3) array J_Rt. Set to NULL if // this is not wanted // // The gradient dx_out/dx_in is returned in a (3,3) array J_x. This is simply // the matrix R. Set to NULL if this is not wanted // // In-place operation is supported; the output array may be the same as the // input arrays to overwrite the input. #define mrcal_transform_point_Rt( x_out,J_Rt,J_x,Rt,x_in) mrcal_transform_point_Rt_full(x_out,0,J_Rt,0,0,0,J_x,0,0,Rt,0,0,x_in,0, false) #define mrcal_transform_point_Rt_inverted(x_out,J_Rt,J_x,Rt,x_in) mrcal_transform_point_Rt_full(x_out,0,J_Rt,0,0,0,J_x,0,0,Rt,0,0,x_in,0, true) void mrcal_transform_point_Rt_full( // output double* x_out, // (3,) array int x_out_stride0, // in bytes. <= 0 means "contiguous" double* J_Rt, // (3,4,3) array. May be NULL int J_Rt_stride0, // in bytes. <= 0 means "contiguous" int J_Rt_stride1, // in bytes. <= 0 means "contiguous" int J_Rt_stride2, // in bytes. <= 0 means "contiguous" double* J_x, // (3,3) array. May be NULL int J_x_stride0, // in bytes. <= 0 means "contiguous" int J_x_stride1, // in bytes. <= 0 means "contiguous" // input const double* Rt, // (4,3) array. May be NULL int Rt_stride0, // in bytes. <= 0 means "contiguous" int Rt_stride1, // in bytes. <= 0 means "contiguous" const double* x_in, // (3,) array. May be NULL int x_in_stride0, // in bytes. <= 0 means "contiguous" bool inverted // if true, I apply a // transformation in the opposite // direction. J_Rt corresponds // to the input Rt ); // Transform the point x_in in a (3,) array by the rt transformation in a (6,) // array. // // The result is returned in a (3,) array x_out. // // The gradient dx_out/drt is returned in a (3,6) array J_rt. Set to NULL if // this is not wanted // // The gradient dx_out/dx_in is returned in a (3,3) array J_x. This is simply // the matrix R. Set to NULL if this is not wanted // // In-place operation is supported; the output array may be the same as the // input arrays to overwrite the input. #define mrcal_transform_point_rt( x_out,J_rt,J_x,rt,x_in) mrcal_transform_point_rt_full(x_out,0,J_rt,0,0,J_x,0,0,rt,0,x_in,0, false) #define mrcal_transform_point_rt_inverted(x_out,J_rt,J_x,rt,x_in) mrcal_transform_point_rt_full(x_out,0,J_rt,0,0,J_x,0,0,rt,0,x_in,0, true) void mrcal_transform_point_rt_full( // output double* x_out, // (3,) array int x_out_stride0, // in bytes. <= 0 means "contiguous" double* J_rt, // (3,6) array. May be NULL int J_rt_stride0, // in bytes. <= 0 means "contiguous" int J_rt_stride1, // in bytes. <= 0 means "contiguous" double* J_x, // (3,3) array. May be NULL int J_x_stride0, // in bytes. <= 0 means "contiguous" int J_x_stride1, // in bytes. <= 0 means "contiguous" // input const double* rt, // (6,) array. May be NULL int rt_stride0, // in bytes. <= 0 means "contiguous" const double* x_in, // (3,) array. May be NULL int x_in_stride0, // in bytes. <= 0 means "contiguous" bool inverted // if true, I apply the // transformation in the // opposite direction. // J_rt corresponds to // the input rt ); // Convert a rotation matrix in a (3,3) array to a rodrigues vector in a (3,) // array // // The result is returned in a (3,) array r // // The gradient dr/dR is returned in a (3, 3,3) array J. Set to NULL if this is // not wanted #define mrcal_r_from_R(r,J,R) mrcal_r_from_R_full(r,0,J,0,0,0,R,0,0) void mrcal_r_from_R_full( // output double* r, // (3,) vector int r_stride0, // in bytes. <= 0 means "contiguous" double* J, // (3,3,3) array. Gradient. May be NULL int J_stride0, // in bytes. <= 0 means "contiguous" int J_stride1, // in bytes. <= 0 means "contiguous" int J_stride2, // in bytes. <= 0 means "contiguous" // input const double* R, // (3,3) array int R_stride0, // in bytes. <= 0 means "contiguous" int R_stride1 // in bytes. <= 0 means "contiguous" ); // Convert a rodrigues vector in a (3,) array to a rotation matrix in a (3,3) // array // // The result is returned in a (3,3) array R // // The gradient dR/dr is returned in a (3,3 ,3) array J. Set to NULL if this is // not wanted #define mrcal_R_from_r(R,J,r) mrcal_R_from_r_full(R,0,0,J,0,0,0,r,0) void mrcal_R_from_r_full( // outputs double* R, // (3,3) array int R_stride0, // in bytes. <= 0 means "contiguous" int R_stride1, // in bytes. <= 0 means "contiguous" double* J, // (3,3,3) array. Gradient. May be NULL int J_stride0, // in bytes. <= 0 means "contiguous" int J_stride1, // in bytes. <= 0 means "contiguous" int J_stride2, // in bytes. <= 0 means "contiguous" // input const double* r, // (3,) vector int r_stride0 // in bytes. <= 0 means "contiguous" ); // Invert a rotation matrix. This is a transpose // // The input is given in R_in in a (3,3) array // // The result is returned in a (3,3) array R_out // // In-place operation is supported; the output array may be the same as the // input arrays to overwrite the input. #define mrcal_invert_R(R_out,R_in) mrcal_invert_R_full(R_out,0,0,R_in,0,0) void mrcal_invert_R_full( // output double* R_out, // (3,3) array int R_out_stride0, // in bytes. <= 0 means "contiguous" int R_out_stride1, // in bytes. <= 0 means "contiguous" // input const double* R_in, // (3,3) array int R_in_stride0, // in bytes. <= 0 means "contiguous" int R_in_stride1 // in bytes. <= 0 means "contiguous" ); // Convert an Rt transformation in a (4,3) array to an rt transformation in a // (6,) array // // The result is returned in a (6,) array rt // // The gradient dr/dR is returned in a (3, 3,3) array J_R. Set to NULL if this // is not wanted // // The t terms are identical, so dt/dt = identity and I do not return it // // The r and R terms are independent of the t terms, so dr/dt and dt/dR are both // 0, and I do not return them #define mrcal_rt_from_Rt(rt,J_R,Rt) mrcal_rt_from_Rt_full(rt,0,J_R,0,0,0,Rt,0,0) void mrcal_rt_from_Rt_full( // output double* rt, // (6,) vector int rt_stride0, // in bytes. <= 0 means "contiguous" double* J_R, // (3,3,3) array. Gradient. May be NULL // No J_t. It's always the identity int J_R_stride0, // in bytes. <= 0 means "contiguous" int J_R_stride1, // in bytes. <= 0 means "contiguous" int J_R_stride2, // in bytes. <= 0 means "contiguous" // input const double* Rt, // (4,3) array int Rt_stride0, // in bytes. <= 0 means "contiguous" int Rt_stride1 // in bytes. <= 0 means "contiguous" ); // Convert an rt transformation in a (6,) array to an Rt transformation in a // (4,3) array // // The result is returned in a (4,3) array Rt // // The gradient dR/dr is returned in a (3,3 ,3) array J_r. Set to NULL if this // is not wanted // // The t terms are identical, so dt/dt = identity and I do not return it // // The r and R terms are independent of the t terms, so dR/dt and dt/dr are both // 0, and I do not return them #define mrcal_Rt_from_rt(Rt,J_r,rt) mrcal_Rt_from_rt_full(Rt,0,0,J_r,0,0,0,rt,0) void mrcal_Rt_from_rt_full( // output double* Rt, // (4,3) array int Rt_stride0, // in bytes. <= 0 means "contiguous" int Rt_stride1, // in bytes. <= 0 means "contiguous" double* J_r, // (3,3,3) array. Gradient. May be NULL // No J_t. It's just the identity int J_r_stride0, // in bytes. <= 0 means "contiguous" int J_r_stride1, // in bytes. <= 0 means "contiguous" int J_r_stride2, // in bytes. <= 0 means "contiguous" // input const double* rt, // (6,) vector int rt_stride0 // in bytes. <= 0 means "contiguous" ); // Invert an Rt transformation // // The input is given in Rt_in in a (4,3) array // // The result is returned in a (4,3) array Rt_out // // In-place operation is supported; the output array may be the same as the // input arrays to overwrite the input. #define mrcal_invert_Rt(Rt_out,Rt_in) mrcal_invert_Rt_full(Rt_out,0,0,Rt_in,0,0) void mrcal_invert_Rt_full( // output double* Rt_out, // (4,3) array int Rt_out_stride0, // in bytes. <= 0 means "contiguous" int Rt_out_stride1, // in bytes. <= 0 means "contiguous" // input const double* Rt_in, // (4,3) array int Rt_in_stride0, // in bytes. <= 0 means "contiguous" int Rt_in_stride1 // in bytes. <= 0 means "contiguous" ); // Invert an rt transformation // // The input is given in rt_in in a (6,) array // // The result is returned in a (6,) array rt_out // // The gradient dtout/drin is returned in a (3,3) array dtout_drin. Set to NULL // if this is not wanted // // The gradient dtout/dtin is returned in a (3,3) array dtout_dtin. Set to NULL // if this is not wanted // // The gradient drout/drin is always -identity. So it is not returned // // The gradient drout/dtin is always 0. So it is not returned // // In-place operation is supported; the output array may be the same as the // input arrays to overwrite the input. #define mrcal_invert_rt(rt_out,dtout_drin,dtout_dtin,rt_in) mrcal_invert_rt_full(rt_out,0,dtout_drin,0,0,dtout_dtin,0,0,rt_in,0) void mrcal_invert_rt_full( // output double* rt_out, // (6,) array int rt_out_stride0, // in bytes. <= 0 means "contiguous" double* dtout_drin, // (3,3) array int dtout_drin_stride0, // in bytes. <= 0 means "contiguous" int dtout_drin_stride1, // in bytes. <= 0 means "contiguous" double* dtout_dtin, // (3,3) array int dtout_dtin_stride0, // in bytes. <= 0 means "contiguous" int dtout_dtin_stride1, // in bytes. <= 0 means "contiguous" // input const double* rt_in, // (6,) array int rt_in_stride0 // in bytes. <= 0 means "contiguous" ); // Compose two Rt transformations // // Rt = Rt0 * Rt1 ---> Rt(x) = Rt0( Rt1(x) ) // // The input transformations are given in (4,3) arrays Rt_0 and Rt_1 // // The result is returned in a (4,3) array Rt_out // // In-place operation is supported; the output array may be the same as either // of the input arrays to overwrite the input. #define mrcal_compose_Rt(Rt_out,Rt_0,Rt_1) mrcal_compose_Rt_full(Rt_out,0,0,Rt_0,0,0,Rt_1,0,0) void mrcal_compose_Rt_full( // output double* Rt_out, // (4,3) array int Rt_out_stride0, // in bytes. <= 0 means "contiguous" int Rt_out_stride1, // in bytes. <= 0 means "contiguous" // input const double* Rt_0, // (4,3) array int Rt_0_stride0, // in bytes. <= 0 means "contiguous" int Rt_0_stride1, // in bytes. <= 0 means "contiguous" const double* Rt_1, // (4,3) array int Rt_1_stride0, // in bytes. <= 0 means "contiguous" int Rt_1_stride1 // in bytes. <= 0 means "contiguous" ); // Compose two rt transformations // // rt = rt0 * rt1 ---> rt(x) = rt0( rt1(x) ) // // The input transformations are given in (6,) arrays rt_0 and rt_1 // // The result is returned in a (6,) array rt_out // // The gradient dr/dr0 is returned in a (3,3) array dr_dr0. Set to NULL if this // is not wanted // // The gradient dr/dr1 is returned in a (3,3) array dr_dr1. Set to NULL if this // is not wanted // // The gradient dt/dr0 is returned in a (3,3) array dt_dr0. Set to NULL if this // is not wanted // // The gradient dt/dt1 is returned in a (3,3) array dt_dt1. Set to NULL if this // is not wanted // // The gradients dr/dt0, dr/dt1, dt/dr1 are always 0, so they are never returned // // The gradient dt/dt0 is always identity, so it is never returned // // In-place operation is supported; the output array may be the same as either // of the input arrays to overwrite the input. #define mrcal_compose_rt(rt_out,dr_dr0,dr_dr1,dt_dr0,dt_dt1,rt_0,rt_1) mrcal_compose_rt_full(rt_out,0,dr_dr0,0,0,dr_dr1,0,0,dt_dr0,0,0,dt_dt1,0,0,rt_0,0,rt_1,0) void mrcal_compose_rt_full( // output double* rt_out, // (6,) array int rt_out_stride0, // in bytes. <= 0 means "contiguous" double* dr_dr0, // (3,3) array; may be NULL int dr_dr0_stride0, // in bytes. <= 0 means "contiguous" int dr_dr0_stride1, // in bytes. <= 0 means "contiguous" double* dr_dr1, // (3,3) array; may be NULL int dr_dr1_stride0, // in bytes. <= 0 means "contiguous" int dr_dr1_stride1, // in bytes. <= 0 means "contiguous" double* dt_dr0, // (3,3) array; may be NULL int dt_dr0_stride0, // in bytes. <= 0 means "contiguous" int dt_dr0_stride1, // in bytes. <= 0 means "contiguous" double* dt_dt1, // (3,3) array; may be NULL int dt_dt1_stride0, // in bytes. <= 0 means "contiguous" int dt_dt1_stride1, // in bytes. <= 0 means "contiguous" // input const double* rt_0, // (6,) array int rt_0_stride0, // in bytes. <= 0 means "contiguous" const double* rt_1, // (6,) array int rt_1_stride0 // in bytes. <= 0 means "contiguous" ); // Compose two angle-axis rotations // // r = r0 * r1 ---> r(x) = r0( r1(x) ) // // The input rotations are given in (3,) arrays r_0 and r_1 // // The result is returned in a (3,) array r_out // // The gradient dr/dr0 is returned in a (3,3) array dr_dr0. Set to NULL if this // is not wanted // // The gradient dr/dr1 is returned in a (3,3) array dr_dr1. Set to NULL if this // is not wanted // // In-place operation is supported; the output array may be the same as either // of the input arrays to overwrite the input. #define mrcal_compose_r(r_out,dr_dr0,dr_dr1,r_0,r_1) mrcal_compose_r_full(r_out,0,dr_dr0,0,0,dr_dr1,0,0,r_0,0,r_1,0) void mrcal_compose_r_full( // output double* r_out, // (3,) array int r_out_stride0, // in bytes. <= 0 means "contiguous" double* dr_dr0, // (3,3) array; may be NULL int dr_dr0_stride0, // in bytes. <= 0 means "contiguous" int dr_dr0_stride1, // in bytes. <= 0 means "contiguous" double* dr_dr1, // (3,3) array; may be NULL int dr_dr1_stride0, // in bytes. <= 0 means "contiguous" int dr_dr1_stride1, // in bytes. <= 0 means "contiguous" // input const double* r_0, // (3,) array int r_0_stride0, // in bytes. <= 0 means "contiguous" const double* r_1, // (3,) array int r_1_stride0 // in bytes. <= 0 means "contiguous" ); // Special-case rotation composition for the uncertainty computation // // Same as mrcal_compose_r() except // // - r0 is assumed to be 0, so we don't ingest it, and we don't report the // composition result // - we ONLY report the dr01/dr0 gradient // // In python this function is equivalent to // // _,dr01_dr0,_ = compose_r(np.zeros((3,),), // r1, // get_gradients=True) #define mrcal_compose_r_tinyr0_gradientr0(dr_dr0,r_1) \ mrcal_compose_r_tinyr0_gradientr0_full(dr_dr0,0,0,r_1,0) void mrcal_compose_r_tinyr0_gradientr0_full( // output double* dr_dr0, // (3,3) array; may be NULL int dr_dr0_stride0, // in bytes. <= 0 means "contiguous" int dr_dr0_stride1, // in bytes. <= 0 means "contiguous" // input const double* r_1, // (3,) array int r_1_stride0 // in bytes. <= 0 means "contiguous" ); mrcal-2.4.1/save_image.docstring000066400000000000000000000020221456301662300166340ustar00rootroot00000000000000Save a numpy array to an image on disk SYNOPSIS print(image.shape) ---> (768, 1024, 3) print(image.dtype) ---> dtype('uint8') mrcal.save_image("result.png", image) # wrote BGR color image to disk This is a completely uninteresting image-saving routine. It's like any other image-saving routine out there; use any that you like. This exists because cv2 is very slow. This wraps the mrcal_image_TYPE_save() functions. At this time I support only these 3 data formats: - bpp = 8, channels = 1: 8-bit grayscale data - bpp = 16, channels = 1: 16-bit grayscale data - bpp = 24, channels = 3: BGR color data ARGUMENTS - filename: the image on disk to save to - array: numpy array containing the input data. Must have shape (height,width) for grayscale data or (height,width,3) for color data. Each row must be stored densely, but a non-dense stride is supported when moving from column to column. The dtype must be either np.uint8 or np.uint16. RETURNED VALUE None on success. Exception thrown on error mrcal-2.4.1/state_index_calobject_warp.docstring000066400000000000000000000054621456301662300221150ustar00rootroot00000000000000Return the index in the optimization vector of the calibration object warp SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() b = mrcal.optimizer_callback(**optimization_inputs)[0] mrcal.unpack_state(b, **optimization_inputs) i_state = mrcal.state_index_calobject_warp(**optimization_inputs) calobject_warp = b[i_state:i_state+2] The optimization algorithm sees its world described in one, big vector of state. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. The mrcal.state_index_...() functions report where particular items end up in the state vector. THIS function reports the beginning of the calibration-object warping parameters in the state vector. This is stored contiguously as a 2-element vector. These warping parameters describe how the observed calibration object differs from the expected calibration object. There will always be some difference due to manufacturing tolerances and temperature and humidity effects. In order to determine the variable mapping, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_calobject_warp do_optimize_frames optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed Nobservations_board optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting the location in the state vector where the contiguous block of variables for the calibration object warping begins. If we're not optimizing the calibration object shape, returns None mrcal-2.4.1/state_index_extrinsics.docstring000066400000000000000000000063371456301662300213330ustar00rootroot00000000000000Return the index in the optimization vector of the extrinsics of camera i SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() b = mrcal.optimizer_callback(**optimization_inputs)[0] mrcal.unpack_state(b, **optimization_inputs) icam_extrinsics = 1 i_state = mrcal.state_index_extrinsics(icam_extrinsics, **optimization_inputs) extrinsics_rt_fromref = b[i_state:i_state+6] The optimization algorithm sees its world described in one, big vector of state. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. The mrcal.state_index_...() functions report where particular items end up in the state vector. THIS function reports the beginning of the i-th camera extrinsics in the state vector. The extrinsics are stored contiguously as an "rt transformation": a 3-element rotation represented as a Rodrigues vector followed by a 3-element translation. These transform points represented in the reference coordinate system to the coordinate system of the specific camera. Note that mrcal allows the reference coordinate system to be tied to a particular camera. In this case the extrinsics of that camera do not appear in the state vector at all, and icam_extrinsics == -1 in the indices_frame_camintrinsics_camextrinsics array. In order to determine the variable mapping, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - icam_extrinsics: an integer indicating which camera we're asking about - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_calobject_warp do_optimize_frames optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed Nobservations_board optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting the location in the state vector where the contiguous block of extrinsics for camera icam_extrinsics begins. If we're not optimizing the extrinsics, or we're asking for an out-of-bounds camera, returns None mrcal-2.4.1/state_index_frames.docstring000066400000000000000000000057541456301662300204170ustar00rootroot00000000000000Return the index in the optimization vector of the pose of frame i SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() b = mrcal.optimizer_callback(**optimization_inputs)[0] mrcal.unpack_state(b, **optimization_inputs) iframe = 1 i_state = mrcal.state_index_frames(iframe, **optimization_inputs) frames_rt_toref = b[i_state:i_state+6] The optimization algorithm sees its world described in one, big vector of state. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. The mrcal.state_index_...() functions report where particular items end up in the state vector. THIS function reports the beginning of the i-th frame pose in the state vector. Here a "frame" is a pose of the observed calibration object at some instant in time. The frames are stored contiguously as an "rt transformation": a 3-element rotation represented as a Rodrigues vector followed by a 3-element translation. These transform points represented in the internal calibration object coordinate system to the reference coordinate system. In order to determine the variable mapping, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - iframe: an integer indicating which frame we're asking about - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_calobject_warp do_optimize_frames optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed Nobservations_board optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting the location in the state vector where the contiguous block of variables for frame iframe begins. If we're not optimizing the frames, or we're asking for an out-of-bounds frame, returns None mrcal-2.4.1/state_index_intrinsics.docstring000066400000000000000000000064631456301662300213250ustar00rootroot00000000000000Return the index in the optimization vector of the intrinsics of camera i SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() b = mrcal.optimizer_callback(**optimization_inputs)[0] mrcal.unpack_state(b, **optimization_inputs) icam_intrinsics = 1 i_state = mrcal.state_index_intrinsics(icam_intrinsics, **optimization_inputs) Nintrinsics = mrcal.lensmodel_num_params(optimization_inputs['lensmodel']) intrinsics_data = b[i_state:i_state+Nintrinsics] The optimization algorithm sees its world described in one, big vector of state. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. The mrcal.state_index_...() functions report where particular items end up in the state vector. THIS function reports the beginning of the i-th camera intrinsics in the state vector. The intrinsics are stored contiguously. They consist of a 4-element "intrinsics core" (focallength-x, focallength-y, centerpixel-x, centerpixel-y) followed by a lensmodel-specific vector of "distortions". The number of intrinsics elements (including the core) for a particular lens model can be queried with mrcal.lensmodel_num_params(lensmodel). Note that do_optimize_intrinsics_core and do_optimize_intrinsics_distortions can be used to lock down one or both of those quantities, which would omit them from the optimization vector. In order to determine the variable mapping, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - icam_intrinsics: an integer indicating which camera we're asking about - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_calobject_warp do_optimize_frames optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed Nobservations_board optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting the location in the state vector where the contiguous block of intrinsics for camera icam_intrinsics begins. If we're not optimizing the intrinsics, or we're asking for an out-of-bounds camera, returns None mrcal-2.4.1/state_index_points.docstring000066400000000000000000000053171456301662300204510ustar00rootroot00000000000000Return the index in the optimization vector of the position of point i SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() b = mrcal.optimizer_callback(**optimization_inputs)[0] mrcal.unpack_state(b, **optimization_inputs) i_point = 1 i_state = mrcal.state_index_points(i_point, **optimization_inputs) point = b[i_state:i_state+3] The optimization algorithm sees its world described in one, big vector of state. The optimizer doesn't know or care about the meaning of each element of this vector, but for later analysis, it is useful to know what's what. The mrcal.state_index_...() functions report where particular items end up in the state vector. THIS function reports the beginning of the i-th point in the state vector. The points are stored contiguously as a 3-element coordinates in the reference frame. In order to determine the variable mapping, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - i_point: an integer indicating which point we're asking about - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_calobject_warp do_optimize_frames optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed Nobservations_board optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE The integer reporting the location in the state vector where the contiguous block of variables for point i_point begins If we're not optimizing the points, or we're asking for an out-of-bounds point, returns None mrcal-2.4.1/stereo-matching-libelas.cc000066400000000000000000000074771456301662300176520ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #include extern "C" { #include "stereo-matching-libelas.h" }; void mrcal_stereo_matching_libelas( // output float* disparity0, float* disparity1, // input const uint8_t* image0, const uint8_t* image1, // image dimensions. The stride applies to the // input only. The output is stored densely uint32_t width, uint32_t height, uint32_t stride, // parameters. These are the fields in // Elas::Elas::parameters. This function provides // no defaults: eerything must be set int32_t disparity_min, int32_t disparity_max, float support_threshold, int32_t support_texture, int32_t candidate_stepsize, int32_t incon_window_size, int32_t incon_threshold, int32_t incon_min_support, bool add_corners, int32_t grid_size, float beta, float gamma, float sigma, float sradius, int32_t match_texture, int32_t lr_threshold, float speckle_sim_threshold, int32_t speckle_size, int32_t ipol_gap_width, bool filter_median, bool filter_adaptive_mean, bool postprocess_only_left, bool subsampling ) { Elas::Elas::parameters param; param.disp_min = disparity_min; param.disp_max = disparity_max; param.support_threshold = support_threshold; param.support_texture = support_texture; param.candidate_stepsize = candidate_stepsize; param.incon_window_size = incon_window_size; param.incon_threshold = incon_threshold; param.incon_min_support = incon_min_support; param.add_corners = add_corners; param.grid_size = grid_size; param.beta = beta; param.gamma = gamma; param.sigma = sigma; param.sradius = sradius; param.match_texture = match_texture; param.lr_threshold = lr_threshold; param.speckle_sim_threshold = speckle_sim_threshold; param.speckle_size = speckle_size; param.ipol_gap_width = ipol_gap_width; param.filter_median = filter_median; param.filter_adaptive_mean = filter_adaptive_mean; param.postprocess_only_left = postprocess_only_left; param.subsampling = subsampling; Elas::Elas elas(param); const int32_t dimensions[] = { (int32_t)width, (int32_t)height, (int32_t)stride }; elas.process((uint8_t*)image0, // these really are const (uint8_t*)image1, disparity0, disparity1, dimensions); } mrcal-2.4.1/stereo-matching-libelas.h000066400000000000000000000044211456301662300174760ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #pragma once void mrcal_stereo_matching_libelas( // output float* disparity0, float* disparity1, // input const uint8_t* image0, const uint8_t* image1, // image dimensions. The stride applies to the // input only. The output is stored densely uint32_t width, uint32_t height, uint32_t stride, // parameters. These are the fields in // Elas::Elas::parameters. This function provides // no defaults: eerything must be set int32_t disparity_min, int32_t disparity_max, float support_threshold, int32_t support_texture, int32_t candidate_stepsize, int32_t incon_window_size, int32_t incon_threshold, int32_t incon_min_support, bool add_corners, int32_t grid_size, float beta, float gamma, float sigma, float sradius, int32_t match_texture, int32_t lr_threshold, float speckle_sim_threshold, int32_t speckle_size, int32_t ipol_gap_width, bool filter_median, bool filter_adaptive_mean, bool postprocess_only_left, bool subsampling ); mrcal-2.4.1/stereo.c000066400000000000000000001231701456301662300142730ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // Apparently I need this in MSVC to get constants #define _USE_MATH_DEFINES #include #include #include "mrcal.h" #include "minimath/minimath.h" #include "util.h" // The equivalent function in Python is _rectified_resolution_python() in // stereo.py // // Documentation is in the docstring of mrcal.rectified_resolution() bool mrcal_rectified_resolution( // output and input // > 0: use given value // < 0: autodetect and scale double* pixels_per_deg_az, double* pixels_per_deg_el, // input const mrcal_lensmodel_t* lensmodel, const double* intrinsics, const mrcal_point2_t* azel_fov_deg, const mrcal_point2_t* azel0_deg, const double* R_cam0_rect0, const mrcal_lensmodel_type_t rectification_model_type) { // Get the rectified image resolution if( *pixels_per_deg_az < 0 || *pixels_per_deg_el < 0) { const mrcal_point2_t azel0 = {.x = azel0_deg->x * M_PI/180., .y = azel0_deg->y * M_PI/180. }; // I need to compute the resolution of the rectified images. I try to // match the resolution of the cameras. I just look at camera0. If your // two cameras are different, pass in the pixels_per_deg yourself // // I look at the center of the stereo field of view. There I have q = // project(v) where v is a unit projection vector. I compute dq/dth where // th is an angular perturbation applied to v. double v[3]; double dv_dazel[3*2]; if(rectification_model_type == MRCAL_LENSMODEL_LATLON) mrcal_unproject_latlon((mrcal_point3_t*)v, (mrcal_point2_t*)dv_dazel, &azel0, 1, (double[]){1.,1.,0.,0.}); else if(rectification_model_type == MRCAL_LENSMODEL_LONLAT) mrcal_unproject_lonlat((mrcal_point3_t*)v, (mrcal_point2_t*)dv_dazel, &azel0, 1, (double[]){1.,1.,0.,0.}); else if(rectification_model_type == MRCAL_LENSMODEL_PINHOLE) { mrcal_point2_t q0_normalized = {.x = tan(azel0.x), .y = tan(azel0.y)}; mrcal_unproject_pinhole((mrcal_point3_t*)v, (mrcal_point2_t*)dv_dazel, &q0_normalized, 1, (double[]){1.,1.,0.,0.}); // dq/dth = dtanth/dth = 1/cos^2(th) double cos_az0 = cos(azel0.x); double cos_el0 = cos(azel0.y); for(int i=0; i<3; i++) { dv_dazel[2*i + 0] /= cos_az0*cos_az0; dv_dazel[2*i + 1] /= cos_el0*cos_el0; } } else { MSG("Unsupported rectification model"); return false; } double v0[3]; mrcal_rotate_point_R(v0, NULL,NULL, R_cam0_rect0, v); // dv0_dazel = nps.matmult(R_cam0_rect0, dv_dazel) double dv0_daz[3] = {}; double dv0_del[3] = {}; for(int j=0; j<3; j++) for(int k=0; k<3; k++) { dv0_daz[j] += R_cam0_rect0[j*3+k]*dv_dazel[2*k + 0]; dv0_del[j] += R_cam0_rect0[j*3+k]*dv_dazel[2*k + 1]; } mrcal_point2_t qdummy; mrcal_point3_t dq_dv0[2]; // _,dq_dv0,_ = mrcal.project(v0, *model.intrinsics(), get_gradients = True) mrcal_project(&qdummy,dq_dv0,NULL, (const mrcal_point3_t*)v0, 1, lensmodel, intrinsics); // More complex method that's probably not any better // // if False: // // I rotate my v to a coordinate system where u = rotate(v) is [0,0,1]. // // Then u = [a,b,0] are all orthogonal to v. So du/dth = [cos, sin, 0]. // // I then have dq/dth = dq/dv dv/du [cos, sin, 0]t // // ---> dq/dth = dq/dv dv/du[:,:2] [cos, sin]t = M [cos,sin]t // // // // norm2(dq/dth) = [cos,sin] MtM [cos,sin]t is then an ellipse with the // // eigenvalues of MtM giving me the best and worst sensitivities. I can // // use mrcal.worst_direction_stdev() to find the densest direction. But I // // actually know the directions I care about, so I evaluate them // // independently for the az and el directions // Ruv = mrcal.R_aligned_to_vector(v0); // M = nps.matmult(dq_dv0, nps.transpose(Ruv[:2,:])) // // I pick the densest direction: highest |dq/dth| // pixels_per_rad = mrcal.worst_direction_stdev( nps.matmult( nps.transpose(M),M) ); // dq_dazel = nps.matmult(dq_dv0, dv0_dazel) double dq_daz[2] = { dq_dv0[0].x*dv0_daz[0] + dq_dv0[0].y*dv0_daz[1] + dq_dv0[0].z*dv0_daz[2], dq_dv0[1].x*dv0_daz[0] + dq_dv0[1].y*dv0_daz[1] + dq_dv0[1].z*dv0_daz[2] }; double dq_del[2] = { dq_dv0[0].x*dv0_del[0] + dq_dv0[0].y*dv0_del[1] + dq_dv0[0].z*dv0_del[2], dq_dv0[1].x*dv0_del[0] + dq_dv0[1].y*dv0_del[1] + dq_dv0[1].z*dv0_del[2] }; if(*pixels_per_deg_az < 0) { double dq_daz_norm2 = 0.; for(int i=0; i<2; i++) dq_daz_norm2 += dq_daz[i]*dq_daz[i]; double pixels_per_deg_az_have = sqrt(dq_daz_norm2)*M_PI/180.; *pixels_per_deg_az *= -pixels_per_deg_az_have; } if(*pixels_per_deg_el < 0) { double dq_del_norm2 = 0.; for(int i=0; i<2; i++) dq_del_norm2 += dq_del[i]*dq_del[i]; double pixels_per_deg_el_have = sqrt(dq_del_norm2)*M_PI/180.; *pixels_per_deg_el *= -pixels_per_deg_el_have; } } // I now have the desired pixels_per_deg // // With LENSMODEL_LATLON or LENSMODEL_LONLAT we have even angular spacing, so // q = f th + c -> dq/dth = f everywhere. I can thus compute the rectified // image size and adjust the resolution accordingly // // With LENSMODEL_PINHOLE this is much more complex, so this function just // leaves the desired pixels_per_deg as it is if(rectification_model_type == MRCAL_LENSMODEL_LATLON || rectification_model_type == MRCAL_LENSMODEL_LONLAT) { int Naz = (int)round(azel_fov_deg->x * (*pixels_per_deg_az)); int Nel = (int)round(azel_fov_deg->y * (*pixels_per_deg_el)); *pixels_per_deg_az = (double)Naz/azel_fov_deg->x; *pixels_per_deg_el = (double)Nel/azel_fov_deg->y; } return true; } // The equivalent function in Python is _rectified_system_python() in stereo.py // // Documentation is in the docstring of mrcal.rectified_system() bool mrcal_rectified_system(// output unsigned int* imagersize_rectified, double* fxycxy_rectified, double* rt_rect0_ref, double* baseline, // input, output // > 0: use given value // < 0: autodetect and scale double* pixels_per_deg_az, double* pixels_per_deg_el, // input, output // if(..._autodetect) { the results are returned here } mrcal_point2_t* azel_fov_deg, mrcal_point2_t* azel0_deg, // input const mrcal_lensmodel_t* lensmodel0, const double* intrinsics0, const double* rt_cam0_ref, const double* rt_cam1_ref, const mrcal_lensmodel_type_t rectification_model_type, bool az0_deg_autodetect, bool el0_deg_autodetect, bool az_fov_deg_autodetect, bool el_fov_deg_autodetect) { if(el0_deg_autodetect) { MSG("el0_deg_autodetect is unsupported"); return false; } if(az_fov_deg_autodetect) { MSG("az_fov_deg_autodetect is unsupported"); return false; } if(el_fov_deg_autodetect) { MSG("el_fov_deg_autodetect is unsupported"); return false; } if( !(rectification_model_type == MRCAL_LENSMODEL_LATLON || rectification_model_type == MRCAL_LENSMODEL_PINHOLE) ) { MSG("Unsupported rectification model '%s'. Only LENSMODEL_LATLON and LENSMODEL_PINHOLE are supported", mrcal_lensmodel_name_unconfigured( &(mrcal_lensmodel_t){.type = rectification_model_type})); return false; } mrcal_lensmodel_metadata_t meta = mrcal_lensmodel_metadata( lensmodel0 ); if(meta.noncentral) { if(lensmodel0->type == MRCAL_LENSMODEL_CAHVORE) { // CAHVORE is generally noncentral, but if E=0, then it is const int Nintrinsics = mrcal_lensmodel_num_params(lensmodel0); for(int i=Nintrinsics-3; i0 if we're trying to specify a value, or <0 to autodetect"); return false; } if(*pixels_per_deg_el == 0) { MSG("pixels_per_deg_el == 0 is illegal. Must be >0 if we're trying to specify a value, or <0 to autodetect"); return false; } if( azel_fov_deg->x <= 0. || azel_fov_deg->y <= 0.) { MSG("az_fov_deg, el_fov_deg must be > 0. No auto-detection implemented yet"); return false; } // Compute the geometry of the rectified stereo system. This is a // rotation, centered at camera0. More or less we have axes: // // x: from camera0 to camera1 // y: completes the system from x,z // z: component of the cameras' viewing direction // normal to the baseline double Rt_cam0_ref[4*3]; double Rt_cam1_ref[4*3]; mrcal_Rt_from_rt(Rt_cam0_ref, NULL, rt_cam0_ref); mrcal_Rt_from_rt(Rt_cam1_ref, NULL, rt_cam1_ref); double Rt01[4*3]; double Rt_ref_cam1[4*3]; mrcal_invert_Rt(Rt_ref_cam1,Rt_cam1_ref); mrcal_compose_Rt(Rt01, Rt_cam0_ref, Rt_ref_cam1); // Rotation relating camera0 coords to the rectified camera coords. I fill in // each row separately double Rt_rect0_cam0[4*3] = {}; double* R_rect0_cam0 = Rt_rect0_cam0; // Axes of the rectified system, in the cam0 coord system double* right = &R_rect0_cam0[0*3 + 0]; double* down = &R_rect0_cam0[1*3 + 0]; double* forward = &R_rect0_cam0[2*3 + 0]; // "right" of the rectified coord system: towards the origin of camera1 from // camera0, in camera0 coords for(int i=0; i<3; i++) right[i] = Rt01[3*3 + i]; *baseline = 0.0; for(int i=0; i<3; i++) *baseline += right[i]*right[i]; *baseline = sqrt(*baseline); for(int i=0; i<3; i++) right[i] /= (*baseline); // "forward" of the rectified coord system, in camera0 coords. The mean // optical-axis direction of the two cameras: component orthogonal to "right" double forward01[3] = { Rt01[0*3 + 2], Rt01[1*3 + 2], Rt01[2*3 + 2] + 1., }; double forward01_proj_right = 0.0; for(int i=0; i<3; i++) forward01_proj_right += forward01[i]*right[i]; for(int i=0; i<3; i++) forward[i] = forward01[i] - forward01_proj_right*right[i]; double norm2_forward = 0.; for(int i=0; i<3; i++) norm2_forward += forward[i]*forward[i]; for(int i=0; i<3; i++) forward[i] /= sqrt(norm2_forward); // "down" of the rectified coord system, in camera0 coords. Completes the // right,down,forward coordinate system // down = cross(forward,right) down[0] = forward[1]*right[2] - forward[2]*right[1]; down[1] = forward[2]*right[0] - forward[0]*right[2]; down[2] = forward[0]*right[1] - forward[1]*right[0]; // Done with the geometry! Now to get the az/el grid. I need to figure // out the resolution and the extents mrcal_point2_t azel0 = { .x = azel0_deg->x * M_PI/180., .y = azel0_deg->y * M_PI/180. }; if(az0_deg_autodetect) { // In the rectified system az=0 sits perpendicular to the baseline. // Normally the cameras are looking out perpendicular to the baseline // also, so I center my azimuth samples around 0 to match the cameras' // field of view. But what if the geometry isn't square, and one camera // is behind the other? Like this: // // camera // view // ^ // | // \ | / // \_/ // . / // . /az=0 // ./ // . // baseline . // . // \ / // \_/ // // Here the center-of-view axis of each camera is not at all // perpendicular to the baseline. Thus I compute the mean "forward" // direction of the cameras in the rectified system, and set that as the // center azimuth az0. double norm2_forward01 = 0.0; for(int i=0; i<3; i++) norm2_forward01 += forward01[i]*forward01[i]; azel0.x = asin( forward01_proj_right / sqrt(norm2_forward01) ); azel0_deg->x = azel0.x * 180./M_PI; } double R_cam0_rect0[3*3]; mrcal_invert_R(R_cam0_rect0, R_rect0_cam0); if(!mrcal_rectified_resolution( // output pixels_per_deg_az, pixels_per_deg_el, // input lensmodel0, intrinsics0, azel_fov_deg, azel0_deg, R_cam0_rect0, rectification_model_type)) return false; // How do we apply the desired pixels_per_deg? // // With LENSMODEL_LATLON we have even angular spacing, so q = f th + c -> // dq/dth = f everywhere. // // With LENSMODEL_PINHOLE the angular resolution changes across the image: q // = f tan(th) + c -> dq/dth = f/cos^2(th). So at the center, th=0 and we // have the maximum resolution fxycxy_rectified[0] = *pixels_per_deg_az / M_PI*180.; fxycxy_rectified[1] = *pixels_per_deg_el / M_PI*180.; // if rectification_model == 'LENSMODEL_LATLON': // # The angular resolution is consistent everywhere, so fx,fy are already // # set. Let's set cx,cy such that // # (az0,el0) = unproject(imager center) // Naz = round(az_fov_deg*pixels_per_deg_az) // Nel = round(el_fov_deg*pixels_per_deg_el) imagersize_rectified[0] = (int)round(azel_fov_deg->x * (*pixels_per_deg_az)); imagersize_rectified[1] = (int)round(azel_fov_deg->y * (*pixels_per_deg_el)); // fxycxy[2:] = // np.array(((Naz-1.)/2.,(Nel-1.)/2.)) - // np.array((az0,el0)) * fxycxy[:2] fxycxy_rectified[2] = ((double)(imagersize_rectified[0] - 1)) / 2 - azel0.x * fxycxy_rectified[0]; fxycxy_rectified[3] = ((double)(imagersize_rectified[1] - 1)) / 2 - azel0.y * fxycxy_rectified[1]; if(imagersize_rectified[1] <= 0) { MSG("Resulting stereo geometry has Nel=%d. This is nonsensical. You should examine the geometry or adjust the elevation bounds or pixels-per-deg", imagersize_rectified[1]); return false; } // The geometry double Rt_rect0_ref[4*3]; mrcal_compose_Rt(Rt_rect0_ref, Rt_rect0_cam0, Rt_cam0_ref); mrcal_rt_from_Rt(rt_rect0_ref, NULL, Rt_rect0_ref); return true; } static void set_rectification_map_pixel(// output float* rectification_map0, float* rectification_map1, // input const int i, const int j, const mrcal_point3_t* v, const mrcal_lensmodel_t* lensmodel0, const double* intrinsics0, const double* R_cam0_rect, const mrcal_lensmodel_t* lensmodel1, const double* intrinsics1, const double* R_cam1_rect, const unsigned int* imagersize_rectified) { mrcal_point3_t vcam; mrcal_point2_t q; vcam = *v; mrcal_rotate_point_R(vcam.xyz, NULL, NULL, R_cam0_rect, v->xyz); mrcal_project(&q, NULL, NULL, &vcam, 1, lensmodel0, intrinsics0); rectification_map0[(i*imagersize_rectified[0] + j)*2 + 0] = (float)q.x; rectification_map0[(i*imagersize_rectified[0] + j)*2 + 1] = (float)q.y; vcam = *v; mrcal_rotate_point_R(vcam.xyz, NULL, NULL, R_cam1_rect, v->xyz); mrcal_project(&q, NULL, NULL, &vcam, 1, lensmodel1, intrinsics1); rectification_map1[(i*imagersize_rectified[0] + j)*2 + 0] = (float)q.x; rectification_map1[(i*imagersize_rectified[0] + j)*2 + 1] = (float)q.y; } bool mrcal_rectification_maps(// output // Dense array of shape (Ncameras=2, Nel, Naz, Nxy=2) float* rectification_maps, // input const mrcal_lensmodel_t* lensmodel0, const double* intrinsics0, const double* r_cam0_ref, const mrcal_lensmodel_t* lensmodel1, const double* intrinsics1, const double* r_cam1_ref, const mrcal_lensmodel_type_t rectification_model_type, const double* fxycxy_rectified, const unsigned int* imagersize_rectified, const double* r_rect0_ref) { ///// TODAY this C implementation supports MRCAL_LENSMODEL_LATLON only. This ///// isn't a design choice, I just don't want to do the extra work yet. The ///// API already is general enough to support both rectification schemes. if( ! (rectification_model_type == MRCAL_LENSMODEL_LATLON || rectification_model_type == MRCAL_LENSMODEL_PINHOLE) ) { MSG("%s() supports MRCAL_LENSMODEL_LATLON and MRCAL_LENSMODEL_PINHOLE only", __func__); return false; } double R_cam0_ref[3*3]; double R_cam1_ref[3*3]; mrcal_R_from_r(R_cam0_ref, NULL, r_cam0_ref); mrcal_R_from_r(R_cam1_ref, NULL, r_cam1_ref); double R_cam0_rect[3*3]; double R_cam1_rect[3*3]; double R_rect0_ref[3*3]; mrcal_R_from_r(R_rect0_ref, NULL, r_rect0_ref); mul_genN3_gen33t_vout(3, R_cam0_ref, R_rect0_ref, R_cam0_rect); mul_genN3_gen33t_vout(3, R_cam1_ref, R_rect0_ref, R_cam1_rect); float* rectification_map0 = &(rectification_maps[0]); float* rectification_map1 = &(rectification_maps[imagersize_rectified[0]*imagersize_rectified[1]*2]); // I had this: // for(int i=0; i= 0.57f) x = 1.f; else x = x / 0.32f - 0.78125f; break; case 31: if (x <= 0.42f) x = 0.f; else if (x >= 0.92f) x = 1.f; else x = 2.f * x - 0.84f; break; case 32: if (x <= 0.42f) x *= 4.f; else x = (x <= 0.92f) ? -2.f * x + 1.84f : x / 0.08f - 11.5f; break; case 33: x = fabsf(2.f * x - 0.5f); break; case 34: x = 2.f * x; break; case 35: x = 2.f * x - 0.5f; break; case 36: x = 2.f * x - 1.f; break; default: return false; } if (x <= 0.f) x = 0.f; else if (x >= 1.f) x = 1.f; // round to nearest integer *out = (uint8_t)(0.5f + 255.0f*x); return true; } // Color-code an array // I use gnuplot's color-mapping functions to do this. gnuplot's "show palette" // help message displays the current gnuplot settings and "test palette" // displays the palette. The function definitions are given by "show palette // rgbformulae": // // > show palette rgbformulae // * there are 37 available rgb color mapping formulae: // 0: 0 1: 0.5 2: 1 // 3: x 4: x^2 5: x^3 // 6: x^4 7: sqrt(x) 8: sqrt(sqrt(x)) // 9: sin(90x) 10: cos(90x) 11: |x-0.5| // 12: (2x-1)^2 13: sin(180x) 14: |cos(180x)| // 15: sin(360x) 16: cos(360x) 17: |sin(360x)| // 18: |cos(360x)| 19: |sin(720x)| 20: |cos(720x)| // 21: 3x 22: 3x-1 23: 3x-2 // 24: |3x-1| 25: |3x-2| 26: (3x-1)/2 // 27: (3x-2)/2 28: |(3x-1)/2| 29: |(3x-2)/2| // 30: x/0.32-0.78125 31: 2*x-0.84 32: 4x;1;-2x+1.84;x/0.08-11.5 // 33: |2*x - 0.5| 34: 2*x 35: 2*x - 0.5 // 36: 2*x - 1 // * negative numbers mean inverted=negative colour component // * thus the ranges in `set pm3d rgbformulae' are -36..36 #define DEFINE_mrcal_apply_color_map(T,Tname,T_MIN,T_MAX) \ bool mrcal_apply_color_map_##Tname( \ mrcal_image_bgr_t* out, \ const mrcal_image_##Tname##_t* in, \ \ /* If true, I set in_min/in_max from the */ \ /* min/max of the input data */ \ const bool auto_min, \ const bool auto_max, \ \ /* If true, I implement gnuplot's default 7,5,15 mapping. */ \ /* This is a reasonable default choice. */ \ /* function_red/green/blue are ignored if true */ \ const bool auto_function, \ \ /* min/max input values to use if not */ \ /* auto_min/auto_max */ \ T in_min, /* will map to 0 */ \ T in_max, /* will map to 255 */ \ \ /* The color mappings to use. If !auto_function */ \ int function_red, \ int function_green, \ int function_blue) \ { \ const int w = in->width; \ const int h = in->height; \ if(!(w == out->width && h == out->height)) \ { \ MSG("%s(): input and output images MUST have the same dimensions", \ __func__); \ return false; \ } \ \ if(auto_min || auto_max) \ { \ if(auto_min) in_min = T_MAX; \ if(auto_max) in_max = T_MIN; \ \ for(int y=0; y in_max) in_max = v; \ } \ } \ \ if(auto_function) \ { \ function_red = 7; \ function_green = 5; \ function_blue = 15; \ } \ \ for(int y=0; y= in_max) \ x = 1.0f; \ else \ x = (float)(*in_T - in_min) / (float)(in_max - in_min); \ \ if(!gnuplot_color_formula(&out_bgr->bgr[2], function_red, x) || \ !gnuplot_color_formula(&out_bgr->bgr[1], function_green, x) || \ !gnuplot_color_formula(&out_bgr->bgr[0], function_blue, x)) \ return false; \ } \ } \ \ return true; \ } DEFINE_mrcal_apply_color_map(uint8_t, uint8, 0, UINT8_MAX) DEFINE_mrcal_apply_color_map(uint16_t, uint16, 0, UINT16_MAX) DEFINE_mrcal_apply_color_map(uint32_t, uint32, 0, UINT32_MAX) DEFINE_mrcal_apply_color_map(uint64_t, uint64, 0, UINT64_MAX) DEFINE_mrcal_apply_color_map(int8_t, int8, INT8_MIN, INT8_MAX) DEFINE_mrcal_apply_color_map(int16_t, int16, INT16_MIN, INT16_MAX) DEFINE_mrcal_apply_color_map(int32_t, int32, INT32_MIN, INT32_MAX) DEFINE_mrcal_apply_color_map(int64_t, int64, INT64_MIN, INT64_MAX) DEFINE_mrcal_apply_color_map(float, float, FLT_MIN, FLT_MAX) DEFINE_mrcal_apply_color_map(double, double, DBL_MIN, DBL_MAX) static bool _validate_rectification_model_type(const mrcal_lensmodel_type_t rectification_model_type) { if(rectification_model_type == MRCAL_LENSMODEL_LATLON || rectification_model_type == MRCAL_LENSMODEL_PINHOLE) return true; // ERROR const char* rectification_model_string = mrcal_lensmodel_name_unconfigured( &(mrcal_lensmodel_t){.type = rectification_model_type} ); if(rectification_model_string == NULL) { MSG("Unknown rectification_model_type=%d\n", rectification_model_type); return false; } MSG("Invalid rectification_model_type for rectification: %s; I know about MRCAL_LENSMODEL_LATLON and MRCAL_LENSMODEL_PINHOLE\n", rectification_model_string); return false; } static double _stereo_range_one(const double disparity, const mrcal_point2_t qrect0, // models_rectified const mrcal_lensmodel_type_t rectification_model_type, const double* fxycxy_rectified, const double baseline ) { // See the docstring for mrcal.stereo_range() for the derivation const double fx = fxycxy_rectified[0]; const double fy = fxycxy_rectified[1]; const double cx = fxycxy_rectified[2]; const double cy = fxycxy_rectified[3]; if(rectification_model_type == MRCAL_LENSMODEL_LATLON) { const double az0 = (qrect0.x - cx)/fx; const double disparity_rad = disparity / fx; const double range = baseline * cos(az0 - disparity_rad) / sin(disparity_rad); if(!isfinite(range)) return 0.0; return range; } // _validate_rectification_model_type() makes sure this is true // if(rectification_model_type == MRCAL_LENSMODEL_PINHOLE) { const double tanaz0 = (qrect0.x - cx) / fx; const double tanel = (qrect0.y - cy) / fy; const double s_sq_recip = tanel*tanel + 1.; const double tanaz0_tanaz1 = disparity / fx; const double tanaz1 = tanaz0 - tanaz0_tanaz1; const double range = baseline / sqrt(s_sq_recip + tanaz0*tanaz0) * ( (s_sq_recip + tanaz0*tanaz1) / tanaz0_tanaz1 + tanaz0 ); if(!isfinite(range)) return 0.0; return range; } } bool mrcal_stereo_range_sparse(// output double* range, // N of these // input const double* disparity, // N of these const mrcal_point2_t* qrect0, // N of these const int N, // how many points const double disparity_min, const double disparity_max, // models_rectified const mrcal_lensmodel_type_t rectification_model_type, const double* fxycxy_rectified, const double baseline) { if(!_validate_rectification_model_type(rectification_model_type)) return false; if(disparity_min >= disparity_max) { MSG("Must have disparity_max > disparity_min"); return false; } for(int i=0; i disparity_max ) { range[i] = 0.0; } else range[i] = _stereo_range_one(disparity[i], qrect0[i], rectification_model_type, fxycxy_rectified, baseline); } return true; } bool mrcal_stereo_range_dense(// output mrcal_image_double_t* range, // input const mrcal_image_uint16_t* disparity_scaled, const uint16_t disparity_scale, // Used to detect invalid values. Set to // 0,UINT16_MAX to ignore const uint16_t disparity_scaled_min, const uint16_t disparity_scaled_max, // models_rectified const mrcal_lensmodel_type_t rectification_model_type, const double* fxycxy_rectified, const double baseline) { if(!_validate_rectification_model_type(rectification_model_type)) return false; if(disparity_scaled_min >= disparity_scaled_max) { MSG("Must have disparity_scaled_max > disparity_scaled_min"); return false; } if(range->width != disparity_scaled->width || range->height != disparity_scaled->height) { MSG("range and disparity_scaled MUST have the same dimensions. Got (W,H): (%d,%d) and (%d,%d) respectively\n", range->width, range->height, disparity_scaled->width, disparity_scaled->height); return false; } const int W = range->width; const int H = range->height; for(int i=0; i disparity_scaled_max ) { r_row[j] = 0.0; } else r_row[j] = _stereo_range_one((double)(d_row[j]) / (double)disparity_scale, (mrcal_point2_t){.x = (double)j, .y = (double)i}, rectification_model_type, fxycxy_rectified, baseline); } } return true; } mrcal-2.4.1/stereo.h000066400000000000000000000136421456301662300143020ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #pragma once #include "mrcal-types.h" #include "mrcal-image.h" // The reference implementation in Python is _rectified_resolution_python() in // stereo.py // // The Python wrapper is mrcal.rectified_resolution(), and the documentation is // in the docstring of that function bool mrcal_rectified_resolution( // output and input // > 0: use given value // < 0: autodetect and scale double* pixels_per_deg_az, double* pixels_per_deg_el, // input const mrcal_lensmodel_t* lensmodel, const double* intrinsics, const mrcal_point2_t* azel_fov_deg, const mrcal_point2_t* azel0_deg, const double* R_cam0_rect0, const mrcal_lensmodel_type_t rectification_model_type); // The reference implementation in Python is _rectified_system_python() in // stereo.py // // The Python wrapper is mrcal.rectified_system(), and the documentation is in // the docstring of that function bool mrcal_rectified_system(// output unsigned int* imagersize_rectified, double* fxycxy_rectified, double* rt_rect0_ref, double* baseline, // input, output // > 0: use given value // < 0: autodetect and scale double* pixels_per_deg_az, double* pixels_per_deg_el, // input, output // if(..._autodetect) { the results are returned here } mrcal_point2_t* azel_fov_deg, mrcal_point2_t* azel0_deg, // input const mrcal_lensmodel_t* lensmodel0, const double* intrinsics0, const double* rt_cam0_ref, const double* rt_cam1_ref, const mrcal_lensmodel_type_t rectification_model_type, bool az0_deg_autodetect, bool el0_deg_autodetect, bool az_fov_deg_autodetect, bool el_fov_deg_autodetect); // The reference implementation in Python is _rectification_maps_python() in // stereo.py // // The Python wrapper is mrcal.rectification_maps(), and the documentation is in // the docstring of that function bool mrcal_rectification_maps(// output // Dense array of shape (Ncameras=2, Nel, Naz, Nxy=2) float* rectification_maps, // input const mrcal_lensmodel_t* lensmodel0, const double* intrinsics0, const double* r_cam0_ref, const mrcal_lensmodel_t* lensmodel1, const double* intrinsics1, const double* r_cam1_ref, const mrcal_lensmodel_type_t rectification_model_type, const double* fxycxy_rectified, const unsigned int* imagersize_rectified, const double* r_rect0_ref); // The reference implementation in Python is _stereo_range_python() in // stereo.py // // The Python wrapper is mrcal.stereo_range(), and the documentation is in // the docstring of that function bool mrcal_stereo_range_sparse(// output double* range, // N of these // input const double* disparity, // N of these const mrcal_point2_t* qrect0, // N of these const int N, // how many points const double disparity_min, const double disparity_max, // models_rectified const mrcal_lensmodel_type_t rectification_model_type, const double* fxycxy_rectified, const double baseline); bool mrcal_stereo_range_dense(// output mrcal_image_double_t* range, // input const mrcal_image_uint16_t* disparity_scaled, const uint16_t disparity_scale, // Used to detect invalid values. Set to // 0,UINT16_MAX to ignore const uint16_t disparity_scaled_min, const uint16_t disparity_scaled_max, // models_rectified const mrcal_lensmodel_type_t rectification_model_type, const double* fxycxy_rectified, const double baseline); mrcal-2.4.1/strides.h000066400000000000000000000035111456301662300144500ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #pragma once // This is an internal header to make the stride logic work. Not to be seen by // the end-users or installed // stride-aware matrix access #define _P1(x, stride0, i0) \ (*(double*)( (char*)(x) + \ (i0) * (stride0))) #define _P2(x, stride0, stride1, i0, i1) \ (*(double*)( (char*)(x) + \ (i0) * (stride0) + \ (i1) * (stride1))) #define _P3(x, stride0, stride1, stride2,i0, i1, i2) \ (*(double*)( (char*)(x) + \ (i0) * (stride0) + \ (i1) * (stride1) + \ (i2) * (stride2))) #define P1(x, i0) _P1(x, x##_stride0, i0) #define P2(x, i0,i1) _P2(x, x##_stride0, x##_stride1, i0,i1) #define P3(x, i0,i1,i2) _P3(x, x##_stride0, x##_stride1, x##_stride2, i0,i1,i2) // Init strides. If a given stride is <= 0, set the default, as we would have if // the data was contiguous #define init_stride_1D(x, d0) \ if( x ## _stride0 <= 0) x ## _stride0 = sizeof(*x) #define init_stride_2D(x, d0, d1) \ if( x ## _stride1 <= 0) x ## _stride1 = sizeof(*x); \ if( x ## _stride0 <= 0) x ## _stride0 = d1 * x ## _stride1 #define init_stride_3D(x, d0, d1, d2) \ if( x ## _stride2 <= 0) x ## _stride2 = sizeof(*x); \ if( x ## _stride1 <= 0) x ## _stride1 = d2 * x ## _stride2; \ if( x ## _stride0 <= 0) x ## _stride0 = d1 * x ## _stride1 mrcal-2.4.1/supported_lensmodels.docstring000066400000000000000000000020151456301662300210100ustar00rootroot00000000000000Returns a tuple of strings for the various lens models we support SYNOPSIS print(mrcal.supported_lensmodels()) ('LENSMODEL_PINHOLE', 'LENSMODEL_STEREOGRAPHIC', 'LENSMODEL_SPLINED_STEREOGRAPHIC_...', 'LENSMODEL_OPENCV4', 'LENSMODEL_OPENCV5', 'LENSMODEL_OPENCV8', 'LENSMODEL_OPENCV12', 'LENSMODEL_CAHVOR', 'LENSMODEL_CAHVORE_linearity=...') mrcal knows about some set of lens models, which can be queried here. The above list is correct as of this writing, but more models could be added with time. The returned lens models are all supported, with possible gaps in capabilities. The capabilities of each model are returned by lensmodel_metadata_and_config(). At this time, the only missing functionality that CAHVORE is gradients aren't implemented, so we can't compute an optimal CAHVORE model. Models ending in '...' have configuration parameters given in the model string, replacing the '...'. RETURNED VALUE A tuple of strings listing out all the currently-supported lens models mrcal-2.4.1/test-gradients.c000066400000000000000000000600651456301662300157320ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #include #include #include #include #include "mrcal.h" #define SPLINED_NX 11 #define SPLINED_NY 8 static bool modelHasCore_fxfycxcy( const mrcal_lensmodel_t* lensmodel ) { mrcal_lensmodel_metadata_t meta = mrcal_lensmodel_metadata(lensmodel); return meta.has_core; } int main(int argc, char* argv[] ) { const char* usage = "Usage: %s LENSMODEL_XXX [problem-selections problem-selections ...]\n" "\n" "The lensmodels are given as the expected strings. Splined stereographic models\n" "MUST be given as either of\n" " LENSMODEL_SPLINED_STEREOGRAPHIC_2\n" " LENSMODEL_SPLINED_STEREOGRAPHIC_3\n" "\n" "problem-selections are a list of parameters we're optimizing. This is some set of\n" " intrinsic-core\n" " intrinsic-distortions\n" " extrinsics\n" " frames\n" " calobject-warp\n" "\n" "If no selections are given, we optimize everything. Otherwise, we start with an empty\n" "mrcal_problem_selections_t, and each argument sets a bit\n"; if( argc >= 2 && argv[1][0] == '-' ) { printf(usage, argv[0]); return 0; } mrcal_problem_selections_t problem_selections = {.do_apply_regularization = true}; int iarg = 1; if( iarg >= argc ) { fprintf(stderr, usage, argv[0]); return 1; } mrcal_lensmodel_t lensmodel = {.type = mrcal_lensmodel_type_from_name(argv[iarg]) }; if( !mrcal_lensmodel_type_is_valid(lensmodel.type) ) { #define QUOTED_LIST_WITH_COMMA(s,n) "'" #s "'," fprintf(stderr, "Lens model name '%s' unknown. I only know about (" MRCAL_LENSMODEL_LIST( QUOTED_LIST_WITH_COMMA ) ")\n", argv[iarg]); return 1; } if(lensmodel.type == MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC) { if(0 == strcmp(argv[iarg], "LENSMODEL_SPLINED_STEREOGRAPHIC_2")) lensmodel.LENSMODEL_SPLINED_STEREOGRAPHIC__config.order = 2; else if(0 == strcmp(argv[iarg], "LENSMODEL_SPLINED_STEREOGRAPHIC_3")) lensmodel.LENSMODEL_SPLINED_STEREOGRAPHIC__config.order = 3; else { fprintf(stderr, "A splined stereographic model must be specified as exactly one of \"LENSMODEL_SPLINED_STEREOGRAPHIC_2\" or \"LENSMODEL_SPLINED_STEREOGRAPHIC_3\". Giving up\n"); return 1; } } iarg++; if(iarg >= argc) problem_selections = ((mrcal_problem_selections_t) { .do_optimize_intrinsics_core = true, .do_optimize_intrinsics_distortions= true, .do_optimize_extrinsics = true, .do_optimize_frames = true, .do_optimize_calobject_warp = true, .do_apply_regularization = true}); else for(; iarg < argc; iarg++) { if( 0 == strcmp(argv[iarg], "intrinsic-core") ) { problem_selections.do_optimize_intrinsics_core = true; continue; } if( 0 == strcmp(argv[iarg], "intrinsic-distortions") ) { problem_selections.do_optimize_intrinsics_distortions = true; continue; } if( 0 == strcmp(argv[iarg], "extrinsics") ) { problem_selections.do_optimize_extrinsics = true; continue; } if( 0 == strcmp(argv[iarg], "frames") ) { problem_selections.do_optimize_frames = true; continue; } if( 0 == strcmp(argv[iarg], "calobject-warp" ) ) { problem_selections.do_optimize_calobject_warp = true; continue; } fprintf(stderr, "Unknown optimization variable '%s'. Giving up.\n\n", argv[iarg]); fprintf(stderr, usage, argv[0]); return 1; } mrcal_pose_t extrinsics[] = { { .r = { .xyz = { .01, .1, .02}}, .t = { .xyz = { -2.3, 0.2, 0.1}}}, { .r = { .xyz = { -.02, .03, .002}}, .t = { .xyz = { -4.0, 0.1,-0.3}}}}; mrcal_pose_t frames[] = { { .r = { .xyz = { -.1, .52, -.13}}, .t = { .xyz = { 1.3, 0.1, 10.2}}}, { .r = { .xyz = { .90, .24, .135}}, .t = { .xyz = { 0.7, 0.1, 20.3}}}, { .r = { .xyz = { .80, .52, .335}}, .t = { .xyz = { 0.7, 0.6, 30.4}}}, { .r = { .xyz = { .20, -.22, .75}}, .t = { .xyz = { 3.1, 6.3, 10.4}}}}; int Nframes = sizeof(frames) /sizeof(frames[0]); mrcal_point3_t points[] = { {.xyz = {-5.3, 2.3, 20.4}}, {.xyz = {-15.3, -3.2, 200.4}}}; mrcal_calobject_warp_t calobject_warp = {.x2 = 0.001, .y2 = -0.005}; int Npoints = sizeof(points)/sizeof(points[0]); int Npoints_fixed = 1; #define calibration_object_width_n 10 #define calibration_object_height_n 9 // The observations of chessboards and of discrete points mrcal_observation_board_t observations_board[] = { {.icam = { .intrinsics = 0, .extrinsics = -1 }, .iframe = 0}, {.icam = { .intrinsics = 1, .extrinsics = 0 }, .iframe = 0}, {.icam = { .intrinsics = 1, .extrinsics = 0 }, .iframe = 1}, {.icam = { .intrinsics = 0, .extrinsics = -1 }, .iframe = 2}, {.icam = { .intrinsics = 0, .extrinsics = -1 }, .iframe = 3}, {.icam = { .intrinsics = 1, .extrinsics = 0 }, .iframe = 3}, {.icam = { .intrinsics = 2, .extrinsics = 1 }, .iframe = 3} }; mrcal_observation_point_t observations_point[] = { {.icam = { .intrinsics = 0, .extrinsics = -1 }, .i_point = 0}, {.icam = { .intrinsics = 1, .extrinsics = 0 }, .i_point = 0}, {.icam = { .intrinsics = 1, .extrinsics = 0 }, .i_point = 1}, {.icam = { .intrinsics = 2, .extrinsics = 1 }, .i_point = 1} }; #define Nobservations_board ((int)(sizeof(observations_board)/sizeof(observations_board[0]))) #define Nobservations_point ((int)(sizeof(observations_point)/sizeof(observations_point[0]))) mrcal_point3_t observations_px [Nobservations_board][calibration_object_width_n*calibration_object_height_n] = {}; mrcal_point3_t observations_point_px[Nobservations_point] = {}; for(int i=0; ifocal_xy [0] = 2000.3; intrinsics_core->focal_xy [1] = 1900.5; intrinsics_core->center_xy[0] = 1800.3; intrinsics_core->center_xy[1] = 1790.2; intrinsics_core = (mrcal_intrinsics_core_t*)(&intrinsics[1*Nintrinsics]); intrinsics_core->focal_xy [0] = 2100.2; intrinsics_core->focal_xy [1] = 2130.4; intrinsics_core->center_xy[0] = 1830.3; intrinsics_core->center_xy[1] = 1810.2; intrinsics_core = (mrcal_intrinsics_core_t*)(&intrinsics[2*Nintrinsics]); intrinsics_core->focal_xy [0] = 2503.8; intrinsics_core->focal_xy [1] = 2730.4; intrinsics_core->center_xy[0] = 1730.3; intrinsics_core->center_xy[1] = 1610.2; if(Ncameras_intrinsics != 3) { fprintf(stderr, "Unexpected Ncameras_intrinsics=%d; should be 3\n", Ncameras_intrinsics); return 1; } if(lensmodel.type != MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC ) for(int i=0; i= 0 ? 2 : 0), istate0_calobject_warp); int Nmeasurements_boards = mrcal_num_measurements_boards(Nobservations_board, calibration_object_width_n, calibration_object_height_n); int Nmeasurements_points = mrcal_num_measurements_points(Nobservations_point); int Nmeasurements_regularization = mrcal_num_measurements_regularization(Ncameras_intrinsics, Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, Nobservations_board, problem_selections, &lensmodel); printf("## Measurement calobjects: %d measurements. Starts at measurement %d\n", Nmeasurements_boards, 0); printf("## Measurement points: %d measurements. Starts at measurement %d\n", Nmeasurements_points, Nmeasurements_boards); printf("## Measurement regularization: %d measurements. Starts at measurement %d\n", Nmeasurements_regularization, Nmeasurements_boards+Nmeasurements_points); mrcal_problem_constants_t problem_constants = { .point_min_range = 30.0, .point_max_range = 180.0}; mrcal_stats_t stats = mrcal_optimize( NULL,0, NULL,0, intrinsics, extrinsics, frames, points, &calobject_warp, Ncameras_intrinsics,Ncameras_extrinsics, Nframes, Npoints, Npoints_fixed, observations_board, observations_point, Nobservations_board, Nobservations_point, (mrcal_point3_t*)observations_px, &lensmodel, imagersizes, problem_selections, &problem_constants, 1.2, calibration_object_width_n, calibration_object_height_n, false, true); if(stats.rms_reproj_error__pixels < 0) return 1; return 0; } mrcal-2.4.1/test/000077500000000000000000000000001456301662300136015ustar00rootroot00000000000000mrcal-2.4.1/test/data/000077500000000000000000000000001456301662300145125ustar00rootroot00000000000000mrcal-2.4.1/test/data/cam0.opencv8.cameramodel000066400000000000000000000006551456301662300211140ustar00rootroot00000000000000{ 'lens_model': 'LENSMODEL_OPENCV8', # intrinsics are fx,fy,cx,cy,distortion0,distortion1,.... 'intrinsics': [ 1761.181055, 1761.250444, 1965.706996, 1087.518797, -0.01266096516, 0.03590794372, -0.0002547045941, 0.0005275929652, 0.01968883397, 0.01482863541, -0.0562239888, 0.0500223357,], # extrinsics are rt_fromref 'extrinsics': [ 2e-2, -3e-1, -1e-2, 1., 2, -3., ], 'imagersize': [ 4000, 2200 ] } mrcal-2.4.1/test/data/cam0.splined.cameramodel000066400000000000000000000123711456301662300211660ustar00rootroot00000000000000# generated on 2020-08-30 22:55:50 with ./mrcal-convert-lensmodel --radius 0 --sampled LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=16_Ny=11_fov_x_deg=120 --distance 5. --viz test/data/cam0.opencv8.cameramodel { 'lensmodel': 'LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=16_Ny=11_fov_x_deg=120', # intrinsics are fx,fy,cx,cy,distortion0,distortion1,.... 'intrinsics': [ 1761.181055, 1761.250444, 1965.706996, 1087.518797, 0, 0, 0, 0, -0.0002835974003, -0.0003584135542, -0.03022744378, -0.08203133781, -0.1543074815, -0.24202582, -0.05843239897, -0.1538549707, -0.0118594138, -0.1011319134, 0.00842618311, -0.08183901997, 0.02885130451, -0.08286249202, 0.04998193557, -0.1029775125, 0.1036207233, -0.1597676653, 0.1999521871, -0.2447525993, 0.02127981743, -0.06014178655, -0.000232072283, 7.104196588e-05, 0, 0, 0, 0, 0, 0, -0.3712237897, -0.2376420405, -0.3579958554, -0.27204923, -0.1735647366, -0.1673810994, -0.06311881688, -0.08844613941, -0.009969875876, -0.03908431207, 0.009963755297, -0.01236842645, 0.01568355818, -0.0001575435139, 0.01668064456, -0.0004669929832, 0.02380783328, -0.01350377252, 0.04672061739, -0.04139600518, 0.1062803456, -0.09292221365, 0.2252579288, -0.1735265916, 0.4140747909, -0.2742235318, 0.3143080817, -0.1737618044, 0, 0, 0, 0, -0.4880198232, -0.2291130887, -0.2591756384, -0.147616063, -0.09598225047, -0.07134443288, -0.01459103649, -0.02229409121, 0.01680285803, 0.005911031906, 0.02383315358, 0.02189319529, 0.01873205666, 0.0289381906, 0.01076090168, 0.02880244161, 0.006642550317, 0.02143486684, 0.01615953236, 0.004799607803, 0.05217806441, -0.02454323488, 0.1426158307, -0.07572185761, 0.3157255828, -0.1525232628, 0.5317348466, -0.2225577743, 0, 0, 0, 0, -0.4284240816, -0.1327106135, -0.1874072424, -0.06979429827, -0.04804231956, -0.02412477711, 0.01270022427, 0.002814628957, 0.03264754128, 0.01863643144, 0.03155025986, 0.02746126867, 0.02068654757, 0.03148544477, 0.007033398925, 0.03144791056, -0.003005645056, 0.02731415285, -0.002105802173, 0.01821254676, 0.02176034461, 0.001803651498, 0.09012743182, -0.02632387786, 0.2416423371, -0.07346567863, 0.4854474022, -0.1333927519, 0, 0, 0, 0, -0.3807655132, -0.05559984145, -0.1460518693, -0.02441806292, -0.02329571601, -0.004019550524, 0.02707852099, 0.007891030459, 0.04082203704, 0.01485634865, 0.03569130703, 0.0188064448, 0.02164963768, 0.02061150563, 0.005091703947, 0.02061850162, -0.008212773448, 0.01881051325, -0.01157208795, 0.01478895702, 0.005658879965, 0.007615525456, 0.06291110572, -0.004786331198, 0.1975953264, -0.02591229831, 0.4423155575, -0.0567943301, 0, 0, 0, 0, -0.3623136554, 0.006839553823, -0.133116841, 0.005670947685, -0.01548309668, 0.004921826677, 0.0315325526, 0.004470546635, 0.04344808889, 0.004196399043, 0.03698145581, 0.004045472706, 0.0219688506, 0.003988774, 0.004438962702, 0.004018910381, -0.009859334605, 0.004137279159, -0.01463320724, 0.00435451504, 0.0006610473754, 0.00470581174, 0.05425720526, 0.005254471709, 0.183793161, 0.006140583664, 0.4236299926, 0.007447343956, 0, 0, 0, 0, -0.3803142053, 0.06936564897, -0.1459815896, 0.03592654352, -0.02317561225, 0.01396574897, 0.027218869, 0.00111017622, 0.04093545662, -0.006424752789, 0.03575456091, -0.01069219387, 0.02164975312, -0.01261389009, 0.005027383552, -0.01255989785, -0.008339787306, -0.01051055778, -0.01174736927, -0.00603632333, 0.005459746853, 0.001862740327, 0.06273771069, 0.01541258095, 0.1974516502, 0.03836607734, 0.4416191629, 0.07178715361, 0, 0, 0, 0, -0.4269950112, 0.1467373447, -0.1872430172, 0.08180404994, -0.0478604174, 0.03443526228, 0.01294109746, 0.006411072249, 0.0328538135, -0.01006211485, 0.03166320571, -0.01924182836, 0.0206843504, -0.02340157671, 0.006905969791, -0.02330081589, -0.003246903837, -0.01890174252, -0.002436681414, -0.009303537883, 0.0214022576, 0.007924805922, 0.08983314335, 0.03734885138, 0.2412980179, 0.08645537955, 0.4833168979, 0.1484357848, 0, 0, 0, 0, -0.4829013679, 0.2416522593, -0.2586178615, 0.1603736555, -0.09582115265, 0.0824085445, -0.01433166024, 0.03204113689, 0.01703745236, 0.00303288979, 0.02397436412, -0.01340500416, 0.01871226744, -0.02061746445, 0.01058361666, -0.02041335609, 0.006306129045, -0.01273958498, 0.01573858891, 0.004509604375, 0.05173711005, 0.03483398387, 0.1422643717, 0.08756439223, 0.3147129924, 0.1661838364, 0.5250457679, 0.2356813874, 0, 0, 0, 0, -0.3590398466, 0.2445486581, -0.3550256387, 0.2842219495, -0.1733450424, 0.1796541291, -0.06294461907, 0.09924054763, -0.009786356148, 0.048854268, 0.0100550216, 0.02154843351, 0.01564194418, 0.009087949267, 0.01645302618, 0.009469885347, 0.02345544233, 0.02292231492, 0.04627141173, 0.05156227078, 0.1058537375, 0.1043428036, 0.2246210714, 0.1865128955, 0.4100667941, 0.2870411293, 0.2994559021, 0.1788385677, 0, 0, 0, 0, -3.329834386e-12, 2.787759391e-12, -0.0005500894028, 0.0006236161325, -0.04362825144, 0.109240295, -0.1552549547, 0.2554044384, -0.05787773857, 0.1641002709, -0.01196093262, 0.1116102924, 0.008394143345, 0.09184999637, 0.02853811297, 0.09302312574, 0.0497293369, 0.1136308166, 0.102699521, 0.1706369346, 0.2011742092, 0.2588762784, 0.03087444956, 0.07912191006, -0.0002180237438, -3.442972264e-05, 0, 0, 0, 0,], # extrinsics are rt_fromref 'extrinsics': [ 0.01989896595, -0.3018330384, -0.0101073997, 0.9485866323, 1.97908947, -3.463230895,], 'imagersize': [ 4000, 2200,], } mrcal-2.4.1/test/data/cam1.opencv8.cameramodel000066400000000000000000000005231456301662300211070ustar00rootroot00000000000000{ 'distortion_model': 'DISTORTION_OPENCV8', # intrinsics are fx,fy,cx,cy,distortion0,distortion1,.... 'intrinsics': [ 1761, 1761, 1965, 1087, -0.02, 0.03, 0.0002, 0.0005, 0.0196, 0.01, -0.05, 0.04,], # extrinsics are rt_fromref 'extrinsics': [ 2e-1, 1e-1, -1e-2, 2., 2, -2.5, ], 'imagersize': [ 4000, 2200 ] } mrcal-2.4.1/test/data/cam1.splined.cameramodel000066400000000000000000000132761456301662300211740ustar00rootroot00000000000000# generated on 2020-08-30 22:56:32 with ./mrcal-convert-lensmodel --radius 0 --sampled LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=16_Ny=11_fov_x_deg=120 --distance 5. --viz test/data/cam1.opencv8.cameramodel { 'lensmodel': 'LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=16_Ny=11_fov_x_deg=120', # intrinsics are fx,fy,cx,cy,distortion0,distortion1,.... 'intrinsics': [ 1761, 1761, 1965, 1087, 0, 0, 9.666032977e-06, 3.934369063e-06, -0.01163190852, -0.01606533695, -0.2019654036, -0.2503001103, -0.1192081624, -0.1787646642, -0.03748015621, -0.09543627046, -0.009906096626, -0.05743111865, 0.004790769527, -0.03945129333, 0.01189415112, -0.04107118534, 0.02748036997, -0.06084474844, 0.05831575386, -0.1034871103, 0.148083707, -0.1930908682, 0.191261077, -0.2291239859, 0.007571622726, -0.007941920684, -8.979703547e-07, 3.337115925e-07, 0, 0, 0, 0, -0.5707042846, -0.3537274591, -0.3096713722, -0.2304453813, -0.1297376529, -0.1218203446, -0.03663990084, -0.05081027108, 0.001608300981, -0.009756653629, 0.01272152672, 0.01307226684, 0.01062297548, 0.02295038246, 0.004964403539, 0.02215520467, 0.003805594535, 0.01041277331, 0.01692685791, -0.01448410407, 0.05943114178, -0.05879990548, 0.1599729759, -0.1341447983, 0.3501598183, -0.2475842673, 0.6050621738, -0.3646255964, 0, 0, 6.504537063e-06, 1.171082139e-06, -0.4622911915, -0.2154309593, -0.2008863018, -0.1128509878, -0.05729448118, -0.04271309313, 0.00544004809, -0.001491904114, 0.02631075889, 0.02258829981, 0.02557947394, 0.0360054911, 0.01453758604, 0.04180286493, 0.0006263547775, 0.041189683, -0.009700330102, 0.03413148601, -0.008711052135, 0.01915769514, 0.01537677235, -0.006930244807, 0.08438746773, -0.05130251833, 0.2388625569, -0.125911174, 0.509996304, -0.2310315349, -2.618506926e-05, 5.716332323e-06, 0.0005880019947, 0.0005057584762, -0.3658736573, -0.1132651046, -0.130512096, -0.04880624629, -0.01550752496, -0.00945848668, 0.03006086831, 0.01334151033, 0.04085712801, 0.02679001593, 0.03327553576, 0.03427940339, 0.01698544023, 0.0375037398, -0.001894432644, 0.03704731068, -0.01753759916, 0.03285057231, -0.02368041917, 0.02427035003, -0.01005075529, 0.00938189769, 0.04073853292, -0.0154276582, 0.1658706657, -0.05799839508, 0.414997107, -0.1260662301, -0.002443078065, 0.001076733694, -0.01248591508, 0.00103304497, -0.3071271934, -0.0459191065, -0.09285340885, -0.01659052075, 0.006447944225, 0.0007825479665, 0.0431870417, 0.01076770736, 0.04870393819, 0.01664832208, 0.03756463616, 0.01989952419, 0.01840257507, 0.02121866719, -0.003110206783, 0.02086173475, -0.02167711771, 0.01880921724, -0.03147011175, 0.01474192981, -0.02338525501, 0.007886107189, 0.01812935748, -0.003418791812, 0.126743831, -0.0227543388, 0.3558765682, -0.05480067649, 0.01084266789, 0.001995297038, -0.04014109641, 0.0007331668578, -0.2886948511, 0.003186273745, -0.0804373466, 0.002088550857, 0.0135123478, 0.001338577658, 0.04760519087, 0.0007776538941, 0.05139855647, 0.0003399430985, 0.03913933797, -2.826165109e-05, 0.01904126627, -0.0003388434498, -0.003320416549, -0.0006076996566, -0.02283079962, -0.000845015427, -0.03377421381, -0.001050848308, -0.0274651884, -0.001248105519, 0.01127391433, -0.001424650796, 0.1142905125, -0.001630845482, 0.3377100828, -0.001880668732, 0.04629122088, 2.483487726e-06, -0.01378877037, -0.001029351203, -0.3053548625, 0.0523336647, -0.09152568117, 0.02075329105, 0.007467833889, 0.001870335456, 0.04403297858, -0.009220573274, 0.0494377046, -0.01599649554, 0.03821031987, -0.0199765105, 0.01897828364, -0.02192200197, -0.002599205523, -0.02210729992, -0.02122363158, -0.02052711704, -0.03108264347, -0.01689344245, -0.02306260383, -0.01041307284, 0.0183385933, 0.0004896250449, 0.1267766136, 0.01940344233, 0.3555963263, 0.05091436936, 0.01106903531, -0.00225787611, 0.0007131876543, -0.000630185962, -0.3619355593, 0.1194924644, -0.1277139992, 0.05291622713, -0.01337545709, 0.0120615781, 0.03181822382, -0.01186790381, 0.04235516011, -0.02619242717, 0.03459772966, -0.03443002122, 0.01815368094, -0.03828484622, -0.0008521167717, -0.0383771948, -0.01662689173, -0.0346751436, -0.02288594747, -0.02652383705, -0.009435730338, -0.01208748272, 0.04114997578, 0.01230314508, 0.1658361097, 0.05429804204, 0.4144496554, 0.1216879605, -0.002378182227, -0.001087488286, 1.081427629e-05, -1.518757311e-06, -0.4561343388, 0.2218715832, -0.1962533008, 0.116740476, -0.05378221639, 0.04511760307, 0.008214124035, 0.002838152521, 0.02869227099, -0.02216463377, 0.02762725678, -0.03630328203, 0.01635870919, -0.04274959954, 0.002219488083, -0.04270849177, -0.008287329759, -0.03615174281, -0.007549114609, -0.02170612146, 0.01632928666, 0.003940498515, 0.0848461167, 0.04764865376, 0.2386928429, 0.121519094, 0.5092588465, 0.226198495, -2.552529995e-05, -4.921651163e-06, 0, 0, -0.5608726893, 0.3573121754, -0.3028300727, 0.2342053346, -0.1244673032, 0.1238301743, -0.0323972811, 0.05168202821, 0.00495285087, 0.00995787219, 0.01569227065, -0.01370674945, 0.01313403351, -0.02420891893, 0.007238401041, -0.02398682375, 0.005661451843, -0.01290217483, 0.01863791612, 0.01160639342, 0.06037280233, 0.05490985134, 0.1605352956, 0.1296716419, 0.349669908, 0.2421489006, 0.6037075109, 0.3566366057, 0, 0, 0, 0, 4.623758719e-05, -2.547526288e-05, -0.0321278702, 0.04598218243, -0.2231639836, 0.2783856625, -0.1097194292, 0.1744120097, -0.03259999184, 0.09409065495, -0.005931516459, 0.05591739265, 0.008456724637, 0.03736262788, 0.0145854625, 0.03797791121, 0.03031981724, 0.05776177951, 0.05979521189, 0.09781207875, 0.1446151011, 0.182054529, 0.2543338515, 0.2812543457, 0.03087952806, 0.03787387151, -4.399770944e-05, -2.25174224e-05, 0, 0,], # extrinsics are rt_fromref 'extrinsics': [ 0.1983349392, 0.09654603052, -0.007980927109, 1.984272914, 1.9938911, -3.09964659,], 'imagersize': [ 4000, 2200,], } mrcal-2.4.1/test/data/figueroa-overpass-looking-S.0.downsampled.jpg000066400000000000000000010763211456301662300252010ustar00rootroot00000000000000ÿØÿàJFIF,,ÿáÿþExifII* ¬ ÀÌÔ(1 Ü2è;%ü˜‚7$i‡\%ˆ,Q@QNIKON CORPORATIONNIKON D750,,Ver.1.10 2020:11:11 17:34:59NASA/JPL-Caltech)š‚P‚X"ˆ'ˆ@0ˆ0230`t‘‘ˆ’ ’˜’’ ’ ’ |’(M䆒,¨’23‘’23’’23 0100  € °  Q¢£££Ô¤¤¤¤Ü¤ ¤¤¤ ¤ ¤ ¤ Ü 2020:11:11 17:34:592020:11:11 17:34:59 x ASCII NikonII*;0211Ò Úê ò     6 V^nv"#D~$ þ%Â*+Ò,>â5";*<>? J@ ZBfƒ„n‡‰Š‹H ‘P@Ž•ÞF—ÈæF˜!®Kž ÒK¢ÖÃÙ£§7 ¨3æK«L°*L±¶:L·BL¸¬bL¹ÿ»M¿ÀMFINE AUTO1 MANUAL S€° ÀÀ304913001000200STANDARDSTANDARD€Œ„€€€€ÿÿÿl l 0100 0101#€ª02000100C01100100x x   0234Ì2‹çŽ(Aøð†›»BÔåჿ¾@IÑØ^cóýlmªûjgÉXQ°×6+Ÿ’õ÷C¯@pY^°ó‘"œ}Ù¥÷K7ˆa˜‰æ»(û4=r?ËL i±x¾ƒƒÌ “ʇÃ~¸q©`–K›dQÏ"ÏßÐyÅsn7Úüygz3ÎèÉ FÛï‚”%œÙ'ØÉ?®I†£*‚¬­,*§£‘‰€\+ª,¥5ÖkÐ\Fãf8ºsOEV¼Ö7o.0^UÐîûCôEàZ X¶w«ÝºÃ}ÈÙÍQÎ2ŃÀ±Ë¢ßŽPzBp)!.ÜÀx“ŧ«``,Üåp¤Öa€:Rî(r¯ Ä(k´$œº HçlÛ\TY®|(ñ¤aTèƒBµ¨–‡zλ´«—Ç÷¾HF‰ß®wk "ÇáÊ¥/æ9·f,Ž(¯¼¢)ÁïÊÍ™—.ðhëGåD>ÇWÅlâ5É’±‹‘qôCá%Žÿ.ýE”6\è¬Úÿ’Kže±eZ}¦œG§Ýøt @‹=! «Š,c­Ù&µŸ÷úeélSŠ´¾o„Æ9®jß±hút=ƒ|ó·‘ï !ÌRy IǨæßýl¹*—;æ@H’O˜NdE„Wh y‚|‹fŒR·†I9p¨|—5a2dEô"Ïû¦Ðy¡Hn7Úü½\z3Îè™0FÛï‚”%5ÄÒ_kö‰‘£§*,­­,*§£‘‰ök_ÒÄ5%”‚ïÛF0™èÎ3z\½üÚ7nH¡yЦûÏ"ôEd2K–p©q˜~ÇʬM̊ǃ¾x±i V‹?r$U4â»æ¹aˆ.S÷¼Ý}œ:Wó¨ÁYp¯ÂTeõ’Ÿ+6ÀÉñgáÄoh¿ìen¹æ![ØÑ鉌ÐtéÖ.ÙƒðÙá±TÛ¸HüQ>Îv‘«á™/Yƒ`à„Ù¦¦¾IÓ é‚Ç$rbM JSþ8ñ)àËÿ²å•Ót™wqòàvH¥)¤ÚC(Gì%µïYØ#8§Z.Þ¿VüL¿ú"©¬-ž“•›˜ Agëß¡eµ¥†o[…‘¡P³— Í=Œx·“êÖ!ù{O3iÅ•·¦ÿËjÃ)ñ¯ãC*-M ðGì1éõ ¿1¹Õ…!C;ø9áÔ¾Ówä]ý¥×s† AÙÿ˜›/yÅåuÃ2«Ù_IÑõ~cç¡smíæ{gã%GQɆ+Ÿ¡õe¶Ý¯$`YÁ(/óW"ƒ}ÝÄ:÷S—a¹ ö»U¤l?‹‚i±H ƒÇÌÜÍâè‡Ã"¦q©ÙµKfyýå•î_¸‘Y+W^kùM€×ò nÚ¢-+úIœú1>çmBÂ×—ræ¼Z4CŒê2N¶#>.Žl 8uÃŒ÷‹2òMg+‰ªÉ§,Z×¢¬ì?„pp‚ÜÍéë÷E[ÌGbÿ“`©¾¸~Ã)ʌ͢ˊÇñ¸x±‹¤V‹Àq$U6â)å¹AŽ.S×¼Ýj`Ũó¨ÁYp¯ÂTåõ’Ÿ+6ÀÉQXÞãgjìímlêçc^ØÑI@¶«„uåÔB/›†ðÙ²)Žr€»Rü¦‚]Ó®á9f;b´…Õ¤ò¿ÖŒéø%G L L [Fþ4ñ)àËÿ²å•ÅtÇŠNMM JGCþ8ñ)àËÿ²äÅT¢Oÿ&@ù!ÈîÓóZ|?Øú—·N`°Æ[o¥LÃI§ëv€ ˜0Ô«û,-¬ª'#ž˜ €vëÞREµÛoxƶhw³¹úç=|Z·“î!!P&{M¢tÅ•ä²ÿËà)ñ8¦AJ M L†G>|1i V ?ò$Õ´â«f9á®ÓwŠ<]ùº×sŽ0Ûò†“/@Öå͇©mµŸJéÛœa­î¦iÆéñb4ØIV©Ç¨#Ošþýt]ʦê¶QS WôE=@{ñ¸Ëô -|cŒ‘8ºçá«…"Q8^UaprI‰‹@†}‡mŒ¿uzHjÐBš:ÿ‡ð¥ÍЧ=yQH…Ùãš9TŽêăŠ<=jÕCŒk5ÕÐNºæ‡‡h“®ï!ͧ‰) ¦sÿ‘­j¢ÕÞ<‹žÎäKª—$ùˆ&÷oÈ«Zêw!&xÙ´GÂÂêˆ,H©bê”–¹©¹×Â6Ã#Æ1Á Éý¯”¤·{i/Nú.ÿóý¢^žR£Ìð”îW({ÁÈq¥„ÎíkYÄ8 ÒöCúàgj>îhWâÌEDÒ4AO«2 ibÑÝ/\†NÙ)ñrµ,ÿÁ>š`Þ¬>è«:Ôc’†È§œ¼ö5ëYù \nÑ ïïþ˜ñ)áÊͳC”uþNÒ'ýø¥ÉA“)Z™ÒÜÝ–³ON±ÇZ›¤¥µDýß_v¢;™ª"5«‡,-¬ 'Ñž‰JrêßRDµØoOÇ—hN³—úE=|÷·7îù ¿Q’{ÿ¢äÅ>äÿ )"8^CŒJ—M LžG?˜0ô!1 Yò Õ…´Ò¦f‹9C%ÓÀš‰]^׸ŽòAð+›„BBåÓ„Á«¶ÝI_Ø^cSêÐmíìjgãÞÄQrÀŒ+5’‘õ¢T¯ËªYt¨¡óþ:-}f¼Ø÷ø.)a"u»…â±Ë$r?V;ix*ƒLŠmRŒm‡b~q`(KŸ2«ˆô•Ï>¦y7Hã¿ÚüN\â¡Îb40ŠÛY‚T%ŽÄc_Öö½‰=¹£*¼­,¸§³‘akÆÒÄ5o•‰îÛF0™èa3£z”½^ü<7ÈnŽ¡ÙÐ:û "«D\fY~–Å©è¸ÜÃÊîÌÚÍÕÆá¿x±ï Þ‹´r±U‹4|æ)¹öˆ»SO^Ý.ž½UmÁYp­Ã%d x–Ñ?îÃzP<å `ôá‰`8êN2ÁËQ—¿„raÀÁ^:|’|Í`<òb1ªvíP7W~'¦Žæñÿ8sgˆC´È®?ÂØý½à¨<öáä„è+ù¶Þ7¦Î²xWJ5$\û5ÊÈ—J^" hÈÑ‚IVq¸® D"³€@aœú»S)s‡Ì=æ³i5¡.%äŸc©‚Ùèà@{ S )uTÙ9¦NžÛÕb ZM¦‡qÁ¯Lwó^ë½íÛ~ô{þ!2(Ø;›@ò_GW(S¨g^TŒ=3õËæìÆ!¶_3å'ÀѤ¼Zx¸yÖ¯ê@¤ó˜‚X8Å&¢¿8ž˜p÷áVeçêºjfç­k(ònYÂÇ*Ô½ÛWAb®¶ÿX6«ðñKßy˜¹ÙÙg*hpƒ•Ÿ¸äàë¡"–9hq‰mz¯ç»{£¤°†µíp™b«I#0?Ê÷•Í¥¥‡z~JbÛ'œ)]™‡Ï>€é1ÉÚbƒ$5ÄB^ä÷(‹®E¡»(¯­,~¦§Y“ôMj_ÒÄ5°•gî„DW˜¹éÎ3z¼üU6voÕ£¨Ò3ú¤#ïDKez~ê—”¨Î¹*ÂzÊ©Ì̸ƴ¼v²¢¾ŠÏsWT4¼…ç´¸K‰,R|ÃÜ)¬VIxÀþqrÄÃcd«@ž+6€È|YÞãk@ìmlêçc^ÎÐÃA$ªx½tVÕü.S‡"ØÊ)ûr¦»jüË=2v¥¯UàuH:†c_…ÿ¥ò¿ ×gèLùR   ,ÿ©ð¤á‚Ê ³#”ru.NÊ'ÓøÉó’IZ|ãÝÌ––Olz±pZ눤'E.Þvwd™ý"G«ƒ,¤­¼&¯ŸáZMê&RDµ3m[ưõh&²àûl<¿}¢¶qïA ¯QkzÈ£hÆÖá—üº(º9¢B2KØO¢NÉEÂ<ø1 + ±ó•ÔŸµ&Ž_gL8Û šÒ›Ê\zhÒ˜¬@ÙðçšE@8ç‘ñ]¿jCþІeËàca0à§jλAHÑ?†÷áEAغóüMÔ¼â¼*ìmÛ·Éþ³&fv’v¸îç”Ä4F.¦BP}:`žš “¡—w–f’d}hªy2^±&I*ø,ɵ¤ß{°JIÂÞ«ŒöH^ÞÖæ›.Ä¢ Âáz0Ó™©øJ½n3ãµá!¹¥kçZh‡Ã÷ ÇŒ¦õ%X¦¹!Î(UŸÐÍÛâA?¸÷xÞc=Y[ðtù~ —µ¨l»ÀYߖׄÓçʘîŸ3‘³KblK ©6÷ß­€U§^Q<Åø<ˆÿV-oÀ(s@­ÙŠEÐ"õ¸ ÆðKa&ægj!ê?fAëÃl׸BMªL=Â[ÇÁà.5‡eØ¡+qqb›Bù{9.Y窈ñv8V``ƒ¢>¹äåê†ú*R;§# 0ÿað â,É•°¸–KwM&%FúýÊ“’ï[¨©Ý–O½i±KZÿh¤µD#Þ‡wª TšÂ!;¨ë/-¬ä&%œØp‚µêßRDµ6ën"Ä#7iN³—ú‘<|¶ÅïY#6R·z6£UÄÊåúþV(19¨BKEL L9F+<ñ2€"> GóÜÔ…´Žg28É ­Òÿ›B\©/ÖËæ@ñôšACáä+…Í«¶HâÙ^c˜ëÄlíìjgãÞHP@Á¦*ù“2ôÊUy®ß¡XK©zò9;æ|I½²ö*/×`ô‘Ôºãßv%r?WähÊy–‚Õ‹˜Œœ®†™7p"aJŽ3¢øõªÎK§TxœIs6ÛüW]HÏí€Ã1ñÚlƒ$§Å¨^ñ÷‡ˆå|¢Ç+¬$-=¦)aÛÊj¢ÒÄ5½–§íÛF0™qè¬2a{ò¼ý"6Îo ,ÑêúJ#âFPa|‘—¨8¹ ³ËCÏ ÎIÅP¼x±ƒ ª‹3s T5£Úç˸Y‰R–FÜ™ÙR =ÀYpgÉÀ¿g k–%<øÃ _SåØc9æ`¨êQÞ PԹݓf¥Ç<Ž•7Ë5:¹c~µ2ò®6~²¦LæPÐ9la¸ˆK«è¯mÄ$úúív³&èëéççaöŸØE Æ‡éxØJ¨'üø–É9‘X4 ŸÎº„­XLª@W­º d®À~i{í‚™9M¼Ð8» ²%WŸ=‚Îé]l¦¾xÕÜÿwa–üÜHTŠAÈNhpÜe¸AÜæëÚþG–(j:qAšX»[~V\k!ù Ü'RÞôøç™S¢ƒJÛÇ-JÒW„úAê ØÖ O@dò왥W(ÿùšžà•c§ó5gçê¥h°ä­n·ÁgTæÂ´*6²_êdEò®KKX3ª:ñ•#’~¿æÖ¥,Jjx“o¹!àb!‘;øMSkMy£‚,•à“dŒf‡;~ªpa%J¾3àÕöÕΛ¤ã{ZI’ãÚÊœ«]PÏ…€‰1wÚÚƒº$5Äy_ öˆ8Þ¢4+„¬­,æ§Ĉ©j_ÒÄ5~• î2G#˜%èÎ3zJ¼üw7ÕnQ£&ÒÇúî#)Ee1~—ø¨¹cÂJÊ{ÍÌŠÆL¿Ø³y¢ÊŠs T4íæH¹ˆôS³…ÜktVŸßÀq5íeì ž+6ÕÈUYÞã/kmìmlêçc^ ÑwAñª:…tƒÕ2.⇋Ø)¼rá» ü=Åvè¯ à/d:mb~…¤ò¿ÞÖ(èùÏ¥ U [ lcÿyðaáPÊZ³d”¼uíN'ø+É“eZ|YÝ —[N§?±®ZP@¤þEkÞ¼wµ%™"9«¬,d­E'sŸØpêRDµJ’n[ưÂhk²¤û¹ KW¹™ãÒ5òsS¶wþ™& gN‘k¹âç›*`/G‡z`lñ•dQ•Ò•Çž°fÕf½v_‚ ¬ÿœÊñ¤TxÔIßl“sMà™Ûù™à*‡Ç$œòå?€éE—ºĺ.=y¸? 7¥ÀqN:i±Ö±;¼÷ô]©‡ÜÊÌ S’–pТ¢D®†ôææ79«_õnA~8—_¨ZºÞÁýÎìÁØÕÿÙΟߔ³¥½JqnW?4ß½Œ·˜¾Q ÔýÆ•hV–šÀ r¦§ÇöhW[…ù&…Þk|Ç÷ŠUû×0R•ݽtîè¶Iª×÷oûÓI.ª‡àØÑ*Óq“¾ÄùF9{A­«ø;×3Çq‰Ä£² Í,ÏðíUõÇ èµþîñ\áÆÊ¤°0—vNˆ' úQÅ2“{Z{zÝc–ÆOÙ*±ôZv²¥ÕDÇßEvD bš¨!«˜,K¬Þ'ŸPc‚†ë¾Rµ)âo§ÆËdh³Ðú’=U|:·î1!Pö{„¢Å#ä»þD(F9òBœJgM1L[Gß>¬0Ô!ñ BòÕÇ´é½fe9ydÓn›\ÛÀÖÝí@EñæšÑB5圄«.¶I¶ØÖc&êmhìÊgfÞ+QÀV*Ù“!ôÀUr®¢¶X¾©iò;|è½dö¸.^aGT»ÅâÄ$á?6V¿hüy½‚Ç‹Œò’†‘>p+aJª3Ïõ9Îh§±xYH•áÚyQ\ŽÆÎ-U0Ú¹ƒõ$Oų^â÷~ˆúG¢ò+ ¬ã-Χ_IÎÞj0Ò•5W–[ïVF‘™Ièï2U{Ѽìý6ÚoÉ 5Ñäú±#’G¶gU}—¯©{¹E‹Ë%Ì(ÎýÅr¾Ý±¿ »‹ÀrT5ÊëçĸQ‰RºåÜCŸNRÑÁÁpÖ²À¶gõ’Ÿ+6ÀÉQXÞãgjìímlêçc^ØÑI@¶«„tåÔB/›†ðÙA(Žs׺ý]<šGɈ@&t;ãf±‡Ô¤Â¿ Ö é1ø>W Lak:m8|M:ñ)àËÿ²ä•ÄÚ¢ÏyPù!Èî“·Z|=Üú—³Oh²Æ[o¥µDRéëv€ ™•ª¬--¬ªY=”˜ €Ý ½Dµ¥Ámð±hN³—úÞ=|Z·“îÈ!ùP&{O¢tÅ•ä²ÿËà)ñ8þCJ M L G>ø1é Ö ¿ò¤Õ…´b;f9á®Ówš<]ýº×sŽ(AÙð†›/BÔåu„«¶@IÑØ^cçêlmíìjgãÞXQÉÀ6+Ÿ’õeT¯pYÁ¨óW:œ}ݼ÷S.ˆa¹æ»â4U$r?‹V Y´XÒÊ̎͌ʇÃ~¸q©a–X÷àDô"ÏÛ¦Ðy¡Hn7Úüõz3Îè™0FÛï‚”%5ÄÒ_kö‰‘ –„,&ª¯R4íëµ…MÒbfüÿ5%”‚ïÛF0šáèÎ;z\½ŸüÊ4nn¥øÐ†ûÏ!Ee:|C†qÙè~úÊŒÍMŃ΃¾X±i Sˆ>r$Utâ¸æ¹hˆ.Z÷ÚµÝ}ž8”ó¨ÁZp¯ÂTeô’Ÿ«6ÆÉQXÞógküímlêçkßÜÑI@¶«„uå”:/›†ðÙA*Žs—º-\,šwÙ¦ Ÿ'F3b·•Õ±©¿@2ô>G L, IÖCÕc•)à‹V›ÖzXêY¸ž—³Nh°Ç[o¥µDRßëv€ žž#'ª¬--¬ª'#ž˜ €vëßRDµ¥o[ưhN³—úÜ=|Z·“îÈ!ùP&{O¢tÅ•ä²ÿËà)ñ8þCJ M L G>ø1é ×¥&k¤ÀÞ’AŒ+g¾9á®Ótš<]ýºÖÝŽ(AÙð…›/BÔåu…¼«¶@IÒØ^cçêllCìjgãÞ[QÉÀ6+Ÿ“ªõeT¯pYÁ¨ñW:¼}‘ê[²ã/8` ‘Vº¿ã„å%Â>;WhyŽ‚÷‹üŒýú†óˆp™a¦JÏ3Ôõõ’ÎK§`xIÞ‡ÛLœ8^ÿ¶Ìmƒ2ÃÙj€'°ÆW]kö‰‘£§*,­­,*§£‘9FjïÓt4••2îkG€˜1é~2§{¼ßý˜6kH¡xѦûÏ#ôEd2K–"©G¸`ÛÇÊ‹ÍÈŠ/ƒ¾x±h¡V‹?r%U5ã»æ¹Ž‰vQâ\Ü.žV ñ@>Y‹.[9®aÖŒ–ûÉPK‘ùj.í»l ç¼^WÑú@~«ÌKu‘ÔÄ/†`ÙÒ(ïs²ºzý<Îw³®`áS;ïbº…Õ¤î¿ ) éÌúÊ· L Q JÓþlñÈà€Ëÿ²r•ÅtqOê& ùBÈî“·Zp1Üú—€»hò°Æ[o¥µDRßán €ž#'ª¬--¬ª'#ž˜ €vëßRDµ¥o[ưhN%—lÜ=­eZ·“îL#}R¢yË ðÇæ6ýOd+u:zAJ Mc«G>ñ1î'Ö çðü×ݶ:cdH;¹ öÑ/˜d_Z¬¸×Ž!Aßö†›/BÔåu„«¶@IÑØ^cçêlmíìjgãÞXQÉÀ6+Ÿ’õeT¯pYÁ¨óW:œ}ݼ÷S.ˆa ’V¹¿à„å&Â=;TkzËã¨ÌŒÊ‡Ó~ôq¨`–K2fGö Íù¤Ò{£Jl5ØþŸ¿^z3Îè™0FÛï‚”%5ÄÒ_kö‰‘£§*,­®%)¬«‘ siÚÐA7 –í^Dµ›êK1’xÙ¿þ_5–lÍ£üÒ#ùJ qGf·}Δå«ôºûÁÈ ÏÎżý³ì¢Ó‰ºp¡W€6g >ä»aˆ.S÷¼Ý}œ:Wóñ¸ËXpù_ÂŒe<’Ÿ«Ù>¼»¢ãgj¬kß]^ØÑIA¶ª¸éÝN/›†ðÍU(Žsp ýÝ3‡w"žá9f;b´…e¥B¾»×èùŽ÷ ü ý ú ü8ñ)àË{°­—ÅtÆM3$PùiÊî“[Ú›Ý\–8N%° [ãL¥ôPßëv€ ˜ž#Vª8-—¬e'ïžüŒ€ØëR‡µéZo Æýzhx³¨ú=+|l·¥îŒ!°P{y¢øÅ%äxÿ6)8^C½JÅMÊLnGs>“1 U öòýÕÙ´* fX9¾ÊÓ/št]{×µŽýA ðð›·Ba岄×ñ¶%I±Øc˜ê,m¿ì?g¢ÞnQ‹Àn+Â’Uõ'TU¯¦¡Y¨ÖóÞ:2}¼×÷›.åa8i»„â¿$?éVøiüxæƒ¥Š©­Œ’‡­~+q`[K¶2ÁôŒÏ8¦yèH9eÚ°Å\L Ω¯0pÛÙ‚Ö%}Äè_]ö‰‰?×£q*þ­Ñ,µ§БM”k0Ò¯5@”ïœFh™Úè‰3!z½Àü¸7En ¡úÐû "'EÚdFÜ–Õ©·¸¼ÃÐÊèÍíÌÐÇÿ¾F±9 ‹rU;4´çæÀ¹_ˆ.SÄï¼ÝªKW—‘Áާ>TeII Ÿ—{òÉíìã;kìín;êç` ØÑJ¶«]S„uu„R/ ÖàÙÑxžs׺ý]<šwÓ®á1î™Äb´…M<ò¿c(ßéÁüŸ÷³ò•ñµø»ÇAé4—Lj­Š]°{&Pù!Èî“·R›ÚÜ—TN‹ú°%[ Ì¥`D‰ß&vV ˜þq{ó.m®$Kð‘ƒZéGQ¶ý#?¼y‘B³Û¬x|Z·“îÈ!ùP&{O¢tÅ•ä²ÿËà)ñ8þCJ M L G>ø1é Ö ¿ò¤Õ…´b;f9á®Ówš<]ýº×sŽ(AÙð†›/BÔåu„«¶@IÑØ^cçêlmíìjgãÞXQÉÀ6+Ÿ’õeT¯pYÁ¨óW:œ}ݼ÷S.ˆa¹æ»â4U$r?‹V i±x¾ƒÇŠÌ͌ʇÃ~¸q©`–K2dEô"Ïû¦Ðy¡Hn7Úü½\z3Îè™0FÛï‚”%5ÄÒ_kö‰‘£§*,­­,*§£‘‰ök_ÒÄ5%”‚ïÛF0™èÎ3z\½üÚ7nH¡yЦûÏ"ôEd2K–`©q¸~ÇʌÍ̊ǃ¾x±i V‹?r$U4â»æ¹aˆ.S÷¼Ý}œ:Wó¨ÁYp¯ÂTeõ’Ÿ+6ÀÉQXÞãgjìímlêçc^ØÑI@¶«„uåÔB/›†ðÙA(Žs׺ý]<šwÓ®á9f;b´…Õ¤ò¿ Ö é1ø>G L M JCþ8ñ)àËÿ²ä•Åt¢O{&Pù!Èî“·Z|=Üú—³Nh°Æ[o¥µDRßëv€ ˜ž#'ª¬--¬ª'#ž˜ €vëßRDµ¥o[ưhN³—úÜ=|Z·“îÈ!ùP&{O¢tÅ•ä²ÿËà)ñ8þCJ M L G>ø1é Ö ¿ò¤Õ…´b;f9á®Ówš<]ýº×sŽ(AÙð†›/BÔåu„«¶@IÑØ^cçêlmíìjgãÞXQÉÀ6+Ÿ’õeT¯pYÁ¨óW:œ}ݼ÷S.ˆa¹æ»â4U$r?‹V i±x¾ƒÇŠÌ͌ʇÃ~¸q©`–K2dEô"Ïû¦Ðy¡Hn7Úü½\z3Îè™0FÛï‚”%5ÄÒ_kö‰‘£§*,­­,*§£‘‰ök_ÒÄ5%”‚ïÛF0™èÎ3z\½üÚ7nH¡yЦûÏ"ôEd2K–`©q¸~ÇʌÍ̊ǃ¾x±i V‹?r$U4â»æ¹aˆ.S÷¼Ý}œ:Wó¨ÁYp¯ÂTeõ’Ÿ+6ÀÉQXÞãgjìímlêçc^ØÑI@¶«„uåÔB/›†ðÙA(Žs׺ý]<šwÓ®á9f;b´…Õ¤ò¿ Ö é1ø>G L M JCþ8ñ)àËÿ²ä•Åt¢O{&Pù!Èî“·Z|=Üú—³Nh°Æ[o¥µDRßëv€ ˜ž#'ª¬--¬ª'#ž˜ €vëßRDµ¥o[ưhN³—úÜ=|Z·“îÈ!ùP&{O¢tÅ•ä²ÿËà)ñ8þCJ M L G>ø1é Ö ¿ò¤Õ…´b;f9á®Ówš<]ýº×sŽ(AÙð†›/BÔåu„«¶@IÑØ^cçêlmíìjgãÞXQÉÀ6+Ÿ’õeT¯pYÁ¨óW:œ}ݼ÷S.ˆa¹æ»â4U$r?‹V i±x¾ƒÇŠÌ͌ʇÃ~¸q©`–K2dEô"Ïû¦Ðy¡Hn7Úü½\z3Îè™0FÛï‚”%5ÄÒ_kö‰‘£§*,­­,*§£‘‰ök_ÒÄ5%”‚ïÛF0™èÎ3z\½üÚ7nH¡yЦûÏ"ôEd2K–`©q¸~ÇʌÍ̊ǃ¾x±i V‹?r$U4â»æ¹aˆ.S÷¼Ý}œ:Wó¨ÁYp¯ÂTeõ’Ÿ+6ÀÉQXÞãgjìímlêçc^ØÑI@¶«„uåÔB/›†ðÙA(Žs׺ý]<šwÓ®á9f;b´…Õ¤ò¿ Ö é1ø>G L M JCþ8ñ)àËÿ²ä•Åt¢O{&Pù!Èî“·Z|=Üú—³Nh°Æ[o¥µDRßëv€ ˜ž#'ª¬--¬ª'#ž˜ €vëßRDµ¥o[ưhN³—úÜ=|Z·“îÈ!ùP&{O¢tÅ•ä²ÿËà)ñ8þCJ M L G>ø1é Ö ¿ò¤Õ…´b;f9á®Ówš<]ýº×sŽ(AÙð†›/BÔåu„«¶@IÑØ^cçêlmíìjgãÞXQÉÀ6+Ÿ’õeT¯pYÁ¨óW:œ}ݼ÷S.ˆa¹æ»â4U$r?‹V i±x¾ƒÇŠÌ͌ʇÃ~¸q©`–K2dEô"Ïû¦Ðy¡Hn7Úü½\z3Îè™0FÛï‚”%5ÄÒ_kö‰‘£§*,­­,*§£‘‰ök_ÒÄ5%”‚ïÛF0™èÎ3z\½üÚ7nH¡yЦûÏ"ôEd2K–`©q¸~ÇʌÍ̊ǃ¾x±i V‹?r$U4â»æ¹aˆ.S÷¼Ý}œ:Wó¨ÁYp¯ÂTeõ’Ÿ+6ÀÉQXÞãgjìímlêçc^ØÑI@¶«„uåÔB/›†ðÙA(Žs׺ý]<šwÓ®á9f;b´…Õ¤ò¿ Ö é1ø>G L M JCþ8ñ)àËÿ²ä•Åt¢O{&Pù!Èî“·Z|=Üú—³Nh°Æ[o¥µDRßëv€ ˜ž#'ª¬--¬ª'#ž˜ €vëßRDµ¥o[ưhN³—úÜ=|Z·“îÈ!ùP&{O¢tÅ•ä²ÿËà)ñ8þCJ M L G>ø1é Ö ¿ò¤Õ…´b;f9á®Ówš<]ýº×sŽ(AÙð†›/BÔåu„«¶@IÑØ^cçêlmíìjgãÞXQÉÀ6+Ÿ’õeT¯pYÁ¨óW:œ}ݼ÷S.ˆa¹æ»â4U$r?‹V i±x¾ƒÇŠÌ͌ʇÃ~¸q©`–K2dEô"Ïû¦Ðy¡Hn7Úü½\z3Îè™0FÛï‚”%5ÄÒ_kö‰‘£§*,­­,*§£‘‰ök_ÒÄ5%”‚ïÛF0™èÎ3z\½üÚ7nH¡yЦûÏ"ôEd2K–`©q¸~ÇʌÍ̊ǃ¾x±i V‹?r$U4â»æ¹aˆ.S÷¼Ý}œ:Wó¨ÁYp¯ÂTeõ’Ÿ+6ÀÉQXÞãgjìímlêçc^ØÑI@¶«„uåÔB/›†ðÙA(Žs׺ý]<šwÓ®á9f;b´…Õ¤ò¿ Ö é1ø>G L M JCþ8ñ)àËÿ²ä•Åt¢O{&Pù!Èî“·Z|=Üú—³Nh°Æ[o¥µDRßëv€ ˜ž#'ª¬--¬ª'#ž˜ €vëßRDµ¥o[ưhN³—úÜ=|Z·“îÈ!ùP&{O¢tÅ•ä²ÿËà)ñ8þCJ M L G>ø1é Ö ¿ò¤Õ…´b;f9á®Ówš<]ýº×sŽ(AÙð†›/BÔåu„«¶@IÑØ^cçêlmíìjgãÞXQÉÀ6+Ÿ’õeT¯pYÁ¨óW:œ}ݼ÷S.ˆa¹æ»â4U$r?‹V i±x¾ƒÇŠÌ͌ʇÃ~¸q©`–K2dEô"Ïû¦Ðy¡Hn7Úü½\z3Îè™0FÛï‚”%5ÄÒ_kö‰‘£§*,­­,*§£‘‰ök_ÒÄ5%”‚ïÛF0™èÎ3z\½üÚ7nH¡yЦûÏ"ôEd2K–`©q¸~ÇʌÍ̊ǃ¾x±i V‹?r$U4â»æ¹aˆ.S÷¼Ý}œ:Wó¨ÁYp¯ÂTeõ’Ÿ+6ÀÉQXÞãgjìímlêçc^ØÑI@¶«„uåÔB/›†ðÙA(Žs׺ý]<šwÓ®á9f;b´…Õ¤ò¿ Ö é1ø>G L M JCþ8ñ)àËÿ²ä•Åt¢O{&Pù!Èî“·Z|=Üú—³Nh°Æ[o¥µDRßëv€ ˜ž#'ª¬--¬ª'#ž˜ €vëßRDµ¥o[ưhN³—úÜ=|Z·“îÈ!ùP&{O¢tÅ•ä²ÿËà)ñ8þCJ M L G>ø1é Ö ¿ò¤Õ…´b;f9á®Ówš<]ýº×sŽ(AÙð†›/BÔåu„«¶@IÑØ^cçêlmíìjgãÞXQÉÀ6+Ÿ’õeT¯pYÁ¨óW:œ}ݼ÷S.ˆa¹æ»â4U$r?‹V i±x¾ƒÇŠÌ͌ʇÃ~¸q©`–K2dEô"Ïû¦Ðy¡Hn7Úü½\z3Îè™0FÛï‚”%5ÄÒ_kö‰‘£§*,­­,*§£‘‰ök_ÒÄ5%”‚ïÛF0™èÎ3z\½üÚ7nH¡yЦûÏ"ôEd2K–`©q¸~ÇʌÍ̊ǃ¾x±i V‹?r$U4â»æ¹aˆ.S÷¼Ý}œ:Wó¨ÁYp¯ÂTeõ’Ÿ+6ÀÉQXÞãgjìímlêçc^ØÑI@¶«„uåÔB/›†ðÙA(Žs׺ý]<šwÓ®á9f;b´…Õ¤ò¿ Ö é1ø>G L M JCþ8ñ)àËÿ²ä•Åt¢O{&Pù!Èî“·Z|=Üú—³Nh°Æ[o¥µDRßëv€ ˜ž#'ª¬--¬ª'#ž˜ €vëßRDµ¥o[ưhN³—úÜ=|Z·“îÈ!ùP&{O¢tÅ•ä²ÿËà)ñ8þCJ M L G>ø1é Ö ¿ò¤Õ…´b;f9á®Ówš<]ýº×sŽ(AÙð†›/BÔåu„«¶@IÑØ^cçêlmíìjgãÞXQÉÀ6+Ÿ’õeT¯pYÁ¨óW:œ}ݼ÷S.ˆa¹æ»â4U$r?‹V i±x¾ƒÇŠÌ͌ʇÃ~¸q©`–K2dEô"Ïû¦Ðy¡Hn7Úü½\z3Îè™0FÛï‚”%5ÄÒ_kö‰‘£§*,­­,*§£‘‰ök_ÒÄ5%”‚ïÛF0™èÎ3z\½üÚ7nH¡yЦûÏ"ôEd2K–`©q¸~ÇʌÍ̊ǃ¾x±i V‹?r$U4â»æ¹aˆ.S÷¼Ý}œ:Wó¨ÁYp¯ÂTeõ’Ÿ+6ÀÉQXÞãgjìímlêçc^ØÑI@¶«„uåÔB/›†ðÙA(Žs׺ý]<šwÓ®á9f;b´…Õ¤ò¿ Ö é1ø>G L M JCþ8ñ)àËÿ²ä•Åt¢O{&Pù!Èî“·Z|=Üú—³Nh°Æ[o¥µDRßëv€ ˜ž#'ª¬--¬ª'#ž˜ €vëßRDµ¥o[ưhN³—úÜ=|Z·“îÈ!ùP&{O¢tÅ•ä²ÿËà)ñ8þCJ M L G>ø1é Ö ¿ò¤Õ…´b;f9á®Ówš<]ýº×sŽ(AÙð†›/BÔåu„«¶@IÑØ^cçêlmíìjgãÞXQÉÀ6+Ÿ’õeT¯pYÁ¨óW:œ}ݼ÷S.ˆa¹æ»â4U$r?‹V i±x¾ƒÇŠÌ͌ʇÃ~¸q©`–K2dEô"Ïû¦Ðy¡Hn7Úü½\z3Îè™0FÛï‚”%5ÄÒ_kö‰‘£§*,­­,*§£‘‰ök_ÒÄ5%”‚ïÛF0™èÎ3z\½üÚ7nH¡yЦûÏ"ôEd2K–`©q¸~ÇʌÍ̊ǃ¾x±i V‹?r$U4â»æ¹aˆ.S÷¼Ý}œ:Wó¨ÁYp¯ÂTeõ’Ÿ+6ÀÉQXÞãgjìímlêçc^ØÑI@¶«„uåÔB/›†ðÙA(Žs׺ý]<šwÓ®á9f;b´…Õ¤ò¿ Ö é1ø>G L M JCþ8ñ)àËÿ²ä•Åt¢O{&Pù!Èî“·Z|=Üú—³Nh°Æ[o¥µDRßëv€ ˜ž#'ª¬--¬ª'#ž˜ €vëßRDµ¥o[ưhN³—úÜ=|Z·“îÈ!ùP&{O¢tÅ•ä²ÿËà)ñ8þCJ M L G>ø1é Ö ¿ò¤Õ…´b;f9á®Ówš<]ýº×sŽ(AÙð†›/BÔåu„«¶@IÑØ^cçêlmíìjgãÞXQÉÀ6+Ÿ’õeT¯pYÁ¨óW:œ}ݼ÷S.ˆa¹æ»â4U$r?‹V i±x¾ƒÇŠÌ͌ʇÃ~¸q©`–K2dEô"Ïû¦Ðy¡Hn7Úü½\z3Îè™0FÛï‚”%5ÄÒ_kö‰‘£§*,­­,*§£‘‰ök_ÒÄ5%”‚ïÛF0™èÎ3z\½üÚ7nH¡yЦûÏ"ôEd2K–`©q¸~ÇʌÍ̊ǃ¾x±i V‹?r$U4â»æ¹aˆ.S÷¼Ý}œ:Wó¨ÁYp¯ÂTeõ’Ÿ+6ÀÉQXÞãgjìímlêçc^ØÑI@¶«„uåÔB/›†ðÙA(Žs׺ý]<šwÓ®á9f;b´…Õ¤ò¿ Ö é1ø>G L M JCþ8ñ)àËÿ²ä•Åt¢O{&Pù!Èî“·Z|=Üú—³Nh°Æ[o¥µDRßëv€ ˜ž#'ª¬--¬ª'#ž˜ €vëßRDµ¥o[ưhN³—úÜ=|Z·“îÈ!ùP&{O¢tÅ•ä²ÿËà)ñ8þCJ M L G>ø1é Ö ¿ò¤Õ…´b;f9á®Ówš<]ýº×sŽ(AÙð†›/BÔåu„«¶@IÑØ^cçêlmíìjgãÞXQÉÀ6+Ÿ’õeT¯pYÁ¨óW:œ}ݼ÷S.ˆa¹æ»â4U$r?‹V i±x¾ƒÇŠÌ͌ʇÃ~¸q©`–K2dEô"Ïû¦Ðy¡Hn7Úü½\z3Îè™0FÛï‚”%5ÄÒ_kö‰‘£§*,­­,*§£‘‰ök_ÒÄ5%”‚ïÛF0™èÎ3z\½üÚ7nH¡yЦûÏ"ôEd2K–`©q¸~ÇʌÍ̊ǃ¾x±i V‹?r$U4â»æ¹aˆ.S÷¼Ý}œ:Wó¨ÁYp¯ÂTeõ’Ÿ+6ÀÉQXÞãgjìímlêçc^ØÑI@¶«„uåÔB/›†ðÙA(Žs׺ý]<šwÓ®á9f;b´…Õ¤ò¿ Ö é1ø>G L M JCþ8ñ)àËÿ²ä•Åt¢O{&Pù!Èî“·Z|=Üú—³Nh°Æ[o¥µDRßëv€ ˜ž#'ª¬--¬ª'#ž˜ €vëßRDµ¥o[ưhN³—úÜ=|Z·“îÈ!ùP&{O¢tÅ•ä²ÿËà)ñ8þCJ M L G>ø1é Ö ¿ò¤Õ…´b;f9á®Ówš<]ýº×sŽ(AÙð†›/BÔåu„«¶@IÑØ^cçêlmíìjgãÞXQÉÀ6+Ÿ’õeT¯pYÁ¨óW:œ}ݼ÷S.ˆa¹æ»â4U$r?‹V i±x¾ƒÇŠÌ͌ʇÃ~¸q©`–K2dEô"Ïû¦Ðy¡Hn7Úü½\z3Îè™0FÛï‚”%5ÄÒ_kö‰‘£§*,­­,*§£‘‰ök_ÒÄ5%”‚ïÛF0™èÎ3z\½üÚ7nH¡yЦûÏ"ôEd2K–`©q¸~ÇʌÍ̊ǃ¾x±i V‹?r$U4â»æ¹aˆ.S÷¼Ý}œ:Wó¨ÁYp¯ÂTeõ’Ÿ+6ÀÉQXÞãgjìímlêçc^ØÑI@¶«„uåÔB/›†ðÙA(Žs׺ý]<šwÓ®á9f;b´…Õ¤ò¿ Ö é1ø>G L M JCþ8ñ)àËÿ²ä•Åt¢O{&Pù!Èî“·Z|=Üú—³Nh°Æ[o¥µDRßëv€ ˜ž#'ª¬--¬ª'#ž˜ €vëßRDµ¥o[ưhN³—úÜ=|Z·“îÈ!ùP&{O¢tÅ•ä²ÿËà)ñ8þCJ M L G>ø1é Ö ¿ò¤Õ…´b;f9á®Ówš<]ýº×sŽ(AÙð†›/BÔåu„«¶@IÑØ^cçêlmíìjgãÞXQÉÀ6+Ÿ’õeT¯pYÁ¨óW:œ}ݼ÷S.ˆa¹æ»â4U$r?‹V i±x¾ƒÇŠÌ͌ʇÃ~¸q©`–K2dEô"Ïû¦Ðy¡Hn7Úü½\z3Îè™0FÛï‚”%5ÄÒ_kö‰‘£§*,­­,*§£‘‰ök_ÒÄ5%”‚ïÛF0™èÎ3z\½üÚ7nH¡yЦûÏ"ôEd2K–`©q¸~ÇʌÍ̊ǃ¾x±i V‹?r$U4â»æ¹aˆ.S÷¼Ý}œ:Wó¨ÁYp¯ÂTeõ’Ÿ+6ÀÉQXÞãgjìímlêçc^ØÑI@¶«„uåÔB/›†ðÙA(Žs׺ý]<šwÓ®á9f;b´…Õ¤ò¿ Ö é1ø>G L M JCþ8ñ)àËÿ²ä•Åt¢O{&Pù!Èî“·Z|=Üú—³Nh°Æ[o¥µDRßëv€ ˜ž#'ª¬--¬ª'#ž˜ €vëßRDµ¥o[ưhN³—úÜ=|Z·“îÈ!ùP&{O¢tÅ•ä²ÿËà)ñ8þCJ M L G>ø1é Ö ¿ò¤Õ…´b;f9á®Ówš<]ýº×sŽ(AÙð†›/BÔåu„«¶@IÑØ^cçêlmíìjgãÞXQÉÀ6+Ÿ’õeT¯pYÁ¨óW:œ}ݼ÷S.ˆa¹æ»â4U$r?‹V i±x¾ƒÇŠÌ͌ʇÃ~¸q©`–K2dEô"Ïû¦Ðy¡Hn7Úü½\z3Îè™0FÛï‚”%5ÄÒ_kö‰‘£§*,­­,*§£‘‰ök_ÒÄ5%”‚ïÛF0™èÎ3z\½üÚ7nH¡yЦûÏ"ôEd2K–`©q¸~ÇʌÍ̈ÆÇƒ¾x±i ©t?b$U4â»æ¹aˆ.S÷¼Ý}œ:Wó¨ÁYpî†e¡IŸ˜)sÖQXÞã3'¼í¾6êçïÄÑUD¶«Žû„uÝz /ÏŒðÙs(ŽsäŒý»?«wJ¨ádVf;Y„î…–¨ò¿9Ö é+ø>N L M JCþ8ñ)àËÿ²ä•Åt¢O{&Pù!Èî“·Z|=Üú—³Nh°Æ[o¥[@Rßëv€ ˜ž#lu--¬ª'#ž˜ûPy‘ÜRDµ¥o[ưhN³—úÜ=ŸÐ?¶ ® Ãòå{DªÍŸì¸÷Çí!û0õK BEDO6õ9â(ÜUûNÜo½‰†Ñoù0 EÚœ“ÔTRÞ™‡ÂH2ùn’ÔE.âƒîP±»N-ߥdí‘jë‘`Ù¤V5ÇË,•˜ ÿl^Î¥ {SÈ¢ù\0–wÖ¶ýZ$‚k²šì±üÐú’Û‹Àx©H–Nx¼…=¨èªÈ†Ù‡¡|¸qòu–KòÍ:5ý¼ï礔{ H7ÊüŒLk33Þé0FÛq¢˜05ÄÒ_kö‰‘£§*,­­,*§þÏ’R:hÜÑé4•ÓîÒD¨˜Uè3!{¼Šý|7støˆ*ЦûÏ"ôEd2K–`©Ü»ÑwŒÍȋǃºy± ‹V‹§s|W‰6J äå¸KŠLQ?ß&ªV+:ÀäqnÛÃÓdŠãžn7ŸÈ6Y¸â0kÅï|nnå_²ÐXBÑ©}îtåÔB/›†ðÙA(ŽsˆDý…=Kv2¯éàï°:^c±…b¤Q@ÜÖTÔø~B F ·ó)Ãþ¸ñ©àËÿ²d•Et@°¶'Pù!Èî“·Z|=Üú—³Nh°Æ[oý¤´DRßëv€ ˜Š>¶¨¬--¬ª'#ž˜ €vëßRDµ¥o[ưhN³—úÜ=|Z·“îÈ!ùP&{O¢tÅ•ä²ÿËà)ñ8þCJ M L G>ø1é Ö ¿ò¤Õ…´b;f9á®Ówš<]ýº×sŽ(AÙð†›/BÔåu„«¶@IÑØ^cçêlmíìjgãÞXQÉÀ6+Ÿ’õeT¯pYÁ¨óW:œ}ݼ÷S.ˆa¹æ»â4U$r?‹V i±x¾ƒÇŠÌ͌ʇÃ~¸q©`–K2dEô"Ïû¦Ðy¡Hn7Úü½\z3Îè™0FÛï‚”%5ÄÒ_kö‰‘£§*,­­,*§£‘‰ök_ÒÄ5%”‚ïÛF0™èÎ3z\½üÚ7nH¡yЦûÏ"ôEd2K–`©q¸~ÇʌÍ̊ǃ¾x±i V‹?r$U4â»æ¹aˆ.S÷¼Ý}œ:Wó¨ÁYp¯ÂTeõ’Ÿ+6ÀÉQXÞãgjìímlêçc^ØÑI@¶«„uåÔB/›†ðÙA(Žs׺ý]<šwÓ®á9f;b´…Õ¤ò¿ Ö é1ø>G L M JCþ8ñ)àËÿ²ä•Åt¢O{&Pù!Èî“·Z|=Ýú—³Nh°Æ[o¥µDRßëv€ ˜ž#'ª¬--¬ª'#ž˜ €vëßRDµ¥o[ưhN³—úÜ=|Z·“îÈ!ùP&{O¢tÅ•ä²ÿËà)ñ8þCJ M L G>ø1é Ö ¿ò¤Õ…´b;f9á®Ówš<]ýº×sŽ(AÙð†›/BÔåu„«¶@IWö^cçê‡mìjgãÞXQÉÀ6+Ÿ’õeT¯pYÁ¨óW:œ}ݼ÷S.ˆa¹æ»OFF 0223ê®»Õsž CŠñŽ™|CÔåõ’Ÿ+6ÀÉQXÞãgjìímlêçc^ØÑI@¶«„ueTB/›†ðÙA(Žs׺ý]<šwÓ®á9f;b´…Õ¤?>Ì_¾h³xÃ2t­>sL¸D~kŽŸâ 2eÁô"Ïû¦Ðy¡Hn?Øüœ½])›3@|1Íî&ø$Åþ^köˆñ¯£Ç*.¯¯.¦ãˆŠ…kNÒ‘5'”€ïÛF™…èÍ3zS½ˆüÜ7?nz¡]ФûÌ"ùEd1{Kj¨p¸äà ÊÄrÏ•2œ±°±ù¡vˆw4[ $ýæÑ¸a‰ŽS"}œ:W—¬Á¦p/Âxdé’ž+7ÀÈQXÞãgjìímlêçc^ØÑI@IÔ„tåÕ½,›†ôÙA(Žw׺ý]<šsÓ®á9f?b¯„õ¤T@ÿ(Fè¸ù°ý®õL M ÊÃþ¸ñ©àV˲ä•Ät¢K{"Pý!Ìî—·Z|=Üå“L±h¢OjXl¥µDQߨt€ ˜ž#'¨¬--¬ª'#œ˜‚ˆ'®D°ýo[ưÝh=³—ûÜ<}^³—îÈ!íx{OªtÅ•ä²ÿËà)ñ8þCB M Ì Ç>ø1é Ê ¹ò¯ÕŒ´f5f9ì£Ó}š6]ýº×sŽ(AÚð„›/BÕåt„«¶@IÑØ_cæêlmíìkgâÞtPÁÂ6*Ì“Oõ.T‰¯4YÁ¨óW:œ}ݼ÷S.Šaä»â6W$u?ŒV¤iµx¿ƒØŠÓ͌ʇÃ~¸q¨`—K2dEô#Ïú¦Ðy¡Ho6Úü½]z3Ïè™0FÛï‚”%5ÄÒ_kö‰‘£§*.­™,(§¹‘‹ôk]ÒÀ5!”ƒïÄF/™èÎ3z\½œüÛ7nH¡yЧûÎ"ôEd3J–`©q¹~‡ˌÍ̊ǃ¾x±i V‹?r$U4â»æ¹Bˆ.Så¾Ýœ:Wó¬Á]p§ÂKeõ’Ÿ*6ÀÉQXßãfjìímlêçc^ÙÑI@·«„uåÕB.›‡ðÙA(Žs׺ý]<šwÓ®á9f;b´…Õ¤ò¿ Ö é1ø>G H I HCþ8ñ©àËþ²ä•Åt£Oz&Pù!Èî“·Z}<Üû—²Nh±ÆZo¥µDRßëv€ ˜ž#'ª¬--¬ª'#ž˜ €vëßRDµ¥o[Æ´hL³—úÜ=|Z·’îÈ!ùP'{N¢tÅ•ä²ÿËá)ð8ÿCJ M M F?ø1é Ö ¿ò¤Õ…´b;f9á®Ówš<]ýº×sŽ(AÙð†›/BÐåq„«¶@IQØ^cáêÆ- g!ÞnNÀåÔ&mpµuT¯pMÁ¨óTºý]<šwÓ®á9f;b´…Õ¤ò¿ Ö é1ø>GŠÌˆÍŽÞ‡Ã{¸q©`—J~2eEô"Ïû§Ðy Hn7Úü½\z3Îè™0FÛï‚”%5ÄÒ_kö‰‘£É*L­€iŒ¹КiXj¬Ó“4%”‚îÛF0™¡èÞÃ:TU•üšÓ0204Þ°ÐqîV_“¸˜… N™Á|½<$«¶@IÑØ^cç0107 010001000100ˆõ0200ÿÿÿ<  R980100œQ¤Q(¬Qš',,ÿØÿÛ„      ÿÀx !ÿÄ¢ }!1AQa"q2‘¡#B±ÁRÑð$3br‚ %&'()*456789:CDEFGHIJSTUVWXYZcdefghijstuvwxyzƒ„…†‡ˆ‰Š’“”•–—˜™š¢£¤¥¦§¨©ª²³´µ¶·¸¹ºÂÃÄÅÆÇÈÉÊÒÓÔÕÖרÙÚáâãäåæçèéêñòóôõö÷øùú w!1AQaq"2B‘¡±Á #3RðbrÑ $4á%ñ&'()*56789:CDEFGHIJSTUVWXYZcdefghijstuvwxyz‚ƒ„…†‡ˆ‰Š’“”•–—˜™š¢£¤¥¦§¨©ª²³´µ¶·¸¹ºÂÃÄÅÆÇÈÉÊÒÓÔÕÖרÙÚâãäåæçèéêòóôõö÷øùúÿÚ ?üMÿ†%ý³G_Ùâwþ:ÿ¥ÿ†%ý³èÑþ'ÿá¨ÿñšíþÍÌèø ¿ÈåúöþGÿ_æðÄ¿¶qà~ÈßÿðÔøÍ9aïÛQþïìñDý>êGÿhÑý›˜ÿÐ<ÿð}{ÿ?£ÿ/ó?aoÛlôý޾*á½Ô¿øÅ/ü0§í»ÿFqñWÿ î¥ÿÆ(þÎÌ?çÄÿðþCúî þGÿ_æ*þ· }ߨ×â±ú|;ÔÿøÅ=`Û¥¾ïì]ñdý>êüb—ö~?þ|Oÿä\ÁÿÏØÿàKüǯìûx7Ýý‰þ.§Ã}SÿŒS×þ ñû|7Ýýˆ>/Ÿ§Ã]WÿŒRú†;­à/ü‡õ¼/üýÞ‡ø'ü¾ïì3ñˆý>j¿üNðN¯ø(+}ߨSã!ú|1Õ¿ù—Ô±Ÿóæ_ø ÿ!ýg ÿ?Þ‡ø'/ü$ôý„>3á¯Õ¿ù—þÇÿ ÿ£øÏÿ†»Vÿäz_SÆÏ©à/ü‡õœ?üü_zøwü3þŒ;ã?þí[ÿ‘éü—þ :þ¿ð×êßüGÔñ›{)à/üƒë8ùø¾ô!ÿ‚tÿÁA‡_ØOã(ÿºa«ò=4ÿÁ;¿à +÷¿aŒcëðËUÿäz>¥ŒÿŸ2ÿÀ_ù ëXoùø¾ô1¿àž¿·ÒýïØwãúü4Õù˜ßðOßÛÍ>÷ìKñt}~jŸübŸÔq¿óæ_ø ÿ úÖþ~GïGô[ýŸàïOM ·ðW닱ùš,Ûøq‰ûŸ¥yí§ûQü?ý—þj¹ñ}„^.º±hô-#ÎÝrd~¥3*¨%#¸¬qxˆa0óÄOì¯Ç¢ù³£JUëFŒz³àæÿ‚™~Õ^0²ŸÃÞñ¥åµ„¬²ÝGføàäþöyP*³1QÑH,µúû ~Ð2|oðSøGÆrH|M¡…ƒP–IDë8bÛH•UCŸ‘—8ì'ž§óº|I‰Âãð‘ÅÔ¼'.G~ÏDúm&®Û~íÑ÷Èhâðx§†§ïÂ<ËÕj×]â•–¶ó>‹´ðçO“ô­{>OÒ¿@œ¬|tbméþÏü³ý+jÇÃÝþ•ÅR¥Ž˜@×´ð·OÝþ•¥káQÇÉßÒ¸gY#®4ô/EáPGú¿Ò§_ ùçÏÒ¹^ ×Ùˆ|*ü³ý*)¼/ÿLÿJkƒÙ”®|/×÷¥g]øcýßé]¬ž†2¦e^øgýßJÆ¿ðæýÙü«¢5„ Ï+‹AËce|“û}þÓÚ×ßCð뺛[­®É.Vµæ˜ä3ŽˆŠÉÇ÷‰Îp1¶{YÒÊ+òJÎQqOÍ«#Šœjføw5xÆJM>©;³çÿ‹¿ðW‹×? "ðWÃ+ë ]Bä<> üÛÈ@Â쌑´1-÷ˆ/€Häf¾)ñ‡Š5¯ø†ç_ñ¹q¨ÞÞL^KËéŒÒÜ0êîıcÜãpÏM¹¯€úî>¾ŽWÁZýû9w•¬›êîú³ìñ|¾9|N—$fïn‹EuѽÚ]—CÑÿgïê7—VÁðýäÉö§Ô¢•´;«„2@‘x¦P²þéÙ‹+È€í?ZxkƧÁÙÛHñÓi¨ë¾'mZÇQŽmë-Œa]÷fEófÚL€1#.×?ÅS* Êÿ9_ç¢}“·•ϱáHrF¶!ùÙúFÏñk{µ}7hýXðE»øÃgˆ¤ÓžÙ¯ì!½6ï4s4FD ´¼Lñ±ÆäfSŒ‚F u‡3ŒGúWí´+NX:S¨ï'[.Ú‘W„V*¤i«.geÙ_Ï_¼ÞÓ¼9€?wúVîŸá±ÇîÿJá¯^Ú\è§LÙ³ðæ1û¿Ò´mü8;¥yU1t)h]‹Ã éSŽ»?Jåuõ6T„>ø?J†_îSUÆé”®<;ÿLÿJλðç÷¥tÓ¯c Ò2/ü7ÁýßéXº†òîÿJî§^ç$éž-¯¶“áê,ñÀ‚ÃK²—Q½ºGH]ØýIü+ðƒö³ý§5/>8Öñcõ¬:æ…ñ‡ÅŸþø*æK‘<:r_Z¤¤ÝZ^^\´·,Æ ”1]Ù–8(æ6¯˜â êâhâ)«¤Ò{öjúù½zm²>«‡1ôèá±z®Ò’ml¯f¾äÚëºÕŸ¬¿þ,ü<øë²ßúX¼=ª6‹y-å±^TïK©ç¯#5éú‡q“ô¯ÕÞ*2¤¹^‹O»Cóc(Ôj]uûõ7tïŽ2™ü+vÃ@Ëý+ÉÄW¾‡¡J™­i¡>OÒ´!ÐñÕ?Jó'UѦZ‹FÜý*Q£(ÛúV¡ª€£îT2h£û´ÕA8åзéT®¼<¡Y˜rzbµ…k*f4ÚEäfk)ãËÄáÆàpFGpG5¨øw9ù?Jì§\å#óïþ éñMð'ü«Åž$Ð5[yWÅöz.™s ŠñÜGy*1žC·GcGQø5¬³Od–É6þ˜õ$Nëž uûÑ]9õuR­=n­ù³›&¡*p¨Ú³½¾äMy:Zéxó<·’8‘w9BÈÛ¤ço2S¦1òõëM𜚇‰tÝ!ìn&gÔ!+´J÷(a¼E@gÚHRçžp3^ìúžÏñ^ÓÆZnƒá=zAuv³jBׯs[<±³yF9,Z?¿ƒÌß©\lúìÿuŸí¹£çÆmô=*îúÖ¿´Œ´iÔo¹’B¯¶1¼…/#ÆgSZþÿ~¿¯OÀtýÚƒéÓú¹úåÿð´zGÀwÇ#Õ-cMcWk4åªF¥ãÙ¸Éucô"¾Îð톗­Y&§£^Cuo);'·IàpGGá]Ø"koеÇÔ%F²ð.¨±!º·o<FÆ-€:“ Ù1©Ghp[aVç½§ußõ4µéYê~€|&øý¡xþ m©ÙØø«G‡Z}{L¶±Ò§¹CqpY„ÓªBHi †‚—p'¯¨?c_ÚïQ¼ý…~%_hÚLŠþxÿÅ6!žÖLZÜO…pı0dÉÈžxŒ,çRŒ´¼æÿòf—ácLe:R­ ÇV£ÿ䩵òw>hýªÿà©÷Ÿ´Gü÷À¿"übYìõ GÃÒÇbtÆÒï ºYšdWY£…‘ŠHª‡>»kÿƒy,¾#x7öêÓõ]j§Ñ¼kðóQO¾ººIÍÄq=´Ì¸WbŒ®2hyN-=?áÝ¿"§Jåîëÿ ©öí_ûeøïOý¨¾*þÇ7Ú¼“hwß µ‹4òãCip4§»Â°]åY”‚NKŽ0*¿ü \’ûáçÄ]"I‹ýŸWÓî†OüôŽeÿÚTI®t—õ £ÈÛþµ>ìñÏÄo|;Ñîõk–ð}“O›Rû)¸E¹š8P»ùQ³ç zw¯9øIûxþÌß<+wâ'â¶™ö ù4ûÍ;Yž(/ád8 Ы±ã•nü÷ I½Œ¥8Çâv5ï?i¯‡Þ$´Ôt„¾&³Õõë}6kë[imçXËBÇ,æàëÓŽµä=Ô>ݬ18<â¿H¾|ký›ÿà_¼pß~/øš÷Dñ?Å}WþÏ ½Ô7òÛDÓI {!+£ùRo@åä`d² †°›‹¯sÙú鮟p|¥.[¥Û};ƒßµ¯üŸQý¯?eß‚Ÿ|S&§yâ†6ú¾±®ê:¨¼}].e‡ìŒX…%ㆌYpx#ƒŠù¬x…ä»÷OªÒ¬‚BÊ’»NNG¥sUÌ+:ªÑ²ó9"¹n‘{Y¼Xž/5â’îÅѤ“—oâû¤`qž+KÀš¥¥¿ˆÆ¡¡[êÐ%»3Xj…¢²s†Á,ç{rkÔŒ•H©ÃTÍo¡ëþ+ñV«üSÒµ]Áz.h#ÓÃÚø=e:Dγ>é•dsµ›ø$|¹Ñ|ñÂhoñÂâYâS}à™mcF‚%2×´²Ä`°1á†ÝÇ… åËæ]ô±Þé´‹ x> ¬Û‹=cP…˜ÿòíaaèXÄ1]Þ³ÿ'øÓð“á—¾|1Ó Ð4ÿè¶þÔõùÔM5Õ’,‚[.hÊ(•.$ Õ°¿)Ö5%(Õ±½:jTîÏ øañ“F¹ñŸ¿á3ñ„Oðä±ZB¾Tkw­*O…GÉ ô'9~Ôÿ‚MÿÁCþ ~Ïþ6øÿïæÛÙj^Õl,#ßÛÜ]–†Ô´lˈܘÎO8 ØÁÆ¢ª¥ý¤¾Z¿Í•î·g-®þ{¿à³µŸ¿m_¿¼/¬]§‰mï-|)¥ˆž,ÚLÈÅ%R6ùfUÎùÆy›^ýº?ké÷¶> ý¤|eáË=^(ίi¢x’}>;’ŠÂ?5mÙ…29Ž:Öñ”4§µÌ%RQÑž¹û/ÁS>;x'Å1Ûü^ñþ¿âÿ}NÓ%œÎÒݳŸ¼í¼™‰o˜òÍnx·þ )ãÏjÓëu‰Ò{Ûí>ûS´ó­è®cšÞFn@|äÎ?ºprÅF;=Œ£CÛMÆ»{ýç¢XÿÁe¿h¿…Þ ÿ…§ð³â¥¤Å«ºé·V’Çl²¡F…ctb ‡8Ý»î‚w½Á?ø8“ö€øaâ_øïZoˆ7CEOësÏgokä\A4!m`AmÑ>ùy’fýÚŠùÌ>gV³”q|×Sµì’Q¾ú´ÚÓ¥Þ«ÌúÙduR‚Ëè4¹Uù´nVóÙëärß¶ü_ã·íÅðßVøKñrM2ÏÃÚ¼Ñijö×Vklcž9VOšF•1c‰Ü̪+/ÆV°üÓ5yµ9õ{íFØÄÐÃcunr3ÌÎݹ#ÔddWncŠçÂIe•Wµ“ÞWJ*ÏUhJítM[¿ž²Ò5R¯CÝ]œnþù"¿‹¼]á¯é–¶÷ÚŽ¦­j¸Ž!¢oNNÀ8Êÿ\לø«â>½â¦ŽÇÄß/Ý(ÄÍ£}°¼ƒ–8RIbG©9¬²œ¾ŒãÉŠTçÈïU+¦ÝÛ|ͶÛIÞúµv´GeC‚iÔ„¡Íu«Z¥m­êyÚÅl.’;XT°Œ:ÈÌ@pÆoÓ?†µ¥Ë‹s-Ì0Ü41–‹z¾{†=q‡¶Wóè¯%(©7¯OëúÐðänè-«øé#³Ñ}ª5ÆÕ›ieÏN9>ýÇNk®ÑgÏÚ ñ¾ÙcðÆöàIÐf‰¦B§Œü úν EJ‹…G³Òåœæ­vú7Â?Ëuo¯]hZ6šÖRÃÌêgpÑJűƒy8#Øž8ê]¦øWJѼc'ˆ|]ªèOm%ËÎöú¼îc*ìsµ…ÁÈ#ž3]>Ò/Th©¸«I•~*þÔß|-­_…žðª/"iôÃyö˜\:–u¹I"S»oG¹FAnkÕ¿m‰Ú‡†$ÑôIì9žõçþÒ½¸œ‚ª¥QçžM€Îþ#Œdç “©{®Ÿyœ¯Æ;ý >8®»a¨è4Õç+q¾[[«÷ºµ|0?ø¯ö‘ñšéš¾µâ 㹞ÛC¸V¶Þ°¤@ˆKœ2Æ‘ü¥‰ÈÃs_"jzŽ¥eâY­uÛI£– J[ÜEåõèJã§OJ>¬¨ÒŒ!ÑU©:Õå6·üúÿÀ#“ÅÚ’7–—I1´GiR=¯"¶|9ñÄm+ZØé«¨¹ÿUÄçŽÃV J¥”ãsL6'ƒ©ípÓqfæ¡ã¿hòG«ðâwˆL‚X&MêCr29\dU½â´vš.¹âi|`ϤG-na/›9Ó#g¾s[G NOf¹—C¦YÖi5þñ-|ÌO|zÔu«S§†4»ue?e´ù¾÷qÉØêk&Ã⮹c:]%Ú…vªÉ:?¼¤`ž¼žh•÷…8«y#Ì'¬ñöóÿ2msãˆuûl/^Ù"q‚-í"FAê9ÈíïXžñÖ³¦^˜aÖç†9\$ž[Ÿ»øUr®k¤—¢·äa9Õ«üY9z¶ÿ2„sÚ`Gh ±˜Éƒµvò8àŸnºVµ·‰<­*”ñ XL*pAÃcèy÷5çÕ¥)Z2è×åoó"ÝÎçá_gø1uñ+RñG‰fðä:ö¼ð¢1’[»í»‡÷‚ÇÀÎF?Z«â·Ó´ýRK(]^Úм©ºW–ÝÉ=z×s§g*‰lÒûïþBç|Ê{«ýÖÿ3“Öä¼Ôç+)Œe"  Û®>µ·¢|8¾üÝz'¶…ÉQ!ÁvÀèqšÃ–ò.Êç¤ü/¹OZKc£YÉ)šMäݨœœ‡žƒ¯ä+»Ñµ›¥`#˜G$­É‹äl“Éã¥uS\ªÆsµô9ýbWÒlï,t«»Èá¹gžå?´%"Bø H-Œð㌜u¯+ñªßßj,5TYYÓlWXŽ@äôŸÖ²t“\Ësw^¤—²›º8ûÍóN‚Inǘ ¢23ß­VûY8}(Il؆å$¼úÖVåfvìtßõ‘qi±¥YjÅåìŠh2¼• >` fÈ ëÖ»}?â‡Â»?Ï}㿇ú•¼PÒA ë-¤}Õ¤„ Œã> cŒLáB¥DëFïËG§™œš‹P[»—§ÒeßÛËyῈš¤òa„ZÞ‘Ñ‚Fx™[ûN= `êŸ,'ŠÅ:F¦óƒæCa©_,ŽÄ\ ôÁëÆ;ÕÏ wφ«ò—ùs-$¾ãÅ_õßZØê~'V6W!ŒKk2NÙêC²àût>†©Æž ³ÑŽ›j’\‚¥®®  zväúãëŠæ©¾Õ¡¥\«] „‰Â+/̵=猵½vÏìwÛ¬qeXÁQ6ƒÎ{ÐUIÉÅ¥ÔIF-3ïír[œˆÁRrIÍW¼þÚkR4í<\ – Ûm|Ç'¦ÐpHäñj/ï&.Œ¯ªøOPñ Œ3®Ÿ ½Ù„ O´Æ;ŒõeïþÎbMJñ#:[ÈÉÜ韼88óî¿OcUÊÙ7±¹6áŸi&)ÔÊd^T‘ƒŽãsúÈž3[ø?g¦Jnt«~‡>T øüD©FJæ«(HK½5$K}_Ltx—Ë zãŽHçžõŸªøsW{źӵ (‘È0}ˆ{ô¨jêËqµgw³²›{‰%¿P&npƒåéÛëTuùÞÕÞXÔ|§fÓ€? γJ“þ·2©îÓl†âÊD¾»‚y¼‹F ¾d(AãÌBB'ð"¬Øxuî°ê¬ƒ¯Ì9©º¿»±Ó>_sfÃLµÒ˜I:†aÞNOà+Aü|ÖÄÙXÎÊÁyã<}kDí¢%ÝêÊðɨx†äGo4­ÐÉÿ'ùÕµðæ±cn/.´é’ï„ÊpqÔp9ªI½ˆºZ\ê6±Û[ÙYÂí;±iŽØ°õîOldÞ°W»”$¶!óK'ÞÚ£–8ïÇný*“¸ÈãºY$c›°ØäôÍkXÉåÚ–'ïH§l1þ`TÎ\±»î¿a¨¹Käÿ!u!Õ¸ãÖ®hå–Ÿaqk¨C<ª$Ya˜&3ŒžTƒ |uœœlÒ¾«ó%F÷M•µoy¶©¥Øé‚Ûȸó™H¬3À!@Ú3€1ÀÀçÕ_ë×RéÐk:-½º`Ã;Ãó#äÄ“Á¯á5·;ÝrØäì5íCL½k˜Ü°vÝ"t ïÇCî+³Ò½·J„úc;Äz=­ã˜Ýlðè0Ãÿ­\ùÒ¯´Ç/i1 ÿæ)N*÷EBZrÈÇñ6¿m£æÆá* Æ}϶kšÔ/'¼†(îsÌ|Éö_oø® òm¨!V‹,;µþgÓ?~ Eâ“'Œt8œ\*–Ôl£REÀ—P?Œ }¾'gâïì{3g º3'Ê&*C6?Ù<þ'J¸öFíjfM¬ÜÞËæHän9àÔH’yþu¢Ü“°ðž¨aHì,ôöYätEHWÌó[?ħ®Iè:ôàg;ÖÚçXŸGµÖìÓk\ ëv¾ðO‡.¯ïn§[{xáL)vè œ*ô<’»üO„ÐÜZxóão€ÿ–`¿ð½ž»%ö Ë3äBñG2°ã|€98ÍuS¦ç;¤¼ÎyMF\¶»<êûáãØÎë{=ÄŠ]<„µ¶,Ò+à©çJÀ`çu¬‹ë9ôº¶šÍå#–¤WbYI>ò­ÛØóPâR‘sLñWŠ2ÄcïÂY}×¹_n¢´vÆÔ^Çq¹I ˜ìIÆx¥{«WŽüä­©é× — wH§%áþ·ðàŠ>)ø¨®®%µÒ,Ø-ýâždè|¨÷ÈŸáž IÁ)s#[s4ßCëe›Èœ>r§·×ùŠòŸŽ¿³”^(3xÇáä ¢Ù–îÁp©r{²vY=GFö=e3F™óã[]ØÝ½•õ³Ã4Nc’9«+‚<ƒZ–ä0vç½j¼‰5c—åÚÜq‘V }äxéVM{Oêº}®ÇV¸†R»£”‚AR¸Î}‡âj-ÄºŽ€Æ++\%ã™cÜCÆIL dôèqùµ&‰qFÍŸ#¶¾²¼ÿ„nÙ¢¶_.H6',GšîI'sªí=©þ+ÔÛUx%@°åE’±«±FyÀŸJʼ¤çI/æÿÛeúšRIFmöÿÛ‘Œ÷ð[^Ç1$òà ’9 ²œ‚+KIñÎïM‚ã˜Î³CÁ³øò_‘Þz_Â_…ú¿Ä‘¡u¶zHr&žE*ÎÀüËzö¹ëÅ{þƒ¦hž²FÐlãŠÄTUþ¤òI<šÍîTWSó×þžŸð´¼GÿƒËþ.•>1ü^Œb?Šž$QÓ\¸û=+.Ʀf§âÿkw­©k>(Ônîî.¯d–FÀÀË1$ñQ/ˆuôá5ËÁô¹qýi…¿ð’xˆp5ûßü ñ§ø~ÇÒñÿÆØY Þ*ñK}ïj·þ4ƒÅ&‘â+ñž¿éoþ4]…åñ‡‹W…ñN¢>—Ò=ümã92x»Tbª!ÀÞéI«´ß@Zh†Â_âÃÁñF£ÿ²!ñoŠÈÁñ6 G½ëÿ;±YvNIKON D750 Ver.1.10 2020-11-11T17:34:59.23 ÿÛCÿÛCÿÀâÒ!ÿÄ ÿÄT!1AQ"aq2‘¡ð #±Á$3BRÑá bñC4r‚%’Â&5Scs¢²Ò'(DUdft•ÿÄ ÿÄS  !1AðQaq"‘¡±ÁÑá2ñB#R3br’$‚¢²ÂCS45Tsƒ“£´Òâ³ÓòUc„ÃÿÚ ?ßO¹Ç©ÁÏ©ôã†/!¹ü½N{n?,ñûL(Ó[©¯hüÄ5Â:ð¶Øzçl}{ý;q‚YÁØœ¾ìpcp:¤Wk¿ÄsÂí°í±Ü|½;ñß…å¾Ýò2N7?]óúÏðÈ('oÐîzÇ^Gà|Ç™Üäzž2ð»d2íŸ"6Óùñ»ÛãB-8püG<‹qòéŒïƒ¯óã3GlçÌ÷û½<÷â÷ h úìŽÄ¶ÎÛ‡®ÇçÆkNNÄ/¨õϧ1—íÛñÔÝ -9pr;}ÞƒÓ·åÁK'8ßËmß?‡ŸßÅxE„³€…’ˆŸŸcÛ¾øúüptpƒÛÌvcÛÏ€ºIw¯³A5Z ŽÆ?"7ôÀíëŒ÷à´ƒå¶ ?N÷—óà†:á ‚ÔZCŸ#ßaÛNس’î3ßçߊ8Œùvk,œÛÒdì01ëŸO–Ã.ü†rGëÔ>‚¨ÿìƒô8FB v¯/¯a“ôÇ|žäü¿—rß‘Úuç0BvÉß·žþ˜ã¡OˆÉÇ–ÞCÏ?Ë9ëwtE7hy¢ãÔä`çq·nü,Lglã;Žþ[Ï…@ÆÀ'qø‚œØñÛ?™ým¿$LÎûl|¼ý8²Ýÿm…1øó‚˜°~¹í¾;÷à´§íœc×¹ÎÛþ|,ðËâ”ç½½à¸é» }?Ÿ>Øñà´¦|zƒ°íÿ>{pªä+øƒ €¤”þ}>¿<íÛë·­7cØ¿˜®ß.(˜´‡5Ó4”øÆ;o¹Ü¿”Ç ãb Û¿Þs·oË…ªŒãÇ–µF°pØ~ ”§Ï–ý†GnÛwÛËçÁIO“Œ‘ò>£ðÏ££7‹xÁ œ³ÁiLGqœ“‚G¡í‘ôü¸)iÎ0úíßú~¼¸ÎªÔWB°i ÙhR Ž”·û‡qç‚x5iC Ž’1ƒç°ÈÎ~þü-Jmi¡ÉE0Õ5ñGH0¤0_!÷úðh¦ÈŒç×î'ùp§Ã[¡ˆçñ-/'éŸåúÇ ¥/ý c¿|qøÿÇË…•^´ôÖpÆ_ñ­ È=>]ñ¸Ë~ÛƒÁ H=6à üÏÝß…pÃâ$55…!u¥vÊŸ0=>ž|( ylqå߸ùpXñøù‚†˜B©F½Y+ÁÉ;gqžÜ)‡§åŒ~'?Ç*Á ‚I  üo…… îGݱõ;úp¨¥Ïpq’sŒì{c€*˜° 5º÷_¸|±¿Ô}8í)q…øŽ;’7üFÇ¿ðj3~4ÐWX‚Ìpò…=ЂNÜcÏÔ€ì\ ¿ïà:Gçø‚  ß¯ËÝqåëëƒÜùýãõ㆕º€ A9ÎãX'}ø³€üat:Ѥ>ƒ¾û}8ïÝ@î;1¶}FÜ]÷ ‰?E ‹G^éÒ£$¶Ï™Ž9î¸ßž¿×çþÜP™€6µïq‹“­kwF›Ôcÿ-²|øÀÓôä·?OŸ|6ý¢ƒ”ti‡šã.Þ[dïÛŒ /mŽIùýO–ü@·Ç‡¦¾"\í›RäíÛ¶ÿˆïÜp“Ó¶6ß|wß;pANÃ6€)jHHÓcË??_—o§ =1ôÆ>Cóû¿Ÿ ¯Í–©šnçlA¾>ﻄ›×sŒco‘ñà¯aG#⟳ãU„”nò;?O_×ßÂNdì Ç v9ûø ^šÊë1LØ(C‚0rloçÂMßo‘Ûú“ôà¯øëŒ K0l!¦Û¶øÀî~£ïý ð#ÓnvÆãsŒ|û *"¤Qƒkóµ0$änwòÇçóýwàG¦ÆF<ûò@<]ÎMý¼ f¦Æ~yùìs÷þÔÛƒçˆÎ7ï·{‹h@³ë”ôÃ|Hï¶2{ýÜ50q¸ÈÎ}7Û}½8 @bð FåÉLFvúvǞǷÏ$¦Üá{ãŒ_,ýx·8‚Cü@7°8xqýÙDÿ·â^;ÌѨ;Œ“°üÿßòã£ôú ƒ¸ôïßP–êúvhG™¦EˆŽ¼"s€}1Øžàî|ûþ>[㯹 Œvù}Ùïßñá©wy· àWÃ-xG<‘9ËËÏŽps¹'|žÀlqòØúýü]ß×vœÅ óËÈG~$’ ǦÌzwü?¼wÆvƯ—èñàqükt0=Î;ðwÉÀùvïŒcaþÜv!ß¶1܆Gþ?ãŠ#Õ°x¬ ãð!E‡?å#ÏØàä}Ûë‹Ä\à}ûíþþ_ºµüE¹ÎöÛcq°îÿŽ Hr#»~¿>(¾cw¦0I8§àÁ LÀí°õî;q¿üúð\pŒŒ?\œïƒÛ¿`+ªEi¥9ôÜdŒ{»n(ÿhnsÒr+ALi)®w›…|V› ²®¡éਪx䞢ª¨Ä:Í=4Nî§©Ú8Ì‘™¯3lí²vU¿h”…µ(àP À¨¿toÙ–5m }–ÆGꔓ‹?Â=›Ìi~ý£5µu&—SrêÕ(E䫱j¨0Ž2 …C2u# FêGQǧ}¸ù1w÷xîpê};, ?‹Wk†ãD·Hd¨´ÕÍ#‚FÙXàž¸ùÆÎþ(JþL½¹³Wd+JUÒJu$…R«Še\Tãœ{Kgг™kÙvÔÚ’EŲTృ¤qpšã^Ñü…{l÷i¹©£môTÐÉ<Ïx¹¥’£¢%êdŠ‚òOQ>ÛEo#•KmÇŸœóý¬<¿Ñs›W'´G0«s߯õsO˜Ðž©-ô®¸!©’‹¤TH1Çkýy²l»=6—9BÑ>’Ò $3™” Hö–RŽ +mô¶ÑŸlUžÙ)V9rO]DT»}•e>ðH9.Â5—O~×nzßµe®Û+ùZm2L%ºAZ¸×GnŒ†žHîgP˜©dé£=$‹×"/IÈ{Èj\óþ¡±µUXÑÑÛ¦‘ºŽª¨aFŠ)ªí—Cv YfEê_uªjh\ùo§¿‰òí›rVÃÛ(•e›n ý<Ô:Pf(ÝL•…)L¥á,ƒU2[¬˜õSøh³ìI›gfÌ]ª]«¦B€¼%¥!Jš› ”T¬êÀ*6kÝóœNù8ôØ÷þ[cŽÅ8òP1òóõ#çúíõ³…sìÝŒ|ì»`úÁJs²íéÛë¶{ÿ¿-1/ÇŽÜ  ¬5º,;nð‚R2q±õÎ<ÆÇõß‚R qéŸÏûÿÆü†&§{h%i»|9ÎÿNøÏ¦øü8":`Øîpq¿ŸËÏ…¹8Pòh0Æ„ƒmü¶üÀúpRSnÛŸÄQÀ>;õ­4¦5}|A‘ÓìNÿ,wùzþ\”Ûà?Ç|oê{þMkã\ 4gÇÝŸ[àħÝF6|³¿¯~ ZûrNþ¹Ÿ¯ùáJ<\C:˳t9Ïnøý8-)û|=öì<þ}»øp…ë„F‡â Jaæ2FvÁßô|ø-)†Ûl—q¸'Èã 7S^Pä¥ÈáñÊ Jmðû‘±ï·oLpdtÀžÇÈíþ[öÜvá P‘XjCå_Æ=°JS Žû }Ýñõß‚R›; ÷–Oë~Ti”@æýø2:nÛ|ý1òþ|eOMyº}øªš¾†°ƒ`!héÉÎS™ÁØyþ‚V›ËïéÉ9ÛÏR»ýõX ’YÅ=£? â6$9Ôrq¶{zþ.‚‰Ð6dyºœ¸, t†Ü( Üp’ªU´ÐÀ–4¯g/Ï”´½IÏÐwùí¸ÿ~J]û¾3æ?ž8Q™¼¸¿ñŠ_8íæ~áåÛŒÅ.ý¼÷ùý};~\ ˜ÍÃŒAÁáQMòùc¸;SóáAMØ3Û·o».¬æ]òî‹H˜~DeîÄÃ=þ_—˧· ÿnjqÇ™;`øóà‚Žïˆ’a{ Œ`dŒ±ß¾ÿóÆL­FCH؃ëŸ,g†^/Ž©Ü]¾ otDP©¨¤t€€O˜íÂMMŒàoç¶>ÿž8·.øò§âŒöó G¦Îví¾0Fû“¿áÀFü0[~Ä®äñgëøpaXeçÉKÓ‚7Üǘ8üxéÏÅÔ={v;þGýø$©Ø½`zîZŸs·þÇõòà9hÕŠ1SÔŒJ÷Á8Ü·òàŽPYœ¶ƒw@ÏJA>y=—¦À}’Ÿ¾>žœV{z@5Ñþ=à)i†IÆvôôõÏoøàg§8Û~_‘âÁpîí­xE… _|¿Ç8Ž­Þ¸øcM .NØÆ{÷Øúñ—ƒ‚NnûsßéÜþz±ÄeíŒyWÈSHèCå¾ý¦=O¯ûñ×¾{g9íŸ^ãçü¸4ýkÚ!Ý¿â2ð~‡ož1ä~cóㆠ3¶ØÆämô'çÁ€ÃC\ ƒ0a|µº2ðFÄywßè°3Œç¹?]ú½?_N-€‡ÄJÔªwG<{.=žÛö;q˜€`¸>G#ÆçùpLÌÙÄĸüBÉF}=|±ØöÜà/>Z|wc çï?¯/Ÿƒkt¨s ,#á=ûäç~äc¶øà¤§û#³åŒäퟻ>,Œ7 §bÌÚbSäŒgÿ?‡Ö8))Á=·Çב·oÐâ3°ÃB-Ü>²‚ÖŸ±lŸ1çÜöõãÀÚOía¤æu®¹Û¢±i¨Ó4ÖÖ%--mû¡+5MLr>Þ,SŠ )2ƒ#fßçÅ a³}6,ÈûíÓ塆iK¬÷))ãÏè[0Ÿ¶Œå}¶YJ[äê)@ðQî‹Vèש§I=òžäñÛëj#£­3­¾+¼fe$Å‚uRÈ®@2c­z›™ôúvž¶ák­š |NòÜ.OMG·B*/J S$£â˜“ñªìÇÅì;FÙ6J¥ÚR‹E’Xùˆ´´€UBÉ ‰n«4}>Õd³IX\‹Ò§,’J¡÷TJpuÀT“ÍhŸv´Úîú~YõÄ÷úÊ EJ™Å=A¤À™©å0±š•kfˆJÈÔò*8!˜[×NSØi¹k¢y;hPòªšxªe¨¤[ŠÚ£½QÓÇ ÒÚ(=UÂó"Ü ª)² ê #;)Á°È³[&ÎýDáe°Y•©B„‚Æêx«kL£5¢lÛ,©F\£>×j]ĤՋ}Ê.ìÔ™drÚCÙT<œ‹å½¶ÿgæ]Ê›Gó Y½6•æÅø×˜*9c[o®žJË u¶ÙKÆ¢®:ª»º )éé^¶‡Õÿa 5zеšÎåª.ë]óPÕÓ i¬ª¦VÓZôÁJJÓÓ±Gšš •úˬ±œtDg(Òˆä¿Å+z%lËfØÙhU’}’}—ôÊM-2æJPY.\¤ËRÉsˆ$¸&>Áü#²Ì¶ì[+i­3ì¶¹6¤Ú¶(˜fÊZn (¤­)ÿ( #Ú#‡RÐ$Ø+ TJØl‚xFÀp¤Œý–Ê’pËÅ9\`I#}»þ?eý õMŸë/¤¶ÔriYЩ©Kž–E¢^öDä­#¨Ëÿ[}5;éªvçÓÓ#fÏRe©T¿!L¹0ýòT…$Š´d´ù#nÙ?]ò{üÿç…ÖŸoöo—~ÿïÇ©$ä9Ç—HÀ>© ­>ÀòßñÏ‘ïÛ‚– ï@rqžÛg׿ãÀF³hõÃ\ …ƒnÙú€|¾»> JpÇ8Ü÷ôÜ|»íÀ³Û-c Çñ%>=01žÝ†GŸnßžx))ú°#ëæ<†8Q!ηW² 9gËã^°jSçlzg}¾£cü¿áßóüxQ8Õô “¸Ñ¾5åÇOòÇlO×˃ŸaŒ`°Î6ï‰ÎÔƒMÚøƒc¦Ïá€rw=ñØwüx) œ}ø#¶3ÛË„¨€k»Ôi¡ÀP~`´¥©ßæ~X‡ãÿŽŽŸÛlúcçøð¢X9:¤8%«=7AILNÀ ïøŒù üx*:sžÇ·lcË$cê8AS–|C D i³ƒR—=³ÜdzŽÝþ¿Ï‚Ò›cm°>îÝ¿Dð…+v°†$;fJSÈ[c?L~?Ë‚c§ÈÉ_¨ Ÿçõü¸R”Áõ”1)«3óì…½Ô’0v’ïÛ¿ àµ¦#°'>Ðð³1š¸üC\½ …¥íõï¶_íÁ L<Ç—Ì“ßâüÇ Rß„µw§/H]i†sÐ Á#;ã#ËoË‚›Øgå÷íúõá&e)X`Håé Šm¾›cÈcùg…–—åõw R鎩1w8ùB‚—#·o?¯|àïÆb—±#;z>\þ:¤]Ðøañ l·sŸ/÷ùüøïÝÜv\o¹ùwÏøÞña-œ,)¶Æo˜ã†›=Àþx?-ø åèu®1~1×»|¾YóÆwÎ;qÏuÛ`6ú~?#·ZíŠlã¯vÈû>˜Øþ»qÃMÿhïéê~œXX}Æ-Žq×»ccÏ/?OÖ8ÀÓ(Îß¾=sÿ'‹ «úÑ»‡ˆèÓ˜óìNÇp>¼$i» yÿ? ïÅ¥y¶«ˆÃÝqä=>í·ïÀïLÀ€ I-Õß}8\WZšk nŒ 1 çl~³¸ù}ü"ÔÞƒñÜî1÷ùðÔÌcL$/OxDÓo°úýûp;SÅsé°;~‡~™€±Ã²¦šáñš}ÎÀz}wÏqòàw¦;íë¸ß¶sQþÜ8+Œ’æž\ f§ÈíÏüúzÇ„›0=>þØÇ˜<ú¶/­y@Ý09ƒ¹òýoôðwøwïþãùðOZkZ’^”?Ž+S€sðùàËëŸÃd¦¾ü`ãË||ø+Ä^E0m g=1ß¹ÀÀÈß>ø¦™Z'G#”Ãc œpÀ]ššÛ¡d ï03ÒP«¡w]_ÃØŒç ôöÙÈÀX ] ® $§ß°M±ëŸ¯çÀRÓãËý²1úü>ë ÿˆCÝ›Éýþüs‰yüG´Ti_‡Û¶1üûý玼/=sóÎOb8ö@a›ãáGqÈ4v"Æs¾‘îwôÛøíb;PN}Nþ£~)‡ÄX×!ß¶ûϧŸØü³œd{üÿã‚M)Ž„@o0}S(ËÀïò9cç¶<óÆb ùß=³Ÿëü¸& :Ê-úͽ¹e­>Ý·ôï°Àû»ý8SÝÈÆ~ýˆÎwõõïôâ°Ù—<±ÂZ|ÆÇÓîr<ûwà…§ÜgËîõóü¾¼F8ë(§ wôפ?l ðNsß|Ÿ¡Ïë<)þ^›î=Ûÿǵ|"b*[YA‰O¸8ôÓCÏN Jp|Ž7?;“ý? nˆàŠà~"µçG1-œ¡å~±×÷)©¢ýÅg¨{lu.¨•—ª€)l´!N ž-Êje` °©ðzOüõ²Ñs7˜TšË_ê†ýÃh5ÑÑM4p‹•}LÒÞo—K½eRôÁÕ‰ xéÓ2£7Oþ'Néö–ʳ´›µÍ]qTÒ”ž !ù">—ô":+.еýÓ'-ÑL/(ò%`0ÌEqçeª‹Zj+ £ßj¨í“_ï·¨„0QG 5¾!šdRÕÕ’VÍn£0«—íáBqFRSs ZhÙ¨ï)+޲»EàÅS4T›F”¶NÐÀÆ2U}æ¶÷U('O+ZÀà|¬«¥*—/«- Rw;” Þ¦äñïBJ@ZÍåLºy7[½‡ŒH´ ¯K_ùjÐrŠåy¼i (­6ÄP´ÖlôuÓ­\òJCÖÕÕj*Ù%=%aHê™› Ž.+²Â;Fµö‚ÕzbÙ¥¡™­±j Õ⪅+mÖÈãJ*í£¹MãÖ-4QGºÛMQ0 ÓHE^7ìíš¡-v‰ÓE—fÙ‰3K^bR2ɪ b%£5³h~Žd¹RÑÓÛ§·Fž¥G6͆8PŒ¹Á쉥oúsIjŽNPѵ5êÍ ïHj Uu¾é®bYb/ BÐø#¬¢Õ4wHª)j©*"†¶ šI(ê)cªŠ(åÜ®prÇÚ6_h/bŽ\ë}uª—RZ4%ªÕyæ]%éê«õ-ùe¸óJ¢ás‚çR—Ë•»J´]+%hjîé宸S™«}ê«ä?WÛ¬¶KT›$ð‰–kd«lùAN\I”/J#nÌ&¹'}cëŸFlË]¾Ï:ÛeR¥O±O°HšPÂèŸ4´àhRÊ–”Ó5=#Ùcm>Y{CÒÉYÊT¹ÒÔé« ÔvJÊUŠžÃKKp6ë= dªàKÎÝNÕTuX¨¦Y U0øõ¢Í_G}·Áp¢pc”bD$ ™Ä‚`>Ë©#?ê2åXî¿ìÇõ §fZ¾¡þmi€Z$‘o²‡z(KE¡ðt™’ŒYST@7£“ÿh½‹eÚö§ˆ›&Yý5¥?¢´›­Tº¤)L?j„é%F„¦XhväoƒŸ¨ÛñžÃ…>Gcœdœn{ñúøŸHüœÎϬ> ”€àaG–{wìp~î Z|Œý=O§~X1‘A¸ÁIOÏ8ÉÉï÷ÿÏ%8í€1‚sý~î¥ç呃å%?¨ê žÀöÏòǤì6î{ùí°ý>¢í»¿t1#‘ø‚ÒŒåŽÇ;ïŸÇõž ŽœzmèAåëßñá7Ƶ¦†$T6?V Jq¶Gååý6?^ Ž—˜ùÆØÿÎxIU”¶þ 䀜äm¿<ïŸÖx2*}ò}¶¶Nÿ1ëøð•,œ1üCRŽí|Á©KžÀvo—¯åÁ‰IòóÎ>ñËŒª[–5oˆpN Ë^bSc;l}=6Æçõ¹à´§Ømÿ>ž[ìxI/®^ÐIÅðôüA1Óv='Ëîàä§9>Çõøp•¨o×”hBI© „”Àþ»wí¿¥8Çm°|¾›þ½xAY-­ÝðÔ¤€ÍÛÝ®PJÓŒl¹ØýÇ·Ë…ÒŸ~ÇëŽÝý~œ)K¡«¾µù†­4 …¦òÆÛg`G<”£o¨ùó p…L#\¢æBÒöÛÈyy ‡%6Go—ôùwùp¢½ÔЃ`вҌz|Ï}ÿñ«Mò;d}vì>œ(­ñÖÀ’2mÛ¡AN7È>›ãýøSÝ©fÀQñ<€˜Üph£~ì<5”N£$…dPëºÆädnDZáAO¿`sŸŸßôà ÖptÚÖdك `HØ~¼ûqŸ»c²ã|gwò'32}R,߹1ƒçß9ù~\uîÙòõØíçþÿåÄkX¦ ìÏñ øÄèðØazºñ±>»öã?uÝ~{ úð]+7[íå–-‡„tiŽ{yùSë_¯~04£Ó·¯‘ôï±Û‹@ÀÅ]¨qªFœyg#¿§—Ÿ— {¨PB‚|þ#œ¾7ûø>“,"\ŒŸ;cðÆûü½6á3MòÛÔ`}áÁ…àÕ4!wa… u ¶I$’wßËvã§îqëééßoþ¸á‰[ã›@”æF©µ?qÜîv~ÞXíúõàf§Ë·Èúcùðг€:¤ Á»T¤§ÆvÆ6''$~\ðnASê0=ç<1*ô5Ù Rpåì`gƒÈí“¿ÓÏ$¦ØŽ‘ëñß><~±Á%[èÊPØkJ|dã>yÀß>?­¸Z}Èù}ÛŒ~áˆ!ÁwzyBÔl»à6§Ï–ûî<÷ǽ63¶AÎ2F=<ø+à0zkŒ.ëdíñå”!îççùÿû»äíæh~Gnß#ó8íÛnœu¬ãÈ iŸdwá;yÇÏÏÐñ˜‡`1‚1ßÓñúþ Øñð‹Àk†qØ„gùúï¾ÜeàwØöØã?Näùp@g™oÄUE5‘ŒÅ>HÀÈòíçÜ|ó¢˜ç¶qŒì2q¶ùùÿ> ¦’©ÞËËú·Z¢±V_­Ð-®‚µAQON¢óQ%w‘Hã#+‘…/ÑŸ°) ªY7È<#¾5o%D}¡@ÀºR6(™òýõW,-3ëNXůÔ÷J§õžÓ”ºÀÚuº š ´Þéré©kŠ{ÄôóÓFP»@Ì©4rZdþióÆ¢íÌ.tkýd%£ +5m辯¼Û šaKDŽž¸RZ-qUWP ¦§ŸÃE-iÃ&H·Ï°NDµ™v JÁ!¹Š ¦W‰$ræXÔ¥Ym”¹¨½išBX1Ze¤õˆºËç…Z/o`I¹ËÈÎyܹ#ÓÔœÆä…u5ߘZ®Þט¨`ÒöÍ1n÷êÞqh{…tƒ÷uÝ-Ö䦫¡*‘ß©àªÄ§¯§ ­¶l²Ï;uN°¶óÊùí%Íxôß,é5^£²òûW])Þ¯Có7ÚV[Ýœ½¾ëVç§MSY¿´sÍe§¥JÉj °ÆKŠ}`eÛ¥OAŸ´vX³™r‹ ³m3.… ¨-))P`.q,>ÙôL¹ÖE”›@³ì¬mBlàMeYP‰JAp’…©*Iro8!˜t¯›žÌ5Ü‹ä§(5%¦ß®¹áϽo³¾YB×ÛnZ Ï_/)týDB´Ö±Zuíâ–vèðe¶ÒÔæ28úŒÑ—ùt¥\ ^ií• 5ôìæYSeªF’õH ±Ë‚ÊH$2ù›7Õcé_­~–úÎÍ-Hžm&ÚP YzOÓ.So2Ôšén¬{Ä}*¯©þŒúŸèËTÄ̳J‘&M˜þÔZzZS4ÓÓªZ¹ÝQJ`«§†®–Dž ˆÒH%Œõ#ÆêX^žàŒŒcíÁ"Ÿ>XúïëÜqý1³Úd[,ö{]š`Ÿfµ!e­8- Râ’1üè´Y§Ù-ì–™fU¢ÊµKZ¥hUÕ%CxP ñJÓã|«}ó‘é·§òà´ƒ·ÂF7ì ÏÏîþ\qÖ²Š8}ÞJ@6c‘ôÛ¿Ç™g·®;yöáj$0;4 ´ƒ`OnÞcËóइåõúƒŒyÿ· QkÖäýiG¨Ç˜ ãÐú‚~î HšSŸ\}qÆu*øë„=8Öµ¾ JrNqé¿Nß~x5)½óÆ;`ú÷í ƒšÐûˆ0ƒA©ý»“Ï×ðàÈé·ùöÈùmÆu«° k”9!ØaéX::rÃÐäã?­ø1`Û·ß±Ÿ,ŸŸåÂ¡ÙøÖÔ¤J‘­|A‰NN—–ûÿOÂR˜íŒcm±õÛ„‡}eJ0 ¶\t ?^ 8Æ3¶{ƒŒ}86*sŒ63Ÿ-Ç®ÿ‡¦L4ᯈpM)¬5œ”ý¶Ûlgåú”ØÀúŒ~'G×ò=¾Ÿ— ­0Ø“¿¶øÛ}¿Ÿ TÇÏT¤0%êjÿ¨§„àyŸ‘ÏóáAÿHûû²>ÿÏ…™†£CZÂ'z^2Øì }Þ³õã±M¾qô8ùäç?ãÅt‡#s…? ¦Ç—‘òÿŸŠÄy|‡Ð|ÿ.¤'<~ ‚ kÛ·#Lq¸ï·>_¯Ã޽ÛÏŸÄŸŸ¦øâºFíãÊ.à禎0ôù‚;žÃnÜbiõÉÈ;“ƒœýx±1ÅN©á¦z¼#£O-óŽÙü3Øvý14ÇÓÏ/.ÇåÁ_PjÀ\ã­~a6¦ï¶>x=Çèð™¦Ëúþðbi!²»ZëxKݶõÆO®Ûù‘ëžjså¨Ï×`8`šíX¢œiÙ­xÂMOÜc¸¶8DÓ>Î~ìmäwv<8MãQßø„Z›·–;Žã±ø©Ž7Û wÏŸåÃS3 ð;µ†»`v¦Ü7òõûóÛ·½9ú|Ï©î?ŸJðÖ<= .³e½6÷yÿNz|g#ê;o÷ðÔ¯ µø…à ~ v¦ï¶ÏË˾?YàCNq¸ß'p3“ŒƒçƒùðäÌ|K@a§õÀ þ¾|ôûvó=ÿ<ãä8bTí_w@5Ù­<ôÝÈS—ëlð”Ãoç°Ádvá¡FŒkOHYK½5H éŽ6ü>»ïÛoüðmœg˾ߘùþ|1+#˜ãË^Т—wÕ`))ÀØ m°'?çÃ[QH*dœÎí¨´ý#ÃVV'Ä Œ–ÁÁøáOÏñ »VŒ<è>òs÷ãŽqïð07»Æ4xÅÒ0Àc±;o°3óþ\uàó¾Fq°óíúòã݃NâAÁÆîi]M§µ¶;¦¹SÜi uRÉSM#xUt²bJivl0HYHcð¯á7ñªÇõÎ×ÛŸMm5K³m‹ ¦Ò«Mk±¦aºçûù) ´‚ë–ӴŸÐÅïà]¿è‡ôïÕ0Lµì{u’Ê›{º•d·*R/•Qĉë$¡Fˆ˜òÉRÞX´À‘€>Ÿ>ü,”ØÛðß/—n?@8mä|Gçz·8\B—å¿cøœ>5?ž>Ú\‰ä%UU—Q_æ¿êÚZz‰%ÒÚV(®u´u(£À£¼Ö´ÉMf¨’B¿Ãš_Pø†¥:ùgkÙ6-VËb‰R–¼²Y€0ÅG!^ÐÙ»>Ñ´í ³Y€ bJÚʈîª[Œ|øû_~Ò]}ÍjËæ”­»¾‹ÒqYê®ô|¿Ó“Îc¸QB³mWvN‰.­ã%*ṯRª ðiVL°òVç©õW1¤ÒP!µ[ítòêÛõ5-D´ÔRÐ3 °Ú/•¬V9EwDòGáÞ¶D{~oÛ›nÓ·-ómÔn¨uË!)P! î8’äÇÚ6>É‘²¬ˆ“).R¨Š­m÷žÖdso¦šÃgºY,uôôºÚ§UÔÖkCx§ã±ÓQQ¥dÍ[;t‡ºˆm´×Y)P„†w»«ä« ‘®ÝlÖšÚË|©zéj"Õ÷ÁKGKWX”v«¥­J‰²'½^ª¨FšQhè à8ÁÔÒÑöïê¤=x¨ŸGŽÀðZ†8p¯›%¡Ò‚ë£-5ÚˆZb¯­¸rÇMuº ÿv±[k£™m6则.7 ›½]ui*D¯Ä§ˆ­Zk]_¡ìºnð²ÖÖê;œ÷íVº1 5§MÚ›÷}²8éáAá$•‚ç+K+b‘3ÈÁTˆ¥^@—,AG‰%iGp =À˜´—QZñs¦Eø×±ãll~ÒÚgÙû–Öþ_rÿ@G¬uu+±"ü§lØfÚ6ÎÍÙÒ§͵¢OÜ\"e­}2‡ùB擽‰³ì=¥.ͰvŽÕ!)‘d™=® ®U‘)³ËpFÜïóÛσ’ÃÓúdŽ3)D³ëjjE)­yÁqÀ}îôÛ£óàÔ§ÜmýC~3©tcPœ÷ãÅNr22Føü}85)ÀÆvÎÃl|¿ ñ•s F/ ËZx1)O˜8ɾ^œ”ý¶Ü}ùíßåÆU/t9)§ñ JAßnÃðúð@§#`?ã8ùwߌæb^¦”oÁ L|À8Û$~–x%)Î@úz~>_íôã:¦Še d ¥¦õÉü>ìúv<.´Ø8ÓÈ÷g·üñœÍrØÆPĤSu=>yBËÏN799ò?®ÇŒ™"‹£Äpl¨™ÿ;Ã…)dwÝ®A"…Ù¾5¦‚֟˧$yú~|f)°|d€TžØÜ‘žûð«ç(h@#SÒçÓî;z!ë‚›~Àg×|þ~¹áe@qƒ §/ˆPRäz ò0> oó„gî¿/§??§û®û‡ 9ûößn%óºÙŸ„wÒ|·î>Ÿ/ŸÓŽ{®Nq¶1ŒÎûüN:Â#ÕŽ^ã~ÿÐ~±Æ M€02|ûývü¿,. oŠ)'\£¯vü>ý»>ü`i‰'¶7ۿ˾wâÂÛã²*èaHM©Ž;ydmÛïóïùð›SãºñŽç=Çlwà‚ÀãñpnÂh1·N=6ïßÌp‹AŸ!ŸÏ›þ<5+º֌üOâ4ç|þx?˜ôïÂ-ôÏþ~\0LÀ¿¶P4l4?0“S÷Øg;ãÚœ}þ{oòòÜvá©›…aE&´Âj>ûG—¦üôÃ'l~¿_‡LÌ+ªkÚèìü@ÏNwûü½;?Ÿ~zsæ=qÛÈ÷ÛË)˜ >p¢š¶µÝ½>3ßb=7qŽß/øùÐáÁm‰Çâ¤â+¡=9ßa÷ ¾ÿ§½?aÏòý? +òŽÛ„ôýÆžsþ߇=?}‡qƒ¸Ïlþ¶íÆ„®››B·ÐŸ¹Ç|äãÏý¸J|Øó;g‡nÜ1*vcQ‡‡¶Œ-Xk„%9Æ0Û~çîýz->3•ÁϘîsŒ;pÔ¨bú§¾øYÐ/‚Ò?øãœã¾ ¨×dh¹‡;¶wÛÌy‘ü{úsÁÆvÀÜg;ý~\{ôІƞ‘á;1ãÊ2çðxì6ÎÛçå‚, ‡‘=³¸ÿî·?‡ q¿â±0á $öÇÜGóc—¤cÏϧ'õçÃbÑMJa÷9yÉ¥ù7`k…Ù–¾ùY‚ŧiæT¬¹NÄÒ±Ý-Èø2ÎÊqŽ”Y$*‡ÆwÌ}GÌ­O]¬5ÅÂZ¤¤§¨©4°(­VÊPÓ%²ÓEÖD1–ðÑFòHò™&‘™ÏÌ?ˆÛiVM‹¶fÊ['fYg-%Ø*y–D°ü¤¤qQ GÒ?†»;CꌙáåÛmReÎD‘1zÛ‚®Àr1ÓÜÆ¿Û)©ŸQ,šÊô÷Kƒê»\€éûpASj ºÚÚ!3UºSÕ"u"–n„†IÏS¤ÐºÎ²Ž*][¡îÓRÈa§ŠŠJI‚õÁQua*¨¦PˆÂÞDdN¢„ÇóJÖ‹oÓ;ZÉõÓóæXfØç… ¤ÿ2Ë= --Js|€»Ä-.›Àõ¿©{.Õbú«c[>™ú’L½¢›\‹“Oòí–uË@3R–Y\²—¹EBé]ô埴]Q [V²Š?z’QN•Êê–š’!fT4¯›k£^>§R]ºVöÖzçEòçLVë-m©-ZsMPB%šíqªXéÛ­zá‚‘©ëê¥ÃÉ,Ç 98ãúAü)þ+ì¿âÒÊÚ“Ô›ØÙ)J6„—¤¹ ‰ÒÃÞ2gL¼Ò ©NJ\ÿ3ÿŒ?Âm¥ü3ú¨lÙH]³aíu){:ÐÄ™’ïäL ]ýD‹Á+¯$¦h.èð[Ûö§\îvë‹•5uœ»Ð‚£÷mv²ÖŸXßw0â‰ávþÍQº±*°3Ü%P¸–v§ãÀî`ó‡Të&ÔÚjÆf¡÷ÍQG§í:„Êï_S]ÕeêµK)芑¢‰¦–N¦as ”’þ/꿨gm»z®®ä”‰iÉ(?¸ëQb£È`iúsbKÙvn²B§.阪TºMÀYî¥Èêq1Ö¯ºhˆ­/JÕÒUÞnš†á=-uΚ­d¯6 \VÒ”w»•šŽŽ¥¨¬­”/¼ÊÖõF^¨úÅ^©«ùƒb¸Z£V W¨üzx騬zFÉ9Õ×Ï&w¨’š8ÞWféÓ†8@©òóµ¬"@)IHJõuQxòu(òmÑè¥ß½0Þë8jP/1þPÜIãܯzfÓe¼ê,‘j»•uƇEÚìòE,6j;U¶ 9"³Ã8_ã4TÖHªŒe#‘k *ù,Àº˜ï:‹_ÁU)'.lÔð­ºÞ’}Y;RRû½*·Á©îKORÓÓ‹ {÷PŸ°¨åŠû„¨bÄØy>P%Â-;¡,–âÕms{ýäôzr¬.“RM%¢ÇA[uÿÛ¥K]ëÄhÃ1uUº 3}K­uϲ«²æÎ_ÚÔÙºHHðH6ã]W{{>ê:ëÖ¨­¶ên`Ã%2iݶÖ)WGÂã^³ÇgÑõ¡¢Š*…’º”h[®†cð›·‘ú뒾ܶJ½ èj´_2íôhµ7%5uþšù[Ì)IQ_t§Ö¯¾ÑZmé~¾ÑP¿zXÅ,7*% 7{dµÔB¹mlÛóöT¹2v]…7¬òÕzlÊu×véjU‰%݃R­‡/h͘mö³ÑÚ&–à¡7’ 1 ༜bÌ®\û8ÚyY¥}†ÓZ_tÿ;t½‘¹¹ ç»SÓÓZµöªæ­þ©[@Ý©(pUê£f¦Ó)Nâ(£Áž‘H÷º'\§ºiOÚªª ¹êk'*}žùYM¤ÒÝUVªKß/½´M%òÇAp¢ž.šÛuÃZØm5TÐé+^cš&t”‡üØ“h™?lØíÈDÉINÑ´Ù R`:I”¦Äª\Å®µ °€'ôÍë³ì ~ÌTÄ)S6]šÝˆ2Õe³NDÔ ]›)-˜w© z­û8lü³ÕnûEòÃOê-5`ç¶´·\i­¢_z¹[¤±XéäÔ”´õNÅ¥¶¦½¾ka=l:u*…#¯Ú ¼µæ…G&=š5&«¹Ù5Æ¿×v e¤ìôt"²Ý¨ètö¢³i»ý®ï:º]z¯¥“*‡û5RY‹$qKàÊí£ê´-wmÍœP&DŸÒÉJf¨`Ì%©C"ƒ(úReìõý%¤*ÉaÚ‰&RYÔ?Y<ªJ8™¨IàîhãD=œ=©«9¯ùëÌ~~\5ÊèÝ_íxåÞ‰ÑOETÿú}sÕñê [©åK”â¢*eÒ\¾ šiÍÜÔE[Ô þ´ùv•U:JÕVGQU]’‚®H+d©¦÷¸¦:9 aŠdˆH"A>¤ÿ€ý&Íþ%Û%Y?²vÆÊX Aê®e”Ø”f¨ zjÙYô¤ ãó¯ñ¡rö—ðÆÌ«rUý³±¶¤²¢±ÖB-BØ(=@¹)“ºP'(œ, `lwïÜçznx!`'îûó¿}þŸŸ´TA/¬£ñêAä ZqŸO<±ÛÈðZ@223÷íõíÂT£‘ÓpšÝG`GÈmøÿON Jû~d`måŸçÆe¨Ï^8Æ€)ÀüAIKØ‘ò9ϧóßÿ?o?»ÓÈp…®™ÃR |tûvùO?ÇÏÏð|tày-öî<ò8Ê¥硯AB]m4”ÛöÇþ_wÇOŒ²;œyŸËŒËX~ˆÒ„Ãöþ¼ÍŽ›'ÏêGóùprSwØ·ÞÛŒk˜Ilã]±¡)~_ˆ2:loùœoçÁiL§¸Ïlm¿Ü@íŽ2ªfxCR—àßdtûl0;ùŽßO> J|‘±õÇm¸Ì¹ƒ¿âoÄ”ùÇ—¨Ç–ÃÇMßnþgÌ|»mÆEÍ ·öC—-Ž„´à ãoÐÎq¾8!`™?!¾6ôã)[—ÖPôËáÏÂZ|çïÜœ}7Ï~ZvìW¤ym¹ÀÏ 3+‹Ä0KÈ—0RSvÛë±×?>÷Dl@Ø`à°v#=ˆÏåÂŒÂ((`Â2gЂVŸY9íëçòáD¦Ûq“œì1·–þ¸<,ÌÛB$ä7FkN>yùà òôáe§í±ôÁßà ÆPA%Ÿ îå¯Ì)îÙô>ŸíÆ~î{oèücÓ€37 ÂZšã£Š\çèvÇn2÷œHãîÃñ1ˆÁ=³Û}ÁïÇûoÇ=ß~ß=ÿóòâÂÝÛÄ[ç€==}>ƒùp’ÃÔÂT†#Œv#¾ÜD¯7Õ"›ƒ¼wàûùþ^»m·¡ïä?¯QZ ù|rŒM?ÈvôÇèþ|"iÈf$’R>Èð>gùpWÄQCÆ Nqé| yíÂF˜ãúm‚úãùðamA¬<àJp¦©50ßnÞ™õþ|$ÔÄg·ùço?N&vˆYNµHéñ»!gî'æ8DÀ=7~ý¼ÿ¦xrWL~!J—›Rœá§'¶Ç>Ÿíß„œïä—ëÓ†¢c6øJ^šxéþ_?Ëé>h>GÏ'¿—%Ì c­xÒ¤‡b+½9ôóý×§=9ÏnÞ§o»ÿøãœ4°l9A WÀûFˆx;ƒ°ùo¿â>¼v É=™î~ýÿ_Ï¢ƒ‡Ç(ùé£6?wÆBžÝûù}1Ÿ‘áeƒË¼öϦ>›ÿã‹|5º#MkÞZ}»zŽÙÛln>@p°„ÔFŒ’{ùÆn$ª‚¾Zùˆ2áW´F½<Âæ–¨¾C7‹k§¬k5“ /Ý6¦jH%‡¹TÖj“‚@5ô£­®f’‚* zÚÚjêʘj öË’Ð\(é©$Y„Ñ‚¤ÖÒ™B áß®6!† cùËøµlJ>—´JQí[L”É*IHX´¬) ýªL’•îJ‰Ê?E¬j_Ô¶Y®Gö]’jÅÕ‰j Z*Bˆ,°¹áiÌ©!1FÕs¦ŽáQ[išK}}A¦§¨®£$-E¾•-Ô³ƒÄñ¬i"Ö6…)"–->ќદ¸­Æz„Òº‚ªçLÕõez›EU–×âÁCošž¹™iÙíÒÆ¬Q0ôɈ`_³ùÎÛôÈdnŒNše‰kAoæÊHA”¡‚å™Iè–’êr «Ñö«Õ"ÜWÐI ÙsÿÉœµ(*jîæ&rÄä*‰º.ލêÿë-ûº×òÙÓûGî/tÔ5IWe‘Zi ŽyëRñ¹Ž¤(ž)Á,Bèï´Ï´ž¿ºPéÈ5î¶ÿUq¼ÅjÓÚz[…M=‡MÛê‹5ªßCâ²[¨ã†4iå@guN§vl0ïÿþ‹?L§imÃiRÕnI‘!.¤HéPB§"€­KBHIp‹·…UO-üZþ#åj6GÓ¨²"Z, E¢Ð¢£úžŒ¥¤®¤KB§P ®ó%Õ¥¶=GDt¾·×:ÚzŠËu[\ïvÓUÕQOmXªéíšqÖߊõAU;Õ;Φž9†éÃ&ƒV®ÕGOØ¡j=3Me·År’é 2ß*ïú·¢j¸n5(XQÆ´OVµ+:$µB¯#Ç<}T©)$‰‹kÊ5¡©îfï4|mÖ„Í èH Ì÷“à8jÚ]£ªuÇOTi-ºzs ôœ%ÀÃt®®šã=}|HV–º°%ãª(•¤†º1´jÉÈš†ï¨ï´ö$zZM5a¥ÒVÍ5g“Á´¶¨ºSOGs©%œ+Ã/ªfIfcÐz%ê YÊËeIª^›Ë»'s}®Øò‡$¨¥+šÉ%59 sÙx´wo£Òb¶ƒOÜêfª¿è+-~¦ªµ[bÚ—w….•½ÂE *I]Qh¡Ž(²Å©×Äþ®wÍW¬4¶Å[5 Ú·QT-²Ýe§zp-ÔJ4ªžX•¦¬©¬ºTW4Î庚߲¨,¤ ©R°P»Î¨@n 9¸Î *¼•G!A·z½‘?—MÃa¼GY=º=Ë«VË4Îjkê³ôil‚ïMCXÂ÷î‰úØ|oR@B]OþSèJ¾ohíPü¦´VSÔ/¼­EëRËá¥î:AN•)^U ¢·OQXѪ#—QÉ×1)‘6}§ô¶tô“ç•\cF* p €…*|¹2hš¡.T°²CîSWriJÆÅrötÝuUòŠ]_i‡T\ DQÓé!mšÛf©¹Íu4öqv“57Zê…ŠH`§‡Ýj%”„‰&b¡£”þÄš¯Ÿ<²ªå"jÝ,•<ÆÓTsÝ´½dÔZƒ–w#¨¨ ^ ‚¼¡³KTÅìÙ6&R_Z¦Ì¹%5Ü UŠ;Çè«%ŽnŵÛ~•µLD™JfК¹«7º4J9É] ć$:fãÜÿd[')½š93¡M:ÒÕZô-¢ºéR†;案ê;ê¶\^.ÕªOsÑ’<¸óÛ¶ždç¾²çö›×~ìÜ›öuæNŒµÛì÷AËÎgW‹f’¶µæ“û­ÀÔó²Ír£”åcnéÿ9%ò;ÑúŸ©m³U,ÍE¹V„ÔGêP¬®›×_Pw·ä 'ÒöIœ%M٢δ¤Ð¬Ùuu…Ûí¹œj¥ËR[9±Ë¿fyyµ¯V³Ú ­´N¯²Ée¥‚Ÿ\òΞº.]×ß"X)ßßõ‘ä}¶ëW 4^= Öª®8f%’¬a~d?8}–9CÌ u•£^M|²VÓͨ¬µ“Ó4¶kÅ}ž;ui¥?Á¼SÑÑÒ%RHO;2€éÕúwø›=êÕ%hb³[lÒ’U"uªBЧ'úb—£‰k%ÏæãE¢}§é¹A3 ïíö;E¥LÛL‹"Ñ1,_¨¾FÍE\6í)ϘÎ;œ~{öíÁ O‚?#õôÛ×êUFñ•Ò)ªkÞZ}²GËËç¾On H=³õÛóá%TÃT‡ZWH28Fsëýp<¿ãƒ yŒöòßúq•krÄÃS’pˆ6:sèwÏnØÉýŽ@ïŒ~|gZ°cHv}aGò€úþ?σ’›ÛËù|¾ïÏŒ«^:Ýëe¥›,= Ô§ù}ÿ=»ï¿ÇM¸Øíßïyúþ‡Ö¿sõ‡¤0 < ØéûmÜc—¯¦ß®ü>ØóÛéõ8ù1­uwÃãÊ„âN°‚ÒŸŸ/ËúpdtÛ ¿,îq¿3.cq¡)`úÊ Ž˜møgù J—o@;zq…s]õº”Ô¤”ý¶ùúǰà”§ÉÆß?¯}½<¸Ê©œuHЄ3A)Nr~ÿßåóíÁ+Nôƒ°<Æùíõá%{Ž© Ï!ñ-88ÀÛãô<.´øô[|±-ûþ\$¯w?-ià‚_•!u§>cÓ¾6óû»ðºAŽë‘ôïûùwáj]+H0–÷…’¾ß=ñ¢b6í¿¨ïÛóá*™Ù $>9^&OK 1SÔ¸'Ž<ÆáqO·làüR–Gî~=Û¢Ò‡…·òÿŽ2vÛÏ}ó<+¤«Á„p>]€?-³ÇbOo=óËo—¤bîƒãâ;ü¾ü¯ð0}O¨Ç¦<þœKáðŠ¹ƒ>š:ð>_Ëîþ¼taó#¿¨Éýgˆ;b]ìöŒ<¹òûþ>10 ö<\\pB` ~þÈ®Œ`iþCoï÷Ü&`9úýØ>ƒo˜ýw0½Øh@]#ö¾„`ÐØ_2wïèxHÀ{ãˆoéÁ‰ŽÀãøŠºwBFœc`_?ÇÚ »Žþ]Ïφá­Ð NáøÇÆzps•Î<½qõýo NuÆ—ËÈ~G†¦a Víå¤àr„Ÿåóô¼Žç·<„Ü‘¶äŽÀ>߇JÃ3”(xü@íéRFþc¾ùßîïøp4”äçc#'úðÔ­Žö×w¼%H »C\ v§ûöÜúüøéÇ|};~_‡DÊ€N©¦…)^Ÿã¿ó=³·Èp+Ó÷ØŸ—Ë>‡)Xv}RCë”ôãã×9ÁîAN4¬d±~¦Ê©ÇÂ3Œ—n4!~:òñ„¶àY È;w­ÿzq“·–ŸäOׇ¥{µ„H/‘€¤ƒâ ®ÙÈ=Ç1ëþü$`Æ;±ü=?— JŸú²–ËŽèÀ—ÿiÿs†ßVøS¯‡Ähgƒœz÷>~xï’ð'ïË9Ü·~>š8ˆùîa«…!E‡'ùc>¿øàˆàÇùsóÇlœzÿ_¯+„C†¤°g¸ŽYâ‘öŒÖŸú{Ê=Uw†_ér¦rÌÀ•\/+%1’&R1,4"¶¡O­'í³:;%¡wšê –ò!¶dt³äÊa×PޏGƒ7*ˆàŽ¢²¡ú!§ŠI¥v8DŠë2vQò7#n04‡SëÊ‹íÆy¡˜ˆºå%cXåjXQŽW |]årF#ÎýøüßüJÕ3cØÔ:²ÌÙÇ‘- aCÕTÀÆ„#ôðÞb¬’öÅ­‰“&H4b’Tµ5 ¤K.*ˆ¤5Ô"È]CH¢VgñTÊ%I;ä` oÃuv¬Ó¶UT¸Üa§u`““âJ:öøÓ«ô0C=î1ÇÏ“"i !7Šœ({Ÿ Ç(÷Smvy ë ¿¿Cb9>DV¦%6Kí¢ï eΆ½Iêv¥ªŠo w+â*±1°ÛíÙïƒÆšóŸVÒ]µ…Ö+R=ÏQéÙm:cOÒÖDͧ’å«ãªÏZµsËk‚ª6D!!K’Ò _a1W6u–JYD„Ž‚C“ÉXñžLWM´m…/)DR€ ØiÙëÍ5¦¤ŽÍWp¾R-}΀Þõ-4Å «¬°hæ¸-ºÏo ‡¥|j¸èªå™•R’ž”à·B0Ö* •ÏGÃÌUzdQO.£»Òø¾=ßUV\«&§³RTøp³ kk騥X u‰i*&ˆ4™`ùŠV´Kë(²p «Ryž·* éÁÑ¡s)*º÷7P{Y$ãŒW¶‹=—N¥$7û‚Sê-5Kuæ%ÇNÄ¢¦ª¶ûSîòÐÉuY’Žb‡NĽyif«‘³’ õ÷ _GËÛ ´ë¥).ÕW K¢³ÔKEN›Žy#hîõjU®u“ÛmUõÌÄ[š|8ML 1º ÍÂ’–ÿ€“=áö†#ˆbCî‚®T4JKõó˜SË`©æÕDpRÆ+/5ŠiÖäÖš:Xcoy®3Z‚‰LkM™:G4º¾ÇÌ –ÉCEO¦´F™¸MWuªjî̶z6ŠšÑîJRÅ&©¸Câ \Ê@eÉK%%?˜… Ü–ãåH©jÈP#s‘u#²¾1_i!x¸i›Ä´"¦éx×—šxä–¢£Ä¶Kiæg¨žLA®¸ÒìǽU]‡+¦=¢ëý˜ô-N…ÑzcB®µ¸ŠjŠÝK­®·¾9Jâ¶-%CGJ·:Èî·¨5Õ5N kYðœ¹Y­S6j“j”Ý0MÔ“’–/?0ôÁÌ¢Í.Ý(Ùf$¨¤¨ŠPCŽCE-«,^ּ붯9µ~®ÖZ’ƒOWQÜ,j‰k,v{ ËQ4”× b¤†’›NÑ%M¹Õ2kÖ  j¿[ïÚºÛ§ôÅÆâiÏLÒrÃI½|Ñhn34!LR¢üŠÓ5{'kÚîIØ“-*T¦£Z%Y&L˜?÷‹P; ãö«,©{ccìùg¤·dÙ¤¢y5{,ëmœK<åË';¤“J§Ô…a„F€*Ç UUQÒ  €§2š»˜ÜÇö_ÔþѼ׻òÚ×zÕ¼òö¯¨Ðº³@kj8j(5*­ÚsPj+ýj9¿ºVQëíhê¡ÇÑO ôTBÏ ž+èù2mÓv–Ï™4Ë™nD¤%@õ’‘53¤ñEÄœ_cßýo>~Ï•²¶œ©"r6tÉŠ)5J–¹] ¡¹WÔ.ØÇ›šnƒ“üî·kÍ9W¦5½–ÉÉ$äD6ÛaŽ¢MÌ-;`³r‹^ròïMSp- ä½âóX*À’ŨžXÒaM7¹Ÿ²·örûCû]uUN¤çÅŠÿÉ­{Kåù.úZ÷Ur ÔOILöQûê¾ãHšGWÁLÍ)ék ¸ÓÓ¬5 ²ÒÐMCúWø3²&í³fÚè¶ !²I³ ’Ô QT™³ï)ýíòI4e]½ù“ø½µ$ì» £c̳~¥3§ÚW*bHºÓåÙÈræ’‚1t©47®ûz°c²ç=¼åÜðºAò;zäzŒþ|~ÃR·8Ëwh–Ïã!)Ç}ðFþŸ‡§­>ãnÿ!œ÷þ|gRð­æ )9ë&:Aõî~ŸO.œà ~¼û}G–§!ñxrSÇCZx5 ØnÀÜzç#׿ÝÁñÓgÛË¿l猋[q ¥¤QéíH:*\oŒŒl=?߃RœœvÆ;o‘õüüøÉ2eyF„‚ÁÇl”ýˆß?®~ø5 c8ßîÈýzñ‰s¸7Ä=!êu†»÷Á‘ÁŸ/ÑÁÁÇÔpltÿ-ü°6ï“¶;ñ’jØcRš+¯?(6:~Ûwï±õóÏÐðb@sŒcæFäü¶ãɇG”=(s\ ´€œ’§ÏùðbÒõÔHõÆÄQóã*ÖØÆ„ 0‚⦡w$œ‘’Gq¸îx)iÛá*ß'#c¶q·—”º¾$Ã’“F¨ãÙ¬·—èŸ. XAÆãa¶qßðá*˜ßá© ¬àç¿—|Z|mß'·ë9(¬åL ’ŽÇø…Öœm·ÓËò<,”àyg;üòß…”ÅàÒ†.ae‡'±Û|÷ôô=¸TBq¸;}Øúg…^0ˤSt(!òÇó>{ãðˆ¦7߆x 1¤N¬5ãˆ{ùýÿì?YáAÛË?™?.®'³ >1ß¿o—aéõí¿˜>_†<öü±Äéè»®ÏÛá0 þŸ‘í°ü8ç¶ÀßËù>%ü€Æ#ÍAøŽ¼@;z÷㯸ÆûùmççÄ¿¼@ݯØÇÀßôó=Ï—{œ¸Ÿöýg‹¾"ÊÏ_Ÿ€}?!ÛÓ¾ü&`#Ëå±=ûùþ·à‚8Ô@Ý«`5ïÙòØ,ŽÜ$a/®üã„ ßI Ï|»÷üÇ´?.þXÎ1ü»ðÔ­Ûxø€R\S²h>YÇßøƒ÷ð‹Aœíå¾Ä~\0LÃ\hLÁBøÂˆÇ³ÓŒ$ÏÂ6ùzð´ë¾Ü<þgÇLJ%f•p`¦÷üûñÎ|äOŒGÆ4À<ÆßŽ=@ÇbxïÝÎÇúcmãÇÕRi\ùp›a•3ZrwÀïæóÆN;þ|° Ú•M²Z¬é–“OÔN´ËEdoBÐN.UÄEe¥=–¹«Î9=©9M¢éÇ>9éí OO¹Ýc†ž×xÑ ª¹›z©Jù#ðªmufëF¬ƒ ¥cPŠXF8ú­ýš¼¬öÎå'"-œ½öʾèÍMyÑôÔN\Ýl¢á©5T>Y#°kê©ì‘ÓW\-â JzÚZúÆš‹¢š¥Ué#ž£õgð_fí NÖ¶í‹ÔŽ™’ñ,TÑYR”Õê%­Ëæ§ü›ü]·ìùVȵKPÛ%Ì Ãl´,¨¨³}ëA$ASŠqä1Û^Z~ÛG˜ú2{ž?P)L5Â?<‚Mq=Û „§ÿ·úyöû¿ ZUÿŒdöóØñJjÃ0¯á­ðdTÿpÛlÛÀ~³ÁÑSo‚ûv/Ëçÿ9–ºãÏÂ4ËN)ENØÉÇË}üÿøprSü±Ø ±çýxĹ˜e£—”9#±õÉì{vùpjAÒ3¶Ç| yyzmŽ1LX4ßP’HzAQE¾ïåþçîáÁ)Á#oÈ‘÷}ücZλ0‡¥8eíÇL>äúžøý> ŽÛc#ËòãŸ2i&5!6µ¡GNO–~á‘éô¸*( lÆ1ß½~œeRÅkZzF”$÷·¦p|tÁ{sæqÿ“ß‚–œí·¦ÿvý¼ûþ`cèFøù}8ÃÁÿnãÈwíÁ qˆÃâ0gÈýq¾~ïžxÀÃŒíýwE1h«£ ¡&‡¾Ý÷íýGnh;í¿§¡Ïž~§ñà‚ð€(Áµ®ØA¡ù|ˆ×<"ÐcËÏéßçžÛpÀ¬ã_(¦hIòÎÄ#ôá§Ïa¦=|½xrV9pÖ0¢—á¼Ó>^§ñòàV§òé;!øpг RX¶ÿˆéÏqÜŸ®Xüø©ÎÞy>~½òxrWMp„”î?SôãÔŸ—½8ÉÇcÿ’1å¶xzffú§âRoÄðvÛ}·ÉüOë<ôûçæ<»ãŸûñ¡3ÚÕa*FñªyÀRS¹[,¿×€ä¦ÎøÎøÛÓyóáéšIëB‘»MËo¯a¶þž\$=öÁÀß¶Ç¿oׯ·b3øð„— a˜W')ù9ÃzEo=ÿ,wÐQN7ùò$úüxÈALã?RF8úíì£æLMF]›µNÈY Ø}qòóóáuƒ¶@=»ý?žãƒ /»?/ÌE–°…dT‚šgHâŠ7–I\ª"$j]Ý݈ ¡A$Ÿ!ž>}9Á¬¤×üÅÕú²GsâõU-å µ@Â’ÕïáÛ©éWç‚F;ŽÜš‘-ñ S¤âsŽÞÂ@é§L`.$æA>Qç;ªêu>¼‹NP¥M?jéWK;Ð ûŸ…WT$«z`•(–ÙÒqÕüf ŽçZõ72-:F tÞ©Ž¾óIAKt¨½NME%%-=}q¼PÅÁWz-?tu³…c‘ð3|Ü v¦Ñ·(^˜¹ª—/wQUÈ€8’r·J™sdìÝœƒŒ´Ìšx/®L/Tfgu¨ª ¢¦Žç®nwJ‹– ñ#‚†ÙÝ/1TÉ^÷«²² Eª3t»ÓErf[d®IŽUsmzŽíQKOq§žCOf¤”Ûª tô0º$T•Ô¤øOìU!3,HQÇM®l™³ et·MI|ÐRKäÝ!íhÑ6Ήˆ–‚²ŠQ›PZ¿åî'œH(-•÷=)5ªÜïu¾Aª× q\ç•îs¹—h)êÑݺA5C¾ò; u>•¡—WésîÛV•³ÕWÆÒÁE§¨4,´:^Ž‘–1ï²¥M+Qø–1=Rô‡üU,) JÀëNÂ/À¯ÌRúæ`½ÕU<›ÄáM;Iri4¦¡Ö5³MfÓ¹¯w›Ìh"¼ê–Š: X$“ M§j­2ôD¸G 'ÝU¥¼ÄæDkÞ¤zKL2!ËÛ-ŠÏ¨§,E•tTVÚzj £þïu•«îu52È“DéÐ2Ü8,Ê’¹wB”² jz¨Pñ)q(Y”W:Yr”J R“è[´Ä&ŠÓ|©¹éª»ÌÕW6ÑZhܪ/—IÝcÖ^áoIk%=µ5UâÙTÀŠ+PøUTp­9Òún»Ci:äê ÷½½Â•,ÞóR´µ7Ø35|¶ë][À¬¥&ñ™Ë"²pk²–¢MR—?èÝW†D¥î,FáÚ"'6¡Ô·kN¿º×\ª¤³Ýk¡ÓÚnΊ"¤‰n·›­ÌÇ(¢¢uŠßOˆáä YÐCŽ&”|·©–‹AièÖ’ŽÇb·Ç_w"ÐË5ËSO-ú¶‘i3ÖjÒÍ5zBû¶ øHàe ­%J5PJK°_òHox²«…)ª’üh:˜“rêªÇÌ-_‡GGx­ÖR´òþûõ!-5·9j ‚’Ë%'5P[ÅiñUŠÒ’á¶•i¿bžrkA5ã˜=;£¬Õ79j«îµM[{Ô÷õ»W¥#\2³O"ÊsY$3勘›9.²l»VÕ˜ÒÊk:A+YvêqªŽy„Ú¶•›g$BÁ˜¶Jû”Á4¦.O™h‘s¿ØŠ[| QË; ÓSЍ£¼[¬ñFu…,TtÑC-Ö–Î"Ôvç%%˜Ó¿¾RІ–h)æ¬ãÐNz{.sÿY{û&±Öw.jÙ9G á­¼éí]z¦»k_Í'Ó•6‹M¢cs E¦¥¶SÃl©žª[q•ä¢AI+ø%úºß3ékNųÛJ§É¶ZVµ%Ö„ªQJù­iB¬àR‡ë¿Eì¹?XÉÛ–›´Ùçìû4¥„%D!kLä*`mê—-lœ/5¬3~üÕ1~Òˆyu¤õµÆ×É~^Ù´.u•ŠÙ]FŸ¾è¯g oÔº’†ûoê’8šŸPé{êR:˜„ò¢¸Ž¦A/§ß³‚ùÉÎxj.w{Pr£B^´ sô‹WÙor Å?2móê=C¯ª-3¡)=¶­u”¨2Æ"Y¦ë™©éäw‰~Yõ™v}’‹D‚™H™a²~¨3³mS°ªRòD€ ÄŠo°ý)j•jÛ ³Ú’©Ó¥m q²(ž¬©6ij–P3º£ivÁÃÑ„[´kÚ"éìåÉ]=z³èý;Ì mÌ;.‚¹h­SKj¿é{µ¢ûS¨©eDWév¦¡‚$vŽtY*ãñ š2Ñ7˜ÜÕå.š°jýmÍ- Ì;¯<©öTæg(/ZJÇNçRr£^èN]iÎGÜéªèé©ÚF¡:å®QÕHªVC4€½,k0ÁôºMŠÇ&}ÕL—¶M¢Ï3ú$¥"ZS4äŒÅKQ%…+”oú²bmöÛUJD©»Yí2³™=Jé©#3q)“ZR(>[Uû[[ížÈËöLšüÌö—åý.¢Öº¼ÙìWe=ÛG]o³rÏGÛ5DÓ·ïý9M¥4h¶Ö%Q0ÅmÖ‘ žH~Þ}u‡1¹‘Éý¬¹³Ê›÷%y‹w³Áý¬åµþëe½Ë`¼SƒOW%¶çe¸ÔŠ›%KÆj)=ðÅqŽ*…Šºš6y?\ÿåm)+Ú$YT”‰ö¤¥A„±rj“$©»(&UÔý·,#ò'ñ†fΟ2À´ZS3h®ÏdRÒK¬©R%™å[Š¦Þ˜IûЉ&/M/LgÓ¸îváT§Æç'Ðvóßïÿž?B©[†?ðÐwÆšRSúãõŒzðZÀ _é_Ÿ–­åž4KI GÖ\p|±Ÿ–~™Àõý Žß ìÌyq‰kðֹƔˆ68FÛoéØn;‘÷þ\8GO¶OççÆ)‹ì}xÆ„plp|½vþG‡~ J–Aï·©üøÄ¹„UõHÒ¯ˆ*:PHÎÀG}±ëéÁñÁŒm.ß<öóãÙ¯M5ø‡ËI$^šÓÁ±Óü¾¾}Ž;烣¦ß=»y ~_¬ñ…k;ëØŸ<?Ënûç¾Ã×¶AàÄ€o¶}r;¯®üc\ÎèÔ„Ðo?RAœg}ßO>ü°vØwþŸ‡ÏŒ«^êƹCœà”ƒÏÏo»Ë·—$>£úçÔþ½xÎUuHrRõÁ¾ „ƒ8Ï}ÇÞ3žXücÈL}8Z— &¢ŒÆ·Á 01úôÀ;÷áuƒ—ÝÛç÷¥6'0!UƒÐþ]ÇÔöáQ¯cøçë˜à Æè°ãlLý=~üðªÀ}ÿóì8Y˜z¤0"¡õ„*!þ¾}¿.ü( ØcÏÏéçßn|òƒ?ÈAëóé·×o—<ûÿ¹Ç§Óòâ_5pï%ËöFB¾qøž;ðFsŽý¼»vúð/pë²:0¿ïúqÑ„ycñ#‹¼F» XîŽ~½Oõã£}?/žG,îx4  Œ|??»=ÿÛùñ‰‡å¶ã·m÷í÷ðA{âFgoŸŸ¯l~<&aÏùwùAÿŽ +|(`. e¼ðN{cïßïá6‹c¶?1ë÷öà‚Ý‹»Eä5Ûñ ˜~ƒ×Ë}ÿß„šçŸ¬×ãÃ÷œ5ïRÚׄ `ÜíùgÓñïÂf y~9×õžyû`Zh6ôôÛùàð‹Aòûüˆï»w<Tp0²žÍA ;ì˜ýûpƒS“·åéó߆‰›è@”äF?;ÁÜzýÞ‡ïåùp#À3Œ€Þƒ¹Ï¨Çë<5*ËwÄ( eH©ÉÎÄäþCÜ¿IÇ äzmœ>ï/LJ¥mve¶4vÀoÃëŒdcîà9 ÛqúþžYúpôÌÀâ!E8ƒ˜€žŸçëŸ=ß°ÉàI Ÿ=öÁÇ¡íúhJÍ3„©9€ÃñINÝG :1œùçú=øJ}ŽFݶîsòÇDÆ»y—<þîíþ¼|°?.9Ãz^']°»¿ã×th?»¶=ñ‚ùýoÇ^àãlœmœùœNÿ‡fºá-9o éñ GGo§lùc~XÆß!ç¿lö> ëƒVag´Ö®:’šÊã ¾ÂíBºfÚÀ„cU~or™£|ü2GmjùÎA¦È9|õë}]jÒ”VÜ'8e™by°HÇÅ4¥²RªC1ø˜?ê;d»<ÅÌY %c›¿‘XnQôü…MA ôÅØ.ùV<ªæ/8*u]ëRÚ´jMÓïSÜ.7:L­]~££ÔUÐSÐRIS¦›û>´êýXŽ9ÑTîu“Þl6ŠU²IïõWúê6¼Ñ†”•VZº‰/töêi¡>û4Ô–kÜæpHñïl±+u‰Oí3LÅ™¦Œ Ð2r+Ï3ÄÖ>¹f—vZºêYKžW@OÀçj©íbã[5êñdªÔv«UñîvXåÕöûÍd•U·ªÊç§WŽž¦ •uBÆÁÉaMK@0Ûv¤£ºØíÚr†²–à¯YD¦˜Á$Ë,’K4ï(éë ó¼ÐÝC$ Ï~t›b"l…_œ B™Ö’K¡J@ñó¬¥Sdªø(’ĆƄ;Á.ø5"et¤ºþô·Ù,éï4ºzíx’ÛD‹%uÂÿàiÛ5P,¿ÁV ôª)ÌŒGÃ*mIjÓÑËÛ}ú®ã«4Ö—¼Údy’‚ë0®š²jª˜þª?Þ·JZê˜S!”D®èðùG¢IÎ÷T›€…wS¾3©7Ä´ŒIJ‹éS‚xy±ÊyWKI¬N®ºêúšš_s¿×SÙÙü*;}ŽÉo®–Ý)D1Ô\§ššR1H,IÓc§m— EåbÕõœÅÕ²Üêém3¨µ['£¨zd[•tr=×^ä•Q)¼"½(ÍÄê‰ve¨Þ›7ò’€žëË~ fMNÑu©û™ÔOjRy¼Bnw»î¨Óz’ \²[5n±[f³ÓÀ©=O__ü8†j$zÛ¥¡C±fQIИQÒ&5:f;×Ut¨¤³ék†-d¬fyª– ¦ÓÜiéb¼3J·Aa×#É•B¨- Ÿæ-LRŸƒß÷0.€ûËv”ã–}Ú/ÐÚ&åÍ“––ßyª¥*’çˆÍYF/w(-¾È’µ%¸KV!œˆ—`êj%½s ˜ZõëfšŽËE|¦²RµI’j.¦=;n’š™Ÿ·¸Õ9êEŒ;ïÄ**MÑD¥eCVX1éÕºª¦ ÿ¼ ÀwÙOe UËžE½Ë]ó6 [OS--uMšÃ¥4ÔWS¨k<())ã„\kè¨íI Îæ$ž²©YVezx*˜x;›´§ž71Ylä/-<š´¤j‰©n1ÁÌhÏWExõêÚ–í7/Úd’Óh£¬™•.ìÜt¶çlý˜6}‘=Ù•™0äàNãRäòΙ²%ÛöŠmöƒÒK”B7q&”|†9ÆÛ{,~ÓŽ\óжӠý±h¡å‡6åö«´ÖÓòG¥5ekøqPÃÏM§¨³o»IR±£j=JÎìáî¶J§3Ý×:ž÷ûQn•pó"­ôf²³Pkº 5©éïZ7VižFÛi.ÃW= L´—ËkUè4K{ãÉ…j¿Ï>«”¥³&.Ó,ZWb³Îp^êVг‚… ±Ä$â{ô|ù›7mÙ‰ê²É¶Z$™ŒJAMë³f‰Š‚”01³|˜Ôœ¥öæ¾ó{™žÏœµnYsâåȾki~dYoµ2QéjÝqÌ)¬Ö?} ºÑÀ±ÔWÜ,Rkª4¥¨i£C[ VMégìÆåE_*=’ô¥žñoýÕ¨o:§]_5 T2npêZí4¦¦‘ãŸû†œ éxÙÑ”)F+Òxüïõí[;gZv¾ÑÓÛ¬³,‰+ÉRR‰ÆOhA¨$TL~£úV]“iíK/Ô[:Ïúmm‘kReæ‰ê›fééý*S„Π "íÕCÉÞhóWÙ¿’z§Z\mÔ ×Ú3™CEÇFÓZu¾•Ÿ[Ztþ°‚®sH«é,TWzÈ:¥Gð¨j:b ¦!ÕßöUkÞtM`æ~¸çö‹Ñ7}9­íKp·Ýtþ²Ÿ˜|Å×–»˜ =úÉ_Cn²@µt²§‰æ)égBѸé}//õ;);"ÛüŸÖ‰bMÕ2×"e²WM0‰ IÎÀSêõ~“m+nXx°ªh´^„ZeØÊdËVô© |H©¨%£j½‘}»4ÏìÝöÅþÂsBÂ/”æ¿+y]j¸ê-<Õ÷mIÉûÕE®*‹Ï»ÚéYšó¤èuìúšËXƒ÷ŠQ%=] Õ@´7´ÛÂÕ¨¬¶Ad¸ÐÞ,·Ûe æÏw¶Îµ6û¥¦çMm¶áG:±SÍG<2¡ÎzeÁÁÏ®ÿƒ;nÓmÙˆ²ªMÙ&\ÉêS7ó ÙiRBp£5ïR‘ùøµ±lû?kÏ›*uå&b$¥/yå„%EY޳ááiÇú~¸ÎsèqÛÏðáANA;~þ½¼øûiVf>D”TWTù‚RŸq¶ÀúöÛåßÿo²óïëŽçm¸Ç2f;†îÍcR H;?>Þ~»þ\”ùéØ`cå±ÈÏ~übR÷˜Ð„¾_ŠA±S`±‚p3“¹ïòòþ¼ÁÆü|¼ÿ1L™\_Ö4¤Po0ZCœavõì>¸ôàèéð;|ö?ON1M˜ÂºüÃå¥Î¸A±ÓƒŒ ï»ŸÀðjS÷ýÞxß׌+^øØ„aJLàèéö_O_¯—Ìðtp|‰ÀƦÿüqs1¯ÌiB*5»Â ŽœÛlã¶vÈíúó1!Æø'ôF3øq‘swÏâ4!nM¤'=¿,vÉ#c~ X;zþ¼‡T¦8¹)HÖ¹éáu„äd~_p;ðJSä ¾~ž}ñŸÖ8J•Ý È!`ÛüôòíÂË<¿—â>fvA¥¼.±c;wÛ8Æ=_.X§nûoäw'Ï…©|\þ Â@ÇY`Ûp{äÎÛƒøp§Ûùgóóß…^Vü €áŒ*±co®1¹þ_!¢ÛùŸåý?>–l¡©Ccâ3äù ©þ½øU`Û™ü³ä?[p%x6°‚mõ¨§„÷ô¿Žü2ù`gå¿x“SH¶Ýx9ÆÞ~§õÿž8`>xóœýÄþ_í"7ëÝþ›~]‡§ÓðãžïúÛè<½3Á^íЊ èÀõúy}ØãÁØ÷ý=ÿ> VpˆÂ10cÓ~Ù;úã\`a#;Žç¿ë·L_Í⮌ëø,Aûûéž00ùôÿ1÷}xcO|Å\R0ðvì.0öóôú. [8ŒX»Bf;þžƒô?hË~ÿøà‚”3x’„Œ,üð}8M¡ù ¼»} ƒ;4 F»!Èmò#ù}ß ¦ßŸ‘úpä¯yq )4qÄ$Ôøî3ø~;ð‰ƒ=‡×cþÜ0,bíA®þø©¼ð>¸þƒ;p3ÒŒõtŽ®ÙÀû‡çÃÎp²yþ5Zó^ŸÛ¾ý‡ôúð#Óç#¾ùóïòí±á¨_âR |p€¤§òƨï¾ÝÁïþùà))ˆî?/»8>_ïÃÓ3Ö•#Ú§œ, }¬-üýOÔpz¦?Ûˇ¦agvЄ©$Â’ûvÆ6ôýx2F6óòïýxЕ¸wg„)5¦°ýÜúÀ¿àïð?ñBã@}ßÏ>äãcŽþ{ñ×»AÆAó¸õ;ñ÷ÌR>LE0Ð…ã¦oL<œ÷8Û¿¬$‡}ò§|víøðWªxùŶ-­ò?ö£óÂÑËûnˆÑ“ÖÄ•-Nª«§šVHSß'm?bªª €‘xËy@2šUÁE×囼ì½óZ²±)gš .”ñUܧ©È¶ªª[%L¶¨ E}¦Œ ëi#TºÅþ´ÚfnÑ´X垪ÿÝ ÈŽw£ê?GØJl’-*ÍÈ|ÝTôðßC*Zi©í3¼TµWŠås­a W±Ü:m—ºÙ×&×mª¹[túø*Íâ Ó»õ;Ç*ª+*?uè{¾©á¥ £¶ÕÕC©®Ï-Ee²jiKQSTi$ŒÙ¹¹!êdd>rĹkRÐF?Ò–òÄ¿.íä%SgJBj¢±A™ÀÙŒwv—ŠîçC¾®ïK¾ßu,u7¢ÆžVke#ÅZ!F‹©Ë4•I4y#¥bl`޵Ã=Ž #Q©ë¯7Äñ.´´³Ûªõ$Ï Jª´µ‘L}]ÕeDðÃn*Øm÷JÝ É,·ÅË[j·@Ï-uRÚtí9†š–1Ó{Õ⼪•ØÁ Q+dÉEàä:^,─oê!.øSúyEÙE¦c±^îZº¦áEIjÑb²†ÏD15l±X­+§á¯JdV1@·s£êvyF:ÆkÚ­gfµhE»râÖïQY© UZ‚'f»=¦…ZZÑu„ UuCžâDz£`šÈB:½iŠ Xà ’žúH×^=QpßïzøFæèeúîyrŠÕ©5®¦’É]ïø¾‚5Ží$ænw(b…d‚š3ûÈÓåšN–  ar£;áÈ¿ÙÓ£)Jé‹‚}MU¨ì—+ÛM«½Öëª5®ÛL¶·MéÛ£ÃQw¦¤YãjŠ‹EiÁyÚTHÄËÝ‘±ìrìjÚ;Jhyé)$/€£š‹aA‰áç-;jÔ»rvvͳ©BI%j½N±HzÃy¨hgìoån­©æ.›ÔF·Lèß~Õ— {K_m~†®ô^Ç©kÇ®§F¤U•ŽjbX++år‹®¼³Ô:G™Z‚ÿÌ>U­Â“V©(¯¶;¡xÖß©/RÑÐS7Š]UÖ¦š¦ì ‘T*:Æ ÷wëÆÛlbÍi™g-2P*)&ÚvÇ­ÙÖÿÖYåZÔž‘\]*dœ|GÅ!4š‹VrÏÚöÏiª¼h]Wª¹Ù¡žjë}eMšýo§å½ Þûnj ÈdŽxgKΡ´Ì’ÂÁ¿„²© ãìÙRýj¦ä‡*4»Ü}îçbÐRÛtªž_ª¾ïOf£[½}\ŒÄÉU=ÈÕM#’ó1'$ññâŽÉRl’mRe…*tûëPØH–„$–v H9;ãô/ðlƒmŸcŸ0¡2,è•-$ÑÌåÌZ€ÁÉ ‰V‚<·öåÓÚúÑí—ª¹Ý[f®µiÎ\{sF§–z¹ê!Km^£‡J_4Ý:ÓVÅ86úú=qÍ+fbÇ9f†hIb'Né9ƒjç?³7%ùcí{Õº»žüø×:‚¿“Üɾø)«´$º3•ú3Nk(h:$«£»Éý£¦{”±ÔËôÏSP^Y$©^>ÇL©»3aíS2ÑayaD·VWOiµË" ‹®C;À¼v¶Ê¦ÊÚ¿PlËqR,›@Ú¦Ý`W=vk-Šk B ˜ºH.ÍÂþÄpòZþsò³PPXoþÒº[œšæçûŠ÷£ìõ\ä¥Ó‘ÿgì >Ô× VmS¤-Ï`¬5ÐQ+íÇ®áU@´”ú)æ—;9_É[]Ó™¢—O‹’LÖ›gƒUq½Ýå§E3Em´[ šz’­,JòÆÒ¯‹*)êãö'ðãm؇ÒÉ% ³K±•))+¥.‚ĨòQ`L~<úóe[“õå•®Ó2y)HR‰)è€LÀ^‰PUsHzE¦½¾½—õ%Ë÷bkz›;´ÆªïVjê{t²4ÑÀ½U´‹:Ò©’]Ú cÆFM³¹ÖÙintT— )R¢’¶ž*Šy£*Ë$3"ºTã=$l3ƒ·qǸ²í‹¼­i·¦ ]=U1 .ÙŽ°‡Ï”xûNεØÒ•Ï”ÒÔH¼ ¦ð88ÀõIt9-6;ƒ·˜~ßíÁ)OÛmû¾~[úðåÌ¥;»¡ I'v„BŸ§áùðlp‘Øl?<~¿.1LXÞíœ÷ÁÑÀmõÁòïÁ±Ó÷È'l÷gcÆ “qá‡c¬ ´¦Îïæ07ù}x:8wÆ<¶Û`Ûïóã׿/ˆÖ„CA©O¿Â3ŽAyöàÔ§ü»—ϾOŸ0š¿¦èÒ”`°ƒR³Øcqó/Ö868nÞ¤öûÿ_Ö³Ae§¬ Äˆ0vÛožÞ]±ÁKóÔç×åߌªSg_ÄiH}r‚’Ã>_ÔùðRB1¶ÿ_3÷qjhrC±`}’@ï·Ì_çÁ @>^ž€yl>¼gRͰà0,?!ü½6Û‚.ÀvùŒþ|$¨T“MÚÊ|»`öõùžXq¿–ý·û¸Áž g ¬ÿWá“úÛŒÅ?lƒßçñùmÀUźXË$y öÆ6û¸Ya>Ïlyn;ðwų<("óžCùýÿË…^X?—üA3¶Gñˆ¾@~×ëÆB?Ãä;n3Àá­k²Â{¸Ç~¿NØÏÝÇ<1¾3åùýß..øâbî‚ÌÞ<#ž×Ïòïåôãž¡?†x—Ç(¦qïáœuáÐü¨Ç‡Ëÿµ]ôïŠlÎ10ƒä»vî?ãÞ>[ãîÇxbñ.šR1ðqåÜàì7ùmç±ãì@Ïb7wJÅ4&`ù"~¼$aŒOŸßÁÑP™ƒnÛŸ§ßÛïá3þƒ~Þ¾„ccÁN°×â!œ&Ðc;ƒçØùÀáGlŽàý;íçúòà‚ƒcP‘ƒ¾ß~ǵ8íüö?/.ßïÁ¥[  7W»‡I©»ùïÛ­¶üøE©ñåø—ÈðÀ³žp PŒ>!§ísùÿM¸éýG‘ÏòßðáÉ^”–Êzqƒ°õÛËòúp”ýð>¿-Éýc†¥[‹QKç<þ~Žøà)!#b2 ÆÛ…ò߆¥{é Ri]aIL¬@tÓm»ý=—M‚£|¶ÀŒyŸ.Üÿ^Æ6íåœpA\ˆ€Íãáëö©óªãΟloÂןtåþÔíË›]M:™¢zm&ö­7]< ʦ›˜¶k½Z"žˆâº ä~Ž–_4f•ë!Š©àýÓe¡‘ªà·Æë4õ1=²K•4ÒýëtûeRK,PÃ{Âã?ç]«4Úv•ºyPy³V²ÂTàs!©tØÒD›a–Ì)ßÔBozÃe<Íq§·‡jm+¥Å¥gø’)¢‚à÷;t÷8ã$Ý.‰Ó£øiÔV©ÂFª[ wÝKp©MBúré(êéj¬õ•Ð-UÞo b²É#…ꢀÙ4}Á–8ØÖ$ffvpíJI’¤ÌÂe1Ê€›åã›'  =ÐIjÖ…ûƒ÷D*n[馻I§dHªmz~Ùmlë[3{Åúä±=mTr¥R´ž ¢‘C2¢2÷È,Õ£¨ýº²í4;K[Wp¸Í4´t~åõVÚˆ¬ÉWVµðÛT’X*NøBÝNÑ&D¤ÙU,²f()ú¨RRFÆð_t ©³&*Ò•=Ô„0)o¹ ¸ÌâdCcX¶´M¢Gv®Ðš=v]9ClÖ•Ì)îðÜ54’jU+S‘i¦Š¡«MI*òH’Lx$´RHTêÊûåT’ˆ-÷UA —;´Ž³Vé= ¤‹À•Ô½|Õ_¼b Œ‰%·1-ð6'FJe­T—Ö¿Ònšoe‰X )ÔÉ'ýâ>ÒLO¯ÜظÝaåÍ‚ÉJ¦µæ¢à/VïmóûµšƒP_è©ÈY&‘(ijቧÙZÜì±ôZŽj;ž©¶Ý'W®¸Vó]”Jf’zµ¡´Ù„“N±FŽڋß5!gÇJJ ìx«U¡IV!’+’“ÚÀúÄ”„ÊMÑGR”k½wÏ}x`Ñ9½ÐÙôä:·X_î1Ehºû–ž£·[Þn´v{ˆÑ;Ä£û»Ïj²xQ²Ffu zF‹XUPkaÒê{6™6uâð•pûÍÖšÙ^«ª£ie•Ò%¦Vvø¤£¢EéÏT€MTHîQ'¿yáHë}©âH î÷Ä&ÕG,C˜:žI¦¬¸kÕ›MS¡‘ê%ÇQU|¸EYÏInøFÆ01Ž%ÇB]nT:6ÍB°Yé­6ä«­zþ“,7KímEHÝBÿ¤SûÂÝ?åRK qWJNê\ó]ÿ#*¢jǽ’”Åíª½º9¯Ë%IÊþUÜ´W*VÏûÇÞ5]&›«Ô͹½}UM@¯¤¾ê«ƒJ‚x4¶z**¸ã éiEênxÁ©l\ì¹ëþ`lknP^¬Õ»jOM¨êo”¢:ÊjËn¶¬¨¥â'éu誑ԸòE¶Ûh¶]éU*@ JGÚ”†H¦ó™ßÉc‘g¿1›<•)G¢\×p«phö–´ œ¼óä—6t'´G/­zó_Û4E6žçƪLëËô·—’–_2l–ÛDôèš‚–à¢ò‘[ï”2Ü*/™G”érÓ|Ö·½5=ÂÏw¾ó;MÚé«íRÉO[o¦Ó4× ÜÕž%9VHzª5•†®hÕÄä*TÄ€¥^(d§x¤·,|²(”‰S&))»ÒK`Tà x˜¹ium“RiîRòû™vû•÷^s!ÔöýMG0ÃOu¹j‘§©ãMJ±¬0Íg´ÄÎÊþ(Óá{M 9“¨4<°Ëm­•©a}Ý¥lt Á 21…^ƒ·Í«³¤m+,Û%¡¥Ìt‡Äq¹£µ²v¥£dÛ¤[l‹(\’ ©ëCƒ½õ‘GÒ¾Û´ö­_íc®} m×®zòv£ZÑrçOò¦ºåO==§OsS%f©—JµZ0‚hm|°µ\"¦Yéâ–õ’¨çšJ®ùߣ¤å½/±Ç´W*VßUÊ®^i¨îV›%S›¦¦åýÆá©õ¿>4Ÿöê&“Á¨ªÒº¢ßNTÒ‚iü˧¯KÛ‡ný?kµËA›·vBE¤ÌQs6I¶ËR$âzË‹K lãÞÙ—û/}’oZ3“>Ö¼ÅÒº÷RûHêk.–ç-&´»sXÚ-Ôw;ÈKžœÔzmô]]¦®FQÉPµrUÌõ-,²u«ìÍû]ä£ÖÜò´éiæ­»Qim§(ktÜ“ìÐ]î7 Ö¡†äô/)J»£RWÚã55H† ™ ’ 7蟧¬Û*ÏôEŽ]ŽÏÑÍZdIš U)$cDŒ@f Î?:íËnÔµ}_i›iœ o͘‚K ŠIZ†.²q'2í”y³ÉÝ;q©æ ŠÇÔ´z³RØc¹:Ûí2T˜ä»QD²ÃM%š¢N„¼ÂåcD¥šIT#ý‘rfÃ=§@ÛVzƒRnU×»ìq·Š=Æåê¾ç¬,Ñ£¯ºÅR°¨ân¨X¼06aDý;:÷Ö²ÒMÃ'fZí!V‹|´ŒN0ý½g»ô|Éàß6Œ„’~àSg´ª¦Ÿuò\Ų´Þ£æq¾Ý±úõà”¦ íòî˜ïøñõÍg­ót§‚’ ùdŸ—©>YýgƒŸ=×÷ÀÎwÆÿxÇ~1L™†ïƽaéI98ƒ’œý?!ê?§ÇÄ+³Õ»í÷ñ‰kq¹£ZÕßáªAÑÃŒl<óé¿ÏëÁ‰ÆÃóõœcõ¿¦,’r1©)%š ŠÛ??^ûã¿Åo‡¯,wî{q‘K|KÔ„8 ƒAÜz 8)iƒ.d‚ÛoŸ–ÿËŒª]I~´h µ®pZA€01¿—$†>ò7íŒúñJlMaéa$#ÈzwþƒÏƒ‚wùíŽÃÈ}xʵœj~ •‹n߇ßÜ¨à„„ÀÇþ>}·Ç*¡8˜xGpÃ^BAœm÷ùýþ™cýÎÙým‰'ðÀ7Bâ—Ï`nÝÇ~—æx¢w˜&4¤("úÿ 1ýxÉcù©þ| á»T÷‹`ú¦½áQ×ååÛŒ–-û¿üÇVí Æz¢#æ?ÜûýxPCõóîÛ€¼ùëM ͈‡Èdy¯n8a ¤p|ÆÞ{oõÏ&þ1‹o¶©ûÏŸˆ¾Mü¿Ÿxoˆfñß…ò>_Ÿ¯x__»õúÏÆø¸ëÁ‡×·Ÿ¯n:ðñòÆÛðúqoŠn]ÑшöûÆÿÓŒL?OÇñû¸ºÄ"01,»?ËŒ|,~?éÆþ_ç|UÞèLÃè>ð-øM£#o¸çõÛ‹ #\¢Šx?ìýãÉ~í¿§øYòÇßÿ<ñN0KW(ÀÁð~ñŸ×n1÷— ccåÁùE6¿1§éÏr~]·9ýmÂfœÿSë÷ï¾üÅB"pY\T•!€e8#¨yäŽzlnG¨Û\pAD0ÖQDe<ÈÇõùö?­øHÓðNÇéùðÔª´Ç^²†fÏâÇ*³Fé"«4`P¢ÁåŒw'ÏÏ>GQöàç¿ö~öfæ_6¹o¤mz¿Qi O菉_íúzÍhµ!asÔw)+§®ÔôP(¶Ò²Ö\_¢’¥2¦-«h›gÙ¶éò\Ùr”¤‚X8WÝ‹g†pë4„Z-y3ftRç-)*Ø bNèø Ö:†·Q]«5.¸šIž²®çpžÙ 1É_[Y$4šê¦6vꧤ©©hnrÎù–¦Ef@Ä9OMp®©§¯¼8Jƒ$æÙkZ z»µª;cTÓÒÒô°¶ÒMt±Zj KŽ™…ÑÆe‘Çž¦VI7˜¹|ÍxrºÊB%ËBD$0˜aÊÝxž¶{檸TÇn´Øí·J«WTRIMMK=ÚZØa¦HãëºÕ¥¾K>pÓôVù)éXÅT÷Š«nŠÒ5§KÀ×zÚ †¢zjJÛÆÁ§’–×ûÚ¦µTâ’Ý{• ‰—ã2¸~©›Í ¡.Ê©„ÿ1û`á,[ƒ·`Ž–ÎI]¥ݘR‚ Ô€àg‰òŠêåc»UPÝu'ö‚ªU¸µ:Q½-L5qÐN¶éfYÙ|HÞI)åbT•ø²~%–:©t½M‚ÃU¿UÙ­µ•è< ¶Š‹â¢?(+L-4Þ,ŒMb*ñáÆÊ$.@JÌΞRfqt¬®51~=éM£¦ `$¬¦…Ü$Žã‹òãÛEæ!KqÔ6yMÕµ%.³¿ËwµÊÛ,“ um %®IÒRõ‹ÔÓÑ€ƒÃi+\1Q‡‰éi.Ú›Uèú«ì«U[¦´5MÈÁBšœTjY¦¦¶SSÒÆ@%–ýB±ç©É¥ Y˜³ *–M8çw¶Âò”× s R{ÁcÁâÃæ´:>Ý­u5þßq¦ŠË¢ôÀ³QÙí~$·JÔ¹SÓÛo:… «˜<&k†¡­xúñÕ,„GÒµ¼:ª–÷¦©´zsLA¢êuEÒŠhÖ¦æ ûꊪ¥fðÞ¦J«OÓ—ÌŠ«'JŒ”Õ¡3¦‰Eþ©sD^ wR8ÒJT©új,¤_âºå¹G(¯-v¦·MX­t°T×UjÝYq¼×¢x“ºÐÑ+U$’·Kxp«™êo…CúqhVY©m3ëq}¹RÐÚ*¨Íº’šœ=Uu-šá[®:¦D‰Œg÷Û-<°ÌÂKî­­¢³ÓΑA˜ÑlÔÍ] ¦Ð«ŽÈS\(ÄŠ>Uv|üÛl«oUºD³-¤ Ì/%Âï}øÖÙSh ™ìµ&¿OÓ½žçMîPŠÛET³¼ÔVIåêiie¥P}?ñƒÔ_¯_gúÛÕvƒ§¤¾ÜêîõvšÛ¥¶•zR%}U-¦ïr°f®JH"¬“ÞìÕn'XWÄJ…,òœO/Ë´³¾³únP@QÚ²ír¢:×R„Nòå%èM@p{“,ßô‡ÔsŠî§e.É=(~©QZ¥ÎäÅUÀbhMÒ›Ùið=}6Û‚R˜ùŒvÆq·|ä>¬¹•'||Á ¨¥!SŒ|ýsØc‚iÔ·ÂF®?ÜîsøÊµgC›¸R#ƒ¶?—Ÿ¦ÞYേ°Àýz1-G<þ#ByÁi Œ`o¶ßÓ~ ŠÇq±Û'löû¸Æµ½phH-­Ð|pãËcïÿœðjAŸ/Çåóýwã"×^q¡),ºZCÛoöÿž HvÜzygÿŒÊSTÔÆ„¥¨N0BÄ{vüÉü8- ìHÇlãÏ×áߌË[œkøhzR3Î H†F|»mž XNÛn~D ³è>Gñá Ss‡¡-SœwB01ëÁ ù9Æã¶ß2?Xá$°0À X³ƒ–ñ?>X¶íø ýwõáE{ ÂG=?¨‡åùþ=¸Qa@ÿ//ŸËùð\kР‡¶{¿üãë‹òëŒmõ?>)ÙÞ€DfŒÄ>£ñ?Ð~·ã1¦;y ŸùâŠÀÕ"ã1ô$ý1éÿ? ¾@~g*âÚ÷ÄŒ¼?žNØÛõž;ðÏ©?wíÕ"Gb-»× ãžµøvúñ›'‰ð¾Gð?<}üuáŸáõý}ÜKÛÈ‘ÃÔ}Þ¾œsÃùŸÃõäøkw´HÄÇß±ž¾góã£È»#B$baù~gúöíùñ‡‡ç¾>ž\XYÜï1ðóßnøü¸LÂ<×?Ÿõà‚Á|‰‰~G—áŸËðãwÎ6?׋ kó:÷q¹Áõ;åõùqу¶Ø>›·óóàŸq¬QуnØ}ñ÷äq‹@|òA?=»~½x°³½Ä ÝkÞ™@¶ºZš Xü(ÚYg+’s$Í×!É>lOãÅq®ù»ÊÞZÑWWëw¥´Å%º©*¥»ß-´~E,t’þíX¥¨Ku’*Êv†•§•[)Û-éÞULAd¤ )è#ç_ÛöÍÜmUZ†—”Ú†“–ºŽÝòê+¥ªŠ¯˜”±M uÊš‡Þ+ ºÙ%mm,14Æ­HØMÒ<ç¿íöæVŠ­‹EsG[ÞmZºÍi©]KUSjŠëj¿þõŒÞª)4ý},÷¹!¯¢¡„Mv’¢QûÝE .©´I!!=¢ƒGÒ%¥,K^ïÈ9ôÃÞ6Oö(~ÓtUûch.PóSPÔòó›U5š:¢Î´BŠšžýs§žm1]AÌ#‚½µ"ÐÄÒ²»¼5óGœÉÔ>æžû~»ý ãQ–$¥òT¹c®1„1sI`Û˜3ëÊ’û|·ýmÀ/OßmÀûÎ?_—•¶mQJŠ@@7òùc·–Ü$?"|¶Øçn™˜ !ET@rCœþ×o#ÀRAœù_3õÿž•ðq¯HINíaW'#Ìÿÿû\s‡­ƒkÂÇth§Øÿ¯‘ßþ8PSü·ú ý1·~Ü}í+×t|fán:×d()ü±òþ}·íŽ<>ý¹Ýæ÷+ýžìö-+¥luœ¬æEÎ='ÌMOs¾R%z9÷@šNÑ¥RQWs’¶Ç§¯QV Ã =;Ó0/V'ÔÓçIØ–Ó (€•9fBÈJÈÞn’ÃSbÈ•?jX¥ÎUÔ ‰!ƒº’B’’ÙÏUN”5\µ ÅádŠzšIÌmK\P ª/ Þ*tus¼tÈ£>â½ER«­‰tÔW·¨¸Ý!µÉE $¢×IUª’}UJ*p¶ÎúfÔ)ß —X×8<|7­Rîíİ®¸ÇÚ$ˆ ÛƒxðC«Ò›Žžš²ª:­t—ªêŠdp°Ñ[4ÝŠµjî6ÕH‹OâPi •ÿy rS¤ˆ…MÚJ:‹¯öjÉQYgÓ–×-_p¯jk„q]hžzøv,káÍ=ʾà0ÌÉC¬™±ã´.Ý–&2’¢ F7€H6–ó¶°¥„&K’ t^$q M34ŠúY5zSÚì×;|T–ÊæÔô×V¬Ñ¼sTFÔæœ<%ƒ»c8 Or âoSpª¥§³S[ªM%·Në+´Ô–yz`ªJ¦m)f¥œS' ‚ vë 6Ñ2]¢LÕJ´*ôÙA…èHò#–žZ¤Ì–•ÈMÙsT£ƒuª ó#·³¼?§ù9M¥/òµ¢+õËHÙd©ŠŽ9®”ÓAÚå}µÐÄ#i!ž¯PhŽW£ª”³ä.Ãi+uÛ˜ViÍB,5Ô7émv}GKQFnW*-5m­š±æ©«Vžš›OGUVêAG$ˆÁÊ€â‘1råÉK,¥ŸóëÈBR Žštâè ¼_ÀG/ÝÌÅISk®ÔòkÚë5ÕÕú»YÁn§1Ž·[5‘+kgi¥v`S_gêw`…A9Æd—ÈôÝ€k Mw¸Ç[HëlÓrYlåf¸QÙb«Ž:E Õ¡–ªƒN:Æ@–n­²3P$¨ŒjÙš9ÿŸXÆ€ ŽÊn{ûÁÝXê=_p¤Ön˜¢¤°éŠ}òåK%:Í]MKŠ»RÁoy™µU}:Êʾ!‘Ûø‡Š¾†ÜÔúëQ$ÒÔÔk_MøÓ‰-†Žp°åزÇâ^ã!IÆ`cŠ ¬—Á7€ JbØÞ[Íý5„^2iÇÖ:eÒ‘i¬ŧ(*'“À ï4Vê{­Ââ`zÛß+*ð $õ«…yyZtýæ·Wh;õ-ç˜ö©¨/ðÇIGf¼Ái¹½|whâ4WZzŠú„klíàÕ‰#s ,Ðô¥ë)BÔGU@¬¤g@ã@!hÂix’[üDñçN®ÔœØö¢æ$êû¿8ù¯«zˆ"mI]]|6jz\5U%¾Ù ÍŽÕ(‚š*zh¾±…Ûˆå÷”üÇä^´³ÖÜiù‰Ê-SKWO|Ò•­÷›DÒKO4sPÞ´–¥²¿T2´F:ŠiŠVé,’) ˘')=2’¥"a ©NÄгàLl—Ñ&RI@ C†³èǦ¼èæ÷´Ÿ´ï³-`æÖ§£æF³ÑÑê‹…ÃWWZm6ms©¬7 (¨-k ­5%ïÂÔºù‡>×%ŒN#È:Ý+Y ¾ÍºB¦Z«eñ/™îÈÚ®’¾™õN»ªÓ5"¤ÄLrSic ¯ˆKª²ºtYë\sCZê:]}«b´X©oÚ7V۴媮‚–sSªmw íÆçj ­ŠI¶ Ì­Ê_¤ô*>|BWT¦`Q }P‘ç ºZŒÛ°þcìcCþÐ-síqìzªæo³‡7½µ}+rêÁz‡XèyIÊM}$ZšÍT.¼®æ6©³0»ÆÔöªšŠ‹EÒ¾K¥!d1U^!Jšú45>¦³xkMÖ–ž¥ãh’š*‰â ,–ÊÚblqœTa‡Gè)…vè^ŸO2mªÓ- ´JZ&¡ Á¨ ¨` ¾ç„y©RdY&Ì—.zU-k*MC€YÓJºH bÁœD×”TË~Öšv×O<Õ?½õ½²Ö–{X™jõ ª#‹OW$€Çyˆ ‰!ÔÆ (eú÷öy¦ëåå%O~­ºÜC«I?}^nz€Ê¦9åI =á‹8–Ff-â7ˆµ Ÿ_ýS([–vYà Ãpz·º’“/è/¬•š«"3¯ûD‚kÚFx‡j|­0ÎËÛcòÓíÁ+MñõØyúg¸þ\}sXkÆ>H„X[ÝCŒ¦?çÁѪvüÎOçä8Ì©ŒÖ4%CáH9)ñåßîûóùðbS¶ï/×Ï׌K][#ñ¥Ë'?ˆ6:p1‘éå¾x1 9¿ÿÏŒË^f4¥,+¤Óòþ`yç<Û·óõï¶xÊ¥65‡¥8) Ç‘9úý߯Ÿ$nÿ,oÛúq™k/LLhBsÖF H7Ûóõõû÷à¸é»|'?–3·–ÜeZ²Дç‹ÁkN íÃóÇ—ûpJB=ÈcñÛ…ŽpÐ’uÊH¦ÿLçO#ŽHG˜ïòÜçåäxIQ0iMŠÂëm±õóÏ}¿]ø Cê?¿ xµ¯ˆ8Yaï·åן@ßdç¹ý瀾yD…< >ï@¼f#`2~| ÄðŒÄ[çaôËŒ„c?ì7Ïn)øÅ¶êÆ^Ûc翈óþQÛ϶ç*V-·Ñ¾#/éóþŸ^;üüü‡ë~*ù ÖQ‰Žþ~~_®üwÐ=OTr#Ç„@ ެsÃóÉÇÓÏëÇ^õýcýøt©¬YIÉ>:×ç†}_¬qÃßõíÄ+1Wx4uáúc×è~\`cÿ·ðÿ§|R‘yn}šóŽŒXò#óýlxcÈþ¾¼P8 8GF<ú×ûÆ/—àß·ñ9Ç<ýþ¹—ø[výwñÄŠðŽx?!ëÜþ¯N9àü‡âx°HÂ$uàü¿>4›ÚŸÛ£“~Ë –­G4š›ZÕPË]K¤¬•öäšš$$#ê ¹&w±Á!¡šžf`:„}\ktZRTXGÌ?¶?íÜÖ“O_›Z×i+EÒŠ¯÷.å“ÀòÔP­ME²zŠ­a†Ó9®·ÖAPµ”IO2ÅGëSà¿5ý»µíÛœ6Ý#p¹GkÒ•÷ë\o0´— õÛMêE£«¦½Ô]ªÜû›=¦éZ{¼hñ; Êã'‚*zÉ8 Éï´Ñ'Ñ•¨}ɇ(ÓM%Y«æÝ×Jj‹•eÆé©Î«åÅÒ®åUQY<÷‹½%}ŽØõ55.Ìï§¹GQÈjEß±â%ÊÐÕ·]]£æF°Ñ:Ž×ršñeŠ=_a…Aí3ÞôÝ Ü{#Ìñ­¿§ ä !fŠ© P>!éÄØ›û4óéÊîqrߘŠŸtºé _`¿QN„f*›EΚºÖc ý:xýgt>§¶óCèíwfq%ŸZém?«-R+ݨ­T—z6>Öi«"ßȹ)B ¸ÿ•·ñŽz)>h9„‘ØàúyÃô´àžÙõ?‡ÓåÃt´Ùòçë‘ÿž4»XC|´ì<°;€=ÿ¯.’ÿŸžr}<öàÂÍ!jNpã9gñùcõ·¼XïúõáÉ™Åô5£ R×(Á¹ßóÿŽ9ÁßÓ|ÀÜÓüF,ÌcÇÏlgùp¨‡åžýÉÛO§} Ý(|1²Óí¸íÜwÛ?îxù#ý½\êçRócIòrñ¢i¬:ÕKý½å]ì_,×›¾¯ºtAa¸\RÁl©š[bûWCGr¤ò™êê5Ç1õ|ùéÙ%2’èš°•—Ä‚0$Þ¾;ÿLYåMÚòLÉ’´†=e Á%ËaHùÑyèôáYQ¢º]iëï4Ø­òÐ×Ó»3]ëåÒËœN 1£Q¢î*¤2Áa±Í&¢zº›•TÔu¢œT,µÕ0Y,Ò×QMRÒHL6÷¸hª‚z‡SGTc¾>BKªÃ5ãW ° W!¸‹9ç]?sÔU6kPðhPZf‘â@iìVYk¢µizÈéÙ“ +Ú,ú©Ô1’YG›6@ˆ\õ¦ ÑšÎËo­ŠãS¨µ-®¾éWOAq3AkŠ=# Ï ©ÌÆ<±ðcÏÀ8åÛÿ™6T’ œ¡TÎâ’ 8¸ ­HéØÿ“.lÝÉR+•ä”ÞàïÞ^dÖv½Q{¡¸EE¶ßmá’•æ•ÿ¼*² M4Mpù ~ÊŒ=ø•O{‚ÛQ%§J[Û‡Rh}-î´GX‘RÜ£žãp¤¤¥–GBÔ÷HVy^LõOP…•Ä`žŒÉê´Z&ϹѪj…+Õ  ¾”ðŒ¤‹<‰R‚ŠÂF'ÖÛ^ÑÎ%zçI½ ûAÜ!‰êj5 ÷>hÞiÕj%Z³ÕUQ["­i2,Õ¶*ù"ÁËvf`\´Eèò–Ù]j«¬€êZÝ/¬®ñ­,SÕGã\mš+ ÷î3‹M=$±ÉzÐ;7 ³M*zh3rB}# ZdÝE¸ÝDõ|@pŠÒ—VÝî5|°xHÛ¤‚ïºÚíæ&yìvËlÒGYV Ff¨§ÓJó2ñ +õ¼ßbš¿LÓAEK5UÃWëjÚúå†7•ÚšÓ %*TNOLB[µÀ–?ø‰9ϪÈ'0È?Fó õÓÈå÷ÿKéÎR{Nè»û:kXûWrÂ’‚ ÍK§¬«O&»ÑôÔÔðÁ ^±äÖ®‚ ŽS"¥jÑMJ¥ ”w):›Wklĉv H§J •%¼‰½‘l«ÌÚ]{z朩* %Ô »[qùÓöèÒµ¾ö®µéUÕÞ4•‚Ëý4ÔtwF·M%þ ‹­uþ÷y$ª§‡÷ÊŽ­§™^_¯ ›XsÈòÒñ¢`§¹hMq$¶i¤±¥¿HÆ×JØ«D$¦"’Üû#Íœl½\y,Ë,“y!J®dÀǯ‘1S%K+HJ”á°=Sχd^>ËÚ*ÉfÕÜÌÔZ{TÛõ§RRé›…Þ…à–45²ß¦­¡yé¦xåž7Ž›¨‚‡$+FŒâqí}z»Xy©ê¬W*Ë-ÞzÝ;OAt·UÉE]E*j }l’RÍŠÉ)‚ŠeøI=.Ç9áKeѯŽ9XwÚ€£>DF©Ùy‰m›]òÇ@êÝ/K_v°éM¯‡1Ü ºÚî+`ndjxkéâ€éÞ’²i:c=+$¤˜ŠÈ–_²0yQÈj¯g}eªµÖš®åú{MòÇ_ÿo/U•”º^š“JN×»­-a¶TÓËxO¡ãhéŽe©hKá蔴ʘ•LMä¡AMÀ-$Ö„ÍA\²n©@¥ù€^±õÛíÑí%|æÇ',ºjç¤á°Ûky‰iÕzoPÚoÔwí7ªô}M‹QÑÙ.V[õ±žR[¦‚ä’%}EMHe–6TdLJU ÕÒÈÞ)‰jtÛªÅOXñäIQ['T©±,$Ëž¿cRUdÛCl¶*Þƒ=_¼ (~tW|£ƒ`³&Ê´ËÞI Òµ8S*¸zW¾úö7ÐZº“›Z Uj-YlÓšƒšôÕ›ÕÂÖ±ÚïUšnëh¹×Ò-]Æ’e¬¸$êc$R5mAW‰ËÌH~>¿ùn÷nVé Ñxr œ†uþ >ñI¦lÔ“–ž°âHHz:OH _?Ù³Q?ø°D©½(³Y­OÕ$N”¤ðRTYA…[GÑ-Ò—gþm³6WD«U¦ÍuÀHWéæ¡A± H¼ á€w"ìZ—ßÛcË…Å?m·¾Ççž>ʵ·¡.{¡u¦í·ë}÷ÿn Jo—§Ý¾}xȵ“‰Õ2HFñ_Ä”à`‘“æþgƒœí¶ô;—áÆU-¸“œTÁqÓà?–=Ožß^ Ž ã#ïùþ½8Î¥bs‡¡-\ÌOëŒúpZSü¿Ÿëóã*—¸ÔÃ’—¬`öúd¯ßÁ)NN`7—ë~¥‡­t#B†µ®Ã£€6¯—,;c¿/Èvã:ˆÃ:yÀÂX>]þï¿ÏnXwØmç¶>ŸÏ„“™¤8‚„8À#s·òôù.X1åý>[𲡕Fè¸!`Ç‘þYü~\,ü¿_3õ<(©±1`²u¸Oá!”§VpÎä&Ýü³¾8$G韸~¼¸ åÎáñv€³øR˜Ç 9¿o‘Çüàñ؇]û`c¶{ñWλ>b6toÇËÃÿ·Ðùÿ_¯t7¦>{p/XUô# ž§ëüqß@ó?†ÜB_² ]Lwп?Ö_wô¯ ýmÅA18–Ž`zÖüwéÄŠ»¼“Àôùýþ¼uè?$]Ð ¹ŽqÇ0=?XÇòâD lÌuоŸ­ÿ_w1úïĉÖUô#¯çëÿN11Ÿ@súóâE0pá¹vvÆ>—Hý_^:ð÷û'·¡û¿_>-Û E6Atã¯Äs véþÏŽü?û}G—׈ç|Q~ýS⬩£·RÔ×Ü*ihh©!zŠºÊÙ⥤¦‚5ê’jЉÝR•A,Ì@dž<Ëö—ý­>ÈÞÎT7“XÑsûD®‚MÜ(éôêT¯WD5¾³4Õ=EN²;œ¹ØÅÁ‘MìÜâ °.ßóqíOû|yéÍ}Qÿ¦<³ž^][o©=»û!4–„¨{ͰW镬ԮæëuލÕÛ£™i¤´ÄñV·ðIP8ùíÖœýæ‡;tç2ÿ¶Zžª¶¦…lúªz7j*r†ô,—Z'HؽzÊú¦Ž¢SS$Ò1µ«3žÃåÊÁJ© ÃZ¬0%)` Kx¶¸åëª:îü¦Ó+,ÚoSj-7TCõɲïKA}²@@Þ>»ˆÕÎ:ˆÉ3Å]Ís%m—•¾',nºžÃ]$$ÛAÝkô¼4Í.7tÒÔzUÎùÅG¦8¤‰Û»áÒë$kÖqòÄë˜wJªm{m×4¼U:žÑ£ù‰ @ bõx¶Pܯm æUÅwBA½9ó…µMt:žRj[d=6ú]_i×6Šu8V±_%¡Õ¶ªpÍZ®4ñ‘‚$öã|²à Á¿åݪÇ:`,¬ŠÀ4äÿõy@7ëL:G™ŽÁK:¥%ŸSÖÒÑT·QV·Å\Ɔ¯)Õ˜ž‰á’UÁ|qúf~Æžn':¿gw!/T-UÏGÚ®\·»:ÈdðçÒWa¶BÝD•eÓUV-“RTö)jQu$¥ûˆ>"<'õê»D¨,̤ôêX1œËêvôíùp Ó¶ûׯ¡ÛŒé]huH;˜ST€%ƒ=ÇõÇÓ}üÿä§;}ûþGÓ†%y á½?˜Éíä??»$§'ËbÛ{ü"„‘º÷séÿëAÇ8+Ç|ÃÇÃÞ4DÇ~ß××Ë…„wÎ>™cä7ãïá{°ñÊ>,ÎMŒŒ,ˆÌ¨]Õ Ô¨20RBÄIÛ$¾ä øø&ý¬|ôæÇ5½¯uå§YòÞ¯–º³EÓÚyonÒõzŠÁªïô69W»°<—+]Sm¢¼]íú¾¦ªaGU:ÓSÜß$åà•ŸÇ}e>`²Y¥%.j‹©Ã‚  ¨¾M—é;2fí%ÍTÆT”N÷)rNä€A›Ï‘+¶û SCA$×䥌W¡ŽKmžšžªÊô3R/AZÚõ°ê‰áœ¸1¨¢==eIáÌ[è˜MIS/÷ˆ)|{t.ñYQ¬¥§¨`²¾i袚ŸQÃ3>è•røjp8ù  —8PâEY¸ñãœ},¾gѪ|Ì6^î‚õY% €ðQµ<Ð[èµ=5ÖѤJš¿ 4•^u}S9À’e ÔAk‚ ]^‰·VtKs\n÷¶éžsÈÇUC dŽ6$58 rS* d²œ€­¶•†bÙ2¥M Z¿¥!9o«—°ÚÐJŸ, /)Ðjr Æ•í†JšuV·¬ŽËS ÐÍT)ÚèñŸ$XÖ’žZ%c˜ê rå_×Ã,„gT–:h.‘Ô^®)¢¯ªÕ|ÁÓöZFOV×#¥´-|Å R-3Ûå|1®¶8ÆÊñ¡++™:i.•­JÊüc0\¹R“B”É€òhlÖšóRÜßQÂZKM¶›–ö(g·4žóW mήÙXá¶Ýk™R>$‰ÈQÓiK¢) äTËG •ºZ%£læ®$þÖ†«ÖÎ’€KhhH\"%DÁƒ3¬–‘7¥TÂÄ$‘W.ä^oQèÑ-2Ò÷”…°&›’b­«¢°éô¹×ÜîñT\tž¡±TéÛkÃ5tt2ÓÚ­ŠÂÞ((ÒÖÝk’|>¯¸b3Ò%³®PhZ=-m¤Óö…/Wj)©ÖjèmÔò]¯D²œ¤M=P4ÌU¤øÇL¿S*ð¼‚äçýæ>ZÉÀ&¡³naüÎø¬•ÆŠ½ÖTÔTTͪ5u;µDïP–ÉCV|ŒŒJF$¼¡ ÆâãÓöj¸9c©‚Û3ÙtFŸ¢ë«h QÓÍcÓkq9pá|oÞ1UYˆiA Œ‘$¼¢jRPIÿŠ"ª…Óä¯hþÎÑhý;}¯Õ·Èa¤½ÔZ©®+Gâ»QÂg{¤…ˆæ—Ý!Aˆ²:OI`r$†ûµò¾á[Ê«†«¶h˽ ƒTÛ,š¦ó¥¤Ôvù«ª)éÿ}ÇIP?{[ÑìÏ ‚¤”ÑÄ}C ¹ƒ£AJI¾”‡n$Rœü8°©á5qÀ7dA9aìÕ̾oE[S¥9Gx«þîZç5†žŠõVâi–+ÝÌÃLgð¼ÂÅ'V$¤¶åm3Ënmòk™¶ih­èä_4ìWX'²Ýhží£/vG’A u–ûÝ<ôUÔR‚Ä$°ŒÈ²ƒ‘ñd\™¨*”ÒÖ´8:1¡¥-JBV Ð@,CŠQˆÕæm²éÎohj^w_¹žüÂÕušçCZ5²Ýêé®7´«ÐÔ4~$¸ÖR°y.~édë¬5Q¬ÓÌóTË4²ÈÌÔNŒ´_`æß2õ§Óµz»û!Í]MÐôõª*žåÊÚ—:v–y„Þ*Ý f4ïà†lD±® µ^@H ÉàBéó'ɽcl}‚tüVŽUßk)âð…Ï[\Ú6QŽªzk}² çã{Çq¶p3Å“ímtåì|»¡°óºåCM¨/ †®Õ òÉ¢¢¶WÔÛ…Jà ‡Ý]ƒDÅãhóP½f< PE0 EÐ9²Àz‰z‚§—´k³åv¥°óVk”¤¸Xfåf²³ÙžÈ‘Mr¢¨¡å­>‰÷ª5jØºË H *ÆÒGШ›#û)}„ù_íãÎ~Kò›ê«w,jO:ù“ªCÜm¶KýKië>š‚ËO Òáh­ZJ7¹QÅOQÓ‘¡­•b–¼9“]’Rm6‰2Ô÷TSy±`§Sq¤dµÍ6k<Ù ¤¥D>–<éÅs÷‘WÙ[jÏgNRk½'ÈÝ-­$¾hªµž·Õv˜ë%ÒVÅ»j 5O¬nu+DÕ×®’®Kj¤U2E•ÁA©5rµÊ•Zb¬.Ž"A+QÚÖ`®²P!hÀcÙÔõc-Óœu”‰R¯"Hꦩp:‚pnqÊ“1sBfÌc1AÐ5X> ʽ¥ãÜRRGMìùì«—F-ií­dh$ðaq¦4®·¦¦5.*¢YTH)Q’G•ÈI¦”1ßnTÓÅI¥élÑ@ñ›O]9 ‡ÃIæ¦#PÇÒ”Ý*&#N˜“äMí voâ-ŽZÐTmëÚ²’GíPµZ Þ.Ê#ƒŠØ>¡±L´-e+ $ìÅqP6K( 3Õæn7Nb–§CïïõÛ·~ Jaè6óü3ý=xûôÉ„ÇÂ-ššÖpBÂa¿–<¾ìoÁ)NN6#m¾¤yzN2©MÌÆ„¤R Jp1¶1ë÷cn H>_—ôã:”ݰä'3Gôû²?ØoÁ‰Oò;wõ#ðúq•kãJQƒçñÇOè>áMø1)‰Ævû²Oèãñã9]wyF„ ƒ›Û¿ž6ÇÔüÏ‚’,zvþ§(–ÄÁ”çË?žÛgÏþ>œ.ãË?¯^Mw H x)aùzy`~>c…–Ç‘üA< ªŒ),Có¢X†ÃÏåßñ<)Kݯ~0°‹±Æ>dþxá@ƒÌð²Iƒƒñ>‘P;ëüøïŠ‹º5ŽqÎ$^íÑÎ9Ä‹ŽqÎ*$sŽqq#œs‰9Ç8¨‘Î9ÅÄŽqÎ$HçâDŽqÎ$QåãœPÀg£ÄÿÛ¹S¯­~Èšvó¢.Õ–¸ æu¦ô(Ã3J×í3©(ôìÒ©êF†H–ÖøÑ¾&PAe€=K©µ´ÑšŠ³QÞ.7»¥«TÙnóq«š²sEw »PÜ4ÎJD•Vû*Œ*øà8l¤‚¢q.;0—€kÜšzÄ3QÝj-õ<¯Ö´£ûâXm¼£¼w-z­±ÒGœ©–Õg²¿¨)Îã*PÛ`¡ç.©Ò”ªÝ©¶Ó˜öé©RZîK£ä >Òšùì'|”\·C„°,C׺3¾ÿ‡þâ°°†¸hNi؃žº[U‡ZQ V Õšz÷’|)û=6m]v‘±ÿ·LIì1P\/v®\Óh»¥cG~ÓzÊá©­4…$ŽJË©ÓÖÚk§»ÔˆÌL!®ÒöCáäœÜ%`¿ ‘ÌÚŒ¹ÉMù‰Bˆ©ƒ²(­ÔÂE (þ bkÌNšû,5#Æ$5ú%´ý|Çÿ„ô…Úåd£N ¤M.—b»ÇGfÎ6‹,™ËEÅ,S˜p kº9³êK`RÞ)ÿíüÆZúE©¾iMH„°Õœ½Ò7õWXij4 ɉÁÄ[£ä™òsÕWÔ{äýÃÿÒÝÍåÔ<‰ç·'*k:çÒz«Në{e!éSê*Ë-â@ª;,¶+OŸ¼qÒ3©múi‰fºy~áæ &`þu•D¹)Kó2Ãø†©É!Çp={Ÿ|yp±o3œyí¾~£ŽsƨH3ëÛ#ßlð ”Ýû~Nþ¼0,æ J^–™·Û.Û±Û$§ï·Ÿsƒù} ¸ÂÊKÀ†œä÷üÿÛŽqn7ˆ¦;£åKöëîmóÙç™Ss]jMq§44$Ðü¼:žÓU ÂÁn²X­ÓÞ,©ú5"WWÀñšuzzt•R:‰zÌp{p°ôúŒzcm‰íÇÚv$ÙªØû-s”¥ÌT‰d•—H ½rÃ6g¬|ÃêIr¥mͤ‰(å Žh’KnrIáîcÝïºcAjÝC¦4µïZê+=Šá_fÒzlÚý¨.0S³RÚí-¹ÑÑŠÉd¡¨ª†0{Éä7Ÿjpj~vsóšZö£OÕiÍA¯5Ƨ¿_¬sUÅrº[ª(uXÙÊ‹œh¨ðSéª{D 2¼QAâ¾¼5óXZ&Y$Ü7* È—Ž`T’ßpã?¤làÚ-V“0:RpbÊ!EGƒ¤ÛŽ­UFŠÊ#¶[䆾îÑ-½kŽ{u¾RÃK4¸a]sŽY­ ?ˆ¾:ȉ¶µ¼W´‘P‰éêÈ,j.7"W{ëZéA-PéY¯afÀXÐÑ08#ÃP¶IOßlëô¬½†_ÓÝǺ#íKWWm¸Ðéäk-¶ððÅP(fÜk®SêÛ飺=t*²B ²Å¤QáDož¯ H™Ûy7h©Öú¾Ët£¼ÜmúÁD·Eý÷U}-梢AyjÊŸDóKâ[k‡ÖáÁBü Ž}œKµ¬ò'&ü©²¦©Iþì!‹Ò€¨ –ã§©Rv\éé7fÈ\°’w©Üv°joˆW.⦵Ù5]ñHW¡±Ýš—Þ߯ÍLðd–Fyj„pY· ‘–ò3•v¤:’ËrTµ .³ÛZ´#JÉS©®ZÕ”šS‡©JYëIn¢=Ó 'ù@‡H5Ìš×èæ3ÍRɘE·}­NaëYWèŠ[¨¯u!oé­ù––ÅÓvD‚k@¦¨¸RÙmU&že‰p –X×§ÂHcÁ à°s »VUQAc÷çµC~ÖÔÉ`©´ûÍ [QV,ÆãâÕI•ükÜP“Jƒ£§¾bË‹²è’jyÝ4äç²-¥2¯€í.{DA®p5Åy•r §–¦²ÿ«-¶Z8á‰æšZ8¤»\^$ :¯nϦ{Äòm1SG_yÔu•4v»-³LA¤áž¢eG¦?»h4ÕeK+H`Ž_z,Îêsœ ð)` °?™#ÄA¸a¼€ý oš;MÇ ­–z µ•5æ®vµTȱ OÞ+Õ=ª¦á7þÉl+H_¨DJ¸;C«uEmã›K[ZVѦµ:ÑÃMqÍ%uÞóAi¦’¢¤õ;°‚¾n¬ŠÒHêà’²¥@_{ Ë/¸KœéÛx¬#µÇmåÍ,U3KPú“VÖ\ê$žC< ¾Š‘zÙÉf!êç?'ãlýŠù5óúŠ- Ms§ñ¨à]G£¢¶i»=²’Íi¬i+õ=õÒÛ§ŠVÝ«™¤’xœ9ê ‘.Î-*6 “.\°£y˜°£>Y¶ÍÚëµ )6R¤Î˜°ž®58ð 1¤löö0åŸ0ì–Žg{WòÊÁs«»TŠš e×|åÒúz ÑOF¨ÕzÓQC ¬Ž(Y­U7Y!djo XL«¹I¤ùÓ£)õf—ªåo´·*h䣬MkË Ýš:nÅ3ËCËU%±ÞãË눘:ÖÓÛ+¢ø‘ž¥ Ú»bÇhždÈ)JR¶%@ðJµÒqphQaÙÛ,™v™k½9%EHýÀ¿ê7†< SäsDYi¢ö¥×ZŠÖÔ!½sƒPÒšÉ*©iéüMOº‘Ø·\µ>D¿¼û™g-yϪ ƒ˜z“›ÔÐj»fÓ¶Û$¢Ño†–ëv¢Õú–ÇE™®×>HX–’i¡¹k¦ŠyÖ9š6škMÉ B©,†®n€X!nw*ÌÄ…oãOa \Hu}#Y(µ£ÑÚïÚ]i[‹K]n{ÆÙMpzš«,wï2tô3ÈöÉYQe6aW :ªÈa\aHÝÙó¨?hŵ+¹™û?ùiMÌÎiE˻Φ×ü¿«£µÇ˘ô–³×[5Ú›PÝ/÷Ëh°Ù*礶uTÅv£¬†UŠT¨ï—HDã:PH˜X,]‰§/(Í0É2–g·Dê|À8zV=§ö¯ö„¾sšãc¹s'—7Os?L&·ÓÓУSØõÆ—´ë:[²ÚêæÒÊÂñ‹íŽyèg𒢂©U/¹qQ6‰I¨l´—ji皥i!«÷Ê–ŽÝ_P…*"Ž8Y Uq PœòQh2ÓÒ •$¸J^•ÜØa¾8ræY¥«¢‘0© ÊR‡Zó¢˜âYèâµ÷Ï–Ég*=Œ-Ôí4xäÏ=/É!¤–Q­nVËl/; F£êkãŒ=m‘›‰oâûûË8 ÛªæeÞaG!8Û.Õµ ô®Ø¨C²(GÏ!~°Ò>žUó6ºøm!ˆà âŒø1uýÛn…KþíäGWe§:´›N[ÒEw3–dTõç]÷–ÚŠžÏnžÃn¡k=-¢áv@eJ‰êk£tI'ªX–%‚š:£'ªC– €4«S{hT•xfç.œ‚­Ðélµö™*#f-€i¬P¼ý`ÃÕ·cÛÓeJ(JÔ Š²ÈVŽÛñ¬~i´ZÌ¥ªYš%¤¹Îêã E›ì£Î:½sÍ9Å×TkKåéK­RÜov aA¦ã«{µ¢šž/Þ÷ëlœU2Ä3†ß§dz—N_‡uÇPïßlƒó·;Lã*Þd%HKQ˜¶á¼váÆ;v‹E3å‚•wr6,M`ôƒ~ß–6û»ž J|y|½Gë~µ¶ußP‚øaG>_ïÜwÛ·ÇL}>~¿‡ëËŒªS»aR–jÁé†ûvŸ.4wÛWÛã•þÃ4ú^bè~gëJŽcNÖ8¹wiÓ—膔6^o•ýOn÷5ê*…j ø3uˆúW­i ˜±.RJæ+’yrw†uR – „§h=gj^?êÐp™›öQæ¥×  S×#MdÈTF²¥(¹4Y땱Ÿ÷¼R@H"ñÉ'N ÞÃ~ÍlŠïn¿gªÞv\,ÖkE?0õŒÛ"Ô-RR¥2É&ÅÜñÝcEûf=½êE•e×<5Õvˆë`§NV³%5f¡½Ù+š‘¡bò,”VøâÇŠMKÏKȾ~»~É¿n{ûYß9£lçv£Ñ7©,[I_ôÔ:=)áÄ•óÏE|¨¨ŸLÖÏãCûÌ¡20^šbÈÂFS6I(*íÅãZá•q~q¥R$ S–’¢¤Ô¦)¦=­Â=¯ãœlŒQÎ9ĉãœH‘Î9ÅV$sŽqq#œs‰Æ$sŽq"G8ç»(‘Î:ÈÎ23ßxõǧp1#¾9Ä!âG8çhÚÝ<þý©û}ì#íG"jí1¥éyƒmøzš:­x·jy%\ †6êÁ‘Ø9ãó_¸[#·jŽliÔ˜&µjŠz0{4ZbëM«a2w-oÓ³#²Ôç¹ÊS’MéHyh/‚ÇwUûⲸ„®å•“ÔúsZ\`vVø–ŸUZ(ª(¢êÆ<5›J]˜Œ´ì|Ï jKÄ–SË}sL¿Æm=¡ï0‘ž¦ªÑr)+>7ët|ŽNNL¤žüoK”‡Ë®ØÈ§UÜûÁ¼â;‚ÛIfçf¦Ò‘™­÷Ší}¢­È:zj£Ô–»ÕNH°ºëTÑîcB~kI÷Q¹êe´×ØD²)JŠiME-KÇ<&v¢‘ˆ3l°…qε¹R¡8?ÊãÎ1I–t©@žÜ<¡¦-Ey¥žD‚)Þ0ô«G$?ÂŽ‘Hêkf†Gé÷¿w‰#.6é;ÆÚS‘uä„AjªMÌ(sU/†^H5Þu• °­F='ê»üG/ÙÄ9@UÇæ¼# @×Å$Á3ÇQx妇«§C<úsUjí7R¯Š”7ZK&¡±D ‘â~‹V¾c»60¤ïúc9°ºCÛVñË©ªnhrÃSX̸1½ÒÄ´úº"ˆT¿E‚©# >?G™ãj¦ þ¦HX3o]ÌAåLw¸˜vË0€ÿŽç†=Ñ÷Û$?×}¾»zqÔ·«&“±Ýu6¤¹RYtýŽŠ{•æñpSÛíVÊT2V\®5.:(­ðB¯$ó¹X Š'–VHÑ™yámŽQªé ßñ¯Ìy]ÉŸÚëìÁÎ_k®p{"ÓÜÓJj~Nék…îõ¬uâÓK¢®—=©îÖSCh¿™E-U¢šß†¾ ‘iêb¿BÇ4 ¯êaHç‰%‰Õâ‘H¥‰ƒ£Æà2HŒ§ ¬¤AÁçžTñ41› ÞŒZ“uDnø8¡ÆØÏÏÏÏÌž–Ÿ ‚1ß8_¯N)ZˆÆ€HÈ'=»þs‰|î1L7ùWý†zï–•žÈÖ¾WZõÑ9¹§ïÚŸUóBë Gs¿jë,wûÝE†² Ëºš †œm?k²¬iÐÀ’B*%µøžÙ-9Ûcçƒç€7ú>Ѳ'É™³6y e¦L´‚ S=~ä—xù~Ý“5^Ü'&êÕ0Ấ‚“Ú›¾µYöÒç¥w³W³¶¿æÝ»HëmeU¦íuS­³B雞¤¸Q´USÔ_.æ:tþ™¡‚ *n:™!¦¢¦¦yBþr~k—Û¼·KµEº‡Š®hÖ¢Ey.WÉéj$Ó—úŠæÉ÷jOs©£•¢_„5!•ݲHòŸTÎ3-2¥] JK¹ÎñðcÝ”w~”¤¦Ù=Jf”$%úÂíI# «Ô醈)¨-UðQÕ´w}BÌ”ÕQÆÈöûMlÛ…=k¼ÊV×Å{ÐÔÓ§F#Vê,{¼iæ®7ËÆ¢­¨zŠkL7ùÿxV|QšK­A©ˆéÓÝ´eaBšþ®‘×ÕÇ“IºÄ€~T ¯-Õ`BYMšiÁîÄb¶åAdýÑiÒ4p_¯Ý©lMwºÉ-¸V[mö¶Üí°À²Èˆ¯s«rǦU’®^’J.Eš>d]¨5θ·jZjHkªi/ÁnwšZûü±ÓÒ5tõ2ÂÍûÀIQt˜xø˜»õ’Iã žJ­Ùå ¹2L¥L¼p»GH"µ!÷a-3.Ç$ÍEùsf]g.é!DaKÃ!¶ÇqK’ºV\¨Êž**Bö¤bšæ+.¶ÿà4­–‚) ’¦2JTœuôñléJ ¶¼¼j«‹Io²iÝMu¬µSÒ´–øi­ÚÓY~½BÕ4àµ@–ËM41FÀBþPáC3(«-8 ¿ðoB–”…MYê aÊévå–…E¤mÕ•’éK€¤žhaÔº«\]«"€¼TþSÅO%D€aXÕiùD`Y‰Ï‹Ç_ÜôÝ]ë–Ö»µÉé*´f¯­°Ú¢éiníy¾êZÂLk'MC?QøÀd? 4L’¡ö•Ýã€Iñ @®YRåQ)éÄ¥¼Å/O¬ª¤´è˜ô]¦ ÷U_fžZè!«¬¬^ÃG=Û¥\¨«yeªEë3XNù ,j¾ië`æµêzºªŠzû­ žŠžz‰e§§†¶ëp¼O,21XQº2B€3¿Ÿ Q*H~ªYÇjS„02x–nÇ#‡}·ÐGO«¹oE 3KM§ì6+ƒ¬q·M8eŸP<’\F«'q¹a“¿]?¤îÑèý^n¯¬ê»ŽŠŠ–ÌtÑMWx©–TIHé·¡ ̧múFO„ÕY…w0OJA¨w»Žò }!·QVè %C¥è/u_¨ ·ÔÔZ…º'¨KUmÂDÃÒÌ!*¦” ñ% pwl/ÎÊa—NÛkšï|ÐÏ_=6”ÓÓ꛲شý`’ZJ…·é²Z–‚I§£žW’C!i>-Êf›ÉPºCñ ×¼18¤š? éâtO²‡8ù•¥áÔZ/’ÚÂÿ@÷:ˆ-Ö›´tÐZCÌ¢ákQ7‹>[0'PXu&meênbò/œ¶Ýi`ºó”7í#æºévÓڲ맫Ršßd¸Wø³L×AUSJ'§‚I ~¨¥Xº$RPå\…‰ej@2Í Cý¡UN,C±f-‹ÃQ:Y]Ä«¬‘׈£ãN‡ÑºFézÕ×~Ok¤½Üõ/5²A<· ÕMA{º[|*ºŠªjuª·HÓÝ«D° “ÁÈ,AijHjÊîsÐêËt†íw½hºy$†xë"’ž/÷5¸™é˃K Ý}$†èb1RÖá à@ׄZ ’(72a–û;ÑÇkä·-©ÙBui‹mgN1Þþð$ã¹>õ“¾äúö¨¹ÝÌ-IGÏ.QrâÚ–¹ôƨ–És¾ ªyž¾žkn©Ž¶¨*u ÖÊÂD‘J±ÀV‚æìÊò¯´h4BH·¤k­žáËié®iWij‰ùi.¥RÑyþÖÌSOªæ­Ô74¡¢–[L©W¨•:–é8§ ”oq¿éúö¢ä!ùÿÌÍ>ghþYsQò?Eèî]ɯ®ñi&©¹›ìš†¢ÏnըܕS‹l””õU4òV3˜©’iq×d´&Ï5&¢€ ŒA)`@á‰jž1϶ITé D–a›*1nÞ4ìx¿ÿh€¤Ð<÷Ô&®[ºBí¬kinª‘%¶§PÉv2PÐ-=!-͈%ƒ(ÎÆ ±iÆ|öR«=4‰ÒMŽ:‹Êò!YéBz*ˆ?¹=»…?g¥¥¢iUå(KcPÇÙÔŽT”]@Ž),ÛÚ½M_C—rN'èß– Rܽì hè}‘¹w\=:»AQ­y»ÊËB˜+ˆIhä‘fªøR¾6n¬¥$õ{ëÊZrÚqd)Ò Väé84t0—0Æ~Óê§ÕTü<|éPõm"w3M7}áÃÓ‰rU÷¿«zŸBí¤`LÛbnôI«3µÊ<¬ä/·Ý–ž÷í*$VúšÚ %§i|#£ô¦¦¸¤F9ªÑRJúKÝdµi*Ƙ9d’läi÷îÿÜýÔßµ-¦&'ª–mUY¤(åP]nšß˸Ò<|363¸3ú†Í0t2ÁcL zS"@Ïqöü¡l”EªzŠ”•ˆd ±P“Læ'sFé{ X¬ñs+SÜ©à¦I¤Ð•TbçM-M|³Š‹æŸ™àjúm©#«Ië‡ßê’EV LÉÕ,>Éh6¨cSFÒi)à‰éòÖ%vøc‚c+²AÑŒC#HÁQ=;/G•Ú3Ú¤‘P‡Ž~©¯cJÙÒîP,©øº…jNçÄó©{9)ýØìqøþ½8))ðw'>˜óíÀ©Dâc¦”3@éx±%\Vö¼Z–¾yPÑ5ÂVM+4Š‘ÅLÒõ»“  &&ìœH〟"?ã×ׄ*bjƒŒ};áá ¡ €{7A±Óàv[üþþ>X?êoÖº£BÙ}¥ÓuTt¦íQÏh«®ƒßŽ(W“ÒÓ˜~5ðÿø™º³ÔÀ0r2­$ÌDÙ*»18‰ õpq‚T™sÓÐÍMéjgC±|A|Føù«ç7*Lêå§Y$B>Ÿ°Æ ÄÉÓüYmLà‘þo™ã¸9Í[Ä“µ^§¬‘?½Íû¾(§ç÷‰ZŠ•Z!âK —8ø¤UÎゟ´mÅÕ6Ü´¤P —ô„¶îØlcA •cAS¸“†÷zC]Æå«nÁ­º‹Têˬ4u3Í-ªñu­žš°LlëG4ÄES’TÉáÛ;ž>Õÿ鑸\³w?4ܤ­–ÓÍ==s¶ÄÌ£¯»éU‚ìÛHH Oh²÷% ¼¹ªQZÑ4¬ÌQýÊ$“LÉz`Þµ@K³Ì–%„&” ä“A^2(—Œ@Àáøo¬ö£ä^Jû>§×ÖûMÏJÑY"½Q=ζ² n:8: eõ{2DXË«)hÈslédè]|&ÔÖÝEt´µr½¹ä• ж!=Ñ-2ö‚ÑvE¹J»Í7o1$Ý4Z‘ô\ñg¸csß-¸áƒä|¿.ÜzkÀQõOˆä”­a =3+ÕR«+ei¢ ¬¤†Vö`AÏâàn7¼|ÓÉÊ蛞ß×tÖZ:+fŒäöžÒ´U'$Úfž¿ZjOÞõtÚ{^_n3Öµ;ŧ–Š%whâi«ªP˜ “ëxAÛ`N;à÷íçØ·VúuEÀ— ³VÎjÈ ÁÝØ×Ýê—VÙžýÚe§ý òzåLñ1åíçþ䯱Ÿ2ôuÖ¶ën¼sÓKÞùOa« Ó·«­$š¶l—Z»½ÚßHÔ¶:8ì· ƒ)«ž©˜GMOâË Cùðݯ+q’®ƒMÓÔPÒÞºžIÜ»V›Ý¢ùIL?ü4fáF§©XF¬ìÌHãõ£¥·%ÞZBKÐU8¡]Ó&"Ï:jÙ(™1Ó¼„¥"¹‡UàÔ |‚,ôtv˼sÖôÔÜ£žzñg‚`¦%¸Ûêj–ëTˆëM"QêªüF>6IÕ†Àᾞ[ΩÓ÷4{ÕD”VºK]ª†´ÔÕ×}7a¶Ï4 ŸA©eñœ’XÅÔNÇ:j œ»¼=cÒ†.xÀH<[¾êå¢ÒúšÛ]Sz·Ò\½âáz¶[µD³Ïv¸Ö½VBÒÇ@®* lŒÀÃ8æu=?-îú4üO%ÚëU[¤•*"™®‹XôÐøÔ=2¯‡Ha&+÷&ÊL‹E²r˜mD• ” xbÄßg,ì+He¬~¢EŽI_B™3ºPsW÷}N]NaÍ!öÑd7ÛU¦ŠÝOQ}°Ô]%2xq%¦ÚÕÕ•Í™L =L'à»J£p%õ6‹Ó·™(«¤½Íª4þ³ºKp·¥<–èªëè먮öúŠÞ¹<& D”½i–g™ÇH€wÜFÂ^¥*I«|íhØu%ÛQj+U+EOg±Í c®»Ø(!‰©Ú*ª¹ £ˆMá, E} Ò¥ÝÉ+öB§¯tLœ¿æ]÷EÔ==Mo/4}úÕ4”RTTÄ.7E«Š¡ ’¢’f÷ÍG*ä¨%³¿£QAšHÄ$ùÐnê×8—ÓÒ"P$©aJîdæÆ<`]=¥îÈÚ®X6“¶Ôßn‘Õ—‚t©¨»Þ+âˆS2uM<„õaB‘“œjäКOLAQq¸Kªèk¯ÓMq†Ð#¨V¼Ñ[Qb·ƒOTÒæ¬ýrã.žƒOq ª´Àgö‡ôÓCX–«‘•1¥xÒ'Öw(µv¬Ót6Ê*[E%‚ïS=a.Õ‰%žŽŠ†–$RIb…ND™ ÒZ÷«·)'þÑÝj®Ò^õùZy $4¶«2¢GOj±Á‹tÎTu‘¶x§R‚Á,üɸ˜R.–rn÷¼x´Q­ç@ØŠ“MCfÓC 9W¯š96̪¬¦K€%ƒ}’Xuv?Aü°äd³rs–ú¶ÙË+\þ‚ŸPWkGIGe´Zç»Âõ†ªmm¨j)é­`„› ¸”;m‘ÓÙ‰³%sæZêî®làgL9¼rv­j“"]’ð\å)Å™Èp(³À4lw³Ö¯ä=v¦»èõöÂöRÓ|Å‚šß·L×sžÑGOw¨iêc¨ ¶kÚø³U·î{8_gÔšoW´±$pØõÕÇMÒ•R†H-–[¡ÝY ÕXÃdPB‚¹\;|Wè)BÑõd‹JÉÇd˜ 8ͺ;(¢X¾è{Çìÿ_Oè>–™fJ\[-a'”¢¢â•ª§üf©7Ÿµ_Z_hý·5ÅºŠŠév¤Òön]<Éd¾j+uDº*Åxñ…1ä¾½  “Ä­ \Ûh‘ÔÓd xÒ[µ ²O,×{5ž €‚˜\ô†™®hÙкGL¼ÖåÍW‰€6K4¤gâ¦;(ûËm®TéæJ‹– ‡È.Ô€ød~K*Á`"I´Hu†P%**/£Ô€äïÝììéæQ×zÏ[Ü«sNÑéØ)’jÉ**}ëÞn–÷…aºÕAP•åŒôEs® o Éžñr­ ­5óA۸瑌g€–ŸjxÓ\Íö€÷-sSi´kmI]hÕU’è=e©hí”:Wê(-‚]KdÓSÒY#¦‹¤SÊóF´”ïNµL†zyå¡ùkí/ t”–˜hyÓ0¼K[djÛµ¢×ÌÛTòÉÒUÛž:h.Ô0Æ "E›¦8"ˆÌ¢hKÇ:¦ÙäÊ“(Í´t+˜ èQ0f,(îЉSæÎ˜´Ê‘Ò&Q)ûÒ ƒƒ= ©c^ôñK~nhû$Ü.òÔEr¨Õ|ÔT•ÕpÈ'§¸\dÒ7+MʪrÞ-<ÕñTº6[©%'9ã។)Y_cf¥Zž›3â—®ÝK] VÒöé F÷Ž\ߟ¤ËÊ 2±ðkßø l?sŽðã‡àxtlà­ Ê ·dUV¥©†õ ÚÚ·[W p·ðä¦Ñú– Jû>¿Wÿ‘Õâ–s€Õs(Jh¿c”ïiöÕ¡CLôëzÓ|ÞÓýBÛ5,o<‘j˜”Ì9oiR ‚BUȬÁŠûÔæ*Ô´1ZFÊÃhôâ#jSü™µfBóÿù†ïƒ\|sñÉŽqÎ.$sŽqQ#œs‹‰ãœH‘Î9ÅvÄŽqÎ.$1_õ5‡KRÅ]¨.´vªIª £Žz¹–$3T8E8'"^¹&“A •4pE$‰®T>ÔV ÿ´µÿÙçMÙ®Wh´V³ÞµÆº¢j±éýYªëïé;VUÄMÌÚt¶£ª©ðÒv‰Í ŠòÀµ„°z’¬I ÞàzÇ^×<…ÕüåÖÅ¢¹­¹S¬- _[¤5&ƒÔw=-wXTØf‡J½UÚ×!’žÕí)*'ðãjƒîªÉ4Ë/Ìg¶!?nÇ$ù9ÍÉtG/ÉÞ#Ç?d¿ÙÙíïÈ_ìÝí›{×uŠÑœå¼Ú*u8ï7¨ëíú6Û«µÅ–Ñhºó.Ž–èÑê½;~¯¸Z*éhç5VëÊO%ÖKzÖSÌÿ ?²þŒ[RÜ9E«¬:ñ/µ*º×]éʚɭ瘚z‚šÁ¬5)5¦«ä¹Úê­)e‘bš ²<‘gг‹Ÿqë* j®p30 qð¦·ÆÑñÎ5£œ~b?µEÍÊÿl^uéúxÚintsBÛ@€0ðéfÖ•šîÐËÕŽ”Íonðñ°E\l‚ÓåjOhz+"xÈÝõòxÒa‡ÿTuͺ©E}¡ætQ퇎åd»Ýôò!QƒÕV–Æ\È=³ZÒŸ–Þ2:å³j|‰ê"ŽZ}Ie¸: ÝUw "žžä(;à÷Šƒž¯˜±”$.`eQDžô®ø„k-Eg/ùkx‰-#jÝ Ì¤Ïu§ÕJà‚H>¸„û.;"üÖÔÐs KëGq5n˜å–¬‚bp^éO¦,qÜç2.ìßÚ eijԄÏÔzEõ° Ü 7ÁK¢TYÒ|‘i»KûQ¬jéŽNpÉl”2•A¤õMòz7n¿ýÄ{é§D˜ÉÍÊ)jhù­K¤*RHëokž^T&0÷-M§oÚR‰ g xw ÚR™Áñpp8¹%„ÄŠuÈòƒŸÖUðo:¬?ÍãO‹ræÃ¯Õ5vêúÚiÌšcWW[è]êÓ¥¯Wj:wqƒ4²ÖÐS¯˜%”`øšrsNéMWS¾éBiýóTÉOQ$}*‹ÔÐ4&D ™b KGÕŒ3aƒñȳ•h˜”ôŠ”f®ý2¸RXï¼wÃS52eL˜Pe›¤Å4mÕv;ûD~¿¾É|¥äÇ'ùËû'!ô–å¶€Ô:vÏ®(ôÖ¶ÅgÓé]¬-twÊúê+m?ðé|y« Œ¨Ü08¹µ¶ŽÓúïMÝ4Ö¤²ÛoÖË•]4¶ë¬M%¦¦’¢‘¼CÇ1TÊ…ã"@“7AðÖK!˜Œ›æ…P´›ª AÁ¼£áöÄ{ûA{Dþ×Wò’©¹{§o¼ìö|¦©Òc”´Úž}&›ÑÚX •N°‘hêîûº;”•wrx}Ú’%§¥‘`÷n-`¿Ù+û@ùª½ž}§ýŽùÕ¥tw5ùe£tÏ8ù‡Ì›%>¸ª¬ÓW }UWkKËO Š×IO¦ô¥Ž¢‘j)kR{C-Æ4Pòb2­v›L©rÑÒ„õ’:ÎÛŠnKM+Ö‘Ö´ÌLéRQ2j¿–„0/v¨X©êÍßl–Xnéfµ.¡’ŠkêÛèÖó=²žjKl×AO®’†–¢ªw¦£jŸÇÍ+"­#X•$_.þ¿óÇX.Íc’Ñ›Iéê‰ež{%¶Y§‘æšY(éÞI%‘‹É#³&Y˱$É9ãœH?«Î# ãÇÚ>:ÿéÐÒT-Ê¿ib¤6kïœËÓºNJÛu¥Šä©¦4ÒÖÔPܪ®1Çh§+Q}Œ­ ’HG5lŽõ4éÒ/»žø¬úüøú¶ÈR¥lË ¨”“ƒ}À)Û‹»â¯¸ÔÇÏ6û/kÛ Âò@«à„æ5ÚñóëÿP§?t>•öM—O­4í0y‰ª4^¥þÊÉqŠM@Ú;CݦÖwôÖ˜CKnšn×N’0Q=MJÅfWéø`®¾Cm3Siød§ÉPõwYúZáT)*ìwãKJ±‚”´¡*nÂ>ž©*œ3+8ó{foKm[*õÖO&`sÅÉŽÖÀ–¹v%  L˜T4€æAh&Ûh[²çp¼Ë-(³ÖÒ‰.µ-KGqXa`qâPYír#ÈT?OžÜ:Ksª¶ÐC5Ëi¶’Úî’uÜjtßî}rÕ)SUŽÁ4.Š1Ñ|ã’TaVo0þÝ ^ö‚ï ;Ûº :z zG­¬¨‰ÐPèx}Âfˆ4rVÝ(¨Þªw…•ÅÖ¹¶*À¡ ç‰.ª¸Z¡å>´Ñ]mÕ·%ªzûtÀõT³{¥L²¥LqËÕ{ÕlŠC¨=DtjÚÅg£é.Zýép£tp$ƒ½¸= :Dl” t…*RÖß°º€¼x€æÑ‘î4ë¦ò{©j»á¦¥3ŸJÓUÓER ?Þ1]O;¤Ë"ž­€[KMØh*9t¡¦Ž õ<Ñi«e‚ŸÀ•?µ7«Öë:¡˜+Æ”ÑÆ²3†+TŒš’f^Ìçt7yïÂw’HbV€y^—ÿ,3Zémº6¾á¸\à™í¶½=§.6zM²’ŠÓGCõ2ÁNÍ#$õ–9:s®røëÎgÜoþj^¿vÓɨ嬡½ÖjZÄ€Ë_t­ºÛeJYiiâC #Ýj‘dT ¤*(┲Ô`¾UæCÜb%KLÂ.¬âÄ Û‹‡T×Þkõ<5w;SËAË)+îÐÈ` žçsÒLÏCø‹-ä%IÁâ/Mm§Mè+jÆ¥n:’ñq–$Kššëe;¯Ú1Ðã¨àn³Þ9ÿÔ=¡‰9 ÕÎ&PÜ«¯œÇ¹EA3As†ºßAS$F8¥¨®ÔT0ÂÔË…lÀfêÁÀ ¾1Ćᤡ Ò:6˨/Vˆ©ªõ î²vž?<²Yé …gªxÑE+䌌“€rO— Y.jîë$ú@3܈òŒÿ|hª}}¢±jjõ+Ô[im¡iê X(-” CK•€i™ò:Ün!\ôÖ|ȼ\-–®h^u¶¸ŠÛh¤ýä××ÛͲßf§Šš†ŠŽÓCq–U´ÒC ÒÄÀ±$Jt€xLâJiVQ´ïÄ)p0qŸ¤!cöh×Z¶Ú·/¢kî´tôð-eB])m±¥\ªî`£{ŒqÇZʪÝA©N ¬6wÙó\ó’Ú'›ºZõÌkhŽSÞôÅN–惋Yê?ì¥Þ‡PÜâ³\ã»é==sj;¼l“2uKK$ŠËIPüf›fX”™“ÔQ7j1Ibûî†Kœ…M\¤­”‘ÖÀŒ_9A—?Zéoe冬¦¨²Þ¯Úº:úÉEl+Yd’ír–ÒÏqËÀÑ—F–0Ù`ÀíÕœ³Ö¾JÙôí%¹¯/`עᨧ³ ­¦§Ží4ñW+I Î)ÄTÓu2¢ôªŸ•9 Ð’’{“¬ Ê P¸£rqåXõÊǺ[-ôËÒ}Þ’žl¡TÁ='áòÎÃOê:ú¨åše[¥/.nMlŸÜ‰)-ZUW©©ÿw ÃzbéV'Â2' (®:¯MÊXkù§­¼Ã®Õšæý§«*e‚‚Ó-:wOi„¢¼AMÂõiQyßÃHXã*èsŸ{ÿb3h·*uŸµ)öuä_)½ 9m©²Us¦^aë™ù]¨´ý>ŠÓ×G‰´–§‡ÞÒ:Ø­7:Á$RØ/ 8ŠœÓÄ­·¥)%JDÃ.dÕ]AÅÔ ™wö…8´I´L\®’Už]ù™2)|ª¤€Õ¬W^ÛÜìÓ|êæ~¢æŠßyÓ6ÍGh¢‘lWË…UöË…ž‡BéË¥#×RÜh!¹Ó%ÖÇV)êY"jšwVjzwèÛV©*âCf£ÅIužž7 JuAK!ûoVå˜51åÀ’1”Ø/Jˆ¾[ ìùL°‘*XCÝ$³îu3öp«5DGµí •Ó¼ŽöV²¬ž !#æ=õÐNmêb\ÚãnŸ~L” àü"Aí÷±ý(þÀki‚÷žpkùzº+xS[¨ºÐŠXî)Ê™FAg ãäÃe(í«AÝ`³œªL³†X»2]Þè.UõâJ.ì{f½nµ¿³šÐ>Þ_ù²Oʯírµ½ÛÛëž5“iÙ.”ÔoËš8ë&Ñ2Þéi̪ÐèznõþÍ:šš™–Eðõ.wðŽqç½§R-¿»éµ<6²ÁS÷U6¹¥²³¯I`b·{TiÆrÒt¤»œxCìñõ•fë1»0cårÉFXáªÆÆòúÇz½Yë%³–¥œM1¬ž¢Ïth¯UÑ·Ïp¦Ð.•ôî"˜²××jKGR(¸Y®*Ј~ƒc§5é«õ9y_©µín¡¶Siiôܮ”†º– ÝO ÎáE§5TÞþôÝ~ê bMt§­P–â´°Ekµ’Svâèݨw¸ >C~e-*ZÐÆòX—²ÀâÎØù$ì>ñþþ^\|ßÿÔ¶{,òVcþ?7êÀñcN¨ôÅ[)ê…~"£-°êïÁTób ?pîCOÿïnŸ¤È!]%ÌT ì6i9i«‘[‘²|ä>ñ¿`àc쑯QÈnž{ê{Ú–þ‡þÝþ¼x•Í úÂÊÅÞÏhåC/Ûúåý mpÅ6‹%lDÏxóÏþ¥/iÚ #4‘¿Ü.Ú«MTj;†µÐ–û•æÇ(ÖRhÊM y¯¨4Žã9H/íOá4óSˆ¥ îþ:—ùÁ±~Ó”ö¼¯ä&}±imõ|‹ä³PÚycc·Q\`Ôsí–ß%uN©Ôv«©®¾\^km † ”@,#­Ëú)½8RWg,®–H8§K/¥eßÔ%Åk>Ì™*AL䎬›AN#ù ú"X‚@™p¶4x¦=£ùÕɽ ªt…×ÙNY袮¦»[µ&¨MISÔÉpµ›5e--]î`°¥Þ7ÅDD”~êG4kmº«@Úuâ÷n¦Ôö‰§-´µ(¬ ¸Oo%æ‚w2Æñ$œ†pYä(SÃm«)´Ùæ°TĤ$îRJTi¸(žÊæÓe"a²N•=o12”ê8R7ct'·¿\#¹[”ÿñÔû ˆÎ!Ç^Fwmýx÷ÿö'×ÑWsëÙR5š9R—ÚÇU@Áj3MsömÖ•ôã‹gvŸMÂÀ¶wqƒ¸9ª ‚$y˜_X%D‚Q÷ãÇ8\ãªkøÍ)¿µ¯˜Õ¼¼“˜:bß@ñSkÎj×ÑÏ]OS ‰. |ºÓMD°†UzŠ›tÎë'ñ–Y£t*\?†¶ÛÍ–™EDQUËqJ¤’yåŠÐ´B˜?DTòZDsHó*N›N– rí¯8ÍE‘$Ê’œw%+…êT=E0¤3bY’ƒj˜•tóf¨º_©d1£†ê‘b*#ëËöDs‚~oû*ë^YÖÛæ§¨åEúõ¤ «š¦EÆÑªé®‹s%<0'ºi뜰pI -|ä·ÓTÔÅsÒ©¦¹_裂«÷bš‡»é«ÍÁ—[µ2E#$ ²«€xÉÒ^—)WK¶) š8ò¤lD°™“%Þ` wæ›Ëâ(¨(i%ÒÉoµ,TIäŸ-¡+så=4s7ˆ.!W¦ÖŠÄV$¼#¨ú™û(î´6ÿmÞGUÓGl¦7šýj$Ù©$•õ7,hjÓœ|gûM~Ç›‡¶ï±÷ yù¡ù½©ôÕG&½˜«tÿ0ôÆ Ö‚·HÇäšÕ>éG¤4…KTQÚoò_´$ôÐËl£ˆSËUU,Ó°ìײ·²?µ×±…–¿–þÇšÏPY¹)m¢Ò3󇘗k$š¬kþfTY£»^5¯)lZÓÁ¦:[ª­Ô×èc·³GA%%> JŠ*›ž”.[M u) ƒ÷0,I"˜eåæ]*)!™DÄ…ÿË:HóMÎIàý휃ûš¼A>šù©i €ÿÆ<ãÄ£V´¼ÊååîbE%U7.¦©#M  ¦Çuê0ÓÛëƒuy–|ž!¶Z6¤šºj¢>¹êteÞœFOS¥V—Ô–-ORÊgPéëˆò#'ËŽ‰$ œÿÓFImÒK e¸ÿ3 !få-Úÿ{η´*ÒXG­tÝá%l¶HÛAPçq¹Ó†Žex•z7”›ÃÒ÷Ý33«e}îË­õÔ«õcã[f¥´¯NNWÔa)Çpaæ<à|°¼;ÍèÏ›³i4î ¤›Ã’ï˾Wßâ›8ê¸[t~Ÿ¡ºJ˜´Æ÷b¸çø×sðœã®n0éi›ž©¦ -5iuå€Ýr½Òjû`PÌf‚¶ ·}x’&¸­àsÌANÈ”YFPÈxONÅKËßi +uK%=³Msqì×&v Ú)õD¶›vq ­¦Ps‘ÒNr;¼râ?ìþ§ºZÕ¢Z›Uú8jcRÈVzg4õøŒ¤ƒ46C)PH‰ej’ªs»_ºÊ´†¡¸FÿÞþñúÔ~ÍvœÇööYÕBQ)Ÿ”zvÍ#tË¥DúRD. û/e o°Þë__ÈñÈš ™‹PL.QyRÎô(ðßÛÇOÑioÚÙû yżRÕ߮Ӝš¼V­4uwNXøúvÙU] M<— Cy0Ã,Œƒ¦I‘$ÌÖìgME§ý˜ù­Ê]It¬»TòÛÚŸ“ô3\§–k”V«'3+µU«0êØêy¦D$ÿ ¥t†€µ†I>qÔPÌ’EH–{ŒÔúçº=æG=y%Éð5¹¿Ë>[³ÓЏâ×:çLéj™éÙZj[ÕÎ*•ž9øhÝL„($ƉsöÅþÎŽ^ ˆ«}¢ìºžº®š ¦õ†®iÊŒâ¦Âöó“€:«ìq’:“µ6“~ŽÆ¹É-Ö“þ¢ÉñŽÐÛ;+e%íöÙrô’ë8`„º·dÑ«’ÿÔ7ì²F´<ù™c‘Ñf‹—ºxE*£Æ&×hâ6#©°GR©Èã¾>…úŒî¥ýàö3ÿõ é¯üI§ÿt¨Ôoئ¤¶{[ï3ÔOQ6ªæ¿1.ª³kÊMl)é©*­öZhRšÛShäè¶³GjC4ñA,ÖNÕ5^Ùˆw;÷÷gñéìK±ØÒ*™Xßb_ùÁƒF=®/m+aÞ³`¯u7öÇË7ýLú¾ËYËOgn\@lfý15&°¹4Õ½èìzP鈚QÔg¥µOsÖ1¢‚TOD¡zš#Ññ¢µÔV²)ì+n)îнú²cбéïVXê-”2ä+­Ö¢Z`äøÌ¥qŒy­ °»dâ3 ÞA~.;ãÐlKÆÁ,¨ÊV9€¦ 2Ÿ•sƒ­6êÛýÞN³$—I,ô涺fX…%mEg‡ïþSê äE\ôªÔ`t‚«ov‹6ž¥£Ž¿ÔMîïK](h-IY>™¹_a«‰ËV˜ê/7f\¨"¦)ƒ·Tn¢˜‘ƒqzÇXTi@[À53hˆ\ívµóÿ]s¬J{4Ôöúm Ôö¸î5ÍT$3Ld1¬tS˜Q¥aX!^×:ƒHɤD5wxå¸Å4µß¼ËÌ‹%46÷IaŒÒõã½Vì`‡ ³2]½s ªÏ2ZPÛ”„)W±«’jÊÒ£){=2éÓ¡EW³º¥w ÅáÂ{Í¢ÑK,—eeÚõC¦®×g¼O@”2ê*ËEd5X©)¨§’žÌoü6$¤dôp^¼¸ßæÒSUÓÖÉi§½.‘0[í}4ŸºîuécªJZÚp²øB |q…È3¶ü¼Ä;ÞÞÓE3”’\SŸo„X<ˆÒ–]Í­Gj»¤Íi¾k»]¶é$2¬5FÏEQsŠäÑÎñ¸ŽE¶Ö9ÊÁJ+ ÅSqÓ—‹ÔºìQQÉöƒXSÇo–«4ôóÑQ6¡©šD•×ã…1Oºç|“Ã.‰e%Ô¢¡ÝqzŒ-+WLAD¡osˆð°ír·Y-õ®ïu½AŽßEgª·Á‰*émTµ–{]MaHËÊËÑLUzaÛ©pK8BTéº Î€ °ØžåCz¥¢Š×[R|7¶Á=âè•UÌ*ãi|FÄ „$ ”`¨±u‰oéé¾N8dD×Xj›–›Ö‹-T4ֹ씖Y­ñ¼1I-U]CTI3»³Ô¤ŒåJ¨9*£<«mSÜ´ç*íWZŠŠúÃgºV=]Æw’¢Y®:Žõ$rK<ï’ Eœtª°AÔq6_po¦ˆìRÃÿHõ‰E¾’*þnÌøo.·iúcW ñ[n±$nÞ 1(ðÁÞ0¸õ¡é=™ùvš‚•t¯%iµeêžÏIJ—ymz–¶’²žO:ʺzƒnbÅ£’@¹ÂŒž:v$ÉRfÌš¸ Ï€rïà1â#µ&Úeþž\…(tOwî¥Ü7bpY=“4mëCêûE-WÔA¨&Šñ¥¬wÝ)ªîÔôV»`H¯ZbÙvž¦Š0õNÏLñŽã:¿j—³'´?²o8¹‹GËËG.urÔhúj«ªËWe2GxÖû`Š£MÛä‚–vz«’”Ó™3H¥Ê„n ¶Û&m²b%L)ƒ‚R((饌n±Yír$É\ÔªìĦ¦£ ×#¼bñóRÖ_ÿ‡‹ŠR¼4îyÓE,nµÔöúŸ•¥’„ÉQÔÔ$52°Hzå YÂô«=þØëÍ;ËîGZ¬š†¡hõpÕtª;„0]f½A_ªZß‹WpŽI¡ž:Q0I#‘[ø¸$€Ñ¥J?âPî`c¤CV„^(j$HUîm‘ßß{ñ£êÝÊýSÍ®dSPjÉìúÞ«Dj ?®d¹,ñÙì´Vk-²ßsŽZ¸iâ?ݪ Gðë Ä2£äñ•%—J^ùgéN Þ?1GëSê›W-­«\–½CiÓ×Y].÷J ¨ÔIÒß j(ªé=儯¥¤ª¤.à´jH“¥}ÿÓ§®4ö«ötöäз:ë]eÃZó/\Ú…6–­¶K¨­Ö›—-¬ÖÚ»­Æ”­Eu,ò7…MQ-1 ZºW?ФæÌ’ŽŠ|Ω’°¤ðR€H'±LøWP3îÚ$ʨž‹«÷$œw¤ô_ÓòŽç£u–µºji¬šÛOk*ÛÜ!hµÙæŠ̓PÑÇOÑZ-r/‰O"åœÝcÃòìe?RìùÅM~EªèjQr‰®}%8âÑî­ÛM)úShÙÂ/Ü´ØR£…U*z’Ôg_#GhÐÛwíyhö‹¾ò:Õ«¹gËý!ÍË­EžárÕúïu«›Pi™5¥–Ëeµê«Eåü[kRIeº½¬%Yc¬¨A"ôt7‰ß³—”ú›žÑš_Jkª[ÊËp‚yå§ ¼MexjJRÕSÊõN²ML©A’}ã ’½'ÐÛæ.EŒMA],°ìô3e¤Óˆ$ Ï”ymœ:j’ªÿ"r…@ªd­C¸€ü£sÿhß!9%È-Ë{ƈ³UYµf¿$¡¸jÍGvª®ÓöÛuƾå$6ëâ+< Y ´=B®#j¨×,$ÙOd^Hò™ºËYÔÝtÍ>±³iyuý>‘«¸M\•od‚ÁÈmY¥g’[¶Wk?0u|­Ð£¯÷À•}ÖâíêH¦³Ì–5 ø(Œ=#.Î9ViÀ-”©sI,Î/&œÒõų‹S™>Æ>Ï×K8õ rޞݩ4ÿ.5f±³Ý´:öÙMîÍd¯¸ÑËp§«£†š®™*iÒIn—tR@ɲ Ç•öšä$öÖ–u£ÛEéç$}U1jI{DÛ­óUMO1Ц Ï:©Eé_B®Èê(¥$Tn1âH}Ü<`ì³&L–¥-WÈþQº?AŽ9Ãл¾!1ñáûpïRÒs6›NG%!‚£˜:ªùY"½tm«—pÒL2õCJÉx¹2%h>ÌL­âå¢|ÉLT£FL Ñ´yyøL¨T>W¨Ÿ=ðG—m!wHÉ2Å8K@ôÖ1·e‚„‘ƒªiëíLÿ°›X׎`{Fh5tKUm›NjÖ§0F²=u¦²+ N$éêDè¹Õ©^¬7ÂÌ ñâç´-=e^Þ-´b©M³œ”vêˆé Ø£†¿SRL*Óz¡f„>ðòÄ?#`¦yg¨€r¾Uh”-¦¿hMÕ!’dýï¬ùQ A³øÑf²Îž„”'ª(åÅC?ñÀŠá­{FÍcUÉ«y„ÃŽ ƒÅ?©ÿhœV›µ¢——QPµÂ’íQK]yÔö÷¦ñ-Ozy`ŒÓËâÉ× :¦`î¬Q^»½{~ëénÙ¨¥åÝ®íWOWUEl¢y«®õ´¾ú’ÕÓÛêêæ’¢$¤r,]« Tñ¾NÍ*QLÅÔd1ÀΕ­QË·JU&M\Û€ñ8†x©ožÙ<ã¹ÜnA9¥î‘Ú©j¾ÕAa¶ÚVƒvu¨žµaáaÕ"ŒB_ÏÌ^ÑžÎÜÏ­Õü¾ä¿8lÍ›D]*©êÿsoÝÔ€\îtUTzbz e5%ËLRWÑMK ´†¢>„©•Z0»‰ÅØæ¢d„ÜX˜%ºIÇÃPSR¤¬ÞM׬xy§ô7´':¹Í>Aû6k«7*-ÿkokM%­ù~¶RÔ6ÒÜíæ.¤­²Xô¬–Y*ªõ;S\©"ŠI.ÊhiõO/¤ÛöIê?iÚ_g~Oi^xZ´æ£ÐT:^«@ró™– à¸Öjk/jî¶{£Ô6ÉÄÍ\m¶’ûÌUo¦ŽŠ¯¦Yn³Š|•Oì䇒¤€9 €–l/)·¾4¤lž”]ž•“ÁÔå‡b~#ؘâHººÌÌÇ»± ÀyáN; 0aèçõAéÚ]7ÏN^몘Ú:MOÈË<“T$e™ët2nv5~ˆ9H<ð&ùŽ8ÝUœÑ„Áÿ*„j³E¡ 9T¿úÐ}#åƒW] ]- ¯q3bžÅs£T‰<ÕZ¦ór ¥ä-îwŠ6ÃÀ\“Á­©¨Ú†‚?I©+5²ž8£ Ms§oÚ€‘T'ˆð^)äUœã#§øö´FAÈ;‚;ëÇа'ML\„&QÿÔ¿k´jÿÙ•ÍxmÕ•³rÿör6ÉU=%`§÷K72hµ&™¸ ¡’UŽX䪎ֽlz“èšEig±m†.U{wþÔUEqA«9Èßi?k’)b™?õ—÷;n´­CÐ#š톊¨© ltx¿Û:¦‚CU:€³7ô Ñ5»~ò|#æÏöãó¯¾Ð^ÑéÌ.\óFÃAfå^—^Ks2áJÛW»óJêíYUQCAHÐ4µMæž'i6éVU'4zòëšzÒ/hçüö*Êõ©K}Ž“HÚRªähʬµ4·kÅdè!™]$§_®Eê*Èê>±³~¨“bØ›'fÊú{q*˜B›ÄÖ¸¤|£ký"«fÞ·íkwóì¤&P+JŠ‚%¤•(°^ŽDlHö/°0ꓜÜÞë;¿‡rÑñÇÖwnˆÿ±Ç¡3œ œ ²xç´6™ÿk̯_þÜþOl_ÿ³Éÿæÿû‘õ-û¹ÅÉö ö[Ñ6þié&ÕZ’Ù­VϦnQè] }ºÞ)umÎé}¶Øônž¯h稆+ÅT±,•W Ò*ºþ™'eOeVŸnßx¸ôýmÇ6\Ö•)‰ê¡"¦ñûS‰Ì÷>AŒl¶¥í–• 1dr½ˆˆÿú˜âåíÓŸœ˜§ÐÚ2Áoײh]rüÆÕ¶û= ªóªë-:“EE¤©µ5Öc’íº }ÜRMRò£®™ˆÓ楲YêB<‚ùYï’K$TÒmÔ¡î¶‹ŠªºsQ4?¾sЃ¤šgØrrÒ©³V”õT£NÚïÆ§æ=ÌQ]‚ÎK¸¼+¸)‡c3pÆ ª¹W\mµU¸êŠõlJz (Œ4TñЭºåSKOG|H•öJÃD²éîuÆÇJ4朧½WÁeŠ‚Òôu*ážä½ô½‚‰»˜§£®ö$„%zXp’àhíÿLoJ‰! fÜé¼Aê¯UÙ5-²ÍEwz ¦£µ›T ék¯b{…=¶ 6j(Kn2­üBX. æ=f»£¿Yiù‘K(šŽ‰ê)£E²ÏâQKS=! ¶©:CULÃÒpìxMœƒ.Ò©!©‰é7™ ‡rBp§kÁÚ¥± Îf!¢¦&ñ•*&¥û;®µÝµ<µ’[¨%è¸i+=ª’I”CN*«otà ÀUqH’;z‚ŽÇ#3kÌ:jCj¤¾]ýÚuM-¦¤ešS]j3Ûí4L‰ -LŒÙP<6î˜-ÃórZ£™ëq—|QIMHËñé}A ÅsÒ–q ƒTTZ/ÒÜexÚ²¢°ÙÖºéH!–OV*©jÍ! 5MÎû©/ztÁ=Þ¢$Öf×k6ö6ù  JJq$jb¯8v¯eÙº±ä6à % `ôÅ oŸJFWxiÍo5«ÕWΏRPõ*ŒÉ ¼TÔc>˜¢‹ð9Q,Pjm Š¿·KÐÌ»l‡÷mMisŽØiú¾ýø‰îÿˆÅ»€ü<õŒmšrõ>—¹[…”õ‹åºjv«™d†ž‚êï.]CtÑc ç«áœÏ®:^®ZN …Κ÷ŠÉJ±‚¤VUÍU[SáE$θêz•zY˜¿`qÁJõE“s×§ŒÎ>C_ˆGN]tôZ®¾{ ÀK¯à©»]iU¢j” «†¦ S3E=9¥~—¨à˜H« ¥I4ó³ÚŸœÄ»Ué>fscœ·Ò* £—M\5eE&—‚jÆu…iôÝ®à–øbu/2†OÏ1}P +'¡!¾wúÁ¥)$(¤Ô'í‡tEt·'9ŸO;êÝj×JÖJލµ‘«Šš²ÙW+PÏO<7*içH[­¦9ã{ìþÓüîÔþÏZ¿”¾ÒÞÐáÖœŸ½ßt(°s;Vê-^-õŠ–¾ÚÒß-Ê¢á=ŠºÚ)$_Xã›ÃxNÈù'YÇRdé!E$.¨8ã%Nª¥ô”!”;œ;~"±¥åv”׺’Ç¥5­==–Ÿ˜«Ý†¶§À¹­ÚgÓVº aWŽjs'…4òdª³§GK.rÄ»-õ¶nK5!§«¶h˽=-á’¬BK6µªˆÕÓÒM*±˜v%ðøÆLÆQrÄÝ'<@ á¢i@ãÁ£ÒªiÔÇœàªà67ÏHé=Áù}xó;SÇCqæß´«Ô(hdÐ7:J‚@pÎ/šR•”J†R6ê º¸D ë æ“æ æ–KƒƒùEO ×›F€ä•–÷r³Û«/ú¾–ëCo¹½%=Î …æÏLðÜ(#˜{å7ƒI(Ì‘²)r2·úTýÿ³ß“<Üä‡í.ö¨æ+î×}kÊ_~—ÙÛZØõ.·Ò•šsZÚ´ÿ4/º‚¢À4eêžZ›½=OþŸÌáã™ H©à¼RÏ4¦XZzF)UàAÀ‘uË-ZÖ±-JE’ÓÞ<Áæ¿1µF©¾iýS­/—S«.¶»L·ÍI©®u·­Ir©MEªi3yº\îé-uO»ÐÓõ©Î†PÊÒHôέ®¹E¥Ñ㣙^ÿ©¨iíöHä– *멎WjZ©tˆiB;;TÏ”ož˜#‰Ë³ËRA!2ÂX(t†`@#¾›Ù =bSa[’õ2wÎ= I#ÚZÊ(ã§£’ÍËmH¦²V……?þ›êl[ÅÊA*Å,ÎÞU”/ R^‚—ÿh/Ú«©/ósÎŦí÷‰ítœ­[âÑÏZõ¯ÞïÕ¶÷œÓCr©Wªh܆K+â% #`̲›»I!Þô”?çYl¨*Õ%·U÷,•Xf›3òʯ?\ËS[ô…’ª®ßÖ£Næ’²´Ív§åü•(äUÔ…#QÅìZÌ ¶³—ƒÇöÛ£ÔºÊRTêßݶÐÕó´ô.BŸ‡÷MÇÛJE!Á§û?1òð†Ëö™w7ßÅ™‚¸ÿAÀn³xd37sã¹ìûOn­Ó— ˆ¢¦­i+ÙäšžžÛ{x{ݯPu·†cSýö«ìäH:ƒRÃGÌûí0ꡒͫZSÛZ•×mHh©ívt¤uɉ/RZô V#bNhj8¢f.gQ z¥éæÂ÷ý çeK)´Ï]Æ »[ =KÂR_ÿгL}ùòÝ‘ùw ž6FGÑzY‘£dhÙÇBU‘¢–Ed ŒwRÎÃüäÕ+O²‡$ Ó¤ßú¿pËTE,Ñôf¤ê8gˆ–ìAëÀÆãÌ@®²91H¸WÊ> éo× -©ª$©¬2RÞ´Ö´µÞ!†¤–z­?S-e¿ÅjÆe´0/ZÈ…Bý¢£}4û#t×û4éI§šŸÅƒS_!I&«¥iY}Þ†t#]ÝLsP ÂFªB€@à©h^ÙÙsRýžÔæÓ¬ÀŽ×˸åÝ·¡röÖ”£y­vX7ýŬ‚ÏFfÀ¾øðëö‰Ý.ÛPÛjnRÕQXéù-QµLU1[©+nVÊššji ®œENn5µ“àÕÈþ4²ký‘÷‚=±t5™¢šåCea;H㎟E\ Ù»¼ÍLH ~´l ã±mº­™4ì«Ý©RHî)üÇÀJ-®–*AOb¥¨øÔáWí«¢kg´'8Ò%¯å–¨§è1¬1³Qj‹ÄÈÝ+l§ @®;ô?ÚûG$æý–—:zˆ5Ý KFkf©¹Ç7 ªYg–›ÿJ¹$q MæI ÷z ÆÑ²t/Z²˜—6ÐQUŽZ‚~éÒ‰ßIÈsÁ™Ï½œ.¡aÜ <þó)MÚôñ@ïÖÚz­=ͪ0´tÿ¼ù%Ìëp‘ŠÍ£néuÀè|/ÇÂDvXݰ¼S_³ÂÛo£¾{0jkbËM|¼{sr^²ûrÕIq­´s'Û;IAâEWQ/ºÂtĶJáPÅDÂfEªj‚ì¬ PîIó³P"xS•¸æéÞ+x¼sŽÂp–>#mÞ¤´Õû]ݨ¨ÉWJ*£¬Ÿ«¦–ì…R¨ Ôe†ãMw‘Ó‰²Œs¿”ZuÒ{•£¡"wjÊRT ?¾*€™¥ €zryóLPRIÿJp׬t,À¤KWŠÎ]±ïwìwÔ¿¹}µimqÖ›}.¬Ð7j¨R®Jzk”‘ÛowjzYâiT·¾PÓÇÚ½=ϯgkÜÞõEOKÍUV×UTG¨)bŽ’“U^íòš™_—ô1¤qÁ_ãILX4ÞeZdZ’±F½PæŒÔ.yg„2ξ±cRÕv¥1u eçm<Áöµö[åBÌy“íÉ-,^%£æv¶\²­²Çk¨¼ ™œ4Ñ”‰›2¨ÆXgDù™ûsÿf+äž–¿ÚNݪ®Tà¶è]#­5¾U]|šXb·Ê ° ŠÌ`ä8èªÕ%$¤,-Cž±ql;Z9I‘5BõÛ©9šÇDZãBu÷ýR~ÃöIÚ“—ܲç^¾dhÄ÷:m%£-òt3«¼s›ýÊs1°Þ™[8Tž7ãT~Óëm¯GÔëu³h'¦é(`®¬¼ëPÍo¡†­­ñÒµMT>ê±õOq¦@$ðØ´Š¡z˜/l‰U¤¬”ô)C}ÌíÈXçí H°ôIJzuÎpvªÃ ½îæ–¶§ååû˜-_®5 Uj-Ut­¬¶Ú¯Z²ëJ*ª.WÉ©m²ÝhÖª4ÁŽ(Šê$U‹fZ6ïOËØ*/ Û¨´åÆ¢7£z›e%eªåR†–G¨"¤A5CS´µ0üLæ69nÖ:RlV ‰rBÖ*£÷¦÷©¡ÀQãÍÚ6žÓ´)*™<È”³Õ’îc‰$·tyçíux»Rsê Ew¬¸K] i Djj«$¬¯i,—(Ú)V¦FêWSgFÝ0´LMj憶T÷èËVQVâ©G¼ŸÞË}T«ÒC19óÈ9b¸Ñ½Î«¡µLPU ¸£§³Èij¼h¢ç@fO®["j©„¼RÕ¨ yå›a (L•gK–B ÐÏÖ$+uEÐXÐEqå[B¡£½j*K-E5;›cY¥_ž£Ý SÍV)` å‘zWá$£Ôpß§.”õú`M¨¸Ýhƒ\ôñ1\Çž™Öž–º÷\Æ·ÃÁ–&˜¼Ž¢ÇL`hǬňݛûÁK²”ž‰ÒЍ¾@ô,4k}‚®+Uɉ©ÜÕ©¯‘Ôx€S\¼Ë–5÷ÈDIÑSïU^ *~ @ ý …ÓÜü“ÙGMë½Kt´hwµ^‹¹^lvZÕ³ÕêZ—Ð\Ф·[$¼SÓ¨¡©»ÕÛ©*`‚zužÝp¸FìgziiüæÒJ§Ù–‘0Ê Zo(}Á= v9*0ño³?–©@µ&YdâYjfï8ÙþVû<òÛ’õ+-¬§NéÕ¢¯4ù¸\î”\®:Žé©ªntòÞjê&Š¡î7ÛÃ>%½èV1¡WËï=ù/¦n«=ÿšz ÕzÓ°ûÅîÅ[ª¬°_-´ý3¿¼ÕYä¬1StÓU! {¬¹aá¿LBl»6M¾ŽS›®I4K°%É, ÅÏtZŒÛLËÀ^S`È`(´jO²-¿OIÍ¿Ú `²Ýho:TsóIëêimu«[g©·skÙ㕚‚JêF¤¨è/W$µ’I,l¦aáÈŽ‚$_³ÖÇ]¢¹)­9W=Xª´roÚŸü¯Ñ‘{½<»t6œæEæ])kQdHm7úŸÃ*eÏfdβ©'ª¡iFú À‚ Js–ËHyv‡ ¡úunû¥WÏYïgã¯ÈNi¢§ŠYç‘!‚Þi¦••#Š(Ô¼’Hì@DTRI;2xøÈÿ©_˜|§çß%}ù·Êqd×Úfº›Ÿ|¾í9T&‚;†Ž½hIu¥ÍB#!Jíp å|9’ŒË É Y ²|¤*D•,&lÅ$¤fBT¢9w=ÝaBŠÖ°—EÕrr’ ;±ñÓW¨mrroO¥moDô:—VÛ§`‰,Š•–=/QI ³7ÂÒ8¤¬ò%ÙÈ*Ljԗ!AÎnVj–«…(¢‡‘wŠÑâø~"[ôÆŒ‚í4‘¹PѵMo[ùa”öÓµ§ê;"&NZ„ÕÍTÅ^~ˆ…)ErÒ ÔŒb¡”y¤ík<Ý ‹2ìò•³VR„‚‹¡€+¼eÖ•‘é‡??m/µg59aËÝ9Í*ŽVó>ßË®{òGœ”j­+™Õu—>\k›mÖŠ’+ž”®¦·SÁT’MOPÿºO¦O £ü\GùÃû|9ý¬=®õ:¹YËýÊ ·2}—mœ’¾RÉyÔZ°ÓRiíu~Ô¶½Og¬JÛbÒjÚI¯õ1Ã;S< Àc$™ò»?ø·-jfØå«iÊ—ou­*C*É"Dä¼´³©]"‚Ø šxô?ØVDÍéÞJBh ÓgW¬^€¤5 Þž®zVj{®¥¾jYÕõWö¶ïqÔš¾ås½×UÞ+õ%â¦ZËöH¥"j–žbîUX¹,Jž5IMÝ*ê.R´òÝ(©š–ªD”´òªº†ŒGlÌc£¶ôý¿±dϵڕk¶-#¦I–” k b”]¤©¨’]*$‚Z<¿ÔV$Ym³e¢ReJ~©½x©$&ªrÎ£³(O8Ї1õ8jZr)Öá\VbB!R+7 >þ㪻TàµôÄõ€KuÛž1ÏJu?íéþ¡û&{Ió‹–Üÿöc½rþ•«oÜ­ÖÖÊ`£Š˜Å¨*.šœ]n7dDµoXY)¥3K{­<ÒÆ‘¤ƒõܰÏWq²Ú+îVÉìÕõÖÊ ºëEL´óÔÚëjibš¦Ý<ô’ÉÓÁ4’Dï¼lÑGe!Ù,SÏéKŸßL?¥#ÐÕçOjÈÉP©7‡ˆ>±ðÿRm«EY=¹,v¾_Ôj'ŸQò—Nê~`Ó]5F°¿ÒTê»Þ¨æMµ’ÃA©n•1ØìâÛo·1£¶-5µgšYc§I3·ÏÓAE Ï|¬®ÔòÊÔTág¸K›@ñ"dS·e|3žœã$gX"Diõ”Uµ}+ñf¢ŠÇ)•Š“Ó#n@>}ˆNZí—NViНSOQ-¡ìU†;™¡§ik­IMUWýÖ–t ³†Ý rªòûö«{r/Ùç“ß9{EµU_y‡d´ÏA5΢ïh1;x»4‚œÒU@µç!ÔZÃmÑÖÚëMú²Ï%4÷]UG_¬t½+ôG#¬‘κ¡úC±Gá9÷‰º {›\¡ë!‚T+Xƒ\Ï*núk—³Ú¯W+ C]/UúO׊Œ\)N¢eÕ--<á*}í ªä€àd},þÃl-sËgOi=5Sìõí¬4O,¹±¨uÿ6ù­Êë—/ozKKÚõšÑMN5F•ÔÚòÇrª¥Ž‹J_%zš®äCXù§W.&Ò‘iµÙ ›<Άy.äauÃîÇÊgT™S§9—tÙòàkHò¯Û˜š_šÞÑšÓ˜ú&ª[ž–ÖZ®¿Qéú³CYK<¶‹¶¶×µ´«5 E<ó[ÜEQÐw½+‹QžŸ´ ¯ >t *tâ8V‡v`Ù}[îæ>¬?ho·ãûûèdÚ4íÃQë={§lú3—õ5¶®ËcÕG—Óê*Ö¦7 I«³íR©Ë]$²JƒÅ‘XÏÇÅßµçí‘çg¶œ±i.}Úy}ªtÞ›¼Ï|³Y«)èíTf¦XdÓTÖÙê—ÀêP³Ï*¬Õ¿¥'¤HRUPFO»ºª©¦6꽤´<5B¢›—ÎÔ•T«ŠZš½9ûâª?ŽfYoº†¤n¤«aWá;›ÿD{{soHrê–é`½è¨¬µüÙ²é7£ÇcÒÖú û,•rEM’çEN)‹–%ÐeÖ@6B‹è–….X!H"òá$1³¨=H£B&&rŒ©ó×rr’Vä”›©PIPÀ©.É'Nø¢}¯®«œñNsÒiùiŒús•”×Í;OWtºÜí5KSéúzûƒ~ð2M=˜Ó¸—ÆE:ü3G„’X×쬼Edöéäü•û¹žã§ìñ9,s5ÚÎÖX !&R|CV#ô©r çÿ7fO–êeæÔ/)?¥¶JR‹"]Òüƒeã£ûu¨Ö›œþÏUj¨ F’æ=3˜ÇSS]íó0!SÿŒóîsÕÜìß쨻Sÿn5=¢™jdZøtüW›šJ©9 ¢jkR(i*éc,¶‰À,ÊBÓ©ërƒ ©ælÄ’¶JV•“5*nÐ.œHÆÈB/:oÞ•1,w­ ÓúIo!£×Ê cÕVj Z‰+%†·Fjj9㫞Y ­µÕÑJÉjzÕ•ÌUH*ƒÃõ€é°-Þz[7³ÂI–¤öÐäEj«¼©ü+Ï:êjʤ.¹“+ÌØ›F]Äù™”9Ë:bJ¥k× wõ¨(76ÁhÕ³’®†in¨änŠå§Ê>ù¸çŒ0Gç¿ûVµ$5¾Ú|Ô’ŠíeÕúÊ;BšV†Jz(ï6»”–uWx䩞¶^™@•GÂHtµÆh+ì5õ0̱þõ¶ªÊiçÊæ¶”‚’•*Sª?&îFç9¿¨ì:/Fi+&¿Õ5Z¾;Ebj …ÊÚÚ†¢ƒU­%EyºÓ$•T•“Ù…*¡dp‘ta™†ýç$F`‹ ÷SvèU¢Ö¤­r€è w‹ÏëÇ|hõ>yŨmUŒk[½4Æ à‘ì+ªŽšš¢†=AËܸպÊÆ©»_ô¢ºóq¸ê*{t×¶N%u]¾õWEo’+Y™&0uT91EÒÕ•ŠÞó2Q5I´O SºR[‘"£“É ­öY#gX ´\T¹‹uèBHlKƒU+ÃíÇRÛëahãž³–Ò¹÷yDájËQÕF|D¨›«øU´àÊ\æjoh­Q¦µ¦¼¼j!xýýd¼ÙlÔwj£¬ŠhÒÉC&:¨K%L~ïOFRÊÊÀ‚G›ÊQŽíó ³$&MœfGŠ2ËÑ_gMSpÑ¿´×’­KYq¥¦ÕÔoh¹ElŒ™ë©îZwSZ¡‚T\ß!„¹ØB{¨âÄý£ÿ´¢óM¨¦åŸ³Î±Ööª½=yš“˜3߬Vje ­°Sij‹jiKLM]n¨ýçÍ+DŒ’¦¬Q”ÌЮªæ¯Üìa(³¦mµKP fìföÜ<{ûq^yÁA ù/Î «¥ÇZiþf[õ ‡]>ªª·ßµªçG5=›U¥¯¢Z—†®jÈçî4ˆh«)£™&éšI=ƒö–ç<ü˜åý[Ú4æ…Ô÷ªj»e5%£¸.+^4òM_hµ2UD¥#ŠN‰á\Íëa…86•¹>Ï:zÏ÷I*q uCœÉ£cº7Xvgëö’Ã,©"Ó2ë€÷BÔÐ`3zG•Ÿo¿hë­ÚçÕGÉûf”¼Xh©å¶6…»]nsH`¥§©–+ŒWÊ`‰âZ¦ð’WŸ¡§}/Ð~Ò.cX´íúª×I¥®Õ¹)ÚŽçU«!†ÅAUd6ÉuC­Š ´÷ }4±Ò¤rJà3 Ày™»ϳ'Ì_L¥Èe‚¨\I¼¢š’MP†&å¿ýLšßHÞ—Ÿz‹IÖHôÂzË•¯—r¥ž­–k¡£³Ý(¬²¥UEDÔ”1º¼H:xÕÔ£´ÑèµÇ µ—·Ÿ1ù«ûB¹k曋ËýAÍúk–­šž’¶ùª4_,*9³dµÕËxV³D/zêÿ.ÕÒÛ£¶šHëª*¼+e6}³:q—)SI´~œ•K2.õŠ‚AÎë6ÜË"L2d©JTÖ TMo$€¾ÅéJGÖ§°ö¦ÓÔº„h;Æš—KssØ+Ùœuö­7%º {ߨÿµúÓr¤´[í”QÛq¢­ödH¨¨c1GHÂŽÚ£Ú¯e§Ó|ÈöÑå»´µšoÚb³Z[kjy*%¦ç?.´'3ªèå–y[ÄŽ–ñ}ºAOJ¥B§,ÅJ¼I2}@Ô`îØ;}º½»}£¹ÕËnF×û#Ós'Ni{®9“ɽmQdþÎ[nWÝG©®–NRèZHš®‚áS-L÷÷ݺæ‹CA–Zª¶jš«u-ñ[öµ{"róö{{.[ô¶ö—›<æÕÜüÖ—ý/j†ž‘k´ÿ$o<˜ÖšCEÍr´ÛmTYë#¼\Ú ª¯àÅqý×PS-Þ'š‘6Ým¶ }¥ “Ð.H蔂/„!!CR¥/ ‘@ñÙBlöyI”…¢`R&ªúH#¨U1ÍÒ”âÈzò£-]-×wËU%GUoö×MݨXÄJ-íiÕ”uÓ!Bþ$BxíjN©¤Uò_S[^å⦩þÁ£U¢‰,ÚãZÛ Àd9 ·S¢áIû8cv”®vÍœ³ÔP– sbAl±Ê<çJ‘k–‘ÖÓ‘ZU\Xåóz›…¶¯Z×T^åŽïku½½cÚfZÙ¯5P[äµÅ‚ ‚ªjy|6UY (F!¬¾Pé›n¦Ôº^IÚÛn»Úæg©HQæÍº¶†¹a¦G`»ÆŒ˜91HéÓñe|FÝÛSöÓ©"Î&ÎÙ¶iÖ)D¥*¸¤ °pYÝ…2Â;K*-{K¢\Þ¬ùˆEðÏR#}p©|ãm)ù! ©(e¡š®íQC<ÉPðŠè©à eñ!ZJd17†ÝÃè\uc>ùé"U’Ë%l–)vYh)dËJP‘‡íHc”#ù“T¥Mšf©@Ô’NYÌ þ±Z…v[-´(ÙGŽçlzvù9ÿT¿é1”0Æ/í˜å‹Ñܲ䮅ӼÚÑ÷-eW¨}¡hèj.œÊ¼[õmÛLM§©­Íq¨htíÚжšêZÚJ•§¿T¼kD~õÇè9ûÿj/$¹Ëìk©æ·4+¨¹ì»ËJϪÝgMs¡±QUê [F¡ˆ[)<{Í v+>3GF$ˆF†_&gÏg·Êé'ÙÊÒ•JJ H5$K—¨.üYéí2ºDàëÿÝ-àäGÉ¿íÇÔz#Q{pßõ—*9Û¨ùǦ5^‡ÐWûnªÔSÙdHn)t¸M¤ìÚ´õ²5ÓÔ4õmM»½LrÏRk*j*dwãÇ ‚¹˜UxQȪ}æYi™d•¦‚¶˜;4 t‚+ؾÀG³n£7kÚ²Qh‰S/%h,jR¸º±È?8„Ë—)( Hf ( ?Mp¬f… v¦‚¢¯¨ÀA‚ «ýò®)™äÿfaU±Æ<Œ‘JÚ¨î×R–ŽJŽ¢Í’+xF^ƒ,¯â«ˆá•iŠ1 Ý`¶ãŽ%ŽÓy{NÕhPHR¯> ÿ¦TŠAc1D±UNü°Á¬Hî—ˆtÅ\VùÒ’íY¡˜QT´’ÓÎÞRfIá =02¼r+œ@ÑÌýnºÓÒ#S^"«Y]b¦†h&†<Æ’Šñ‰5ÃO]d‚K¼æä»Xz#£n·5”¾ùIo‚A nÅZj„RXôªÆ¿’OUš•(jì”ɧ£Yêÿ~ROUX`I"¨÷:JÊ‹µ0…$ëñzU—•c€Qìö=¡SìIR‰RÒ¥I¯Ü=·fQ¢S” ’켃úo‡=0Ú¯WiuÔ*ó™­4—Š«Å=ž•–ŒX(%¯¤Žzåoॎ¥©¤.]B«Y%®œÔ//}êiªä:º®´=T²TÊ Ü¨q$ÌÌT `ûcnÜuJo\rô¼§Ôwç• ä 1úá¼hÚnüê:Z«TÒ³7ú„t¤¾øñÏ—Ÿ¦Ú¦ñ4q³"iiéÕ•³Ø!0 X`yž®Ü }¼„G¨<¼„aO§o5Zn‚Ôi^ ¯ß7ÿªEV™ièˆ7$|lçÎN<øÉ¦f›VR\ÍlP%– ?L`XŒ3RZmŒê™zöF|sM)…G—y×£Ráñ òÞïC¢u¿Xiº‹N¢Õvi¨oI§nnnVÉjiîÖê¸!¹Z­•pÔM¾SS)AÛœÓÐ5•”u’ ŒM¨,œÓºÖFõuÕ´°44Á_Äuñ¡Z4eož=k¯¹Y¬o5·»Ž•×ðVÖ c(¥¿Y §šXi ¤–¦QWf¨x¦•àj‰2òuÏPã(„=“yi¶Öå¦rjù©',«Nq×´ ¢Î3T¤[pn¥`Z{·SC§­—J'¬®‚Q|¹RWÔÉ-=ŠO#ÐQC#Fñ”brH\ž#T3ÓÅSO$ÑŠ(Ùˆgž¯M&–tW”¼@VE™†z†z7T hT*´ l€øî×kl2It,´ÕtàCPµ4øJZSW§fšãlÒ¯â[•†Ën~#ÚSYQ#Óé„ê#ÿ½«To†$‘0c•`PSœx‡+Øðb—N?ˆ\j…:퀌±HRB¬ÍÐÞ:FâÆ3 oµÁÛ↋ÜôÓáVC"1’N¥ БÒTÇ~ýO梬1Öè´’±ükB&ÚJá $uá|}Q4~$d™ ©z‚îK0Ìb0”bIÎGÕw±_´³÷-½š¢å‡35V©¹_õ>š²Yëï5뮚ᦴUÞ¢¾ãk·H¦ì”ó:S=Q‰)J[ AoÊœsm •ªuû 6ЃMÅÈ.Ë*ViYQí•ÈqZê>x]yáÍkÏ_IKk¶húûFŒ°Ùh+*먭öÛ5 Ú%jz¬œ§«¶UT‡ȵ*è_&FÖeÙy_}¢œU£Pêëõ0JŒ¹‰$·ÚjãLøC V¤7mÌ…°3ÆÄ¥ž® R\ã‚kãXȆ @®¨¤v>=чQ[ôç·o²Æ©kM5z³EQT×Zå*#VÕwiciáHJ\IöIG#­sž5ËÛâÅZÞ×<ü»iË„w-‹XÕu\*¥ž¢jYi©!3Ó³½U\•5°ÍCQòË*‡›Äè†<$LÉ©LÄ2œ”(÷,xeã”\°oÍaÑ΂œÓn_ó’.[¾¨¾Zî¦é¨+d¦§±ï5¹eŒ=]jÔSªË JÕEQUdu«£ásǪ>ÏÜíæW4ô}6º¸S×Xä±ê¬4w«íeÎÆߦn6Êk­--βymz††šÛO3ã=(Oˆœ|ø…*x³Í·MµLL®‘äÊMC eJQ¥ à¢4Ä<}oøok“;hY¶l­Ÿ%jæL›=cù‰UðÄ.ݸ’ýÄäaæ¶©ºLhãðhA¢• ;֢˭cÒ™Öœ´È}稂æDQáåÖ¨õ=Æ“OÜì´µW'£¸ÔBµ1ÑSÍOICE8¬,·J„¦1´Í3¢Å×*0Hçèëfeo›lÔ%vÙ…ä%i_X²AJÁ”X‚ª$5T@ëdÚ¥HÙóîªâ–’ž 7ˆR.Cj¨¿Ú–¤Pš«SþášXÿ´‰§²Ùªën0Ç%ÎFy¥¢¹ÑÐC7‡îÞüѲ–Wª%DûÐ+‹·1ô09o¬è¨ªïZΆÀ×Ê:*ú;U=#ÜmCq«4õ±VÖ½wG»ÎàfÜtÉÐS(?Alí‚$H–'͸° €Cë”’ÕÄ9HcP ~|ÚP Ó¦‰¯K[$•¸'ª”’ hà˜Ø-mÊ=Q£®ÔÐRTÞ+î÷]'u† ô”ÑÑ «:Îg§•­4‘øT53jˆüP±ø„Q$—¢û¡ö¢Ò>ÏÜ•»h­?¡5uºŠÿìÿÍîKKK¥9±¯-ô¿Ú=U£ï—Š>`^(ê¯SZnk×§íÔ÷ }-–Ý}*¬žªlNwm†‹D‚‘5HL±F%É,šQ‰|K´p,ERç&i”™Š[ù1 ¸Ð eÌÄïöqþÔžiû.Tr‹›–^½g{мŽÔžÏ•:gUº6–¿h±ÌU­ô¸¯šÜñWš»Eeõá¢aR½ôÑÒŒS)FÜýIûzý¯Î­æ¶³ÐM¡ùsvçVŸ¬ÕË`¦º¬i/E¤-_¹çÔ Q5±–ÏES¬¦_RD8övÇEžËf š¥1é^€…©Û¡î÷­(M·*j–²€ ĦY¤¥Að­äƒ‹50ÇÏ~i{wûMóš÷1¹Ï¯5«Æjµ´jmMyÔ–Å©`T-£¯¬ˆÔ*‚©'OˆÝQ€v[®\ÌÖuž:Mz0Á24PÅqª§‚&YÌpSJˆ„`c 1Ž;²$"P]Übô©'¬NNIçf¬Ì.ªÒ¨Çp¼"a65Í D)µ®ª¤‡Âê²€À ¨«Æ{o.»s§˜õ²1¬Õ÷«Š2*•¸U5ÅHL¬µâL¯Ë·ËŽªW10,ß»œŸ=ñÏ2å­7T€q Û¸W·Ê¶ëËåK”­†Å]̆hëôŽ‘¹,¡ t™¾Ç'^7}¾#œ˴Ñs GÖ骛6ˆ¶OQD(­×Ûw/4eÚÄZ+Ýí5V»=,”e§z†aˆÔÈNzÛ)ÛRuƒbí[mÁhýž|ë„$_èå)wo’¦`  €`,–)smÖIAF_K2Z¼¦©#¨¨§Õ[_²>‘§Ô]5F¥¸ÌÁ*±ˆ¡BzZ‚뀪Ab1¶0HâàÒžÐú¦šºÕ sÖQÂñES_q’gT–/L¤b4êhÉdw=¶ãùý·?íõnÓVÏÙÖ=— šˆÚVÔTf“(àÊco°ý³lâôëDÛLÎwGö²…s¿HŸÔ¥ºRL¢’Sžì°¸ÆrqëØïߊ¢¡¶sj톋΄µTa!–‹Íu$ÊŽ0Ü)r3Ñ¿aÇÅõŸ×ŸSÿlÙ-{V×jì3Š$ÊyRÒeªLÑrL„¡Ý–¤õR좜 ¡;eì}ž›4ÉvyrŠ&Ëu+¬¢ ®ÕK$š¨œ¢UYuµ+a§úCĹ;ó0Ϙùq_ëM5Kq¥­™ t’j*¸•Ú0:üZyNA9é>}÷Ï“þœúW뛪˵Óöó&Z’J¿O?Irn;ÇU»ile¤Èýt€¥e}†;ÙǤ6Ák±^ùA2ÍEG,—-$¦G¦Wu«’Íâx‹)LõŠ€9È#”€[œ¹ Ô=òSƒæ3Õ¾üs‰ú)?úÚ;¿ü ?Y7ÿVWqö„-7ølôÒS4”òÜ ¸SÓB­4²!þ<žï,˜ áH+ð šY5-}¦Ž¶ãiÔ¶zšŠk½5D–êÛ=d°]íi¹PÖŠibÕZk+éjexä§«h·ßÄø¥²M¦ÉiVЗ1fu¡A/xž©HA¼ïBšpÊ BUyï’ù“È3nüã:‹ÅlÒQ½Æ¾ªZX!• ÄÆHÃ*©1ûQÅâãu@£ Œ``5WuMw÷ªJºH£¹H‰•,)¤VD“³øˆŠ¹|x¶ÈÎVIغ“Œö‹Žù§4lÚ®éRó]ªÕîãzh­–è" N¨JÔI-Q•p¤õ\g`q’A¥›íÓÚ3MÑÌ” ª·vkŒoW&9­ 4O&µ?.&°ÞšI¡Tº­ÎФ‹µ¼Z]I•ôG=-»@ãQ9­hщËZš;dµâC¨)« =ÎêÐK%¦’UT4iüB!À/§Åñ2à›£œëb…±¦êeW±I´HZ¦% !DÁú¿^ ²[+ù Z¥)ÌÔÚ¥©buo¤Õìf‘H¢€‘Ô %ÏðkÞ@TEWU X´ 4´qWJL´ÕbTjŠ4—¥ðò’éŒÇðŸ‡k(w£Aç”lJ‹Ô¸qÜÀûÇ¢©JÕ†*§ï¿c\ï÷ñ¤5üÆ×tš£œ“-U¶¶£H ÓÕöð´ðÐÕê»RIg¸Í •j(°Œº‚±fÉÊJËoÂUw 5aš·˜wŽžåÔM5fª—YÜ.Wr‚W§{tÚªª2ÖØjiêãUè3+?krxú!ýŽ|¥ÖwÙõûNy«9õ•ŽŸ‰Wu±rñtÏ'µ6‹Ö÷¦®·šê-uO¬¹mt¹×Ûåm1kˆEOt¥‡Ã.É ÔŒö‰ŽQx`H4)8ƒ;^ XBúBRœúG¬xE¯õÕË]k:«ÍÚŽÃIQUy·U m–Ûi±Ù¨Zª¦÷r’+m¬ÖôÑS¥]mD‘ YU„q“©I5d±b4Šÿ¡]Ez|ˆ($^¡©j˜È#{JÄÿ%’:gêµCÈZVÜÕâMGñ…‚1>Zì‹û’u„s‚Ui£O¡ùƒRFÐõÆ!å0ÈAK+0uû¼IˆÈj(¨.oýcYyçMdU†•×KòÑ´å%e=KLÕtt¼çºÜ¢­Þ¦AW‹sž3-c鯙+—&T´­bê°ë ‘ƒWÆ¥ëS0©wMÜY%J“RO@n‘3åM}\üÊÐñKSyO¨-Ô…d†8at©¨Á$ú:eíèwØoRtø‚Ê:?†Azò|+!#©Æ>Òíÿwo>5õRAc•§Ö¾s«É3hŸºS»–èèÐÔ2+dj:ºš¢ee|aØÈÀ¾`NwÎûð¦—Ô{>ór9kš“ݽ£ôsL‹%DtQÏ¡y¼®‘Æ“H‹J¢ƒ´J¸Ã,Ä-e •8jå:=«Lµ"A$å&˜â"èå}Îä­“ÆšúŠ~g\mÅ)룉ôµ4ÏU4)d¨‹Ä¨ªB:#Œ0ÊI!ʤ{—ט¬ß´Ùöï4±RE¸äm\ÓO'¹ÇSóZÂ$5Tq …‰²K P2[bG)f}µ ;‰Àq áH‚p'ŸÃgkûm5k[‡²¦®¦¾Xovëô¼ø6+•Ú–†{n_=¢I n§¸©’š§Å,Z—"p«J˜Ëhÿ²?7íüç%uudbZ[¦’ÔÚ&¿+T­M¹ÔzÏI½cÌ$”Ô7(k…‰\S„Ì}^7 ±ÉU»éÙƒzt‹L •3…¤17Rø;,ÔXöÕ’tÅ.Té3 0Mä(–z°Ë>õs¤õõŠ‹Ú—–—zšëg¹[yí!q½EG=®j¨è-Zƒ’õm-0†¼,ó4QÖ„éu¤Õú~dy'Ï 'õµ¥ÓÞÚºÕ.™Ö¹«¥SVUèkgÍQAQUîÕrxÑLÖå áÉ#©r’„òrþšémf¢prYÁ'õ_3iAJ’j²0þ„n4ø¥¯d_ú‚}¹ùÏ~Yi®j[ùQvÑz‡ZÚlwÛœåýÒÉ5mžðð[g©¢¼$Õ÷(jîpÔA„Íi’)‡PŽ>Ú®qÐPWWLþTTu5rÉðžˆéáyðÄ • ܶçq(ªJçK\Þ•ÂT $;¸ º®1°Q^+|mÓrŒbÙÑr4”q3‡š¸FK¬Eúâ–gŒ;L‘»°ìNIÜ“¿SŠ,– ìD™GÃâ3mIv¹®0˜ ÛºÞuyßÍ®hKËKÈ¡¯uMg),Üì¾k*=%Þ²m*š½|Ø×SA`y<7¦·WÕÆÓˆÖb•Ò+0ÉIÿwUæ"Ô³/[2ÆJH¥‹uu ÀébG ôãÖY.\¾  3MòÙ¨¥.x“G0¹‹=KÊûCvhµ´lRQØç‚­9ÖáW=4¬©×M­-óGtÉYDÂ9“s"'„ê8V‚¬ÒÔáÄ´‚…fŠ¢£¥]¨ã’•A =C"€zKF ì$É© )¼Ö3•ÝJwwfG ’9-³QÏ<Ï“M$nµqD‘ŠhíÕ”q½LtÎNª•À9ÉU9(2]}ö)-Ö9_&JZ¦–Bæi§gY$A‚ðôpÂÊÊ;³-òÁ(G6a㩉—Çž.;°„c¸SÎÈ•¾02Nêh„eÛÞ#1"ã¨e •–Å@%sÇ&jßx=HÆ<†*w˜HT»sÒ@‡OQøF.ÖWu8“êG„PS†4fÖ³€Úºxb¼^¸a~ÒáºågêwÊ9ê³`dã#†äW¶~¤äeEÒ’MiMI[Y¥õ•³A­¬PÝíô4ZƦ޷I K,f:v‚š¨7ñ H*ÝH³p›D¡97YÈ-¢¦«aI9{`Þqyò3Ú»Ui=i®.›m²¾É­%‡PÔ¬ßf§²ÕC-KÖÅnŠ’•!†Ýu)*¤QA Ò¨:¯~L{DòÛDè½y¦¼»Ãu×7‰mðÄ^Tª·UÛ­ô‘½,âD%`` ýE@ Üj“iBBµº¥€ü›¼DH?nAW»+ï'Í~nþíæ]›˜;NÏ¥íöºÊ:Û)7!r‚k•–ä•Ô÷©Ö–¢œJ°–‡â$®L¥²Äž|ÙµãS\5%æ¶«ZVÖTWÝÖºT§¸·]GZºø³H®ÄEüSРˆ÷ã*ÝgTµÚ,ªDô$LJX ¼Y7(19F©r™Á3ERHbK0«gBì kôAd¿TÏk©–ëm§G»SÅHªëã†ey"HÈ\I’&¨²Æ®z[n!ùͬ4õýèíôÔU¶ªj+Ü1i4¨©Š…îÛr š® I\=U\+^î 4m#Dƒ­[ Ç‚ú£iÙv–ȶ~²B¤Ì²YÄÃ,¥KRÃt„3” ºBÀnª¸?°úvÓiØ{BDûÙ,À‹ÅÀZ-Ã1U øÑ¿u6ú»Í Îõž%¥–®]4ÕMu}$w(di)å¨:‚Uä¬ôr‚¦*‰*dÅ( Pš¹Å"¯4Mô CKSU[ ¼[ý_Z›„Tô”óPÒV´y*È‘VV4¥P¹rb$.ªÜhcÑU7+´Öjjj:e­%ä§§ŠšK厖ÖëðD³ÕVÁ'½‰¢ $ª)I!f·ýüCú«ëP™v‰Ùf"ñ™*TÀ™"\éi¹yeNV…;©X—$œm/§dØÔ –\Í£5*‘×**I$²FD3˜$Ù]5íK«ítZT_©l7šJjK|WˆÖhèîpÓÕRSš“K4·Qq…¢Ê’F©#²ÇÔŒ¥Ä‹œ<ääv¨°ÐZí7jIj¾´T´6ŠÚi ¡¹é›þŸ©š7ª‚%šhÅå cž°@¼SZã[M[¨£¯Ózšd¶ÍC Fžj»Zëi§—®Zjzjä‚­j`Ÿ¦CQæ?uCGn¥Ø©öRŒ±}}R A£¥F0ÎþýF”L ÈQPaüÂ+Õ«) Öãm›2J8ªïÀÕˆ!Yú ©žF™c_8‰r_;ùã vjIb\‡ÌlÏ5(#)S…É'ˆýw4­ˆÅ?{VM˜§=t°Tô–H™‘ 'Qg/©aÛ›ìÏ¡?„{0$Ùv%–b g&dó—þ=ñáHîZ¶/ñ&hy¶y×NRæI²–·çªþrÓCO<ÉkÕuÎŒôRÓSI+¤é+ cZˬ£_+œäb "²»óJQ~²j*ª'Jk-Ê’¶’hhS­utÔAs‘|D’ßâ•'hê‚I8÷ÿLØ‘sg -‘)jKL¹c*P ´ñççý)õ/?eZff䜛 Û°íƒè9½wºê_ìå>‚¹Ûᚢã:¢éS$vd’Šž®ZI§† i槉F*×ÿˆ3l Ò÷í}µ\n6*ž^Iu[U`¶-ÎÝ_SîWEJYdZÊHÿvJ;¼ '”)#¿jVÓ±J-T囤Cœ+CHãÎúsn!`MÙ6©WjæDÆåTðñÓ>Ðënѱi*Í~Mo6ˆªp­ï´•óSå&PDq¢,m·r0x…jn`´ªkÄÊÕ¢·Xí4•(j ––†Š–ŠvŽ‚®…2’àô¶ê1»•i•=ú0•.ZZŠ·Ww'o8ÂlË"”-y’’³ûФÔGÜøÅqY¬ŸQÙ$¬‚†âJ x©jc¸xØ’¤¤8Á?.:—˜4õ UuÆž[LUR°Ÿ¦ y¡IaX:õ êÂ’?ÕƒÂBË‚\Þ†P`Çå„r>qé(iÖ¦V¸ÕFòϘ¨úäÅ+2GÒ:*#ìÝÁíÆÍ=Q_ SR\ŠÑS­dŠðRÆÒÇ]J†ˆ æêïõÒìNÙ0´ª¬jÙ â!cØöe¾ÿ×}?ÿô‹¯ß ?y5{ž9ÁôÉÿÃ>=þ¡ßu·QÕÜ«©£ªŠ"««É$lpŒ:‹äbÝ$¹ÈÙ[áþ묫£•*‡hat!P±ŽP t¼ŽÿãÈÙËg«s»üy9ö 3™kMô¤=Fñå”,ËMðšu}·BÔúÚ²¥i©åcŽW–8¼6ÃJå )élž :Hq*¬ÔvÚZŠj˜!ŠÚ;¤Ò¼°ËtÒBÀ*0AaÕÃccÌŸ³ŠfËLº"`XVòàT÷n…™,MÚ†¾"QU©ê¨¬÷´ÙZ®šéMMDQ4rRG—§©¨,x¾L‘FY]£˜8ŒÛ-öÝ=CY¨æŽ®²gZ` $饫§šÃJæ’«ÔG$„„,NIPùhÖzŠ’Y᪖d¦›¢y D,l Ó¬EÕ6˜Úœ(eܶxÚ½g]†H˜®žpMì G.í¦Î-CUgÝïJ×JÒdi© HäJQ¢&4~³áKRîã/•Üɸ~. (*‚Ž a P¥5Dw c«x:ÒzGŽžžžZQÑá#½IfèèIÒ¨½\©Ó'lkU…HYB\¦{Ĥ ’ ©G‹=i‚™*MâîØvQ¿ÏOe‚='IS_;ÖÝ()µ2ÃYVóÔU7\D¨ªg^·éˆ ¶``5yfŠ$mª ë.¸Íu¸0 }qú}^J„ÉR¦U¦% ®W‚[ÃÆ5…9½Ø@„'öbQÒ ¶¦v'ɇ¹A±]¿?.%3EPÚUÔG†³V@b.:Þ8cGé8“«õLJ ƒTåózÿ lWª­?i¶{œËP·K¥RÃRéGJb´)r%qО0“¹9 ož&°Yk$Õ¯z-L”ôIOLÈd¥[e*€#ÇFàd°>xÆ8`I!ø_8­Çôƒt5%»HU.¤¾GQ{·9¢«¬´[jã³ÕÍUSÍàEs¨¥©Zi:ƒ!§pp¹ß‰eÓÚE[êfk t­TÓTVÕœÎÔÚ¤‘†ŒôvXí #£”]¸Í2@H–••f¢Yù8~þÈR¬Éž¡1K)»J7QnhÿÚ&ŸµQéëç±—²úžÚ B¶¢—šZ~ÿR ³L¯p¸[ù¸©, Jz‘9îg:ßœ¼¥ç÷-"‚GhgËœZ´x÷í¯µ½îßw‚žÐ’‹|T÷PVÁfjØß4쮾àU[¥ØoIhé³<ônICEgdáœk{1@ ’®¯X䆩Îw¶ú`Ô¤z×{ÐV;¨¦§¦µÜµÛî ”õ×G%{†ejÑ\€Ë’’ñ}GÍSWÊmIʜŧSFÐÍJco¥RåMMãC0rI›8#`¸êß"`pãw‹xùĸĜÔA=€ð¶ZŒ.A'cžÄŸ#·§o_寤\4V£UsIâXzµ¾®¢Ðb­K"Á|µË4U zLÅ R *À²“ÒO —EVüÈ%h8úD&妵-&”åü~âÝzJïv{°JŠI‰Ö÷5@‘9ñGIÏðú²®·þÎÏh}U`ö^ö»åE—^r»OGÎc[f¨Ó·Îrr«Fê At·¥º™èktö¬Ôöúél“Ùow¨üw¦©¤–Eztu’UùQYfÛ6reYæ*\äN³¬’ÒçJ˜ ûŠRA‚c~Ç´þ’Ö¹‹BV‰²§Ëe zI*BK•RN£Ìíej¸Y5Ö§´]'µ[ªmWº i’ÛrŠãiŠEáPÜ4åþ::ºvêÃ’™ÚGij…“Ýj*eÒZqXJMKw Õ-2‘ﺇ, N¢\†fYd“9_& öƺ«¬N±õßâH $€¤â<þ8n‹Ç”÷ÚJ^bšÚ¨ãQ¢¹“Öõh)˜ŽRk(é•c{Íj-Aª¨Œ$«C”Å]!E¬§_Ú§Wi›·15¥e²ÿo­¥š‚ýMA"VÓÏ-O_4ÎR)©úä÷ |OðÕÊ¿ˆéÃ*ñÚid¢X«û°|³òƃwôç¬1Áñ Ëžbš¤×–kUBÍ-ÎÊ!w®*Ê{+;‡ "ëyñüW? ZéÓ?ûD]ŽÒÚ>«™ÚR›XZ—–½;s’º’’í«5*4M|íl˜ÑÖ˼èzÊØPN޾*[¤ô·r9VëïÔ~¥M*DµUk!:·„ —Á¯qŽÍ–Û$É—e–“>tÀ(Õ@(?½¿ÊaÖr¶U²5ª¯œ\ˆ²Ïxª¶ê]8i¹¯§kU¶Ç6©²×\¡kER¬´ñ×Ãq…¥Ž:„Zê¢iH$Ä&û¤4Õ’ËBúÃÚÓ@ÑØ¯ôõ•Ô«h¨×úš’áMo¸T[+gX¬ÚG¦X£¹PÍêÀë€ãl †Ïi´$’çN”«-Bñ¼’ÎhYë*±nŸfft3eH´)Iª„¨€¤½ÑQd†æïQê΋å¦å½Ò¿ÿWtÅâáý¢¦»Zm×­1M'öSU›UÎÖ"ÔtkSãûÕ$«Öôè˜ttë 8¡eæe¾JhbLÏ1‹x›r"§R:#¥žÙòóã¥'eÍZBP—$2K´`ü 39ëÛ¢Ue3 ýæb¦¡; 8ÁðêåÁªb´òöª§ÂÊ£SR^«Ì¥' ‘ *Ë.pp03ÄŠËAϤufŒ²ò›XÜ-šÎýcÕ•SSrûSO]KqÓ¶Un¢¦¡’†‰c0Jº¦¼ÎfŽiœÇYP) ¾FËè‰R¦*i €ÃñŒb´m^œ%2ä"Jz(“ˆœwáÎ$ÚcDû]ÑXc°Z9-Ì(å¹5d‚§—ºŽ–t’!C8–¶•&ˈ#nœÇ„/~Ë>×îãûîáÊV.PÃIm¥ªHmöÓVU·]ñ}åÕËŸŒ–Á8áröE’Té“À="É%ÕG,0¦- ™´­%¦]RûkFjÕ¼)Â,+ç²§·_04¯/4>ªÒ‹¶åm& ‹@Ú/š·A¤:Yõ1‚¢ö”SM¨K¥Mm Œ²¼ªž„\ƒ¼ûûNhË5ïQrâ²÷I¦«iæ––Áp²j«¶ßOR•é¶Øëg¨#W»˜ãt Ìd*Ë“d‘&RåH@–’T¦©eÔ{I$øn…¢Ñ1s¹„¨Âè¸dLZŸÚÎ Ï´.™×|¼¢ª¶U¶™—— MVEUËRé=a]o¹ßì—yê*¦Š™k*¼^N’b6êÜi^½ª»Ù5.¾Š½Ö9ª/z‚ÛuûT•WJsxµÜ¥ŽæR¦c]¬¤¥’EžG< –Y#Èó{'fIÙ“¡×ZД©ê:«Q~N²Ã†qØŸj™lJç}²ÂѸ]HmøüIÀG¦_³?šëÎpÔ5}ö}cfÃÜ+殊zº)=à‰Ðû±VWaÒ­ÓŽ¥Ã?U»Œ¶­e¡îÛ+¡¸YµN–¬jË$–ÛͦOw¬¤AÓT££A6ŒÄ&Ûh’:-™*Jp TĨŠdTyˆ\°¿ÒÙ¦V%ÎZJ¸Ý–R0 «Ñùq{Zê¸t¯¶=F®ª©¦ŽJ;²!”OâµEÛ–PÓF¢ãRK˜‘ƒ¶\F@Á!€ú{žsÃnªi.´pÀÕÓ1ꙩá| E Tbel³¸$ñÇ—%6‹&Ï%ozÏ(s`ôÃ~Q¢Ý)HµZŠ“öM^æÀó'¹{š¢MtØ‰à›˜7ºÙåø¥yc®¯‘bU»uÀž¾Ö{|jæÌ(”ᡟº2Ôªé-Ÿˆ×!ºMCm©hšìdÌ-1ñ¤DDÅPDÍ 6©=D.0 …-b— ìÕÔ4L­DóÇ%;#bþI]ü #D@ÏâàÕÂ$Y¦$ºP5Þd‡×‚Z‚P¥#*][MR)íÔñ¬õÓ³Ô3ILÌY<0Š¢vDEØ’>.¬°c‰æ™ºV]#0©UE@%/L½ypšn¿‚™@Ÿa ³ƒšƒgAY[›ÃÏfìàÊJ»‘ñß(hí5U5µ Š*;gCIMHÒTÁ$õ’ÂÒRÀ±Âzê$Œ«)$’Ý^¸‰š; UÍV¦Ü| fW†½ƒGZ‚^ž*™N‡f–5øz@!œ¨PÌF3mµLD©¨7n4©RY$f US¿ "…€ôñÒѵвò³˜ÚËUßtéš³MŸÝV$»/ö¢ÙZ’1´ÍAoˆ™j©’ Mz6Í!OQUYO3U“U¬R/*ÄÍ(ÏHÃ.{qºÌH›6Û*\©òÀ¼—YLÛËrC=䢄fSDvvFÊÚ[Yh‘b°.Ó8ºØuRP Må†w«³Óþ¿¤Ñuúul¶Kõ]Õ¢š i£ª¦¬H d¨¥ª«§YH4±l|<6Ý#‚,·]¦â–eŠª«­UUª¡¤,½#§¨Hò³dànrF6#ã‰$ý/a².Ä©s¶¼•L3ˆPèЩª ¨²JI ›¤;–9ý&Íü:úžÙ2\éó$l¢Á5Q˜°Ì!@©‰f Ôˆu¶²’ѪŸSÒR´s-KÔÑAK4”‰LÅZ 9ê“ÅW¦’d˜„“¬”éÜ‹åâÅÎÊÐCn¸ÅŒURMT• Ðáл¤ª:•ƒ`ôƒ†Üí²-rÇ1Erv%žTÛõ¤L_E”§'£©êIrYãÕX…V9a#hm‰ö”¸UÙ`JEêu˜ß/Ä|"UUÎa½Cái0wí·sÆ£lž×RnÍt ;gˆïŽ´½•d”$”îvö¥’݉¤¥êɧ…pÅ·žs‘¿mþž\fbBô¢©9ì€òÎ?YàU>bÂJ¦x—Ü+®pÔÙ¤K£””;`ÝtUf·ÀÛ‘êv8óíöß.ûgé¶=O ›1Wh]ü(5ó+*Á¨@ÅøüÒ1=9yï¸#?=·Ÿ 3.p1’|8>ÿË-*P"¬|Ùµé”ÒŽÝŒtÅp3‚{‘åßËóü8ÁŠŒ ýÄÿAú<9 U1új°…æ†Ë!6d#àg`Œƒƒûq—‰ñcnÃÛrO¯ëåÞµý¹f0„–t‘^<¾7sŽÄ€ ëçŸÆý¿ÛŒL¿é9ô ä“’O—}¸°N& m|Å¥=3ÃñÖµü¼ÈëçøqÑ‘r2p}FrAÆ6¾ÿŸ †ƒÊòk†Máë¿8Éf9;ƒ‘ç‚GóÆß¹l1ÁÕ¢ì×[Õ©!£Jl¬¯ŽR’µJU4PΊ[Æèhƒÿ '~üvÒ¢ÌÞ;°ÝãAêîÞÀúøD~£QêªÍ?IYûÔÒÜ¿z×Q‰é)é“û«G@V!‘>SÔ0Ûc«‡Q%Î]mo&ãpÇ,Õ‹S,‡¦{Ÿµž¤’º­ÖÎYZ)‹*€Æ¶­äXÉUì2O«Hê$“]éÜ cÊ 6d šÁ·qßvcmµ2ý„ùÊîJjû·³æ¨ÕôœÑ²_nÚzkÍ>»ßÒ=;t§¶×¾§žªù0®jŠ˜ ŠX^"‘”Õ‡öœ{$Ùᥡ°ûS½%±*)íÐURèz¥Ž¦sQT”ýz¿wŽZ©Iä3±f Ûœ¾–ÓüµKLÉgö©Š\j.—mç>ÈÝcRlÊLÙkR&'#ª¡F, A7CgíeЩ-%>”ö>Ó‘R!¥·ŠOkd¢§–¦j¹!¥¦¡åÊxªÚ¹Œjà*$}ÙØÈöPößæ‡=´;u-‡‘vkV§å…’Ã[¡t•5eh¤Öu÷ø5DsÚæ®®§¤Ž­j¦£éÖä¼:Pžê2vpxcÀB¦ôwŠƒÔæCÔ€rׄ6Ýõ϶.£½Cw«öÑuÓ%5,ÑOYÌnYÚ£¥k%=ÆëD#¹ÓÍ"­5Éæˆ¸!¥ðVBXåŒ2ñígÏ­—3YÊgM)=¦—Å©´ËÎM5u¹#’v† +o/SVÐÍJ)ߩӚŸjM•v›T¹(QaxâNLõ'½ËFr™C%`ô.zFsköûCê;½ºžÉûŸCPZjMD±éªj´šZ©iˆÇq«©­sQKÐõ/XüJ¿HÙ¢§xc ûGý£Q¼w×óÓËáÔÂV–Ùaš^èz=m¡ÔË»/AdÈ2ÉñB|üéûB×rmšÜdÞÅ!))ɾàKçÅùB±bœ7wn]ƒö‹s®ßZõPó y–ßAcž¢·NÙoUÔÖó)Šh室‘‰ƒ ޵º×i”©rvz:Y«IR•1D¥ ¥ÖHÅK.Õ ñeÔ% îìß»…#]¨ù·ËÝ[̪kÍ5Ee¢¦½k¯Tš`=ñâjiZ* ¸+¯MM,xl4#È_3ô÷+/ÜÅš‡–ήm{Ž˜PÞõLtÔ3QÕTÛàZǸxüzX+¢˜d¤s¼L1› ùì¶Õ)…®_E:ö#íVÕƒv°9;d¹…)}PCcŽ^Ñj{*{ÿ,ùÇœ¸ÖRMSh×vZiê­Îõ–Ú…š¦JšG1£VSÉO*8Uˆ`Ç«ç°Î¹ æW±§³Ž³·–WîOi‡¬2²­%ª;c‚®z7ÀÆ;(Ø`Ûó 6ÎËžòfØmñ=5žï «ïŠÈ¤mB«0[¬ärè-«½îîË/ö…j˜*½¥µuòâ•-•¶{sBàÄdžÍ§(-5-… " ¢d>ЉIØ`h5÷U\õ¡¸\’ÂGm"B®Ë·‡cñ2¯×¹8ÉÆ“ "Á³V ó%È@Öâkè+¶ÜÛûBØ”Ñ&+þcáÖ…ªÝ¨5,‘Ztźå¨jä˜Aj†IjªL.B$cÁ úQ°ì¤)^ ;ñ$nTk{\Z’ýªì•úf—MPQÞFŸ¹ËE]J]jg ¡jgFðŒôµ4…™.ƒ­xêM–L©“”n(_áûø´rŠ– °ç»MÎ*Zêõ¨jj—1%= ÑÌû´²Ã"Lþn@ ôü8Àì8\o´Ê³ÔŠ:UœIÃ-*E Ôåº]²ó¤¶ýÀrdËZ–•vœÜ‚{7S|gH* “ª3úxÄRÝ|´½\ñÝ ¸OâG*QKGUGB´ÕsGÓ õB[eWJŒC:¢#¸GŒñ,µX…}%Â–ŠºH4’Iq£’ßRÿÏHj`–)gÄ]kñÈ£~:×.D¤’ƒˆr*Ò25¥kÙ P"¤ºi‘|F¨"CIOqŽzynÖ¨ ¸ÐÅkéi¡÷“ D°VET­“©\†d‘ÑÈ=l€èÒßCM$”µ‹kÍCxiQ,s$ŒÂœ(+N#œ¯\nijHH,Jñg)ï DÍ–XWw99H##e'lÇCLÞØE lI ;7~àt®ç¿á鯔}#¶ (È æ´ Û”|ü£,ÏâgÓ p-÷ò¤©Çvô$xòŒKÞ™‚xÖüœ€Šqæ2OséþüftàìjmèqÄûnv )Áü;4£öª™Ð„¾õ¾æÁ'^8WüRúm.ÙËé’xoX„Γ¹3ÜhÝDþD³LH;|³Æ#HWÈÅMÎ=²‡OHçø”ë¶ÇϾ·†¿2J{VwnH1ÎüWØ`ŽEªf È”pÌÌ$w~°rú¾ë5d0Þ<)!£5gˆ*ž¸¼qºËMMNÍ0€’F‰u†ë‘üAÒÙ$1IúgÎ(LÙŠBN* ՜ԛ>QÌGñ/mÈY˜%KœK!j™v”É@Ö„ò„õ¥×CÚàš5}æ¶hüh¦’¬¤+B”X± „7A,ùê å@ÀØð•šý¤+i Õ-|5‹”‚jå_\1FŒû®Ï…\dó$u:¥ý;±ÂÌ«ófJA%!DÐ)Fñá ™üLú‘SUiD»<™‹JPR²–ð *auĽ)¾/ë6ˆÐ·;u’·Ã­^(¶8žà¯GJ¼bA †`ò0pOnÒCÊÝoŠ©•H û܃ .ã—üñè$ý° R³&bÜ%ÞiÅ’p 3ÝùŸÅo«–×gH•{t„ïÔU¸Æ/ËÞ^ÅH•¦›ø=]1¯¨`²+ÈŒ¥¢“á\¡=ˆÜøÞìü²³{¹–Ô*$šáZŠz˜)üfqQŒ/ŽÒ7lcnáÿù)ô䔪b¬…A,¼™…õk„e?Ä߬¦‘´R—Á¤IàøË,sЧVû5’ÃDújŠ:y뚢7–9ª&tx<¡1Š’£9pãrA@Ã5 ®µ¡‡ŒÀ´EŒÌHTbÌNF2226Éߎ]«fج©’lrD©l 9& fI>1ͶíÍ¥·„›NÔµ~¦xM׺„— º„¥9îxqŽû"ºôÈ#QÓÔáÃÂ: ±Î[§¹ÇŸRêJ“H©-DÌ`©y£C+tÁ#²ª,c¨t±éBzAg~2ôd=X–oˆç„Ôš÷>e͘³Rlj+kÕeXººªç$áJÔNÀ2õ–›¨äg2{wæ]¶iì©%}zÏOp§­¨{쪰ÉI=)1•ªO²!¿OSnã©eµ¥»åžêct’BXS…(Úù‰Ý%’–¶žæL”ðÕB]«UÌ5¬Ñ—_án‡\#Ç8ìî<ý ð狀vΉv†I)i!’jšlôÕ1‰f’ÚgÄ#2õ‘ʱ!Táxh-u2Ì.*»IJš‰–ZÁ4lÐ͇Óö¡&t‰2”%L¹‰Y  ËPr¥L°ת ×!`¬$ž¡ð4üvÅVeˆZ+iúй¼¤½ å˜{±Bp ÈÊ~|:ûôSÝn5Q¬‘Á5¶®™™‡X”Ý,뎣4` ÜdÜ}E'í<»¡äP¶CÐ@ßÄk%%/D¾*\g’8ˆ`V&Žì¨Ø÷äúžb©xïÐW¢ÆÑ%4Lò°¤Á9@Ä“'Âp@ùƒ¿(9]ðˆ*CkWN\i,u_qŸÀ¤’ª U£<Ý <33x(ì„F8ÎNÀ ž$úïDÔÖUK5ÇQ4U eZm?”0${Ê“°nŒzùq}"‘Òä±mäB&H™1H)f黊åß2}ލô­ºŸYÜ}§Ž§Yjš¦“Jè>]UØTÙM*ÐÜ/ö çv¦ðZO!Ó+º¨*ö¨“Ùÿ˜ú¢““÷NuÚ/ñ_mñ\™zwCÐÐ=¦:¤¨Jx´ö£­“ÞžAD ?HÓ«ª‘V©³P™@JI¢‰ë†bCPðxb6|¤›æq\Å1)jJ„T4º O¢åÒ’Þâ€Úî×ÿxµ(1Ê'§¥¨Ó=@*z¥Lÿ°ïè=F”¥–- ukÝ<5z]­ÔkE7Hí×éQ5`Å’Ò‰ßç‚ r7‹{ú4>ã)ÁkÄà¤YÈpþ¿\PwÿŽ5ªù¥ljíc,ú¦Ší¢µn´Æj8粤5özñSTòTŸ"ñ.ò$c ³瀢Kà0ðƒ.KaðѮӚb7jˆë‹[%ŠãyK5JÔ[–žøò¥¦ºhi®"I’eŠ?Ἐ2`®N×,õ÷(¨©õ½—›zoXÉr–ñr¶ÓTè½_e°-]Ž®)䣸þðÒ5òøFušIL(@%Z=RdˉwfÅéNü ,L) $¶cJU÷ƒr‡IþÍˤbñk±Q%úÉ‹dÚÒë©c»4ÐTõ‰c¥šª K¢G(¤¤KѬÒ}ûÓÚ¯`Óš¼„¦‘¤€Û.F4Žš•²ÒËÒ ˜z|ñ8ÿW éX¤…ÈbÜÿ- 2Ô(Pû c]=§9Ùìëì£hÒ{ÿ$ôþ£RÞïÿ»LéÍ!ÛîÑSÐWÜ®YKUT 1yb$FCð)ãQh¿j×'`\éf—ˆõ„ƒ®ñ§ìþ#øŠ˜ G¦'á™sñdyg‚3–€µªS‰*"´ÜP°”b¢Ãõ‡.fû|r¯]é>Yê ³/y…ª*eÕÔ5Ì¡»IËi(ë-Ð •ËEMûÆ’ëE$ôñRøMm:Ìʬ*i}¼`³´Í¦}•9lZw ’ÜÒAÔJ£Jiã¢p§pCGJü`qÎV×Bft]%Ô+5§½¹ÂºI á}T¯s3ƒV~Ó>uÀÅ¥¹kÈZy©é…,bùDbgðÝ¿·pÆ‘¡?2ãȌǕߴۛBÁÌë§7t¶œ+}¶Ó/íºZÓ[d†²ëRn‘×Ë4÷û¹Ã KC•fPÏk“´P´ªôæXp¶á…O‡gI!iê¢á¦/à #E9•í·Íhj Ív«¹×˜ŒSÒÑéØk/Ö­7n¥iRI]ªóNï0"4ÓÎ[«2©=šë[©Öó01­’MHÏ$T)W’:9z¥ŽŒÏPKÇà IñX‘ñnÍ€9ìë™üé²Ñ5jUâK’CMIAÕŒêIQÿ À9`eçÑëÚH)ÜL‚®’F‘¢ŠzykVµ£õ¹Ê£ÄòÍ‘°_u I"®M?¨©j$µÑ-¾åVÒÈÎMcP4ŒÕHŒ_t4íBä2À1-¦Ä±>Rˆ’OóãÄݘѽ¡a!%Á9zoÖQÏï0»E QEQG$Ò$PÇáx눌Q¼4hB# •¨='‡»ErÏHäB‘˜üñ$«÷s%J+·Ç3ÊH¤Ž2§*,:ṄÐ,K 9’ŹmãÏ ëž1jk­cu¬å²ÉY<¥íz¦Š¥ARÂ($´ÖRITõž¼J„¸_„ž’K8×êw’JÚÃ3ôÁQG !ÇT¦­jŸ"\ž”_t Œ¯ Œg‡XR&HAk·ƒðM[^QBP€¯:GOre—ªž$E‘É/ˆzˆÄ»Ød¿2Ë-êEY¡”ÈÂgéB/‚ÅOL˜0³ŒpÉ’’´ý¸¶\CA–£dÚ×d\ܱæMçJjË%Þ¡j¤¦¢«£©¨©h'i·¹’šC4q–,®rz@Øl1õõì³ÿPe×Bûi¯c›?³UÃWWÛ¹W¬ySc×”ºž¦ÕI]O¨©ï”vû‘‚®Î"5”Âö㎤÷0TÇÔz8;ocZvœ›%žÉjEš|¢©`LIPèæÝ¼’ ®«¦­‹ŒÐìKMžÂ«mžjì†b'¤Ë`ó$À••!—×n²iXù­çÖí’çM¨,4VÙuæåv†®T†ªè“ÇOAJÐWŠ÷ðéÂIùYÙÕ~(˜%KÊÔ»Q…,Òþ죻Á[ÔV‰dE×E»Ñ€]¡¬â=@tÓÈ:ðãÑIU•+•d¾ó%%)` Ð'‹¸/º%§cmi¶eí•YÚÉ<•ƒy9•P|Abâ':rý¢¹sCQU¦oÚÖÍ{¯´¼W4ª£¯¢¥§»4sÅ[3µ-=U"SÐ×̰U¯T‚t,A™xÖ«öµÕ:Цº¾¶ã¨ëcZ™ekµUeʲi¡ñ&Y"–®f%‘Ë–‘3ÓÔÎp¡ŽBÖŽ™hB””c…[Ÿ3”y A¾—’YC0A¨çg·[õå@RêË¥iꊥ0†þ"Æ)gÃN¸V`¤ý¡ÔÃÓ<‰EÙmÕÁ†ænÝþ ýG r³êj”iŒ½,óT¨X`yP Eá–N†êëbÏœg°›8­A¡VžC:Rfi ´ñÌ\¬µ]c£ì†êl‚GS`pá$%kXÅCv8hiÈ ¢ [ìct5“TV?º•i¤ª›ÁŽDhÑËôªÊÈò…îÌ pmMMÒ¤z‡˜#IO J•Ú6‘œ¼}R2F2±_‡%Îíä@$ªðÝðp<†1]Ronõ~½fÖ½CYA5-[$Á$…"Y©Ô"ÆàLI"`ª”t¨;ñsZ9ƒ¦­4”µ5‘R¦©‘•i*¤f°KYQ$¦–)s7 ®s’Çæ87eR¥Z\.ŽÎÎA»·BÀ.3ÉíÕ4ÏPó›@ÇC \š‚(à’¦ZX¥k]ô‡šš(&™J¥¨‘„ª‡r=gx¦æ·/ênvóªé"®¸~Û5yÖyh0ëe(¢Xj`l>.¤‚t.S¸rFJzà_Í.æ2g89™ +Ý©èõŽªD‚¦¥ÐµÂ–ž‚šjÊ©JÖ[ã %5<îs£8ÉáXuÖŒ®Š¦J]Y¦dJH®­Ú÷AÁ UAH²Èj%@«ïUtè #y‡¯†pGhÁž‡&싨Å',XâÞ±.®Ò³Š‰!ÔšVt¦…j*d]_¥ÂSÀjiéVYÚKÀÆj*i£àuL£¹Oª4¥t˜ƒSi ]"’yU5–”“Â2M3˜ï'¢%Œ3p Xœ¡ƒ-**f¨!›hETé ò}ÛŸ|×=YP´¶íM£êfžh᥂ e¥**'’V‘Ç‚^Fv  nIdãŽGq³Ï Òò0^SUiÉ:ˆ8 t9ïNéw¾”¿øÓ˜Ä$ý¤(¾Lrnpû¥µmšÑ~{MÊIÒ¶åEMO@”Ô5µ”Õ†¸¤´¯Op¢¦’žH$B§ÅøJ u8Áŧ]ͽ J«´’`]XihXŽ"ÔÞcbIJ£éÇRÍh³Ë“usT’q¦ìŸ±ücù+\ÀR ¼Û –÷Œ5]yíË»tQ¥F¢²AãSÇQ ý†s<G‡Ñº\„ KpÊ@ì3ÄW³Üáž#xi!øá+œ’[¥²A9R¡ØöìqÇT÷W“ª‰I <ÍâJž¥8,¬>#ö¿ûm‡n9éAºí‡Ç´0%ñÖ”7 ªY㨒¢‰˜<¥ß-4r/K@—ÿÐ#aƒÁ ¤Š²“Ä…BôÉ  GGBϱ²·ÃŒ;´}¡¢³™ùiࢆóZÑÓ¨"yY&y¦y&fÁ.ý;c¥zwäz­Ww¼´&¾äõ-J@pR(ã^ ª…§ˆ3’|˜äŒñžm¢z‚¦•„¤Ž ¼k%¡5J[v{µÈCMmòç3K U}UM:¹’e“¨DÒǪ¢`!88ÿ1ᅧ™ÐxѺtKY|g*Ø`êî:•‰Æw0•L!J5`òiQ"èÝ–Q¹T=+øH„Â…C¬¯RîÊàv9¤>£¸T$PÈ!ٺ׹vŒäÒ¹ìŒï¸ü¡ÒòΑ¡ mÞÇ^°ïÈ—Ìa ŠF(K|×âÙr<¾»ù»Ñ‹•lQ¬“(–¢ž5 K+‰JãÄ%QÇ}À'#§‹– 3š7ƒ@)'w>²6j¨ìöšI*äŠJ[m <‘K :KÁKMˆ×VEe ‚@ãœw1,n’üÌ“Oó|E-i¥šÉWtHnQÖÒUSÉKÖî=±]#¥Ö¡–X?¤8ÓÈÔ–X椠Y#ä©JÉ©¤*^0Ë:ÁããÞ`Š/3ÓÔ¡cŒ’^¥­Ówä‡÷L´‹TòH¥á§’(êD²­7@¢o^ßãY®W‰ÄÕJêQÞ TÃ"O†3#1ŽbŸ·Cô"å°²œpO©9jg§•féH).4S–šHf+5DUÁR8ãOXðߣ9$áL€»¥œ+˜{¬xV£8å]pÀŒü=¨Ù´#IzZû}$õž42ÅÖh-ýt0Q<¦XÀZ‰eE†^¨Ç`A`Çp_í:ª©å¬¶O<ÁcT%5\"@R8° ‰QzÜFêRzF;¹–4(t—n”‡)ßî|ßÁû Jhì@9\jN³ãßt݆ï¦ê*()šŠ÷IPÓÆ)Ð×Å;Æ¢™b•Ñ``¤‘Ò„€€ ¸4«CT®'Ÿ®9’6C,dƽF%•Y˜ÿ‡ØôŽääèÙÓf-¥Ï ªZÙ=aÒ•ÕeTŽ.XµuíÇ'[”¦Ï¼4a “Ä‘)Ð":ÈPu>b'ϤäŒqÄ›JÉYïS-\ÉG,n‘OL¯M"T Ê0Ì‘¥‡PdÉÈmsÀ覗$`7𤋮®Ý â‡t6ëùªé±¨ƒÞcñ:¡%Hk¤‹±UppÇ Ùn²Å†ß<“Ì Ó·„ªÑÔxr’ÒFé… n£ö°23ÅÙXÙ$’pn4aàa€2M44"ÈCK6–)d¬[M5|2ÖÉMk*DR´IN*1/ˆ² «F$X¤ ËRmÊë'1h5¯/ùyšO[´âÞôõêh«.2ÝêíSÒÍSnµ_ëî1VI Í ’²zi©V«øÉ ©¤^: ²lòʦ ®gJ ª†½à "èÉ969ÖÅ®\¥%7eÍY¼´ -ib²á(Uă~bšZ©ŠJMWwZÛÍÆk~œ¡£Ykë*š))éÖš‚6žYD4tЫGt²G´ª*¸-©®P‡ =b ]úa¡ˆRÓ4l,”áDÌCˆñ’Äàq  @HHà*pÜÝÝ•…Ý Ö¢žšô¶Ó´-UjºY¬—Ê›­’ªší=ÚÍl¬t¥–Šy®Ïu¹I‹ÛcŠ™¤¨Ç$t²3ÂUz‡§úÛ˜Á å®‚嬚¾ Þ”Ó·jË֞妖»UÑiî_ßg‚ ÏÞTÖKfŸ§´Òܪš÷p)UnñDA3TimR$²&t#¦8b.Ä–ãÕrïy°1µçªÌd*yUžI7R¥Q&c_¸’izèé.Šõonæ—»]Õë%§Ô*Ñš‰!j{å|òSÔ=Ó´‰ I¿v¢º§ŒÉN¬ eQÜ´ßte¢åªm5Ÿºn±ß*¬·ªijª­·Jv¡¡¥5qURDërI Ä¢ý%›n£‚sŒŽ ë§ÆƒÃ“E]˳ÓËXC”˜êŠÇ:3ÈÌc‘ ”âœ3J’619ûYß~1ŸQU ¹iš:Xa0­9°š_1‡Ì†2R^”@YTÈÜŽ¢¼@%›vc%‡lGãèÞ*)Öy11ˆ†IzTcÄhÙš#Ô¤Ž žÄS±’µj ½Q­žïNˆ“ÔÖ:è¤v$Ë1#a°Æ É-–V…ŽnÖ¨TjB‡¬F¦bú^ &õAí°ñíôÙØÿþ·×nc•—]héNGJòôïý»]…sŸ¢6¥Ý$oG—â,Žª¸%~bÓÉÓ¨îiŒtéít¿BºJþ?§åÀšo?»uÈÎz´œXÏýº·K>Ïý£‚HÀWüºîŠWÜk‚‘ÿ0üG4¶ö½vvÒ”Ä`ä k=#óíŒþ<¢ýçuVìÚKXwÆ2šjç(ü1ø}üIyA²õWÌYýÇ+ÃÊ\˾ѻk´é?ÿ×£õ8ü}wâ“âNÝG·}‰í>,µÄeSÿLþñ\|ÕÀòúÃASË®FÖµ4~ñ/.RY& ŽÔµ:¦(³æN#AçÛåãk±Ûì üñéÆí¡-(MœŠ‚ ïßÖ9û8©HYQsAâ¦ðh™jEަ«GÂï᤺VËÈN::¥«^¬úGüp÷i•émFÔä–‚¥ç ¸($*z£ U›ÃS† 1 8^ž9“ÔRSøÝùr«P|wUsŠ9Hd3#4AA/ÕÖ‘æ8j@nD÷0ï¤wi‚)’›ªYšVÈ+áÆXÜÔÝ@Œá=Í%É‚„•R&B3…#.¥™¼B C9ñ¹¸'tWü@3˵LÅ$b,!DêU”ž•$1úWqŠTÉS ìd /_DdˆÊ¨€`¥=A=÷ßo(ņ·Dl&ô†Ôަ)_Äû@ÌÝa²ªýxf–ø€ÛbwíÁñV˜Á Së ¶Avpz¶ç8Â펇`ô§¦1/:4,̲«Êî±È0áƒ+¾c&7 :z€#ÁÏ õ•I(I£‘Ee‰S%¾oâaþ`Žÿ0sÅ 7(°Ù˜k¹>U ‘àõ` =]`–'cÜàzço.‚»xJ€I…Æ]˜uF‹þ®Ûú|øn„N!î5¡jñdÉ”24AUGÄ]ˆ$!ê cÀ>¼K4½•w{tÁ¿» „pÈÈ&1I,!˜:¿‚펠vÛêyHˆôQ5;¢Ýžäy•Ê—YdW=ErÁØ1éžÁÛ'¼sƒ*Æœ>"‘…|¼RU·º‡­´µÈo$yf€Ñ3 B‘šH¹NHQƒÛ7×4³˜©ž[DØ–´¼SK,ÁåÄqÕ4 Y.ÎJ¶T…òSå¢Ì» ¥¨¢ZTbH7•rëâA¼W›B®5Æ ÀÆ ÈY55ŠªSÜj.´q™áe…V9ª}ÞGw¨UXˆú‹aBœ±Á<[¥-S®ßT\!ªE¥º$ÔñÒXÝÜž±+®°¬"êEé†Ãö”Ç´YKtrú5-E‰¢T›É¦d=Ø“OY˜’qÀ‡ÇÑð€£¦«Ó•T×5j[¤”Õ–Ò“Å4rV—TQÓñåUåvE sáuƒºÕ—f¿EpIhÐ\bf”ÛVXÙã,KBDYzr\’¹,™‘ˆ!º‡l´ÚW+hJšetA)) €|1©Ràhr„±™u@Ý)˃¥É5áX5=Ö5¡¤ž:e¢§–¢))€¦–¡•äñ$˜“ñK·KŸ‹'¨õq>¨Õ•ôõ4Q t‚šyêhêšz•g’d÷o•'RêB‰ €RX-û6Éú©`ÍèÄËÄH¼³Ö%˜¹sx|ÄT”’@S‹ö~b ªM,f -Äx IEZAG·IC$R%DSÂTÐ$t©e©©Âø£Ç¯­(̲]r¦LŒn¤ämÃŒz[–ôµ2øzzÚòÆ«á­YY‚‚ª¢ôøI$äýÃ9tu°©†·Å„K¬ý›¢UnÓšn ·òúß4Î@ˆÑØ**¥•›w„øƒ$ŽÄ÷ÎÙâÕМ–æÞ¹ªž‡—\—ÔʸˆŽXl:>¢iéæ?áG ÷`"vRƒâ á²8Ç>Ûf’»E¥2R1+X-äWÇti•fŸ8ÿ*Î¥³}©}Û„YšÇÙ;Û–º\sW{7óBÏ¥9h‡PjŠêÝ=î«UQš®yk"<"Y™~1Ô°;&z0=œùCÌþ|éíC³êþQrÞ×m©·¬±s¼³å•ÎQs£zÖ˯ÕuWh£ðI”QÃQáK ŽN–eÚö%Hh³Ì6´HRRz VJ‰ PâĂ®haß ´²d¬ +œ^4 R‘½™Ú¸V.x=•´­ÖRëomg»]±Þ$Žß55ô<0˸Þyq¡/µtèd1ÈÆD!àuv‚]9_È{V%ÿÚUߤ¦«¨¥¥~Xrж¶–º5u4Õ‚§™½;-5<€)§2'Np”m-£i'ôÛ`In´ùˆ”îÇôŠ w£öÊÇ)#§ÚñpÒÒWƒfJXîvî¬V—Ëw,é) {5O2.Õ“ÓS¬‰vm?`£Š¡ yü9íRÕÉS"…AÓz›9éÅýŠ÷Š¤Ñ ’Ñ3Nš§ZÞn”Õ¦@é2Z©m’FÊîHèŸ}† ï¼K·¬¹²äd¥à )E"˜ÕdÙÆr»"ê8Rª!!èîßê"”4¶3Ì:íaGhÓôõõ “%šà³^4åžCC5®J{e·PÜj¬æW ,r¸gê ²a熾¢šÙj·\9k@ÔO1ŠUòž:· Ò¬•µpi±OâS$˜‘Vlø¨Ž·2Ã&GÒ̘«€€ª1*Lµ%$—$¸gÀ…¢Ø¹%fZ ³(JȨê‹áDÛ÷¹¬9GíMÍ+tU6ùyù®-´^ü•RÑéma|Ó¦¨¡×Ɔ×g¬¦§7Bz•Z3¶x yí;SyñgÕ<ÅÕº©äGÔ:²é{žhãHÀ÷¹Y€±E$ô†?> ͳ¶mArìr‰r« ©úµ¼C“ARN3mÖÙ …Z@£ lÛÂ4«˜\î·ÜEL6•r²§OR‚›ž®¯ˆc׿ž|¸ÖƸ­]KWÖ³´ÊæX¢GXÈr£7l('cøè´”­ŠC]ÓÇ<¥l\ãñÕÝêVu‰j”ŒÏ'Ã×,R´¡·Ãu0r~'l(í«&hªª%«5r—¨žirÅiÕYUº‹—.Ìr@ .ÀÆA,$%ƒ~aw@=OÇ´rija:½p¬÷ž¨éÙS¦Eð™QćrÂFR•È;‚8ê¦;¥SR\…SL¯¤“ÄœË$`‘8fê’OÂÛüE†z”qU× a­vEŒMñ…ùzù&š½Ô´‚)Úš¢œˆ)•ƒJòG (Tx‰)¾Äô9F*H-æ,‘Çy¦‚–ž4Ov…ç0ÕG2Îd,bHãq€dr ŒÅÃ|8~|©!A?k{ƒÚ-#¤a@|7áĬb­‘â†~ž‚CJ…DkÔÞ(ÈR¬Øcb»ðÿhÚ¡R)"h¥W+â1¨\2 =+ØöRÛŽ”Áu'1ø‡(]íáË^tÖº½Esëš·—Áêºc"#!Œ€øêê¤P:T 93¹9r”TÕ"½$”ô÷Xî $PÇWMP%<ì’ÔŽý-B°bœðûLÏÛŽu‚BŠRICâ/‰Î„TãJ‚(QžÅy-XÔTu‹QY8U |“:K[¿C… t³1º¶ÉÛ]:V›YÞ!µÓÔPÉ*Ûí¥b«’¢Ièé¥KS3Í!5“x`¹f=J`AªD¹—žé˜î¦P+R@û±§3OŒãn¹GuÓ††év£»]-vÚ«}î§MÛµ-^‡DöÿâDס¬oÝ×{Œ%=ÖãYèŽiIôMsC–z÷Wßµ74eÑ<² z J (Ú–¶ûtŠÑ^Ò=ÂájŠÝÉ]^ç¸ÖWP­òhžŽJ[[KtÕÐStÂÇh“6`¤–fÚh€R:F` ˆâ4¯}Ùԋç]ÙA8שƒ–Ï"GêRê- jÔ7¶µÝ·Ów(îušNÇd×ܸ{­®¦{·JýK‚€Ùiíæ¶E§‚‚B’1ˆ!‘c†š¹Z4 ­7'k¨±[ª(LÐ[¯¦ÝWv ª÷tzú:É-ј$‘ªÞ¤Á,a|hú ¨‘¤Œh—*Õ/£—jMÂÅŠ€RP@%.0®$±„­RT¥®W_"΂^‡‹ 1á–¶äî›Õám®b·ÐGCM)¹Ñ¥¥nSÜ)¤«÷ i-‘˜ 0Ý+Mtq¬"yé f2c~5Ná졪í’Ë[K¨4Üñ@D-W8‘Ð`‚áézas‘œ ÕŽ¢7ãë‹”–pÙQ³ßÄÃDÇSx䆮چɵƿ¼m5pEÓ$‚V§h–C:T()$bL°ØËQ˜#2äeösžÃ>ƒó9íÇ@nI>XãõÅQâ´ìÏ/KI ƒN0F÷Œ\sò ð%²«üA"¦SRèÆiË?^ ° ß{ƒ¾8ÀU´…ËtSÒ5%€.¤±pÞxïé!"€Þ5H"á9xƒ$IøÒÎ@Äܨ LŒs¶8’ªR‹l:»n[âêéROž0<ýE%؈ˆ1Ãâ:’®½åŒB­‚ ¶Á´Œ1Ý’IòÜúð¢2†…åi:€ÇJçì†Ýœ`pO/¯«Æ, ‚2oH)HzŸ XÝŽ©G¨ŒŸ»Ïv‚áo Ûy0˜B üdîÙ;‘þÆüRHÁµH®ÊG*%è¦TfìARzˆ¤’ORú·ßcØp,U‹‘Ö¡Pô€%@8=ñß·–8|A)ùݯxÈN¡‡„Aîc(ʼnËu-‘?Ùî÷d¾]!ª4”u<.k)ãL<^öªbYŠ6Åü7u8#n:j ¯H&Öº‰ê*àÌ Ò‚@\ ɇϦÜsŒÌ¯êðƒ 4ìöˆ}Âù=mÊJÛŠM- }r4lŒ©ñxʲɆG.ú’+ƒiÛlt²QQÇZÝ*BM=MtÎË ¯M™#‚Y@TBzÉ,Œxç©bl½Ž•ÎéÅšgBTX.áMÒ¯%W ¹Ãb ݸK¬+ƒo‡Zz+e]ž¦P7C,ô®÷Œ©Té©35,ž ©"ŽB‘,ŠK³+3šû+YW=-5 «SnêšX_ÇMÖÝO™YGR²FX'WÂ0a»em…6¥NOû4³|Ò«¬S‹Ð%€c‰‹DË…jUP︸‡{ݺ³LRÔÒUQÒMCS2S™¨äv{uŠ@GLç£Ä…7 ØÊä ÆØ{)ò¦ÅÏ>nYô¶ªçO/y)¤$¤­¬Ÿ_óR-c=‚†šÙNeJh¨tN•¾\«®s+£§Z.™Z,;ÆÙ[j˜-;>mªÌ“<Î `\¢”( P\¢Ï-6™ÒP¥Ü—1@@¡êï `ìä äb=|²û<~Ï-;Q¨hu‡·V¦¾ÓZ.~íjnQû<ëMLº‚“Ühj¦¯¢þßÖhå¥Q[5](JƒuÛÌÀxRFJ—3û14¼–t³Aíu͘á$—Ú›-¹;=Uµh*ü [Q‹Uë8èækŸ¸x5<ËîæeUñ:Ñ"Ñõô!,2l}êé0ªn©$p]31éŸdYÒ›óÕ<† ž©˜¥ŠH|H›\·Ão>ý‰,V;œ³ö!¼Ï_YE55 ÿ›ù}_YCPñMsѯÓ),±Êë'†dèsW,¹â?7¶-º(àCÙ?ÙSHKO PÑÜÃ×S–S“4”üÓæ}ö¦.zˆ‹S#P@±öŒàÖíµ=HUnJ»)1Z•ùR?Ú69.ΖT?rÁX8~Õ)`WrŒ'¥½¾½¦ôõ¶hÝC têX¾$´ñª&ëe#§U#Óñ×—"U"Z%¥2÷Ë 2mÑÏ™:lÕ^\Ã1X9$üÇ~pá.ºÐÖÐDµñMÑÔ#…äÉ(¤á@‹Ôù_´Îs·n!š‹š)Q©¢©‚EYƒ"9|5zðã=I€@Îùî8`ZS@+ÙÃ_˜Q¹gŠÎéíaFu¦¡{´BO€?DÑ ¦Ã1é;ýsÅcWí°UGQ¾ ¤§^˜%«™Ì‘…éè!¼b«Žä|öà/z¡‡ã”c\="pçeöçRÓÐÓF&P‡tRà©f,^%É%²IØgˆ}Ó_kÊ•QCtV®¦ŽcÓ‹!YÑCuË Èï¿™k,šÌÀ•&¹Ç”WSW껥\­,þ5ZÆà·¼ÌQ%ŒÌŒÀ1àà`|C~ülÑS]Ú±ïZ– TÂ4I®•ì³ÔT1ŠŽ::Y©ÖVC<‰ÖñDæEŽn’œZ%^P ,7œµâð%L(ðã„Gêô|”t“V3Š•¦”Ã#ÿCPAãCï+éðÝrŠJ8$o‚ÅWHiVH$¦êb’>¸d)*‡9 êÎû' Ô‡ÈçÝœ”.àĶîÐŽ¤¯£š:ŸfZwŽ E“¥H)’¬|0\·V ê$p× Â¬¨£¢C$*dbMÔ¥• àŒt†]ƒïŒñœ 1Á5ߺ!¨¡ƒ0ù‚kj"ž5š™åJÊyÃ˜Ì ÒÈ I‰@ø]_ÄR Á8Øp5}Ds»à½<ÒuK= ÒÓŠ†@I=$2’ Î1‘ÄJhÄyQ €&šÊ$zWÞ"¨’hš&yĉ÷M55MDUÈp‘Y€=/ªZQÒ$.©?ju%ÃôˆÙ+'%´V­z–Ókx4t5m/tÓÚ–Õ,ôF8%žó04µ™%0§÷¯y>èÒ½$1Ä·òsN[/ÔÖª›$Õ45Ö§©k•eUCZé®4ÏÓODòTtÁW-¾UÎ)¥èFè,½{<‰e)˜Qt»1aGù|ÆP©«T·JV>, Wž°ò&‘/©ÐVФýÉ¥hjŒ2¬WÍM4”QK)ÄJ’‘‰™úOH8 rT¸â1Y¥¯ZWPÒIS§ijnTÊõï úÑQ=¦š¦žZéhnTrCàÅD2ÊRšU^Ý[ ´¤% ³Ã/8RK©¯79áÚÑtÚ*yÞ×´¨‡KòòßxšÓ_v’–m³[’ÃUšJ‹Å‚²¢+tVE§XÊSÏN”aD}¨(¼9UZµ}þÕ¦ï×{“¡§—ÆÓô=!£ìZ%/ÍIU=Aªª±YeŽ+…Â5«ŽžZºjHc (Øx€sT¹„)e)R™î¤%ðÛ!Z5 ar”Q Üj:ŠŽ¸'>;‹CÌšóâåbžZ+e}–Ž¢ºê*®V‘CAGM2HÞùK_(©¬ ,`ÓÂ7Y(™X-+ÍËg9ôÅ“J^ù®¿³V½GsÔ4µ˜VÝ-y­¨±ÑŠÑQ5\"«–Ò–êk‘눒I#Yš7ž—$éÈ‘qS *J\ë!) %ÔÎAQfJ\¨„‚c§³¬ÓmST‰-z\¹³Må!I2Õ6`a ¾P…'îZî¡KRRk^\_ù‘¯ù“2sUTéùlW»ÁÓüÊæ½ºöõQØm=BÛ«žzH¯w¹.­KIOoZ…ŽYzºÒš¦¡vΞËk‚Ç.¤Ô÷ûn›³ ¤–Uª¬¼hÚ`÷zKe-â¶hïÚ¾ßW,Ñ[î—†’h\TàKÖŽ£ÚH±Ê³H·ÎHµ)Rä©i—2\¹–…IOD ˜nƒuÖ°’ ²²°Dz‰¿O+mÛ6…³é© ; J´[dÊŸi“>×g°Êµ8µKD€g¥E%w$Ké¡9„²!=[g¶h*³«½S¼47‹%<é§ia××PÜ€šG³¥¦ýIOw¨Ž6ŒI\ '2Gë4d m9©b¯¯¨¶ß´­^Ьž©âÒ5%¬áÒÚžÑe·U×ê«åÊ骵-mMžº?r¸¢Ž•â†+ŒÍUW†!Q[q+™`´I›+û>Ý.J啬¡SÞºÅ"ðèä•#—J„°’¨èÙ~L«&Þ°Û¬VÅíí>Ó"zdÉ¥Y•#£“)*š‰·VmقζI’2Z¦•„Åþ«OThµª®¾©¯°_èèà–…Ù§f¦¬žž8œ¢‚(a2“€n4C^rþQª’“OÛn54sÛ­“8‚ši’Jã4YJ;\®´´ÆX$H³1X‘Ø©(×lœ&d¸_±ýDx)rŠ]9’ürŠÔÙ*•¢§§Ž_xrG'\) Y žXÐCW#¨HʳuuÃÆs°^nïî«MW,2QípÒø*ñIïW=Dus¡L’7bFrb\`‘Œ`¥iR·”KÝ®ÿˆnð妚«À©&þ"ºñYÄŠ NÑôŒt’2»‘äH1ømMPj ¨Lò7JJT…~•1°*à¸]^OœÆuQK94=Ð"èûR¾ç%Ú­n!:‚ôX¢Š=¤i€^Œç¤È@È$`HÛ맆J˜ß& ‘ˆüFbca… ¹*¸ïÜdg‹H’”do¥;wE€í„ pTôÈÌéáÈXª¿À ‰…|dg9Û·cÆFŒ¿[î§âÔõä‘þ³œ}Ç;ðÀ0©¦µŒãâ&~–žåO$aÄ$TR®OPd=XÁÊ™\äìÀ¨Â±âQAe‚†XgYæ£*±R¾°ÇV®Ã¿|ùyñªT°«‹%·ó ¯xRœ=ýÆdÚõÖßµ5UDh¸*±Ï(@ü"ÅNÿN6!ÅË¥ù­¨í²C#Î*#GÓà  LB&cœÿŸ?Lq׳Z'J!TÜj2Ö„bf’°o'¬Z¸°ù»Ò<ÚÔÚJë9m¶»g]‡FÝo5U­[=ºD‘ŠX$ŠIUI«ž>˜#~²±¼„¬qÉ"yµSuÔVë] Íp¸×[ëgŽvz¨©ÊÌPDª„ª€Ì‹lsŒqç>®é¶¢¬²W/«-*fvrC–Ȳ|ë ÙöyvYkPUå-aŠ™À>¦°Îú§®ygªÙFUË0'á#•ˆ#cØíÁô𶦫"YiÍ4èÊïX¡£ÂT–V@±“ŒqóÕì„¡= ¼•Kf)p C›Ç(×4+¬o¶ú¤yCµºÃ¤%¸ZõpRÐUÛîôºZ˜ØÒšé¨êië‚<,Ì<4ì§™K“YKÊí=K<‚MZó¬‰×§¶ªK1SÕ0z¶ñ"[à)#q>ƒoíUeŸe6µÊ,•Þ’É ¢Õšóø¼.Rf¥j©- æÌÛ%ÌÚ}³KØR˜°ÒÚ6m#ªå…{µ-Ú(kÚ ™§Þ.c© bg Í…ãVaön¾Îê%Õú7’4™iá®»OUá¸,OÝQ¢Ê¤.>\{;Û²ía.Lõ§gÚh‰Š.»Á\ V¢¸5!A± ›ŠœR}w+!‘Œ¯Ü“d¨¦j­B ÑÛ­ÔE)­ÅÁ4T±S¼‚IkGHi#fÇNÝ\@u5¹¬ ª¦xÒS,‰j0uƽg¦BëŒ/–wÛ¡k³¢WXN¾¡•­Æ.Lã>ên]J@bîìÁð†̳D“HÅ\uÄ"(ËÒ…Œã¤‘ö‰È ㎕|˜Î½­#n®’¹ˆ?Ku§¹ÆÇŒ'Æ4ù>µ¬¥Š}ª‘^6”È©¥Z€HÏÙ`{ŽÙ žd€M+!þ‘«*–bòV’B\u‘†ür7ß‹‹%˜¶ïÄŠ:$Pþð0¡_©AbX‚„^ÄyïÁ) X˜‚ …fL“ß¡b£«brÜãÝ+÷ãøí„ê§—¡ G†XÔYúЂåË(ÀÇp3å¿| ˆ¬‚*•r³ña˜žäuc°ÆÄúFãÄPmØeÝçVJzйÞG1Í<´½qô»¬•(!*Ч&N†$oŽAIŒQI$O…ÉE“§«p HÛ÷RèvÎÀ‚}8X=u €ú0Â’’* >žÐ40fY¤,ªU[ ÉìŒccÛloÀ5OTφA= –±)mò3¹=óÁÀãC—Æ»c’UBPuDzŒœ‘¶T ÿnÜ.·ì+¾! @Üeˆ’7Üv;$D³W6÷×(’Mež™iZœÓÖ-LJÀÃP’fV-ü"†Ž^§¤€pàö`8ZÛC3Ë!JR®#ÆQº:-××åßê7à´ É*¨`‚áÝþ ¦¶\ú›¦ž°®OI 33± ±àŒy¸çéeï1Öñ0¾¨ž–®žr¥E&ŽQRá¹9x~|QÈå{ì žœu`CHõFÞáÖ/\.°Ï?e( ;Ôx¸Ž ¬‚¨»ô¶ *Z,Io¤T³±º·±z5p„¡Ó-/R Mq¦3®¶<Þ÷WKoŽz˜)}æaï‚j9”K5J0†œ†œÓ”R— NÀ’{D4À¹]¯–¬ð$X¢U•²¥§a‹ÅsðHŠí&LõœÎ+<éJ±ÚU1]"ä 8ºAeJ[$1ä3‰)Iº äÔáçÎ3¾ÊõS£¨¡§®4´%¤’ i±–Ja‰",…‹å0øHã`tŽªÓ9otW¤RÒXhç4£Š¦ß5åe5”)W 43;QIïrá¨R|9Dn«™ù{zÇiµl¹["Š'%),I´®WVñ#¬Tq'*Ò‘F]ûfè¨<èÞ$qÝÕ%«Sè›Í\r.ÒM-æ‚‚®®¥d½MDíMàÒˆëë#¦Ž> q•¬y›hŸ¤8ª"øíKO]ûªóq²ÒD•¥©–ÄÄB®æ•> 8Tð¿†ŠÊ ¶QqǙ㤱Ldt—BˆÀÔ…{Áå¬ÌJˆH9E(1%‹¾a‡˜ˆ­™¯M%uM+Ü$zi&ô솢6£§Ä½i5J(‡®&B[­Ÿì©n¦®¹Ûn1­Õ+)dŸø™äxQ#N”©ë™™€eO–r:{è‘ež»T€T’0bªŒ¯9ãJ@—S§u[”L «Wuéš´·ÒÔÅYü µbSÑŠ”¨y ©¼Y%Š "'‘1,1Å™ Åâ!œòÚŽZIÚÛUOOŠæ‘UË¢² yR©—ÝJÑT2TL^žFÔÈ1&ÿsÕ+ôV%Yå^R%-ªd,‹ÉÓªšKòƒê¤KZIÁ$r”§˜Úêxa÷êØžo U¢‘ØD#QÖ uFA…œg¾ÇÈMx·R VJŒª1g‡$±Œc9Àû³Ç½”¡Ñ£ps ®¼c}âM°óg‡§Öún†Ä³ ’³¶ jYS‹ä˜Î2xg§æ~•¶[ÕëE,µk»;:Ÿ´2>º±øIÁùyìËéIvv÷"ñ}nøõ1[wÃKWãRÄeÂ’ª‹tö ÷wÎüsö†»|FŸ¦#œâxcí3uüÏÏŠ f¦†³‹PHÇYEmwç¶¢«êOÞÄ) ¬‘m˜å— ÷#·Ëˆ|šóSÝ™b…¯5®ýn‰þ (ZþÔ’¢ØXöÀ%%½é¯,`8ÓUÝ*ž“Ê’UˆT;×Öu8M–²±wã©l—É ¹˜®K-eBÇGGK$Þõ$‘—ÂÈïÔ1†ì„’;Ž›2ˆ¨¯c{À™ÀUßË(„ÑØµÆ²(&¶Þ^N’‘ÑVåòÞ@¡ÜãÈqqRé}¶Ûl¹%-8s[G,ÒO–G *Ñèæ®¥‰0ˆ&¦q…ŠvWß¾:C ù¸px`qL‹Ë*S¨–6ÿØÆ•ô§…ðÜñná«”Þ;ô#9¨EM9Ö@‰ t.Ò\áúÿ*´ƒ±óo™æšÙOSn§¢ŠJº†¥4óÈ1-;Fñ4/ ,h½/ø@éƒÅ©U¢Aê7Ë•1Ýô]¢ÓEÑØÝi©æ»[¥§šg§—÷wKEENjºb¨÷¿K" !%›Z´±Ô×Ü$¸;ÓÙâs˜m„%¾*w•à7[‚(oªy±L‡¡|YÚEv±e Yº¢òÒCP¾‡‹¿d"cKJK:ŽþcÁ°˜>ås³iµ£¨;½E攽E¶Š–çU4±I|z•ŠP WÈ'¥:Ÿ¤ üK_¥Â®ï]4¦UCUq’àèÓ˜h`ªšRÂX¢_™”° ÌrŠ-ž6¨‹ÝAöñΞšÊ3 ($0&½”ó‡÷¼×2ÎÍ[RþòÕË$Ó´õÌ0Y3°©7GPÎ羚ùèBVôÉ!…•ãøzãZÇI%¤YK‚¥ñxŒ˜Ë¬,3Ô(UAC&ôhƒ1ŸÏ|4VËq«‘TJÎÍÔÌÎY‹g©™›»1$ŸÄñNó3—:«WUiˆm—ÚËM@Kª‰©XÉRÐÜÝ*a!ªcø%§ÕÔº«FÅ_*Øã-¡S$«·•$–òô¤h²™S˜9º8b¤¾ü¼"½Ó\–Õ<¿ÕV[v¼VÜ`¶ÜâF¦d¦€ÔG"K]4†:éYa–‰ªPdáÛmæœÃäý¥ïÕòÜjîõ ­G<´÷9⊶’Í-GB˜¤¦0ºöÊȽ¸£$+ûÅt¤s‹°kÊg´Í”e,ɼ›¦í%‹¹Ûº$0Á[’‹CéÛ”¶Ï(Ž–¯yMME-]5DUÐ[…L ¼&JØ‘à`Êb©fUh…L²­-ÓœÑkÊ}_ªy›©®—ì^hî‚®ùzª¼Ü-wúzª+Ý–®¦®àä[ê)kîpÍ.u eŽ0ZvmŽÒ»Ó¬é˜(ÉS‡yD¤ªY–3ŽÝƒê=µ³S-=¡2BeZkIJ˜‹JRP™ÀãzâŠ]ëµÆ®®C$TуôÃJ'LÝ~<”1è†fG~¨¿YðÌLÄ#’TTÇ0¬ ¤”×-<þ‚®Y½ÎbÅZ*ˆ¢¨Œ£‘ø• ß̃·Ëíµj,”sÉ V¤¯« RÄç¤ÅXUSØ)•ˆòøöÈã•Ñ.b“ö)/Ⱥ}!,ÅÆ!uÏ-ʦ¡BÔA7JÔ0‰¸eg©Ha¶FG}À¢ª–Tv•R9ðªØ*–˜`yöÿèýøµ‹ÊRÎãUŠbBNO86œÓttŠ&ëžO…dpãàÀ'a°ÎËÔ;p‹-eJ³DfHe9Á#t•EfG‘@eQ±¸$ãsŽ)r5 îöŠ—‰˜R’’ ‹­¶‚¢ª(š®¦šžz§UhiÞ©Ð$®¬Ê hJ†$à)'|Ä’ï¤ëèmÔ5óS¦x€É `E<”Œ9fÆó'¼Ã’6xÜ0fÁaq¸‰Z¥–wˆi S”ÛõÍ!+Z9q"E'¥š=ós•þV¦ž¿ZkÓ¢ž²žV,ÎbŽUgQN@ yŽ7Jœ“t6„fš’îøÆ$ú§Zß4|z»5tô´ yèkÄLDsôESƒ‡W…§éV!_¸‰æ†öŒáx²j;]žëE¨?vC_4Ô´‹^imòRÈ´qUIðàu¤7D¯ÐÊǨɤMRT\]`íH¦$©iZx¹màhVY´ Î}<.PÔÑI[t†Žõp¡–AIS|,Õ°Çj‹8´ÌÄõ+ƒ$*2GƒrËÙCÙ>ù_XõܹÔAWHën‚­)©ÿwæé!jšŠg_(¨h¤_Š GX2ó,V+é³jIH–@-ö«ª\OcqxÑ;¥ºž…œxã^à4ÑL{Gû_4m=÷‘z‰y‡¢£¢ÿì…•Vå¿éúˆã̲É‘ºÜÝ êñ**²H„ôN×¢¹_Ò¶ŠÅ]p¤³B•w›Œ?îÛrÏ0¤¢zºî•Šž9*YR>·^¶À^0[6*,ó”‰ é$ÍH ½(¥?ùs~qIœ Ò Šúí8sñn¦×Ûê¯RØ/¢ÓGOTÞ†²’"3åœÃc´ËQR§,̨”¢Å-ƒŸÁá”K(d‹¥-QűÏF©×ñÏ%º–¾–HÑiåéV’HäÊVŒÆ`ewo û\Ç¢ƒŠ¹ã£Yæé3[RDL’™Œrõâ;lz‰l`"à p©¶ÉéÒºÀ@6Å”–”±}¾8g¿t8TX´lôÒ¼± 0êQ¤,Ç“"HÚ‘œ¦:z²W9F¥¹ræ¡Öq»ÒÍ@ò—«!šŠ®@zZ%ølÆXœŒwã%ƒêè1éER‰*H¨,)w7ÍQjUÚà7fârÒ·Ë/‰<´Î”ÐIà¥\}E%=Ã.~"'f*+ØáDÀ#¸l¶z_§=_E*8õÒ-­$¬-'vF”æ( H4?söÚ4@q!yI-€¥Sž®¢{œŸ.Ç厖^¦ÜaÆw•æÌÃøÅ¦¡Ž°×â&š6E53fF GO-ÆDt9…T œ©Ô‘œ£#lñž¤4òHUX³È@$ªä·GÂ0åÛnéxgýÚ2|‡¼"%|ŠI‹*†øz°,Ë’<üÿ:»u º;•JtRÊñ,OÒìIG[@dD+ëWèvRTåAáÁ%N@v€t‚Ï8AúcMɨjÌ]§‰Rzªƒ,Q,¡ºXõH§®wr½*0PÍÒT·u+ÞÑ==ÆžAWNj…e ÆššáK-¾x‘•§†XâGfR¤ª4R *ÒuYä‚ñA ¸áCÂ6c›Ì08¸4Àò1.ÔÚ2Ã_$Uôv¿wˆ³5ªžJXšg9y„ (PÊ€.Ê£üÆ+Úí3l²HË LÒÅI'êYW‰â"•S¨V ¡ˆ$à¸á6ùr¥¥K Yj N%½÷…ËR€ ÄîqË=zÂk4TáwPwf·˜P@û‰>9Ç.hnå×áã˵ %ϦËdh랇®¬È*Õ#–zhÂ4é VÆ;±ñ&|*¨Á†–¯·^Ú”SE$”*ÏKJ¸]á ɱH¹ÜÛ„ØfJ-Ëž¤©jI¥Ð¦g©li‡tIB (=ãy‰ÅâíMk²$ôsÞ-÷[­!‚®Ž¢™Z’ª–Y'ŠW‚²Is"û¿ÒL]]O!ñ¼š Oq‚[UE¤UU STò*¼’CN¥)᧨h×2Hò(9Œp¡x -t+Pazhr’zÉ–E×jb*œäAKMÑx6 sÖ xZ„ï,H¥iÖ2íGÒäOŠYLU]jŒ0I…=KÁôõ•–ø©è¦‘j£«¸QTtDÓµPŠŒ¤IEKt¢G…ˆF@ ö‰ÉÉ—5YT8¨+­Ì‡qÀÁ¥‹(ïÜ^ºÝZmGQ*Öiµ§ƒ4õÏ=}dÑÔG‚ê‰SÊ"І~¬h¸–m=QJÉ Õ¶Ïu2Ë$Ž?y¹Åîr45¢¾™ hΆw0‚΂9:O”ÚVy6kE…©ÓQ0²œ\]Ĩ%’Bª§À“S‰¥%H¸@¨.xaËÖ*‹t–ê¯Ý÷(£«IBÃI,Ð,3MKQ r$u½f4“‚©RFñbrŠY]UÈ^ièƒ=¾£÷x ‰ÒH«Pˆ ¼¨áƒJ`9+¤"¸Á ×é¥ÉL»Dé‰_Rp!±` ¢0bhHj0ŠP¢øŒ1Ú,{A£÷H©5 0qWàË*“;ˆä"!<Í X£=Gr…A9,²y5Í-%44qQD‹\ˆÐ¢Óε4}+MVfï*#PœŒmèÇf&tûÝy3dšŽ°HWe0çÂ! 5IcÙœpæÍÒªZ‰™–6”(vyd‘‰Uéëfb:œìI>{çˆ=V»¸Lï×pr¥²R<}ÃÏ™R®KD°z‰Wp5¸ Fycþ÷¾\Ú1-ΰ2ÀÜ$Πmüø<[55VëKFöž Ìpw¥8#?"|øÝ&Á:s2.'y¦îӮ̳-re0Rï+r{1Ê$Ö.YêGR´¶ÊmC~ð &Ÿ³ÕUI“ž¦š)õ|_ºcØ“œz–Hš _C ª;Ujû­-ŸÃ³GWT“°| v8òòã³fØÉ™€¨R¦‰Ë Ìsgm)‹dÉr©ÄbMýþqnbë~ŠŽ:žgsk–œ¾€*;7 ’Œôø×‰­Ñ´»²î ÅCÌkO³Æž £‹—¼Ò¹k½lµÂ c‚‘ňÛM=I«–:¨-ž‹â­?@ÎHÎÆ™é±Ù¥I˜óTÌ”Ð=1 žòЩ µÌ˜™«OQ&¯‰vA0¹“sI•)Ìöv¨ŽWž)¼X掚²”¸§v <&V#¨•ÉV²úzì‚ÿJµ5+0®¬µSÆhi%E¨‘%-TãôÎ~$ê8±ã‘-`M–ýÃÒ:«AÖ«Wý¢àÐeƵ®²L¢¢¸ÉWN\“!YªáƬݣTp7ûgˇëú©4ÜqÃü)-º–jN®•BÕ¨db ‰Ä”êA|óŽ:ÛvÌ™ ²”Òðõ dñ¤r¶LõMéBÚ[°(~bšòÊÞ%LÓNÙÏ\Ò´„‚NýNÄãïùíæ°…<—ϱäöxó¤}§-qŽäp/Cp|¼±·`IÛ<3_%¸Ez$ê#ÌgP` ¾ ƒÝ»$’ð;rÊ)À:áÍSÜ«ú‘¤ycŒxÌÏâ²F#ž¥øHiT´GŸ= ô/N*biañй9ñºQ»c>}º†}8U×êßÝÈ4 ‡8`/ aïü© ±ô˜²ÌØEG$ÄUCnœdàm’=Õ2´£¤tî«Ò23Ó¾¤ ùw< Û…Îâ¼ÓÒ°é-=2ÑT˜›!(>ÓxåJµF¡ EPè…„ <‡!~<;¢IÐ[†  `d´©üròÝ”$‚T7~!Xe™ ç«;88,C;~³ÂºÁšÎ+ˆ­ôìcL½r;JØ$ ©êÇa¶1Ž3ͼgÙƒáxç’[Ö5J JœÔ{£ÄëEqJÈ#H­”TÇ4©*´»’¾'‹;#$l` ³’A­¹Ks¢¤’ªi&sM 4ŒÎÊ”TéKKY9”°A.p©N@bÕx*QÈ’h÷ …P #=û¢¸šy"’j7gÏSÎH;o±ò; »íÃUþ Þ`’¶PÏ_¼‰Ý§‚ErÊ÷‘‰EœîÅÊÊI2·LPqL0!U§ã\¢¤¬¸=9hdR˹W#Û#»ˆÍ]ÖIÜ’¸ â!ÃJ?Ó1Ï|Ÿ9ybš—ØüC’¢á»{„4Âò¼òIâ2NT,†v‘äÆ:P’dê:[ÐdpMÎY¦±­H2GûÍ犡GÀ®ô©ÅÕâ“ÖQòwòã6JN †ïh2ô£šEgSD]K¨gÃʤ«Œ;($džÏqª •†I}ƒٱŒmòá`Á«­|Å!ê˽ôΞ bÕ'ˆù Þõ 2à¡9Úv$6CéÃÛÐÁOKKOâôÔµÕËÅ’ûÐWŽ`HD0E€¸n™}8|°¤©Cí ž5øî„›Å*N S·ƒw>pÖ ±ÔÍLíXÑICKÓ;R—Y2ïPÈÞ#Ž€éôŒÓºÝNE’ŽÂk)n4ß¼šI:„¦z# …ã¨Ç4u_¼#YSí,¶Ï±â1:&Z%L›5r‡F&€.ö%ü÷ŽõÊ”¤J”zEËϾ¾‘Ô=vù^˰Xð‘¡-ÿÄÅœíŸÃË~#U¨Â°²¼™8\qÛ– Ô1¾;q˜ƒx“…=!ÎàdÇÛñ WDhêé£S“ PAoã'ñSÀË'VÊÄ4(H#*ÃQF¸o-ߊ!ˆÜXyAƒ@w´XŽû©tå{Yšå5eHœÑ\Õ.4¬¥AQáV+„ÇQÁB¤• àð*_­™¦–®Õ-!ž¤e®–'–#Ó\V 8þ =(ñ.û`pÀMDÇUÚ>tlë¬ RRÅAÎìµÙšmC , I¨Hª’ˆ/ÓP·K«H'¦jˆ›+"Œ»Æ6ÜqdÚ9•©­…*M<~H¨¡¨JøUF>?†Wð×oóß<°å$(‘žXŒû!ScJå—‡?Í­§½£u ¾\Áuª]`µ #n—ž¥ÆFçÏ‹/–ÞÐé1ªéiâµÉhÕÓÒËsµVÐC5 DQDÁ< ޲FÓl2ÝdøÕ&hLÉjg¸øî!ˆä`&#¤K6ãŽìÆÖMíE¤µþš¡ÒzÇOÐK§!¹ZëªívØib¥ºÃjŸÞ©h*@Œ¼4kW#²Åá³ ao Nèé?kO×Úì–(m¶­=IMzŠ:j*zT–GTó"ø4â©¡“¥OI÷p¬ ³=5–Û"ò×0f¥)%ƒ„¤Ñ<ª£½ËGu‘N‹…º1Lsg V¦žwÖ:ï‘…çn­‡YÐj4­U\r¶¡¨µÉ¨¼… îÔ‚†®¦§RÝO,èž4…z0l¬G^þÎ~HjƒjªÓúý7= <†¾jY(ëâ»O4‚Dy ¬ˆø¨lˆ¢€GÀÚ/blË_N²MëB‚ ÔÀ–¦*.UΘ@‹mªJ¥‚À1wëTúa΢+I?f®”‚²W§æ5ßÝ^AÔžãM,Þé„ov–¤OÓ,¹ zÌ'† çNy·ìw̽'}ÔÉ£ôÝÚû¦,f:ºkäþé=UÒ)©žj::b_¦'Y£Uñ?…ÔT–yý«ô “g¿`½>b‹©Ø2Iq¼¸aÖm¢fL¹5!71á…«íZ›HVÉ`»Z«-׊uóHĈ¯2«˜4LÇ+Fpxg÷›¥kRRÆ+ç©@3M Ø€Š#„/Ä_©ÆØÏû,¢qB¥<ä,‚ÀÐGEFó(¡“S]‘&¥Ô‘R°£­ 5Uª“™@UŒ#FVU 0Q¸+öŽçˇ±U¥+‚ZÍ‚†g1¬•s )£FÀþò0V\0ÝGv=8ã…k³m)ÇiT¢¥9š35U“‰/ J%¤æ¢<[7øŒ)ªtŠÇ=vª[pn¢…\K$«Ó q'_ˆÝ/Ñ€îÏâ-S§t5ʪYV‚zpÑ¢ðêZ:`ÅÿÅ‘£¼ÿîÄ©êø‰#lökN۳Μ¿Ô‚gXß Í×l€`(7…­ ^]~xcéÝßì]Žk‹ÐÎÕÔóRTžejQdRª²ÂT‰ |HYr¹Ûn!´¶:šÚø¨)á&IʸÝT„%‘m‡XÇbs¶ü{{-²Të1´«ùj`T VìÅ>ž¨È%éÆšÂ-‹.­q†ç~œM9Ž šj( ‚9£šHf–qÔAxcÝé>l3™¦¶Ó©©lÖË=’©èéèeŒ4Ï5M EM<^éK,ñ{ÁÊ‘É2‰B3••±Ô8ó³~«"Ô¡úk¶"ÜÞ ‘Ö4`ýfEq¤, ¥k C°æþͬ4Lñ*ŒžÚ¶¢Z×ÔÕTÍ[v­j˜âDxh⫨‘ä RÍâÓ0Áb^çÕ:\žœÎJ®Î˜‘(œ˜€±L\Ng°ŠA7Å@ð0^£Öµ]-¨âŠš‰ž­£¨SQ"V;JD”ÒáB)2pu7J‘²S¼UŒÞíãx°Ë2Mo²Æzz|TÏZJNFÅŽTd•Y¬©²Ù&ËoôÅk}ÅeØ ¨Ï¼¾”¢]Ðjª×³MÝ}ác†1E5 Óõ4¯ã»KRæNµŒ)¦Ë°* 9߉šü•qE uÝ*àžš¡+¦<ùŠi¦)P®¿Þ£bQ]\œ¨Øƒ“ÁÚd‰öt©.©õñBÇû™‡cãX¶ ƒTçÚ ï‰^¥j †çl¯†ÌUô²IP9¦¥¾u©Ý)ߦIR#ux1¡8n¼2Ýõ-oîúE2FóÂiêýák¤’¡ªBvƒÄ!|6]FÄ0bÛù[>Í.|»'M)§YjÀŠä £f|b¾”Њ×°Ë{¾­ ‹\‹ 1ʱÆCF©+4«ñ4ž 2`tíXïÄŠ+´w 4ðIOUlŠY*ª’± šEJv¥B«î­àô#Æ]ƒË(]#¬«9B%]U%)D^©I Á‹o !«QDr îfnxE“Yg­¹YéêCCMT”Ò ~¦‰ ¦Jf––5$NìÊû‰ ³õd8âS§+a‚¦¦²ã#x1Ï•š¡é*„Q\5 %²– fÉhÞÛý]Ê­#$µ* mŽ3lX,À&@銮±©oÜCv¤5`%ì©ó‹ÏS$bôaJ]×%gæ¦ý¦¼Ø»bÝËÝ  ô#7\—Úê`Wµ%&p7ê¡`qä8£µ_´´N°‹ÆÖœçÖ4±WÄóGlғŧ)–H|9ÒÄ´Qôx¿ÀRR@Žwã“;iÚí*(3 ´+$ÑðÅXžñI6+<”¤¥!E9žÌ¨"©¸Xš¿—ú—PTÔVÜ+¨/V™Zçpªzš¹c©ŽæI#gñ«áŸ´W¾G¸¨•@éšT?)c°È!²6ǘ‹‰”ïH/Ì‘é‚æ`´·€>°´5Õqº«©^’ilî¹8ÇãÆ×Ù´õÂ[4º¾a6»-]©—ÆA2ÎõA ©‡Ue1,@\1Á$ÅKJ” Sû:݉bqå¢ëß5¢õ¤i5aÔí=á ÆJÓÉg¸H¢eˆ4†H£~¨½Ú UOoJª*µëÉénö}Y]n•Þ‹ûC%Æ›®†C]Å‚uÅ,jѰX*TÓ¸ãÑí›L»E–ÎÏ~] ‚(ÁªÌpnÁÛÄÙ²&HŸ4¬†]@Ü?¼PŠÇ¶zAÀ#¿~Û0N~|."tRÓ„Áœˆ™”ù¬l:ä\cì«wíÇ—%’äÝmñÛvmw@5ôpd³<¯Œlàg~·}GJöoVJ«ãÔE-4p!†Pc‘c‹¡J·p'—©ÙH#«¾1Ž ]Òö…7E8$eØ­Õ°£¢ê <Í*ÃÖu*Hp”e¼=†N ¸à9-0¤ñ¬Ò;Ó¯W‰Ñ"#½‚M"¶lî„|8px‘Ž_p‹¬þTõȲ>·‰AðبE—ÈøÏIÁÆÝ÷ØË¡®µ,±, ­%mP1*É„‚žzˆÜ¯Q±àn¡²;pµ$­A‡WñàÖ„VÙfŠOä†I!•Ï„åzÑ]:z—íd8óËvóâigÒÕoÖèA(Ð<ƒ ±·Ù8æè|×-*Y Źp†u.K+ñ›¾*{Z%5µu0ÔTA=@Wê_q¯‘-K°–X œ¶6&Ô[ô~-dÑÒÈX ŠH¡jYrÌ&F“øD>ù8Òp5%WSu#ðo>?Ê ÷-QYr¨ zˆB»"i"¦W~§@™š0½Ë€>áx&Ýv­‘ü::zjšÙå‘e4ôèŸjN©% ´ìÈ›†¡Ô‡%µíH ßô×{ŒÑµ-5Ac&EUdQø]y^.¡×$—lHùØF½JÆÚ¬ýE~2F6Æ{·ãBíGÐ…žç<0RÑÒÓ­ T¥W‡0¬~¤2ìȱS”bΆñ³‘Ôd*êsiã@ŠnØ‹;“Éê#¿s“߇€9a¯8Yvvr~5ßkm5+A]-MDtñÒÒ3¤`ƒQUS$‘ÃOO 3Ž ^¹eŠ;·J°ôòåð„ü9ý'‘Ÿ¿úpÍÀVœFìàòî~!ÞžVnH+çå¸bHùð•ðŸÞ³FIa ŒœtÆæ5î{aGžwì8΢zycü*ñ(ù‡¢²–Fô›Š ñØÛ>Yó¿ÓˆÍ °DZAñ­\y`vòðŒž]Øps>×þ–Ã4 1løñhb¾Ó°ÅRˆ“ƒö—½?ŸË†4‘È•p(,½AÕÀt‘Y%‚Ta‡…‘™X™\Ž Izò§p¬RN»´"+¨ôüRD—É¡ª.ª>ÛRÕ"ƒ=¤Œõ.AF;¼L­ž ájŠÊˆ ð íòõž3­ùÝÔ-¬yÁ Ðz>·C„Ãàôƒ„‘w’ù©ÿ2dn¹Áù¢¦Z¹†¢•¤V’®±C2¨ßÇÅ 8ÉaéçÆ5K. ÀCÂÁ îD ºbe§e s §bÁ‰¦wŒÜ#(û¼ûðÔöBä$ÅÔ©È2¡>k"‡”ùî¡òà ­å» »Vœ‚Š’ðnÀ¦–J ‘ÈLSÐÀÕ3ÔÓ |‘3K2('«3äuÄW×Jº¹ëêªJ‰åi:UHD’5|(ªß…Í,‰i&¹öajø ;[ØD~bÀ;úžÿÔþ|u óGÒC†ó9ùƒ‘öOÓÐp A’Õ0|×ZÙâh%”ÉJ¹,>£$ç!ÔçŒá%@tªf´"˜¹rÍàLÂ0Xç_‹¿—êÅÝ ÞC²t•TÕ!Ðx.…”–_yyœ;†>]øj¥§ž9+EB2x‘Ä ¶êÅ®TG†AøzÝòà‚I}aFoHžsYêXš2¤{¬á˜ãe9ù†A«ešÑä^Ý+lFOÿeniü“õæk¢¦Z×¼E'röŽ\X-D@0Á ¶6;gĶҷ—ŸÅøñ=ÓtK&¢°Æáš9mPÏ"ä©q% ®§(}Yq¿>œ&q»*jƒ,9ïŒö…™VyÓE&Zˆæ;âk¨l‘COáÒ—#%ÓÃ\’GŒêd(K޲¿-‡ôYèdeªš¥¢ÇJ´= èÙ©‘ÙD‹Ž­²§'¿‘Çcµ®pxÝ‘‡g[Wk”ž­ã<;*wD–ŸYUÐ(•*¦x¶Ï‰ÄËÕÛ©T²üöfõõâ_læ”ÂH^JŒà2€H;’­¸>@åÇY…¢x#§r®Fëâ-Û=.>§¯–0 (0ÔI Ó¥$éßé>¼_Z{Ú«SÓ"*_ªÁ\ga>ã·fL Žçn:Ò-å ÝVÂlÉYr\6Þ:e[}¯5TQJ=öÆwVêëd`«‘€²l¤.ÜíŃmö¬4f” å†Y”0a‚rdàäQŽþ|lFÕš7¯Àö@›* {¬ßážý¯ùGÍOÝÕz«OÙ«®ÙÑéªæ…Ë-2ç ”ޏQa‰ Ïsì“'KR“0•¥³838~^1¸û(svÝEAq¦‚Šá,ÊZ*£Ó´ŠåÒo„‘1€zXïÛÈñ±òŸXêk¼Úyh.t7KEzšCN@ÊñD’H†£&A^¢JàäyËGÓ6™V›4µ$(O ‡ºìy9àXcBm’ú5L"èF г†ï§Ö/ªd®bGn¦®¦ºØã«x•楺CtŒB0D5t”• )FEvïø¨uæƒÕ<¹«JMKl¥#³Û*éªá«uRtôtÍ ‚zã@T{`Û?JÚ¬Rk/ ÝJ’ ¬R*0 >þÆ‚³ZäÚUvé 󻵌T7[­[E4“<1Fà,K"Ôp<’§bAíœü¼Ï,·iRâŠA‰ Èá2z‰uc$àã9Æ@Üúùù– bÌ%”ºhàð÷|j˜¦Žx78™Ã{‚Zi㯘I2™y!YY‘”¦ì“ ~Ø8 °Îpˆô^ôë"æšX²ìõ¯W[â@FFì; qijÙ&YŒî L´¨ ƒq1¢”¶~Ð]}Mº¢AïM$³F„7L‘áÑ †?ÁaÐêeÎFGn™l·hÙ ¦©¦tbˆôÞSÑòêôÎê\¿OPß8;qÕM¢Ü)`¥(”Γ‚jR8˜ŠBT\†<;!Ò×Y­¡@!ÄÈÁq°eèø[Èò;qÎ4ÿnÙ³‘1ù'ÿº0Ü_øµÛ%5Lô”UŠ„JøŠ‡wéëHÍösÖßý8Îxl§º\D”?Åw4D%*ʾ2"@A’sÛbIïÇ è¥Lé '‘{·]ÿËO˜Ò(H¨üA³TÉ[\­,hý*ÊÐ"2€¡›¨,~&U`BƒŒƒÛ‰mŽ–™îÄÏâSF•¿Â¨òB/á+°aíÔÅz(Ñg±Çí?ɳ©).‚Ûܾ°¹¤JÝÛrÔ'­£†‘𙩢¬©¨3¸£DOŒäxÀôtȯ Bá²XçLå)aŠ(M o\•r)„TÈûËFÅ™DŽ팱T^É(‘,­DÞb@¦)èÞKR fñ’’æ¬wvC¤úŠëq¤Z °QG5e-Õ;?SWÒÃ-0š4sˆâ˜å…=#2Ý©ZJ·ªX‡‡XCôÆ¥Ê2®d*ü¤d‚Nw9;6iH³”¨—zœÏPà‘ã=WjÖ½ay-ïGIL©P“Å,âX±g§ë XKÔ§!€\ à`ã¨q.·ÐQÖ׺¥,ĵoO$h S¨hüRǤÓSÊFzª6PIÀ56zŠ Ä/Ό㶹…­ëMWÆ,­= ÔÝìù‹Á…–’wª’*p¢R£Â“§©fgÓ¤ Ì¡—lÀ÷©Ó7î¿¡¨‹¦i UE"‹™~ŽûîVà6-µ"u¾ÊTDé²ÒH"•g#{ UCŒ&åò~ä¯Ê÷¿d\2óªô=œ'å]¶£÷L–=OjºPÜ)5\öë½Îž¶K”× T6zjpóSÇU]Îd™`Ä Ì‘¢q¯T£™:Šî¯oԛΠ¬‘¨–ªá~¸U×t©ñT »‡à³ œ.P}xôÅR-kRe\BJRqc“ðb„èHY³©S:áN Þ£¾Q$æ†ùœ£«¿RÜ(µAí[8šYc ã<¡\¬ŠÌe~ HÉÀ󨎠EmžÜDï<õ*Ðô³4kEc•ü2ÿ yQ°Éé9Ûg³&Ze]–’ñ€/‹°g5DÕL R”îMxáLc|Ó×RK$2¤kS.Èꇭ‚œœc³-íFD”‰ôb*Šlìr!™*HïŒæ¬ýÇrê°x7”0)ÒC¸pðm¢ïE&‡Öf¢uЦïCBÖälôÏ]Op’rŒøéŒs '³ mÚ“«²×ÑÈašÏŒÿ’u‘‚ÑùwkœBÓ Œe¢éçx‘àD"XRfN|AéHôŒ(¨ UÓERÑR¬•!÷ĨHzUViY– ,@'d·tÖÍEOCp±ÙnvÚ‹5tèÞáA}³—¬ð^3L Õ‰Vÿp²£F3á)+Ôàeö¥@,¸b  I`qgÅ»bÖ[î€çcF ¯![}‚"Š:úmEI^‚Xêc†Ï‡“á Gu$•%þwÅÈ© å À—Ãâ.{•¶A xë*ƒiX´¤°ô°.àl€¼Î©4¦Ÿ…^çø’&QX³3¶©â†g'd˜n7áò„´‚F^­JÉsŸn誮·šP²SÚ誖i¥¨1EQ4ÕK<Œó<ÒË3K³u0Sœ¹ûÙ–Žª¦%–ª¡i©IcÎó'ÝâÈ·ÂAv!A\3õS›ÅÈ`>7E¨Š$s‡J RÔDòº6Y_ dV=€5uDª ÔXøiÔáÌ,.¢ž™}Ú“©z—¨jY{KTêG[ ü*Dÿ(ê,Í %€ åB¸p9ÂÉv­FŸ^±!µÛ–I"E\³²¤hƒ©Ý‚¢¢Ý‹c¤>'´ÒKc’ª˜(†¨Ç=\Uñ™áBÍYã-K(*T²ôÈRä µ!"­ñî@íÖ²Œ¢’ eåŒ6GPÆbÙm‡ÝÁ1H¥ÉVÛ²†GN,7û ƒ¿Ï¶Ü1 br¼Q`ô Ùk%ð Æ]]ð£,”ŽŽ® r;Î1Û‚©gˆ(UêÏHÎcqñ1%øwØw'‹IâݘkU¢rÈz¶1!³È²WQÀRB&¨§°JdIƒó^*? SÛ6ÿá´ÝµNF~%¶Ó!únüKAÿeµÃ̼cÚ¬Vƒÿø•éëÙmœ ‘ôÆqØ¿ŠvãLؾ,äy 3ß¿}œMà}ÇXÇaš»ØCö©·Å)jŒÂÆR!Õ\ã?…Æ34à ’r@Ø@Ø|ÁãÐ(pp8eøÖêz¢‚ªªå’9¤R…~"@,Äùçüª~ãÃŧ¹ÀNdëTV}‰ôäàçÏ?NäÜõ¯x&w‰…³˜,¬©!‘žäaA$’½¶]øžÐko)JœöÙ\6‘½8zf`0mÝ‘ åz]\øH3¶ùé`w9 }Îÿ>%´Zêª ¡+&U x…—9>^{ÿ.4¦c [>P²]UKÄÒƒ™×8UqXÙRNzÊ’ 'Fwò#?.%–þnÝá%’y™H0“,qþœã±üxrm MÒƒx4T†ß¬¢lç­b´k-OZ¯Pé|3ðŒuï²çñíÄÖÉÎ8®š£Ü(£¨­u–²¢'¨a­4™Ì˜8ÏaÇBFÒX"÷X$¸|‹®µÙåÌ CŸ¸‹Z—œVbTf(¶Ãl<ˆòÎßw~(?h'7,–;†šºQÇv²IVíAU'†•ÐTÆŽÑ |ø”ðªä…!Û«Ž…¶t½«³çÙR ‰Óbp¼•$ŽÂCv¼sÓ!VIò沂A½<üªÐº®º:z‹5m K$R»OO4pC¨ÍP¨ƒ©#;lHìx†ß(.V ™m•ÐË êªÝ, ‰D™‘Y@o‰J’;í¿~Ï*@\ÙE.¦##ª™¡jK·‹6¸C+ËUZR責OÒz‹x0 dƒÕóÎ~|gO]$NPãÄÆH…2¥ÀÆKtçÈ‘óÏ5ro%RØ– ÀâßЃh&j¾ñüB¹eXå^©§¯2üº;ûvmÒ_§j‰]|*jqÉCcððX… ¼Øs“ÔÛ“³ œµ­ÍÀ(0| xë8"h“¬ ?ílþBLyŽÞ]ÇàÆÊ”ÁÙÿÊ=¢]WïˆJ÷n¶Ú)㣨ªðkiL PÃ1i–XÎC¤MÓt˜Üõäž¡‚à C§HÔ´”òÒѰÈ1uÉû7m†1ê8×aš¹Ò:U¦è™T—Áb5ÝHÏ,’HÆ£‘nØ*$©rБˆ¤‰œ/n¨Ø…l•À'‹s‚O+l°2[æ†'iéªC$Ð’‘–7Žedeñ]ºdP‡*ÎùÎH!vÄÊZbüÚ z`S“oÊŸˆ…Ý(楺UÑL®Ï †_•(¬6VVwÎAÉÎx”RÕIAc¡¨ðÒxÅML4“0– Uâ1¸ÿö²’ü'D­€Hê¹Í6M˜?VmÊŒ.àïÜwÄ5JÿmW(9)+ª¤…b*ÁÖ&> J™_&wc2t€q€°Æ`É-ÔÆç@mÑÔÉÒÕü ,ËàʰÇ+,0žŽ¥»¾X?K³…1äuO*”„©G¤è˜šT‰Ê¥¹e WU 3ÝôÆna¬ô•VÚšJ˜åIÙ©£ÌR¤lðxO0!j R0¸Ft$Hx :Ü#³ÓSAUTtÉ%\r;TUš‡bD®ëðF€0 ¹_â6X·1WÊ%Ú/ÿ)D¨6`¡˜ðu?` ¤…3—¦tùÄÆ×[Cmj2GQ/ï*g© š?xëOÏWO‡§Œé º`Ê (?Íé[­Å–zê•*B²¢ÑÇ$#2‰!U'§¸±Ã·öEf"©’Iã¤uÙŠ!” ~[ ¤F›c`£Ór¥§îI©ÇÂ4"ZEÌôc(ôm¾%>%* ð-Ô3ƒžøÎǰõßæÑ”¯“2¨Ü‚ dg9såô^5 TŠyD2ÜR„üDb«A ª¨${œ4QÂÁн;TËœ†ÀD ?ÙìHw$1AO"»»tIJVH»ˆ“¶ï¾þ|h Gâ,à3|hGQÍ@ü"ªs–ÌŠrÒ0ÿÁß 6ê/ñ'´±üKWrg~ PH’pïŸw¤IØHÉ]‰N%€ø„MjÃÒé媮dI)‰T`‚.¤†b~bÿ =Éݘ‚ÎÌı˜ZìÆRZyâÂ+?PÇúˆ 3ôü¼‰€N%÷EuAÖµ”XÛYe©D1ÔÛk©Ù%Ë$´•´Î^']•à“¡•”Ž’Áã%§,^FPʼnêfbOQ8Éb{úðÛ¹=?ÃÊÆ;©å IXXzT–#Äucí°é;\péj»Z¬wz»Œb¡iCOMK";¤õG!£ñò¸j?}X8Ý_!úXô…>§8ÁRX3cøˆj>ÛµñÝ;jRW] Ž¦¤³+`{µ<“®2 ‰ˆíc;ÕJÎzݤ$±'%ÉÉbOÚ;w;’~|!íS‰j1ÞUÛV¡D‹4ªš­Dî,ÝÎ`FÕ i–,BΤ‚äºöŒ"†ÉŸO§:ìÇR¶2@Á*GÄNps¿Åü¾œ9@€Kã—t)9|píÝΞ§®ž²Ê¦ÿ(= Z30†áGÊ<öâ)w§Ë ÆFrTe|²>¿˜ôÇ+û²“P !¼e1ú@§©†îúÃ/S2ú0°{wù㉾j»{i¹íI³é©%­XÃKSayÙy>9)³°”4}@H0GÚF4í`ÞZxR‹T<ƒ§.ù)Ýâ’/ £fB… 2:’ ²Õƒ Œçn"U4ÁIé@‰9¿Ënç„—å¡ I>PM%;’¥•ˆ!Îy«1òáÉ$Žª0¾’5ÉYña;âZrÛ…ó#?"ï‘iz3¿Ä= ÁòhI º$ÐÚåÍ5r2T•VY#vFxågÞ2DkØöØ0mþÎVá…R…—¤ã ßáëøÈ;zo·ŸÓ.`Ppéó0Õœ1Ïv^Å=!‰žc$ä«#÷‘¿aÛñàlÕ'‰KÓ"ã«Ãfù– Ä€OËnøžd»áÁëaÝ Pzk(h˜Ø‡¥Ô•!ÁÈ`q‚žŸ û«JB¸ß¯c@l¼e˜4·1œ6T[‘²@è|ìÉñdy¾k±ùíçÃlÔu0†f^´ÿ3G–ÇÍ×AõÛcÃR§ iº ÜSÄCeº\£w¢£–dÉðGb3B ¶<³œÜIŸK¤ÖzyâÁX¦Xc—©žBílÔ®W©£¤I|±!—ÏŽŽÆ-)ªB]'Ž8fãâ3N˜©fY ,yS†öˆ,SÏO˜ºQqâC<))«Óa©ÔÌÄc±jª…þH¿pãÐÌ ¥R´ìÃÎ=J €r€â§žJ)ŒpÊàÔÓ¨*ŒÁBÇRX’ä¦~g„â¦dZ“$°Gˆ€ÿd*ZhÈ€9^ì7ׄæ ÙüÁ¿lrž(¥<²”†BB¢Æ¹~˜þvbÅÐzð¸2ëŒ:¾UVbÝDa@*£|ã·§—™›XDç´W¥*D’K8–nŠ€Äô Ÿâ …þã±âGªžŸ,a€ÇønTýpÙü3çÁ…9Á½"ˆÓr‡ú=cJý!ªÿLà Éï–Pr;çωU.£êUhæýHà‚2C)Æ{þ³Á¦càpÊ(1¯‡¨ulåÁ€zºNÃëå·túƒ¡ºÖFG;ÇÓ'm³ÿŽV PÝÐjÚÈÈ)W‘æ­•#|ìs°Ï°ëÛ„!@•úG’¹=ð3<—Ï2§*Y*I sjŽÌbGkæL± ­ÖY€A’(P0|³ÕøŸ#ÀU‡Kj;´5÷º z°‘UbT)@# ŒÈ=³·¦8è‰ò­L¹È¼—ƒÃÒ1© AUÕ1áÙíîcÚ4® ¯²Zl4¯Au–ª¾#A%,B*$Œ–v(êᜂND^çɵÑÚꩵ5E]ÂéEnILad®o?XŸ¨"–È;vÀçZ¶t›TËdé*èS,$¶$%.xÝ- ’$ÊP¾áÉ|7x¶éý“ô寬^¡¸ê%¦‘è)¢Å5$“êJxÄ­ž¶€,{œ’7<+pö;®÷zi-·4’žz*30œ°­‚©º^¡Lô쌓çì{þ‘ê¤&uR„õ²*~³q˜gÙ]”åÍ7MÐüzÎq†×ö(Ôئ¥§U,ÅU­sU$áX‰ðHÏâ¿ò6wþ³ÿÿî‹p°ÿfñÿð®¬{•Ʋ³ÝÖ*%&:~©f›1G¼HÌÊ>Œ³tŽçàŠ¸iÒ’š:p¯4ƒªPÿâÄÀ`¨øAÔÍÜd€£Ëx$‰e¤ºP=€ jèGh»¤†>’š iÔó †\d »ü'*¸‘ñcb1Ǫ)Šª<¤8›©èÆW©OÃßb7N¢–§­íý‘ƒÞøçjš}§Ží $&–•¥¯Á…ªV"é€îe.`Ë¿R±w˜Âœ÷%m¾8ã·SÔKUnx#Lôè“GT³8“ÝÒI\%`ŽEÁ‰º_ ®}™iE)e!.A/Fûw¾ã‡ Álå)H¼¿°ëº†4kzpÞ <ž áLñ±eºý¡ÕÒ{ö2û|öŠZKŠTÄMTŒLÞ'SÆ]¤ 3¤a\……Xƒ¸êdÏÂqÆ+RgÌ —,²Í×m׃ù˜¹ ( qÀˆ>¹…U<˳‰ uË+³6c¦HÑ%bHcp%DXíÞGXtÕU²$¡ZÊr· ÒVG¬ŒC$‚šx¼QáJñ•ÂÏWJ!=KÛyÒÿA2Ƒѥj¾–ÅÂR¢á;ˆ%*1 gïðÄGÝ}¹Mj¬dP´2Åf!¬- š‚D T»$hÁZxÁÙAã®bÔUƒKE}){­3S­Q§z4j*"ËP‰Lʨî¬:1¹C–Ýf³HDË2°™*ZîòZ’I8QA›q¸jèCÞEÔõA¯xòÝ 6[†1]=Ò*gÕSÎï÷¥·½ ˜i+$ð癋2H€a’ Lw©«® 0HñQÓ‹‚“øâŠC††3ƒ( :8队=úêR–Nï§œ2èM4"å·ÑRÔ·Ï°RÝ$i#xª(–‰èÃS¤«&ꪻ‚3Ò2¤õ0Og²[àkš]a†2U©’f‹| Œ«2™2ý{ÔU·#·¤<Â\Ý><›¾-Ô¢ ¿OHîÁªj`­‡ÝîQÝ(¢Ž:ªâºÏ†­ HÊD¡ÝC¦Ã¨|@ôñj½ÒgÃbFN¤#ˆ€ †='×âmÆÄ÷ãmœ1P*}ÜpË[áòz¥Nhr‡?apv.I8Æ{·M^î øŒž¯–=1°=‡ÝƦ¦:¤0®¥Ž©ó«zƒ9cÜàã9=¾áåóã©'H,êrß?"¦äqUn?ˆªFïMhGtÚ‚zG•iêé §“¤ꑌnÇä¬ ½=]àã :IÅÓ:úåkJ©ÖXžJÀ"w£š1†>® #‹³•Jî€ü]·ã× µ,ì%ØL·œ%¥šV‚ €lyÇ—^ÊXÛ¶t(,¨‹»ÐCÌæ"¢³iªB•/<óS˜ê¦EÀf4rTªEI#™2-¾7á³ZiZ;dPMj©,ë\¢®Vjž§I£šR]%‰G‹×Î2Vìxä/dÈ$ÛÊÔ©¥ P!ûƒèC¿µ'/i¦Çt&PYNHÈã¨Ñ‘gRθR »ê*U¤–#Æý¸Ø*êýa®tG/´mêŽÑj´h+”VÚñG(¾Ýd¹×IVj.d,¢*ou‚$ L$a#¶GŸ’VzYiYÀ$“ J©ÅÒÜŸœzµ%*]Ub7±öÂö}´ådJtªªf.õS´“T<ŒI/—\&NsÒs¿¯ŸIÃ~-m1^‘”bä622½;¿áßI“pW ýÚø„^vý¸øq†½AÌ[U•wXÂ\®JâX‚ÅCŽz´— vÏB.qœ‚Ev¯®¸ÔIWx¯¨­©™:E1’u22,> Ê‘ÜóörG RúEÑ,‘ã„ièP¬ÅŠÿ„RœÏ€hm§´×מEZZ8ÈFëHÆB1Ì’`ç¡A8ŽÃo„H””°¿ÆÁLÌ¢Zª‡8(>ÿ¤÷óàaÈB€œùaRƒ¸ÕD<Çl†‘Ù#**°2„+CNv±M7ý¹éí9PçIg«2ø’¹'©úº‰ÀÆI}Î7ÆÃ'@9z{BÃîʾ9¶YêV@̰q©†Ø¬‘¾>^|N(íÒÁQˆj)åŽx¥$Ç,MÖ’¨*@`êÎwÁá `ùyÒ±ŸÇ^Iên5rTTÌÓÔTM$ÓÏ;³Ë,²¹yfšG$³,ÌI$“ŸN ªÉÔÉàÄEí–P;)³ô¸àÀÈ×C_˜î ãñÅÕ,ˆå‰(P­ÔŒ€C( ÷,cÈ໋,}tµ˜¥…ŒR$‘*K)*Q’a”`zd!ÁQ€´5Û1q„B°@¹HU3ݱ¾b\îN2s’w<¬u«öXUKwÈ lmߊ´|ù‹$X?+{1PÜj¸+EÐ_®®®–¯Ã¶:%|üúq –T’y9þ+ì1œdŒäycËåëÆi´ÛOiî@WšãDÂz 2F$(ö•ä‘1¡uN¬§­¬Ó´´õQRÉ%<înêWG ƒST²áÍêWüYVÔô“Yî•vªÃ­ •¢ž(*©jâIühµ4“\wÔîN°N†`1ІÙMU%0y&©–Jº¬gšO†*@¡Tä‘–oÄñ”6Úµ‚uxL,ïÅC,-áªÌ]‚9ê#¨'`OôYÁ5qt€Ã—M=´"ÍâN_ÄŒ)0ÆÌ  cŽ©ºHÿ ²Fù<Ù-òÍTí *!Œ36ô—TGÚ+×äO*¤ƒ¿Èˆ¢hhï—t9ÔÚée•Äó7Z ärß;…ÜcŸ—ÚŠh㕊T‰©†û°8û¶°’q§žC°K ;&HócÔ> 3ÔFAIdˆÇ†Å?ýR28X n‹`{ßËFèïwDp¢A2ï.;ËŒ~dñ-£»VH®”ÿ™×%<¿Ôü¼»ñaEÀÂp\RÊ‚Cï©4ð‡Øëj;ôÈF6Øöõ?Gtq‘ÔF>[oÜý8s¨ ‡ô„‚ଠønÌF ç'8;ƒ‚xr†ñۃ꧶þG†¦kÃâ¥êï‡n‡ÆYÖsâ Yþ,~ÏWïĪŸQTL©þB,‘Jƒ¨KC}– ¸ÆùD‚<ø>–öƨ­o$ðGJÕ a¦i¢X•!YcÄ «xà —s¹ÉMt¢XM¨§ãó’LÉŽ]˜÷€ÞÇT÷ÅÏ[OPÌÓ'»§Auh£ 0d|Œ²à¯ZU•Êž z›"ÍWC\<ÔýáNŒ"1¡R …Ëug¹^I‚¥P1KyÃT€”$ŒOoxq޾ޑZ"(ãÞ‰ "0£ 34¿N‘ñÃøŸlp3j¸š|B:³±ñ2È@üI®Äœžä|üøØ€QUÝáÝ’Ôlû¡Â›PÐÕ“u$Ê1 Ì2qÒÄüG#ÈžEt@‚zIޝ"Àì7òõá—¨®„'ˆŒýãÄÇK3ÿ$ãÈc\ëXÙkȘ{½,þ**» êc$FÁLJž*!Ê¡8ôüÏY­¯k”ÉUAs’&§ž¾ä0`21² Îq‚& ©!M»>þÂa>,O­-+ƒ=P c¡Œb\œ•z×ü2g¼â°Û¯Â€KSdÖT_îQ>Úgj>ê.²½C‰£‚–Š™H.ìÎBS ݉Ë3nYÛud©§…–Ù,d¸h§¸±1I0`Uâ£G¢€‚A8H ФÇà ê¯,?B€vrá>&‡Ç6ÝA@fPÌH$¬|D²“ÕØ`ýâYGî|Dßb͆ÆÎwvúcˆÌ¦îè"hhDãOܴ客I/t¯vos˜Û­ÑÌ ¥¨®#¦7ºL“Ç4TQ†ë+d¯Ah×,XÞáM’XAg%T8fÜ*õð€vù/@kµ'»Ãæ ñx¼•°*¾&U.¸-ÕŒ¦Tàœî§;ã×׌cik ôI4Ð<½*~ gN’"CÀ*XN ƒ³c‚Ô+DùR(Ð0©üD¯MWÛlבs¼È±~çZšØmÓÓ<Þûs£Á ¢ž > f¸x ?YAîðH.Ȧq¾¥uÎzŠ›ƒUUTÏ,õ33)–Yêd2O,ŒßjBYØîr[8Î8ŠWXÑIjŸˆx§¸Á$c!TôžŽ¢¤(‚Œà?ÈðºÔQ´ÞcÒ^”,ƒ‰*½þ£Í%ÀãñÝÙ¡ÖáH•GV­g®zAQ#{ÍLªO÷t†¶¢Yr,Óäùu>"))n¼£]Äz¾­ú‰=ò,ëm·éFû9B¸æñªrZU—wGŸùÖiJÐŒ#©ä¤…Ì“,x!ve^Ÿ‰1ØÎÇÓ¾8ŒÜ%ŠU ªªä³€ `”Ÿ‘úñ¤Ï8žèBEXå­q€m2#ÕD¨Ñ±S‚KA!”ô“‚ÊHíþnê`H'xÊ€«°a“•?dƒŽÅX~<$, JQ…äz·¬2é2JˆÁMÞ=ݱ ¼Rô3—=@ŽùÉ'çðá¶žE|@@%†0IwÏ ýÎk¬#XF Êqó°#ŸóÄ’Ž©*|$žF‚¥L5j@é#ì‰ …ÉÜïóÛ~¤³¼MCi¢mO;LâžâëGpÀHjÁIY¾­±„ÿ«±óó!Ý©¥*Ôõq‚ÐÄps¿P%ˆ# ‚A{p¼ -ãËZ¤w0>4a‚¯N4}RÑ€ñà“QÖΖÜmó>™à§D8‘\6pÁÀò9c¸ßÓ‹pôˆ DoÚJ‚¼´Ôahª$„SîÒ“¹êE_á±'ºã`ž+F¥©Óµ§ßieHæFˆº‚P©e"HŸ³€È¹Àc‘ž1N•Ѩ-?k÷a‡í?vs|±ûŒÖV=âÛît¯'JÕNÕЊzrÇì‰$“žÏ¹ß#Ðh¹ï¡¯º^¬ŽÑ¨ŸCê:sl«•ÚJÚÃL¢¦*ZˆS\(Ö0YÅ=Z…ézXÔ®}6ÀZ: z … RC€á($€ù±~8nÎÚ€™Ö5³!*H*/),O>^RÓVÎý]=MÔc¸ï¹[Z$Š‚µóÕ!A$ ôF§8íþüqáíçýnh[ÌnÝí¾&Ú?ì3d§Ìp¹>Coëæ7òÛo¯¸+(è&‚¶yáød”2«†š7è‘cÝrØ °ìšLSч¨ŒUY¸ö†‹Åþ¥cIó†#]÷_„wÎÞCˆ½E],“š–·ÓÍ3ªuË;M6Y#Xþ|Q\€Q¾§¿³49,ñè,Ú8A0ÝIQ…†Ÿ«ü:dJxÔ1Ü”…@$í‰8ïÃå$Z¨þ ‘ï$‚U×Ã`b©ââ¶vÛà„Ä­¡Ë 7[=|@7 c¤‰¡XÂx¿[ņ(YazIÆžÜ0-uTAÒžo$eë+³ “¹wú¸ZËÔÐó†`2GÐ$“¾j‰\¶ÅŽq¿Úc’x«Ÿò0¬ÈÛsžÜ(b2x$ ‘ƒ„ÖšßRÙëªÊ˜â«n‚ˆG|õ8¿ËŸ¦x‘A¦I ÕÊIíÑ=#ÌåØg·¢ƒèxЙj aø$$¶ˆ’RZ(èÙdH½ ’X•$XïóÛo§z4”%é ¿|“ßÏðùq¥ H`Õ0¥(œN0é¼’Û‘‡Ëaòü¸Í­ÐË´‘F~} ¨e¸sᆴ¨‚ÞPMŽÂÃ)ŠGê©l£¸Vr¸ÆFËܸðÐô±O:2½D¾& 9ŠLFlã¨ô´[2ppsŒë”Ä”×Þœ!É[ÑUméýú“üzy£9fCÒ|öuÛÏ‚i®Å!ðGýÞ{lF{ÿÏ’RC–ˆ:(cS‘_X›¶ÉzöÇÌpáñrwøô‘ÿÚŸ@xҙ怚ëFeݽÚð/ò`b¥»ógŽpïÕç¾ÑñJðW~8؆œdì0=0Iß<(%:@7`›£œq·ÌoßÏÓ5³ñ‡úb–4ªhº µ‘¼G“©”•|¬F>• `|'?7 ŒPK ¸RË)J™–9"r¦Hå(²T#ï–^¢0Àð•ßñˆ…&rIªOW éÑ÷†áñ'$5\÷ý ¡k´µPÑAYMƒ$“C$OV=D´@Fα;£Ãs˜•ÖŠž®¾zÊšÔ«k…]KË °ÏOMO ŠYb¤’¥d%A. c¥²Ìxê‰Ê6TIJJ”[2nÎùwïøqeWCŠ*•ôìß ¤k(z·Ìk(®½N]£Ž)ÀÈ Â)B6©BFøÏ¯Ë‹{MÑÒÇd¥­ñèc5M(ì+ªªB§ð!‰blÄ‚AÔÌê¡W øn¥*8»W‰à1­8ãH×b³"Ñ:b )º…¬Õ(C‡|+¸ÕŠöÍG!0üJÉê6XÀvlŠ…%NØÉïƒeÝk§1×]k’R„%2¸FÙJ˜’¦0ÉŽÞ|.HJf*òˆG»\!S^âXV¼²€«*©ÞH »ÔÏrÅF@)ŒQMQ=[¡xç=DÏQ+d–?é vˆîw›•–ß(–²íWMALð **fH`ˆ·I9i]FÀ“Ô Û‡)‚™+¼–Ì5(8ÀKJÖ¤ %Ö¢âMžeÓrÿZÛõ†¡ÐÒÛ"¥Õj+ѹRÔ¢ÈÉû’ %¨ðƒ Dì±,o+„v¨ƒÁtW*ºKrSÅYl6èc»GRª¨ÕÑÍU‹Js“ ÓENíÔ¬¯"Г@"â°Ç†8Ì”@h¯ƒ­ÔVT«Ê5ïÝ»XFpSˆÝ]X–S•=Mr>,çc°Æ;wáyºD}R7eP6É#â>_3ßëÃO]Xε¬ ˆ"ªTZs,¥*&RÔêH‰ä‰\©dΕz°[=;‘¿ªkx†0§Š>Ù!HLö#v׋> ª´8Á qù"© À)9'rqßåçða lV?â±ÄjÈTFÎz†@ßÏ ž`ÚÊ*º;z>):e™°dr>Óc| úFöÜ,ÈI,ª6ý;}Ýø¦`ÌÀüEWmw顺yã£ZõaK*„‘Æ0¡pØ]Ë ‚gË‚éYaT…zÐ.[hÊ ±þ#ž•ÂäžÃÀ&&Ž[v½`QBÃ(Z¦àªŒ…:T¨PpV4d.rߑۆKxšzº™!1d4}LªÆF‰¹Âïðžžä|9ÆxªÓdžè À>ˆ‘ĈÃ(Éé!@ 3Ž =|þ~œ:Æ~ÏÆONägäãóþ¼0ÀãñXžMéMrÆ%jÏš¨•zºU‚r½ ÒÖXà‡c¿Ø½·¸â”œ H`óÁ;ý8äìãznÑQ­éêIÿt GJÚ”XF¡Iï$ùˆ©¡H™é˲d0¯QPA#8òî<øb«ø@W †VI+ž­ÆãnÿwC@)†µãà__‘®‰Ö‚s="±”:º€ÍÓÔHGùCwÛïâw[‰ ¥ªPze⨀#žÎâ)ÑIõ‰½6Å7«k²Zõà{›Æ™aìÓéTÝ#¼W“DnàŠðõuÇ=D{m·}‡çÄYÒ)s‰ 6íÛ$;vü0fùË„bjë-j«-M7Nì …9¾Ä ƒŸ»‰Ö½[âZ»ð´Þ Xâ«|æKuZwjsþY"‘ÏXÁ Œzƒt…6•¬(Š*‡‘¡ó‹=`h Ýôöˆ&³ÒušrãQoœ+¼}3STÄ: ¬¤—㦭¦oóÅ$`m¹VâR8¯¥¤ñ«lŽØß}øJ’R«§—â *7AÁÛÒ儦HíÛÌí¦7áä*߯{ØÆü,‡5¯˜'Àë#‰u¶é Ä(n*f¥`¡$K 'áhß9é;`ãËm¸—QÝر¥`zënž¥º½â‰[²¹8Ä23ÒzN 6O #ª N8àᵺ垧Κß(d§dŽd’:ŠysáÏ-‘ƒ‚X|3º0êìA¡Ym¥¬ø¢_ p>2þtÏÆ6÷átIb\þ+UÀ GÆ¿ÄÖéÓ©fŽ!ÙA €Ã'u%7ØŒŽîjzÈžzhå…— ˆXgqð¶sƒb;ðlŒ|pa®M­sŠª¿HUØîT—½1Ù NèÒsšŽ¢ ?¾v˜ã°?Ÿ6è§´Ý.ñÊÑ›u]¦†(ž?TT]}úDWq*ŠeJ{eSç¥òW§áÎE!J[þÀÄ÷ö† jUÖMâ¢-ã M¦ôÝ]®›ßâŽå#R'‰:Äó±qM‹ð¦@ì l` œçˆuNÑ4Ò‰c5Iâ+û¤UFWu\‰ÞdŒÙõ¯±·µH³th* W~¦Щ×ÊY€,ǃåNÝØC5VŸ±ÖÖx–ÚU¶Ó¤A^Ž7ye.®äË#ÎÌé”(1ÊçƒaÓVåûº3þ#åÛ>G©É þ_‡SgAYX8 ÑÑ™m˜lòì।b£½E¼ Äµ, #Š4*‡á@[ œ.rÉÏåÇmn•It/n¦PpN6ÈŸ^q™°üF;Î]ê~?T‘¢á¢’ ñ¥Ünzpq¶Ø=¼·á_ã  ÿ¤ã¹ú' +”P®%ßâ,O¤)´ŽÝ]]«´ÕÂÿp÷i[IPIv–íEKS"D“VT X¦§‘dŽI ÂÓzañËO3ÉŠÄÈØxŠY@aݺÆÎBdÌ„ÔÍ%)&ëÐIIp*3g –µLeX&€µET%Ük²£Ü"©ÔÒÊsžgXÐüþ¥Çžü7Ko¹ÏyŽ©[á‚há Ò¥d/0‰žL„!ܼ*£âPŽA$ð –ÍCÀQ z*ŒOÁÏ»¾†e›ÁP*ô`(—bÿùAÒ6<þÉï±á¶{u_ÅàB·ê‰|6È“õõÏR“ˆp´MÜ OÄBïTRÛ †7’_ባ…#rʰæIHéè©È9%€*6&?A__2³ÅŒTÑF”#âðê*sß㜰¤Ì)N#âé®0åûÞ lb”±92¡ø{ñÎ.ú÷ø˜P÷h®ž! ¹%¤‰@`‚Áˆîw#ëà ®èD‘üBÍMƒ²³6:Ln„?T ¨ÈÆpN@ã–]H,*~;a‚©Ã7œ)k ®Šîhe‚7yZ8äé‰\¾„$‚¦O±• g Hš~ì‘zdxf¨¤‘‘Š|ÝË*²ƒÝ&·SØú»q-KZ‘€gH¦.ïCkVŸ·Ÿ£Äž)#—‹*z\ 1,FNpÃÏ'‡a,/ ,ÈÊ$Uë•X‚:ú›~ @#'¸úqÑ–„ÝŠ‘ObKvüG$®Àr£'|ä|;†vý¸o’n°7Î{àžÙÎØ>˜ïÃP &õNú"ã°Å¿Ó¯¤+š5Ô–h¤ŸHUHBµe2©z«²>?Ê¡¢ê8èXÜ>¼_h+è&š7V‰á–Hg‰ã)42FÅ$WWVRÆA^$À fÈó æ4b娅œðíly<1* ”d Î~`vÏÏ?Ë€*éÈéuSÒ{€7á.ôvµ”0ÑŽ-ñXÂeÃbwÏßçœ>%V«¤pƒI[¼ÑÊ ÉýA_f1œŒ6ý|wàX8'ÄZj1ÝàÐõl¦ºXŒ·; s³I 6ª”Ꙝ±HÕÈ“§l*ã¸\nnÛîשhVk<´T5ôøzÊ*ˆ¢2UÃÇã4laBÄb_ ðW c€(CujX ð£‚ùŒ¢-DYÁû¹Ò°UE;´ej*©Xº£gy*ŒlÐOIK¶C|qº08 ã!£×+u#œS  ÁH“oPÇ#8Çèð7ÁjWñÝ‘@NãÓÎ!õV’儊Äj³±yA=þñ°â¿ÔšÛw‰ÖHª€&:ˆÂøŠpHêMƒ†såØŽl¤Ì ¿â"IÓZîŠù¥/vOÑç¥V5´êÝñ¼ ;íº‰Û†XîrVSÖ§|yõê;öã•2]Å¡Qã†l?ˆÈÝ#QÒ¨Àg,:²Ûa¶ß†ü7 È[ûº<¥Æä°ÉɨÀîG—–8’—`Ϭb‘&é ª±ß ›”àˆc(RH‰DHm؆à|¸Â;}]C¯\ƒÄbBžVÈÇOòü8 j^QËpŽÅ—eNšÉŸìòC:•JS‰ .‘«˜`` 9z™`nv‰7óóüø¶jyyt°è{T—ku΂›PÞ¦¯‚i­õTµ”Ôêd¶ËóDDOûÒäÈÀüAK)#ö{$鈙0¤„!.@°$'¬rÅ«ù»FаXL¹!ÒMYn‘Y”‡7›—dK}DTñÒ±–j8C¡f-fo…±’ÌÙÛ?3Õ:Ĩ²ÃNT v1ùäãÄU~üq© Á.ÀÃ-gI‹RÔTzÊQròq÷ƒk­qA ¬ôÒšúygŒSÉ/‹L#«©£è–EE蘚bãÃv¨zƒP4F®21ÑQÇ!+(ðοk±Ù?÷ ø` uO'€`EF,ÞÆ)¦…ðŽ<)Xáb›³60B1=2öXŸÄðpzuM4*DrÈêì½"8 $ÌIìªÎ€úበ€ImïÙç P óñùêž(¤š™–B’Ç D§(һƞ*O†Ù‘GlŒî8p¥©Ó–ªÍÒüÕ¯Wg{sQ[iDqEr’i ÉÖ=<Ý.ª#>„¡ÖV&hÊ’!RÓ8%oq²gv$”€ù>q Z’Éû”@}ÁÞ,³ä"%Y0¬¯zØá©‡÷…CÜ–ª®Jù))c1Ó{̘2¨©r0£y€=wƒ%k‘-QÃù¨¢ƒŸFF?”§˜H S!äÿà j»6\vzA­SO-GHé•# U™¾ÏHÝOÄî{Ÿµ-É2ËP>½^@wóíŒðÉnMIãÃÍâõ5=¼!x–Rc¬¤tœùü²Ç8?‡F #uh×9eÁe\îzFøÉÇz®¡A…yR è`) ·ŠÏz„Ó…%ed€8*Œ§~Ç*6ùgˆÅe¾£RÑ a¸b`q¶ûa¿Û¿—-£9I´¢éj|ûcŸiœ¹SXÿ—`1Ê» ÊÀÀ ©ÀlM†8ç ýdßê:탥°§—¼%¹%œG2Ì‹ÐdÌáÞr¥Ž)ØHTq’ èhž–LÛ¦µ*+Æ„« †RòtJ^&`ñŒu’ªç#ÃÃôíÕIJº'ÏÝš‘Ø !âÿ˜•iúäÃSLMU<Æižh ÉÕ’Èò °¥”tž¯ÄÝH/\¼½b¹©®’²K¥5\rE5E,¯È„&(ÏŒ rCfùãçÀKàOgµVĨ³$Õ¶Úæ@wOª‘ßiŠO:ƒé8㘹Vé!*dÌž‚±½*¹iÿx„žp¥ *TÂER’ÔÌ-$øªÀµ5ÒÁÒ!b²„lîàddoßòã šû„°Ò™•G…\m,ŠŽ\4ŸÚÃÊ®z–›«PI4KvàO…ÙÈs™õ¦o" ùxJDu>5ž¨:êjÖ•LvR‘‰¿ZåžäÍãS1„ !TFϲ1Àê+’Dž%7T¥à·„j$-)T|C³iø¤Éë r1¿ãä;ðÍ#'»µ%@¥4ÉT´êÿÃ¥©T`’ÂÀF4ܸÎ óãT…‘ÒÝècÊ‚1Ï–e©™A·="M ­SÀ‹œ„ #}¥—â\€N@;$–½7_[ Ž*y$ u-Чbòþƒæp7áwIS „4æMÆ-K^Œ·ÛãYnUÎÄ+x08Âà6CÈ­“Üd»¾3Ä‚5‚Aîô‹ %:A¤ <ܨø›á''Ôð䤓»³_•)J¨ áë–`“Ö,‹ ¬2Yør½ÉÆûàm¿—‘M JRÛ%•³ÐÒô#*/P*Âl€0rNßP‹¨‡8ùq„9¢® Wj¹dŽX’GŠP€úº,} …wéÆßyÛˆT÷Š[e;GnñWø§¬¨oVoóÉÉ=¶ù¶sÂÜšàÞ¼; ÒÌ1ÏZóˆM]ÀÎÅÄ¥ÚBÝCâfbI#ü£ëÀi$¹!sëÇl“œã?AÂèô¨§¤1°jhB«oÏSF…F> 6ÉÀ××Ó‡4¦`c «‘ÒªÍçŒä…ôü¸°#Æ»bªûâe¥)í”×zAJõ¶ˆœ½m-ªO(¿†ŠÒDÆ2ã¨^¥ ¤ä\o|Ðu°T Á©Ñýáf§¡ƒ÷l0U¤2E ʽYž:háÀHiáŽ:tþ(dêžM2W- e‚IݺŒ ݼŒ¨Ð™ˆRÔ’•³câië˜xt¬Õ–Þ©y·_55Ep z8§’q†ÙJPQZi#«o¶[¤TÊc<Þ÷9 ãj-~VÅ”Óðš{;°«»U‰ª¯UòÿO{©VjˆVPO"£TJž!Š–x© ‰d’ºW‹9Ïp°Î™J+–VÀ!‹ ˆÂ­ñвIäêËFIfûA‘¶õ8;CßëÅàJPYªn5šÚõ µÑG4G-=ÌÙQн¾Õs.©m««¡YªòÆ pà ž/XYî¡W”n°§‡v%ŽF°s‚ŠBP—r–5õˆ´-÷©-›íÞhi'¼jj9()fŽXÒÛb¦¦„¬55Õ°4ÐÃONÉ0’¢¢Hê',´ò^Ü.‘ÃbM6»µTiºI§»ê+­¬ÒÔ¤z“%-–ËN‰Eî¼Õ+ËPò“ É$Y¡Zvëе¦ŸÏ MA7!J n-t>'º¢ònÇÀ –ȇ%¨8ÆÐÖÑWéý1 4¼S[h¨ísÝb·Ïdõ52©’Ùj©­§\*)©ªL“øxˆÜn5!c&%vki`³ÓYt•¶J»4²ê ÈäCQ>¢¸ˆe¯·ÉP´åü#¦£U*)ªo#p©«u’ Á™Ø÷‡ãÆ) ž$žÖgâÙo"ÛµRÞ©-–û6˜¾iÆ·Öiz{]T×:(^¿Wê$­½Üï5¯L’C 7§%Ü)£§c””áþ¶Áª¥Ñ6[Ã]Ëä¹ÅW. ®ž–ëm‚‡÷ ‡Ýi­t7ZÞnÕ7ZúùÊX­¿ œêºM9 ”„‡!ªGp bs©Œâ¤(È]⢧î䩨A‹ûSk; f¢ªÓ3ÿb´ôvzš[T”Tö‹¦¬ÕðV©§¤J@h¡£®¦jª€¡cJ[ø²F†æeÞ+þ½Ô÷*ic’÷“RR4"!¤¶¢[©šâø†‘BŒaÁgœ ¢oN@yäp‡HAé) ),ÇýÓž&9Œ¢r`Õ•›¨B”ðD ¶Æ:xѲ¤‚ ~ã°ûñÃ8y3”QÔ1IùŽüa²7é¤PÕ &›À÷ ƹõ4Q‚ˆî#ÚT Xœ$¢~#ö#nØùqœ€•,0© €6o€űü;ñ¥¨ÃçJøB vkÞ"µÃ£Äe²¾¸;|ÀÜðEª£Áž' ü,9Ü©X¯U'ËüÝøÏ1!Ræ ÕÁùfꥩ³¹¡jöŠŽ·Ã,~0Pˆ ¼$‘êŒÙúyù8X+m4·{}Uâš*«u-H5TóÄ'”#ª»@&Þ£˜Ë¢È#è' Am•wåʘj|0™È¸¥ }É$xŒ4ۢʺëÝ=d¼Ð\ª)l—kЮ†ëAc¸As†šÛLfÑ<ôõTòBòGO,ž,«ˆô‚ž QÕúº]97îÚ»EÂÛQWUOS%Î+\U1ÑE"ÕÈ(¥Ïo¥Ô=‹ÅŠ(’5’"êˆ$¯¼éÖ®Ù· ál@|ËcŽM¿|DénGSOYGPÔõ”ÓG=4ñd|i—*\°›©Å«žQ˵Zm6δɤ€Àe–Î,ª-%t>%-@Ÿ¤“ Ò[¬.1þ`6û¸‘Ý.:®çh Ó—åêãdµ2Im´Õ\«jm–öŽ7„:æ1S²Ã#¨èQ…vbxè!KBUÑM(LÀÊbYB”P¡Ú„eU%%@)”C‡ Ó{·d0þé‘1 >%+1ØŽù>›oÂÙä9dˆì2B Î7°Çqšš¦µB½»ÇAº¢†h®ôB6 lµZ¨Y ’Rd¡†ZÕ9ô¸OU¶<øŽ=8XúÂ@9øFÄ>ó‘õÇ1-@`)ÙMsˆ’èA#<@í¯¬E*ïtrÅWMäL‘©ŽDEq—ŒÉ’‡qÒºÃc§8íÅk=殚¥Ì3ø†`ñ’‘KÄÄy iaˆžÃàÀØàsæL%®*£`Mâ;ŒJ´ÅÊOž*ºŠž‘0™à‘ÜÆJø“¬Š¸À•ê pIÈøŽüY…£¥££«¼ÐTû¥Ú²¢µ]é¼Th‚*GS Öa‡©wÈVê–YÔÝe Á<¤z˜RÃ))p’²Ã˜N#YÃ&«©¤¸Tš«57îÚN‘’9 Ï eÄ #W .NÙmû1ÚhßÞ|9&–x2dbÝ!Ï^\–8ß.[>¹àË.qRz©Q,`[\!‰IJR ¼Â§°DèºFŠˆ<4tŒ€=?/ùð’{6-·8d‘gi“RáPÒ‚E`:eÁaŒ€3ÕD·Íjr ÇXG¡5&ö²Õ5CGGrOHѬAŸªG¤(K§ˆý ²Ç1$c Ì=8±ÆÈ¸Ê«”=Ôàd3œvôó଩)I½\Cöˆ ÀðŒLËtmç‚ɾ6Ûùp#Ê\’=ÜlpsåúïÆ‘€HååíòŽ4½*ç˸õÈbAúp›OŽÇ|måßÈm·É•u„X$k”"*ж@'Ó«sõÜüý8ÌÖ»©V'„’>Gn*¸ûr(™ˆ%*Ã;R­³wøICöu†‚²Ž™ÊЉ©êPƒþôâTê ‚0bšE cËÓŒ³¬éšÊYRÔûú5…ÛÖ±aE" 1œÀш¥MººZhýáTä4O–\ož‚rwôÏ5t³É HÁ£FÓIÃgvǧ¦üh.H&„kZ0 7Y…ÄXV4¿· ÈV5 rê1ðÎFØÀîx›Þï:z<-nâÍluµJ¨R %1Å$~ :º‡0’ìIp`€ƒ·ZÔ(”ÔžL~;aÅiQwR¨;Ä2Z.UL Àf”1‰ü3Ò¬èN;ç†_—|qÜN{íÅ£÷[}E@-"QÓ•Ÿ¨Ž®•Wèñ[«í9NÄœö:e&êÝÈ$5+¸ün„Mþb’‡f5¦îî:°Ö-#§§¨»Znu‰ëƒ%Ù,ÎÞ¢j#wšwpGDqÂ^9JªªæDee9ÆøÇ—sÄzÿ«ºÔBPF¥ƒzR±x˜ «TÊ’» ®8ÿ08âÕ1øwpå(‡ zEes½UVâÊÈ€“k´J@Ø`³|ò{yqª™œ¶K1Ûrü¹9ÉÏ 58÷vC…0½5å­D¨Ý- DÈ?Û=·ç=‰áÒ)$¡›%º’&U,áŽf :@Ï–ùâ‡ÐùˆEÿÃC‚6GS’¿ $”`¨`œ¹ü{ïÄ‚’$eV)åX¡‹#æ=xbFÝNYôk€;œü>J§’O¯ŸÓ:J«‰R$õ åˆ#9²~¾|à© æ&šoLÜõ$Õ[„ <µ•µ•ÓŠK} 4JÌe«¬“á„V ؃€ÄFÌ—22·C² ,…T¬¤àô‘¸ØwF`+Š ©8KzhY·ÈRvÝ·Ïù†ßúp² U$<€0é?ÄbÆ~O~Ûýx‚¬âÙ‹œ?X@SYá!ä,M$Žþ#4 :³1á¹ø@9îùüO¥ÖŸ¥‰Že ùÄÈPžù}x‰K–#ˆ£@2|»´ß0©¯‰£ubä8Ua‘ˆV œ °Ýû ýÅêÙY Ue%*I#4³ÅRVÊõŽ¢A‡Ó9?ŽÜ.z„¹Viq$¿!®êÁIs¥ ¾¤‚>{ûÁ¬¼S{íÅÇ^d¬¨rÅ !|V +>’1è¿N{ÄŒH †9Œî¤ÇÈü¼ø8(“!'¥!»¯˜¹¥+›1C£âwþ#1xØâ)7*z·ñùãÏ¿:]D~ë6AÆXƹÐx¤ãaéž5€'ã3 "•Ë^PÓ[^I9Ïú±ƒ¶:IÛ· ‘\dYTR3€Kƒ·sÓß· R@-¿â *z†îÈ’Þjå¸ÛmS‘N†8¤¦.ˆ‹2M¥É™ú3.Q²¹;`ã†*–t…XŒ ø€!bÀÿ™˜Ÿ€ç>ü*ÅýÍÒk-KHãuL< Ò˜ÿÖxU)'6Ç`©Ä«Jå0zqðà3g …ìIá¶š¢Håð‰cÔp„ã99Æì1÷Ÿ?g !Çw¤<ø5lpÀ†# DЧ¾Jžøâo µ5ÓD_©î‹Ö[æŽJÍ®Z‚`¹ZêEU,‹ÒW¯¤uFÄ—U$êV7)RT2#Z÷…±b–¦ݪC—49}o´USj3)©Ñú’?}³Í‡Ò<šk\ìwYc‘d  2¼nx£*iÚÃW99³ÛnßíÀ© Ƈ œSÓT†%NO ·(Ýâv,:˜Ê† GŸ§ëù¦Ð rF|ÈïåøððÈaáÆ,Œ/­Ð›S”ø‡Å؃Ž}A> úpñk»U[§Žx•““~†N¬ô²‚2›ÿ¶üFºB…0ÏT‹3”[Tµtú™!ª·H¶»í"ަ&_uC4e:jhÜìÀúçán%{Ý3Õ5³RRÁGZˬª¦’± ÕRHãÅØ‘»Çþqˆ°€ÁnÉSqcO=g M EIOyõ¯odJ$ÒÖ>ƒU ²ÙQŸ©¤¤ó^¯"cÁ\ ðq÷ð˜°Y:|h­´1†Ã- :Àà±Ø}Fÿ  ŽÝ÷\gaݨÙÓ_ˆ*šª¦Ždž•ä…Ô ¾r¤z±ÎFÝ»ñ=´ëˆ°°^iÇ@Ûß! X™¡âß$”ßþÞ.aE28ÂfI=Õü1ô‰šš¸EðM¬¿V3†\eNÞxíÛ‡9q¦²ÞhnóZ­Š KKh»Ã%E¶¹^7ŒÇW2£}K†xÕ·Æ”¨%hšXI ºp5<uå–‚Q1”P‡jƒ¼d[Œ5Ýæ›TjZûí‚Û¦£¸:Êö»dõÕ4©9Ç™¾¢GÜ’@`ƒÈ ɬ¯4uÕ–úÿÝ)ISq¤0‘CQ!„I†O¾P´ªzÈŠrßi‚+¢`𹓾’èrì «vøÃ%"âe¢ñUÀ%œ°Íµ¢’¤¢®ŠçV×}'pþòÎ’¤tUÝ(®½*E7RJ0Kg­}DŠ7à*Í5¦…MBG][O%-DЕ€­U4é%ðó$,W*K19ÏÑ- uÒA'Ï^PðînˆqŠ!G‡Çd)@”Ý_ßú1þ$e°1åáãÏ=ó¶;yñ4¦¤£(­D½jÃøˆcvØlIÁnã׿d¡ ƒ«ËÈZʤüpø„e¡~¢['eLÜî1ëëÇrõF^¢ØÆNv\÷×Ì~!WxÙØ¡Tp0ÓrOóâ-yzX61‚ôÏo?^<½Wkœqg¸0ôŽ õZ&(sì7Ñ«c"ä÷î}=~¼s·Q»À{Æ‹¼w̱MįlÔ8^³-{©éV!iÙÈ,}ƒ.NvâÚ‘X¢w>›÷ì~^\ª$°ÇáàGÄ!øÆãp~ò}{ðvS·líßrHòóŽ qÃâ¬u×¾IÜo€HÈõ?øôO¬3rFàw#Ï¿¯õÇ…Þ‡ñ5^š†@,wüG–Àwõl:ˆß§O½¾’Š×ƒKí…2$n’ȽLQdq#»IØžœ¶ÊÃBX+3߯˜RÖHº>Ññ®0ù²®Œù0=l¤ç$©øFýÈúq ·[a¥ËI•úI%Wálrq–É8Æ1õáèJCc­pŒÊ%…;»!ΪëGO¬“RÒp½dž…ƒ'¬ô;úŽ W;ÒHÄ7jÙÏGPbŒ± wÇmo>$ÅRè5üEËïaóÛJ›Ó¢È°¹‰ ;>7 ÎÇl“ç艪ąˆvv;–$œ°9Ëœžÿ £1£wåÇ1¯M45É3dgÁd]Žý‰ß^ ‚¼ùöòÈÛ9Æ~œPÇR/ tÞP¬ðÇ|#¥ØáBd0lnÉÒÃp1œíÛÏ#2¸S•,ŒbMÕK2ø²9ÉbJ·nÜ`@Ö^ݱ4-ªAX›1¥<ÛäÀ|^§ …\H@ò¸Üc8§¶@%Y#,†0ÂBX#–P<"ü ) K‚Û•Ö“AñH§ˆzH‹•CÖ±C8%œàc¡\}rÄçÓqž—çn•UÛ B¨Ü±Ž‘¾øùöâñÎ76µù‰LÚÙêôÕš´PCi¡ó]« ©žj½E1é1ITÌCJŠG Õ÷8-ÕëÎû9=Dl;ä mý;ñnTƛ›OÎ$'äœé‹~p²©ò8]—q|ŽÇ#óãŠí!éFÀ`Œt±#lÏÈoÄu­ðLæ¸SÓº0ª)¢02Êi–øÝŽJ€OÂÇ„€ Ûƒ)RÑõ‰d$ruÏÙŒÈW;dgf`8âc@0øÓD°žÝÚÑ„š¤Èv?h|( 3ùäž•D¥S¶wb­Ü È#=¶ü~Ü@íŽ?²hÉèàvL¢ÆìÛ’rw‚þgÏŽÞŽ™Ùé¹à?õýá·’F¢ròáïŠH¡\cy»’ `…ÎOÆGaŽÛöÇÍ7m†;œuh}Æš®¬MÚ iB˜œ™ dmß·öšŠv}±C@a‰K°¥í¶PÎÄؤ“ PÛ©^E‘än³ÄY÷ôêíòùð µS»¨SÕ‚Ií‘Ò1߀Q# <„e~±9“\3#Œf´P«œ‹º«¶3ßÇ~§ ¦=NaBWf ¸øŽe'bJ÷±Áƒ–öôôÇÎ+ßCØJ®–„°D\Hßnä®Ón*nê¨ Ü c°ßmþ¿Ïˆ­æ­®"$d5Q >% ¹R´c㢾ÀðúR£q¹þ)?$ÇȰÉ ÊÃ¥ƒã88ï’6Él†äûZ0e¥C’5Â4ÚAT«*Û1æ•§"" SL ¨x~LŸ$Àùu| 5PàŸ ÊÙc9_Cß°ßTË zkøÊÄPÃõ®¡gŒ,‡2 ìr>Y×õ¹áÝH!”ïÓ‡0|ûŽÿ> Uhj5»Ú-]¨íÒÓUhmRM7}p)§vþ%ŽèÌ<*ªW?á#º§VAPèŒÝ(eê¬5Þ‹¸é;ÅešàŸÄ‰„”µ*†²ŽBæš¶ãt]÷=¬§âVâÏY9¦”ùi¢¹×Ë]ñ\ vˆpIßþ¿>†×]Wµ%%MK€ C,ÄI¡éÎ3Œð!%J9*4nÍvw¦’7§Ç|r;UÉ¥«€QÎÒPÂÕP˜ØMO 2«Êð·ÅÒ½kÕ…øCe°7âMOË-aq°Ã©­6ŹZå2ßYEWSdËôQNeŽu\Bø`Ý8 ðÄÈ™0¡Øw–gÙÎ"Eì eƒÕÏÄCiêª-õ9W––ª*WttpJ¸ea³dÊGÈŽ-;}ÎÓ«(Ͷ÷™úq ›†/Œ,´î»Å(;ã=‡˜È C–±ÕVXbÐj~ªÑŠ[ºçœHmõZVžŽÍVЦ!·Ö€DRÝIŤ"’«cE)/ÖU&©:Ãõ·XÉ!•ÿÒA¸¸rÉz†ÁˆÁßÜe¾³-Øšùyaù„j£è*q“ðá@¹Ïo@xÔÀ\áT*Ÿ·Ô2GH Ÿ_/^¯»†žæ>P°Goá¡–z1aw'‚ò¨}¡¾þøß†‰ ‘ô÷øOVB#}ÃgsëÛç˜qå’-hà ÒÇl½Ó/º×Ÿ³SUël¾:’<_ˆŒöl†òâ±¼i«­‘Ä“E×LìUp±’ 3öQÛŠOûXße›+¬TŸ´· ²&…ššÝNpÆÃ8VLö8Îr{wÏËËŽš%aœîsðäç#>>3Æ’\k‡´eK=} ¾54]ÙƒVÉбž¹~\Líz²&)|>QÁªKG‘€ c¾À$Äa†ãã!Xµ'[F¬µôl£¨–‘ÇI8ÁŒGŸ3žžL(ã>YíÛ·õ<@­¾Ð !„7É.KçïìHÁûø¥òÀÁû~_d/vgñ ’NH¶ÝˆïåòÿŽ: Hòïœãå¶ÜL°ˆ8X'VïëŸ"IùðªÆWŸ„žàúv·& ø~ ØáóÜퟞN߯/ÄèáVà1’3ßÐúŸÇ‹Æƒ8!½ª>= ˆíñ»ì£8ÀÛøw9ßîúðãNOV[$®2Bà``oòúúñ@>Ä¥?Î,Û6˜¹UªMq&†•–|J©~˜ãqÓ /ÄýD¤ñ<¥¢·Zãhèh”6yçJ‰y¼Œ2«Û쀹ì,3Ÿ¸øaã¬c4Ù…D17sðÓ÷C„ÔJ$²E¾Yõ†È989=ŽqŸ1ÄŽŠ‘#!Ùås³â9ø»ôãáLãørC3ùò…À6ÿh•GMKx†~¦_·`>½Jèþ]·ÛˆÍËPÃ’žV¦£¨ÇˆÎ5ƒâ:œ!Î=OÂx%($qüy@$^|À#Ò+ËÖsÓTË]U¹èÌ)á;㬟¶AõÉßÏ¿šëŒµ]F5P‘¯|ô®7;ùç·~ —!Ɇ³0ø†i*'©ˆE°Áßíüûð3ÕÅ€±8É8='=·Î7Çn|@ôËA¡X$³‘Ï–0IÎ>Ö>¹áÂ9°¦îs¹sŽÙ$íòâÆ",ÖèX+æ©ÈâÎá´$08häœ,©Œwü€ã9ê*bžž&*üU ®´ã­ ôõ C!èpÎp7|p@ÛŸÚÖ膟¥ÕH>²xK‡wfEErLdœ£¸Dñ&¦®Í„€ díØ~xá®3¡Š®8·Ä:†|@dcȃ€=—çŽä¨Z©Y=Þ/ñs·ŠÙÀE'²qž¢1؉8V§ã_˜!çñ ,зÁ l ‘Ô]à p;ŒvÏ¡ã2ã#¬e¶³“ßìžÀ“ÿŽ,`šÂ¯Â3Ù{‘œõ36ç ?ŽûýsÁ}Hû`’{úþA•0ø‹|ÿv˜ –*î/Y$Q´&J£“*Ë*ô‚Q†I ãì#yç‚k¤‹á§@ñ´˜‘ã=#Ì…q¾@ï鿟ìþ"\d=i£{ºçÄij“ T¨.’ß[ùoÛÏŽ©á29MTR…fpÇ$öéó#òF=R.»Gõ‚ÇR»;O+u‹0=$Ž”#¾øùœãVw$Ë '¨7HÂï°ÆÇéä8:±®©¸ë-oݬm´å]ÊM,‘È ¸Ë:;«ã Æ‹Œva‚0—ÐÅà[/aJQ{º»g½Tª˜=_g#¯·|ã 2;ö=·âPG¾è¦` ühÀ’epK’z€ùíüþ§†r½+öY†û3ŒçÔùq›½„5ïå ÚêÒšéMQ0ÄÄ5JXôˆ&þ½`ã*#f?ý§›.½êe¯O[¤ºUQ¬'Dª,A±øÕ2"u:Ð:ºŸü àŠP›ý¤PéŸ(5?r_Á~¦b,)R‹tS òZRŠ|3Ý4Eæx.•ÒÓ=šn²’ßx†hÌU”ZÓ­3ÍDå[Ã2ÂPÉŒu:ö‡ éR\uѺí¾‰-rBµ)],ÑTtÔ,ñE3€˜¤.¸eÁÆA=YrºE¨Ü'ºqŽq𒤋ÀãwøÂ‡–RQëj5ò‚*Ǥ’[myc-ΨS šzC+L¾çâŸ.¦ VXÂô6GÝË‹¨¦Ôñ_5F–½éÂÓUAYF’ÒGE‹GQ=La–D0Ö|î?6'°i’’B»©7ƒŒ®€AäF š¡ÖJ]N“Å‹l@õn–®Òµ«I<ôuÔµûÝ®ën¨Z«uÖˆ±U¨£¨f뫡ã) ;hX¥¦æ¶”m/t•±Óqøú~¶¦OŠëF]RKtó8ÏÄ|$bI*Ïß%W.¨Ê5– ƒ¹Ž\ 4JVzzSÞ°~¦·ò¦Òi*èlÕ6IªìµM=x©–Å}J9Η¬yf’¢Ëª`zdͪ¥@‹¯¨>M>ÓÕòÚñIx²O%ÛGê( Ôr>#ýá@PÕª†ZKý®RMD€8W§›¥Ü¾.H"ᆨŸ³.£„&Uõ0˜oàx†ÇŽ?éßÝmzºkŠk++Éy¶À¾÷Gz¤‚’JtÒR\i)²ÖĽQÍV%wRÑ2“+¶šzûeEçJÇ3R\úVèªIÞ’Q] ™…ÓLʇ4×X”K,£"HŠšœZ/:­î²H£Š†*Á(&„¶…òÁ±Æ¿˜h¹òö«TéK¶ª¦­£ºVÙÚJºK²Ô2×_¬t´²KUÞ”š{í(Ž5¹yGˆ×Ó ¯CRÔMƒž’§*ÁˆJv9˜mŽ3OBP¢^øwßǶ„ñ†ÙÖ K6àÃÃÚ-};©¨®~쾤R¤ëᤳ–1083…|ã±>‡¼7ï&ZQ;Ü´óa£©Í[l‹9Uÿ·(¿Å‰H ”R $•°jš+ˆ¥yŒGhÎ)LpÐ+6<> Nè.+[OÑÍë"zdêVû2à Ȗ3Õ±_ôà€À¨^jg‘²r2˳» oœ|ŽÛðÔ—ê|šÝ vba¦ZV,±– Ǥ…bF7é;·Ä@Ø öù·MFÑ ãâœ6Fr \àŒŸ.Cí£;eÊ(ÉlGƼႶÙ,dž‚˜Ë.Ç~ý†>}m¸og‘A$"Tpã‘D‘H¹+‚JÇÓÌç€v;ÈñøƒÅޏaë¾ŽŠ°4–fX'$“C9> „°ÿáêü#¸ø\ôï³(ÛŠîzZŠIž¦ ž#‰Ue|o‚3ö“ÍHÈ#pq¿¦"á$}‡â›ãl©…aÜxñ÷ã,Lä`2I';c#q÷ýÜfÔŒ¨QeeR>n‚{ôøƒq€vô;c…[8{v ‡tA<öÅSïâñ 0q—p@Æ1åÄÆUÓ?Jסˆ¯þäe‚>À €z¢?1Ô3œðÙjºköùaáæ +í¡8CÃ×SN¡£=iŒ«#u©†Y~ÑòÏ|‘ÃMC´ƒ øTžø|ôã9;í÷㇓{ ÄfbF>Ø(¦™R†H? 9ßá+Üþ_Õ KJg,NXëåÜ~+_ S{C=çÂŒ3 bÊ>SNp2<Ž1ÄaœN1#a†@ }àç«õ¶xYbhwC†£F•ê†B¯óøz³ßwÇõáZZ“˜ê¶b +ôåNOf#· Ò ü~bñ®0ã':Ž®’:z²0@î¤v |ÿå¾²DH ),Ä€ fc‚Fs¾ã¤qžÔ»²&«0“äЙê¹"i4º’Ý´×(ŠÖÉÒ¤gÈùŒŸLã¹íøñ¸KÜzdc=ÁÎÙýwãÌÉ«Äq,¡Ô†#„GKnrànvê;|»qÎ:`0tvº.,SP@$õ’ɆPA'¨_¾céÃÍ$5¢DL4¶ú¾­Áø©kFï?ÃZ¸¤ ýÈÇÏrÁâ8ãO_xê¤QI"”1]d0Én®#¨ÒUÆÎ<Ì2Ÿ@sÿwGoN+HcÉF!ã'G"‰ì?Ò˧[¾ad¬[nlàã?‘üGŸ `ØãóÈϨà¢PÕõïé˜>»÷8ôýzfªrvÁDú Îý¶þ\LðˆÕM+ݺ)“¬•Á¤ã9#$ç>[cêx(6!ô«3NÇáäîFíåÿ“ÄjÅÍÇâL,ˆ`ãÏï>U;c$ìPrs€Ãoøùñ` V(³`Çñ¯8’Û¬u5XiºB<ØfF|„ÿ)Æßûöó3ª;e¾†5ŒAÒ|Ï2‡~¥ ‡®äga厔°r\À.a"è:Öè˜SÞkBƲôN§l¹dq²( ãü;“¹á⎮æÈLX&Œ¬xøA 1Âç¾Ý@ü°6x:ë\ó„bÜbHë )·[†ˆ+á§Iß-¾mÈû¸k½²!#êY¤cö@Œ“Œ’Àùz’ H9ˆ€öÊ#wm@õKýîOt§ á2õm‰‹é»ïŽ!u·Ù!kGÈ%A2¸ ä’OÃÛsÜúîxS»Õ0†À_Jòˆ”µ.„—RA#ªMØäÎÎ6>dïÀ/PÎ~øùݲóߊx‚¥ÙôÖY‰WeXòUÈo3ñ1=¾íý8RX¢w]úA^¦éÎT“ögëÅ0pLXv xÔoÉQŽÀ€ cl}£¶çúmÁa—¤z2,Wƒ Š©’ÁÆ|¸0[hhï€cŒ,’BÂ:º† #¨…êOÙ9>XË çf?=‡˜Ï|ç#îà‡*ˆ†£SF’äftV f܈õ ùãîàød™ „ª’ª“Bñ¹ z0Xª²FÄ«dÇ9[CB"Nñˆöל4×\êÜ4Šå%‘$o€PJàŸ\oŒdü'SH17ˆC4JÅ*c$ág#NßQÛŠ¶@H„ŒF°ö‚E@$cfîÇàm‘ð÷óî;pªÌ¸#±s‘ŒäwÁòâɨָÄÈe­g‡PëbpXçb7ÆÛïŒü±ò®G1¥5?Å<½@þU,ò6;/a‡Æ;îX0ˆñÂS¶“¥HX`‹¾Ä’K;1+Œeú»m¾n`¨3Q)$¹øN0yäcsÀŠ0Ì7¦¼¢×|g,¡S¥X/ˆF@ÎË‚00@$žÞ[팑0SÑå¹Û |XîNç·óòÏ\5” ʪ‘ä79ÎØõÜ|¸8l©ó¨yÎ~ùÇÏçÇQþÚj†0³9™½ P¥{ž—dÈ “œ6GÄw?ŽøàµÏ †òd9Û°8û;7×c‡,Ì~>"Tƒ™üj¬û¡9û$/HÏÄzŽF3ñmúòáš~2@ùíœã||_Ë~"ª\à>9E1ºÿˆB¡‰ê Äo‚0ý¼ûg‹Û–WK¤u”Ö:‡£»j-1]OmšÌ¿¾ìtÒÏGÔI$§Z€¤ƒñ üd+2­û=iUÒµ®_úÐHít† &eŽÖ… ×þ• ð¨+MkYµ®µ‚‡SGJ?µ{ûu®HÄOUW'_î[ÍdjkéªDš»÷-5~ª²ƒK¨4ÝD»/¢@Š|I©åiik”«â)iªOK<52Ì£6Që]R{1mχ8Z•£_Ú=¤W¼<å…­9O¨oûȼYR¤êÍ z»M¾ ¢Ü­µseŒŽa*µ¡cŠ{q™ŽLƒF¶Ýk¬· K­­eÉ4²²œ‘Ï)*ëّظ]ªX–©Lo^H ïÝ܃µLJÉ Êoêñ³Qfæ.——RÆžb¢jÊXƒMSc¼SA ªibã0 +oQA,s0ŽD Å3c¥©·\®|»Õ4UÕš~àæªi-tò\¦²Ô$9¥Ö6XáRj)–˜«MÓ…¨£fW=kKR…ÐŽ ÄU·0¬PûH"éIqØGÌææ¡MEËûå~™«jÉmõÉ¢[C¼±ÖQN†Kv£±L ‰ÃÀÉ"0øeLÃ(†Ë=·SÙ¯2ÔÛ(*¯vÊ€¦¦¢I-ÆŠgC4u ©¥­YĉÁ<9©h 7åJ$7ÏÝWÿ0†!‰QVâ r#ÈÅ£[uµ$Ô–:ʺ:½IN²×Û^G·¥ê²†UVš’à GlÖ°Î…°ý+<ŸÀ™‹Vj½?n¯ik)¥¥ »:TÔ"Ȱ[-×ô¦Ï½˜àyØu,N¤TÐÈR9â¦é.‘Hé·VvµÈ–=ÄŸ€– Hê¹Ï޾Üb£IÚ'ÈÝFøÆ|ÈÎ~G‹3Mk&¦Xé./ï[FÉfIéăüðàî{¨;ävÀ…™j|³JEô°Èë|K¥·Ímñ.š]U$¬Õ56xäéRdévªµH[õ ÐPpW8P`T5_«Jj$¨žs#““–cðª¯vbNžççÄN£hç©„H‘TLòÆ’ÌòŸ„.½lz lä †ß^9;JpL£(T­Ÿ•#Ð-e ¿\€<u!¾¾^àüÆ?Øñ ¯c“ŒäœmÛæÛë0ªx·u#‰$”ñoHO`rp2Dˆ Ÿ3ÒcÛéÇ8ë¦C®Øìºwˆºmº^zÊIÝÒGt…‰1‚ÉÌ1ü+ö†5$ìz@ˆ¶þöúº”=<ÔòRMGÔúŒˆÑ»HAêhäŠ3ÛLlIãm®P³¢Îµ+r{ Imagµ™ó' PK`;E{·Cý]u´lð7‰LL#n¯Š'9 düjøQÛ„­ó¥e?Y 4ˆ%C‚èÑåGXù`÷ôíÆuuM>Õ1Êš1®Q HqÖÀó ðY„È ~>döõÛÌýÛxpzH‘¾7ß?Cøqlè>!¡8t#%¦Ü˜Îq“»nsôü8ÈÓzºFŸÅ¸>˜‡n èñEë¿èQ!cŒ>g9ßî>|-N[¥UÙ‰ÀP¹'¶0£¾ÿÏ‹âˆ-L? £²UÈ©%F"ŒÁNWr1ÙOžýöâUo‚†”b8ˆ1Õ$„—-¾NNÝ;ö m߆¤SB~! SŽ©Ãâã`@!À }±¾3³Œÿ>€ Å[«°=DœíŒúöòÛ‡ ¸gÝå /Hy‚`,W;ŸLlÂx]ê‘T»KA˜ôôùOW§¯óà‹ ªW^ Y¾!­îòºôÛŒ´ê¬ O–X'$„ÏKI9#¹õìÝ=é¡”Èj MH\x¥AHò%@? zùöáEElÚ>+ Z3+ñ ïZõ2žRòwËd:¼†}8éj#ËøH$Aø† “ÝrFþ¼^ Â)‰;é_ YVRq÷ÐoóïÛýøEa˜– ~È8õ9Ïnß.-žŒÑ(é­ié ¨V“ª5‘’Š}¶*2é‘Û|}ÙÛŒŠ¦<³6T• @,wÏ©ßÈyüñÅnzhAÇ<¡ow‰õõ•Ø(É‘¿žÃ=€ÇžÜuR<€&0 $ ‡Úϯ®~yÇh5”ö¶š`¦dŒtô«rH?Ln~ŸGÕ° †$e±=€%v_»ƒŒÛâ%—Õ!úÛGWq¬¦ ¢ë+«&H)éâVi%–CÒ‘¨¾{žÛdœdñ=×ú$hE£¡ª¿ÑWê ˜cš¶ÓI¡mbH‰é’·­ÖaÖ ÿí±~€¼GRùS@McªÀ^!iK8g<+é|«Ø«8w*ßÈpéžýOœŒuÉàke@ª¢§•TÂøß¥¢rŽ>ºü¶ÇË…¤¹|¾D0€.ët:¨'?hnsß²òÆù=ø%ž:xÚWøp2A9Élt(\œ“1矟 ÉîâÑF‡ R;Yzc2KÔƒ ±Vߤ[\œ}Ã~1 ñ:iÕVi êÜõF¬z–&ÏÙ錠#'-ƒœðO†Cñ—ÃOHå/މNºK£7eg Å”îÿèãŒÇÃÀ ;nCc>½—#É8ðÐG»àB*Yä%”„‚w$·`<Èôôáé„j2ÈIÉ$wœ‡áÁ k¬"Mp…b@=Dã¾ã=ü€ÇaŽŠE Ò¡Ë0$œ¶1œƒŽûc>gsÁ³Ðãøñ€ BÆü¡ÂŽ7XBà†2Hïc©’<Ý$¶KìÝ9ÈâG~a “MÑŒƒSW%T„žÀÏCÒNw@ãÏo¼qË·’«VÈ–ôTòNöL‰§Í£uŒ"Þ³[²†y™Ò‡¼ $½G ®‚¥²6 œcØ‘üÎx œ'WHP +Ü|#XÎõúqÔv%²øŽyÅOÄ!ÖÆ7ý CyÄa€;úvÎFx%¢sX€¬YŽÌ6é=\ˆfíØ%æÀE± û¡I>$ÆS £d±# þŸùò5Ïžž¥ø[à#áÃd ¶m·óÏTì^½œ"]àíðÏ rŽ’Ä` Ž2»íØÎsõX: ç-š²"}òÁWI¨h‘$dy–d÷è¼D9DjC*v92»‘µ§~–Ï.Ôþm:BÏùzii_üQ¾Á/¥2ÎKþ¢TÔ‡ßÑ•'þ4¦&w^_Þ®Zêjm-O/º_`—RiÊ©ƒA E”¢è¢*˜£)Ë#xh Ä”xë˜ö+®­[·´Úëk_U[bŽñ ¾Šz†¤ÕV–‹¬SEM÷y&’i”>Ú¥ˆÎ3Ǥ”S14&ðäÜ¡b±y µŸ™cètÐݨ4v¨×v»5lvŠöÕÚz(ô¶ªµÕD)+QiaØî“CVÈU¥¶È‰#¾ÚFÙâqÊ9*´=Ò·Më›D‚{%®áªì´§Á¬©kuM3Ñßi)ÌuqË}Fœ±V1JY:×b–•˘&)=RÀñ, âðµ”ÌOF•:ƒ1.)Lù>ƒÝ™ >Š«‘mJ›Ž¤å}Mb¡{]þ:u//.±HÅM-eeX¤n‰BDýR3Hx×mYk·TÓ&©°B”–úº¶¥»ØË‘6¼^ZDGø¤´ËÑ+ÓIŒ¨V‚L:ªšBXáPøÐ ¸ §¸¶èd«ÈR‚³5Ü0òP=ñÎ]kiôMú*‡w’ÍZE5â” –•ÏOŒ!,ÒÆY˜)ÇZ³&T¸uØñ¨,¼µ½X5ÒĺƒG̦£Ißé*‹¦•š²z›43VÚ¼)åzUw\DìH#Ø,Óz3x‹âY›‰Dá:]öHSy½yÄ=½£é´ÕÇSÛôæ†ñ¦kkR¯N œ†Ý5j¢Yî”±Ãr¶µÒJ‰`€<~ˆÝ8Všû]ÌKË]®WK]= ’*ùä¨{m 2KA³.*k%“§Ä“øŽÄ•T“Ůֵ] HÇ2 àöa˜I³ÊH/Ö*bw8Ú»÷å[¥ÞãtiÍ]SÊ•B²X‚Ç F¯Ãš*ª²˜€‚‚@ß=ø`šWi¦w‘Ü’Ò;f=²Å‰$ãÌúN2•§æuMe HbËʘB 2÷·ó¶ßùá’HXÇäà‘Û ¿ŸãÂÈ݇âšxVƒÊ'úkUÔÚZ1Ôe¢'ø°œ“bzšö;œ¯ÔòÞÙOwßÖ˜ékäE2½À('Á­ˆ6rÔu;‚A—üÄtdõ\[á *¼ÝUPðÃCŒdÕˆ³µ¾ãÐÜ OâÁRÅØ(ø|hfí]IÜxƒã@ÃÄ%ø—Ër£•C#¥A 1·‰–ÄŸ $‘€ÇËlöào0¥2僌wžêÁ]uKÐr"•ø ¦’§ãiL ¸_  ‘±Ê¾>Æq¿I › Ž0þ K$Ž)ïž“ŒÈîzº@$àŸ Üq åÙ¯ˆCŠ0§vp×,ÆÜTw€ vÓ°Ûq¾vá–xª¦A,QÂêGK#°!~»àyöê|9” –5ÏvPª¡N¯ãÓÆcСW¨t#?QÁ` u1 Ol~G=¸…ÝìqUÈÓBžî^C".#Ÿ'á-¦N:—÷=\.bSвð†IUÅ…eø×ŸEMe#šN¬…ŒÅ!¸8[Àó~“¹œ`®<þ{Ïú‚Æ:L¤R† XÑ7ÙÛ`Îßs¶à íÆNC½ãïƒÝW Û^Öñ í¯â;§¨š•™¢w8émÑ€?çÛ¹ÿn=ùgÎ M°È“¸Æ7QQŸ~,)›pø€R¬1óÃÊŽ›1u·IìÀƒóÏlcñá²`T`¡Æzr,I;`íœ~^\EÀë-~aBµÃ@ÂÓ²·^†ÛäŒ~ccŒo7Ú[RÀ–¤.R’wÉb>Âns匓ÆYó„™ef§-j`Cñ-ÂíWt ³ø†VÄj¬ÞlOHX£ sßlï¾O%ˆRRE“ˆ¢UÏú˜‰õ,XñçíWÈ–¥«¬¢ç€¥ƒ…––IOD)$ÎeC9`~C?\‘èAˉø×8”N°‡h,rÈCU1²£u¹ï³8ÙNqÛ=ü÷áÞ)è†!AÛ©ØXü[õŸ,àmÃÐ.³âØwFe,Ãßå¯8X;Èç¥G`Iï½3Á==%ˆÆ å±>{úyp`½u¾‡WU§æFx¶Ér ÎNq°Ûöíõ<;ST éf`§í`¤wÛÏúmÁpz@š±ó쎪o†‚YÙSbþåˆÜädà`vúwà†cõaOHNI×`ª~ò`{>Œ© ’Ćs¾|ûíÿLð‰A“Ùº Gˆ÷b1߀H'Ïö?øáVÆÙl.3Ó¸$¹,wÜ6ìs¾{qa¨ôXž4ôÚ±\ôG*ôåW'áݱ€:‡¡ŸÃ<¬±ÿ ['Î@:N3ÕÒ¿HÉçÓÏ$q[ëInükT]#gر`@bwÆAíœyoôáÒž>€ÄŽÀ(ÆpäýÿóÁ†¥[B1­Ð¨pùc$düýGõà¨AòËäoñc vƒ~@Kƒ™ò¤[:IÁš¾qvé=]¤t&˜¨¸Ú{—1+£0%Um%ºÇ ÁºÅ 3ÿx¨ ‚í…êf?†¬%§ë®U5Õu5×™êj릪©žG’gv–vl–›ì; ˜µ¤¥ L±ÞK9ÖP(MÒ¢ª•žáFלW•ÚƒÞ*½Þ†ê‹Ê>%•ó4JUzbÁ e÷ |=Ïš zØ! Z˜6îR%ð"“6ø¬¨UËŒ)¿Í(uTP|ˆ3J>#Ú"®!nÇ`gë‹3¼êÕò„„…:®RÄVI\>óg À âká®1N{¼!QïSû°GY@gÂÇ)ŠDþ,Nùé!z€ïÓž,=¤êuv¡¶Øa¨H —Ä«ºÜe ËUmQr¸Ô<Òˆ”êøg` ”RÙ`x´ êÙÈæÔ¬Q,—j»‡Œ7k*› ~ª¹O¦(ã ÓTBu¢2ŸÇª§¢E„Üêä 3ÔÔÊ’Lz²Ê*džŒñ•ò§|dzvÈ>Xý6âœTh7Ì;9eÌ”¤—)ÄæM9`«ðg9bw$dm¶øúãyã)&*Z3¸ŽœŒŒ€FÄìpèpAŸ”Q9¶èVˆ×±=m‰ÁÇÄwï¿–s÷ºQ˜ÓáQ‰:0$x˜ »X#·lùmÅà Ðì„)Rw$c'mò@ØwÎÝýxrÔÞ)¸Øh'9(èéƒD4óº ÷l¸98?_<`ôÎ4Â0 ýüé¬ 7–`Ì3Fѳ'Dl²Ô|RÝ*#á*IÎA߃Örc0#NIÏP §}À>›}8´šäGÎYòïˆÙT3zAe•¢b?äʆ`°H‡ðí·n*ŒŠ@ɘòbG¼~?N,š%†?aÉ 2³Æ~ö>g·ß÷p妫…¶éI+áT3PÕ† §«þ —ŠÌŒ}yqÏÚrE¢Ál’Õ™)`7\7Æ« Ã&Ûf™”µ¤žN—~b6Ns®ÿËzItu]² ÜvÙk×Q=T”’SÂ:Å<”ýê›/‘Œ£¢@ý%Cô79oÚ"žéEžâ—JÙ.K-Êž¦hèkžÒµ£ïàGy^Ä`«gÌwÓo¯àQñDz,ƒÝâÐ%[¥²¤ ç}ÈÈ>Ÿï‡â8;žÃ#`<ó°âã€øÂ.¯QªyB!ä„å[á;åòòïõÛ‰=›PV[œ5,Ì™ZXŸLtä¨éø$éâ í ( ¤±a7Ý$c‘ì1b½—YEÌóÅq¦ÓÕG3EQI+|XðÕ‚²äAŒá€9ãkåÏNÔGk»£bδuËJ*Õb R5IØ'¡™Ž, $$ ¢©[Z0úà 7Hë'"Ž5Ç|XÐÔŠØ£žˆ¨²Ä£â¶Olõ‚A*ppr2á^‚Ѓ,meaÕ±cß N{zçχ =YœM|BV8¸üC<”`¦:¨8@Fzve/Øo“ååéÃ%JS–VSÿ¶¡ÀÎÇ±Û vÎsåÁCãXó…ŠTÕ½ñÓC3ž§u ¹T"Oˆ¨Lƒœ7I`Gc¶{7Ƥ»t²ôà'HéUÃ̓·òõQ4éOMs†§ú¸c§ã ÔtÊÍÃãE'PdhÒT *Ìä–Üvï‘Äz»M•qQn‡b ý]9éØå‰898ÎÜgZ/ RžPùSz5~Óñ®1’!vŽT1ºŽ7.Œw'¤ŽØßÐñÒað ¸ ‚Cdg>C#óíÂ:§ñë”l"ð¼ ;÷F Ú >[žÛ{ðªS”›'e}Ηã¶8ŒáÛ„PÏø…šs°Œø`‰v0Û#¿VÛo¿%Qa‰‡Kuœã¤¨¤†;ŽÝˆ,÷à Ž÷â)Rßçðñºj;em2ÉKàtD dƒ'¯¨•w œ÷÷ìG½ekÊe˜Ê&2³·“&V –?àoŸ¯lü‰ë3ç€ýI-Èš9ôüÂÉ ƒüFZz1[tŽO ôÒ+Lä©(F2Ì6o•½‡Ÿ¤Ö¶bªpIÛ×wm¼¸Åkþù $y˜á[ÉU¦ZF¼—öˆmtÀ‚sëò>y;þ·á 7šîgx×àˆÖ³º‚T ÝÁ£òì26ãM w§¤m²N¸CŒ·7idlŠG=ýXŸ>9ÇZú·ÇL`"Ä´j‹…ªšáõê-òÙ:ਠxÞ)Ö¦œµ(‚¦9—j…rñª3>z@$Ô2×UßnõõRORÅ!Ÿ¢<1  ± IéÉ;’nm°ÚlÒëÄÔ°`¤ÉÎêÆ;•2§Í˜Q %'¼ÊQï`9–[4ÕÆª_h•æž)gX+Z8 eÖ–)Tc,R7ÇXC€r¡§ÚÎר*´mŠýT.F›LTÍK¯h„bÝtžih¢V Š÷,®y-“‚xÊ(øHô½jrÃ(ÒX)j"ûF¸WìéŸ,7n ¢†ªWðé£iŽäýN7gl¹ó#×<9H¸¢—ÀØBHð‹DÄ”…㹇œJim0²L¶ð£8PÝþ7;±úc¿¨áéZ8­4k -ÓÙ°øöËöÿœw‰4wÄÕxcHZ'’ t0*ØØ6@cœ–êòü~œiCá©ë$UHvÆävß;úmÃFTÇâ€Õ+­ÑÆ£ðÈÉÎÛ€ÛÔù»…@@€¶Oc±;g#ùp@1Ç ya*ÙÞŒÕF¾# ‚HÎ{aA;±· ¢i*ÃŽž Wo†F>`oü3_¼p P4ˆ )®$×épôÉþ.IÆ@ì¹=c=¶úqªÔª%uŽ7ªuûL,j¸ê œÀ#}¸×*sø‹Ì â ¶ÞZ¹fa„ð•ʱêŒõAF.Ø‚6;ä`æ­‘ÈU\¨ç#¾3ý8jUxØÀ°€Õ#$21’ôÜ÷Î~ƒo×s–ER¨­Éé )ÀØ»•vì7ࢋV»©†è)#ŒÎUÜç/œoŽÃ6Ûä1ÃÝ–Í-Ù¦•ä6šI.w)ºä‚ž9¥ 9žªG=1D§©Ù³²†`IMåì3;†~%WRàVÇ ywÄš]†GIkëð* ¦¬1»Û-XŒ=çQθM(,ðÓ"É<¥ºUUg‡Aß®2SGi€Véfýß¾®‚.£ûÍ©$phè›$ÅU™‚'QÉ èVTÝ¢ôæç„™É {ôîb9§3]4¦£°J)îÖzÚÆÓ@Æ)D@´¢)”“¥p[¤ž‘¹á¡Xª”¨8ÉÉßa’vÜcþ8•K!$2·we¬¡ˆ)Roàë^Q˜e0 cÏ=ˆÎÙß'¾~¾œgrA?äöÎ;u »ß^S·ó]†·BÝ]¿ÄÄ”ÁÜ ÷óÏ]As–: † 0n–c¶2C€1±#9Èïý(Aßî1rë.;áÕIguºcìAÈÈ_¸úð<²ÂqFÛ=Ãw_«©¶ ‚=FàÁÄ'†©Û†„@ T×·†ŽPÈ笒ùéé?8óõÜü¸«øÎräõ`‚ Æ1ç¹ß×?kcóï“Ö`kå„N¯õ2ÝM ÕÇSUPÒ ¥%E* yo¦5$d‹éˆŒää“Ó’J‚¨ Œç¿žÄgâ>œs¶èö]’ÎÿdMR—Ñ€ký)³j»té­ýýÙ¿üD¥tàê&eëYÂ*¼lN¥r$R|ñ†%;oÒ~|2XÖLý¢Hp¹ s“¶>î; ‚LJ<ZhæC [Óæ aê.¬’‚fÉùíô߃ᛩSu‘åÜý~y^ËÊž1c"\8pޤÉÛ¾s·q“Ûcç¸óòߎBòFÑK’E42‰c’ðäGƒ!VR °*#‡#pF/,3ÃÊ͉§¤líQs«D~ï©xã×:uÑÎí{át,ˆýºi*Ö' Gà J„‰¢I5^¶–¢’¢Zj˜d§©¦–X'§™%ŽX¤),2# £«©Á†-ÍŇ7†üHaØð´`Rn| CÙœ“åœôí¸üãÀ$)$m¸9ÛqçÛïáj‚2åíÊ£î¿g>› ôÏáÀÈä7Cw]»ƒ•úylxŽýŸ>²hQÐ0œí¹ÏóõßùpL'©I‘ý{·—üð*vµë•?gæíWšŠ*…¨§‘’P¡YJºöeÛýˆââ·Üíº²ŠJô¥t!éeݘvñbÛ°-³.Îø=Ù%Oüµ v0P¤–»ñÂ;¦ŒbÕÏ[cÚ8«°òU[‘‰ b®MEb0ê:Óæ<¶\’¾–6Žu/•:¼m‚8ÚHŽÄ0Î{Ž%®+ïGˆ£qÈñG…L ¥*Šð4qí³tFà/qü<àœïÒ¸îw#>xùïÄj¦­G—¬u.B9ÎWsŒùmè~µ·ˆJAQl¾PÙQ$$HþÑFPT,2¤œ±ÿÍò5̨EGaÔç%³‚¤15lúqLKŠ6½aÉqtaõKLŽàVUTÀg±*@$g÷ωجkð‚»1€Ä Ùbùó%·Î9ÎNsÀ•3cFÖ €¾ÿ|ÀU”Vžª„`ðƒýáO‡Ó’ÂÅI}ÏÙÀMϘGj¬õ0)¨R²@¹(ðçáóÌŠI!qé±ß· ˜‹ìE¾QªDÛŒ…ƒiE™˜R¸c‚G`¤ ‰ßÏ…˜c'£*3°$àמçcøp§ k¡ŠEJk¡ S2É…@ÌA]ÔuùøPw=ý~¼Aõ]å-±*z¦Ž­œš…•¥Š1Ô lÙ>¥‚í†ûge´ÌAH=eÐp™DÈ™=FêÀë-ÕŽ£¸1]TÖxʽ~8WØÊÕ(p@=LpÈXíØžü7*Sôd0*Kuø¥—£,±œávõÁœY”òC ~J8û ßî?—χ•^ $»ÝH vÌ¿l9R@j¾#Õ܃¶q¶Ä’1Ÿ¯óâAOfSÒǨŸ…bÌF0[gñùq`åº(âXCšÙFG€•T,¯¸$1}ж=1õá¾iÍ XúMLj«ñ(ÿòŠžyâíê†%˜’phä†ßí U5+¿Kƒ‚NÇ#qœc=»pÇQpv&8[²&G™Îäc·}ÆxŠQ}p‚N²ëHäW©˜Ë0¥KÿÍÂX„ïß¾ýöá*ª©$PªGF@Àl02GÇîàRg^‘}Û1îIê!€À A#'¾çôâ:,”ýgøµú2ƒ äôõ²dŒ?Ÿ´…ùràâ)Æ»=áænˆÖ8TF£º¢ž£Û%‰9cêNûpde£ûQ™vêW$az› ¾<Æ>|09qŠã‹ú´*’¹Ã7Zì~P ·ÙÎKg>^\“Æ@ÈÁß¾äØäý8°C°¬[3ëu{4ñgéN[^5SÔÕ0´ÛçÃÃ$à5M\c’’“­KGÓ“ÖÅWŒƒž,6¡¤÷ƒeÒl*i,mžæÔþñl³WLDOSFÍý¡Õ³è€ËV8Qpì›eK HQ&úÍæc^T<ÀÆ%,©E‡Q8ïJ6™ÎPmÿVXôÅ‘tåªÝUæf’{³]-Ñ’¾G,k/!¤JÛ¿R©1£²@à°è(PÑz¶õ¥(ªuÝᎎäòÉž ×½OU8`šbÞïkƒyV(Æc^BGf0t—%,xà;I&ëñ'Kd:¾ù‡¸Sº•<@+ÒË÷髯W{l’U¹hZêżÌ޾á`²P«³K#³e”|r6$•ÁÓ%µé}+«o7›¦º® ÷«E¾JÉ´å=%%ŠÚ –’ûu£ej›Â½q¬«ÐAAÖŸeÒÔ‰ÂYšP*x–~`P“¸3¤”)]Xи:h8ÔÅøÆ«ÜžšKÁí¨ ·5mS[áe‘š:3Pþì¬òLÌJÂP¢[mØïÆ&Y ìÌÆ‹¼ŒÛ*¨QñíçóÛŽnö̰ða¿Î7¤š9ÝàØÄ–ã¢õ-Î{¥Š¦íMi{…4ÆVÓH)E\ÏsžVXèÞ(JœÎ±†,@â²¥ÓWD¨ ¸\¨nPGsŒ×Z§’)áK‚™J%DQ:"Äjñ‚­Ðz[¶mR–“TõRXîp@óÕ 0*€³û?–«E§dcÔN2AH9å#°î{ƒÁ1²ü]Ep@=H~"N0§¾ÛþgŠNì4;>!Šß½½ ´g­…9?k¶ÇÔï¿åœðdRŒut‘ÓžžøÛu rz}GŸìÌ{‘€èE… ì7‹¤×{ä–Ó0­ëQUapi¡|ÒÛ!ñ$«ª¨ÂDÿ8,H…ê›äÚÇQÜõ-Ñ>zJa9dz©Å¸ôׇ‚ ðø‰Î”C=úÞ#™ÚgÏH !…Îw ý¼mŒ ¾\D¦›ÞïwJƒ±‘Þ@Hç©©r;ä|ð08âÊRU·í)û›,x_™8ù#Â: q²¬î?¼Ÿ0ÿ¥‡…èq%ÁÙWr:I³qÛ¸èßc¸„«tÊúz»¶}Oníä{ç² âíJÆC|›õŸ3–. OÀüøÁ–jg%•—¤)ê(q¸ ¸ed®Ç=ÇÔØ”¾-ã…1ˆs?›ŽqßSýn¨Êôô3 À#m™}1Û†“TZ¡ÚE2H¨Ìý*‘Œxb"0r¥È9êÈ'Ë<,’ì3ÃÂkVa ¼¬¬È]|Gí“ÔpÙ?kçýÒ–gP µØ|ðHÛ¯~.˜ ÞÞšC7ü{D®Ý+TYjh˜®h%J¸™öc—ñ#@Nê ÌÄwqë“¥8ÄŒdˆ@UþÑóû8·Å·ÝœÒæí=GE<¨r˜”.Ÿï?Ým¼¹v)ì÷¤„öËQG’Sƪ‘ °.2ç$‡ ²œý®Àçþݶà:ØD|€[v ÔÂ27ó=Xÿž;, kv<üûã—˜;›Á¡¢¥G@F UB’Nø=¿Óœ öõØíØ(e1•R¹Á8êVÈlçáÛõ¾õT»aOMzD`@ɽ P ('cÜü9=‰_#Ü}8ÃÄ#¤çc¹ÇÛsŒcßÏ‹5¦_V ±hyÓº†³L]©nöòÂHd,]l©SLÎ ´òÌQJ¶3ˆ’¦‹ÃšZrß­,s?KGÕ)PS _X”,fä`RJÔÀÊaª°ÄFPJÆò9 Þ”´ ”u†üCóa†RI¥â—›F¬Ô¡É8À'sŽû yúüðÑ*’;œüžqúî8KaZså®Èf'\#"‚2sÜ÷ÉßÏcÀR&p˃žùÆÇ}±ëŒqMJåñ®Ãõ ¬!!!C†;cÌlp|ýŸ§9¶7À#òùçˆ5 |õ„Áü$÷þ§°Çn­÷†HäŽVŠhÈde8*FG®ùÛ±‚0OHô ÇñHº¬¦+ÄßpHŒÌ¥]r“©?äÉÛcºœöÈÈᎾÙpÓ•-W`-ˆÓÏjü2I2Klfû,rKD~Î Ï ÔR•§ïFìÀgŸc˜$”«ìW«k´Ä†Óªiî´ë#ʪt,€©ކ¿Â”u#`ŒzpDóG‘œ‰K®Æ‚”¿W™9ÏÜ|øuôÌHS¸5ç„g ),i—ˆ† hÙÀ©zÛ¬79R2<Îsß{ºÌâ\ˆñ’C¹é2@ÎAúwÆáM“üá¿^ÀHm µóÕzC_ ”t,Á_?‰–#†Àvù熨ٙ˜á˜³Ÿ Œt…’Ùó]»c¸¢]Ÿ‡§„ZÊ€oì…òå6%‡ÅÒTy–ŒçÛ? D#%àÂ0Ïù<˜€6=8Î;dð$° Cð> “ÇFš1ÔÖ¸êz§§dêlÑ®1å†n¦ùÛâ7yqm¥ñ«vV%"J£Èw¨lsŸ%;yñe…ì@¯”t¬AV‰Ò¬àu¦($v=b¼¿ku²…£·4­q”:É ¦—¨YIRÛo‹r6ΫҬ€•1LTy·±ƒBE¤‡wpÌ?S3’™ÎtáAÁ8íò9ÂZeœ*Ó¹ˆÃŽ•QÖÄeº† ß'm»O“p%°]žQÀ}õvôíÓÄþ)⊖(a Ç iŒŒá§sëóÉᆲpÌÞX$?ØùvíÇ:X!jQ©'ÛßB<ô´•WñX–ºåMEW‰4È]ú0êm»(^¢}âÁ©§ŠYÏø¾íK4p@T:ô¦ÊÁ;!T’Þ¹Áã³)7e b¼z)T¤¶ óm~b+6¡¦ŠYbDwXäxÕÄTøuF*¬>Ä~þ9Ã@Kq‚¨:¦>€©¦Ž¦¥‹å^Ua‚I³|LÜØ8òóßÚ“>¶Ma¥©¼--q”2ô‹5{±ébˆ£¦Ý##ÿ,N|?…Lj1 LÀ,yõnÇ…¾,<½1ªK<ÑäG#®z³ÒzX–É ¹ì2O§>:ˆn–ŒÄ¢ØÉ$ãs¿ÏúpÔ‡a„Q4 ¬!†åA%žïG[ñ ;Ê뺬ñãÏ;1Œ©îc'‹ŽÛmÌpõ`øH`A 1Ô¬ÉR3æxhÓ­a;Ú&4vè”tºŒÔ2 ,v»|øs¨©a‘ãrÁ!’`r:¢xÇZ®@ÆT°To“±@çHîI¦†š0jiÒl¨Y# ­¹XdÏe ‚ψ]Îë B°yrƒv'; }Iì?ŸÃn}ðLs.ièñ ’F‘žI\ÅIð”ô ß ³yyä²|ø{ŠÇü8Ž’øùž®•Æ1ÛËËB Ò3rr Á‰Û9ì~¹ùp¯ŠOù²wœùí±=ø0 ´<"cÆfÉíê@\×óã.“¼ûy“Ÿ<ãõŽ -ØÑà{*9ðöííªêŸþ`wô#§¾.YCÆ''äq„c·èðb dâ,eÃ-#f`‘DÒHì©(,ìïð¢*®IrÇ`3¸âзèÊ›8£j»a¬Ô°ÉYMGUˆìöJ8¶–çy¨$'ðòHˆ‹Ž©I%cfÊMá{–í%›Üðç š»¬0¿åGâç¢Ic´K|¨­Š‚é8¢èhõ>½­‘ãyéÑžÙfj†çBb~¥é.>ˆ™[[íÐiPÛiU¢–ðÍ ª¨2å'–Tæu'®r¦wP<8ÇK:ð–…7¦Q?å¡*£¯‹ ¥îÉmŽN£DîŠäÈäI7JÍU2€nDŽ'¬„;„1;É,ݸžãâ<2àäuƒ°#>Gm½x´´5³R>½®·ÉZôµ‘Úte·ÂiVù«' S0ˆ ÍIFf“"*+†V^@ë…cÑ×´3w–¤˜hİY ò~àç²'K\×Íng–ä&®ŽãÍMQEÑr¸É+MM¥a©24‹V̳t.ZQ#1^“xÖ²[4âK¨¸ÁsÔÕT°PéZ#@°Ph«4@Ò¥P¥H&©Š%d§(.%•㥶vWJ¯ØY#{ ÇúŠ—Æ÷æt`QAÕȱ!¹§¾,­'så4ºJ¶ xé/PX©}êå|±fª«©¥©‘ë >5DÕ9T^¢ÝJ"@B‚Y4†ƒå檒ªãx¦´GY}ŸÞ­zrßpf×o…ibZZ¨Ùª]JÉPq€Ì*#†ÿ³ÍèRgBY’7™ÇPLÔt…É$Ôâ±<7 ïˆ=+íú‡YÕéýGWn´Y1þÿ]VõÖÈ.YgžŽ„ìóMC¤¦ÄÕ"ÆÚÌÍMËëµ¾–á%Ö:Ûw¾,HiYe–Ž@— цSq!¶NI’eªzK&ó$fÁƒ¿í¼¦)ÕRΣĶPñˆwû ´ÔXDòÃj­¬†áUJ‘ÃÑ=M:§2Ê »t©û„yºz€!:=ÖºŠíu¤§Ií¶u¤{@žÚ—ßd0ÒuG$Ÿ®`@##q”$-Gð÷?œ=D&¸@í,5º–Ûs’:ކ©ÖëQîÖöH¤s]Qâø>2ƈþ.F'$yàq˜¶ÜV¢z4 ©jê!"ÕÒ*¦LØŸÞ!–„¡¨0# AàÊV:¸³nÀyWŒZI%Øð,ýô„`ÖìPíÈØ“ÛcLü¶Y–$.Ú!‹Ä…Ï–IÛÏ¿—Ÿ´g®1w…uº)Î mð>Ê…$äöz}~î Œ²ËP@oz”Ï‘€Â‘9?"éÈß,IóÜÛ<â<\?¶1bhÐ"žñ\@AEf«pÅI*å3êæ+€{ïÅkJÕÖ¾ÀxÐFr­“ÑN²g=_dAÇÌŸ¯Â/mݺ¬D´Ùeòik˜ßüÏñÖ´†Ù{, Tg¯˜+Bè‡ÆlשD}/Ô«“#U,sÒ~¦#‡¦8 ^8•Ø©Ô0HÉêm·ÀÛ`vÏ]М³Ç/íÞExå‰(èňÈ°ÛCÁGž9ax#U``d,I;á =ÉváwA ŽéuØš7ÇÌ%TñªFŽV6eêR2¤œu7Vq·ŸùvíÇ*&f‡S†ÎzKˆ >ÐÏaÛçÀ‚X>PlÄ׈j¨a Ku9à Á‡Nq²ïóúð38ÉÁ]=@œ1öƒÀïãñ¯H±F© ;/‡rŠ9ó%=J½$ÈËÔ®’î#$).ç¾Ü t§–…ª©ÙBÍK4ŠT7J¹‰þÉ\€C&;‘ý÷räÌ Úö¹@Ò|™kÐ¥!]¬P94o˜’­›!mYsVŽÅ% Hï ÓCr|n?‰:T¸8,|˜äc;n<¸îxÄÇíR0<ðÀydöÈüûqÚMsvÓ˜åš"#3契s²7'çè/É®¨˜ˆHøº²ÄÀ–'a¸;ãn® x6©§¡Õ`Øßáf#ãbØÀÉ>~Ÿ~<¸%Øt>ÉéÉ ŽØlwô$gç·È‹ähqÆ-¾¥©Ý­e"B,PI…Àmëåøž-¾Ukäï?»nR,šró*ÅX“ãÀ£ž@"JÆW|LGP3ÒÑá›>å*âРX=yÇ"Êo$†cO„¹¿Ëä®kp·Dí¦ï2I-½ÔõÇARq,Ö¹·ÂOT,Ĉc©š9¡åN–eÎÙÂç>{ßôx¥ ‹RZ€Ó•ð1B‚Tî}iÇÎvßáØƒ‘Ü€ þ—áÓ·Rž®ÄcaêN[l‚OßçÀÕÇôÕ`›°p ,˜a¾>½·á5|žÎÛ¿žÄüXŠ«püD¦QŽç¸Î ÉÛ? á6Ù³Û÷p1Ø÷íüñÀ‘PúÃZ8C%{ÆêÊ̬¬0ÊJGfþ~üZšwS‰Ìt÷w!"˜…Û`Éìø'äIíåÁJXvÈÓË[âLC¤°¯>Z§Œ+~°†•îVZzïµS¿÷Zð2U'ˆ‰pr®pN2T‘ÃU³P Ô¯Ó×ÓÕ4“†Dê¡7cöá`>Q¿VND¨D¯yˆ_Ü„–ªqµ+Ù)æ¤4ñôÈò3–ë v 7v “œyyù¥5R¼&“¬u¢2J²®XðNq¹ÁÛŠ*Å…@U5 ø€e©¢Pª[¹8=m‚NWläœ÷ùq€Ä`²žpŒºKŒ}“†çý¸kËÃ"¸ãáÝRÌ¥d=AÆù8ltŒñŸ Î7à))ÙÀðÕÛ†Øì|•;ŽžU×ã8´»‘FüAðCàÆ¿Ähº›  d†ÎsŒö'¶ãlg†›¼ÒM¥–!5#IftÇ’ ød±ÉÏQÛ#Ì窠½G¥!’ÔP°¤’•$‚ÄÕçëªôMTU3U[åÄÎä@îdïºÈXàìûP6â°”ÍLíñKÈpêÿ@Üo¹ßéæn9%\QcHÒ¥ªbŠÖo-U'ŽøÎ9¤Πcua»±Øìçl‘øðbO:¡Ž6‘•!Ÿ’Øê|(Ù²vúyð‚P±…”»nÎ ‚½¢\R®A!K‚pHl¨óÆãÓ¿IQ3åúXGñÄ\dFç >™ùŽ% ÅYûô#³ƒ1JÞÞš0~ššš†¢²ãTÃÇXš@Ä€Z]¦db0BJŒ÷ñsåÇ*¯µusM,Å3¯Žå¦g%üb}ûå·’áH/¡.±7ƒvåÊ.Fó*¾Ž’º“Dj ŠJÊh*éj#¶Lcžž¢$šôî«èÜs‰zOþ ï…þ¢OõøhöÚ9úÕj)ñUN:÷±#f`{ü†OÌ”WÛtô7Jjéë)¦§®£¨è’ š9!”4npAŽFØï“ç‚xXb OXˆÔ@aFÐ×´y™Î>G×òÞôՖ垯H]j­u€xžå+u;Z«ß  cfÇŠ‹‘–WÅiIkÊ‚T1ŒœgË}Çßž)Ȩ¨¡çŸ~<¡OŽm jÚ*7Óu«Q2@ôÈ*©_¤åg€eÆNLŒân 2iÍUr–†–‚ž(%þ…¥˜±h¶‡ú|=$džÆxoî-Wh’ÎdAÂ-ZÅUºö¦# ޳Ñ4‡eYã;—9Àq¶\)Ý“¿êZg‚jT”˜ÝZ9¥„‡ëêÈx"`GP+ÏÙF@øŽT” ‹Ÿ,"î¹Iý§ÎIµ mLBž‰<©ÁˆŠˆ öP¾gè{pÇ=d4ÊD’øõ-³î:‹òp1ç˿׊ji¡ã»ÿÏ%\³Ò…GÙQßëÛÌñ€e(ÍÖ2pC6s–êéÀo¿Ä0;‘cv1^™=Y äv$y~?¯Ÿ !Á°ØÎq»;zcñàƒg¬"Œ* 4Š{l~`gmˆ=°~›ðà­)¾Ã'>X#mÏëçugfå”Fbûàv‘¤8÷¡^øÁØü¶à•DŒÃÒ¬[¤ý0<¶~8´Ñ‹êš>¬ß%Ò÷ø,Wê ¼Ô‚®Gf4áÔJ Äñ¬ÈÍð¬È\2çlŒ±®Íu¤òÁq¸” Tžj™EÎñÒßç LÎ\/Á“XC Æ™sz¢Qê¥D’x0§2ÍÅá – úFuî+È?cD†ÛEu×TpÓ«+¢-ᢷRCO$Ï[P +,±FT×8—%Ù›ÃFì^N¦TØlZ$ª½ÖRj ÉÙ,p¤‘ÓÆNëqÔàôÀ™%)•˜ÌÇü0ø; 5g!=×G&©áÎ ?Ê@¡w/ÉÏ=Ïí ÖÛun®«ªÔº–ºª;JTÃOUZ±¬•w*ÆQ-šÇMŒOVQUQ|(# XéVwÔöýG[{·iŸÝ±P ZhÿvéºYâ©6¸'Q-ÊXAQpx™džG=x”d *¼D¡EySHsÌÐvµãÀ}!lÌ™nÛ¨'±îå˜ ê÷Ce·¶–Ó¬%t6¢¾Ä =Þ­P¡¤,¡’Ñ‚Àñœ9\‚ÇHýLE8*rzÎØ°í÷oÂæ(2I(HrßÚkÛBH qÖ5<ËS}(=âäÑ:KLû‡ö§_ܤµØ‹I ¢Þ‘Îõwê¸IGGN†W F.Ñ® ü/,# מ¼Õ ‹Kè-G>¤¸B±XhÒÙÃO[«Ô™*ªÓ$QִܳµLÕ0[™k/×TA½êYbFT¢Š@‰À89V(²4ÆÁ,<»ÑòëjÌE©õ$s[´m;dÍCD̰×jOý¹Io ˜¶2Ìu#-+Ö°MÙ!ƒ¾ ¤÷×(uÖJõ˜\îÈ‘Nî‡=!ª/×ÅÒZVÙ*Ø­wýñª+)ã÷ñgï úÚé¼^£Màx1„g+$­Ôà/‡5ï15Tš·S×\³#ÐÇÑCjŽ]ŒvúV”E”ì­$’I+ œ4årBŽ.dÕ*R5â2R8ã„:• V¥éú%r”ï#ü@æ@OÚWZ VòÞ–áÌ-W¨n6:oÞz QÛ¨æƒÞ¤†Åi‹Ý(f†Š–'1¬þ+*§xƒ¶Tg‡²R‚€Hz‘RÀ|odéæÿ17]jgÝR žáœß¶Ù54ºMiJk\-ªn]ãEAOÇj££êiƒG3ÂÐÕ< Í2î6"K¨yUËDå¥ú‹NÓÛÅëKÛ§¬’ãRTÝ"®¶RµtôWiccƒ-7R´nªª%WŽ4éP"‘-K´(€ 2Ò Ž5ðâD,¡2¢R\µqP k™m2A¤µ-~U CÒ[Ôàõ13à|¼9O`OŸÒn¢ÊT—bÎF>&`37Nãçöxñ» ‰–Ý¿89&Ô”aýi >$øÇ¨·›6Ê”ô/®lÃäÐé7QŒtô´ŠŒtdƒÑ±&1ñ¦=‡f#}ø„ž%øAXñ ELŠzd+â*·NǺçÇà™Ç.:ø™:ƒŽêÁA A€ .ã¹ãArŒƒ¬t‚GI*† œžÞøŽ;ñ ?P£È é9=@¨Ù ¿öÆûðØð;ñØ.Ie²©ެcpwÛéÅQ­Úã€ËT€æ.ì@ÆàÄ)ÝOÞOååÀîûD 1çƒßêü>þ ïЋflÞíS\*RJGQ=,rÔm™Ä$*ž©K„é·íÄ£WAïGs„΂ Ùw"9cc–23öÄi >}NxóÓ§¥?QXЗ æJ^昄͖Gl…Žf:ò¥(ì{R•TßBÓ¼\WF¾þ•>dR‚Ç.Ä(l’@aå¸À;üÿ‰o‰ÆOm‰ÜœñF ïóúñꢋzj±Ãº—rpø†JˆÓ|à1€ ÉÆÀ†Hß·§ sªIŽW8;`3Àg¹Ø~QË·ÆQi4Ó‡tTmÑñ¾6îpVà`ŒvO£¢È’ *ãËŒ©`{‚6þ`· К\0Ë»ž»a3’qêß×~ÿvþ|bí•Á?n2q韩â ß½ðI c-ËMMA­tÝg-ud¾+ B¶šÉ ñ–šê„ÀI=5”Ž)' ̦4”¶¼êí1pÒwºÛÖ0%§~¨fŒUt²åéëiÉ?/IåOR6XL7¥Ë˜ÕSžæ×S€5Ï„D&€c$pIÜôv~<+m°_oáÙí7 €Vèg¦¥–XѳÚY•:#ßýL;ð´$¨„¤^8oݲ”‚¥($©ì‡û^‡®žîl—‰ã²V2¬UQ™%•QŠÈ°*™eU™LŠÝ?‡«Þ€¤ÓÉOqþ=Ú’š_þÉS•hZJr@Òø-ž•9ëBÄìOP‘¡(T¬PjžLH=žŽ•Ô(Õõú@ßítU6Ë¥6˜¯¯„½ ÔÜ–Úù/ðÚÉL‘áØðß1–Þ&8^(½C§îºnã5²óHiª¡ÕAQ’"ª¥˜ OLá[¥—Ìl2²‹´Ê@»6QênpâÄ61R²Lµ‚ã¼g\hDt‚F<½sóí¶;ÿ¿n‚­°ôÇ— ïÆsøF¶4²k5§•(êÞFL…I]X”mºUÛ+¾Í¸Üãq*»Z)o­l2Zèšk„=>"t®ɦ„õ¤l‚ ='¤C=AË…{!G¨\Õ©˜.u\RÝv G\¥|¢ÏºÖÄw¦,~ÑÎèNFr¹ÄÒ3 •Q¤Ž.¦4PÍðž¢N; )߈wÎÔŽ·ÝB’Ç0àr‹Qº:£Û y£¿ËÏ€¹8³6ÿÄQ㬑ZGJd9éÙˆ=ÛrÌG|dœq»þËÞί«ë)µÎ¯¢a¤mµvË|èÊºŽ¾Áñ:“ jŠTćÿzAà©`²…ÔC$6$><ùˆY#SÜ÷v&eÀ$.OsÛ‡+«LϗĉjZ‰%1=Þ1•®÷éüz©žUbI(Äq©8Ä0€¯Ð;ñ Zxi`‰j¦iU³|Dß1€1åŽÎÁùøvCg,0N0ö†Ê˼€xtãÂB¸'8$g(íóÏŸ 0ÎÌIbY˜õdäñÜç'þ87|á0arGJïŽÄàü† òíÇc8=]·õß?/ÃçÅ(¢6ûgçcœíåçÛòúðFÝñÜŒŒù6ùßäx±”P.) #Ä»°ÆO Á?Î?— #õ’À†=±“Œ`zçÁ ƒî§tSà[R èÂŒ6$vÎ?<üû~‚„.OÅßsœqÆý‡áÁó§¤U@áåÅLgañt(8$c!³Øïü±ôyŠAmÙ僺œ2mºöÆHÆ1ž ]ÞQOåæÔ‰Í‹Tßì= nºÔGyðé¤e©¤ÈøiªQ‘I$öP~| M-Âñ f¥’¾¦ŽzÁ5ÍéŒrVÔ%ÙcHŠ¥˜*ä·Â7Ppmò«¡d”$àõËÓ–½t2ŽmÊ­Î/M ¨ô\÷JëÞ jK%‚)´…‘D¦*êG] SÄZºê D .òTdzlígM¥­šFáxºMtÓ•ºÙ•èà¢7ۣψ´µñJż\4¨$‹ÃŒ”f^¶G؉’̇4SOô“Õºà#%ÕôÀÉ Ù¸ I<¹|Ìi‹"Ô3åNs‚ ÔpØý?¡Ë­š’®²çq¢©m?d¥–º¹hÕŒ÷9i!ñ’ÕFÁòj]—ÇepD€_%œ+tÃ>°×Û½S4ÍDôTtϲÖÎ QZhÄ”ôtÃì3ùš®ÓC%um¾Û =²žŠ%ÜŸx¬™"QŸóÈ™íåòÂÔ)g–XžõS•ð‡¥W—9_µÀìz¼_ÜÁÖ•o˜ÔOa1ˆ´–™¡Óöõžh’9­¾+LX£«§F# ýÓ¤žœç^ܧ¡å—8¯“ÕÍ(¸Ãk³ dg&J«„òÓVÈòHÄ<å.±Æ ’Ç6ù3¦ŸÚ‘3þVô²‘ÐÊpê&[÷ƒï¦ˆ=k}C ωq¹Ë;*.z¢ˆN°NpˆwÿN;ãŠþŸ¥e ¬¡³özOÄÙU9ǯO¦OS`u‘´¦b&Ûm',¾ŒaþFì1ÜÚÀ¦e‰¢Í v”ÿÕø‡èËm‰= Œ¬˜Î±¶H÷òÛlpÞÒ2U³?Ê#»m†àïß·ú=5‡§lr³Þû» 5¨`®»ä¾à³¬Œî7]†Ý¼¸FfjsðK–èÆ’¤àà{ùíåÄo° Î?Â,ìL’²;Áž¬‚;…lŸÄŽ–a'Aé l$ÿó¹û8ß;v;qN[ U°ŠÎ:¤q”ËRp2¹ÿH8'>›öÇ©P§$l{6ÙÈÊî|Ç×í!Ÿ='­¡¯˜q°\EÒže#=~p>Z„d'¤êï‘óO>&ÏNjtÝÌ2Ê'²Üt‰•íº¬<ª•Ø#’= ˆãÇí¥ &Ö±[o] U”òþ£¡Qä¨>9aý™üû ¢ÎÎÂy̤ÌùȤBb3!Æl ¿<þ >{cè5SÝ+•ý¬äw 2–;|³çǵ¹Õ4#Î+ïhi™A 2á€'#`{ ùc á¢df,|Pç6$ñlW8Ço¯@ÙŠva›x÷rÖøxÓZ7Tjû­5¯KXîš‚ã3”ŽŠ×G=\Îà“á"PJä± Ùz/ÊÙcÏþ`B— L-zÝÜ\.P5QÀáA¼œãmÚr¬—PK8.Œ…19pßãueýŒtf!ûï›W9§+‡ýÙd§D§ÆcÔ2{œçóx¨ýš"('‰ù§ª¢©è ’Úí @êFzרÄv/ œ²(á2ZXLÄŠ ¥ÿ®ª‡b¡« ZŠ]EÆ4pR¡Þ¾1ç.¨ŽkÝ=$vY-õôÊ+ê×,«]Jà=](†–€¨8a#v*Ã*:Yn÷»¦±ÒëWl¸TAUi€G¨,ïáGQOŸÿ S$Xjˆ‹0ñ£bÂ3Œ.3&­S&¤ Š9of~ñÇte¥"QÁÛ˼V+û Öšæ±ß¥±W?[”šÙVGJܨ‰Sáȹþ" r9 Ï(aб©yw«¦ñ)êÝBêÈU¦÷)kX%, ῼ٪%1¬‘ä˜d92 ¢Q`z‡’šéÿu^ÙĘJMáFëcÚ<^*«í’ç§nµvkµ9¦­¡Ç ÏR:7Å𸖃#ˆ#¶à2°ÇÄéÎG§–3Ÿ<çŒëMÒRªCßBœ%@Ñ@Ê„k¾2Š`Œ€ÊŒŒœcmÎãîâSfÔRQÉá–yiN‘A/C×$ ÿÓÛR«„÷Ê(‚ªoøò‰Õ]¾×¨íǬ¤¡”<!h¤eãuÁ >ýðr;ñ†¾®ÇQ 5隢•X%-×%S­H €S±éìçcݰrÅŠ /¤Å*kÞ {3튔„¿Y8xR'‘UÀðË=;…iz£L¹º6t\‡±Ûã¾x"†¬Ë)bT)™Jž¢A$*“ðoò–ÜRµTq>ÂE<@ÁÓÁRÿ è t°Á9ÁÁŸ?2D•&:À#¼=KŒcp@'È©Û׋$09í—$Õ"o‘ê驪b@LôµóÒ[Ä©…˜†9ɰÆÄŸ1Áê“Ĥ[%w#È~xã=Û«°í¥ ¹ÆØû4{?×óNî·ûäSÑhŠ µu„4r]ç„«½ªÞäAê_x•Gð‘°ˆË`­ÔvªJ+U¦(íÔTñSÒÓÄ«0ÓS(Š8éà,hƒ§±Ø`o¿ I¼§w¹Nd³÷aÎ)r”ìÔý´naÉf‹¥p’°éaNˆ`~ }|øç º7Coðˆ¤´ÝJeÝ}Ýœ‚Ù㥊Iƒ° `ÝŽ;pŒ ì›ï n±Õ€Ç¨2t–=E@lÿòŒgqÆcCÄüx‰.ÃwÄfb’ ÎÓ'Z0 WbUJà•9Øïë±À×›¯VY+ì—ªU­¡­Œ‰ l)©åÀ0NŽAW`W±àEC>>th%žùG•üâåv«åµã÷]]TõúV®¦z‹Â4襙»5=J"âž¾%,$Bz[¨ËUŽ*h­cÄñ'*U@ ©ƒÒz{6F Ü»·…±'­›pÝéÍHBRt Gg®È.Zô¦A u.Ä(ÈÎÃrs€>€á²I¥©bò>çaœQžËòÜþh©…L êHéÇlãïûÿ.U õ탱ǘy}3ÅÞ>"xÁ*ÃðòÎ0G˜Ç—oÃ… ¿cbFÛïëœpAⳌÔã`dgb2FsÉîåŽY Ó‘¶så·o¿ÿ<Ä1Õ"‰…T’1¾Þ»l7õÎv=Ï ¦8à,y‘õÇÙzÒ±\…GˆlA'õÎùþ]þ~}øRÓ¾I*ªÅT¡Œ‘Ô ü½OnÀž­˜Ï»\"õÖZ÷‡øcQ…¥W ’H;ï¶Ùß·ãòàää¨=pNs۾öü] 7êÝÙ õIðøe0X,2Uq“ƒÕ±êÇσ¢ŠZ‰a‚(å–Y¤ ŠÌ,¬Ê±…DÈåÈ{ùqå›­ñC‹Äm—AYyCm·k~ak/rSfÓQº<”u‹Ñ536K,•ÈýîCCÈøÛëÆ§Õ]qvk…yŽx@§£¦£ïOKKU!cé$–26d';©vH5MŪӰBå‚I˜CPröûÃA‚(ÇLb\v=RÊÈÀ‚ ¤;äîFû“ÆÈòûššOJi¨+g¯¥® YäžMï pW•æi©ž(úLå§LŽŒ|5ø™@<šbe,©X1"r Ùa)AÁ¡‚Á"sûq×:ž¢4…Rc’´Ðô+´”V¨z†g=s•R4UA•:RA{熬Ë-E³K[ªxp¬¿»a•JDD&P’WÎaRã¨a!mÊÆ½MCÌJ%Ö´*ò³` 0µÖΙI‘øùíÆK×”T~åï@”¤ ÜÚå½eò¯–:.Ïh´Ï-&«Õ=W‹½D1­£·7ð­ÔqŽ‚É;«àcãGYº@fR­Zªés¨Òšjڪ뼑нÊZú™ªj$¸Ü%cOM4“JìU%«¨* E,{7«¦HûRŽ”ÅT߈ßREC•ÞSâX0[ FÂó"ëGËÝÑÛ§Üd³Sèí<#pd¦ hPÝë]ÑÚždv^ÒSS6rHâŒäM~—´jʻ樺ÐÛE ºX­‚´º‰«kÛݤ’6é`:)Dë–#üq<:a@¶ËJ‹"U_Ž!ÿá¹IY²¬¤:æŸ@ úÆÊö‘¾Ò¥˜ÓÖÆCh“QÎÐ(A,=5 í$Q\Ûý•Æ{ñXrFÜ·~`Z`¢–Õ]Ú¢VÂøbž ,Áºv q©¤bvÇNr<’¢f[@ )ð÷q† \²âÅCÄÓXùD?PÝMêý{»åú.7*긔àøpTTË$‚Äœ$-¨òã·ÕÂ5±r OSÄ‚:W««.S Ôt+QJÝ`ì@–†‰†20s¸<*Y Lõ(³¤ø©#>pk¢¤$ë“éHÊ’!O&Ñ€´X&«–=†d©)N]Žøÿlvíœãn)W˜T{ÒNõê'$ Á;M*´u¨ë|*6W©q2€Å•”|÷é™Óíë&(n=$ûTây´ÀõßP'£—dC1*Sáÿw*Ï,Èu 20hmÆÇ« ¾@Ùlå~]÷ p ¬Ê¤‘Ôå•€ Ò2‹`vòÏÓ>í¨jƒÆ<Á8pø€ÑÐÅ*õ0ÏÂ@,7';ù}ÄíÇuX LJ’Ò+(ÊôX–Á'C¸Î7;½bå›C\" (]ñðÂ%É 3ö‚† { ›pwòÎݸ*>¹K( …:ˆ+ºƒàïñc¶FØß‰€©ÃZïÊ0<ã¸ä²ç=d’£¨Ÿ€Œ@Âîaåøp$ßÄÓœ‘Ø$±#ý'~ãÏ<aÙñJ=4<áhB†L Xù®AÎ ÿ'q·Ë¶Ü\´µpU×PÀøZ‚ÖÔ—öJ:æ ‚!«Gú€2O+ëK)±ÏJ]2Óió&P´KüK:{i—éÙÉ ´ÊU Ì’9‚Jùu'+Ï&ŠÎ¶¥ª¨¢•CÏM4JØ_ñ#s`KýŽ p|óçÃx¤©¨Žyiéª&ZDU$Q¼±Á$ fdCáEÕ·Q|ÏÎÏ53ìò'"©š„¨oeGœy™‰è¦Ì–®©–¢“Ìh°ìü‘æ]þ†žãG§Z+}LÕÓVÖ×ÐRE%=Dk<3Gµ^$‘ÿjﳟ%®5)%O3µ5¾Y ¨¤±•ýГ.W¦k‰=Yêè,ÃôõÓ­’vušZVèd€K oœyë%VÉËY$KwZ‰sVq\M+Yó?ö×{Nj¹êmü»²éŽ]ÚFXd££[Ñc?fO{«PeNÿÃ8#¹ãKu¶×µV¹‘¤ÔæÕ²XõGMqKz mʤVøâ ½þ¸ß-?kZ§L*Jº$½™ McÓ"E–BBdÊ3P VX’7ë8®(ý¡9÷k«’²››ÚÕdu£ßîçüË$3T2Êœe*FÄc#‰O,ùƒU¢§¯¸[ké%¹IàÞkìöyÚÕV“LYj«,öúR´’G#³,´jÅLäýDéÓ%ôªTë¥è #wÓx ˆ©’ÀR”R‹Áœ²AÁœÓ‡ßfsjßkÑÚ¶-C`­{¥MÆ…%Õ–)­µT°WÛk Žo~ñ’ ˜¥§–'2ÆíŸ DfT2±i‹HPë=1û†ÝX aU}еÒe¼jÈýç¦îĔք9#ÇGø¼9¿£I›6ΠзmÒ_€P7º’æ·X³çƒg¾é>XÚ£[õ<¼´Õi²ûnžXtÅÖ·1½~plU²`õÛ§p¢&ø‚1Jc;§,µ—.i©õ"ÔSTIG'U\T 4é;§.‰ïŒ ,˜Plä©.¹Äµ-jK.MÍÒÞ™ïûá* !Ñ2¯À®Pýj³é]c©©·Û©hæ¬fÄ;½U¶­œÉÓ wÄ0õä§J¬nƒ  « Ó·˜ôµþžÍ4:+]y¨´×u¥L6ê¦ÀI¢‘XøQ¥fCþŠ€ÈpN„‰3)‚‡qs½Ž-¸v­)RŒÙJë5Aî ÂñÏ %tújEXàh+ MBâ½'¼F(ã—¥eµl¤yÊØÀÇ6r1Üy<ý6ýic>a»ØC¤¦ì©iÜ=}5XÄ®|†Ç¾|³¿oÖüf²ˆÙq€G‘Æ~‡[ãn2W‡¶0䌎°¤>Úï•ù: %¡‘‰šŸ8NxúÃ&ùàù0žRÖQÝ ˜LsÆRX¤ zq±VB;‚sÛÏ>@ðh.nœ«@¨0 Â"³­v˜g–‘¥©³±_àƒâOnê'"0ùñi°~ÎpÛæ˜Ùï4•±¤èÑ‘*© O Šáz{u#c ©ÉÛ[D(‚£DáÊŸŽ[àJB“x –§tKi&ñ$À'§g«=u ‚ßé; »dmÂÕ1ˆ¡“ÄÁE‰úÝ+"îO’ŒË¾x3F š‘GÃÂ+½+ST¶Ÿ,M®ëv¶Tõ3y¤ ÂÅáʙϪ‘çģƀ7S0ŒËöJîIbNà Ï}±êqæ3,1Eh@ò ðROðÝQâ)&N¦˜b4f!†zK7QóÏÙ; ÿ›;4T"³gqºŽ€àö <—׸⟆>ðX^îÈg­¢‘ó éÎugûñÛ}¸‹Oki ߟrù`Ê>"(¿oc×áIȳ|{A^f80ÑSG!c `†HºrÌã©JàƒÔÇ+þR~~YâYÉgúîrêvªxf³òîÓYÓtºFž\$‡Ö›Ae!ë$ŒfI0R3u3G¢mþ"Xc›57gÈEÔµÓ÷S´ûT˜õòÍi´é[UºÇb ‚Ûi´Ã *GKO+’³)'©òÏ#³3±ffáî”É4`ô•Fo •¿‹(V#,jßæ9!Tý£ðÍÀ¤¤ˆÜ|p†€›¢ æ×Žœ¬h¬°¡‹T€Ä…– =ðHôÛŽqlÅÞ b³ñŒ.ðÄIÎ:ÒWÃx˜Ü'Ä:”)ÈÏšøÇÒÆhJ’JY²B>I8êÆQËz‘·Í ¾{½ 9~ ø*ÅJ…6êuÈ #¯¨‚ñ°'l¹à¢…‰y3" ,‡bÊ6f þÈ#;íÜEG†¸A“Õeˆ»!“Qé‹.°´UÙ/Ôi_A],¡ð²Á(E< 2`ªºŠ:î3ƒHãÊŽsò¯QòÂô`™d«ÓuÎß¹ïQÆËBXRV•‚â‰ö“euRñ’¹ mu@â•S¶ÚE;„(Ò¸\»âœU$dçb3“¿Ë;vÎx)A#;Î{œ]¿.5½Ñ‘eòÆ1ö9SÀ-"–e;>]Î7ßþ? Ù!`@9Éíý>ŸË…˜ì»÷;÷ßaôÜÿ./(¨ïpNF|ÆÙû€òงÂ3é8`g=ÏÓ‚¬"™…yBåÆÊãlî{{ýß— nz€ìNû€'¹ÛÏ‹ÆùvE6ZªBd=r ‚¨ æëÇßøïäáÇ‘ÔA$Hh}ãë¿0?ÄFËjC¼1áÆ3Ó̧á$œéÿRãù¨àã†Â®ØÎÿóŒý;ñ}®A°åÛ„)ÓÓ¾ýöÎs¹';®ØûŽxq¢­«¡šžªŽªz*ª`þM+´5±,Òhˆe8$}®ÍÒ6Û‚MŒDS^ÇXoÊ2¾jK櫯Y/Zû›ÓD”«=eCLíc> Y$E“¨¹P:ݘ’If)Æa†0ª1Ò¸êãlö\ì;géÄr£x—'dS† PSÓ/hÀ•À$޶ÎÝD½sñßÏŽ‚®í¹ ÒÄ‘ŒÀôQè7>yâyE€-4(!HÂÅÔ~0 "¶[#¨.:ŽFAõÁâ}¤9ª´|sRØë`†Ži¢Z9©)åŽI™ ´¡l˜âQ +°õ9kTµ¤±…­!he‡á˜n0÷«ù•~Ö””× zBd´^*ÒKU e5.³ÌçÄXX¢‚pŸu¿œ¾¾X4…=çTTNÕ:º’%¦Òv¯tžHMR4U7Šš <4#â5,¾<”n'7¥Yë )G]ÉàD±s£OÛÇ£î«FÂòXé:m¨§¼ÜmÔ÷K†¡©ª»Ünõ´ðTÔÇ$q•¬C1ñ'ˆ–ªDéê̲Hp2 TäæU§PÅ–ÑñM'nªz—’t ŽåP:ŒEi!UðéP4¤ÈÒõ²/Jñ¦lä ” õÖž'¼Â%ÙÕú…ÌXê$¸ÜônáÄkMÖ:9$ަhâ^¦d’M•— ˆÔ‘ž¿´p7ÁÏÒËåš—SjÛ=¾«R¤¯[VZ7 ,1µO‡18'•R3’>}xÅ$Ζ‚1 yF©®™j[»ð×´_Z¯FÖRëÚ{ž ´Í² zèQ˜«Á=JZcLèÄ•Q¼á”•auáßxw#­³kŽg\5\ði­qÔÝðàÉžPhí”ÙbÛ fpI'û‹w&$<ؽ C¯o³+tÒ[åK= dH"µGîŽ".ÇøMXµr.Oñ°21Äß–4âÍËÞgjé2®ÔtÚvß*¨ •uF6r½GŠª›QÏp“åÁ •Z&M´,ñͼàV dËA.I@ñKùvE}yÒ×½7žKåÐÉy¢÷ú*fuj£Dd Ó¢àuŸ²¬ÝcÃ=J›fôç%½­‘ò‹Bô²KjÒô•‘*î“ÃMPÒÇKxöʃƒ¾$ÿ»©HóˆÕt‹LúºV,†ŽÉ ruœËM,ª³’Þ-j ±Ûï⎤tIõHÙ—¨®Vp ÷S‘Ÿ3õ;xO¢’ÒmKgYCò³KQñV„zϩɿfN ÓùêHðD-b»²(Œ°+±É?RF|Àç{’8M\˺üGâ,KŒápp2¿ù¼€Ïä ‹üG•›qŽFaQ F>Ö2'¹+Ù»oùpßR¨ò+±˜ºÑ"Y\ÂCލŽ|8ÁÆvÏ☶¸Dvá¡í<±ÆwðÈ*±Ž’Q¾J+°Î ß玧¨Br¨K:¯S¡*ˆêˆgåqóâƒ`_MSG}kÒ3¹xúu`Ag'99uÌ? ü¸¹$VF_â1|3da”ƒÔç8íÛ=óô> j4¦bž‘€•p®dE9lõóïè~î,=9,‹d¸Öuz³TÐ\éØà3ˆÝÔmºx+&G›zgTÂ:¨´Y¯7ô.j%/²ìÅGcbúÅ  “5·^J ÓÿM,7Š2ì—i ­Z!¦©ŠxÒHzkcZ0Ì$)F4’±;€møÒ“eÕÚÑ/Ÿw¬Ò—¦¡2«ŒRÚŸâÈf4—Ÿ?ê}¸êý1|lM–…›Ó,èèTqr„‰ôçí¤¤mKr€º‰«à¥Ä÷•|ÛK).¯YMʧBºÁ% «’ÍW!’†uñ™G…z”ôEAÎÜAy}íUfç^±‹7¸i}SUªåQ=P–¤VÔK%=º¤„‰@¨™”*Ô,pWH›D»ºõC¿{q=½‘Ë]•+•i¯X0ìõ3_sšK7(5¥dÔ÷+Î’Ššk¹µZ§zzæ.×p¤’’U© ­Ë柪B·€ 4=cÓ“|„æ›TÔrC›TV»åI’Hô¦»)2¹)¡ºÂ ÄK’&9=øêíTIµM—)S:9á.‡ÀÔ8e6„H*”›È½ÖY5߆„UVïcÿimIÌZ^[Ú´|תúv®¢®ŠH¥±UÛd§’çEw§fŠ®™fxÕü>§Bê²"ú÷ÈØit¬†ŠñÏnbMK#,rÍ`Óê"+d©$¹#pH)ôÛŒ;;bN´-kµº%JS]«!¸Q,qÄŒ7À[6¯D‘*Ʀ¬UgÙf®bwGª·ýšžÈ¼°Š©ù{E~¯€!÷ûù7ätâf˜œçr6ãehùCÊ+ 1ÁgÐZVŠ(ÆóPezs€KÂOp7òóã×Ùì’¤$&T „Ó*œó«qŽ“Ò+¤0͘sR‰­0ÝÁ‡ LhO¶7²†œÔ–ùu®“³Zèå1IIp¥Z:X)(k+¤e-0 ?r’fН8Š’áQÅ„4õwº“óÙr¶\ù'­*-5éYO¥.µÓE Ô¬‘ÔXn°;ÁWo«Ž}àžG |3D¨ä–ŠDclHý-­6€ Ç€,¸äcÓl¹½4…IwZ@#±›ËÄDKWY©õMÊ{D…`Õô´«_¦ëd‘Uu5¡ÕåŠ×U0À7zpr–þ/»üG­]l\ÃÔ·)q³E=F¶ÓôòÃ%¶ïFÒ~ù´À 5˜€ºo.D±HH«¥™›£˜IDÅ)Í]øYr~þÍvÁ‚)­ÕÑ„|r¸ÆFädmùþ¾|8Ð]§£g§n—ÈWFÈI—(þ„ƒ³w\ù‚T¬’â‘x€7ÓÊ,* ´‹)Ãà,°I€ñ“˜ ‡Sñ`î¤yíÃ]¶ªÕQ%ÆË þ:›oþÌÊ êhÀ=°3·ù€ EÒ•¹5òqÓt×åk>§§ªOz‚B­ª™Î&…°p¬2 œ08>¸ÏD©Z˜„нBA±ÿµw9$O§Ë†^H:ÊRB’ø– pˆE²G·ë Û;“.¬¢ÄHïnn’çš„ÂÄù˜ñƒž3ŸÞmõ'Æ”™ (A!z2̦vnq¹ãÏC-¸Tž3åŒã'Ç—Ÿ—Ÿ ïmRW‘J"“•%œÝ:rUr#m¸^(™gÛ9VéPIPÁ”PFÞž§Ïˆ*Ï€øˆk®P鹯rA#·| >Ÿ®ü;Bƒä[8'æÀ…ǃ¹<cA‡ãÆ*¹a 0S€X€íל¯Q=‡Ô·€FûwÀR:z†À|ÇmÆü­F°Š æ× vB‘‡˜eU! * ',wÈÇÓÓ€ª&iI‚ ÁÄò†ß*H1!#¿ú˜³ñg–lÌ@¾ |AåPD  …##`o€3ëÂÿaŽØÏÚ9êl1‚v?–Ç‹åEAÓB2HY€ÛÏÛ$±ÇaŒd~^¼…€ Ĺ p;o¾}sëžüP£Â,0mnï‚“øÀ`àø˜îv'(‘÷OªÁê•ÊŒŽp ù.ýýx¿X ÷ŸÆ¹B°§Q 0FÊzúI'ñt’|†Øï·N$h(S®wŒª¨` "ÙTôàLí·ôlu­4A–gø„i*…§b±Ë ,oN]K€Gˆ­ÔB§$›ì¨,K}‘Ô@ˆíðøyw‘iû„kV(äaîõQKO)wûaGðЯg'p3Û«çÇ7kK3¶mµ^X–T‘þ$2Óâ‘Üñ·g(K·Ù€+H/¹Fé~hs¬5™rØ«³\l°e§V Ž1º©Ia#´?!ÆÇØêã¾_´N·ø ßôÕÏNÞ™H ûƆ“©ÀìÒj±¿ù)“¸Á7ô´Ñ2EªP­Ùå`nJÊf §»œVÝ•rt‰‡JH%¿r:‡Æ]b‹ÓuMËÞeÝ4µÉü[5èUéºÅ”ôÇUAt^«eKˇ§VíҳʹÎxÓ¾fÐ]4޵YÌe¸¼–ê×GTª45QÔSÔÇ!HÝ Lç¤íý8êO¾%$Šô+!÷©®ý±ÏCíÒ¤ øG¥Á¤æÞŸ4×=CyKæŽßZÖš é(U㪶Þ,°02°WlêPJåN7ò«˜ú&óÊMwwÓ5Ì*mUž%ÎxÂÛ:­U¦ëLÈÙUš†Xæ7ëŒèÀoڒʤȶ^$½ÒÙQÒÝÇ™Œv¦ú¤¨Ç€=ôå™{ûzêÎ_ë[†×÷úÚ»%udT–-C+¤—[ÊlAL‘MPq<’˜ã•=B‚³®šq-/Ö¯/y§»±%hž—÷¥"S-Ò*)ZJ9…]4U”{\¬KOd® ššW$²¬ÍO7EU=Dqú¿¦í¢ÙfÖoN“Õ%êX §¹Á8R8;jÍÐO –›¨›P÷–önØ–I|C)‡¯¯£°èêÁ*HÜ7ÇmM_å’A? ß8óõÏŸŽã?„q™œ»üB3ÍIq£©¢¯‚ª*Úy©k)j"Y©ªi§C ðOŠVH^'ut`AV!ü]öÝöf¤¸P_+(饩4”¼j§š®å¦©ž*:-S6ZmCdª¨£¡¼6Yª¨ªí÷9Ý¥¨¹ºr6ÅO²-Ò÷C¿¸M#£³'™V„1¢˜gžOÊ"0:³Óœþ­À‡ ‚Éüå RK“”’#¬s)iŠ$ ¨f“ÃWxÄ…Ãa†\ç>lc8+J²2 G8ËIÑœvìr¤¢’ö9ÜG\3áû‡ãCjÔUv«Õ%=U-m4”µtÕ)âAS  +E*I·_I%N6éN@Ò1é‚´æ ë!b¨î6I°ý/-‚Bž…ðcßáÊt!X»èué¸b$Œ “ö¿ËÛŽþƒ¹þ\bGNÊ2=O¦1¶O~߆Ü;µâãHcÜÿ0sõôÏáåÁk&Á®òFGßäsŸ,ñxÄ…ÑœœoßÈŒç#¿!ëÁ2ÀAómØçÓ9ßqòâ(ªò‡”ƒ‘±=ó“¶ÝÿØyðb(Áõbmþg¾Ü \F>O–°Š<*ßZ“/ÒX¶Þd0BäygùyðtEK.0Û¸õFzT“óïòâÒK÷z|D ½+¡í© ùnG|¸9_Ÿ £±%H°öÈ/@?–x07‡'ó!'•¦qO6Ò(•”œŒ&4*r\’rGÙo,b²®Œùc¼Îùõ; JõC üF@¶\Qv©û8>g·pOãÇnÝkÉÓ ã'9ó+€#o^ œGzŒ?È#ñ U÷b@Ø ÎÿqùöïŽ `½ ;c$å_¤÷ê-¸Çòù@ô ›¿Ðl%$2$d&Câ×·¯DŽÎ[íd wßÜùv}8¸oÇãÎá„¢üD°~¼•$1ÝA >Þ½;gƒÑc!Ž$±Î;1}‘åëÜéÄÍ…"0¡Ö^ *”¦pÝC'©I9U“­vêFV[§89ˆÄÌõLRRÐÄD1u©¾TK# €Ì¤t »£c¾8‡7ÅÑÉ5?(qEE]¾ p@CÔävÏôàZâc¥ê`£¤¶7ê_‡9b6‘¾ßâÈ×tPT°Ðö†Ê–Z)bЈß.§`<ˆ ççŒyq#´}JTŸðÏV!|³çf Àψ7oˆ2pç/ɲbÀVDô¯Hb7êÀ#o–=;p¼uõO´’×U9 Ljf’(ÙRд=!À#b2;lÄœ…(=5Û_ƒ·”v¬:>!zŽøX•À ºœãQŸ-ÎxRíª.Õ«H—…E\Êt£¤‚ªYeX)€<8˜‘á(XáQ܉WP’¤¸çw”Xb!ô"ÆNgkš­5™ŽùT,‘@ H‘ Z–£ „¦’¶4ML#*ÁŒ„ §Hh™n ¤Ð–ÛkÉ)náXc…7LH'üØÎsÇžúÂtÅl  o¡ƒîZÐŽöWëý<„ÿkØ™7@YYméASö·.ÈëVN`Кu>!SY/ïØ/ÀÐTJý§ùž±FHéñ\Ò­MD Œ ÿ·²† ðƒ¾ì3³çŸé?³§(a:ÕiWÿ5Iÿ—·Èýd¤?Ù"@ÿ*õ‚%¡ÃîË*üJzIÔu.Û Ûo?´N1·‰W £]œ ;n2 $ ùcËÔ€1Ówâ8šå»-yÂbU ’rÙÏH©é9'aê»ú9ªþ $†ëÁ€0sÕŽÙÜyŸ. .hâ ·Gr:± Ž€¬¤ƒñN@!qœdãýøì8~¥$&Ä祟«99ûG;yNNq´Ì6_ÓEµ öxFj€ÍÑdÄy`p:˜:ú[§îÜp.½RD€®d=L¤’ã {îpÝøÉ¡Ý­vÄÁ¸üB®æ4(»u€:ò3Ô Ž1Ó€?¦ØÏPN!dÊ«DÊáÈ ;TÀß·ãßÓ€˜›ÈR2P ö)j)ZT1IÄž‰`’ºX˜ôÓ^í½JÇ,ñ!ŽFÎp»•aóÎG"ïbH¯zf¬ž‚st F`Î’2 ‚Å“ü,±ÿù‡>d'ÒªT«\éKêô²¥Ä *B¼e&:›}!r%ÍJ~Ù‹ãEÜš+ÿ¼1çJÕ»WÓajíuÕzjðÑa]*­Õ• M1éẨ!Éì*£@qYó>ž‹]hmò¢ªšŽ²5Ç<½ᮤ!±³¼2È ýTÄ…~¡ÂbR¾ÐÏâc€’B¥J Oy¸WF&þÏüĆ¢×hµ¼€UÚ(à¶UÆNDþ‡Fï>\â0’pmeªÂ’1Øœ0{úùðM<vWS˜Ü˜Îê õ¹÷=ˆà'¨#Ò°Xµ5M7Ž- ª¦®V‚¥WÆ+€Ø¯¹&<ç;‘üÆ8ÈX"pÓRNéTŒ:Xô…X0e=9\‘Ü`ã#³l íV"½´¢˜·Ä:Ûu൲î 5I…Š_)ÇK¨'ávóÆßéÛ® ¥¯f:çC§µ4ÌUÔŠÛu+4j „x9Î>·Kqò‚•C@¡Ü=^†­OH°+¥’•Zžg uÅ*·Âñ‘”`s°*Aï€N2q“zž·&dŸ#©:GT€a—>}9ÎÛöØ‚è¦Ì|vëœ4ذôÖ„l'¹=Y¬þ ŽK~˜€‰!‚Bbª½aÒ± ‡pRArzcî]w²šßIN°[¨i¡†ŽV*JdÁ)¨uŠ"$DdžØôÊ”\†!‡ÃÁËØ‡*{CÄT´Ð‡—¬<Ñ„ Òœ£9,ï*ô““º6 ÒwÉ(׳â%)’ÌE[I )¤ÁìF|±Ç8_òôñ)»Çâ!s$Â9%X¡‘’e@úDoø …VWô Ô¶í·{ÇVD^|ªG)UI:—Ãð˜à¤d÷øw9 œéaFÇÕ¡µ|uHU©)IÒΕàΪz£êeYdÏV+d`ï¶F@Ã$•†:¶Bn€ª¬ãøDä(vŒ`öÂ瀥u4ô¤ 6µù‡Ø«ƒàTxÍØP$‹##èxˆPñ‹¤ü œ`‚Ç'ÐùŽûoÁ :pÀäôô•' Žùm±ýoÃ8ÅÁ åŽ1³±ß>ŸŸæxq‰S¡€, ùçÐÇÏõØ…ë(£Â)áwÈò$÷-œàï¶ÿÌwàÕˆQ€“‚><¨ýx$’iø‰ ÉƒÓŽN1¶:s烿¨`7¾~œD°-§§¬FÝ Œ–R¹*v9=ÀÛçÔŒñϘ´P°/Ý™FZ/‰@C•=LW8ìG-É÷fÔõÖèªwüBÐFa Ĩl@ÈÀoS“ñdŒŸ3æ8Q¾1±9 öWË÷'#ŒmœöâʼnŒ¨$‚wúoçøü¶âž¡ÒJôwÛq»dlqëçÄwŠf#[µÇºUðÉ`qÖ¹][N ’½¼÷Á¶8^6wÉv ]YØm‘¾T“ç÷q)ßñ ë“ëº „=(O´~.¢wmˆ]¿Õõ > ¦*ÌXŒßg 1’ m†?ûm¸¸¢+†©¯Ä9†a!²UA€!v`y·o >›p/¼• X䃌Æ+ÜŒ®ïÅëË|@(+»Ònå)'`YdzC3Í#t P¸Ë™07õûø…YcL0fU ]ˆpc¹Îà’NI$·Ï~°‹"œÛÒ Yƒ†?#~€¡\*#ãÀ~þ[mõàjÉ“œ €qŒóŽÇƒbXäl˜›¨A ¡ NO©ß'þ [[¼`h0Çï˜ B©!˜‚Xça¹Ûìç?\ðÇK$sâ;õ:ˆúUR4Sá´jz^zrN>/´•[£?Ä@ZºË\!îÝ<±ÓÀ™U+|@œã= 1ܰ`<,K ¦-¨&3,rV7¸ É$u ”ëÐ|¾9Üòü<¿ÕeömžF?¨´Ù’FñÒ¡Drê¿Ìv¶ÿm›5¿»“9\FG™nØ_˜KN,–èÜ?»[ç™#ÇIV‚¡s¶•±ß¿o> Ô¬±Ä2Ê ;ä§.T<²ÛmØ÷ó/¤ÄUŒÞ•|ïÎZ±mÆ/êþ×µ U2º4åûe oàÑÔò³)ms‚¿]ó¿rNÿ‹Aa,Äe[§p›«9RVQsò$Œqèñç„q_y~ÎZÐŒ×1UE$c¨©K‘ÓƒØà~¶ã²®Z%é!€ØÉƒ?ª’óÆÛðBŒ7·¡Š1üGx†p>0ÌW¨.sß8 ŽùÉìFHá,>8¾#â•Ç`s† €I'|Èàq‰ÜãÇ GÂG#!™IÎä«0lvôÇqߌ"AÎì7=»lÙžäå¿çZHÞ+C–©¯HîUWr:B¸b Ò s¶;䑞ùΗ·^0¤îFK|DK¼ÏlãÏ'Î@å½0ˆ*_3Ç”Ké UÀH¬Öš¸ü^ÌM9u†dÏs”žœ~=À8t¶\ÿ±üÀ¶Ý¶»&¨†A[à)ÌÒÒÔÇ á © ”ä„óÊJ—³v’I¢¬³kÄäSàcb‚-–2‘„ä7"G¡ñö)ÈÞcÛn´VËmDGNj‹|úB´r¤´ô-‡Õ:&•d·ÖÎ*mÁJ¤–»ŠÃJ† d²q±RÔ–ç ¤àƒçŒ7qõë:‚¥*Àr`¤ž.‚“Úcç“é 8®½®ÆœŒ •ÀˆRK`ó·—ë~ J€FNÜä¿Ó~ÛŽ¹o€ÈÕ#Q}¥y?o×6ŠÊ?hWTVÐÉnº(è]7ÌÊhߦ.óH>ͦõJ"°ÜP’Fµ4h²x“/Î?64µïJÞ.š®ÛE%¢ñl¸Ü,ZÞÅ4q»Ð])j^Цz¨Ã£Î‘4@dŠvPÒ?O‡ú’A—=ÐQóIÿÒ¢r#ÕlI×å*R‹€[°åØC¿ø£We’Gv|lY‚(IfP«°^¬àŒl8²I; 3ëòù><†àcÑÄÒœ¹B›;ì¯þ³çÇEÈ`2Ý ôÎmýÀ~'‰žè²À>š”Œ± Žq€z¾}½ŸÏ tç¾Ø¾w—þx„¿±.ÙxB=c=ðsØãý¾|"ùó8¼œ¿_N&#\" ƒúîõ„˜guóÜùãåó8ᾓƒç¶vÁ¶¦>¼,† Œu­±¸Œ>!d•£À†ùÊ’Nr#±íÛ׉-²úRUY›|NÁÎØèù;y|»IºRÇw¦ŒBÎu®Q&®¤¤¼ÁÐåVdÀ™@/ðÔ]Ç×óƒÜ𢧵ܢi²M È:ÀtREo<¡Á=À;ö‚USÑB¿1@8ºu†¿1&Òº¢*±M§nI,Œ¥!·Õxm,”ò±X¡¢¨%£,@‰ÆÃ¨! ˼ܱöz¦›Ró,G -M&›ûBO-·eQ—\V˜¢J¬¿æ‹…M)REÓRˆfÐãÛ€I»€zxåkO•Ž*p))!Œ”§ª(ÉX¢ W • „t… ‘—JrѬÀ•é (•£ðÔt’:b-’Xé‘¶{Žö¾X3ð‡Í€‘…|Ë 0ˆ±.ª‘¨`K†Å|FÝImÇHïÃLµ̰FÏ"•‰Áë!pÇ* `‰×ƒäOIÇŸxœ+äÂ* k„w“DK{Ô3 kFñHÊÈ”ïÑ»Ì@ìF0m=MM#½4Ñ x’*x²3–RÍêÉ Ù·õ %˜o:x ßx/÷…!ßÞ.íú³ugÏ ËðgÓË·ât‡úü¼ Á tÓÔ[çžžã$A'»Ô<²Æ«’Ä9nœ~<"Ïj¸DÑLƒ)–ñ EYÑ•ºåxØÖÇâ^¢pNÏÕ Ðãå®ÀTȸôü6£hÏ$4ÉNÂ)âf›ÞQh‰›t·Pn¡™NãŒeŠa"WGQ‘¢JÆÏX¨¤ô"£á%.23)eÇIê“!Ùë­wÃR@íoF×twûÊ™"£’4•Ò $nÕÈZ–V„•WˆJ$èÒ[§$Ž¥Î‚â¯B޵Í1ô""…\»‹)fr:†)Ž‘’C°•â8vk¦ó—Ä:$† |hÙš•š4ˆÁë~„d•CI’A†\d€p@8¥<ñ¼fT†G*!` Gˆú°ÄäH8ÈÛ†P³gñ ü_~c*J§£a ÿÆÍ†Vê{ßâ{aN~zÛÏf‹N¾Š§Uhu¥´j©ËSH¸†Ù“%™ªP }ÍÎH”)7øË–ñ”I &ªF[ÁgÝ+SøÎ<нXnºvçYe½ÐU[.t2˜j¨ª¢h¦ŠEßœ2Ã+)*êÁ”• –ÁÈÉóÇqé¿oF(YcÒÀ6Ð!<ãðàøÁR;Û;œ€Ÿë<,+‡ã\bŽüáÚ)r¬UL/ÿQbpN1Ø)Îä Ÿ^ BFOaŒïƒ³¿n ,~;b<îIØžý»výc…6ë?ôÆpp3°'ºíÛðâÄqø¦²ˆ0Œ%œ$o$yû;¤0b@P ˜¾p>ø^$ðã°™ˆÉêr7nÃ9=_àÀüE³Æjù$… lTõ¸ÿ.GôáV”ªg ÌØ-ƒñ’vÀÆÏl}1ÅðÁ¾?CvèÁŒ™è êTz«æ{}N}8^%$îI,3ÒÇ¡ƒtnÎÝ[c·˜âpˆ† Â`0ä¹|¶OdÎsôØöà€äᕈûLÙRwÁ=÷Æû¸¾1U×d+Su?Xô€€unßgï<Šñ)ÇÅÒ廃ÕÒ2U±¾Àãç¨âg®y°Ã?qŽ¥J‘• UAeNrJOŲÿÉólªš0K“€X’0sÒHÀì‚2–1òóÕZ=åMԈį,õP«"ˆÀwe`ÅË7f-¶1ð©É`:(UUéÈË`‘æHíվߖ7â.ቋ8 ›ÜBf¥b–¸98y`ù߀<âz¥êÇAÉ ã= Ù'¶Ã~=ýH3’p?$aZ¿¶èz”†~¼(UPÁw%»Òsð°?ÔŽ0G2ÌɱH™€,¬ PvCôÆã:p‹|É} >PT0Ç@@ÆBÍ’HìTtØãÿÕ·—±º°ûÆ[cŒN:HÈÁ`68ÛƒN§´#\5XÎhÂÄò <0=E ЍëTç«ìr22G~;4TòP« UèW@¹f\îX°A$möNüB+Sªw Ô¥Ô•Û'<†Þ[p³²Fèé ìA Üã¹ïŸ®x±B ¤@wTˆvŒuÕ(Y¶Ò- [)V‰*l3eô æêJLz9 éöa”GÛ&bxº&&jqÜ ¢]©îs×iݯhO]ÂÁ4VË›lZ_w‘Pxî ’¬Ñ°=¶¸Ÿ\q ×A,zªÇ­íÃÿ±÷µŠâ}š4K„MѲ™)eRs¹y_ý'y2¡K¨#£Xí&#uä÷a£^arÖ¢ãp®½[g¥K}j‹„#Ò´’Ä%˜… JYêÎ$íűÈMg,´4tµR±Ô- @s— „¢ŸØ=2„>lôò±;îvtªE¬¤ÜýÒ<+ šS:A£P¾öo™’‚÷ËÛ½c´†‚¾ÚM-’¬¨póÑ¢T-¦á2xÖºè麂Ë3qïîÕ°ë =Mtïo¯ŽIí×ËD²,µ6;ý²f¤»Z'‘T Z¸¤ʣè…£¨„´3FÍî>Ÿ´ Fβu+œ£v¼JT“É<#ËíiBU¶r@`Uxr[à {áÒ¾œ\hkhd’Xª–zf–)”MFdŠT Ç(ê%XT€AÛˆþ•Kµ‚ËCmº_f¾ÖQB ’¾¢53V¬lR9jJCDª\ŒeòvÎsîÍÑÍ  Iw÷ƒ5eÎËW§®Ôz”SÓØëh*i.SP!ï4,’¨WS Ëž¨äFFꮌ>|½ ¹•ËígÏOk°\-—k¬özHõl1Ò,¾áGFöú¹kÖÒ4ºÏGGO49Pï6‡ÔÎ}De"Ë(¨´Å¨Žþê;KÇwaËš©“f J––|œ”÷šÙÆ<õךP雄3Òø²X®Ñ{횥‘È©#ÒÍÔ2'ˆJ÷de}‰eX2 ù¾Äg?,ÿ¯œ{ø“ Hº °R³î„XU¦—Ä*ƒ(X9ø†BŒrùo>»íƒžª«ÇŠ2Ä‘¤…C"d'¬HÀœ>ìH róÐ>1b£aå UuÙ`¨Í*û¿R˜D~&K?OL› ä­ß dödŽžª£¨ÌØ‘REĆ …UO²p;33|XÈq /‡Öè€8×Vi#¦•!f–32 ÇLdJdšgÆ |sÂ\z]‹)‘á…¤ }áˆn´‚5Î@ wÀ'rxSŸŸ vA€voñÛxÎÌå)±,PÊARÇ='¤c#8Ûm¶ãœPfB{à.?´1ЪÉlˆÈ¢Bô‘3—‹°èÃ1o´G‘ÿŸ1éÒ€Õ¨„Èȃ’3Øî brÛÉÎýø!R^¸úABÉödùx˜ù|vôß„Ø?'8ù}ÜWõpH£íç € {€vO/’ðd@u‡÷ÿaøpc>Â&c·Ò R|5ßüê>ï?;ž•Üì û÷‡aøqq_´vA°ý¨þhùùýžþ¼8 2HõÈÉì8‘Y'³Ì@#üY‡—Æ>àØðà:ÀªÀ2@؈zg‰ ê×?hmUS°"ä (H,³öÇ׌МÏâÓ=üᣬ„P… –ëê$düÉïÂVÄF™ú•OOƒÓ•§«%ºr6É?N.&c·ÒØ‘ P~’a|†Êv[“øðµ1>,£;gòÆcÛyüx,»=b ì?ÄaÛÈ2>˜'ƒPŸ÷?dyŸ0ÙþC†' n”â#¶w˦Á“u±Ül?£øS+±ñ*7˜¸ùñXSB/öòø…˜Ÿâî~Þ{ù–|ž-´U÷n^Ž‘…ŠV…™ðÀy6×:úä››¸›_ÿE:=oÒÿÞ[ÿÿWÿ©•æ·øµ…׫âþ÷J7ßao£oä?F€:{`cüLvúøq龜ÿÐ…–Ïÿé"8ÛSÿIíý¼ïÿQQܪ¡_ £¿`™?̟džŠÍãõ?ÈñÛð¢9‡í¾b;$˜['8ØgÈté¿ àˆÏT{ÿÏóùpàÅS/h¯Ü;= 7Üw>(=ðP’3é’xN =ÎcŸSŸ< 9õÎÿ^q0y'³Ò:¥ÞHÁÜ·pr휃߅Ø„8Éß;HToôÛéÄŽq\wzÉePǨ\¸8ÏnÃðá®^ì|úÀÏž:Øc?@?,à5…œµ™‡+&åL 82•#'}ÒSÒG¦@8õHãÞ H§u÷ІéòêèfêÇúº€9õy=µÿ¨ægÿê““eÿ棊§ôælÄ·.u’1,‹UHê„åC˜¨˜°S°n¥SžùP|¸j/âr›N»ümÚEŸâhÔËyQŽê¸UØmðN= $ 9åŸù£Ê¸ ºOH·’ú"ÎÎK°· Ǩô¤’".O@@6â¬å‰)Ì DˆJ!·Á!U%TÈ.T¨Ø¸Ieï‰Xvc–¬žšÇ_éò¡öÌíôNù=4É ),ŠRx »)FøRàü-7íÇ<÷¥¦¢çw6©(éत¦æ±†š–šà§§†-A\‘C(X¢TPT8ݶëd±ãÿ/ÀîŒÛ7ÿ:´ÿ”xœû"UÕQûFrÙé*j)^K•ži i"kÉš'h˜Œ²©*v%FÛqõçË9$ÊæBGÔhþTݧ­º'ºUSêš ›”ÉœIp’†Õk†I›2QЕö«0#ì6õý!Âiþ!X]¼¾ÎŸRKc‡°ƒ9 ¾D$ßi~ïçÁ Üòÿ\.œ{¼ÄWôñÌC}Gþçÿ!?¯×†äûGéþÜ AiòŒŸì!ó dùÏ~ u‡sÅ;GœA‡w¤ ßlþw_nÿº?ýß’y18Ž^‚;—ü¿_ê8õ?ØæŠŒrèUŠJaUQv¹G=H‚!Q:Sx&˜'T‰wè H^³ÓŒžª³ÕÈ‚ðö³3Vw$–@’XŠ@'p:@AŽ$á†N† g`¢(ÈP<—;ã·1<=„8þîGÈA3îò6P‰°ßæÂÎÇËp?"jÌúr©™Ù,ÌK!A‰;œ“äçOX•ÙÚ•U" ¡G@8“O·ŸS1ú±>|HmнR6Plb@>C<)T zEŒ»?醇Zé–@$^ý.Œ‰0Ðøpú¨Š¤ª*•:J¨=@õtàmŸ>¯½²¤ ¾ãéIñeÜÿˆþgýGŽpØ`…#ÿÙmrcal-2.4.1/test/data/solvepnp-ultrawide-focal-too-long.pickle000066400000000000000000000167031456301662300243740ustar00rootroot00000000000000€•¸(Œnumpy.core.multiarray”Œ _reconstruct”“”Œnumpy”Œndarray”“”K…”Cb”‡”R”(KKK†”hŒdtype”“”Œi4”‰ˆ‡”R”(KŒ<”NNNJÿÿÿÿJÿÿÿÿKt”b‰C”t”bhhK…”h‡”R”(K(KK K Kt”h Œf8”‰ˆ‡”R”(KhNNNJÿÿÿÿJÿÿÿÿKt”b‰B ¬Zd«l@!°rh‘ Š@ð?ð§ÆK71n@T㥛ÄÖ‰@ð?Év¾Ÿ×o@ã¥›Ä ‹‰@ð?/Ý$ßp@ú~j¼t9‰@ð?V-²ïq@fffffâˆ@ð?5^ºI *s@“Vƒˆ@ð?33333“t@oƒÀʈ@ð?Ý$•+v@33333±‡@ð?R¸…ëx@Év¾Ÿ<‡@ð?žï§ÆK/z@T㥛ÄÆ@ð?q= ×£ˆk@ö(\Â…‹@ð?'1¬ m@ /Ý$A‹@ð?/Ý$n@ÙÎ÷S‹@ð?ÙÎ÷S1p@\Âõ(Ê@ð?7‰A`å(q@¢E¶óý†Š@ð?¢E¶óýNr@ìQ¸…9Š@ð?= ×£p§s@¨ÆK7‰ä‰@ð?–C‹lç-u@…ëQ¸‹‰@ð?²ï§Æûv@ð§ÆK7+‰@ð?ƒÀÊ¡Ey@‰A`åÐÈ@ð?î|?5^žj@!°rh‘óŒ@ð?×£p= ÷k@®GázÉŒ@ð?33333{m@Ház®™Œ@ð?˜nƒÀ&o@–C‹lçnŒ@ð?\Âõ(†p@î|?5^:Œ@ð?ÓMbX¥q@sh‘í|Œ@ð?î|?5^èr@²ï§ÆÃ‹@ð?´Èv¾Ÿdt@²ï§Æ‹@ð?Zd;ßOv@Ûù~j¼7‹@ð?R¸…ëx@áz®GíŠ@ð?çû©ñÒùi@h‘í|?jŽ@ð?^ºI 7k@T㥛ÄTŽ@ð?¤p= ×»l@#Ûù~j5Ž@ð?;ßO—Vn@åÐ"ÛùŽ@ð?ºI +p@ð§ÆK7ú@ð?q= ×£&q@×£p= Ù@ð?ÍÌÌÌÌhr@V-²±@ð?¬Zd;Ïs@…ëQ¸Œ@ð?‰A`åÐzu@þÔxé&^@ð?Ý$•ow@Ý$•0@ð?= ×£pi@1¬Zä@ð?“Våj@¸…ëQÜ@ð?Zd;ßCl@}?5^ºÕ@ð?d;ßOçm@ìQ¸…Í@ð?øS㥛¸o@/Ý$Ã@ð?¤p= ×ãp@X9´È·@ð?#Ûù~jr@ú~j¼t«@ð?^ºI s@fffff¡@ð?¬Zd;#u@Å °rh“@ð?‰A`åÐw@%•C…@ð?ìQ¸…—i@“Vޱ@ð?B`åÐ"Çj@R¸…k¶@ð? /Ý$.l@j¼t“º@ð?áz®GÉm@B`åÐ"À@ð?fffff¢o@X9´ÈöÆ@ð?= ×£pÕp@-²ïÍ@ð?î|?5^r@Ë¡E¶sÕ@ð?^ºI ss@ü©ñÒMÝ@ð?Õxé&1u@P—n’æ@ð?1¬Zw@sh‘íüð@ð?X9´È¾i@ÇK7‰Ám‘@ð?Zd;ß k@ôýÔxi{‘@ð?q= ×£|l@ü©ñÒÍŠ‘@ð?Ãõ(\n@sh‘íü›‘@ð?Ãõ(\òo@¶óýÔøª‘@ð?é&1¬q@!°rh¾‘@ð?¾Ÿ/Ý@r@°rh‘mÓ‘@ð?øS㥛ªs@V­ê‘@ð?)\ÂõXu@V-²’@ð?ôýÔxéDw@/Ý$†’@ð?•C‹l?j@ßO—î(’@ð?²ï§Æ“k@J +‡?’@ð?d;ßOm@ffffæU’@ð?Ház®¿n@Zd;_o’@ð?/Ý$Sp@øS㥋’@ð?•C‹lkq@ ×£p=©’@ð?¬Zd­r@ÇK7‰AÊ’@ð?¢E¶óý"t@žï§ÆKí’@ð?yé&1Øu@¢E¶ó}“@ð?Ñ"Ûù~Öw@{®Ga>“@ð?¸…ëQ(k@¨ÆK7 Ý’@ð?ü©ñÒMbl@3333³ü’@ð?\Âõ(üm@Ý$•“@ð?d;ßO·o@ +‡@“@ð?j¼t“Úp@)\Âue“@ð?¶óýÔxýq@‡ÙÎ÷‹“@ð?+‡Ù`s@ffff浓@ð? /Ý$Øt@NbX¹æ“@ð?çû©ñÒ•v@L7‰A`”@ð?çû©ñÒ«x@žï§ÆKQ”@ð?!°rh‘l@sh‘íü““@ð?Ý$•ƒm@㥛Ġ·“@ð?Zd;ßO)o@X9´ÈvÝ“@ð?NbX9zp@¤p= ×”@ð?þÔxé&‰q@D‹lçû4”@ð?bX9´Är@T㥛Äe”@ð?'1¬(t@Ï÷Sã%›”@ð?•C‹¾u@ƒÀÊ!Ó”@ð?žï§ÆK‹w@j¼t•@ð?åÐ"Ûù°y@V-²O•@ð?X9´È6n@ð§ÆK7í‰@ð?Âõ(\Ëo@î|?5^£‰@ð?!°rh‘Åp@)\ÂõX‰@ð?‘í|?5Èq@—nƒ‰@ð?Ï÷Sã¥çr@d;ßO¬ˆ@ð?oƒÀÊ-t@¦›Ä °Jˆ@ð?ú~j¼t­u@¸…ëQâ‡@ð?w¾Ÿ/cw@ÇK7‰At‡@ð?}?5^º[y@= ×£pþ†@ð?¶óýÔx«{@`åÐ"Û…†@ð?²ï§Æm@ÍÌÌÌÌU‹@ð?j¼t“Œn@oƒÀÊ‹@ð?-²ïp@‰A`åÐÞŠ@ð?P—n q@Õxé&1™Š@ð?h‘í|?r@‰A`åÐRŠ@ð?+‡ÙPs@¬Zd;Š@ð?²ï§ÆÁt@¾Ÿ/Ý®‰@ð?d;ßO[v@yé&1U‰@ð?ßO—nDx@V-öˆ@ð?oƒÀÊ{z@Ï÷S㥈@ð?ö(\Âl@°rh‘íÄŒ@ð?Ãõ(\zm@ ×£p=žŒ@ð??5^ºIo@•C‹lpŒ@ð?7‰A`ånp@F¶óýÔ?Œ@ð?ÓMbXsq@þÔxé&Œ@ð?NbX9œr@š™™™™Ñ‹@ð?R¸…ëõs@+‡ÙΔ‹@ð?NbX9ˆu@žï§ÆKP‹@ð?ƒÀÊ¡E\w@°rh‘í‹@ð?P—n{y@P—n¾Š@ð?ßO—nzk@˜nƒÀEŽ@ð?oƒÀʽl@bX9´,Ž@ð?ºI +Cn@é&1¬Ž@ð?V-þo@ñ@ð?B`åÐ"ýp@–C‹lçÒ@ð?¨ÆK7‰r@¶óýÔx¯@ð?‹lçû©ms@yé&1‹@ð?J +‡êt@þÔxé&c@ð?\Âõ(¶v@V-²9@ð?h‘í|?Éx@Ï÷S㥠@ð?…ëQ¸ k@5^ºI Á@ð??5^ºITl@ÇK7‰A¸@ð? +‡Õm@ /Ý$²@ð?/Ý$}o@´Èv¾Ÿ©@ð?ÁÊ¡E¶·p@ÓMbX¡@ð?33333Íq@/Ý$—@ð?¢E¶óýs@j¼t“Œ@ð?Õxé&1”t@#Ûù~j‚@ð?V-²Qv@ßO—nx@ð?}?5^ºax@…ëQ¸n@ð?˜nƒÀöj@ð§ÆK· @ð?-²ï3l@yé&1ˆ§@ð?Zd;ß³m@ +‡¬@ð?´Èv¾Ÿfo@áz®G±@ð?‡ÙÎ÷§p@ÁÊ¡E6¹@ð?5^ºI Äq@Âõ(\À@ð?+‡ÙÎs@ÙÎ÷SãÉ@ð?F¶óýÔ€t@ìQ¸…Ó@ð?•C‹l=v@w¾Ÿ¯Þ@ð?T㥛ÄHx@!°rhê@ð?¸…ëQk@/Ý$b‘@ð?žï§ÆKwl@®Gáz”p‘@ð?áz®Gõm@¢E¶ó}~‘@ð?ÓMbX¥o@/Ý$†Ž‘@ð?Ñ"Ûù~Èp@é&1¬¢‘@ð?‘í|?5èq@¾Ÿ/ݵ‘@ð?/Ý$3s@w¾Ÿ¯Ì‘@ð?˜nƒÀ¸t@ /Ý$ä‘@ð?33333yv@T㥛Dÿ‘@ð?ü©ñÒMŒx@q= ×£’@ð?!°rh‘•k@åÐ"Ûù’@ð?V-òl@ìQ¸…5’@ð?€n@ìQ¸L’@ð?®Gáz$p@V-²g’@ð?yé&1&q@%•C„’@ð?/Ý$Mr@ƒÀÊ¡E¤’@ð?‘í|?5žs@-²ï'Ç’@ð?î|?5^(u@F¶óýÔì’@ð?ã¥›Ä úv@ÙÎ÷S“@ð? /Ý$y@V-²B“@ð?NbX9Hl@NbX9×’@ð?¤p= ׿m@®Gáz”ô’@ð?'1¬fo@ªñÒMb“@ð?‰A`åКp@ÁÊ¡E¶:“@ð?‰A`åмq@²ï§F^“@ð?}?5^ºÝr@ +‡–Š“@ð?1¬ZLt@/Ý$·“@ð?}?5^ºÝu@‹lçû©é“@ð?‘í|?5Äw@?5^ºI”@ð? ×£p=æy@V­W”@ð?h‘í|?Mm@Ház.‹“@ð?mçû©ñÖn@yé&1ˆ±“@ð?Ãõ(\Hp@˜nƒ@Ù“@ð?B`åÐ"?q@ ×£p½”@ð?V-\r@B`åТ4”@ð?ÁÊ¡E¶£s@ /ݤf”@ð??5^ºIu@T㥛D”@ð?V-²Áv@ƒÀÊ¡Å×”@ð?ªñÒMbªx@ÁÊ¡E6•@ð?ôýÔxéèz@ôýÔxéY•@ð?T㥛ÄÄo@ÓMbXWŠ@à?ú~j¼t•p@œÄ °rŠ@ð?ªñÒMb`q@L7‰A`Ò‰@à?NbX9Fr@´Èv¾Ÿ‡‰@à?ã¥›Ä Fs@+‡Ù7‰@à?Ãõ(\ft@´Èv¾Ÿâˆ@à?Ûù~j¼´u@Ház®‡ˆ@à?¸…ëQ.w@J +‡#ˆ@à?J +‡àx@Ãõ(\¸‡@à?oƒÀÊÑz@h‘í|?J‡@à?“VÁn@+‡ÙΨ‹@ð?fffffp@fffffx‹@ð?åÐ"ÛùÆp@u“V=‹@ð?'1¬¤q@ +‡‹@à?Å °rh™r@#Ûù~jÄŠ@ð?ÓMbX©s@‹lçû©Š@à? /Ý$Þt@ü©ñÒM5Š@à?sh‘í|Ov@J +‡ã‰@à?×£p= éw@Zd;ßOމ@à?åÐ"ÛùÌy@^ºI 3‰@ð?ÇK7‰Aìm@Év¾Ÿ@ð?V-2o@áz®GÞŒ@ð?é&1¬Np@•C‹l¼Œ@à?çû©ñÒq@D‹lçûŽŒ@à?ÇK7‰Ar@‹lçû©_Œ@ð?Ház®s@+‡Ù/Œ@Ð?‹lçû©?t@d;ßOù‹@à?¢E¶óýšu@j¼t“½‹@à?ÁÊ¡E¶+w@Ë¡E¶ó}‹@à?žï§ÆKùx@¬Zd;=‹@ð?33333Wm@V-²gŽ@ð?33333ƒn@ºI +UŽ@ð?h‘í|?ýo@X9´È<Ž@ð?-²ïÃp@T㥛Ä#Ž@ð?+‡ÙΡq@Âõ(\Ž@à? /Ý$¦r@ö(\Âç@à?š™™™™És@{®GáÈ@à?q= ×£ u@\Âõ(¤@à?D‹lçû›v@¬Zd;@à?X9´Èbx@î|?5^[@ð?¬Zd;m@ö(\ÂË@ð?é&1¬?@[qr°”t”bhhK…”h‡”R”(K(KK K Kt”h Œf8”‰ˆ‡”R”(KhNNNJÿÿÿÿJÿÿÿÿKt”b‰BK)³A&™ûh@¬q6Ód@à?%«êåÅ@°ã¿@_@à?—wJÇ‹@%@7é[@à?9³]¡ŸÔ‘@?ŽæÈÊy\@ð?Ø pA>•@9 Q…?3_@ð?8ÀÌw ˜@Jy­„î›a@ð?Ì †: ‚š@6ÇeÜØc@ð?”í*T‹œ@äÖ¤Û’4f@ð?2*ÁHž@bŸŠvh@ð?j ùœ+ÉŸ@ŽDÁ ¥j@ð?¶×‚Þ›@n@²tÑ©‚@à?ðmú³?L‚@v6äŸYá@à?-—ÎY‡‹@é}ãkÏg|@ð?Zhç4K­‘@Ý”òZIFz@à?ìk]jD÷”@›8¹ßáy@ð? †7Ë¿—@eM.†^x@ð?Dý.l-š@·e¥Ix@ð?™ò!¨Šœ@Y1\€ x@ð?˜iûW¶Ù@“âãr'x@ð?DMôù(XŸ@½ª³ZàYx@ð? ËŸ¯øs@Ýxwd @à?4J—¾Áƒ@®»yªC8‹@ð?óÇ´6MBŒ@¥¼VB·bˆ@à?¤‹MûÇ‘@TªDÙS†@ð?öïúÌYè”@¢`ƔԄ@ð?^+¡»ô’—@œÀtZ7¿ƒ@ð?T;ÃÔ¦Ú™@Bé !ñ‚@ð?™»–¯Ñ›@²ž¬\‚@ð? Ê4šÜƒ@­C9Ñé@ð?à+ºõ*ýž@î<0À™@ð?kÕ® ©bz@.ɻڕ@ð?:3P9×…@½5°U‚½’@à?#÷tu'Š@»ÑÇ|æ@ð?ä…txx’@hwH1ðŽ@ð?ß4}† •@ãpæW¶Œ@ð?j‡¿&›—@¢©ÛøŠ@ð?+2: Y»™@àºbFX–‰@ð?ZGUÔž›@vÞÆfG}ˆ@ð?Õê¯WØÉ€@ tí Øì™@à?N{JÎÉ[ˆ@ué_’ªL—@ð?têÊg4@¶€ÐzØ)•@à?9_콈¢’@CYøúÊl“@ð?H3M‡P•@æ=Τ’@ð?fƒL22©—@w.ŒôRá@ð?Q._x·™@ôÄs¶ â@ð?}\*ö„›@« º¶UŽ@ð?al!ȱ@a7l[ô @ð?È”A%}ž@)²ÖP*ó‹@ð?èÀr„lz„@½7†ž@ð?€aùó‹@´éàG›@ð?ÚV³‹@­/Úbó˜@ð?åÓc[fG“@ï­HL`—@à?D¤¦]lµ•@W>Ëóc•@ð?^‘šÖß—@qZð¢ÿ”@ð?‡ÁüuÌ™@®ÙÊKNå’@ð?Œ¾‚4C›@’w5ï‘@ð?$)éa¸@Ðïû7ÿ‘@ð?j¼t#Xž@¤Æ„˜kj@ð?‡Å¨k͈@;‰ÿ¿ @ð?ÀÐ#FÇ@Fѳ±ž@ð?d²¸ÿx‹‘@R)v4þHœ@ð?ÉWø“@Wíš66š@ð?Ižëû0.–@ÿX«öo˜@ð?‰—§Ó+˜@ÿ#Ó¡“î–@ð?Çdqÿ±ó™@T§Yß¡•@ð?^fØø‹›@D6.æ…”@ð?è¡¶ Ãùœ@Çž=׎“@ð?È$#g‘@ž@}ç%hº’@ð?Ù®ÐÇ{‹@¬„¹½2¢@ð?#ÜdT)7@t¶€Ð’Р@ð?Ò¨ÀɶВ@Û÷¨¿Ž0Ÿ@ð?÷°n¼´”@ýøK‹z @ð?^gEIJ–@§ÔEJ2›@ð?}A øƒ˜@h –Í,”™@ð?BòìR*š@·_>Y!*˜@ð?Œ‰B;§›@æ“Ãuï–@ð?£’:aÿœ@È ~RÛ•@ð?ÉäÔÎ5ž@,ñ€²Iê”@ð?EhæÉžŽ@­¹¬j£@ð?V+~Iu‘@zªCnF¢@ð?Dˆ+w„“@ir1öÛ @ð?ØñÏq•@Œ…!rêŸ@ð?¤¦]L£=—@7‹ #¨@ð? â;žå˜@!°rhá÷›@ð?J¶ºœ2jš@“Ã'h{š@ð?¬pËGÂÌ›@{+™@ð?› ê>P@é~NAþÿ—@ð?æ!S>´4ž@«°à²ø–@ð?xœ¢#9¼@Äê04q¤@ð?1zn¡ ’@<õHƒ $£@ð?â¢Î¬q”@ 'LÅô¡@ð?ºW•í*–@Ð(]ú?ã @ð?žACÿ4È—@Q0c ¶ÚŸ@ð?ø6ýÙ¯K™@·aŸ!ž@ð?µûU€°š@¼ÉoÑI˜œ@ð?×£p= ú›@Õv|ó9›@ð?^»´áð'@¸”óÅÎý™@ð?ƒÜE˜Ò;ž@€&Âfä˜@ð?nÚŒÓãs@"4‚ëJf@à?‡¥ÕU…@»¸ðå`@ð?š™™™ùòŽ@¥]@ð?£x•µý€“@sIÕv¢]@ð?»š<%à–@nOØn`@ð?÷HmB³™@áFÊIÐa@ð?F$ -Ëœ@}%;âc@ð?5#ƒÌž@½Â‚ûf@ð?a2U0úÏŸ@Ð&‡O:Bh@ð?¹4~áU¥ @œÞÅûUj@ð?oëÜv@_\ªÒVÅ‚@ð?ÞT¤ †@l@„¸Ò€@à? iQÿ@\X7ÞÝ…|@ð?¸•^›h“@…ëQ¸Uz@ð?…?Û©–@£9²òy@ð?Mh’X’h™@‡jJ²Qx@ð?ÚSrNÜ»›@Ä]½ŠLúw@ð?¸@e8žÏ@äw@ð?PÅÈ"lŸ@W=`röw@ð?vÄ!r @Ø—qx@ð?g¸Ÿßå{@!u;Û@à?$ñòtއ@‘~û:ð!‹@ð?"O’®Yò@‰ÿ"HQˆ@à?Ó½Nêû“@=FyæE>†@ð?&§åg¥–@гYõù½„@ð?§Y Ý!E™@Äî;†g¥ƒ@ð?J&§vv„›@ê{ Á‘Ô‚@ð??;àºâs@ ¡ã9‚@ð?ŸÊiOÙŸ@×…œ¯É@ð? ~bI @Œi¦{=q@ð?&ßlsã"@jݵßô”@ð?÷ÉQ€¨­‰@]Ot]X ’@ð?¾IÓ` @bNÐ&GË@ð?"8ö ï“@ÝJjÀŽ@ð?(›Ì–@yè»[Y‰Œ@ð?àJvl”F™@ïoÐ^}ÌŠ@ð?sL÷?l›@ùdÅði‰@ð?júì€+H@¾PÀvðNˆ@ð?_#I0æž@…'ôúj‡@ð?EJ³y$( @Å °r­†@ð?:豄@ëÄåxe´™@à?¢ U1U*Œ@Õ h"|—@ð?mâä~Gs‘@'0Ö •@ð?YM×-s”@ßnI(I“@ð?é~Na—@G²”æ‘@ð?R˜÷8sf™@t{IÃÂ@ð?‹vÓl›@Œ‚àñí¦@ð?+‰ìƒì2@\ÆM tŽ@ð?$ –Àž@¸<Ö,ÒŒ@ð?Ø‚Þà@üþ͋Ӽ‹@ð?±‡ö±¢Oˆ@G!ɬ>À@ð?¤U-éÈÎŽ@nÁR]P›@ð?äNé` b’@[&Ãñœ¾˜@ð?«Ð@,[•@c›T4öÓ–@ð? 0,®{—@ÿwD…::•@ð?6æuÄ! ™@”¼:Çâ“@ð?ÿ^  ƒ›@()°†À’@ð?ÍèGÃI/@ m60Ì‘@ð?{/¾hÿ«ž@»B,“ü@ð?@ß,åüŸ@¯–;ƒI@ð?ð…ÉTÁÒ‹@øŒDh”• @ð?þòÉŠq»@³¶)Gkž@ð?*6æu¤\“@Lo.º œ@ð?d[œuÕ@Íùæþ™@ð?¹nJ)ñ—@ö$°9ç?˜@ð?€ÉCé™@ýú!6ØÁ–@ð?—þ%©¬ª›@3¦`Ów•@ð?Áªzù>@PU¡ø^”@ð?yÜ5§ž@b/°­j“@ð?TÈ•zfçŸ@ÏJZñý•’@ð?Ui‹k| @ÓÛŸ‹¢@ð?U…]¤’@i©¼í¨ @ð?7U÷ÈFU”@аáéµéž@ð?ˆ€C¨Â{–@”i4Ïœ@ð?ƒÃ ""t˜@'µoùš@ð?•ï‰Aš@¹q‹ùÙ_™@ð?¯]ÚPà›@Ì °Nú—@ð?‘îçTX@è¼Æ.!Ö@ð?Í®{ «ž@øÅ¥*±•@ð?Òo_îÜŸ@'3ÞVêÁ”@ð?µˆ(&‘@ùŸüÝ9£@ð?E½ŒÒ;“@?ÆÜ æ¡@ð?ö³XФF•@:ȵ @ð?Ûܘžà1—@úcZ›KŸ@ð?´°§Îù˜@»}Vi@ð?äóЧnš@—¬Šps¿›@ð?$šœ@ 7àóóGš@ð? `ãÚ{@œÂJåø˜@ð? +‡»ž@‹y‘Ò—@ð?à¹÷p ÜŸ@†Ë*lVÌ–@ð?v7Ouxw’@rßj=¤@ð?ÃÓ+eY[”@8iÝõ¢@ð?h‘í|¿,–@³z‡Û¡Ë¡@ð? •-ã—@_ÐB&¾ @ð?Þɧdž€™@Y¿™˜>—Ÿ@ð?q¯Ì[ÿš@ósCSVä@ð?¼v¹bœ@‘›á_œ@ð?1znQ¨@í)ö›@ð?ì3g}šÒž@ÙÎ÷³Ë™@ð?¦H¾ØâŸ@gš°ý䲘@ð?eýfb:û{@ØÕä)«™b@ð? CäôuS‰@flèf>Z@ð?gòÍ6Çt‘@À éÓ*&V@ð?ºe‡ø7w•@ž´pY,V@ð?rÝ”òêј@q©J[\—X@ð?ë§ÿ¬éŸ›@?ä-W?E\@ð?±üù¶pû@oH£'@`@ð?ÀïúŸ@mŒð’rb@ð?-ëþ±(× @1$'·Ÿd@ð?§îyž“¡@OÜóüÅf@ð?h”.}'@¦ F%Õ±@ð?²žZ}•"Š@‘¹2¨öð}@ð?å&jiÞ–‘@¾Ý’°}z@ð?Ø)V bk•@lèfàVx@ð?>°ã¿`¤˜@òz0)~w@ð?…™¶…^›@÷‰í®dv@ð?Òäb <¬@¦œ/ö^v@ð?õÚl¬„£Ÿ@rkÒm‰ v@ð?~úëÅ© @¯Ñr v@ð?dçmld¡@Ð+žz$Qv@ð?ɯbã"‚@ÃóR±qË@à?“ÇÓò¶‹@_B‡Wû‰@à?’w’@ž ¸çy4‡@ð?kf-$˜•@±ýdŒ¯.…@ð?–“Púò¥˜@`š¸ƒ@ð?óÈ Ü@›@ª› ¦‚@ð?•ºd{@™g%­˜Û@ð?wiÃaédŸ@Í®{+òG@ð?v§;OÔ… @“å$”>Ù€@ð?•~P'=¡@PÕ逆€@ð?œ…@ü©ñÒM—”@À?eȱõÌ×@‚sF”Æ’@ð?oÅ®’@ðùad7@ð?46<-÷•@QžyY¤@ð?ÓL÷ºÏ˜@ñ Ùu¯w‹@ð?²,˜HE›@™¼f¾Å‰@ð?øúZ—:e@sò"°iˆ@ð?å ZH0=Ÿ@a‹Ý>«W‡@ð?¬<°ój @J(}!dw†@ð?•ÖÿÑ¡@^gETÀ…@ð?aU½ü®Îˆ@ ³ÐÎY™@ð?ôÃá"@õ½†à¨z–@ð?ÌE|'v~“@\-[f”@ð?UN{Jžz–@»}F¶’@ð?Û5!­ñ™@Xf,šX‘@ð?/¡‚se›@Ù“Àæ|;@ð?¾‡KŽkf@#Æb£Ž@ð?og_yP'Ÿ@…Ѭlß@ð?‹¨‰>—X @ýÜД}Û‹@ð?6;R}Ç¡@Æú&×ÊŠ@ð?˜iûW6[Œ@{Ic´. @ð?œ¿ …øj‘@!®œ½ã_š@ð?h<ÄYf”@7á^™ ˜@ð?KÊÝçH—@2U0*9=–@ð?ø8Ó„íy™@ìL¡ó ª”@ð?;¨ÄÅ™›@~«uâbV“@ð?g)YN2{@¾ÙæÆ;’@ð?NšE£$Ÿ@áBÁ­K‘@ð?¥»ëlðM @Æ‚@ð?åD» éô @гYõ9ž@ð?ÊýEAÇ@–Tÿà8 @ð?Œ¹k Y·’@þ Ú«¯¾@ð?¸u:Y•@ïW¾«f›@ð?Ü*ˆþ¾—@ÐCm¦e™@ð?@Û5ë™@Ú¨N­—@ð?A×¾€Žá›@Ú¨N75–@ð?ö²í´… @{ž?mñ”@ð?jLˆ¹¤/Ÿ@%Û“@ð?–˜g%íI @¼!*ë’@ð?7pê<é @Ü M.’@ð?Ö唀8}‘@5³–⦡@ð?kšwœö“@Ü,^4Q @ð?:­Û ÆG–@¾IÓ@Ež@ð?3l”õ{o˜@†¬nõ¬2œ@ð?x_• gš@aNÐdš@ð?Ÿ!³l0œ@KËH½·Ñ˜@ð?‘óþ?Ð@ä„ ão—@ð?”g^«GŸ@ñÆOƒ=–@ð?ΧŽMK @ŒgÐ0•@ð?ó“jŸ¾â @(vŠ¥C”@ð?‚ªÑ‹ö’@EóVÚ¢@ð?þ{ðÚE •@@j'@ð?vP‰ëx.—@™Óe1±a @ð?Íä›m.™@KþÙ¬ž@ð?ÃJUäš@'ƒ£äõÒœ@ð?Úþ••戜@§®|–·-›@ð?j¿µEž@dWZF*º™@ð?@¦µi\dŸ@-^, Ñr˜@ð?ü©ñÒÍU @—nƒ'—@À?ØG§®ìà @ÈBtìL–@ð? ܺûK”@…Îkì’Ý£@ð?KÊÝÇ5–@=™ô团@ð?³_wºs ˜@ÂMF•¡v¡@ð?r¨ß…=Ä™@÷s ò³m @ð?Í®{+‚b›@Ó½Nê+þž@ð?À”áâœ@K‘ʶ]@ð?y:W”Âÿ–@8N ó}\@ð?=`2õRš@<¡×ŸÄÂ]@ð?Ìa÷³@Á¨S@`@ð?Ð)ÈÏÆuŸ@^öëN÷b@ð? ¶ôhb¹ @YŠä+ác@ð?í+ÒC’¡@l{»%9Øe@ð?‹mRÑ€M¢@YRî>G¼g@ð?í‚Á5·Aƒ@0.Ui‹Ê‚@ð?(I×Lž¬@V+~éØ@à?𓙀M“@BzŠ¢|@ð?ØÓí—@mo·$‡³y@ð?nN%°Fš@UgµÀÞ9x@ð?q8ó«úœ@ }°Œ _w@ð?©iCŸ@‡1éï%çv@ð?ñð¤Mš @k=&°v@ð?!?¹np¡@ãÁ»ý®v@ð?Y¥ôL/)¢@3£ gÅv@ð?q:é†@0¼’䙩Ž@à?Cp @dXÅYÀŠ@ð?p”¼:‡Ú“@Ov3Cà‡@ð?o,( Z`—@šë4ÒÃ…@ð?ÖVì/kdš@,µÞ/8„@ð?¦}sÏõœ@ ü¨†½ƒ@ð?¯w¼')Ÿ@= $9‚@ð?§ ?† @жšu¦—@ð?L÷ÉV¡@}x– C@ð?ÝBW" ¢@Ház¿€@ð?hx³Ïh‰@H4¢¤”@ð?)YNBIä@Ä>³P’@ð?U¥-®a™”@«Ñ«Š~@ð?¾D$Õ—@/¤ÃÃ#Ž@ð?Jš?¦Õ¢š@Úå[å‹@ð?¥ ¦ú@.‘ Î`$Š@ð?¦ÒO8 'Ÿ@\wóT罈@ð?ÿ²{ò˜{ @O]ù,/Ÿ‡@ð?Ð)ÈÏVE¡@ÅrK«³†@ð?üÞ¦?Ëõ¡@Ðb)’Oó…@ð?À?¥JTýŒ@8N óNF™@ð?ãSŒ·*’@Šè×Ö·–@ð?}<ôÝz•@ffff† ”@ð?HnMºÝh˜@"o¹úñê’@ð? `­ÚÅüš@Ãc?Kˆ‘@ð?úGߤé>@*ý„³{e@ð?¾¢[¯8Ÿ@ÊnfôcìŽ@ð?¾OU¡)y @Ndæ·_@ð?· ÷Ê”:¡@ðû™Œ@ð?Fë¨jšä¡@IZÖÝúŠ@ð?fÚþ•J@þDeÃÚ:@ð?aEœ~“@Ÿèºðcš@ð?Öp‘{*l–@òÓ¸7oN˜@ð?¡ö[;!™@ëŒï‹ g–@ð?Šcîzk›@OÉ9±'Ò”@ð?^ P:‚@ 6u.}“@ð?xî=\BZŸ@Œ¹k ‰\’@ð?™¹ÀÍ} @ùk¸¨h‘@ð?»ñîÈH6¡@R||Bv˜@ð?YÁoCÜÙ¡@…]Ê@ð?ÔMæ’@Ü M&I @ð?lyåz+Í”@­‡/•á@ð?ú€@ge—@!?¹ÎŒ›@ð?cñ›Â ™@ôiMˆ™@ð?Žg\ã›@­ûÇB´Í—@ð? ÛOÆ(Ñ@*§=%WS–@ð?½VBw‰Ÿ@²õ ᨕ@ð?óåØWˆ @À’«Xüô“@ð?g}Ê1y7¡@ kcì„“@ð?qËGRzÓ¡@½pç¨-’@ð?(š°è›“@/ö^d±¡@ð?>ê¯W( –@"ÇÖ3Ì] @ð?çmlväV˜@»Ó'`ž@ð?N³@»ƒvš@óWyâNœ@ð? 'iþ¨fœ@©„'ô:š@ð?´Yõ¹z*ž@VId„ë˜@à?LK#ÁŸ@Ct¹ˆ—@ð?“V|CI— @˜ø£¨cS–@ð?ïTÀ=ç<¡@ÚâŸéD•@ð?ß3¡iÑ¡@xak¶rV”@ð?'¢_[ÿ•@+3¥õ×ߢ@ð?ƒ0·{i6—@t&m•¡@ð?6ñº®>™@¡drj§k @ð?'ÛÀý%›@ ¦}Þ@ð?µ‹i¦;èœ@XS6çœ@ð?µÝß$†ž@Û¦¶DB›@ð?Iö5þŸ@MK¬œÏ™@ð?]¥»Ãª @çim†˜@ð?L‡N÷E¡@ 5CªH`—@ð?­ÞávàÒ¡@°÷­–\–@ð?¨È!âÖc–@$A¸Šß£@ð?öÑ©I˜@™,î?Ú ¢@ð?‹vÈš@ÍÍ7¢³}¡@ð?ñó߃—Л@Í”Ößu @ð?Zö$°¹i@µRäŸ@ð?të5=ãž@bg ·a@ð?0œk˜1  @økèâ›@ð?¼çÀrä¿ @½¨Ý¯B‰š@ð?Õ%ã©Q¡@'¼§îU™@ð?YŠä+yס@ó;Mf|A˜@ð?Ä[çß®Qh@c¸:âÇx@ð?ÙÎ÷SãŸ|@Ý$•_~@à?Øô  ¼…@HøÞß`ß@ð?ã¥›Ä kŒ@#Ûù~jc„@à?’Z(™Œ-‘@Ȳ`â/³†@ð?ÙÎ÷ÓГ@ ×£p=Öˆ@à?/kb_$–@ PjtŠ@ð?X9´È/˜@‡ÙÎ÷}Œ@à?¼ "5]š@iqÆ0Ž@ð?3#Ež›@Ë/ƒ1”@ð?K[\ã³úc@ª ãn°È‚@ð?‡ÙÎ÷Þ{@3333³C…@ð?¤p= ×õ…@çû©ñÒ¥‡@à?å`6F@cñ›ÂêÙ‰@ð?ƒÀÊ¡©‘@¤p= ×â‹@à?×tB(j”@ãÔ½@ð?`ç¦Í¨Ñ–@è¢!ã`@ð?¾3ÚªÔí˜@PÅÈw@ð?ffffæÍš@ºI +‘@à?ý .RØfœ@ ×ÜAÑ@ð?vü‚ `@”ûŠ¢PŠ@ð?7ûå¶À{@ý\¬(MŒ@ð?«?Â0À‚†@=‚)5Ž@ð?¤p= ׎@ƒÀÊ¡ü@à?æ\Š«ZP’@ZFê=Ñ@ð?‹lçû))•@Ë¡E¶sŽ‘@à?~b¼æ —@_#I0<’@ð?¶óýÔx™@3333³Ó’@à?œà›¦_Ÿ›@ô¦"æ`“@ð?¨ã1%B@¨ã1%Ö“@ð?_&ŠU^@Ô{*—”‘@ð?Â1Ëžš|@øTN{ê3’@ð?ëW:þ‚‡@OË\õÔ’@ð?IØ·“èx@p"úµ%m“@ð?h‘í|?&“@-²où“@à?ŒÊÂÇ–@ërJ@l~”@ð?<0€ðÁŽ˜@h!£ ú”@ð?2•ñ¿¸š@„ºH¡Ü^•@ð?^-w–”œ@Õ[[e»•@ð?/ž@ò ¯$é–@ð?.äÜÈ­`@ðH€¼–@ð?Þ Š_Ò~@c_²ñÙ–@ð?€)t‰@ðMÓg—@ð?ÈÏF®;³@*Æù+9—@ð?o×KSô1”@nÝÍÓq—@ð?µpY…(—@Ȩp$§—@ð?Hþ`àÉ©™@28J^­Ü—@ð?mçû©qÍ›@ªñÒMb˜@à?×3„cF @¡J];˜@ð?‡ÙÎw2Ÿ@F¶óýTg˜@à?Šºý¼f@h³ês£œ@ð?L÷w@N·ì_œ@ð?)ZÜ“@„, &þ’N@ð?IŸVaP–@‰'»™Ñ²Q@ð?SÎ{¿R˜@P@¿ïtT@ð?ÛL…xþ™@ýñÖù\W@ð?ó=#jf›@ ²º2Z@ð?§@fg™œ@”ûŠØ\@ð?6WÍsÄ{b@ak¶ò2݃@à?ï9°!@ºòY€@à?;pΈcˆ@F”öŸ8{@ð?,bØaL—@¹Qd­!x@ð?6\äž>¿’@’"‹4ïu@ð?6ŽXû,•@ËMÔÒœŽt@ð?Ü 1—@)Ì{œé–s@ð?G«ZÒ¡ã˜@ÃbÔµöír@ð?<¾½kðSš@o~ÃDÃ{r@ð?· 8K‘›@e‰Î2‹(r@ð?³±ó,Si@37߈>Â@à?åòÒ¯|@˜PÁá¥7Œ@ð?Wya§¹‡@šD½àseˆ@à?‰˜I”\Ž@,Õü˜…@ð? q¬‹‹ú‘@üª\¨œƒ@à?Zœ1ÌyO”@y­„îRö@ð?3l”õËH–@qqTn¢½€@ð?kò”Õù—@ÅÈ’y›@ð?sL÷j™@|G q~@ð?rúz¾Ö©š@ïb€Då|@ð?—Îù)Àq@G¬Å§o–@ð?>{.SóÛ€@t&mÚ[“@à?‰ìƒ,Ë·@µÿÖ ü@ð?º¼9\K×@„Iññ)PŽ@à?†[Ï0z‘@!Ë‚‰¿n‹@ð?k'JB²“@ÖT¥*‰@à? §Ì–•@Ñ O!X‡@ð?÷”œ;9—@aãúw}Û…@ð?z¦—{¦˜@Á8¸t¤„@ð?6<½²ã™@™Ö¦±ý ƒ@ð?tÓfœ†~w@UMu¿›@à?Ѳî«j‚@Úã…tøË—@ð?­mÎqˆ@ƒ0ê+•@à?øU¹PÙÅ@'Ø+ “@ð?c('ÚÅ:‘@s¹ÁPwR‘@à?}<ôÝÝE“@©¿^aaÕ@ð?˜Þþ\t•@÷"ÚŽ©@ð?©¦ïÅ£–@}”—‹@ð?Œ†ŒGé˜@fgÑ;µú‰@ð?¨Œ<™@K®bñ›•ˆ@ð?Q§“lA}@Q/ø4·Óž@ð? ë©Õ×:„@‹‹£r㆛@à?D¢Ð²`‰@kævïŘ@ð?ÞXPŽ@–±¡ûz–@à?аáé%‘@ðÂÖlµ”@ð?`·îÖ“@vnÚŒCô’@ð?ÜœJÀ³”@á_ž‘@ð?‚É"{0–@;7mÆIy@ð? ‰´‚—@7n1?7ÿŽ@ð?ê’qŒÔ¯˜@¥ ÛK:Q@ð?³A&Y@“o¶¹¹ñ @ð?ªôÎ †@2ZGU“§ž@ð?ŠZš[¡~Š@¤Q“MÞ›@ð?)_ÐB¢›Ž@Z/†rB~™@ð?¥iP4ÿ3‘@TŸüw—@à?Ï, Pè’@ÃÔ–:¨»•@ð?lŽËv”@‘`ª™E@”@ð?´WÚ•@˜Në÷’@ð?Ä$\x—@Ô¶aäÛ‘@ð?4 ~<˜@ô7¡1ã@ð?š¯’O߃@¤P¾¾3¢@ð?¬Så{¦Ø‡@Veß9£ @à?½LŠ/®‹@á™Ð$‘†ž@ð?i㈵¸K@J Áªªœ@à?é Œ¼lR‘@µüÀU^ š@ð?¢CàHã’@‘Gp#E=˜@à?¨§À?P”@̛õ¥–@ð?bØaLÊ•@:d¯·D•@à?¼W­LXÌ–@Ã×׺”@ð?€Þ—@m6Vbžý’@ð?¡cu(†@\èJò<£@ð?,cC7[މ@çoB!R¾¡@ð?i‚§°àŒ@ë8Îg @à?ް¨ˆC@ˆ½PÀönž@ð?òêB‰‘@ä‡J#ÖUœ@à?*嵺ð’@-σ»Syš@ð?~þ{ðê?”@G¢`vÔ˜@à?™ Çóér•@‚”0b—@ð?”í*Ž–@»¶·[B–@ð?ÜõÒA”—@®I·%Ró”@ð?kÕ® ‰3ˆ@É w.¤@ð?¼Î†ü³"‹@&ŒfÝ­¢@ð? <÷NŽ@ÙÎ÷S[c¡@ð?0EH l@óqm¨@9 @à?8×0C£À‘@x&4Il]ž@ð?O•ïy “@|F"4ò|œ@à?‹ mµ<”@åîs|¤Ñš@ð?Û¦¶dY•@G ^×ÿR™@à?åCêc–@¿Òùðû—@ð?ØÖOÿYY—@}w+K„È–@ð?MöÏÓƒt@¤ng_ùÇ`@à?¼×’@ð?A¶,_7.—@ÕyTü¯‰‘@ð?b»{€>¤˜@«\¨ü n@ð?{k`«Tñ™@z3jÞòŽ@ð?Ù=yXè›@¸! ?Q@ð?%•#X†@Òq5²‹¦ @à?Ö8›Ž@‹@n†ðÉ-ž@ð?BµÁ‰ƒ@œ‹¿íé~›@à?B@¾4Α@’®™|33™@ð?iQŸ4®“@Ïù)Ž£;—@ð?þíÑkb•@ªžÌ?jŽ•@ð?ï!¸ê–@ÌE|'f”@ð?èú>TJ˜@³_wºcà’@ð?À^aÁ]†™@¼s(CË‘@ð?Óø…W¤š@£èqÚ@ð?an÷R¯ˆ@x—‹ø®ã¡@ð?„º„ƒ¸Œ@«%åHa @à?mò–ûI@PáRÙž@ð?§Z #’@·î橾ɛ@ð? Œ¼¬ÉÈ“@És}^Å™@ð?Ð&‡OêU•@M-[ë˜@à?a³é˜¾–@\uªéx–@ð?îyþ´Ñ˜@OÏ»±€"•@ð?VñFæñ2™@q $ ˆõ“@ð?§X5cEš@Ù$?âgì’@ð?§±½”Њ@¼çÀrdê¢@ð?¶y˵FŽ@é™^btx¡@ð?ÉÎ@(š°ð- @ð?=šêÉœk’@-xÑWÐ ž@ð?aˆœ¾Îï“@À“.Kœ@à?öz÷Ç[X•@¡×ŸÄw8š@ð?õ‚O#¦–@%êŸf¡˜@à?Þs`9"Ù—@ì3g}Ú6—@ð?äg#×ò˜@œá|žö•@à?ó;Mfìô™@£¬ßLìÙ”@ð?ØžY€·Œ@"—ÞÅ£@ð?E¹‡º@¬ä¦e¢@ð?B žB.V‘@–¬%¡@ð?9µ3L-È’@Z ‰{œ @à?Ë2 ”@•~Pž@ð?›s´i•@)—Æ/5œ@à?º„CŸ›–@-'¡ô哚@ð?}<ôÝݵ—@È%Ž< !™@ð?Á‹¾‚TÁ˜@ä¢ZDDÒ—@ð?wLÝ•¶™@éî:"¥–@à?#¯ë—s@ÍÌÌÌÌ i@ð?|¶Ö)…@Ä ·|¤ïm@ð??ŽæÈZ@üdwr@ð?ZKio5•@~åAz ²v@ð?þ›'NÌ™@ 3fL{@ð?³Óê’Ù@â#bJdþ@ð?cÕ Ì¥¯ @Ã}äÖdM‚@ð? m5ëd5¢@$A¸"}„@ð?øq4G^„£@<¢B5††@ð?qè-¤¤@vR_–Ö^ˆ@ð?æÌv…¾îj@ñ[šÙ@ð?Z~à*ÏÔ‚@ØœƒgâO‚@ð?¤©žÌ¿cŽ@ësµÛSƒ@ð? 8„*Eˆ”@#1ì0¼„@ð?!£ËR™@½VBw _†@ð?“°«Y‡@Lûæþ*ˆ@ð?Ýê9éå• @B’YÖ‰@ð?éEí~m&¢@«?Â0à‹@ð?ðPèS|£@­mŠÇÅ @ð?¾öÌ’0¡¤@4óäšuŽ@ð?X9´Èöác@lZ)»Ž@à?ÀuÅŒð\@ç¦Í8íZŽ@ð?–{Y!@@àºbFX|Ž@ð?¶.5B?”@ÐGq¡ @ð?ã¤0ï1 ™@qUÙwEÛ@ð?J ÁªjY@&4I,9j@ð?þaKž‰ @É­I·uï@ð?|Cá³!¢@À’«Xr‘@ð?¬‹Ûhh{£@WBwI¼ñ‘@ð?tÒûÆÏ¢¤@É;‡Rg’@ð?+0du«€b@'g(îˆ?–@à?Œõ L @;ŪAX›•@ð?‡6Ð@F&à×(4•@ð?¨68½ ”@ƒ§:ÿ”@ð?uäHg0™@ù¼â©—ð”@ð?–è,³È[@'l?ƒ•@à?á+ÙÁŒ @W[±¿!•@ð?a³é&¢@±‹¢ÎL•@ð?àŸR%z£@^ÖÄz•@ð?y=˜﨤@íÕÇC?©•@ð?}=_³Übg@Ø—?@ð?Ì_!s…‚@´<î.-œ@ð?ÔMvÆ@<0€ðÁK›@ð?;Ç€ì…X”@'†§‡™š@à?…bÙ<@™@6X8I“š@à?=_³\öŒ@µ¥òz­™@ð?å™—ÃV¡ @oÅ?h™@ð?¬äcw15¢@-—Îi4™@ð?Îú”cú£@%;6Ñ™@ð?É!âæ\²¤@³Z÷˜@ð?ÇÕÈ®ô.q@5Ó½Nªÿ¡@ð?h]£åÀF„@äK¨èG¡@ð?c ¬ã؉@[{Ÿªj  @ð?:è•@f¼­ôR  @à? pz™@œ1Ì úŸ@à?¦´þ–`î@u‘B‰Nž@ð?b¢A ¾Ä @Ø-cý @ð?O ìKP¢@]¢z‹@ð?»š<…¡£@ÓôÙžœ@ð? \âÁ¤@¼·_Ž<œ@ð?¼é–"y@–íCÞb¥@à?Ô|•|,ˆ‡@e©9¤@ð?+Lßk(‘@¹nJy f£@ð?¯w¼Ç–@Ïkì壢@ð?;TS’š@á ½þ õ¡@à?8L4Hqyž@Ò«J³]¡@ð?ž•´â³÷ @oe‰ÎbÚ @ð?Å=–>|t¢@Âl ki @ð?—qS#»£@°÷­&  @ð?bøˆ˜Ó¤@-î?2oŸ@ð?-¯\oû=@˜Ÿ˜Ð§@ð?B_zûSn‹@»(zàÓÖ¦@ð?31]ˆe¡’@Dù‚ªâ¥@ð?)&o€©9—@±ˆa‡Áü¤@à?…Ì•1h›@ÞWåB­)¤@ð?ÏÛØìH#Ÿ@ÿ°¥—k£@ð?5²+-»4¡@Ô›Q‹Ã¢@ð?•Öß ¢@î—OV¬0¢@ð?Ë€³”´Ù£@Ö‹mÚ°¡@ð?Ïù)Žãç¤@"ýöuðA¡@ð?œR^+!D†@`®E @!ª@ð?ÇG‹3¢@-@Ûj¦©@ð?„œ÷ÿaQ”@9ïÿs¨@ð?ý.lÍ¶Š˜@d=µb§@ð?&§v† hœ@¯Î1 £"¦@à?*ß3BáŸ@¾Ü'G¹I¥@ð?μ¯2y¡@Mž²šž†¤@ð?Øb·ÏúТ@¡†oaØ£@ð?]ÀË ëû£@#…²ðå=£@ð?t È^÷ÿ¤@#žìf®¶¢@ð?Z¹˜uI‹@%Ί¨ ¬@ð?n¿|²Bë‘@pwÖnƒúª@ð?KÔÔ–@ë8~ˆç©@ð?—qS}â™@ ×£p}ܨ@ð?`êçMup@>—©IÀß§@ð?üà|êS @Ëe>õ¦@ð?ÎQÚCÁ¡@`º2¦@ð?„};!£@÷Ì’]\¥@ð?Ìyƾô ¤@!seP]®¤@ð?£N¥@Ús™š¤¤@ð?”t”bG?³¶E¡ÊÀƒ]”ŒLENSMODEL_STEREOGRAPHIC”hhK…”h‡”R”(KK…”h‰C š@š@§@^Ÿ@”t”b†”at”.mrcal-2.4.1/test/data/synthetic-board-observations.vnl000066400000000000000000000602001456301662300230440ustar00rootroot00000000000000## generated on 2020-04-22 00:14:48 with analyses/synthetic_data/make-synthetic-data.py --relative-extrinsics --Nframes 3 --observed-pixel-uncertainty 0.3 --object-spacing 0.1 --object-width-n 10 --at-xyz-rpydeg 0 0 2 0 0 0 --noiseradius-xyz-rpydeg 1 1 1 40 40 40 test/data/cam0.opencv8.cameramodel test/data/cam1.opencv8.cameramodel --reported-level -2 # filename x y level frame000000-cam0.xxx 1009.558 1190.205 1 frame000000-cam0.xxx 1095.337 1208.062 0 frame000000-cam0.xxx 1178.470 1226.291 0 frame000000-cam0.xxx 1257.580 1243.112 0 frame000000-cam0.xxx 1334.105 1259.585 1 frame000000-cam0.xxx 1407.417 1275.753 1 frame000000-cam0.xxx 1478.849 1291.551 1 frame000000-cam0.xxx 1547.901 1306.018 0 frame000000-cam0.xxx 1614.314 1320.539 2 frame000000-cam0.xxx 1678.716 1334.702 1 frame000000-cam0.xxx 985.369 1266.027 2 frame000000-cam0.xxx 1072.900 1282.503 1 frame000000-cam0.xxx 1158.429 1299.469 2 frame000000-cam0.xxx 1239.102 1315.999 0 frame000000-cam0.xxx 1317.535 1330.289 1 frame000000-cam0.xxx 1392.939 1346.050 2 frame000000-cam0.xxx 1465.688 1360.738 2 frame000000-cam0.xxx 1535.865 1374.478 1 frame000000-cam0.xxx 1603.901 1387.896 0 frame000000-cam0.xxx 1669.592 1400.628 2 frame000000-cam0.xxx 959.058 1344.106 1 frame000000-cam0.xxx 1050.656 1359.944 1 frame000000-cam0.xxx 1137.446 1375.215 1 frame000000-cam0.xxx 1220.766 1389.967 0 frame000000-cam0.xxx 1300.634 1405.060 2 frame000000-cam0.xxx 1377.565 1418.234 0 frame000000-cam0.xxx 1452.323 1431.364 0 frame000000-cam0.xxx 1523.585 1445.193 0 frame000000-cam0.xxx 1592.125 1457.635 1 frame000000-cam0.xxx 1659.615 1469.364 0 frame000000-cam0.xxx 932.768 1425.714 1 frame000000-cam0.xxx 1026.420 1440.187 1 frame000000-cam0.xxx 1115.048 1454.266 2 frame000000-cam0.xxx 1200.693 1468.106 1 frame000000-cam0.xxx 1282.512 1481.501 0 frame000000-cam0.xxx 1361.619 1493.512 2 frame000000-cam0.xxx 1436.916 1506.091 1 frame000000-cam0.xxx 1510.210 1517.450 0 frame000000-cam0.xxx 1581.673 1528.589 2 frame000000-cam0.xxx 1649.716 1540.535 1 frame000000-cam0.xxx 904.253 1511.154 0 frame000000-cam0.xxx 1000.716 1523.804 0 frame000000-cam0.xxx 1092.330 1536.267 0 frame000000-cam0.xxx 1180.078 1548.649 2 frame000000-cam0.xxx 1264.644 1559.945 0 frame000000-cam0.xxx 1345.231 1571.051 1 frame000000-cam0.xxx 1422.135 1583.225 2 frame000000-cam0.xxx 1496.758 1593.568 2 frame000000-cam0.xxx 1569.496 1603.690 1 frame000000-cam0.xxx 1639.254 1613.728 0 frame000000-cam0.xxx 874.759 1600.840 1 frame000000-cam0.xxx 973.477 1611.369 1 frame000000-cam0.xxx 1068.755 1622.648 1 frame000000-cam0.xxx 1159.045 1632.244 2 frame000000-cam0.xxx 1245.029 1642.387 2 frame000000-cam0.xxx 1327.658 1652.493 1 frame000000-cam0.xxx 1407.459 1662.058 0 frame000000-cam0.xxx 1483.409 1671.359 2 frame000000-cam0.xxx 1556.784 1680.540 2 frame000000-cam0.xxx 1628.498 1689.836 1 frame000000-cam0.xxx 842.334 1693.986 0 frame000000-cam0.xxx 945.504 1702.935 0 frame000000-cam0.xxx 1042.362 1711.563 1 frame000000-cam0.xxx 1136.058 1720.051 0 frame000000-cam0.xxx 1224.179 1728.328 2 frame000000-cam0.xxx 1309.646 1736.693 2 frame000000-cam0.xxx 1391.321 1745.185 1 frame000000-cam0.xxx 1469.032 1752.792 2 frame000000-cam0.xxx 1544.159 1760.744 2 frame000000-cam0.xxx 1617.292 1767.872 1 frame000000-cam0.xxx 808.234 1792.547 0 frame000000-cam0.xxx 914.844 1799.579 0 frame000000-cam0.xxx 1016.053 1805.723 2 frame000000-cam0.xxx 1111.899 1812.541 1 frame000000-cam0.xxx 1203.228 1818.747 0 frame000000-cam0.xxx 1290.039 1824.751 0 frame000000-cam0.xxx 1373.721 1831.342 1 frame000000-cam0.xxx 1454.174 1837.852 1 frame000000-cam0.xxx 1530.363 1843.249 2 frame000000-cam0.xxx 1604.729 1849.715 0 frame000000-cam0.xxx 772.456 1896.794 2 frame000000-cam0.xxx 883.346 1900.434 0 frame000000-cam0.xxx 986.808 1904.629 0 frame000000-cam0.xxx 1086.190 1907.602 1 frame000000-cam0.xxx 1179.841 1912.197 1 frame000000-cam0.xxx 1269.907 1916.600 1 frame000000-cam0.xxx 1355.521 1921.089 1 frame000000-cam0.xxx 1438.327 1925.863 0 frame000000-cam0.xxx 1516.742 1929.979 2 frame000000-cam0.xxx 1592.444 1934.846 1 frame000000-cam0.xxx 733.051 2007.337 2 frame000000-cam0.xxx 848.355 2007.470 0 frame000000-cam0.xxx 956.137 2008.087 0 frame000000-cam0.xxx 1058.646 2009.763 1 frame000000-cam0.xxx 1155.529 2011.281 1 frame000000-cam0.xxx 1248.500 2012.883 1 frame000000-cam0.xxx 1336.766 2015.466 0 frame000000-cam0.xxx 1421.352 2017.576 0 frame000000-cam0.xxx 1502.343 2020.745 2 frame000000-cam0.xxx 1579.606 2022.780 2 frame000000-cam1.xxx 3256.363 522.958 0 frame000000-cam1.xxx 3317.237 540.190 1 frame000000-cam1.xxx 3377.420 556.513 1 frame000000-cam1.xxx 3438.953 572.574 0 frame000000-cam1.xxx 3499.718 588.983 2 frame000000-cam1.xxx 3562.598 605.377 2 frame000000-cam1.xxx 3624.127 621.062 2 frame000000-cam1.xxx 3686.002 637.023 1 frame000000-cam1.xxx 3748.189 652.539 2 frame000000-cam1.xxx 3811.652 667.543 2 frame000000-cam1.xxx 3248.793 582.842 0 frame000000-cam1.xxx 3308.991 599.593 1 frame000000-cam1.xxx 3371.003 616.384 2 frame000000-cam1.xxx 3431.651 631.952 2 frame000000-cam1.xxx 3494.121 648.777 2 frame000000-cam1.xxx 3555.997 664.471 0 frame000000-cam1.xxx 3618.102 680.777 1 frame000000-cam1.xxx 3681.201 696.051 1 frame000000-cam1.xxx 3743.807 712.353 2 frame000000-cam1.xxx 3807.464 727.839 1 frame000000-cam1.xxx 3242.234 643.322 2 frame000000-cam1.xxx 3302.947 659.271 1 frame000000-cam1.xxx 3364.229 676.462 1 frame000000-cam1.xxx 3426.314 692.711 2 frame000000-cam1.xxx 3487.919 709.180 2 frame000000-cam1.xxx 3550.121 725.143 2 frame000000-cam1.xxx 3613.075 741.590 0 frame000000-cam1.xxx 3675.547 756.624 0 frame000000-cam1.xxx 3739.458 772.865 2 frame000000-cam1.xxx 3802.752 788.760 0 frame000000-cam1.xxx 3234.795 703.829 2 frame000000-cam1.xxx 3296.272 719.974 1 frame000000-cam1.xxx 3357.601 737.149 0 frame000000-cam1.xxx 3420.291 753.275 2 frame000000-cam1.xxx 3482.214 769.773 1 frame000000-cam1.xxx 3545.038 785.897 1 frame000000-cam1.xxx 3607.926 801.994 0 frame000000-cam1.xxx 3670.883 817.460 2 frame000000-cam1.xxx 3735.085 833.778 2 frame000000-cam1.xxx 3799.786 850.025 1 frame000000-cam1.xxx 3228.188 765.077 0 frame000000-cam1.xxx 3289.661 782.696 2 frame000000-cam1.xxx 3351.887 798.623 2 frame000000-cam1.xxx 3414.231 815.043 1 frame000000-cam1.xxx 3476.584 831.839 0 frame000000-cam1.xxx 3540.118 846.452 1 frame000000-cam1.xxx 3603.207 863.613 2 frame000000-cam1.xxx 3667.016 879.385 2 frame000000-cam1.xxx 3731.522 895.759 0 frame000000-cam1.xxx 3795.815 911.987 0 frame000000-cam1.xxx 3220.942 827.656 1 frame000000-cam1.xxx 3283.768 844.398 0 frame000000-cam1.xxx 3346.222 861.032 0 frame000000-cam1.xxx 3408.305 877.052 0 frame000000-cam1.xxx 3470.809 892.940 0 frame000000-cam1.xxx 3534.686 910.359 0 frame000000-cam1.xxx 3598.286 925.811 0 frame000000-cam1.xxx 3662.489 942.495 1 frame000000-cam1.xxx 3727.044 958.499 2 frame000000-cam1.xxx 3792.542 974.369 1 frame000000-cam1.xxx 3214.405 889.663 0 frame000000-cam1.xxx 3277.184 906.822 2 frame000000-cam1.xxx 3339.929 923.528 0 frame000000-cam1.xxx 3402.829 940.106 1 frame000000-cam1.xxx 3466.407 956.774 1 frame000000-cam1.xxx 3529.776 973.359 1 frame000000-cam1.xxx 3593.941 989.363 1 frame000000-cam1.xxx 3658.417 1005.657 0 frame000000-cam1.xxx 3723.191 1022.048 1 frame000000-cam1.xxx 3789.210 1038.475 2 frame000000-cam1.xxx 3207.281 954.047 0 frame000000-cam1.xxx 3270.245 970.670 1 frame000000-cam1.xxx 3333.783 987.770 0 frame000000-cam1.xxx 3397.316 1003.377 1 frame000000-cam1.xxx 3460.954 1020.857 2 frame000000-cam1.xxx 3525.176 1036.975 1 frame000000-cam1.xxx 3589.885 1053.588 1 frame000000-cam1.xxx 3654.990 1069.689 0 frame000000-cam1.xxx 3720.327 1086.190 2 frame000000-cam1.xxx 3786.532 1102.764 2 frame000000-cam1.xxx 3200.578 1018.636 1 frame000000-cam1.xxx 3264.327 1035.591 0 frame000000-cam1.xxx 3328.562 1052.018 2 frame000000-cam1.xxx 3392.082 1068.919 1 frame000000-cam1.xxx 3456.107 1085.084 1 frame000000-cam1.xxx 3520.585 1101.004 2 frame000000-cam1.xxx 3585.433 1118.085 2 frame000000-cam1.xxx 3651.069 1134.379 2 frame000000-cam1.xxx 3716.839 1151.135 0 frame000000-cam1.xxx 3783.801 1167.603 0 frame000000-cam1.xxx 3193.982 1084.585 1 frame000000-cam1.xxx 3257.688 1100.468 2 frame000000-cam1.xxx 3322.112 1117.757 0 frame000000-cam1.xxx 3385.889 1134.017 1 frame000000-cam1.xxx 3451.175 1150.694 1 frame000000-cam1.xxx 3516.244 1167.465 0 frame000000-cam1.xxx 3582.344 1183.542 0 frame000000-cam1.xxx 3647.605 1201.026 2 frame000000-cam1.xxx 3714.410 1216.998 2 frame000000-cam1.xxx 3781.632 1234.017 0 frame000001-cam0.xxx 1022.981 1124.312 0 frame000001-cam0.xxx 1083.547 1085.539 2 frame000001-cam0.xxx 1141.267 1047.963 2 frame000001-cam0.xxx 1199.188 1010.479 1 frame000001-cam0.xxx 1255.506 974.265 0 frame000001-cam0.xxx 1309.702 939.327 1 frame000001-cam0.xxx 1362.393 903.889 1 frame000001-cam0.xxx 1415.053 869.977 1 frame000001-cam0.xxx 1466.723 837.007 1 frame000001-cam0.xxx 1517.093 804.027 2 frame000001-cam0.xxx 1067.313 1176.127 0 frame000001-cam0.xxx 1126.551 1137.437 2 frame000001-cam0.xxx 1183.636 1099.678 2 frame000001-cam0.xxx 1239.525 1062.388 0 frame000001-cam0.xxx 1294.252 1025.752 0 frame000001-cam0.xxx 1347.611 990.625 0 frame000001-cam0.xxx 1400.518 955.012 2 frame000001-cam0.xxx 1451.205 921.195 0 frame000001-cam0.xxx 1501.251 887.554 2 frame000001-cam0.xxx 1551.094 854.938 1 frame000001-cam0.xxx 1110.594 1226.601 2 frame000001-cam0.xxx 1167.681 1188.027 0 frame000001-cam0.xxx 1223.822 1149.832 2 frame000001-cam0.xxx 1278.951 1112.274 0 frame000001-cam0.xxx 1332.196 1076.314 0 frame000001-cam0.xxx 1384.267 1040.685 1 frame000001-cam0.xxx 1436.209 1004.942 2 frame000001-cam0.xxx 1486.362 970.620 1 frame000001-cam0.xxx 1535.918 937.260 0 frame000001-cam0.xxx 1584.247 904.465 1 frame000001-cam0.xxx 1152.343 1275.274 0 frame000001-cam0.xxx 1208.327 1236.967 0 frame000001-cam0.xxx 1263.033 1198.681 1 frame000001-cam0.xxx 1317.095 1161.724 0 frame000001-cam0.xxx 1369.212 1125.626 2 frame000001-cam0.xxx 1420.777 1089.132 0 frame000001-cam0.xxx 1471.441 1054.089 0 frame000001-cam0.xxx 1520.505 1019.946 2 frame000001-cam0.xxx 1569.350 985.912 1 frame000001-cam0.xxx 1616.616 953.131 2 frame000001-cam0.xxx 1192.515 1323.710 1 frame000001-cam0.xxx 1247.491 1285.275 2 frame000001-cam0.xxx 1301.596 1246.679 1 frame000001-cam0.xxx 1354.637 1209.876 2 frame000001-cam0.xxx 1405.695 1172.874 2 frame000001-cam0.xxx 1456.432 1137.859 1 frame000001-cam0.xxx 1505.205 1101.969 1 frame000001-cam0.xxx 1554.348 1067.196 1 frame000001-cam0.xxx 1602.291 1034.011 2 frame000001-cam0.xxx 1648.662 1000.834 2 frame000001-cam0.xxx 1232.909 1370.672 2 frame000001-cam0.xxx 1286.503 1331.749 2 frame000001-cam0.xxx 1338.903 1293.387 0 frame000001-cam0.xxx 1391.167 1256.140 1 frame000001-cam0.xxx 1441.492 1219.724 1 frame000001-cam0.xxx 1490.958 1183.607 1 frame000001-cam0.xxx 1539.466 1148.903 2 frame000001-cam0.xxx 1587.200 1114.015 0 frame000001-cam0.xxx 1634.393 1080.310 2 frame000001-cam0.xxx 1679.879 1047.179 1 frame000001-cam0.xxx 1271.755 1416.410 2 frame000001-cam0.xxx 1324.522 1377.795 2 frame000001-cam0.xxx 1376.177 1339.307 0 frame000001-cam0.xxx 1426.755 1301.703 0 frame000001-cam0.xxx 1475.809 1265.610 1 frame000001-cam0.xxx 1524.752 1230.082 1 frame000001-cam0.xxx 1572.539 1194.351 2 frame000001-cam0.xxx 1619.021 1159.716 2 frame000001-cam0.xxx 1665.686 1126.008 1 frame000001-cam0.xxx 1710.415 1092.441 2 frame000001-cam0.xxx 1309.178 1460.766 0 frame000001-cam0.xxx 1361.186 1422.242 2 frame000001-cam0.xxx 1411.857 1383.720 2 frame000001-cam0.xxx 1461.248 1346.328 0 frame000001-cam0.xxx 1509.985 1309.986 2 frame000001-cam0.xxx 1557.878 1274.312 1 frame000001-cam0.xxx 1605.090 1239.146 2 frame000001-cam0.xxx 1650.726 1204.397 0 frame000001-cam0.xxx 1696.118 1170.210 0 frame000001-cam0.xxx 1741.148 1137.471 2 frame000001-cam0.xxx 1345.918 1504.612 0 frame000001-cam0.xxx 1397.238 1465.850 2 frame000001-cam0.xxx 1446.499 1427.731 0 frame000001-cam0.xxx 1495.664 1390.248 2 frame000001-cam0.xxx 1543.306 1353.684 1 frame000001-cam0.xxx 1590.198 1318.281 1 frame000001-cam0.xxx 1636.147 1283.097 0 frame000001-cam0.xxx 1681.476 1248.391 2 frame000001-cam0.xxx 1725.729 1214.274 1 frame000001-cam0.xxx 1769.410 1180.917 1 frame000001-cam0.xxx 1382.394 1547.472 0 frame000001-cam0.xxx 1432.139 1508.152 2 frame000001-cam0.xxx 1481.188 1469.779 1 frame000001-cam0.xxx 1529.260 1433.661 1 frame000001-cam0.xxx 1576.075 1396.510 2 frame000001-cam0.xxx 1622.150 1360.316 0 frame000001-cam0.xxx 1667.003 1325.301 1 frame000001-cam0.xxx 1711.701 1290.302 0 frame000001-cam0.xxx 1755.341 1257.194 2 frame000001-cam0.xxx 1798.846 1223.423 2 frame000001-cam1.xxx 3039.821 521.374 2 frame000001-cam1.xxx 3090.507 485.636 1 frame000001-cam1.xxx 3142.421 449.943 0 frame000001-cam1.xxx 3195.281 413.767 2 frame000001-cam1.xxx 3249.176 376.143 0 frame000001-cam1.xxx 3303.861 338.000 2 frame000001-cam1.xxx 3360.144 299.840 1 frame000001-cam1.xxx 3418.574 259.502 1 frame000001-cam1.xxx 3477.748 219.753 1 frame000001-cam1.xxx 3538.214 178.535 2 frame000001-cam1.xxx 3062.186 567.387 0 frame000001-cam1.xxx 3112.828 532.360 0 frame000001-cam1.xxx 3163.865 497.104 2 frame000001-cam1.xxx 3216.978 461.492 0 frame000001-cam1.xxx 3270.648 424.995 2 frame000001-cam1.xxx 3325.519 387.165 2 frame000001-cam1.xxx 3381.630 349.763 1 frame000001-cam1.xxx 3439.063 311.262 2 frame000001-cam1.xxx 3497.243 272.126 0 frame000001-cam1.xxx 3558.132 231.290 0 frame000001-cam1.xxx 3086.146 613.096 2 frame000001-cam1.xxx 3135.797 578.070 2 frame000001-cam1.xxx 3186.823 543.638 1 frame000001-cam1.xxx 3238.970 509.277 2 frame000001-cam1.xxx 3291.855 473.009 2 frame000001-cam1.xxx 3346.526 436.606 1 frame000001-cam1.xxx 3402.507 399.053 1 frame000001-cam1.xxx 3458.589 360.951 0 frame000001-cam1.xxx 3517.982 322.241 1 frame000001-cam1.xxx 3577.591 282.119 1 frame000001-cam1.xxx 3108.383 657.926 1 frame000001-cam1.xxx 3158.013 624.489 1 frame000001-cam1.xxx 3208.779 590.185 0 frame000001-cam1.xxx 3260.775 555.225 2 frame000001-cam1.xxx 3313.459 520.350 2 frame000001-cam1.xxx 3367.444 484.151 0 frame000001-cam1.xxx 3423.348 447.367 0 frame000001-cam1.xxx 3479.572 410.493 2 frame000001-cam1.xxx 3536.987 372.091 0 frame000001-cam1.xxx 3596.995 333.370 1 frame000001-cam1.xxx 3129.928 701.871 2 frame000001-cam1.xxx 3179.402 668.661 2 frame000001-cam1.xxx 3230.108 635.037 1 frame000001-cam1.xxx 3282.039 600.852 0 frame000001-cam1.xxx 3333.853 566.535 2 frame000001-cam1.xxx 3388.451 530.911 1 frame000001-cam1.xxx 3443.708 495.041 1 frame000001-cam1.xxx 3499.561 458.278 1 frame000001-cam1.xxx 3556.887 421.499 1 frame000001-cam1.xxx 3616.253 383.488 1 frame000001-cam1.xxx 3151.936 744.716 0 frame000001-cam1.xxx 3201.728 712.351 2 frame000001-cam1.xxx 3251.590 679.319 1 frame000001-cam1.xxx 3303.733 645.746 2 frame000001-cam1.xxx 3355.075 612.015 1 frame000001-cam1.xxx 3408.796 576.972 2 frame000001-cam1.xxx 3464.129 542.577 0 frame000001-cam1.xxx 3519.305 506.066 0 frame000001-cam1.xxx 3576.360 469.159 1 frame000001-cam1.xxx 3635.011 431.447 2 frame000001-cam1.xxx 3173.739 787.537 1 frame000001-cam1.xxx 3223.031 755.513 2 frame000001-cam1.xxx 3272.842 723.031 0 frame000001-cam1.xxx 3323.720 689.611 0 frame000001-cam1.xxx 3375.497 656.299 0 frame000001-cam1.xxx 3429.075 622.478 2 frame000001-cam1.xxx 3483.233 587.780 2 frame000001-cam1.xxx 3539.247 552.179 0 frame000001-cam1.xxx 3596.236 516.268 0 frame000001-cam1.xxx 3653.565 479.928 2 frame000001-cam1.xxx 3194.908 829.253 1 frame000001-cam1.xxx 3243.982 797.903 2 frame000001-cam1.xxx 3294.029 765.858 2 frame000001-cam1.xxx 3344.623 733.526 1 frame000001-cam1.xxx 3396.088 700.565 1 frame000001-cam1.xxx 3449.135 666.660 0 frame000001-cam1.xxx 3503.234 632.336 0 frame000001-cam1.xxx 3558.759 598.763 1 frame000001-cam1.xxx 3615.392 562.647 1 frame000001-cam1.xxx 3673.143 527.140 0 frame000001-cam1.xxx 3215.844 870.704 1 frame000001-cam1.xxx 3265.057 840.154 0 frame000001-cam1.xxx 3314.229 808.064 1 frame000001-cam1.xxx 3365.216 776.373 0 frame000001-cam1.xxx 3416.794 744.417 1 frame000001-cam1.xxx 3469.494 710.843 0 frame000001-cam1.xxx 3522.840 677.384 2 frame000001-cam1.xxx 3578.238 642.739 1 frame000001-cam1.xxx 3634.597 608.653 1 frame000001-cam1.xxx 3691.527 572.337 0 frame000001-cam1.xxx 3237.127 911.085 1 frame000001-cam1.xxx 3285.682 880.516 1 frame000001-cam1.xxx 3335.129 849.676 0 frame000001-cam1.xxx 3384.892 818.381 1 frame000001-cam1.xxx 3437.154 786.403 0 frame000001-cam1.xxx 3488.904 754.576 0 frame000001-cam1.xxx 3542.760 721.349 1 frame000001-cam1.xxx 3596.268 687.689 1 frame000001-cam1.xxx 3653.075 653.036 2 frame000001-cam1.xxx 3710.709 618.919 1 frame000002-cam0.xxx 1184.360 1214.543 0 frame000002-cam0.xxx 1253.273 1241.350 2 frame000002-cam0.xxx 1321.219 1265.547 1 frame000002-cam0.xxx 1388.719 1291.417 2 frame000002-cam0.xxx 1455.755 1316.154 0 frame000002-cam0.xxx 1521.205 1341.488 1 frame000002-cam0.xxx 1586.360 1365.367 1 frame000002-cam0.xxx 1651.715 1389.789 0 frame000002-cam0.xxx 1716.204 1414.110 2 frame000002-cam0.xxx 1779.811 1437.723 2 frame000002-cam0.xxx 1150.430 1280.379 0 frame000002-cam0.xxx 1220.741 1305.974 2 frame000002-cam0.xxx 1289.550 1331.676 0 frame000002-cam0.xxx 1358.467 1356.348 2 frame000002-cam0.xxx 1425.848 1381.950 1 frame000002-cam0.xxx 1493.432 1406.235 0 frame000002-cam0.xxx 1559.973 1431.094 1 frame000002-cam0.xxx 1626.042 1455.935 2 frame000002-cam0.xxx 1690.673 1479.829 1 frame000002-cam0.xxx 1755.615 1502.838 2 frame000002-cam0.xxx 1115.677 1347.919 0 frame000002-cam0.xxx 1187.261 1373.805 1 frame000002-cam0.xxx 1257.742 1399.208 2 frame000002-cam0.xxx 1327.617 1424.242 2 frame000002-cam0.xxx 1395.960 1449.641 2 frame000002-cam0.xxx 1464.084 1474.182 2 frame000002-cam0.xxx 1532.247 1498.749 2 frame000002-cam0.xxx 1598.925 1522.957 2 frame000002-cam0.xxx 1665.810 1546.819 2 frame000002-cam0.xxx 1731.032 1571.115 1 frame000002-cam0.xxx 1080.105 1417.192 1 frame000002-cam0.xxx 1152.006 1443.137 1 frame000002-cam0.xxx 1223.768 1468.162 2 frame000002-cam0.xxx 1295.168 1493.479 2 frame000002-cam0.xxx 1365.622 1519.378 0 frame000002-cam0.xxx 1434.650 1543.437 0 frame000002-cam0.xxx 1503.651 1567.776 1 frame000002-cam0.xxx 1571.983 1592.709 0 frame000002-cam0.xxx 1639.229 1616.660 0 frame000002-cam0.xxx 1706.093 1640.236 2 frame000002-cam0.xxx 1042.204 1489.255 1 frame000002-cam0.xxx 1116.203 1514.695 0 frame000002-cam0.xxx 1189.474 1540.106 0 frame000002-cam0.xxx 1262.486 1565.265 0 frame000002-cam0.xxx 1333.459 1590.237 1 frame000002-cam0.xxx 1404.202 1615.095 0 frame000002-cam0.xxx 1474.323 1639.244 0 frame000002-cam0.xxx 1542.984 1664.353 0 frame000002-cam0.xxx 1611.719 1688.309 2 frame000002-cam0.xxx 1680.185 1711.703 0 frame000002-cam0.xxx 1003.045 1563.731 0 frame000002-cam0.xxx 1078.802 1588.640 0 frame000002-cam0.xxx 1153.629 1614.453 1 frame000002-cam0.xxx 1227.829 1638.780 2 frame000002-cam0.xxx 1300.633 1663.657 1 frame000002-cam0.xxx 1372.377 1688.784 0 frame000002-cam0.xxx 1443.848 1712.998 0 frame000002-cam0.xxx 1514.484 1737.492 0 frame000002-cam0.xxx 1584.552 1761.483 0 frame000002-cam0.xxx 1653.203 1785.806 0 frame000002-cam0.xxx 962.379 1640.298 1 frame000002-cam0.xxx 1040.060 1665.922 1 frame000002-cam0.xxx 1116.427 1690.781 1 frame000002-cam0.xxx 1191.817 1715.730 1 frame000002-cam0.xxx 1265.934 1740.547 1 frame000002-cam0.xxx 1340.093 1764.585 0 frame000002-cam0.xxx 1411.859 1789.595 0 frame000002-cam0.xxx 1484.168 1813.579 0 frame000002-cam0.xxx 1554.816 1837.953 0 frame000002-cam0.xxx 1625.461 1861.595 0 frame000002-cam0.xxx 919.757 1719.950 2 frame000002-cam0.xxx 999.322 1744.858 0 frame000002-cam0.xxx 1077.024 1770.219 0 frame000002-cam0.xxx 1154.181 1794.990 1 frame000002-cam0.xxx 1230.786 1819.489 2 frame000002-cam0.xxx 1305.593 1843.689 1 frame000002-cam0.xxx 1379.427 1868.188 0 frame000002-cam0.xxx 1452.648 1892.728 0 frame000002-cam0.xxx 1524.926 1916.417 1 frame000002-cam0.xxx 1597.430 1939.778 1 frame000002-cam0.xxx 875.412 1803.710 0 frame000002-cam0.xxx 956.604 1828.242 2 frame000002-cam0.xxx 1036.901 1853.566 2 frame000002-cam0.xxx 1115.796 1877.626 2 frame000002-cam0.xxx 1193.833 1901.651 2 frame000002-cam0.xxx 1270.175 1925.945 0 frame000002-cam0.xxx 1345.828 1949.585 2 frame000002-cam0.xxx 1419.812 1974.123 2 frame000002-cam0.xxx 1494.104 1998.172 2 frame000002-cam0.xxx 1566.688 2020.993 2 frame000002-cam0.xxx 827.803 1890.507 0 frame000002-cam0.xxx 911.690 1914.940 0 frame000002-cam0.xxx 994.036 1938.425 2 frame000002-cam0.xxx 1074.475 1962.744 1 frame000002-cam0.xxx 1154.086 1986.661 2 frame000002-cam0.xxx 1232.381 2011.616 2 frame000002-cam0.xxx 1309.917 2034.774 2 frame000002-cam0.xxx 1386.369 2058.582 1 frame000002-cam0.xxx 1461.138 2083.310 0 frame000002-cam0.xxx 1535.296 2105.742 0 frame000002-cam1.xxx 3284.554 570.483 2 frame000002-cam1.xxx 3350.042 591.148 0 frame000002-cam1.xxx 3417.494 611.734 0 frame000002-cam1.xxx 3486.622 632.179 1 frame000002-cam1.xxx 3557.794 653.201 2 frame000002-cam1.xxx 3630.022 675.194 1 frame000002-cam1.xxx 3705.312 696.473 0 frame000002-cam1.xxx 3782.442 718.736 0 frame000002-cam1.xxx 3862.515 741.544 2 frame000002-cam1.xxx 3942.886 764.213 0 frame000002-cam1.xxx 3258.379 625.296 1 frame000002-cam1.xxx 3324.225 645.663 2 frame000002-cam1.xxx 3391.442 667.078 1 frame000002-cam1.xxx 3459.699 689.174 0 frame000002-cam1.xxx 3529.369 710.726 1 frame000002-cam1.xxx 3602.826 732.960 1 frame000002-cam1.xxx 3676.699 755.064 0 frame000002-cam1.xxx 3753.187 778.050 1 frame000002-cam1.xxx 3832.198 800.563 0 frame000002-cam1.xxx 3913.634 824.279 1 frame000002-cam1.xxx 3233.102 681.100 2 frame000002-cam1.xxx 3297.700 702.175 2 frame000002-cam1.xxx 3364.365 723.414 0 frame000002-cam1.xxx 3432.928 745.675 1 frame000002-cam1.xxx 3502.956 767.241 2 frame000002-cam1.xxx 3574.687 790.587 0 frame000002-cam1.xxx 3648.596 813.214 2 frame000002-cam1.xxx 3724.967 837.113 2 frame000002-cam1.xxx 3802.456 860.344 0 frame000002-cam1.xxx 3883.570 884.363 0 frame000002-cam1.xxx 3207.688 735.613 0 frame000002-cam1.xxx 3272.125 757.356 0 frame000002-cam1.xxx 3338.909 779.308 0 frame000002-cam1.xxx 3406.810 801.922 1 frame000002-cam1.xxx 3475.855 825.023 2 frame000002-cam1.xxx 3547.305 847.853 2 frame000002-cam1.xxx 3620.924 871.730 1 frame000002-cam1.xxx 3695.805 895.505 1 frame000002-cam1.xxx 3774.232 919.840 2 frame000002-cam1.xxx 3854.586 944.442 1 frame000002-cam1.xxx 3183.002 790.030 2 frame000002-cam1.xxx 3247.322 811.880 0 frame000002-cam1.xxx 3313.228 834.711 1 frame000002-cam1.xxx 3380.369 858.250 2 frame000002-cam1.xxx 3449.710 881.403 1 frame000002-cam1.xxx 3520.048 905.598 2 frame000002-cam1.xxx 3593.340 929.292 1 frame000002-cam1.xxx 3668.386 954.033 1 frame000002-cam1.xxx 3745.825 979.427 2 frame000002-cam1.xxx 3825.573 1004.232 0 frame000002-cam1.xxx 3158.032 845.531 0 frame000002-cam1.xxx 3222.391 867.610 1 frame000002-cam1.xxx 3287.148 890.616 1 frame000002-cam1.xxx 3353.715 914.838 2 frame000002-cam1.xxx 3423.147 937.866 1 frame000002-cam1.xxx 3493.403 962.515 2 frame000002-cam1.xxx 3565.963 987.373 1 frame000002-cam1.xxx 3640.589 1012.451 0 frame000002-cam1.xxx 3717.731 1038.197 0 frame000002-cam1.xxx 3797.010 1064.603 1 frame000002-cam1.xxx 3133.618 899.490 1 frame000002-cam1.xxx 3197.073 922.594 1 frame000002-cam1.xxx 3262.493 946.358 1 frame000002-cam1.xxx 3328.525 970.380 0 frame000002-cam1.xxx 3397.467 995.159 0 frame000002-cam1.xxx 3467.186 1019.844 2 frame000002-cam1.xxx 3539.399 1044.332 0 frame000002-cam1.xxx 3613.785 1070.993 1 frame000002-cam1.xxx 3689.495 1097.137 0 frame000002-cam1.xxx 3768.776 1124.583 1 frame000002-cam1.xxx 3108.643 954.672 1 frame000002-cam1.xxx 3172.271 978.361 1 frame000002-cam1.xxx 3236.624 1003.180 0 frame000002-cam1.xxx 3303.472 1026.765 1 frame000002-cam1.xxx 3370.935 1051.547 0 frame000002-cam1.xxx 3441.108 1077.367 0 frame000002-cam1.xxx 3512.072 1102.648 1 frame000002-cam1.xxx 3586.545 1129.953 1 frame000002-cam1.xxx 3662.388 1156.687 0 frame000002-cam1.xxx 3741.073 1184.126 1 frame000002-cam1.xxx 3084.359 1009.314 1 frame000002-cam1.xxx 3147.788 1033.665 0 frame000002-cam1.xxx 3212.013 1058.990 2 frame000002-cam1.xxx 3277.626 1083.467 1 frame000002-cam1.xxx 3345.473 1109.008 0 frame000002-cam1.xxx 3415.065 1134.621 1 frame000002-cam1.xxx 3485.980 1160.538 0 frame000002-cam1.xxx 3559.716 1188.289 0 frame000002-cam1.xxx 3635.319 1215.326 0 frame000002-cam1.xxx 3713.537 1243.343 0 frame000002-cam1.xxx 3059.755 1064.063 1 frame000002-cam1.xxx 3123.537 1089.003 2 frame000002-cam1.xxx 3187.272 1113.772 2 frame000002-cam1.xxx 3253.175 1139.925 1 frame000002-cam1.xxx 3320.361 1165.953 0 frame000002-cam1.xxx 3389.434 1192.270 2 frame000002-cam1.xxx 3459.954 1219.228 2 frame000002-cam1.xxx 3533.463 1246.544 1 frame000002-cam1.xxx 3608.284 1274.822 1 frame000002-cam1.xxx 3686.307 1303.675 1 mrcal-2.4.1/test/data/test-optimizer-callback-ref-J-0.npy000066400000000000000000003200001456301662300230640ustar00rootroot00000000000000“NUMPYv{'descr': '÷šÀ ÀFד˜šÀr¨û5;šÀ@7pÓÄ:yÀq§´ü2âxÀ¶r Ìž@)—¦BаˆÀ”-¥ØŠxÀÉx¦óóy@žF·×˜y@üS û>y@Gj©>VI|@2²nPX}@á/,3Û'iÀÄÇ{ÓÈ­”@0Ò±ƒnq~@v—|Ê82}Àcû5õéI~ÀX²lÀÈêéÿ‚EZÀ˜4¶/A[Àˆ•ر;w@á/,3Û'iÀ ^gGF\ÀÐ.жÎ[@ñ)î{“!\@ÓþÅ/]@X‰¸›Â}~@—Hû«¡€@sAÓIžiÀÁ&ÝŽË•@»úC·$‚@diÜüÉ•À†ïq j:À—õèWË‚À¡Á½rlT[ÀnþÃ(oÐ]Àñu5¬q€@sAÓIžiÀÞ•óu!C`À@\žôjO\@s`Ÿº>â^@¦ÄœD{Ø`@ÐÞ¤6xj€@¼=?‰’Ó‚@ôpñ½jÀ&j½4Pö–@ªƒ™ÚJ—…@. ௽À¬éÿ h“ƒÀNV½Ks†Àçæof\À¢îbKI`À¥Åž0@ôpñ½jÀ†1\7­bÀî.é¹Ò‡]@”úöî`@"¯~†kc@L²W#±§‘@ϨûÇG•@ æ…²ˆzÀÑ Âu¢.¨@È1<†q¦™@o½Iá;n’À㬫77–ÀbiýAåÆšÀ©Uí;zmÀÛÇ÷æÃqÀz7ºš÷‘@ æ…²ˆzÀ__ÕÖÇiuÀŒýµºÅn@÷²9…®‹r@oèšÝ•Zv@&^%E–ö‚@‚ èÒnˆ@%”–sMûjÀŒ Ðu™@׋»pkŽ@*V¼¹±àƒÀųX:ï,‰À§Ékè£âÀF6ÑC5Ž^ÀO_ç~YcÀäå‹?}È‚@%”–sMûjÀÄÌ“è²hÀôÞ{¶`@\•^Hd@qðóÂ=°i@¥ØëV„@QYžÇ‹@ûô®©/mkÀMÿ‹kÊš@â8 Q°’@Gy÷òi…À'l¢ÞŽ|ŒÀ^jôL[ó’Àl–éÃl _À4bˆ eÀØÆú,£ƒ@ûô®©/mkÀ6N7þkÀ}g^¥`@åÇ7»%f@Ü[O‘Œwm@Ï;sÒ”@'›*kž@ñÚÐtå#…ÀÑg3º´d°@nnxÙt‹@Ayîi}”ÀÚ¶fŒìÀi¬£õ‹Àù?™dÆÚsÀ~á½6fpÀ€!¶¬U™@ñÚÐtå#…ÀTm0kÀW2Íö8t@pBA½O³p@AÃÓ[Œ–k@ šÚ´þÈ…@àË'dô‚@?8F¼(ŠuÀÓ«3~P¡@gt,cb}€@ZRôŒ>†À@º“ßYZƒÀÌí‘]Ö€À?ÏÇ’lµdÀuø{SbÀ¥sÚ›Š@?8F¼(ŠuÀà˜Y_ÀµT@L?Ä_ŒR@ëÍ)ê.xy@?Ù,„x@_]_•SfÀX~y—èH“@4á&¯w@}Gz‚)zÀn|xÖƒ:yÀ´¹2r TxÀx¸±xVÀ%L£vi«UÀ¢%"îþ|@_]_•SfÀéÙiuåTÀOÒ\%W@‹6‡IHBV@ˆ˜®¸ñvU@Zü©þã{@•K·‹µç{@`]/\oµfÀÎ?â§{V”@¹úo Q|@_{áXW|ÀqDôVÂ|ÀÕš×é.}À¬ú]-`WÀËz6Nm¸WÀ$ £•U~@`]/\oµfÀ]§QiúXÀñEARX@FãjsErX@]®¾+ÎX@[mÏÛA©@,6п©Ÿ@Ê)fW‡À:µ‘k@¡éLEãp@‡ÕKà$úr@¡ßóŽ{‚@îö²È?î†@¾ ÞäØ.hÀ$KÙA ™@eáÓÊùrŒ@S©)WƒÀî[j´þ‡À½fŠÿÄÀ5å€ù?[Àß|ÌúËÉ`À·VwÝá,‚@¾ ÞäØ.hÀ&(1ZÔdÀ±›ÜþÎQ\@|ЇâD‘a@åýÅx“Ëe@Õ*¥—…Ö“@ʺ|OÝ™@¹©ªˆxÀÒ ¾7]ª@À©V‚Ü @ÓŒK“‘Ø”ÀgÉs-›ÀâÃ<S·¡À¹/·±,úkÀÌ›'¬Æfm@#—4Ì*s@BWŒGüx@Öæz{ÿ†s@Œ•n‚u„o@ߨ:IJ cÀ’'·£û@ –¡ØNoi@Ä{.åÝsÀºþ»pÀ­Ð(g}ßiÀ5Žçe›QÀTïÒ^kLÀÕ}«PZx@ߨ:IJ cÀš'RìüîFÀ½ôSéQ@OÅHHYèL@zON#TG@¥‰'!â'…@²ÐHaþ@QÈa“;asÀsäÒ=¡¡@Pµõ±š~@Bè&ês“…Àó¹â‘ŽY‚ÀŠò¥„N6ÀdäÒfèWbÀƒ2on€3_À± 6¿t€‰@QÈa“;asÀ-{+‰ZÀ»_ó_-µb@’m}ô%Ò_@Ë\Ô[@æÛ ­(æ†@‹™E6„„@ʓڨ ³sÀµ÷$éù¡@Òpºa‚@ˆTõ\k‡À§r¬{Žû„ÀÀ´ì§Ì‚ÀÚà·ÓÜcÀÑïæJaÀÒ—)²´Š@ʓڨ ³sÀNÆËC§^À,`~œí†c@[b Ì~a@ÖäÙy“Y_@i6ï‹>Ãx@÷PŽ«;]w@± àdÀÄ7ªGø’@+ÒÏp v@uZmæfyÀ sw¥÷wÀ¥*v%"vÀ×—ÅUÄÚSÀ•ž:·»RÀÆô¤£÷{@± àdÀ8à¬QÀQŒw1ü]T@npEù…7S@úeþ°!R@ï(ùzÀz@Dò¼z’z@ +;A QdÀ¸¥œ4”@ÞepšÉdz@ð$Xrˆ{Àkδÿ»X{À 7ñôµ){À3Z„R TÀ¸Ö"‹|TÀDâÙËëI}@ +;A QdÀ€†.ïPYTÀx{³pä9U@½C¥dU@$Ûœ#ñT@=Ô*qß|@º÷Wb.~@ïTÐÝúœdÀ“ž˜1•@P×6Œ@T€*ÏÐ}À¦;½½*À5ôå÷,J€ÀU-é[×fUÀX¶ÒÓ&_VÀj't›5¬~@ïTÐÝúœdÀÈ›'H·bWÀ=Ÿ_¡V@4¹vW@oìæËƒ&X@mñüú Ÿ@ÄIñ¡f¡@zEq´¬æ„ÀMÚFrÄ:¶@ží‹òfÒ¢@Gåÿk! À«¿jJ½¡À‰8VE=‚£Àtt¥‘[.vÀC‰Ê¬·dxÀóö§uš @zEq´¬æ„ÀÏœçÓzÀ•当ýv@“…QàšHy@Ú«Ü.Î{@“zd @"KwÄb£@20‹ü-…Àø£—zj·@½ ?dk¦@2á`Òo¡À™t +¤À½6,6ÍS§À†þ:…xõvÀ<À#b"ŽzÀÂå6~ÓÑ @20‹ü-…ÀP„C^·~À.‹ußxãw@8ÆY¹j¡{@]È·±jõ@`Œ[ð‚@`z¨12ë…@\¬ÉÁreÀø=èâ觘@¢–m!¨Š@²ö_O!Ô‚À¾ŒÖôå†ÀÉØ°çôØ‹Àª”oÁâºWÀ5×éÛ\Àct3†)@\¬ÉÁreÀÂèC:^ŒaÀ"h8j]ÊX@ü„ùœ&^@Õ T_ Ub@[B…[£@×#B÷ྨ@™ÁóPÑ´…ÀáNw¬ó¹@2ívã-¢¯@pø@h•N¤À¥}EC™õ©Àhµ¥–±—°ÀË©,}xÀÄóNÀtÙ zr¢@™ÁóPÑ´…À亿`„À®às3‘°y@yÎ’k€@—@:4 ý„@)Ð 3÷r@Žwa1ïm@ ò56aÀЇ| ³@¿ÄÕ Ÿg@c„B» FsÀ ßJx knÀjD‘ÞhÀŠ/äÍ‚õNÀöF "nHÀòÝɲÓrw@ ò56aÀýáï˜9GCÀW”Ø·uO@×™MÓH@ªUwL—C@žBw„@×À×W@nablxDqÀÇJüôh¿ @æSº"uw|@Ö•Aò„À‘³Oï_mÀ{7ýdöÿ|Àº,/`À¤4€mËZÀ>ܨˆ•ˆ@nablxDqÀêK[@@!L!¶V@$$"¤eD–@´ïNˆ“@ŸuI8ƒÀù÷ž*|¯±@sú%Z‹‘@9f¿Ú¿–À oˆUò“ÀÜ—*Ù}‘À÷•Òý»pÀil±XmÀ[[,ð*Æ™@ŸuI8ƒÀ‰’¼iÀì’0¸q@ÿ‡ Púm@¤©QÃIj@ìð¹x@ry-¹=Bv@vS#Ÿ'ÀaÀw17t{ª’@,úL1~t@4ò+¯xÀŒX ÎvÀoèèžuÀázД–^QÀA‹ùŒ PÀü ÓR{@vS#Ÿ'ÀaÀ|nêmЦMÀNÀ1æËQ@³÷ uàpP@ïR>ÿ`N@ÊUœZÔ Š@=}tÊV‰@±ÀIšLúqÀR‘"Þ°£@‡Ä[ƒœ§ˆ@@ÙÄŠÀþ<°ù ŠÀn¼;îV‰À~Š¸È•bÀbhæ†aÀþdLU SŒ@±ÀIšLúqÀµ/’4í aÀ02Ý‹§‚b@p ìx¯b@?2‚,†a@X(øŒ@šé\OÎŒ@ÎSôÆ1rÀ öœ!ä@owkmë@Ö´_.À&Í?Ù´À–ížÃnŽÀRôohÖ¦bÀV;rS"cÀb=_­»±@ÎSôÆ1rÀV¯c_C’cÀedD¢À¹5‚¿}JsÀ”NVwÌtÀÉ~†ÂU Ÿ@°dð$mf‚À³¬8›kvÀ/`â:÷s@o\Aœ9†u@V/ÖØ]4w@Íên^BW€@.0è}¸ˆ‚@™Ö*˜bÀt¯e-a —@LøFŠ…@n¤ÛÒ ú€Àb}°3[AƒÀh9¾ôÖ…ÀqR·Ã‰ìSÀìaw™VÀ/G²YP€@™Ö*˜bÀ$æ7Б¡YÀÔæ ³T@˜_`àå’@¶ÅO+´—@§ÉL¡ñrÀÑ—H­©@ÑeÈqU»@±Ïþ* Ë“ÀÄ]¾Ó˜À£WSñà#ŸÀ°NˆÆä&eÀÜuí‡jÀëSŽ’Ië‘@§ÉL¡ñrÀÔ u’£pÀ×™Óód'f@c½µô§Ék@^õ†Xmq@æÙgÐp’@àŽOƒ,zŒ@/P^¼8~À‘;ÛB0¯@ç Žèý…@©U$tÉ·’ÀØ!¬SéŒÀgƒ€S†À‹8nACíjÀ³?ÄÎcËdÀ­PT%­ž–@/P^¼8~À4·ÓF `ÀJÆ0DVk@\`ÆRe@峊M`@E½Xsÿs@ÿ^öF„Jp@zé1Èg^À::7ùÂz@°À›¡óŠj@á`ôúYtÀ3±8D”pÀÄm0kÀÖ]¹ßœóKÀëù}FBÅFÀa¬J¾w@zé1Èg^ÀLOg‰ÁŒBÀTw"&rL@k32+W,G@f<»àB@ û•g«u@Ã¥èœr@¼U6qÀ^À~ÒÀ¸g‘@à ˆ\9úo@¹ð-)‚vÀ±EY@þrÀ,vióPpÀ; ðjûLÀÌ—ÇåHÀ×ë»O¬ëx@¼U6qÀ^À”Ôèq]bEÀ2ͱ’M@!l vgI@XºAûÑE@7ØðDVu‡@œ×ñ<…@táÏ oÀ½äýãq_¢@hàöW:ƒ@d9[VkˆÀ1•åáû…ÀÃÕæ)­ƒÀÿk)¦^Àõ¯ig,[Àjþ4h'Š@táÏ oÀ)ÃyÎý™XÀ [gSá¶^@¡ÖÏ«Î[@Þdaxæ,Y@©!´}§^™@ŒøX6ì2˜@ÕÔÇÙ‘aÀNäq~cb³@¨á—@­ÚÈ šÀåîµ%טÀ…¶¡‰œ±—À5ëì oÀK¹«VœmÀ9›”Ýr›@ÕÔÇÙ‘aÀnu‹€>lÀÆ@Z…²Ýo@´¸ ,7en@úåLÇþl@ÞËS©h‹@,A<­ˆ‹@5ìÀˤ¨oÀ²‚vžq¤@PŠÖ¨‹@2Ì"í‡:ŒÀGï°ù€[ŒÀ|ŒÀ¯¹é.`ÀÐ=ªÛè`Àб“ãlÌŒ@5ìÀˤ¨oÀˆÃî­¸-`ÀÆä‹§ð‚`@ hsý9–`@¢\zÚ™©`@`¡Ìˆ„”}@ ‚T™H@ȇüéè_ÀIxП⋕@Il>劀@V‚¯ù›’~Àd#‰7©*€ÀÔ³a¹þÀûÅYçˆPÀhÍ 7ª|QÀ^U€ÀhðÄ5"+¹@­Ð#Éoÿ«@zï1ÖM£ÀqcMÆ.ƧÀÉ€À’ð"={À°µ¶ùÒÇr@>Oc#!w@ãµ2A||@µp¢Mð@Í~=²c#{@·0ª—) jÀœÍ£iº±ž@A¬¦¹‡t@U<Í•þ1‚À™¶>äņ{ÀРˢLÒtÀÝbáÞËWÀ§ÚæKyQÀ›¯hÒYÝ…@·0ª—) jÀO¯Ï[oJÀÈŠÀëdnW@Z‡ªI¹Q@¤†vì)ÐJ@aI‰çŠw“@=cPO¤@Cc’i+\zÀÅ-²»8°@+f0´¸Ïˆ@›ÎÅ+ÖÊ“À,4g¯ ™ÀG35 â9‰ÀLüŽ“égÀsWÌÍcÀÛkà!4ú–@Cc’i+\zÀt,À0z^ÀR+äOh@þ(5%{hc@†¼D˜ü^@Áœîá•@\.jš½Å‘@|»ÏÁ‘zÀDö˜Œ"±@îd@Í î@vdPhƒ•ÀÒ`¸´Â’ÀxIÔÞ‚ŽÀ?8o7&¸hÀîñ6çÐdÀ ‘q[¬$˜@|»ÏÁ‘zÀÎÕžgq‡aÀ¶“2i@T&5ÿ7e@Ó{­øAÞa@¾Õ’ÈÛ–@¾“Á®ØK”@qS’ÀzÀê |G²@åý¿”Àáx\råk’Àk=Ò€r„iÀÑüž6¨fÀ†r KV]™@qS’ÀzÀEldÀ$Jz‡j@s (e)g@¤·ÜËod@j?½ª»˜@ÖV!G%—@ÅE[ÅBèzÀtßÀ°³@¸3Äåø¨•@ÖÖÍé[™Àí™î.=»—À—œ¾ðN5–À”ÿð@?MjÀ§æGhÀÔ8/ͤš@ÅE[ÅBèzÀYÀ1¨gÀD*¨÷j@|V^0ŽÅæ5sk@ö•ÒM1k@·ú}ÊÝœ@¨Äàø@˜ì± {À‡ \^ù8µ@°óÉ66Ÿ@7þGµËÀ@Ô¦¨´ïžÀN3Îp Àö ñÏÎkÀ-ª›ßlÀ‘ô–½¶b@˜ì± {À(ˉ÷úmÀ“šì³l@ÞëV6Ím@Ä<8Dñn@GFËÌé!@æµC®‘@F Ù0kÀh²ñ¬\¦@ÓÁ䘒@{z.‚ À˜c.– ‘À9â‡eD“À޼)¯ƒ\À ,æÅÇ*_À3è=A‰ÚŽ@F Ù0kÀj\NÖ†aÀO¼‘¤Š]@µ=‰ã%`@ó]6r›¥a@$*ÂÄ€@aß«ÌIƒ@A“¢µ7[À;Úïíx—@¤¯;Ä/†@%ïc¨pÀžº[}‡„À{\;+5‡À¥2IÜv.MÀgkkˆÈPÀP=K¼ô1€@A“¢µ7[ÀÅÀþNSÀÄÜYN@†iT/ŒtQ@AŽ:êT@ëý&lh ’@Îûéî«Ô•@¥íŠ5kÀw%ñ˨@ü_Â:Æjš@¶Ø hÔÖ’Àßúñ$ Ì–Àл%g–›À ïÇ—œÌ]Àh±î‰£bÀó¿ãÏÿ@¥íŠ5kÀáƒwRÑeÀõÐY¸E_@‘Y%ðÓb@{ñ]ŠÈf@ÐÞ]2 x‘@ ó ‘è‰@Yn(À£MvÀÀé´õè7®@;¥:q6ƒ@–m’BP´‘À9—«õAŠÀ2Dˆ»xƒÀâwcÀ¦RMLmÞ\ÀE$7Ä[.•@Yn(À£MvÀÉ(×phUÀ˜J 1ºc@D‰ìÊB]@Zû*;N²U@ÿru÷r@_g•Õ(³m@¸.7*¡gVÀQ×À­Ðñ@´Ó#™ä@g@\ðtCDsÀKA.n+nÀs<ŸgÀ½9”õDÀñ‡‡m?ÀÒÝÄHv@¸.7*¡gVÀÉ Ø?›8À±inû;cD@–ú]EÌì?@Ã,äþ8@"›Ô‹’”@f…Šsÿ@XÁ ×CzvÀžÐŠæß°@i”­;¸Œ@ªˆÅYó”À,´1woO‘Às®"r䚌À½e]©dÀ¶qsaÀæùN´¦p—@XÁ ×CzvÀ8+âv5\À¿BH e@žÃ,ìaba@¦Ï!Ä3º\@\~¾JÆJ†@>™“mƒ@}SP,+…fÀ‚žŸ>YÑ¡@f &“î€@³’ëšÃ†À‰BôtáÖƒÀzG¦þYJÀf.l/:;UÀë0ŒDê€RÀ3÷ÑP•¦ˆ@}SP,+…fÀàzÁBR PÀ«¾¬ïN®U@M Ûî5åR@Ñá$»wP@?¹!”!ˆ@:dƒ],†@÷ þCñ‡fÀd§I¹²Í¢@U(tÐ_„@~€Õ·ˆÀÂﺆ¼µ†À™eŸ Þ„ÀÏ\Ù1ÇUÀD+4ÚTÀŽÀ PÁÆVÀÜá -ôW@ôçŸÎ“oX@[,îÍ€jž@믕&V @Ù÷*[vÀ¶áwå¶@(¹é½{Œ¡@ˆœ×LÄxŸÀ¢3áÕNç Àqcj(¢ÀXf&27gÀ ˆ#1ðhÀdÄ4ž@Ù÷*[vÀ €è–ÀÉjÀçâ^Nh@½lÐæœÍi@l}›Ç·k@¨¾(íc@—ô…ˆ’@Öéë§û8fÀ_•î4¸5§@áëþ‹Öô”@ \.‘ÀÛôôü?“ÀuáHKÄ•À´Ž?ršWÀQƒ×Üu°ZÀO¯•øœ@Öéë§û8fÀûßÃ-^À¹\¶„X@Âă2«¸[@áGƒf„X_@ÒóçYj¤@rwÎý„@óâ†.R VÀ™ç2p˜@2¶öùˆ@Ô_pàe‚À@»"‡þã…À±o›Ù ŠÀüʲ´ßîGÀq©þyLÀviPµnš€@óâ†.R VÀJªFõðPÀ‰ÜÓ¿QõH@ó>¤B²M@À‘]x»ªQ@¿e<¤ø‘@…C¸¶Çˆ@à­£jrÀ |W‰®Â­@ÿ5”‚@é.QCh>‘Àê~‚@I*Œüin|@<”O1ÔˆbÀ­¸è%wŸ@úµ¶;Úu@ø3-ÛèÅ‚Àë %¡‹Û|Àoœ†Ñý-vÀ *–bÁhPÀì{zšP9IÀ, ×”~©…@<”O1ÔˆbÀ2ùcœcCÀƒ—òª½§P@ží„"šI@ý'ŸÏp­C@)uâ”@‰[ I@…€…9UyrÀ{ÃÈB´Ÿ°@ô4;—mŠ@:àO:ùk”Àf݈ö‘ÀëŒ5oÕãŠÀUA½ˆÊ`ÀPD£à>[ÀÖ›ãLÏ–@…€…9UyrÀšgFÛdVÀXÁª<a@"ÇäFݸ[@uœã2`~V@ËáY±Â…@¬ÿmú× ‚@bኼ+abÀZ£þ&Ž¡@öö*3Ïå@%¸ÐY2†Àae÷µ=ƒÀ£7¿oE€ÀS’¨Î#QÀ÷ÜìYYMÀûPeý¢ˆ@bኼ+abÀ¤]J ¦ IÀÖ¨›€|Q@Úc‚ã9ñM@ G¾°­¢I@Ù¥{ëw@m¾ÿËFu@ÕËÜPé?RÀ¤•cöV‡’@(HOvG6s@Ï-|ÝáxÀ'?UÙÅuÀa²ï?¨sÀ()°¯tAÀc_í(†?ÀÔ¤©Dy@ÕËÜPé?RÀ®$?w<ÀÁÉÌ=ÜA@#±6“• @@-Ð,!õ=@} ÙX¼}‰@­ãÙCˆ@JŽ&’bÀa¿ïK»‹£@Cà܇@—êïgÒ)ŠÀÙŸ8¨çˆÀx™À×ü´‡À Íì F»QÀ%ô)CïàPÀðî’ÞΕŠ@JŽ&’bÀ¤jjPÀYr0Þù2R@–ÖÑáRQ@v MÉ}P@ǯ;A7Œ‹@ÕªDx¹¡‹@óÃAàaÀ2šNwÍ›¤@RQozL·‹@ÿjOl^ŒÀåä-¦’tŒÀ?ŠHÊŠŒÀEסöQÀ°¬¿¦RÀš86V¹ö‹@óÃAàaÀØHªžRÀNÉkR@þ'èrR@Ú•Àû›R@»5‚€­¼@ côèäjŸ@H(‘hà qÀͧ¸µ@äûk5¶˜ @’5ýÍŒ»žÀa¡“Å< À&ÒÝaõ&¡ÀDg/)#bÀ6¸7€)cÀº°Bh@H(‘hà qÀW‡Ž Ê>dÀh£ñ!¾b@;Ú\qÌÍc@@7VOìd@I»8œ€@†qy EÕ@ã@ÇÝlVQÀE›Vá–@/ÇÙ\Öƒ@׎–Ùl¡€ÀApë‚À·ª0”„À½äŠã@BÀÐWÞwNDÀïBê£ê~@ã@ÇÝlVQÀf"J–FÀÞ;HnïB@_ò¨ü`E@#wMnnG@^§®PsC@ÿñ¹1<6„@Æ*ˆàVQÀ`Þí€>˜@Ôîè^í©‡@M&»ÑúÀ*Ú¶Ãë …À^Å5RG¥ˆÀ#NEà-MBÀö±ÎXmEÀ<?€@Æ*ˆàVQÀ}@™?,IÀ}­Í’C@¹)úïðPF@¾½i"£ J@”‘ ¢Ôœ€@Ólnü¾w@18ÞÄÍ]ÀMd‰íQ@åà7餸p@ÅåôÏ€ÀÜÄ‚xÀ²<8ÖÞ,qÀ“9×ò>hIÀ,¾Ê®“(BÀÈöŽw€„@18ÞÄÍ]ÀœH4ªô9Àûü@±n¶I@™nLét`B@Í7rŠD:@ÎÒ»¤ ’@lÐ8·fD‹@N·HZ~mÀÖëbK¯@[Æpd€—„@pôWÿoO’ÀcV§PƧ‹À„†ÃŒâ„ÀèŠáx?ÔYÀ´ß®0zSÀÄS“ì•@N·HZ~mÀ„Nf7vMÀ6‘ž\a2Z@Ìèr”ÈS@‡SŽ`áM@ -²J™s@Ì»MwßBo@ª‹À™­MÀÿÃ™Ïæa@B·B†îh@¶öÄÅììsÀ}îOÉEÈoÀDÓD"êXiÀ<‰ŠÅo.:ÀÕ£ zcá4ÀÑj0“?v@ª‹À™­MÀÅ”l§0À«Ÿ–Ë(ž:@Ψv }:5@¥Œ /*î0@A…@põÏÇwä@þÞ Äܧ\À'qØlM¡@>|ܵ¹~@ì—1Ùiª…Àç¼==‚ÀB&š×Ç´~À2ƒDCUtJÀ+¢[˜üDFÀÔùGq‡@þÞ Äܧ\À[~B¿BÀ=æë7;÷J@P§$u-³F@éÜÙ{áC@ägG ó‡@_­fÖGs„@ùª§œú\Àô ºµ‹C¢@(Ísn)‚@eÂF{ñ‰‡À}\ ¢ç„À‰;Æ‹¿‚ÀÝmäˆ=£JÀŸßÂ#¨GÀ‘ïçΰˆ@ùª§œú\ÀkcÐÜnEÀíçöÅ:K@+Ñ‹'·.H@bøóyE@ ŒÑëx@3VE—›Vw@¦ùyN KÀhkAϵD“@Iµl¶"Ûu@3ÚåàyÀ…ð}‰îwÀ›ëÆühvÀ¬ünì;¸:ÀzjIÈ9ÀJ˜¾••ÿy@¦ùyN KÀîóé«ìn7ÀNj §e;@8˜‡®/¨9@÷¹p8@÷ùÊ´)ñz@¥FI÷ñ—z@ù„Á” ÍJÀÖ´QcQ”@gNÞªá?z@óÎvÿF·{À|œ95[{Àº$Xç{À;Cý (°:À‹ÒÑ’ÇW:À÷½€Éú]{@ù„Á” ÍJÀ(’ãÁ‹:ÀõžRgt;@F8§û|;@áÔï´¿¿:@ä­o+}@Eêº×‹A~@ä×EçåJÀYµ¿‚j•@é,ÃËv@Ë–þ~À<ɦüû;ÀŠMðÓ=€Àùäʇ:ÀdKïyÇ–;À;Ë¢]«Ì|@ä×EçåJÀ$•¼Åİ<À~÷Éò5c;@Ø(${<@Iâ>?ž=@Ò”õêÐaŸ@tlÈ1/¡@i$˜qiÀ_ŒQ%H¶@y;3âÜÑ¢@q6B À±‹uSΡÀB v‰#€£Àè"ñ ÿ:ZÀñ<…ëº\ÀÍ‘]Lž@i$˜qiÀÒ*dðu_Àë(þºå-[@àÞeÄ]@ùæ<ù¢L`@ÿn‚ fç @ZÕ] }£@fCwá{!hÀW-ÛÖÁ·@øÍ=gÞw¦@¥ìcÙ}•¡ÀeEóÔÂE¤Àñ"ÿC_§ÀbëR!yÆYÀÍÖoú]·]À[H2ÏÝŸ@fCwá{!hÀR‚snB!aÀ65åÄíÏZ@熵ié^@I½Ç‡­Ña@:ñ\9€@•*Ȧ³Ìv@EAö£VÀ—Ý䨇åœ@øM—z%p@N”8¤h€À®¥ê!>Ž@>éK—uc@."†àqÀ1O®0ŽjÀ$ÚÿÔ ¹cÀ™›+Å$3ÀH>‡?¿o,ÀM 'Ó›Ÿt@\¼Ø3FÀ°CQUÆ%Àcãtp"g3@ÄÄh¼SÒ,@4>¡×ýg%@~ðšÒ'“@Ï£<9Ž@Ä•V_qeÀ<÷èn&°@;ÀDÉ•‡@ ã›òÝu“À²žÒh±‰ŽÀɦàõ‡ÀÏÑ[SÀš@ŸÁøMÀ#|`J–Á•@Ä•V_qeÀKæ»w(„GÀI¤f^RgS@(¯_BÞrN@ „ÔøãG@ÏA<¼(È„@©d~Y7@Fí,¦¹TÀj¡@ÜŒÒO†|@îKŸ§¦*…ÀâkÓQñˆÀÔu Ê }À‰ãôBÀ¸ýh?ÀgÞl/;ñ†@Fí,¦¹TÀ>ü!@ò:ÀÄw}rºNC@µˆwZý?@r&Ì•B€:@T‰w×…†@<Éu¢°ƒ@»‘D„ ìSÀïì˜à?¢@dpEm£6@¶ÁÎ'ç‡À=a8B7„Àk¤B¢°”À¨ü#ö´BÀòbp›ÞY@Àe«º¸/ˆ@»‘D„ ìSÀ9 ÉÙÄ–<ÀÒBÄlKC@ýj‘5³@@|¶áù2=@q¬EwIb˜@›÷ùzû{–@ïD/…cÀ#)ÀÏF³@{"/»”@Û•ëªú˜ÀEïç}—À „V =•ÀÃüDì"TRÀRú蘘æPÀªzØ{™@ïD/…cÀ7µÐõ+OÀ¶˜õ"­ÆR@ª£w6PQ@¥e¦ï×íO@môÎÖ^š@íØ×E­¢™@€UpÜú bÀýçtñ§ ´@¯Ãë˜@{3³ö›Àš_|±–XšÀMê‡všœ™ÀÓÙ¯ïÈÑQÀyº|†£RQÀÙÒ Øš@€UpÜú bÀUfU ×PÀ{´Ó;PR@ Èû+ÍQ@> KâˆNQ@Ö¹¦µ||@ìÀ.}@ÂH‰9Eõ@ÀføÎMß•@¥„&%å}@¶ŠW¹`}À5—sKV~Àt¢}×nÔ~ÀÒR4ħ)1Àœ‹]ì”1ÀlïêdhD|@ÂH‰9Eõ@ÀbƒdÏ2À Xq³1@:Ñ#¢¦!2@vÎ~7ù’2@4è×Oï¼~@zsà}•€@Ì€ZŠ?À”(Bo@–@µ•Tå@/´xŸ·ÐÀ w"H*À5œ¨…‚À!É„31X0À™NÑ õ¢1À~"’›Á}@Ì€ZŠ?À¡‹ÉÞ3Àb˜åÕê0@œ;u1A2@éž/Y²3@ªµ¸Û% @-fÄ»gÑ¢@A <Ôò\ÀQeâàn·@ì¸6@a¥@8ʹ5¡ÀLôß—…£ÀOWLSú6¦À+@k³NÀ-1=ÿ³pQÀCQ±dPŸ@A <Ôò\À‰vˆÐSÀÜ­sÝRæO@Á°x R@jP‹Yœ–T@P¼¸ÿSï @X6Ó¢L°?q àó2A@ÚZê cP@ÀÐŽ«Ä|T?zbâ›úë À8cMG‡J°¿ÒÓô^zT¿ÎH£gRÑ @k[q²?*^R¢ù3R@²µ¾H 3A@Û’i÷¿ÃV?¿5¶™Í À  a²¿ ÒaÏÀV¿5Ü·Á’ðò?òLüæ‘ú?eªÂ%@AÓùbÈõ¿H.…ö¶G¿ÐFãÉó?Áìõæ‹RŸ?¿Ø5£A6@»¸Ø?Â%@™dÙ8ÊH?ÿj:TºÆó¿Íebu‹MŸ¿ÐÑŸØÆH¿/rMÏŸú?ñyÈNîþ©?ém‡,ß*@¿mʃ]ó:@è bY?6ìûì™ú¿A`êù©¿zÛ@ª]Y¿<ö§|wú?~G·¨HØ©?!q LË:@€»ŽYß*@Ò{+ÕÒ\s~ã?Ĥí%J@µ(è8ýª\@ÞvWΣ?Ud .ò#ÀÏS|Ãwã¿aó€sG£¿ÛÂ|q!@&sT?á?¿Ýì Y@M+œ¥jJ@aC ?>$Çk!Àš'ƒB1á¿o`ÞÜÙ— ¿>?ÖºY)@S{€º_Tì? ›¢/›±N@À&Oº!À`@ž 6a«ý¯?Ò…–ÏÆ )Àp*¢ Iì¿ë·vñ¯¿Vîæ o%@Ö»¾ 24è?º@_Fd¦\@âÐtpê±N@S˜µýT«?ƒÑ]êÞf%ÀÃVσõ*è¿ÿ~J«¿bUakÿ/@6þä-#ô?~Y©¯×Q@úëlcc@ðX’£Ýº?bi{ù/Àz„ ½ô¿¦± Ðî º¿¹³[à *@Í`èá àð?ÅKuUE`@Þ ŽQ@ÂÅ|N~Þµ?ƒR"ö*ÀIQ:ŽÙð¿ G½‘TÕµ¿e.`8#@ ê\|ì?`[ïC@-xJ*@V@ï%jñ!¹´?“Ç‹”ý"Àn¯»ì¿"ž˜¸¯´¿sä×'!Z@¾$t1Q#ç?8D^R@õÖÓGïC@:ëÏn±?Íh«äKÀ`QiÏç¿8W­ ±¿Cz¶Ñ8 @®BÝF;²?º?á¢ÊB@ú}P@8KÇ\¯¹X?ÚÐW¸$5 À7ƒ°)µþ±¿Èq 8¶X¿c Ö@æ‘]~¸?göÿû¶U@¢¸3ùB@(õÛmÑ`?DS‰ÓÀPà ¥îz¸¿KqìTÏ`¿…:›Ž>ó?üD * ?å…ÎÓPÏ&@ Y€¿FÊ4@ý)©(~K?ÛMV 󿨮A¾Þ' ¿² *yyK¿¿o>Ì‘Ú÷?¨¨êålH¤?rدõC:@o1G¹‹Ï&@Ûê‘ ?Q?ÄmáÖ÷¿ b,÷÷D¤¿*òF0@éF7.@#,@¾UÎGÁ`?i_ùI5ÿ¿#Å­„²)°¿)(úß½`¿3ò¾Î&"@t[~tlÖ?XvÑnQ@ÔÁ¢ZÒ2`@~Mè¦"ä‹?'oHÛ"ÀWFö}gÖ¿»¢·‘}Ý‹¿“y=æ©$@ýq`Æœ÷Ø?Sñ•Èb@ÇÛn^;Q@v,÷•?Àôæ¦á $À £ªñØ¿‡?$‹ª¿**u/Ü'@ØQšgé˜á?U3vH¨AT@J#6êc@q™áàíô™?EAcv Õ'Àç7”Ὲ1éWË홿R£Y'c)@´øÐEB¹â?_™a€´ìd@W¦%–ÜAT@ÍýÃÇ@ž›?ùª§â,\)Àþç·´â¿ÉqU©–›¿ì“gÄ>í.@„w Áê?ÚÞ ÌW@êÂa‡g@%k %§?—Ž"”ã.ÀE;ë8¸¸ê¿/ŒÌ§¿aþ‰çø§/@4!Sçbë?´ÐA–kh@oP¨QÞÌW@¹º*Áۧ?r¸ÂØž/ÀëÛ‹˜Zë¿«Û^©§¿É±’ph°@Sä¦}ÉÓ?}Þ?½RЦUªê¿JCyv=”¿>_´à¹>¿qþ»àÍÿõ?·¸D"IJ ?  US·9@êÜbDâ…"@Ï rpYI? í6lüõ¿äR€3° ¿¦”ôŠUI¿°“χÕ7@K­§?¯¿Á?nã:ƒG@ ¿”T@ˆÏ7Kdp?î™Ã`N4À±“¶%m¼Á¿‰x3ãHap¿ð7Ö¯p¯@>oy÷ý}Ê?œÒ ¾É?^@bœ°3PG@¸êØHxwx?åW²Ÿ,ªÀÄ{†ø yÊ¿ªJÊyúrx¿øcÔÏ€¶ú?Ëóô•¤­?Jb¥T¸-@Îõ\{©Î9@ ñ)Cìq`?m+r¼°ú¿i£ìc±­¿‰ƒ€a_n`¿þ&ûÉ­e@C¥°Äëi´?46ˆ¶Ã¡A@“bL -@Ÿ¢û¿¦f?ZÙµaÀ·Ùe´¿ÔÙ­Ü¡f¿xR*âM "@ K6_$Å×?s‚?‰xQ@³§¦zŠÂ_@€’ãÄšS?ž;üwÊ"ÀKøÎ¦1¿×¿)FúÃK¿qÆÉÌ?'@Kª¸ß£Þ?Ø^ ,cd@õ]iã¥Q@@X ¬·0”?´÷Poû9'À¹¬_°4œÞ¿þ#Fª+”¿ â¿ ”Ç'@ÆÙÅkâ?ì¼QçT@ŸSDîý:c@VÙ¥ªˆœ?¥*NjÆÀ'ÀdöQ¾Íe⿹ÃêÜœ¿=‡v^ý,@}Tø%tæ? Dsûfg@ÅžJQçT@Áïä’+d¡?2iú#õ,ÀÎ&¹mæ¿Ã€BÄ1_¡¿Jÿz¹@D‡*¶Û?{ /–ŠH@ßVf÷V@å^Tcþ˜?]½ “¯À<µH+­Û¿Í¨ƒQö˜¿<¸·qÛ!@”vý+à? †i׋¬Z@†AÕŠH@66 ?~V.½Õ!À ~Xøà¿@5>;¿kzœB‚@µÑÄ„kQÔ?!ÜêP}<@yÌ~·K@Î5a5,)•?Jו<{À+º…èJÔ¿¥êOì!•¿íÛêbÃ@’3V1|ªÖ?U—¿«8N@äóâyš}<@#â²t+›—?hé»À©þ/S¢Ö¿ °Ì«’—¿/ë5Ÿ!h(@ÈW¬ý•!í?Ò˜9-å`P@'3@p¤_@³Ñá“b±?yb5{s^(À|J´'í¿$,°®[±¿-¢}D*@@§Y7±Yï?g«[Ta@3¡‰waP@•øo|µ²?q³/‘¯9*À N´BMï¿Y¿ÞÒ1®²¿r’OQ#>@~*|ýx@Ûh{±L­b@çÏH"¸Mr@â»R`ÐË?›ÚúL>À<âÎ &pÀö¶:]ÄË¿¿WÀç;l?@•¡W?lX@ßc$ds@ÎAë|­b@¥3îÿÌ?]ç¢Ò©^?À'9kP4OÀ#ßhóÌ¿3+ˆCþd2@¢ßØ“ƒEü?¦Â}ý6%U@"[Æïe@1‹Ù‚Þ¹Å?žaãzq\2À1#‹ƒ_8ü¿{É}MůſchKš¥2@AöBßШü?m» µJe@ºo¾–m%U@5Œ„6.Æ?¤àÍzïœ2À½xç¦~›ü¿ô¤ÈˆñûÅ¿(<>, @ü\¿ªö¶?'–ø"­B@ ¯'ÁSP@~>(u#hc?•/Gw' À0‚cÆò¶¿@wøkÙdc¿SE"õÿ@”˜8ËbÑÆ?*a;º/^@a®Æ1S­B@ÓÀ¼¡Hs?ÔЉ¥aûÀ‚ÃñÀ„ÍÆ¿eZš ]Es¿NY¶M{@A—)ú÷¯Ã?…n¨æÚG@Ps–ª©T@o„Ñœ0ås?œL.×mwÀTu¦¡ ¬Ã¿%¼¥®;ás¿h€û³21!@-艬_Ñ?Yuza@Ÿ§Ò@$ÛG@a,u¤Ž?¹EeÇ-!Àgöü7\Ñ¿ íJ&‹¿å<ï ëó @ ­‰§"À?0²T ”=@Œ¯»°I@ž‚˜§Qs?¢æ´í ÀúåæïÀ¿ò–k33Ms¿øbï_= @“ÁúÈ‘äÉ?i˜Â®…T@½Ë2´Y”=@ê?¡ôk?ß`·Ì@›Àº¡¼U™ÞÉ¿{ ïEù~¿‚Õk‡Õ"@H ÿè&zÙ?]1¹kîQ@`nNÉ8n_@ÿqà é‘?ü "À¹<ÞksÙ¿ßT–Nä‘¿‘5-ã*@æ”/{Çæâ?AWàÕíùf@äðšîQ@£¹/ÒE“š?‡¦zÇýÛ*À®`(Éáâ¿'5ý‚@Œš¿!“¯ íÌ@ÇÁQ@æ{Ã?e¦‰©Ö\5@®ÖÊóB@­ö’Úæ?ld²2ÎÅÀBP0þvÿˆ«ŸÝ¿8>ù;€ˆ@§î3ÅË?1Æü1 J@^jÒ ]5@kkÈø(†?ÅL ùƒÀÙ–ãû« Ë¿›¹J‘W"†¿5ÈMù½¦.@EæKoþì?ÂøŠgY@ZB=‘f@¥ÇZQm«?äÙ'myœ.À Ïâ¸ô쿞·[âc«¿(·/C!4@„ëlš ó?¢Ký9¡~m@¥L”1ÑY@À‘÷&²?2&ê„4ÀFŸ€9ó¿œdE‡úü±¿Êt%ah3@¨–›”Âõ?R‚÷ ]@ÿ´Ÿãa’j@"¯'8Û¶?eýÜ.a3À‡ÎR€òõ¿+ ‘½Ò¶¿)ÿÐH8@?iˆª”Zú?/‡×@”p@_¸B!]@G ¥}™¼?u¯lÎ?8ÀëêÄÎPú¿Füæºá޼¿˜¨JÅ8@t¼>•õÝ?ýûFŠÀ½@@é#(úCúN@Ï")‡¢?qò­Ìí.À² BòhéÝ¿mêaå¡¢¿Wý½lâ @)îùG@÷á?hXMÄ€ŒR@´"ZÄë½@@—Ëų8¦?…­À`/f„óïá¿ÜÍX¬/¦¿çPÔQïØ-@¥­Ë–éô?ÒˆpÞÜS@¾uŸæa@7PÙ„ðM½?ÇbSsËË-À¿$…éaàô¿—ßm× A½¿äMþ=1@ŒƒK)ø?ÐNrIæ©d@ rt#S@]€;!³íÀ?¤UöEg61ÀQaÿ§ø¿åRŒ??æÀ¿&†Û8/"@åawtñµì?Ÿð2N#—E@ÒV2…T@fE6ÄDª¶?còå£&"À}Uõìe¨ì¿O"´d“Ÿ¶¿o©Çš½R$@{ÐJŸ3 ð? àcÆ_íV@²ª› [—E@ø‹¬ ³T¹? 'I$ÀGñ¡ð¿tl¹Ì¿H¹¿TÙaû?ÕLª?y a~g‚2@ȆBs½Ý@@HJë”X?Üý„‚8‹û¿çm`lª¿ »pÚX¿fJ­w@Zi².¿?VQU‚˜Q@çÄ:I—‚2@wöT]m?X?-btÀûÂeˆ½¿¿%ÿçyœWm¿êd•Á¼ó? Ãë¥?¯î3à'@Ì_îŒ5@´B¸uYX?1]η󿞉Sg祿 ûú¼2TX¿úÞü}…@ž3d³ƒË¶?¾L©³RD@!¾pà'@É54Ri?cDÀ¤õµ–ƶ¿£`ôƒ‡Li¿Ìf-T:9 @„ʼŽ"¬Á?•÷ép}È=@ž‘þUÜI@BDhÃñv?^QO€2 ÀÖé̱ħÁ¿\kôìv¿En£B>Y@º{¤|ŒtÐ?8ç,¨YÌV@a”ÐWÊÈ=@ý¬;º9]…?^àO×úRÀgÝ{pпùìÙWòW…¿ŠÆ*ßö=@FáÖ>€»?~vdÀ»2@-Šie?@àKUt?–UÜ8À ²]3]x»¿<ƒ·ýµ´t¿†õôA@mìç.dÇ? àˆÉI@ÖùwŒê2@HöjŽ¡?4Åã’ÿÀØDû…ƒ]Ç¿kY”_Ÿœ¿äÍ.Äêá@#ç+ÄÄ?¯7@¢¼¤5@4 ‚ŒÓB@µÑ„‚?p>* lÚÀ¨Ž?ˆ§½Ä¿“¹iÙ‚¿»Š•ÉÞÔ@ÒK8€×_Ð?QÌM@˜òÅ„ô¤5@Áºž=ÇyŒ?KZÛõÎÀñ Uú³ZпƦŠ~×pŒ¿<·V`ª@&B(qÌÞ?ûÁr®uI@ñ³®v9SV@ªa—c“wž?«HË”jŸÀ“o3w%†Þ¿¯2ò3õlž¿@g>c«&@yDݦc˜æ?ìé¶V‘D`@)Ë kÃuI@‡æ*Z¾…¦?¸“Óû1£&À~£Wăæ¿^J)÷ä}¦¿S¤«]#@øIò–þå?ûÇe``”M@mk¦ó©4Z@Yf«û¨?§ÙÜœU#ÀûÕ(ö忺ÏöDò¨¿>³î¾+@ Mw Áî?dãµÍÎ'b@cò¼À¬”M@/½Í·¾w±?/%¨^ +À k³B×µî¿P¯— q±¿1[•Z¬(@þ˜rfï?×Vý âQ@g±_Ôz^@;ÍöûËø³?Á|(À¡8,ûî¿`˜þv𳿠\iÊ?0@W3Ÿd¬ªô?m2fÞ°.d@¾û Q@;Û«šº?°*Þ 0ÀðÜ2 ¢ô¿è&–º¿ÄØÌ)Õ¤@++ê‚å?X•þìcC@s e”Q@wD¸ ¶5¯?0rª—ÀºñNZxå¿wcš»­'¯¿Q~çé"@äérë?óú8#TZV@a•üIcC@Wj¤D­é³?ˆyœ|fá"Àôü‰­eë¿Ù¦õB¹à³¿qÊ{Ÿ¿"@D 1šXí?yûÓïE@¾ÆÔÞ T@;›‡·ã·?#•î‰þ!À,ád‡Jí¿¹ú9¢×·¿¿™áÄz$&@'o²ò?W/·Ôß«X@ѪuWïE@œ˜¾AhW½?É{YÜ&ÀFu÷^ýñ¿pÝ\VI½¿3fÕ<“¼ë?.ö¤Á—J?æ²V¡"@o±Aœ§ª1@tÉëîN?—~7×¶ë¿[r‰D¿}|“†èN¿–àûhð@üQ%yµ?€Sã|:D@ɤçÏ"@+VA¾šJ¬¿P‚úoéZ@+w­O ×? µsÙ=@S!$OµþI@¨øŒBŽ›?öÂc¦Ï'&E ?uÊô5ÊB!@ïƒÕ:ð·2@mÜýn2S?É63îë¿x|æÅqA ¿Ùƒÿ.S¿ é¿[ô@[$t.ÆC¼?Ë©TJG@¿ïŠÇöB!@®äbø¸¬p?|…†ïÀªOE¢V=¼¿–1í¨p¿e8ÆÓÄõó?øM§/Ïëª?‚Ç)ëú&@¯ÍI¿Š6@M0q«'b?Œ<­ðó¿í䮬ð䪿¨ @‹ #b¿¨ö³=‡È @@ß\N(iÃ?Xq×ÃØI@‰2ã>?ú&@Iq^Ñ(.z?Q- /Á ÀtÇ®`4dÿ^A~²z'z¿±B¤S˜@, G 9Õ?NçÖVë9M@!çà‡Ì[@~gFqR?Ö«XzÀ´ºoÁÿ2Õ¿¸w¤ÌM¿.¢ •%81@5¤p|ê?™u×ÏÑl@°-Í6:M@F bT´^¤?R¿,›?31À¿mâËçtê¿ñéèX¤¿¿út–u"@6gMÙà#à?Çö6”IR@»)sZÁ`@üZ’…9œ?ÛüñÄo"ÀñÿzzÊà¿#ÁG 0œ¿]+ ߀4@ÈBP kíñ?=¢‰Õíp@÷u×xR@ƒ~O'¢Y¯?¾ ¢hz4ÀUÃütÄçñ¿W&xÀO¯¿ËãFt@Ù†ÐÛ×?îæÌ»²E@nÉ´ßS@Ë%½L¡—?gÖ“« Àà}èrÓÒ׿‚ l™—¿# ¥†ûI(@%ÖŠÊ!è?©„JÁa@)ÔÀQ²E@ᨥÖÔ§?j!岎A(À¬ ¢`Éè¿i  t’̧¿l6ˆ.ÀË@e&Úµ6á?Ä*"¦•«I@´µÎÑ^IV@Ðz_\>£?5 ÷ïÀÀà»<00á¿–Âr7£¿O5͸©Ÿ,@|ìÂÿï?Õp÷žc@-^î׫I@x–e×ßâ±?»€/Ñ”,À!¸>¢óï¿ãáVÚܱ¿L° ]@ĹbiVØ?æ.‡ò=@ÊË”ôîI@š­À–ž?½\Ü,UÀnH£jLØ¿i ´0Šž¿­Ê¾bÇ @C§ö±å?n™Œ÷žU@¨ŸnNò=@ß:êZfª?*žÞ¯~À À~®aÊå¿ÆNN®ƒvª¿ÉZ!GR@ Aæà?t«M‚ÚCA@ý³ŽFpõM@hzâÈɧ?>Š‡Ù¸÷ÀQ,”=œÞ࿾éxjH¿§¿Åø=üp’#@g9N`+ë?ÖÁ_‹VÂW@ùç¢DA@º7z^Zd³?ä’,͉#À\1£™ë¿á¸*¿Ê[³¿A•À~Lh-@Æûk®÷?_´¾ ·S@ƒ„¤ÓÝ/a@pÕÄïÈ#Â? ßBÁvZ-À‹™ÁÐ ÷¿«c<@¿´ìîP*¸6@ãòVû×@×iž_* j@‘¸Ü ÷S@eÓëTÌ?¯òœz­6À•®M–ÏÀŒåž<%ú˿ͮùè{Ñ!@ý×a³ï?mRãOdUF@Cµ½n˜S@.ñ»Eû,»?®g±¢È!ÀÇÐþ=ï¿Á!Yt{»¿[à߆ @*@΋€Ôfìö?ãŠ'“w\@ö\‹úUF@ºíÂE Ä?“@]3*Àûø Ááö¿Úl!©®úÿdEÈåý @3­Õ¨×¿Á?òØ)\¶3@@C¸_(T@í1¿€®Xw?dNKÚFö À Ÿ~h»Á¿Ñ]aÙRw¿ò™îH©,@>(ÆÿTÇâ?müÅ4Þ0j@p¦Ï1à3@@J¸/WB³˜?:âN&‡†,ÀDW ¤Ââ¿—Õ¢­˜¿- |ØÑó?ë^ÜS8q­?ádâЉ&@“ ÍÇo­7@P3#iIÞe?»:¬]Ìó¿@Q’ri­¿xš­š=Øe¿%Í=Oìä@ØíÍ8±É?/ò‹ M@ ÅÔÂ&@¬jNô£‚?”@àÀe´•îÀÉ¿‹öÌž‚¿„™×l­“û?3¬‹Ùù·?eÁg},@°«2jWü;@‹¹—B]s?M»›E‹û¿?©6£î·¿?‰H-¨Ws¿pú‹‡jð@šï+ñyµÐ?M‡›…P@ ±—h},@\,mŒ?‡¯VêÀ_&b°Ð¿ÜõÊHyø‹¿HuT7~"@ý„^Áxsá?±c[ô¼¸Q@þ•§ÐOz`@×àûìw ?W…Ø=Øw"ÀÑ›é¢má¿ì=)Õjr ¿·-!>;t7@º%ñ|'"ö?ª}S`»q@%7~¶ê¸Q@³¶êîã´?â'ìˆcl7À sÂÓÀö¿ë?ô Ü´¿†¥„_#@k’öDÖÉ?Û Å|áz5@¹U@7šMC@mV® Ñ ‹?0¾ ³CÀ1]GnÉ¿§¬"ì‹¿Ì+þ ã{@Õ*­n#Ý?yÐ-ã…S@xœ7ó{5@}`ÒeÑãž?È2ÝÜqÀ[µHã~Ý¿Ôб3Øž¿QßÁ,Ø@“±ÎQâ?átãp$‡I@:+U —zV@¯À„¤=Á¥?íxÍûËÀñ1›IáI⿎+;¤¸¥¿ÁŒÄ 0@ŽHÔd ó?LmÜåqe@áà[f‡I@[\¸ªŸ¶?SÅm0À2ÉAIÝó¿²€ÒŸ–¶¿D$ ±&_@þ«©¼³Ù?4Ù_ûÀß=@Ü‹hìJ@¨,Òþ ¡?„ƒéVÀ£øø¨Ù¿p:û‚¡¿=à ›ý£"@HeÏ$»ºè? .a%€W@`Xà=@UhŽàOg°?„¾›œ"À;°6°è¿eE:uU`°¿âœõü7@J‚𿈷@¹wƒCa@¨h1ˆUìm@÷:¸ÙŠ,Ê?ç„×ì8ñ7ÀmƃÔ{¯À6ÿ)¦ Ê¿*G[a“E@P˵6îß@G*’±y@"6 °Ca@“´‚‹×?>D–“‰EÀíàÙcrÑÀöV¶Öπ׿>¸Ó]U=@¹Z9<@üÑ­¿c@œ»ÎTq@m235ºÓ?ëGø‚>G=À¾if§À¬êÒµ°Ó¿á©Ç;ßH@D†ÿwe@µÿzW|@Z)Ïà¿c@)ÃFuý¹à?#ßšÝÓHÀß¼+¦[ÀNòîï±à¿Ê!Q %¿!@ÅFÝð?­ˆieF@G9üìrS@d„¦œŽ>½?ó6Ö+¶!ÀÁŸð¿s@BôÄ/½¿‰¥÷蘎,@éz®ˆéëù?Ÿ›ËЈ‚^@i®>×eF@S“1~‡Ç?Ùj:(€,ÀÈÎÞù¿Je”Y˜{Ç¿†:O½Þ @ÕÿîýèÂ?ÙKœ;-¼=@‹O9Îÿ‰U@Àki1¥{?{ î6®× ÀBåYÕã¿cwõO¦{¿Æ«ê—´á0@*}¢G®è?ýi“1vm@¼¶·z¼=@üÚøøB ¢??Ý\Ý0À,û£SL§è¿ðu§ÒV¢¿^ÏKCRqó?Ÿ±ƒa¯?”ùeæ$@²¡›ƒ 9@*öý·mði?<ûëíƒkó¿@¦Pœå¸¯¿,¿®èi¿ *„¾­µ@W STÐ?¹£Lƒ6P@ê™u]Ææ$@²¡l KŠ?œ+mÿʯÀN’´6пQÑØ7ÆCŠ¿Ÿ~¸FÚY@B:…)§õØ?|\ 5ÞuK@ôІÅÃ2]@ @øúÆ–?ve¢ŽðPÀò\ñ„íØ¿Bí™ÎŽ¿–¿¢ ¤Xzú6@ÙÔÎL&øô?”½CÐq@‘?­%vK@û>ƒÊ"³?׆àfýò6Àmú/öPñô¿™ƒý޳¿É8£Üo@Po8E?ÈÂ?T4C²úG1@lQ\M2ÿ@@ò¦I"ƒ?Å6ÛTiÀa5Ð.˜Á¿3È¢‚ƒ¿>W§»@h¿Òä%;Û?WÝn†>‰S@Ï”?Q'H1@ã+±½›?ˆ"ŒI‰±Àƒ6´€1Û¿üڔݳ›¿5gÔ[Z@Ð ,È cÛ?Éoù–wE@qÉËQ™ºS@uáyNŸ?G«×Àõ>®¢XÛ¿ÉãVd Ÿ¿y¿/@ã1R›ñ?Á…â<_be@ê×£®E@õõ9,þ³?-BâÞö.ÀÜÛ)Y“”ñ¿§„Zƒö³¿r:å™àÖ@U®»…°zã?¿p…:I@4F€ÎV@9[TØ‹›¨?©4±S+ÊÀÅ꣩rã¿·Ç"÷g‘¨¿ ôâ›éî1@(oz’§ö?|"¥š\g@j ¼3Æ:I@+5pž¼?²ÌÐ…ç1À¤DýŸ<žö¿ G%,¥’¼¿/DSnÌ\3@šp<*â&û?¶yÎU¤]@ûË^V4Õ–¼¿t(€\¥C-@¼ïºGùù?žê8²S@r,B˜a@¬=1ä‡Å?f4î;5-ÀMí©œ ù¿îª]¼I}Å¿{¸~Â)3;@—ꥪT@XÑön@ÿÎñÅk²S@M‚øÔ?M[—Ä%;ÀûÉçE-IÀVŒÆÿ5ùÓ¿­DÃÝû®1@\‰ôöç¶@:{zÅ_V@hÏPÌÖ`c@e˜Ø˜Ï?I‚ÝÌâ¥1À¹8î‡N®ÀkÍ?ù–ˆÏ¿Ÿh"åÕ ?@ªÝIÄYW @GzFkRp@ÿ;ð?ÿ_V@y‡Öñº»Û?Bô¹]Ýú>ÀSYÏIAH À 8$=v­Û¿å.'ES¶È3ÀTÂóð¿gá»ï©¿ðÝÎ^Èò?Ò—úˆìÔ°?Z1r€½r#@Ë}ÐÌ…¨:@¿Ûµ*n?ÔDÐUÂò¿$³„ϰ¿íxs!n¿]ÓÜ,Ú@ߨ2„zÔ?¼Ÿ&Æ ÿQ@õÕÛ·ïr#@zvZ¦ùY’?ÆI: ÕÒÀ•´µïsÔ¿Ðÿqne@A[ÔÝ—²@@ã˶™U²?"žÓjM.À+ò ^Ÿ§ð¿Ä1~¼N²¿ãQ]@÷Èö!2Í?þñcÃQ˜4@š! GD@µxáZØÁ‘?°¥¸öÀ}¨£æù@”a^kˆk@áGªç˜AM@m®†w/É?-·˜ðCØ6À­ëœ+òÀs%G£þ#É¿Ž÷XÊæ7@,¾‰«r‡@ã*WAfa@ôAcFn@ìTû êÏ?!Z¥Û7ÀwѵJ~ÀÈî² ·ÚÏ¿„^­ ·J@§Ä¦ V@ìyñÛ·Õ}@¾Ô1’a@ÕõlÍoá?…î*JÀÐeÛúËKÀÃx2£fá¿,Ô8Ó.@Ø“…V7ê?ðNs¯C@„:¡àï)Q@¶Åžd£Œ·?ïL!# À}—êè)꿪 ¢(É€·¿ë b42¶-@xÃ0µ°ú?/àkû†#`@£ùu27C@°¬¦}àùÇ?ïâú=§-ÀMªäCF£ú¿?ô»FÏíÇ¿8—¹ž!@½õèÆ]ñ?:èá¶DF@RKºlaS@$š1ÄÁ?¬m‚•!ÀÃ9Êã±Tñ¿!4¦ÐÁ¿”J§DLÛ0@1ÝB|*@†ÇÚÁna@ñðw“ïDF@p·í_Ð?5N(|{Ò0À"U2z”Àghs]Wпp0E˜3ï'@à bËb´á?ÂñIþAPT@¨q›ª*³c@û(Z1š?ð„´?›è'Àãæ¯á¿¸g€"*š¿´Ñkð‡)@IU³F¼ââ?àûƒ:e@ d¬qvPT@ÙœN¨ð›?×ò¦rç€)À‡ø|ˆÝ⿜×Áeõ蛿tváEå\ @­Ók3É?8syVÙ€7@CcúçÆtF@‘޹¨ø …?nYWÆS À+}øÚ—+É¿œ«½@š…¿0¡ÛÆy4@dc£¦èÐË?A UÓÓÇH@*öX7@ÒÕY(߇?åb (q/À¦¯ì¸DÈË¿ø™«Á%؇¿˜ê¡ ¥Ð!@”9R2—á?e|O­·òJ@ƒÊÙ nY@ÅÔ(Åx^¡?¾¿ûîzÊ!À?yÏ‘á¿âmßvX¡¿©êkÎC$@î'.[8ä?LyÃÞ¥é\@9à8BýòJ@Ï›„ ²Á£?‚<«<$À‡qÏÔKûã¿ñ¯ nܺ£¿©j2¡4h@/ÿ„»Ç"Ø?ëˆïµ§>@VCÓE¢L@ä2]g6›?€Áu‘ `ÀÏ œ_”Ø¿Y Ã,›¿o³G<2@„•L2Ü?'ž]‹ÃµP@‡»T¨>@L<ÁÀnÊŸ?é^Àµ©øÀ„…õŒ'Ü¿›3_P¾Ÿ¿*+›áª9@ö«8–ÀM@ƒP|ÞPa@ôòèê³p@ëàÅnXÙÄ?¶Gu9ÀKº¨ÍúFÀàüpJ¯ÐÄ¿¿¥+™D‚>@g$GéÖ@ŸN3x3(s@8ž@2 Qa@H‚6òÈ?þÈL3˜u>ÀãµUv¼yÀÿ´n³çÈ¿v ’".@ÿ®ËÚ­¸õ?CéçcqS@©zÈÜÞa@°~à‡ÃP¿?fÝí .À7¨àUó®õ¿ÿ€·ú¼B¿¿c­EðVk2@œy{L Žú?I¹­p§Íe@#ÓN•qS@ÒÜšðT$Ã?hiÅc2ÀΖ'‚ú¿)b-Âÿêºq4 ­1@ΗÃ@Óü?cüT#n¶U@†ÿ8}Ôc@nm Ç?Ãö¢é-¥1À6&ƒÝ†ü¿S1¥>Ç¿ Ç#± 6@ÿ$çóÏ@¹P³±§h@z,Š3¦¶U@}ì)½@ËÌ?Óa™š)ÿ5À¸Þ¬5qÇÀ•ƒ±Ö~½Ì¿p¤žÝ¬›D@ Õi$¸•@ì™Ö !h@£ÜÒ:êu@9gƒ„Âà? ÞêH‘DÀî¾WYŒÀêP:*ºà¿ÿÍ}ÿ¹&J@£wVgs•@Î΋ò·{@Aæ¡#L!h@”…M„´Då?Õ÷¨“ŠJÀæ(`‰À~ _Xû9å¿irªÑ¯á'@ŒA.ì÷?ßx¾Y²J@È™àÙ!X@ÃS²öÇ?¯þ¥¡Õ'À\ÛÏç˜ß÷¿é!RÈêÇ¿XÃ9þ‘Í.@ÛËY{Ûþ?¼2ºâ_@R:/­ž²J@Æ8vëªèÎ?Äb§®]½.ÀÞ6¶ àÊþ¿n? ZhØÎ¿ÿÎÛ{†+@oå¹x€þ?1ÓÒskM@)Mb{Z@Y÷çmæÐ?¨uôŸŽw+ÀXõ\Fîoþ¿lÂ'»CÝпK›Nõü2@†0óÿÒ÷@|éiñ@a@qî|¿kM@‘HZeš Ö?×­°b7û1À¶žëéþìÀ…Õ?‹šÖ¿$¥ý@ÈY<¥º@[-rƒùno@rÕlóÎýY@œ'GºvÞ?9³\—£í>À‡(÷è©ÀfÚX¨ÂfÞ¿¹G.*@Ts¾íœü?¤ã L@J¯‰ÁahY@;=c~]Ï?ßVË´ *ÀIí0€sü¿ŒÖöЇLÏ¿£8Ù¾¡2@Ì]K#Õ@7XFSva@±ztû_ L@%h ½Õ?a\ØÔØ 2Àò8piÊÀÎ`ν±Õ¿¹(¿ª.%@0ÆR.©ß?ÁµhxŠS@_‡]p¯a@ØåëÝݸ–?CÆÈà(%À\Qo†.þÞ¿Å+¨²–¿Jk¢–*3+@;ZìΆëã?ÍXå÷LŸf@²S-ìOŠS@ºí@3Z-?%Ïž»++Àà ¡'æã¿©e.å`%¿»±¦ï{@üR¿±%Ö?Ëc>‡F@P†0´CT@Ž}Å¢¤Í’?ð÷$‹s À•´1˜<Ö¿š¤ÚÇ’¿åf§ç!@*€}8lÝ?ëØ~}xZ@µViN‡F@ ʳ’®˜?©=¢!Àu9xÝ¿Ùj¢‹ø¦˜¿?Ié¤.½@‘oæ¬ÑùÎ?LJ¾…OÁ9@ÊRä˜Ø G@± î9';Ž?Ë;„K²À£Ö1ïο>›þƒÈ0Ž¿‰ Ø|=@‘«äs¿ºÔ?éï2‰$ªN@O£’Á9@£ Î&;”?™‡¨36À@.£³Ô¿—¢<64”¿< /Xs@–Á´YGÕ?¶èw:=@»+7T J@9xí„ò¯—?õ̼:À¼SøÙO?Õ¿|U»ÿ¦—¿»”Ý–5@L–ˆ‹úÜ?xJó$œQ@¼¨ÕïÊ:=@í5ÿ!! ?F›4 `þÀm™ïÜ¿Ëʦ  ¿ŽÐ[ºZÐ@¨°D×`ÅÜ?~±:;1z@@nÐ+ß©CM@á+•N$¢?u}1ÉöÆÀç~u/‰¹Ü¿>ÈñÖ¢¿·ã׆Ύ@ Q3t*æã?´½‡šT@èKÜÆ[z@@ƒ1žX©?Z»7ÑÀ =U¦ùÝã¿n‚¶L©¿ÿÌ"zS@Xv&Ÿ,ã?}©6ÔbxB@c&¥¡4ZP@;d_x:«?)x*/WõÀ{í–$ã¿ô È·b.«¿kj/@vñ"@à~êuæê?²»ÀÛ¹V@ÌA2…’xB@T ½ë‹³?Š´»ò é"Àª!ñ‹…Úê¿‹ïëÓ³¿UðÏÛçº@•J§ë:é?÷o`ØD@¯ò¹0R@Æ)òèÍ´?YË8¡à«Àzâˆø.é¿ýstM´¿ÒÁˆÕ”‹&@DDmDíñ?(\´]`“Y@î÷ñ÷˜D@YÍ/„M‚¼?/oŸAç€&Àk;ÓÆäñ¿Cð×Ìt¼¿{7Þå„"@ôxÃp5hð?Ï:GÜF@ö &­S$T@©€J-£½?QÑAÔz"Àdq§¬`ð¿Z„‚/½¿+ð)¸‘Ÿ*@x¹STL—÷?–d€« \@MÊA‚ÜF@×ZšqçÄ?¹ËpÜ@’*ÀÓÙšº‹÷¿¥â:ŒüÜĿ¶Á\gz%@»i@õ?)£Ò¬îCI@Ä()Å7V@ÑyÒάÁÄ?éÍ..o%À Qÿ7õ¿Ò “Ô¶Ä¿’{ЍÄ7/@¥T_°þ?ôs¦7Lã_@h·ké/DI@%’[:E+Î?;êÿ3u'/À[V þ¿P¸û ‚οCrŒö‡Æ8@ó…)4é @Ô‰ %ÀÐ[@½åjTPkh@$›·þ:Ý?e!¬ñ)¹8À³w¨1¯Ú ÀN3`9+Ý¿ù?Þ)‹/B@›¾¼êÏÀ@²à‰q®q@–€D÷Ñ[@èßW­ªtå?ƒ¿mU»%BÀ¬Z¬–'¶À"›0iå¿6PÓQHý@b7ÊéŸOÍ?Ä—•ú C@™àAÙP@©m+e}…?ÚóóŠÐ÷ÀS æ`›GÍ¿öXq;„w…¿^Œ–|(@¶Ó&¥Ô?þÒ’³Þ€W@^®ªÃ+ C@2(éΖEŽ?{C±­Í À톮}`ŸÔ¿›þN=Ž¿t¬}í¤@ûP3äÁìÔ?*‚SðE@+¹PçƒXS@)¨íJÄ‘?KtÏ]VÀ&MPæÔ¿¼‰oÒ¾‘¿Ê³’„¡£!@Ìîª9ôÝ?×Ï1 Åb[@þÉ'ŒðE@ò/içn™?’x¼¸2ž!Àùƒ«áÿêÝ¿åg™¿È­GFa@ýÞÍ7EÍ?1#k—9@›ü F@Œq„ˆŒ?!©üîü ÀKî%ü:Í¿i×ù¼~Œ¿ª:Ë¥Ì@Õ~KÝA@Õ?¨TmÜ:œO@ècNQ9@Z¨f·”?Éΰ%-ÅÀ‰gdUù8Õ¿G†÷oL°”¿ã(bv@Öý­ÇœÔ?{OBNÏl<@ß3eòH@ã4-˜T–?ÿš”s¢ÀqXÏ’Ô¿Ãû+L–¿¢¡­ž@²(—e‘Ý?ç”1­çR@QŸm³m<@ijÙk ?¹íB£”À™Ù>†Ý¿ñЃó§e ¿nJA[ž5@^m&%-û?ON I`@a©ÿ´Ýl@e]É®ÚÁ?Ʋ±z•5ÀÞUÕšû!û¿í•×˜Ö Á¿Î—õ@@ò¢‡õ[7@"Fì·t@_¤F`@Õ$CÛiÉ?+”Z@ÀK\˜A/ÀÿÐòåj_É¿3)lj›9@L[y|'@Jõî£òa@@ òHeo@ÈNáÈšÉ?2/uü9Àô‹[}#Àùç¡DrÉ¿îóþ¶?C@¥_ú88 @éNÿ7w@çúù3òa@§x»8=?Ó?ˆ1_{17CÀoø«>t, À£§ë·6Ó¿s9÷¨.@:~êÐ÷?phdT@™ ¬ya@ýQá0i×Â?´)èp .ÀêÄjÔªÅ÷¿>l÷‚ο €5ú—Ø6@ ° õ@â›Óæj@(Ê/ 8T@Éx§ü˜Ì? 03ˆÍÍ6ÀÃ`Ü™k À¨}£6z‹Ì¿ûð½P“A@^l¿(xö@–r"½2f@›=?^s@h½&Ž FÛ?XBƒ™ŒŠAÀÂ÷¤çÀÑns8Û¿º¯åìéJ@‡Q%Ü@´@¼àj#Ç}@uqt >2f@úè¦õ<áä?ý/PÖ¤ÛJÀ6E,n¨ÀÛÛ“äÒÖä¿È‰ôà3eD@jdî` ê@n$­ù…h@‘×ã au@ …Ö•óqã?ÞÝé’ZDÀ«°ÛŒ¿ßÀcAybÑgã¿®d]Î{O@†Û#½@Ò]¬£M.€@ã)9ÿ8†h@Ÿ¯ÐL¥î?– å´jOÀòŸLò­À3þôí¿iêÅш'@­å÷QÝ^ù?LÛ‘LÞýJ@’kcÏì‚W@o檷•YË?P̆ %|'À!ìH4Qù¿¿©=ØÛJ˿ڶ€E L2@Kûè3º@á;³Úéa@RFþ#þJ@ˆŒžðDÕ?@ìÅB2Àà¾#~¯Àç˨ª8Õ¿_*/Òìã@L½É<ÕË?jâ<Ô}}B@M‚ÃÓP@+V÷Ô&„?÷¡¼ÞÀ-„s˜ÍË¿OípI…{„¿PÁÙUƒ4@ /ý•ïƒÕ?‚:nX@Ù;g’­}B@·óJ`³?a¨D~,Àêðø~Õ¿ü7ò›«ª¿·de`ÕP'@*ÛëDÜã?ûÙžúIU@ÐÏç‰b@€6õÉê ?\a¾T¢I'Àæã"Öã¿ÓHk´å ¿¨3ZÜU52@œÐbï? èÙ½œXl@E—1JU@ˆÈ²9lª?íÈŠ¶/2À÷Ô€Z~ûî¿êè¾^dª¿ƒ×uÏún,@?c¡Y(Äë?T¦PX@§¢Ûì3&e@‹P~&X«?eŸÖ8e,À›Ü ¡ºë¿(Ž÷ «¿Ku«th6@¨N XÕáõ?h§ùivLp@ÂVNPX@áÑ~Ì^^µ?¸9Ä`6ÀÀʲíRÚõ¿¹ú“ Wµ¿š@$Øk'1@ æ»t‘ó?ŒÅ'tH‘[@ó Ä|ög@0çz%ú-µ?ÍØ ó 1ÀÇV}`ó¿ó~&Šü%µ¿0·JƒB;@®$=Jþ?Onq Á˜r@l3~¢‘[@¤ßÑÔÀ?¼]3o:8;À-ÏdžÏ>þ¿bG\u¿ÍÀ¿ug´©Ü€$@ÓMiÌ`Àé?G”Ø=O@FŠáVûZ@¡Fä+°?Þ/n rx$ÀZN­Îµé¿­<A%°¿ DþÓ—i0@\žû ô?,1ïtue@ôñ+ ŽO@ýÍÉùÆã¹?nÛb0À°9‚Ë•”ô¿Rï¹R&Ù¹¿ÿž‹åL8@#>Y¦‘%@õнÊea@>š*Ç/6n@1ÅËò´2È? )Áü&B8Àˆ=WÏüÀKÎZø(È¿n‡ï°}•C@$Q’Þ4£ @ìj  åºw@U怩÷ea@#rpab€Ó?=<üÔŒCÀV;n”ü– ÀÍÃwÓ¿ f£6•<@F½^E}Š@åý fdc@‚¦¦—AÔp@¿ÉÎÆÑ?A´¦—‡<À`9cÜÀ{ίUl¾Ñ¿%Ä·£-G@ÖdxG@bÉ=¶n“z@OÕkw3dc@–Ç<ÈÔÜ?zEèµ"GÀX AÚ>Àÿ’hæ/ÇÜ¿)iâç²±@@an×­I @´Öx¸#ƒe@ãÈ—áë©r@åL¸bß°Ù?Ìã¬wc©@À¼è¼; À8ö§n¤Ù¿¶GB0;K@sÑýB ã@<„G}y}@À{>D[ƒe@ÖöM ôä?õý¢-KÀÙº£4'×Àíc9éä¿Åx‘×5a#@™à>&‚Óò?™z0æÄG@~wޏàœT@ÖÚIÂ?ém!W#À-*7p·Éò¿8þˆrW@¿×UÉÆÇ/@ÂîÂqfßþ?|¨d=m`@65¶CWÄG@ rÜ©ýÍ?¬>·/À¿¼:¿WÏþ¿†Å’îÍ¿zí Gš^F@4¶,Uø@ÈåªÆÓ'j@ ÌíÄð­v@·?4·`¯é?Ï#—”RFÀÙZ©rëÀQ!\E’¡é¿:ƒ5ÀÅnR@QÏo¾dÀ#@ìtÀöù%‚@G´O(j@Ço’¾+*õ?^ 5HÝdRÀâkËÆµ#ÀÝxTËõ¿´~åoêÝ!@úzïŠÍŠÚ?É]9ÍßQ@·^¥†÷^@I.K¼·“?›NÝÏùØ!À…hßvƒÚ¿I.CM“±“¿í÷ñX.@Îÿûbê‰æ?®Ià fi@û9:¨ûßQ@\ý ?u6H£O.Àå}¯ƒæ¿›: g"¹ ¿JžÅ‰@&@1¢a&·ëâ?Æi^(•T@C––šÄÓa@ ïòd’7 ?TШúf &À„€*Øåâ¿ñóø-Š2 ¿”\ð—[Ó2@ÑqmÞ±"ð? Dë…©Xm@j–³ƒ]•T@ò[Nzਫ?ùì*„Í2ÀÒˆÕ!°ð¿Ý öOK «¿ ¥ë¹ñ@ ïy‡ŠmÚ?}Q½™b‚G@mÐøÀ× ±bhÒ¿^ßåì²*”¿äÄ!¤ãó@æq,U%ß?J5tES@Tº$<©:@ú‹ðZ¡?™;èŒRéÀ> ß¿Ûcôº„S¡¿A|nàt#@w•ÄŠÈwè?Ü­=¥m N@xÑñU.Z@Aí®Å®?”seâl#À(ÛÞ »mè¿üuq{¸®¿r¥ã—YÅ0@f µ?,õ?Å; V™e@Åf6» N@”›ŽÑ…º?¼¾y¶u¾0À*¯I ‚õ¿wýéìzº¿aH€7@ NaÊiG@2²¤,Ô`@2«+Óü%m@ ‰G±øÆ?ù´\7ÀJ‚žE7@ÀåDÞF‰îÆ¿íh*8ÊòC@ÜBÉlB& @ DâÂ'Bx@²¥ªXÔ`@Ì’%¬lÜÓ?[¼ï`øéCÀÿ`[Ð ÀS¸¤ÓÓ¿5?Φ«&;@‚i7b@æm-Âb@A©yÏ>p@¾í¡c×Ð?I ¦®à;Àc~R$XÀ)À8tÏпü4üj«ŠG@€§}Š@˜á­ {@—,™Ü]Âb@âÇò~4Ý?¡ГGÀB¬»;ÁÀŒíö^»&Ý¿ÌVÆ¿º?@°™›rà @sÃ3Ðd@%«Er@6bO¹ KØ?Ͻä ùª?À>p2¤µ À-m€‰ø>Ø¿S]AlÕ•K@·.­¢##@YêVS^"~@Åå%ñEÐd@ÏãÏõÆå?W@˜1ˆKÀµ“íJ#ÀR *¥Få¿£DߟhlB@‚DT³eÕ@@$Æø²þf@ò†`i"ês@- ß‘8Cá?ÛšêÖbBÀD$m"ÌÀê«8A:á¿öw˜ËP@ÆÝbY@À‘àÝC®€@¨–—Xîþf@eÆJ‰î?Y*qtPÀt—~Ï3À—Æèî¿\ GN³EE@á>5Áð@»;ÙöúNi@?`iv-ëu@5ÊÌ4è?9èíæG:EÀЍ°r•¤À¥˜˜ 'è¿áEòzÞ•R@ôÊ€_Ó#@†¡&ðýd‚@ä ùO 9wâgZ@öòtL&4A@•M_`Ò‘?’;öfàŠÀFó¼9 ²×¿ÓŸ.CÍ‘¿–’…Æç@;€¶XJÒ?‘oÔåÒC@éÕ¸ö6Q@â€R†8E?¯Œö >áÀË3¢ ¤Ò¿ÂþÂòr;¿Z¨xõñ}#@¦ÕÞ_Ûà?êùŽXb^@®ñÄÓC@Ùk!þ'?Á{¦¢Úw#À•º¹WÖ࿯ު῅ !ï‰@e༇Â8Ù?nºó‘ ¨F@k"šË ¬S@GïÛð—è˜?ð…dÀ MÓâ0Ù¿*¼¯ ùߘ¿X§äd÷Æ'@ݽ@.d{ç?'t]^Wa@°E¨F@¦È.Á0§?Œ$¯»¼¾'À3Mþ¬Csç¿·‘žº(§¿<Âê“Ü@\›á°…Gá?-;ffÓ´I@R¨œ…—QV@£<Ü“rY£?f‹»ÞÐÀÿÂ’÷@á¿Î•mR£¿ÁÇè²,@—&M¸…ð?TÚ•{¨c@)Á~ƵI@| /‚Oþ±?CÃmÞ¨,À1d\4m 𿟻? |÷±¿˜¦ü‹¹w"@5üC·Mç?e¶ý ·úL@ŸSö²¡(Y@½-î)f­?Áf÷p"À¶ê°pC翣ŠZ­¿X\b‰=(1@¼u´¿¥õ?Ï÷ç·T$f@Rx‘ÞûL@Öf bP»?Ÿ"-!1À‘ú!õÕœõ¿DèCyÚD»¿»g9&ˆé5@@‚"ô¤ùþ?Uœ…œ=`@¶`b…2l@ôzt®äÅ?ÈŠ_Õß5ÀþKïëþ¿ž0ˆfýÚÅ¿vºN¯”WD@ѱ›rÁ @ûC'gÍx@_ƒ¹÷Å=`@Yf˜‘SÔ? iàÏ“NDÀ'û}é·´ ÀYsˆ°JÔ¿%n_Ì9@èÐéÊbS@ùîç§òb@S|@õ¿po@²,C)—Ð?R7À9ÀyS)›ÎIÀv¨PøÏ¿׬˛ïG@ÞI‹ðÁÛ@´©‘î¤{@¡.5j!b@MÝI·Ý?«û TäGÀð@FÆÞÒÀ–ÉÀËH©Ý¿²~ÅÑV)>@Éζ‚ ^ @Q:¥+-d@ú°S“Krq@φ¿êî ×?¾VY>ÀÊqÂðP À1š+z׿µ¿ï±àøK@µôÿt@Ì0«~@|Îad@|-+Ÿ›`å?ûzÂùêKÀäm]ÁîgÀü¥eÀûUå¿O:Pü„A@o1´ÞOì@rôëó6f@bQ\iÄGs@Y…áæÕXà?ÇX ´ä{AÀž~~‡ãÀË6)ZPà¿9ßE1>P@•£þVIa@sÁÓ¡3ñ€@á?ØMY6f@\A3ÓOî?"³©BÃ5PÀRK=QÀørÔ@î¿?$’!@ºWÙHæ?ÇuKx³V@Ì¿ˆ<á;@5TÉ(C¬?QèuüŠ!ÀT<k¤?æ¿õÃo7¬¿Ê±Fê<Ï$@o›Êׄí?«Ò ;EO@ÏË7 5Z[@$J*Íï´?(ßtÆ$À÷wñÀwí¿Mã çƒæ´¿Ky´ÎÃ4@T2Tà tý?x[^µL\i@Ì¦ŠøQEO@ÞDsMäÄ?`Sˆô˜º4ÀŒ!ØVgý¿^ÖèÛÄ¿¤ß°Efƒ8@žïËGâY@S¶Þ¢²qa@Ç:€n@Øò]åRÎ?€?ܸÕw8Àj”Ê.ÁPÀZ é~οw/^\\H@3]¢Á;@a6[ 2|@PY“­ßqa@ÿ„Ž´ª\Þ?Òœ}úÝPHÀu­2þ1À ÈÉWNÞ¿3¼H*¬<@Ûë`¸w @á“>_Õ^c@"fƒèíp@’ÚHMðÕ?IÂBé<À´ª0èÿ ÀÞ¡riåÕ¿ø().dL@ üo€Õ@ÿqX7@ƒ³Ac_c@Ȇ¾µí¸å?-ˆtÃVLÀg¾0í'ÉÀÂG@3!®å¿5äP©0@<°%Þ5@Uا´jU@#GÕ)Í´b@¡$¤D€ Ï?7l« 0À4 É¶Ý Àz·MNdüοg¡Åûq@@܉Ú¿@¡,Aõâ5q@·UgëjU@– XÈd¥Þ?úyû{si@À–]Yà!¯ÀêP~•Þ¿8õ¼È(@3@Ž‹ük+n@Ȫ– –W@,§ŽÔ˜d@…а®Õ?–Ï¡×53À©4NÚ7cÀϤƒ¸£Õ¿Î¿,oòB@F){D®@pJsÕ¡èr@ÙNß|]–W@®4ñÔ$Wå?à²GèBÀüeêæÀ ²4a´Kå¿Ä’Ú11@ϯ¡Ã™c×?+/´ÐŒkO@\’z¯Í9\@ >)o’?Ô{&Ž(ÀÖЩjè\׿+дà?’¿zÌ•*1@äÉF3¼˜ê?Þ—Ñí†l@¸¤ñÝkO@C’‹š¤?í@ï@¬%1À|¿â‘ê¿ZC¦”¤¿·S^’Ý·@ñYØ—™À?3´¹QÒ)2@½ª^P6A@@‰;ŸÏ_q}?©ÍªWæ±À4rìqM”À¿jŽ}ýg}¿”ª`Òjù@Cj AÉ™Ò?+gü“GP@¯Ù7*2@2Ésïê~?Œ›ð„»òÀ<¨ˆœÛ“Ò¿s| ©y¿¡ÄE%zê@ù[`É"Ç?aʲüÐ4@+š8§ ’B@3yxf&F‡?|š@ÕlâÀˆ-MnÇ¿\0`àø=‡¿âL ¸$Z@J¹Hû§ŒÙ?c/îð¶rR@ƒ„r2Ñ4@ïaã¿™?Œ:D›?o…så´™À3õ%NÓ2Õ¿Ä þ›¿ãæ‹™R"@S/'Öšç?¹Ï_OEW@Èaº4¾:@¾±Ý­_­?ôÀÑØû!ÀÏÇö÷æ¿MP}S­¿5«/`Á3@ø•ï®~*ü?C7ÓÅs^@ÑUÇS›j@Ä7Ç#Ä?Ü:Î+–¸3ÀQöÀöü¿æÛçð4 Ŀà †d7E@Õí$ľ?@m‡¿‰ˆîy@wW·LÁ^@ÝÓ» GÕ?ÂÝôô-EÀó c—I2Àî?7¯†Õ¿{•¹òBI@who—râ?ÇÇÃ@@òw@š ªM@\r 9­?!ßåVA>À Š'­ai⿲à,;+­¿J9¯.ÏÐ(@ ²“ÑA¨ó?¾ÿ¡ÆóÃ\@À¼¥QòÃ@@ÙÅßi$¿?t(äÅ(ÀþˆN÷žó¿I,°±¿¿Í!áˆ@@—ØRâç?†¤ \¡B@‡A¡±uP@Äû«î´?ôÜø2À[HÒ£oÖç¿>Q•@ä´¿ÄÜšÓ•×,@’nPGù? '”4ÌÆ_@ck$Œ¡B@“Àg\S'Æ?• ºÓ;É,ÀsÝ_}:ù¿6ƒq]MÆ¿à¼:]Ú¯@âéËÉØšî?éá–»œD@ÝpT0R@+¸ÊL½?žãÓ«hŸÀmœgÙöŠî¿Ëy¥²õ½¿~Ö#šª0@®»Ác@þÃ+|a@øßôÎðœD@ç2Þ^Ï?æây³k¡0ÀSìt À¹´KN<Ͽͽ'I(P"@ïêÓN6ló?ÝiL}®¶F@ʯ“ŸT@•òMz™Ä?;½WF"Àd†Íaó¿ÿÔ9pŽÄ¿G‘‹§'3@2ÃÁ$ÄP@ËÜñ,c@w»)#é¶F@\>á‹Õ?#ÿ[c3À+ËßàEÀ"jøU€Õ¿FÙ6xju@¬ÅÆðvÖ?Ûj’ QÊM@Íg§.¢[@l@})©»‘?Pvü¼%mÀÆÍËßipÖ¿‚,C1‚¶‘¿µÃ4ë¿í1@Æ.«.Nì??AŽƒ¡m@–i0÷ÊM@¬ÿåW¦?IheŠè1À:´·àÜEì¿´”8gQ¦¿Ü²,ªÓ¬!@Y± `„Øß?^Zj¶DQ@Ÿ+rLË_@KÍnQ°œ?†öϧ!À²Fˆ>Îß¿Z5[ì§œ¿”›åiqÊ5@ •Y³l¡ó?,;¾±×p@¼#çãDQ@ü«åÈ:¯±?*÷¡iÃ5ÀYçèV›ó¿- :(†©±¿3FJÃÄ«@‘êÏŸüÆ? âÑGíÕ3@Bµ$¸‹%B@))¿£–†?8‹Á¤À 1#Æ¿Û{*8 Ž†¿¶jg)7@}Î7&ÄÚ?÷ëàw¸S@þ§V Ö3@u²£G±S›?'šÄ@.À‘µÉA§ºÚ¿¥¼dÿI›¿W·å¤D@6Cï^4Þ?–«CË šF@Vºá‘T@Õ È<]¡?ºL„Æ}:ÀÆt±(Þ¿Pš×V¡¿½‘Ê!ÞA/@X¸®~øñ?T¿ü°[e@Ù5'HšF@žèö9ç©´?Òy[É5/ÀÇÏ•Œññ¿5¹×¤ê¡´¿…Eçß.…@[KfÓKÔ?K€×fb’9@d_+æÉ+G@;Ã/I#š?Ñ.rxÀ([CÔ¿Æ¢È`š¿Wþrh{"@·~3Íç?,ÖÔý­ÚW@…þn¤’9@9jÿÿð¦®?Œr«ï±s"À£?¨HDÃ翳a5Q&š®¿ï¥þá½@ô3z\åÚ?NP©?À<@äÝk oôI@•³O†ˆL£?lZ¢ƒµÀd£ YÙÚ¿XGÕéC£¿—ëÉ÷=²%@$R"½Ì"ï?ºã÷ЃZ@‡]íå‰À<@Ú_paW¶?7¾¿)¨%ÀÎzË“äï¿#½ùßfM¶¿ýàn@º@ÅÞ)Ù˜á?˜‹L‚@@_Ú“8íL@(¥IÅ?¬?˜(…2@À2*|b‚á¿Ü0nùõ«¿ÇŸiBÔL)@Cõ7#ô?ôÒ.³@X]@K­uÌ«@@Æ÷IÀ?McþÖ@)À:þKû¬ô¿Ç¹}-aÿ¿¿‹šUä)@Í*ÄB»Ãö?TWz‰ áQ@8úe `@" $Ä?‘JB×)ÀÖ]ƒc¸ö¿¼ý¼ŽúÿxÐ2îR=@½ç ˜…È @àħ—,p@M‹µ³;áQ@ HfŽ«Ö?‹wËëPD=À,ú9¬» À!¡?2B Ö¿1Í;>@?Ïò2% @ÃuR|Ìc@¿ i‚¹q@Œ^¹Âx3Ü?ª©`>À»’ / À ”½‡Ó$Ü¿#§ÆoXæP@§Ë/N.Z @ÅþëüéÃ@Käu5¯Ìc@áKf\¥ï?o™«‘ÝPÀ!ZcT°Q À«´!F®”ï¿ÉÓY¤³jA@K«Ç 7{@›­¸MŽÕe@¢Ë)„s@âh0Ubœã?¤_‡·]aAÀ‡ÜÒ OqÀ?—Vß‘ã¿å1¬dUaS@/â,A‘$@“W»rƒ@‚(L®ÆÕe@iX“¯UÒõ?gêõ òVSÀºFÞ_‹…$Àæ„U£Æõ¿bD¨ õy@üPí€ y@J |g_MVÀÀ¾^ŒnÓ@èŽ+|**x@ç*ÿ·ªzÀ€ÉѺyÀUÎón¡ÒxÀ~§v& FÀið[(¿FEÀ)…šê${@J |g_MVÀĈóôP‡DÀR çµá¦F@í?Ó;ÛE@,ÙôxnE@óHÜ5V¾š@Àžùœ*Mš@£š¾bösÀõá°ß€0´@̯ëÝÝ™@§\½T›À?Ò‘üï ›ÀÏÊÆwššÀ—_ÖcÀÊá)kVµbÀ¯P<|›@£š¾bösÀY—8i+fbÀ -üc‰c@»s±Ì¾=c@‰ÌhŽRìb@†is÷"‘›@Û%2x¦›@+óÔá ŽoÀ†zÖ ´@ ïÝ»›@ºÓ¾?zcœÀà{¦@ryœÀ»Ñ½A{œÀ×÷L[®_Àr”}’߯_ÀÀ×VÒá›@+óÔá ŽoÀ“¨`Ñvß_Àøªl P`@\¶4«\`@]ÚšˆTi`@ž¿@²ÉmŒ@BÜòo@ó‘…­XÀ¹‹"ï…¥@³±J¯yÈ@3ÑåúæPÀißAn“ŽÀuKÒ›h¶ŽÀ!±ÐlPüHÀKÙ=òã’IÀ®És„3UŒ@ó‘…­XÀ¬Šë-JÀ¢œe»ëÃI@rÒÝ/2_J@úHi þJ@I§IZ T}@\ƒ-Òê¦~@Òc§Ó§ŽAÀl榋•@Å…9€@H*é§J~À Uçh§ÀÕ"”¸?Š€ÀªXÍEï1Àq¶‰¾2Àã»[@ÔÖ|@Òc§Ó§ŽAÀÿ¤¸ÊK–3À´C—FX…2@¦£‹ªõZ3@ñmÕ2:4@Ô~mHûEŽ@[ÅFç(@‚ zµ|_DÀq{MP¦@&ãXÓ„@‘@6уiOÀ‰Œ“–¶ÀLS^¹ÇבÀÔ£L×p5À¥oÓŸçl6ÀgWT÷,g@‚ zµ|_DÀ[<Û|ïð7À‚ÓôÚœ¹5@$°e†17@«ôiØÂ8@’z)J,BŸ@]³¬ê ¡@ƒLêPx4ÀÒiKœ„¶@|\œ¢@ønM£³0 À×-Œ ª¡À•©·JG£ÀÌ@E‰”O%À\ š A'Àü¥>Dºž@ƒLêPx4ÀáÝxÙ_)Ày1g&@wše¸¶(@iL I*@ûîÎÂÀ$ @öâ ‡•¢@´¨ŒƒUE@o¨i£·@Ï HÏä¤@¼¨ÔÝ=À À~±¢Àø&9€Û¤À$µz~Ûo6@³a÷èZ 9@÷r ýµž@´¨ŒƒUE@ËA…õï;@£%öG7À;­Éaú9À[ y ý<Àjßì"®€@Âôök ƒ@íÏ}pŸþ:@΀Œ—@”l“ª½…@–uCŠVÀ%ÌáÒP˃À¡t´‰*™†À7Tü4°,@ç~ÞM`0@Žïzu@íÏ}pŸþ:@‚ù¯2²2@°ûiÙÑ-ÀC’`¤1À]$Íþôn3À¥;{y[=¡@+ ‰‡%¤@–¯Ë¾ðe@KDY‹O¸@†*O¶.‹§@@deUÌó¡À{Ug®»ú¤À+V„¨À[HÝⲑW@|×¥‹[@j£öÞ" @–¯Ë¾ðe@§4 `@2¬±1‹XÀÔºÏ÷‘®\À(îé’TÂ`À‘”sоžˆ@7S·é†@6Xü„QdÀçì%á£@R,qÆQ…@Q¬¸“<‰Àðz{‡À ì—…Ú…À¤¨¬+«»SÀÖ$•Ý\RÀ++ Š@6Xü„QdÀJúN^lQÀ-B§ðÆ9T@ŸºÆx7ÒR@ -ƒ ƒQ@IÎyõÞ]y@癸÷©x@»†;Ò2QÀóI'ÏI|“@i’‚*¨Òv@‘ˆªI«zÀï‘3¹°xÀjÖnmkwÀ=OÝ Ô@ÀÙµï Åí?À¬‘"êÄtz@»†;Ò2QÀË΄TI>À2»IEA@K3¿a@@¨æ=ªÔ?@,>Ã&Š@‚÷#ïK‰@ºË£›ï[À^õ"nè£@"Âñçxˆ@ÁC ÷‚ÝŠÀR|¿eý‰À/,Ç–$‰À[Dˆã¿KÀëEÂÈÓ©JÀv¯^íYÙŠ@ºË£›ï[À¢«¹eËIÀ^ÛQL@¤ÿàdK@vv†Z€J@Mèø¬÷š@°R™pŸš@üN`‹h?eÀåÖùç%W´@ó÷¥íTHš@|×” ¾›À]ß$Gc›ÀG7‰´ª ›À¼¨¬% %UÀ´š# ÚßTÀ/l¬\JK›@üN`‹h?eÀß$R›TÀ½c×’“ÀU@~” gyU@åíi$3U@ðœgÓ‹@ž[UÚ Œ@îo¯€ó¦LÀ°:Isɤ@=7%$EŒ@„ ǹ©ŒÀÑ=¬FäŒÀäÄêñIÀz‹xH4Æ<À±Íö½ú=Àx Ë‹@îo¯€ó¦LÀÚŠÝA9<=Àxc>¤=@@‹¶Êà=@‹5Þ®Ñ>@¬$m¸Œ@Z{•jô’@‹Zd½Ä¨<ÀÌ  j?¥@PG¬núsŽ@~/5ý Àl+n‚ŽÀMtX%’jÀCHËÔ-À(‰–íë-ÀOM cüXŒ@‹Zd½Ä¨<À€ëg€˜Ï.ÀÛÆ … ú-@!Ž7Þ.@/×½É/@;4 9¨@o…Æô£6Ÿ@B†´‡,ÿ?Ù›÷0<¸µ@"–ûl @kð±I¤žÀ,ñe÷ À;y$ý–ø ÀW_³¬Íï?5B·vv¼ð?0xÚù¦õœ@B†´‡,ÿ?2ž`rLñ?Ëueœýmð¿`dµJñ¿é %R3ò¿I}§¸¢Ž@¢éñu|@–7Ì’žœ?@mwqZç4¦@]#}à_¾‘@ ^[2´À¸LgÀÝ%"±\’À ެj[0@ÆÛ>`š1@¡Å³G¡@–7Ì’žœ?@©¸o ò2@©Û(øñì0ÀÑ4Np72ÀqKòó#›3ÀÇåD8¨Ÿ@ÍTÀÌð0×\@ ‚ hôp’@OŽ²Ç¡X@MžF9§@Cx*óÉ”@É´:gfýÀÂö>O&“À‡÷ì¶••ÀœÁÑ dI@z9‘9ŸL@ST¸(@OŽ²Ç¡X@jB|8!P@ÛTY^JÀú?Hˆy¸MÀjN½Ø¿PÀâ¿zþ]w@Õ\=kÎût@üº/L˜sRÀ“ |Ol’@öýU7Ü×r@Ž–OT´æwÀh¶|X’vuÀ[Ò]FsÀ¯3NµšAÀ5ûäž?À¨ý°$y@üº/L˜sRÀ7 â¢cd<Àã2¢ò³B@JÔ?•~+@@—¹ • =@¥‹.„x@Óš1ø v@¥fî–ÓNÀÀu~òÐ’@÷Ô0ƃ,t@± »T§xÀøE',;‘vÀŽmT¨tÀ i°A¤=À„ S¢";ÀwµÝ6Í{y@¥fî–ÓNÀ¶ƒÄnGÖ8À¯ÖË-Z>@B wŸÈ;@{*¸¯¶n9@ PSjÈј@(£% ,—@喇М‰hÀ%_.BŒ8³@ì‡}=¢•@#w¬q™Àk툢IÁ—À<!îš-–À‰7)‡¿ÊWÀÇ-p6VÀ¡·þ„tß™@喇М‰hÀöâLA÷¼TÀ’£µdX@j²e¡ˆÅV@ïZÉBU@þšòù˜‰@N˜â_cˆ@aUjUÔRÀ°s?¦0££@ã„Í;g<‡@Uœä&FŠÀ—Ê]^‰ÀBÞ"šÙ‡À±x\£AÀA6ÞßÎ@Àɇ PŠ@aUjUÔRÀ7¡ùyÇ@À²Ù¯_°B@³†¸?A@Yq‰o@@dìáÁuiz@ˆ¯íÕ˜±y@°!‚…™6ÀÏýò%ô”@ÛÃoÙ»þx@âЕ0%{ÀíwÏ8hzÀFMd°yÀ· ȬP&ÀñŸÓTµ%Àò„xFÎz@°!‚…™6ÀÌ<E6%ÀÔËÖIï&@x¬Ùþ O&@ö_RP´%@Àˆ”€‘C›@ËJÖfR›@2jfü‡[AÀùßë´@4?æWíš@ÍŠ¿ ;œÀ'D¡â¸â›Àå[U}¶›À¨"1çÅN1À;UÕ½Q31À²ÌtM»Y›@2jfü‡[AÀ‚‘§ 1ÀX—%áÐ1@Ê›B£Î³1@¬ÒÚ6º—1@(—’ž'|@>«ß‚L™|@¼þRÛ@o“º—-ö”@’£úrÅ }@ÞDóµ}À³å~”ày}Àåï3Jäð}ÀBÊ×£1@67°h(c@˜ƒÀÒ®ó{@¼þRÛ@ìñˆ–Á@⃩ÿºÀR7qÙÏÀ“<4‚#|Àzmà¬í}@ìnDrc6~@Ñe²E—4@´Ê“ÄÏm•@qÀÉ b@&ñ~ÀtØ9hÕ/À ]ô2€À¾©Neôö$@E/]ºßÆ%@úLCXOœ|@Ñe²E—4@ Ùž&@Q™ló ¤%À¶hòð«z&Àõ08œY'À7¯eÍž@ºë}™ñŸ@q9D‘ûa@´Úéèµ@hçîNù @ Q῟À™Q×pƒ À¬ýE}ªŒ¡À»M¢ƒR@iÜ×GX¬S@ûü QT@q9D‘ûa@¡LàQèT@ά?–»#SÀ´RJ#WTÀžU¿ÓUÀOë—‡Ÿ@5ÏÛuæ @‡ÍØñäìi@(‘SÜ’g¶@eQÀOb¢@ÑU€ À3 Áº€¡À3'vk £ÀÙž2þZ@Y†âä\]@ñ‰ïG}ž@‡ÍØñäìi@S‰ŠêÛð_@¹wŠ„˜ô[ÀŒýÅkíh^Àjbh6Š`À}·ÖL1–@c( >“@ >ü舱pÀn#»ͱ@¹N="¯@æéž#¨–Àì^ÁÀcuÿ _‘ÀD@zUL_À$nA¼&#[ÀŒ‹yǸ9˜@ >ü舱pÀ™Ïª¿“‡WÀÔS઼ó_@IÄ?¢L´[@\ÅmX@¨[ÔãÝ–@ö)F6”@G“ï°wkÀ0ÁtRç-²@‘'í :Ý‘@Såtf^—ÀñV:.¬§”À‰¨ÐgŸA’Àtr¶ôYÀö]ËVñVÀ ÉÄX˜@G“ï°wkÀ¥¦ÔH GTÀÕ^Úv•†Z@ÝR$ÄrW@ñ ߸ÿ¸T@£žŸ ¸’—@.R•*j@•@¸õ±XeÀ2Ÿe*„‘²@Á?EX£(“@l\„§ÿ˜Àb¬‘`ú½•À`Rr÷Õ™“À?“ëý¥WTÀvhÖvËVRÀªêy#ó˜@¸õ±XeÀªhò‰rˆPÀ²®mìÖÏT@:OÕ>&ÃR@ŽØ”!êP@×ËLÔPˆ@²ÍR^†@¬Ä¯DËNÀ½—ðø¢@iç+[”„@칈Ó2çˆÀã"AVé†Àù ^}@…Àý ´ß<ÀŽ3×¹‹:À¡Ï\Qzb‰@¬Ä¯DËNÀŒýV­ªp8À-¤?S%“=@s…Š)£5;@t¯Ž9@ Þ5Zy@È:‘w@¹>sœwí0À,`ñá…a“@Æï®#v@« ~‰iºyÀ kY+xÀü€w´vÀàóeäžo À*lè,_áÀW¨óåÁÞy@¹>sœwí0À39"eÀ‚$çÛÛ @•úÉP«@2‹VÀ@S³'ˆÊåy@bÅ$Ÿ¥Úx@¨†êý…" Àd¹rÔΓ@ù!¶hDÚw@|xÛs˜zÀiÉ »…yÀ ±æ—u~xÀ#¬0ªœú¿AŠÝ&Šù¿X:ô bhz@¨†êý…" ÀÕ?³‚ø¿å»«ðÙSû?첆ùô9ú?ášuÜk+ù?‚J›ì»¾Š@@Ò̘0<Š@T¨E?15@mÞ7À=¤@¸Åv"¼‰@¶]6Ù‘€‹ÀHÃeTúŠÀ,V-.¦vŠÀ· Ÿ%@JR@fš$@­¢{YÆÿŠ@T¨E?15@ ()Œ5$@7å?Ö˜%Àu㧨k/%ÀtœÈ$ÀÖ†•³~¡‹@AZóÀ“·‹@'¸ü©f I@ef¢¦°¤@\&+tºÍ‹@Í ü^tŒÀo+ÿ‹ŒÀ· ~R졌ÀûLõa9@óg?p,9@h5u]¥‹@'¸ü©f I@8ÆŽ@9@s}/Fè×9Àª » ì9ÀÙˆÝ|G:À)1z¢aŽ|@«ü%Í¢N}@— ¾4ýC@Üö/>Ù&•@ÁGŽRò~@ ÓPQås}Àœ¶Ð°/:~À•w(±ÀŸ`ƒ­@4@tö—_É4@.u šY|@— ¾4ýC@Ú 7÷T5@€v³Jtã4À.’ p5À.]šj6ÀÇË<±…@äÔÕM@&¨g¼”²[@Ö¥ÿo ¥@êÆ·²J@Ám•†’ŽÀåH9¥æÀjÉuü÷ÓÀÛõÚ4)dL@ÒµNe'ÓM@£AÃò@&¨g¼”²[@Ö×ýn­TO@qfxTMÀ($S{˜ÏNÀ"Óî.PÀã`º Bu@ë6Òœªq@ÎçžÞNÀCj]z5‘@$Ý ›˜m@çÍI=~uÀ4LžßrÀÄ/Á)nÀ ˜è’´;À_]Ë«þ47ÀN³â„Q[w@ÎçžÞNÀ ‚… dp3À|;S0Ú;<@º€O¦7@ð‡NÏ3@Ív@{i»•@ù<ÈW³Ž’@ ü»8NhÀÀ˜èˆ ’±@Þ½kl±@E!È+–À_Ñûî’À¨ÂÚ,&*ÀŠMDqU“VÀì‰r‚GSÀJ‡8ò±—@ ü»8NhÀɼù(vPÀJ°fZW@Ð5"µ&ªS@CÁÊP@Fˆjg†@F7n‘ƒƒ@jœ×`WRÀËÅ­zò¡@ÅG7É(ÿ€@‘î2+ªà†À¾d¸‡-íƒÀHÏšU%[À›\eÉd/AÀu¯Î7Çï=À+vA=}ˆ@jœ×`WRÀ«¾uE.:À þ_afŒA@³ X·Ë‘>@½7švL :@Ƨ $‘w@ÏÙÜJoŠt@Á$¡yZ8À~†_U’@¯[¥ÚLBr@ôñËSŸwÀ…'SøŽÿtÀö†”ÉiªrÀ¾u:¤c'À²ššx$À"‰?e¦x@Á$¡yZ8Àp)<[2"À_¸]>³Š'@å/9í$@^±|Aš"@ò¢ê_-؇@ÆÂ'ýš¤…@¥*]ÓÂ77À-N3¸‘º¢@‡hyÒ¥ƒ@®ÿ±zgˆÀñ»TP­&†ÀUüùÛ „À’ªèØ+&ÀùȬ@Ò$ÀËVDh[üˆ@¥*]ÓÂ77ÀòÖ"-D"Ào±&@la÷Ę$@€êvZô±"@2y:ßx@Ð}‘yÓv@¼Ydúfêø?†R ]ó"“@z˄۱*u@ÄK†9yÀϱNxdwÀ¶•“;аuÀŸîÛq è?N iÉ!Jæ?Ÿ% _ÿƒy@¼Ydúfêø?cNÇòU«ä?—3Ñ¿¡è¿OÒôq]׿¿QhJWM.å¿¢£I l‰@·{¬,ˆˆ@h‹p¬ŒP>@œßZƒRŽ£@¹iÃÖ†@ºÑÆàŠÀ÷X¨×‰¹ˆÀß}Ã2_o‡À“Æíu-@ȘÞf,@Eó™øŠ@h‹p¬ŒP>@îXhDŽ*@”h¢T.À,ýò›¿,À^j¶?+À;ÎÙCŠ@¨·®]u‰@U`Œ2ß3M@e¾¢õÂü£@±Ðyn8­ˆ@)|# óüŠÀ—ÁåÇ(ŠÀÐP º [‰ÀÓ!ùOÑÊ<@„ô>)wè;@,Ì;¿°»Š@U`Œ2ß3M@mÁÞ} ;@à¿õǺ•=ÀÙõ l%­<ÀíTu‰´Ë;Àf›™=a%{@WQëÁ¨ëz@‘£á*4ÚE@½)ÌYn”@d–‚k²z@ ì0+ï{À"Ѥų{ÀŸMdÞx{À÷ɘKË5@bHéSôœ5@æ pê”l{@‘£á*4ÚE@ôbî—ÿn5@a uMm6Àò³kU=6Àx¼üR6À´Ï_çœ@M4ƒ†6}œ@óúÄ"xVm@—²ñ)ã´@ Hp§'ëœ@ŸÉ­ôìœÀs«Œ•\À× ž(äÍÀʺ™*¿›]@È™ ^@ño3Í,œ@óúÄ"xVm@ùBâý^@gì²=äƒ^À2.Œþ¦ù^ÀÃ^G20q_ÀCMgrŽ”@JÇÄ =@s§¦XójÀ¬.u餰@£8Χ‚KŠ@Á×ÔÒg”ÀÞüš—d…Àû_´Ž‰ÀŠÀï¦oCgXÀùQtuÂSÀõà¢È§ˆ–@s§¦XójÀ¶²KþOÀ°fþMßÓX@ù,^ñT@Íœ'WFP@eiÑɪ„@µÈ¡)@ߺ•ÏÁSUÀ;‹¡þ @Y._È])|@’ÈÀ&Æ …À¶Suã(_À€â˜„…­|ÀNë3tyCÀ\g°ð@ÀcëmÞ†@ߺ•ÏÁSUÀ EO‰:À?ÿܬ×ÔC@òßö‚^@@žÆeŽÖ;@ð™Ë~N…@?'eâ‡ð@ÅÃxJOÀL%ƒyîZ¡@fÿç5~@5Ã=ú·…ÀbEXI‚Àß¾½EË~Àô·Å•—<À þ]ér8ÀïÎEI«?‡@ÅÃxJOÀÁ6Á‘›D4ÀÔßí›$=@Ä24Ÿ‰8@ËîS°ò¨4@Íʲê÷ùu@+÷¦„âr@8Ç83À~ûE'⹑@'¹Vh:p@¾«ÝËlvÀ#«;1EsÀ5W7P3pÀÙ)û6U±!ÀEœ‹pOhÀ±ë^¼¸¬w@8Ç83ÀZïE:!ÀÒ§1Ç "@9ºÓ0@3³ý©@ú+뀭†@œ¬Eæƒ@ ‹®Á¾y*À†ƒö-¢@69–f+v@8é\g›*‡À:ž0þ T„À=dújÖÀG›¾lÞÀ 6ìñxÒÀí‰bîñ%ˆ@ ‹®Á¾y*ÀrœÃ&ÀU¬—g@xø ÛJ@»£#µ@0kÄwfiw@¾.ýt@ƒ]_üÄ@°K×€’@‘mDvòÐr@³ôÑËñwÀ$]¨ƒYwuÀ]HÖ‘>sÀe*—‚@åI’@©5tµ«x@ƒ]_üÄ@È€Ecå@ÇaÏ)w À`}¾µ\ŽÀ¯ª%H3SÀΧÕõ-ˆ@=’ÝiK(†@eú†—kC@#¿Pç¢@­ƒÔëM„@Ÿ iˆÀé5CP¦°†ÀLxßÊ„Àâmž„J¢2@¤›'Z1@Iidèd>‰@eú†—kC@‘GäŒK/@=b`ö3À·¢%o|1ÀÇ—Z 0À®Zlz|û˜@«B3Ègi—@z%j¨‰`@·îº|ŒQ³@Ð(þhšð•@5¼Uoæ™À‡¬(Á›˜Àœ(ý¼<–À¦/Šy^ P@-Kö'N@È eÞ™@z%j¨‰`@-%% 0L@Ôy³tPÀŸ}˜Â³×NÀÅ ¶MçLÀŽ•GÒ™@;w–ÓöÁ˜@J•œ•g@•ç޺ɾ³@íxBðݼ—@ 9A¦ ƒšÀ0Ü‚l™ÀLy!dç_˜ÀìÃðQÛ'W@K¿x§3V@<ùéÊŒš@J•œ•g@CÆÅƒIU@í©:UåÆWÀ+Úq=$ÌVÀUJ¡·ÛUÀso0u£²Š@ÌŽ¡3Š@AÚ&<Û^@*kI{/¤@ì9íÚû¶‰@kjß´Zt‹Àp•#A¿ñŠÀÓ‰R!‘qŠÀjDþ¬©N@‰¼TÎN@T‹úG‹@AÚ&<Û^@’¬¼š¥ˆM@ü£B8)ˆOÀ ï_%(òNÀ¶qú¬ð^NÀoòk¢ùƒ@$ŸÄ ã}@¹>­›‡XÀ÷ oü @3b[—fw@™eBôDcƒÀ?tu*\~À¬°I,\ÅwÀ‹¨CÓ ^EÀôÿøïº@ÀD‚½ûøÀ…@¹>­›‡XÀ•‹SÏ2:ÀÆCÜ©´E@©ž±þ@@üG×{èœ:@§.l€Äªƒ@ìKCf@Ñd1'…RÀÊ«‹°uq @~6?~¿y@DOJ¶éþƒÀâ ¹îšìÀÖ Â~ý{yÀ¹<×ü @Àá¿ÊbŒ:À¥šÞ^†@Ñd1'…RÀàñ.z15À-US"è@@t­$þ:@Áͺ 'Œ5@’‹¢)®F„@R„Ëì‚€@z ¨?£¶IÀ¥UhÊ @]#86äz@Ûk1k_¢„ÀƒMš —Í€À|ˆjóÑ]{ÀâR‰^L7À¿ɬõø2Àm³¯Oèv†@z ¨?£¶IÀìÝÍ×Sæ.ÀY ºµ7@ A.ÈÁN3@Þr/@ù- þé”@ʼnRøa‘@££í‡LÀF®íúã%±@²Ç1û.åŒ@9 îþM•ÀTÛnµ‘À|¦“YoÀ¼\lŸ\¤9À|ZƒÖ÷O5ÀktAêâ–@££í‡LÀEYº¶1À€ùø:@CiBàµ5@0[ym 2@!áä4ý”•@ «ÁaQ’@zkªS\õÀ”3Ó´øƒ±@ŒZ?^N@T›Nñ#–À¼›­d®’À–Ä‘µÀ‰ä߇œ Àû:ÛVTHÀ4ÛM¼Z—@zkªS\õÀaŽ6µ)œÀ_Ó]í·, @©ÈŠ#Ã@ C7f@á8IfõGv@û¬ŸWRs@Ó\ú%'%@H- ·ä‘@n¹ÑZÁp@pkÜ,¿vÀ$ãßf¹¹sÀ²¢VqÀ¯&Q!÷­@Ä=¶åÎ@æçlʸÞw@Ó\ú%'%@±W”™ @Ãú$CÀµ!‰lÀ¦‡ 7m7À3(\‡1—@c·f”@þj_eögW@ßy 0H²@WƤ’@fCÆ™z…—ÀïÍ&›Ù”ÀVäˆõf{’Àp×+~F@­µ•[Ø—C@2 ­èN—@ÏÒš6M@ïRæé2@†E£&^;À™ä®5ë÷6À‘7ºF3À€?t-eê…@WëÌŠ<Í‚@«¸{cS"K@ ½o±t°¡@aâ‡ÆW!€@k¾ÿi\†À= G /ƒÀÀ&:Cu€ÀÜÂHŽ=99@¼c ÁÁ£5@TºÍª‡@«¸{cS"K@ö‡9…¢2@ÿ†3x¼9ÀùñW6ÀÕôº8ñ2À½¨ª¥†@–G{WNÞƒ@éæýµ'T@Ú"Àú¢@Bʂغn@3ç!‡ÀÜ¥AâK„À/fkßÎÀ½âRëÖB@­æîÓè†@@¾ÆÌ^»Eˆ@éæýµ'T@^ò€h=@ŸÊÒnú=CÀå~Náâ@À7Vã$[ =À$ïh—@48_3N•@î}%ŽÝ°j@ÃÇ@¬>x²@P]#0Ý’@EOb%îð—Àæ|›í&~•À·ãѾxK“Às%‰fjhY@u{Šü<ÏV@ý]p–í˜@î}%ŽÝ°j@&ÆÉåzT@ÿ€¥ËôüYÀ±©¹—–TWÀ¼žlgÌñTÀ®Y«‡è3ˆ@­Ùq§=†@3ÝöÊÇ`@gýíõQà¢@©‘Op„@ÁÂG@âɈÀ³hvâxdžÀÕVÉÂî„À3Ä×,P@ç&£çä¹M@F¿¤µ¢‰@3ÝöÊÇ`@Ÿ±àQK@ŸÆ\wÑPÀ(ŸîrNÀq•ÇþIúKÀºÐ²M¹P@ìÂM{ey@³éu—RÀÊbxñò2ž@"t!QŸr@J½ü¹uŠÀ ۲ȹyÀd¾)iÝrÀçïƒû@À«TÌÒ*z7ÀB–¾ÌO„@³éu—RÀ‰¼dN71Àï—ÒJ[7@@€`8sÈ7@kÎ϶p1@“ƒ÷ב@o³±T¯Š@/Ct>^ÀZÀ‘ÍTòÓ®@›13õôƒ@43®’À(À¾ ‹À€nsz­:„Àá5ó,=GÀA©ôÈt`AÀJ* †¤”@/Ct>^ÀZÀ;L›ü9Àu=HeG@þ²‘ˆïA@Ö_sbŒX:@œþ¦Ü«er@\ê–Æl@ÿ8@÷/À¤˜Žµ|y@°(8Øie@N}ºFªrÀà óœ/{lÀ[õögBºeÀU)Ô„ À ~"Þ{bÀÎIœÆu@ÿ8@÷/Àø*XXPÀó˼Oeq@¤Q¥iʲ@„<ù˜›@›#ÿú‚@ÔµAè2Ž}@ø²Œz#ÀoøX× @Kñ5òów@˜…PÂEƒÀ²ÇËw ~ÀUšªB·_wÀI Äí—@À°àÓ•Þ À4IüÜm…@ø²Œz#Àeî}ìÀv“Ýõ`…@ ëy¶I @Êú°Zê?@º§m•“@ÍBŒ{&@,ø?Ôb:@"WæWRi°@ËðEƈ@X»ybkè“ÀQU…Ž]ªÀlôž2þ.‰ÀoÍ!ª'@±»ÀÈ"@C;…ã•@,ø?Ôb:@u)PËÊß@Ütƒþ¥(À €as¢#ÀÃóó¬E^À%Ãèo)8„@Ü´:Rn€@iÂy”lB@QKV>à@ |•d´z@ ÿ‡Õ“„À£#÷2¸€ÀQÿ‡Ñv,{ÀljN>Ú«0@ËŒÍe+@rVÒ»Èc†@iÂy”lB@’º¯Q¿&@Ìòù£Ïö0Àæ…â¯9’+À³7k¡¿g&À­Î;Vâ”@ì(ÍjY‘@77 7Ÿ^@ÄŠ¾©±@~ð‘œSÓŒ@m~p©F•Àv—»C¬‘ÀïÊ Ôù\À§ýf˜ÃL@O2ì5]HG@c¬ÊGð–@77 7Ÿ^@ªU°mƒWC@¼ltù˜ŒLÀwþý‚‹·GÀÖIò3à³CÀX+zO”•@J%Ôv®U’@ ™¿:t™e@G&˜ä¤~±@]ëõiä'@§]ñc¿–À nKª²’À¿…ÚåÅÀž9ŠT@£YóbÿP@4ïól눗@ ™¿:t™e@ø^–³áL@yÙ„fTÀ¥©O¯DUQÀj w,tMÀŸÇQZN–@HÅ*Xd“@ ´žl@ôy!“?à±@ùžÚªËÛ@b%Þ{Æ–À|ãÈÌ“ÀÖ¼¸–6‘ÀX8j„+TZ@!3öŸãV@¢ÁÏ.˜@ ´žl@ŒF<‡æS@ô²:÷áZÀ£¾må^WÀÁ†ÏHHQTÀ»ºÕ¿—@<|Í·†”@ƒozÚ¾aq@Oß-JŠD²@.iÿ>D’@71¥”—Àðäü”ÀCiÈ4³¬’Àœâ `@Ÿô¶Ó_]@èe‡ø à˜@ƒozÚ¾aq@gžîþ#Z@ЦB¤gß`À1YäÈË^À–í»Ðy¹ZÀ l‹ÿ‚€@¥ãfrw@B`X·PÀ¨RëÊWB@EãP빦p@b™ë—г€À:Ë(Œ¹wÀe`G-ñØpÀf<ÉùI;Àx›^;a3ÀS÷ú¥ƒ@B`X·PÀŽb¹´¢†+Ào‚¥Eœ;@JÖ⬛3@ýNç¥Ù+@d»O£q@¤Šfõ£h@Xµcòd 6ÀÂ/`ÔÝ@¬ò|F>Øa@|Z­9qÀ÷÷®qóhÀ"hšp|bÀ"SyùÕ"À[¡^-HÀwŠÂZ|ùs@Xµcòd 6Àh å_öÁÀø‹ée#@AÍr±Ÿ@ÑÃzW@ÓÉjóVŠq@¦@,·çëi@¤;2Ž'Àë‰/V­}Ž@Q™T'c@,FßQ4ÆqÀéiªÒ_DjÀÁù5s³hcÀ|K‘çÀÿMGfRj ÀɽŸ%Xt@¤;2Ž'ÀüØB9¼ÀIÅ„H€+@+(‹·Î @v±Èg@:¶îeû‚@“fsÜK{@~·»30Dö¿îL5 ý!Ÿ@laÒû–t@àiѱY‚À²ágòþ®{ÀVUT÷ÂátÀÉmèW¿2ÀøMj±îâ,ÀHSU¢#A&Àqø ~Gs@ãŠ0wàZn@"$|ÞQ6@¼Ëè÷6<@ƒ¼=)”åg@û‚ˆWË–sÀ‚èóŸ¼×nÀ8[®ÃßGhÀV—åøÙš#@îF¾ïÞ@¸ªç™‰´u@"$|ÞQ6@Ø|'çL@ZgŽ&~ë#À° ö]À€ÐƒÃÛ°À”ë?Wàés@f¥¤çäp@Ê¡å$fñ@@Wé`Ïc•@´º†7Ìi@=u¯ó AtÀÅ_ MpÀ‘[ %=jÀ9L:†Š.@ëÖ¹s‰”(@¥†­«*?v@Ê¡å$fñ@@©DÊbÈ#@Qì7/Àyœ")ÀÒNMÌû$À‘´Q§²“„@ä€èÌ6ð€@u.@ÔW@â‘ñ @bÇ»Pãâ{@?HÚ‹ó„ÀÌÎþ?ÀànœÈd|Àî—0)H E@Ï.N5ÔQA@¤6p•Õ†@u.@ÔW@Z±Ph˜ƒ<@±íîºIlEÀˆ†L4¢AÀ°vEIj=ÀVTг9E…@±ðüˆê@J”s`]@?îa(O¡@ÿÛƒ.~@âPµ§£®…À_]SC‚ÀÞOHÄ~À ¿[—t!K@ƒ_S/ÚF@“\ x‡@J”s`]@ÅP®S¢?C@©Â>†é§KÀi)7pKGÀN‹Q'ŸCÀÙÆÝØºþ…@oî÷‚@žûó"ða@ä<ÃÔÞ¯¡@$­x CZ€@ׯ½2®r†ÀN[?c [ƒÀ×Ú£w°€À"€eì÷ÇP@#øí‚[ðL@Åm@†$'ˆ@žûó"ða@Û~VÒóH@©9Ún QÀ_òÒíéˆMÀKèQÓ\wIÀ¨¿Y] â£@oÌH9~²@h¬õ§@ ¤÷çú¾¶@_WZƒÆ2Á@/ääm—€¥ÀLì,5ÿ³ÀBn•ΘÂÀ@1¯_äa¤@XžJš”ô²@:¨ƒ:ˆP·@h¬õ§@õÿ¢FØ Á@±6¤Ð4 ¦À5Òú0´À7IJCÓÃÀrê!¶qú @8=-¼¯@ÁPú ‘¤@gºMn|V´@Àÿx”„¨½@wtÏ_B ¢À>®ܰÀõ!uUƒ¿À ÿ+³_¡@34Ò\­<°@~€ÇÂÏ´@ÅH&œÕ‘¤@ ËGèdY¾@wì~ÊØu¢À²1rðŸ@±À§*‡¿¢ÀÀNÃí `¨@ÒEÅš»xÏ@ê…ICôº@ú§ÑVXIÔ@EwC™(Qô@P›â¤À¯‰C¸wÊÀW½ß-ñÀzžG` ¹š@È [@Á@ÔÂìUÙ_Ç@ê…ICôº@HU¿Fæ@ªéÏTy–ÀO̰ƒQ½ÀíFÓ£y»âÀDQ«@|[âº@ˆV²ŒÚȰ@ûè#­£›À@I¥t1¡lÈ@-Ž#Áot­ÀbmãUW¥»À+ίòÉÀöNC?T¬@ž®¯Ù–º@Ñ|þ:øÀ@a»oãɰ@‹dßÎôÈ@À÷k¡©®ÀAÖs6{?¼ÀÒ*¸A\ƒÊÀ¢²·±[¸@OõDËdß@ó1h†¿Ë@¶Ýó-ä@ûtŠ7:A¼žbŸï€´À:ÀwalÚÀk/“¢­ÁæÏo «@¹{+›kÑ@ ÿ=£x×@ó1h†¿Ë@0¨ä(sö@da¯úÎÁ¦Àdü‚ÎSÍÀ)½fµåòÀ–¹N¬ÖÆ?–¹N¬ÖÆ?–¹N¬ÖÆ?–¹N¬ÖÆ?–¹N¬ÖÆ?üg"'WŒì?üg"'WŒì?üg"'WŒì?–¹N¬ÖÆ?–¹N¬ÖÆ?–¹N¬ÖÆ?–¹N¬ÖÆ?–¹N¬ÖÆ?üg"'WŒì?üg"'WŒì?üg"'WŒì?mrcal-2.4.1/test/data/test-optimizer-callback-ref-J-1.npy000066400000000000000000001465001456301662300231000ustar00rootroot00000000000000“NUMPYv{'descr': 'E£ç¾¿à?2«ÀÝÞ?à?E¨F¿¾¿à?J!³) Óï?ð?c((N>—οð?E^ÒhMhÐ?Ð?̧¥žto®¿Ð?Ÿ ÐxêÐ?Ð?ékÛ—ÈG®¿Ð?]§EÊmpÑ?Ð?w š½ ®¿Ð?÷ìòT@úá?à?fôŸ ø½¿à?]*?@ú‡Ò?Ð?V_ɀϭ¿Ð?pg˜Ó?Ð?(P'‰ ¦­¿Ð?m³8ÍIÊì?ð?ý·ç+`Ì¿ð?­ZTuc°Ý?à?<ã–¿/¼¿à?¶zèœÎ?Ð?ŽŽwtÿ«¿Ð?Áè­%Ï?Ð?ö´V6:Ï«¿Ð?¢ÔŽ3EÐ?Ð? ·ÇŽúž«¿Ð?/}¥ øÅð?ð?:ß7—nË¿ð?ã‰êãJá?à?hXZkè=»¿à?ÕzB€àÒá?à?aGH» »¿à?P‡=o(_Ò?Ð?äÙÐÚª¿Ð?_ 4}Yïâ?à?Nöêyاº¿à?†UÿõÀÌ?Ð?Ä‘ër¸©¿Ð?Ob:sÝ?à?[œžnž€¹¿à?h((Ž]Þ?à?<øË¦H¹¿à?÷?2À%—çÛ?à?g~Ö¬¬ð±¿à?„qã9¸Äì?ð?›5È…¤Á¿ð?þ.ŒPܧí?ð?êµðüuVÁ¿ð?ê yS‘î?ð?Aãå°ìÁ¿ð?L¤0#mï?ð?xE¥-P¸À¿ð?É[æ;<ð?ð?¶Z ^ƒgÀ¿ð?èçL[»ð?ð? _+öcÀ¿ð?/`Ê 7>á?à?9Z™±“ƒ¯¿à?x8èÄÑ?Ð?7H Ùž¿Ð?±<¤\€Oâ?à?!}VìÈ*®¿à?K D]Õ±ë?ð?–|›¤Öξ¿ð?÷~ö¿çŒÌ?Ð?ü<œ¹(ž¿Ð?µáG ämí?ð?šþëÑß½¿ð?û"Æ;UÞ?à?Í]K>ÊÔ¬¿à?ÒP!ÚBß?à?ü\û '¬¿à?5€ÂÒ¸à?à?ÂhûÛev«¿à?Bx‘>•™à?à?ö¥²•ª¿à?ŽŽÓŸ#ñ?ð?LÆ~K º¿ð?­ aá á?à?âND¸-P©¿à?rѵO¾)Ò?Ð?Hµ×˜¿Ð?š@¨Ë#}ë?ð?âËîKöɹ¿ð?´ µ9VÜ?à?íäYÍü©¿à?4«ù° 5í?ð?QlPAa¸¿ð?»Ýñä(Þ?à?Á¯–Ü’¨§¿à?ë”(¢Ï?Ð?"X«Ð¹ì–¿Ð?—3ÓÛ÷ß?à?Ç WLw-¦¿à?ïElxà?à?ÑE›¤„j¥¿à?c¤;&Ùøð?ð?Û_áí’£´¿ð?U¶^è|Ñ?Ð?,/Í©JØ“¿Ð?‰0ËÓÒ?Ð?å›9«K“¿Ð?"Ô›AvIÛ?à?¥³0&Ò¤¿à?”Húú  ì?ð?«epOè´¿ð?\Ž…ýÌ?Ð?èg/²rP“¿Ð?…n¹óqàÝ?à?›5[Њ¢¿à?×|ìy·ÉÞ?à?ŽoÐÁ¡¿à?8â#¾¤¹Ï?Ð?ýª.ó¿Ð?~ýúBXÐ?Ð?S.iâ!¿Ð?Ã[ñóP×Ð?Ð?„ÑpÌg—Ž¿Ð?ð5cZñ?ð?GµýôUᬿð?2k`»àñ?ð?’óÌÝÔ «¿ð?Æ‘1ÁÛ?à?*MB¸ÍŸ¿à?UTêìË?Ð?^Ûæªd7Ž¿Ð?vRß¹Çì?ð?Ìã’¢¼™¬¿ð?Y½Øoè§Ý?à?ç-‘”Kôš¿à? ÕÍ Þ?à?Ían’‘F™¿à?¤÷/Á|ï?ð?6ïù§¿ð? $-©8ð?ð?¼]Ð¥¿ð?1àÐi„¶Ð?Ð?íÁÇþ„¿Ð?9gå8Ñ?Ð?pÄ~81‚¿Ð?â ó2n½ñ?ð?×ú¯pþP ¿ð?U˜»ŒÜý·?ð?¿‹/N5§º?ð?¨8îIÓ›?Ð?|ô?Ð?‡+ôl_²Ÿ?Ð?Ic|Ç_Ÿ?Ð?ÛD³›§Í±?à?eŸ›íLü°?à?WêIÂ%ÇÃ?ð?ÕE³•¡·{ßÊ?ð?J¥¯ïÑ»?à? )#â0¼?à?:Å2W%±²?ð?ùE= |‘Â?ð?ˆ—ºÿi¶?ð?%GÕ>ÆÃ?ð? ‹x[,ª?à?\…7ÐHþ´?à?g›É¼_÷½?ð?a‚«9Æ?ð?q¤×â æ ?Ð?V5Œéwx§?Ð?·8ß!oÕÂ?ð?ñ‘±lúÈ?ð?pº¶ÉÄ?ð?š"K£Ê?ð?‘yrOæ?Ð?™³¾3/J«?Ð?B¸èW¯Á¸?à?Ø—¼?à?zƒ¢w¦Åª?Ð?Œ µè­?Ð?ˆ‡¬ÐLø ?à?©²÷)jD´?à?Ã\©»¨”?Ð?’ÖŸy¥?Ð?ïàbý¸`¨?à?ðÆY° ±¶?à?S„øDž"œ?Ð?¹ÉöˆNì§?Ð?¦ô»ŽàíŸ?Ð?®8¶·ù*©?Ð?PÏSOYá±?à?jÿ<\mº?à?Á2È¥г?à?ä/XÕ²»?à?(>˜óĵ?à?=߃3ü¼?à?#IÞ„c¾§?Ð?“üeæSI®?Ð?ú`9K½©?Ð?bX õRš¯?Ð?‘pÁÌωŽ?Ð?Sømpñ¥?Ð?Dºp¥ë’?Ð?ýÒ×°&§?Ð?†Eú¢>›¶?ð?Ý ”Ù]È?ð?ºhÑiÞSª?à?¤4Þý˜¹?à?Ôփ粮?à?ÙZ>ւ׺?à?¤üÕôvð°?à?=žŒ2¼?à?žôš´âÚ¢?Ð?)‹é/_­?Ð?0& :ÊÄ?ð?)aÒ5¨Î?ð?쓹󜾦?Ð?¹ÿK"õ¯?Ð?(Âc.¸¸?à?GÆõ¢À?à?Æiɤ-‹?Ð?Tª„›¶˜§?Ð?”qÔkÅ4‘?Ð?eûO/ͨ?Ð?dŠÔ•nÛ´?ð?‰J×>âÊ?ð?Œ27øŠ¸?ð?%Þà?Ë?ð?÷òSC¬?à?v§o >~¼?à?ç^”²°?à?õ-7À½?à?†JGWè¡?Ð?‹+g¯?Ð?„©®„ÒÒ£?Ð?Àòº61'°?Ð?²•P Cµ?à?å@ÍÀ?à?[gÊ̶§?Ð?b"šÔu±?Ð?E„/ÝÑÛ§?ð?4ªFœe:É?ð?yxôEz?Ð?¾Ðؽnª?Ð?g ä#!“?Ð?Ñ4Þ‰L¦«?Ð?Nb™IÄǶ?ð?—FºJ#áÌ?ð? niMwš?Ð?œ½Æ#U®?Ð?Ã=þ‚î/®?à?”b¨µö`¿?à?‰;•Ìíø ?Ð?Tdâ3S°?Ð?ª®³¦ÞÂ?ð?­ªMr÷Ð?ð?´ÿ¿8@ÉÄ?ð?gÝ~í±Ñ?ð?Cd¯Gܸ¦?Ð?“L²ÜE²?Ð?ü¶ƒß”¤?ð?+1(¤ÖÊ?ð?!·oÁÑ­‹?Ð?~HÑØ ¬?Ð?‚%e07l±?ð?Oáom@BÍ?ð?VŒŽÔ •?Ð?#Õ•Âì|®?Ð?×(ºÅ°¨?à?žÃ2ñº¿?à?yÿ[.a`¬?à?‹(1~À?à?³.(‘ À?ð?çî/« Ñ?ð?ª }ÈÑï–?Ð?pwÙœ¨°?Ð?ÒrÌ]•–º?ð?ªËPy$¸?à?†b^ƒÁæ¡?Ð?ÇK1Cü©?Ð?2ý°HÚð¢?Ð?ÒQר«?Ð?yÔ4ýÃ?ð?–k:PºÍ?ð?%ßV*à Å?ð?-|cË Ï?ð?BL}ºì¶?à?¥Tc 4ÆÀ?à?9 l0Ç?ð?Ú½ŽS¤¾Ñ?ð?Qÿ-sFÈ?ð?ïf,ɹÒ?ð?BagL_©?Ð?ô¿Bé¶·³?Ð?E•¡ùUÏ­?à?žœ ÊO ·?à?éwŸòÑ¿?ð?ÞÝÍÝh×È?ð?[zE\ìÀ?ð?½óO¥ªÊ?ð?{osàñÁ?ð?oñŽ!wÌ?ð?yÿû’ù²?à?CïÆJž]¾?à?ù¢ùÄÄ?ð?¢i#UÐ?ð?P€{¼Å?ð?eˆ”Ñ\Ñ?ð?–÷¶#TÆ?ð?YEÉöÒ?ð?iž×X[/§?Ð?+^&5³?Ð?‚¼ ræBÈ?ð?òª§]+ûÓ?ð?ìûÙîÏö»?ð?Atv¬½Ç?ð?É4A¶Ôð½?ð?ï2Ó3>†É?ð?]bËàî¯?à?Á#÷ŒñS»?à?–vWu…ø ?Ð?–´,9&­?Ð?ãÒ íµû±?à?é.ý¾?à?GÈùOÃ?ð?SÙulÐ?ð?,È^ Ä?ð?Fô²ãÇ\Ñ?ð?Ÿ€n6yÅ?ð?N07OÒ?ð?CÚp«Æ?ð?× MEÓ?ð?˜2GJ-Ç?ð?8"=Ô?ð?o)ùG(ª?à?ƒÊÞ,²l¸?à? u:Lø¬?à?ÇÐ!1º?à?Múi®?à?¿9’^õù»?à?Èå2 ‘°?à?´i’Cǽ?à?ÆB±ïc±?à?Aù$™¿?à?»ç7MÂ?ð?'0WÚ·Ð?ð?úóâZÃ?ð?g¸í†¥Ñ?ð?“èk6œ Ä?ð?&˜û¨¨•Ò?ð?»Ü!Å?ð?Uz2PˆÓ?ð?"þÆ?ð?øoCé}Ô?ð?+û5¾Zc˜?Ð?ÿưv©?Ð?ŒÏ+ùLº?ð?ÿ¿~A:ØÊ?ð?µÊÌw]:¼?ð?ˆ¡ËÁIœÌ?ð?n·tœ+®?à?â¸V»d¾?à?Äj=f ?Ð?¡‹sÓ°?Ð?˜ø ±?à?^•"“Á?à?”Å´± Â?ð?˜ª(´ªìÑ?ð?(¦#ð€ Ã?ð?HûL)ÚÒ?ð?JK[u€´?à?7êSÊÃ?à?õ|Ñ{Áµ?à?f‘Q—ž¼Ä?à?'wuá®§¶?ð?PѱzÀÉ?ð?ÏVCx‰˜?Ð?ƒÿ/¬{«?Ð?oOf!énš?Ð?gÒŒƒ;­?Ð?êÿ"Xœ?Ð?2)tDÃþ®?Ð?/1z Ež?Ð?S°ãÛjc°?Ð?Ä•ççúÀ?ð?÷Ô±IÑ?ð?ÒÄöym¡?Ð?Uþ]$C2²?Ð?]2cGî¢?Ð?ðì–}.³?Ð?òšKŒ£?Ð?â@wƒ ´?Ð?N¯HÕW¤?Ð?äuPSú´?Ð? ©ã÷ëô´?ð?¨<ÛádÊ?ð?Ú‡϶?ð?K<|šÌ?ð?Ð œ\Õ¬˜?Ð?ß?à?ïó ]Mª|¿à?™‚Â&EŸÏ?Ð?a&ØO–ó@?Ð?Kà?à?ÜÖƒ/Ë‚?à?êÝ 53à?à?Ûœ+E|Ù‘?à?žK ÐHfÐ?Ð?á€MçkŠ?Ð?p $šBšð?ð?dRm^ñޱ?ð?²–Ái?í?ð?‹á8X_¾±¿ð? %Dgê—Ý?à?VîÕ®áÉ›¿à?¯iT~ÁñÝ?à?–›`¼ºþ“¿à?[®åûLÎ?Ð?æÎ¾5x¿Ð?Ûívh¤©Þ?à?Â+ãù rp¿à?ÔðéÊÏ?Ð?éŸ8Maá_?Ð?…J@r|gß?à?jƒ{Ç`ˆ?à?RmÇÈï?ð?Ö‚—â ¤?ð?;zñ‰Üð?ð?ªÛ€ï¬?ð?jYYZ0Hà?à? NïÆ½¢?à?"·¶÷ÚºÜ?à?O¼U  ¿à?ƒHD ÛÝ?à?÷?°{˜¿à?%`Å¢hÝ?à? —©²×Í¿à?Ï¿‹ê±Àí?ð?ؓź¡’¿ð?p»¯q¡î?ð?U48 ¹b¿ð??Œ«,úuÎ?Ð?q:•G?k?Ð?w+TiÉÒî?ð?ƒüwõÆ?ð?OCºÁ1ß?à?Wêy<¯—?à?½êm ‘ï?ð?š»C“¥\¯?ð?꘎B‡òß?à?F$™pâ£?à?ÏÐñ÷:Ü?à?ÎxWÅÄœ¿à?Ƚn¦–ŽÜ?à?“ À-CI•¿à?δ|±gãì?ð? ÉáÚœo›¿ð?ž.¼žv9Ý?à?$¥6dñ;x¿à?—¹fÏí?ð?nŒJ¤”k?ð?_4|i~éí?ð?Ë Ü:D“?ð?÷[gCÞ?à?);r÷~‘?à?ü½,uŸÞ?à?E椆¼Œ™?à?Õ‘òüî?ð?pŸûUçÚ°?ð?f…ÛuœZß?à?Jc<ªŠý¤?à?ʃ;0{¿Û?à?7F‡O ‘™¿à?ÁzsÖì?ð?iQ$ì1¢¿ð?èÂÝScÌ?Ð?[-óªVt¤?ð?2º> Uî?ð?JÆÏÛró«?ð?DmKº“lî?ð?çJ;Úâý±?ð?P2TIÈî?ð?œ3¹¤¶?ð?R‹w¼$HÛ?à?^—áÛ¨w–¿à?Œ;žœX—Ë?Ð??qÔìIc~¿Ð?ÿÆUiŸçË?Ð?RéÏŸŽYo¿Ð?‰ƒ9Ü?à?úåH=R9¿à?óUZ¸‹ì?ð?ñˆ,z=‰Œ?ð?]ͪ>OßÌ?Ð?8>vW$‚}?Ð?êh³M4Í?Ð?3Þ@;µw†?Ð?PšÒ—ŠÝ?à?´,÷Fž?à?T«µ7âÝ?à?ÚdÒУ?à?Ýîë<<;Þ?à? °ÊB§?à?"%çÜÿ¸í?ÍÌÌÌÌÌì?Òtfðrî?ÍÌÌÌÌÌì?¬ÿ»ê?š™™™™™é?½ ÒÙ˜ê?š™™™™™é?6l–=ø?ÍÌÌÌÌÌì?{Cd"tê?ÍÌÌÌÌÌì?+DäP(5õ?ÍÌÌÌÌÌô?õž?£õ?ÍÌÌÌÌÌô?"Òð€+@ÍÌÌÌÌÌü?pöÇ1•Ðú?ÍÌÌÌÌÌü?°YÅþbW?°YÅþbW?°YÅþbW?°YÅþbW?mrcal-2.4.1/test/data/test-optimizer-callback-ref-J-2.npy000066400000000000000000005300501456301662300230760ustar00rootroot00000000000000“NUMPYv{'descr': 'NÇLrã¿=;ä«@™4ý3îÊÀÿÑemào@ŒÏÍ|5‘BÀ¸¹…çVÀl%ê9=á?r®cûíð¿´€Ù#Í2@dÈØìc%ÀàÏiãƒg@È“W#" $@T{á œæô¿îå7à0@º2èËà+ÀB%ssq`p@¸ƒ2‚CÀ1M |¸WÀ6‚ðø·ñ?´ïè‘E$ÀÆžèÖ|C@üâî«T&ÀYhbÈg@„#˜­$@"ÿÊ™¡ÒÀØ•éšëI@KÙ2o¿EÀ‰YèybÕ€@ÂúB Š{TÀZðÙŽcmiÀƒÀHj&Q @œž.Û=À¢ºk'‚Ü\@BÌW\)»6À6qå˜<x@^º4@”0 ‘% ø¿¼ŸŠ«©˜2@ÁzpØ'.À¤ß"`¢Na@Ø“kL|5À¶V¾¤å7KÀ¶QMD}·ò?lUñ!D-ÀXÕ©¥¨xC@ó¾éÁ•YÀ“ÐYpXX@ k>üÅ@€4‰ø‡Àô“ø8@‚ ñÒÿ–3Àù5×’Ëa@à> hƒ6À…2ÿºÖMÀ†¯æ ø? ‡ávã9ÀR‰s¸¢H@:IŠ4èÀr ;Òð£X@xLˆùöÌ@ôÂ){»™À"ðc²’@@„t$8j8À•RlÜMKb@9‚`òŽ7À^dp OÀ¡H%—¤ý? 0›Ÿ>À ÿUöíM@Æ ˜`Àõòv¥ñX@¾µxŸË@D¯x[¨ŸÀqæÅŠô T@Äÿ1 MÀ/‹ª€žÌr@(úLHÀ±_UŠ`ÀíÒÃäÂ@8Ž,R1À&xð­a@Φ,ï0»(À:” ÿfAi@½´Ú[½$@.#£(À‘]8†ÔtH@q«,g~AÀŽ­tiéMc@m°´½¥9À=´uÿ,–QÀp¡k‡w×@p` ®ÝÀ<%/3€tT@Ô0v9ïÀÕÏénü’Y@8'Í!ˆœ@iB&šÀË]9ûKM@šœ‰ÀYDÀÃå(×Íc@$ް$«:Àœ…Õ£¨RÀó ȸ@öòRJÐÀᜠÄ:MW@Œ>\¬òÀvŸêæY@lWFYb@–ßrÂ-ÀŒž–ò#Ü¿¬úPÎŒ8HÀ® @rž¶~@—'?…º&QÀɯuŒYdÀ˜ùðáÜï?8z_H‹ª´?Ü™dÿ Àm|©¯[†0ÀYbA©w@¨[ŸA«Æ*@)ùçÊÁÚ ÀÚ•4>*ñ@7R–Psn?ÀÆo¡‰o@tlF¶3BÀlKÄG™UÀâÕ´Fºð?ø]d9A–ã¿öNÙA1@rãƒ!À˜¾[S@g@g—@ ÖdrÀÈìu©:·@ Ëè_¢™3Àp«l§U3`@&CŒ¿ð2ÀíBíè>1GÀUÙ€€è?,#þcÚüã¿¸ÒÆ2@ÎoAGÀ»ÅŸÝ‚W@¨-¢51< @äˆ8 óJÀl¡% /ý(@)â!+TÇ7ÀÏuÇæ°¦`@½£ëâ3ÀûÌWú"ÞHÀL7ÑËš»ð?¨”‹îí¿Å¦bÃÕ;@R£ß0X"ÀÌÅ`¦ÂÇW@Чô¸=õ @ö¡Ë>xiÀ@…bžü1@Ðc)—C<ÀÌüù“Œa@ôáÔùÜ4Ào{²Û¤ JÀBÝ/tõ?4pcØËó¿êõ›ãB@ã%¨ÌÀ[ŠX@è."D¨ @A²NÑ<À“>×4X@Üsyÿkˆ`ÀÐ1S_š@Í¡óþÌÝUÀ|yRÞÈxlÀË ‹l@PÈ$ quÀĺ7d9úg@OŒ8@ 3ÀèØ¾,ŸXx@SBÃ=P)@h¯.”ÂB0À£v»]w0O@nXÌ!SÀ5CÕ_r@û"¹ÒãFÀv€Uef^À¸íV£@hm¼:ç À\xm1]@P˜}/7e#À2ÞD¢€¤h@€å ˜Ñæ@DxxD2À:Qù–2~S@^N[ ÐUÀzòò¨všr@žÌ£êìGÀ¤ùØ(3`Àœ„øÈ•Œ@ØyUÚš‡Àñ7<“XDa@ù½uB¥#À×D%Œòh@hª d@@Ô!5ül$ÀàãþÄÐG@¥Í’r°HÀ·s‘.c@tMÙÝGö8À›ã-ó£žL[WÀ|!šOA7ο0{A+ú7À¸Î"f^@~Øi#Vª0ÀØèíg8£CÀP£s dKÆ?ØPZ"–?¾o翉 ø¿ Ät…?þÀÆ|•ÿÁV@Ðõ7Ñöˆù?¤:‹ÑÉ/Àu‰ä4~@:Ô;´ÔKÀÃ*Í–5o@®RÚÒMƒAÀŽ¿¦ôUÀhñÖìÅ”é?ÀfOAíпl^Bº§.@¦)60hÐÀf½6pÿf@ȷϸN@›ºØÃJÃ1ÀÌjW-@ÒÿTòøOÀ+_ÍA•p@űíÃ]eBÀDö§¾¯VÀ|œs5,mô?8‰ÞUàFá¿)9ãíA@ü ó¾À;v4T@g@ ~Ç6ò@§$YytÊ#Àº²Ö4# (@¾Xð?_5BÀ}{Ny`@rhÿ”7P3À…Ô†® THÀ„QÐ*¢}ì?p«]}Ù¿d; ñZœ:@̦£Tš^ ÀØV ƒW@`¶FCÄõ?•ÅIü%ÀéF­¿H`1@¢ýqb±–DÀ±\u¯ï`@j‘1ØJC4À‘ö-q¥JÀ´§y½~ò?U  ‚ß¿ó*(»¤4B@b¿<— Àv­ypÈW@@êò*¶gô?FÔÍZ(À/2r¹p7@| JŒ¥!GÀZ‘©Cja@Äâ>³=5Àçîÿ½ùÞKÀšG–ϸöö?Àõœshvâ¿C¯8G@°°a㥠ÀqD‹)X@@ècŽrðò?êþΕçJÀ´äõLC^@]ЬÏÖiÀTBFYè@4ˬ›%>VÀÏüå¹ÄmÀNìVy¦@0ÁQ`À—9‹ñr[l@¶¦Q›-À“&Ïô6Zx@ð®&qS@Žé!‡£MÀÿ¦4=|ñb@V¤5âµlÀ^PhÎõh‚@óâ6KÕBWÀ²3 àì¾oÀ¸­ŽmoF @0À[ÓãfÀž¤¯ßøÎp@Ssz^-ÀKd4õƒ¦x@€czßP@øû2ŸHG0À\Óo,G@]üÁÇ`½OÀËífÆêb@xÉ ]I8À’"{¦ßåPÀÎV’ØÝÓ@°B‹X忇¯ÆA{€S@žÕíj Às"nºíôX@€‘9zÞê?°5©ÓQÀg!Â…™Õk@ê+>("uqÀÿÐallƒ@Éôpí NYÀ;A¹$ôqÀeØKÌy%@P™9±ñÀWK¿Œ€Bv@0›‹›'--Àó޾@Ey@ ™äÿv@6Cb:‹Æ$À T^| 3Ø¿¿¼ŸècÎAÀ*3£\^@eáÈ‘Ñ30À?¥V^r4CÀàñÆ6Ë¿qb×]kp?Lõ©‘ú5ÀÈâ¼cK6Àˆ°Ôà€„V@’°šæ,¼¿xDÂY7ÀïP~"Ô-@ü$4uÚSÀÈã\(Hän@‹³<]AÀâÚJ©TÀ0ó¿ÀÞ7XP¢?˜H/ÏÐ*@ö2…ÂÀa4Áf@€2T1·&Ý¿ ÔŠ“rIÀeþamMî;@Ú‹… fÀR5ëTbº@3 ·>õßQÀˆÏäH 1fÀ2êé¯ç?@ñbf6Ì?ÐxS‰“…O@’iY¦óG"À\À@ñíÿv@ Å,•Oö¿4ÇÛ,À¬h›Ðk'@X2MÁ…fHÀBðU?M`@4ÑJ,jÃ2À¢ÊFçýÎGÀ° ú¬Ù?À0­ä¤o¾?3]쮄49@Tç®ÖÁÀUÙÛAW@€`)bGRÞ¿Í `ŠÝ>Àÿ¿12£Ã@@¢HùŠ!êZÀž»3Âp@«,QS¯CÀÔpÌYÀÀì[ög!ô?@2Á*¤½Ú?oj?)tnQ@4á™Ö{*À*‰$°–„g@ÀµIDA[ó¿Ø92âsð@À/8ßÀ®F@¼C…+“˜]Àø®GXQ;q@øŒ”Çþ¢DÀf¡j1]J[ÀX¯?ˆmÍû?pJû¦¡å?‰Ióœ6ÀÉ:7¨OÀ¼ÎQÌö?Ð ‰ Îmå?¿:ÌrMP@Ä’¾N»³ÀzËÖA]X@Béoâð¿@¥ÚŒü6Àa„š$ŠF@1’ÆÐSSÀÓ7¼,â¹b@t}1²Ÿ7Àœ=q­‘PÀ€ÇÀž|ú?ðtü·âÝì?+-1 ßóR@gU‚ˆÀŒgÉÓªX@ 2烇¾ó¿ï£Ó†³HÀOó–/"[@/àty½ýdÀm軡;s@¯³ì¢HÀ(£‹ÁœaÀ1Îx)žÿ@èˆ+´üö@˜€£kªe@–%?À\VÚgÏøh@ÐcëŽîÀó-¾ŽKÀîç‹^x&ÀJ~‘ƒgÀp>J`=Í}@SÛç…OÀº \ŽÒÉbÀÂ<ÒW· Àø†N zÀ¿‹ˆ=M‡Á-Àœz—ÐbÀÚ[eFAJv@0æ‘æ`ÀòO>ˆâÖ-ÀaVú ]%@~XÒu­IÀìc‚p¬•^@ O20À>íL(ˆ7DÀ(A2ºÿÒç¿ Ë¤o„Â?bO>9Ò@ BÙªòó¿cž Á%…V@È÷v‘ãþ¿6øDfüe0À-‹^¤×{@úkÎR~þKÀpûǬOh_@à²]b`1ÀQ }ãá¸EÀXtARâ¿ ®ÑEÿšÖ? „8(¢,@p€¶´qô¿;ÙÜB@ÂV@1%üd½ÀX9›(üAÀ²Ú™ö!6@2|á¤x^Àºgø ‡"p@¾è:¬o™Ìùì¿€Ô„-ì @%a%›‘`@lظ¢—À\ÑŒZCw@'Ñ49}#ÀOï¯Q€EÀ·w¹o)ìE@QvST÷aÀ,¾Ÿµ• q@)ÙõlÈ DÀº§×ÖݺZÀ€I\a±~±¿ht„kÉ@(DPÚnU@0â{/À£6,­p‡g@<ˆúaü÷ÀT!>åp7ÀÌÔ*Èm<@áÈ×=5vSÀäâëg‰a@¾µÚ¶5À&VÒ“‚‘LÀ@›“Ó~hÅ?<².Ò¥½ø?äÈ%ÑÏhJ@ØqO²Øõ¿ºÑe‹æÍW@\ÆÛ'ŠÀ\ÖÊF9ÀºÔ”|”ÛA@dkð×P UÀÌiPavb@:û¯¢û5Àõp*Pc}NÀð,½%Ø?MƳ6ÿ? £!€O@@ &OŒ•ô¿áœ©Ý´X@XPW[Ù8ÀUŒ!Q±[ÀÁ-jUée@d‹„‰ïµvÀôœª‰‚@Ê£#ÔùVÀ¨Lê¡>pÀHŸ= @õ²uC#@G@¿ƒ[r@lYr²òÆÀ¨ ÑDÉax@H€ò *À¸ßýÿ]Àíå}¢5dj@ôùy ”txÀ6)- ƒ@ý†sýùWÀ*^v}GqÀ¨L£ Ç9 @\6H f'@½úßyu@)"@̈À0ÿ ïx@ȹ4á´,ÀÈÑŽáwŽ@À:"\ýá±ö¿ˆ£’]ÀaX´Ã¶„m@”›p}ý®>À[©lþ$cRÀ(Èuáó ÀŒÕëgõGƿᅮ·èK$Àð%:ß×`㿵!d2f@¦‹T-ÀÁ\Ò.»-RÀ¿ÃP5B$@[È~ÙdoÀÌKÒŸ·I~@"Y•PÀ´ÜVi5ÊcÀ§\ˆ=>À@í³º Ìï?>YÙˆÐ-@0”ßRü‹ó¿^P§zKv@ˆÌÝ ì»,À×^x $êSÀÝÄ;âøÿ8@¢½¢ŽóépÀœ¡|ë@I)‡xæPÀ×¥£·˜DeÀ\ gÚ_hÀ§_t°î@Œ»ÙdjI@׬dó¿|æGí†v@°€>T`X.Àß4›:ƒÅUÀ‰£ÐM¬(E@·»N? 6rÀÖIÁEJò@@÷(»QÀvÕ€DÓfÀXÔÕÕrÀ€¤ž¨ô@ÐÛiNàU@`çX˜Íò¿7­¬žÄv@ ~Q…0ÀâxÁWÀ™Iy‡lO@bsÒêQ™sÀ’:ÒÈj€@ê´§Ì|˜RÀØÜôvwhÀDÎNCž^À_|àDø@}ÄÆA>_@ TaG¬¤ñ¿ã¹?žw@Óô]â0ÀÓCØæ¿ßYÀ“Ýl—Ð*U@™ 3°uÀoòòëá€@@Ž(~SÀoØãA_0jÀ˜}ä5B-À("× @â7ƒ¤hd@@ûœÚG…ï¿Ásvý÷Fw@¢f48aÍ1À|Ž$B!\À]Un…[@Dýu£vÀöýꨡ[@U…gNkTÀ¿­˜„ÿkÀÈHYqðàÀ2OJ€$@+âfÞMi@à¥;põé¿Æè•±‹w@†h“˜„Å2ÀknÞs·†NÀ(‚ã“yRQ@2!,N^JhÀ‡Õf­Ùq@(}>y$_EÀˆý ä]ÀØrüS5ùþ¿LNU£wi@ÚiÛ éO^@€ü&±Ø4Ò¿ö- îÈÒg@Œ*ƒ Í#À>ö$.ˆ@À´ÔJE@£*ÊùäZÀßðTö@Zb@D›´*X6Àxì[x4ÝOÀ VÉ&ê¿ e-ËsÑ@Psèá·Q@€ ú•L¯¿3dD2X@Êbá†æÀ›Ë;ÛÞQÀËkëò®Y@åÒ71ÚkÀ##ÃQÜr@¡ŽojTGÀJÐ: tô`À¨Y;áRøô¿ä}$/^c"@rƒœÝ!Wd@U»…«¶?ÚMýÔgh@N%GÜå&ÀñIÿmNpSÀî(ÑsDº Àcì—ĨOqÀòž>ñ¶>}@ûÖAbâMÀ/Î7bÀvúb ø)À\fûÆ$‹ä¿:ëØt¿T:À@ÆÃVt@®~øá3Üu@º¢•î3À˵†L5À}¤³o¦Ç@¬ð™ RÀˆ,”b[^@2õæH—Z/ÀßI-˜å`CÀl¨p‘‘À$v×Õ?”EábP½@X˜÷yaã?»òIŽõV@æÿáßÚÀÀ”HWÀxiOmœz7@ë àÇsÀ¼Pn„+Ì~@GáJ0rPÀ‡6h¢“ÔdÀØBjƒè(À/¸Uí° @Þe -8áE@ðã\€@Áá£õÕMv@2·9¦ïÏ5À@¹¨ïSfIÀ ¡·r,4@xdràê"eÀMXüê-¢o@[=#i?AÀê³²@\VÀ0­0ö–ÀœH+®<3@oÉ_¿í÷C@@W±éÞõ?mlÈê‰f@øP6BñÎ&ÀkRŸââ¨KÀÆ2Ó¸—Ö=@Þ)G÷Z•fÀrj©¾Ap@YØ\³rBÀjqƒ:ÄøWÀ¦Qk—lÿÀ!Z¨qD±@û™jŒõ/M@üAÒV‰÷?R ÎëCÈf@Ö@²AÙ'À4…*bNÀEÇ€ýiD@ Ø hÀüS¤ãµp@è0ôÞóBÀã¹Í¿ªYÀ®ënzfÀ¢¯¢…Ò:@}ºe"ˆMS@ å§Q “ù?rß§íñg@ŠYªòrð(À%ì“PPÀÇo=œžJ@˜*rý‰ÀiÀgM…‘ /q@îô1ÚCÀ“áÛE~r[ÀÊSe ÆÀz1iàK?@è ÖŸÊX@hPü`á ü?g×ßýKg@š#9šO*Àª–Éq¬aÀ®xk0›Ê`@l¸°'—y{À:Ú\oø«@¿Z$Ñ ÇTÀÞ |ÖOmÀ¶*5Û %À®{‚z¤d1@+Íã m@ˆ6ü‚@=B±g‘w@L´ÐÝL;ÀnA[vSÀ5Ø7~¬T@àáRœImÀ+\.ý¿+r@½¯—{þºEÀ5å¦B_ÀdÌ}u4vÀLã Ô–ò$@DÛKp a@LB*?°U@AŠH/+Ùg@¨°Ð–[–,ÀÜßl•ôŸDÀI€eñ´ùH@DÑaD//_À£„{,­b@¸m†>¥²6ÀF ™9¸£PÀ&ù}$ËÀ3aá\­Ð@~עלS@ZE—7~ó?ÞÜB,6#X@È´ öBõÀ6k`·2VÀ¬„á2úžÀ‡ŸÝTtÀ¨m^z+û|@Á!ÚýMÀeË *Ø aÀDTw½¹™2ÀÄK]T)ð¿Å#z@Àòö½0Û@”W¨'¨u@„ÁV$'":ÀqP¹íBHHÀ1ÕóNå@‹Ñ3BCeÀî÷A¤‡¹m@áfEµ)Š>ÀÙ˜tgûRÀÿSjqœ"ÀìO•S`Óè?H‘a’Èã?(ˆ0NÏ@aÄà—wÞe@^£Œ®ó1+Àt-µÎµZÀ?=òŒªë5@ê•(~o—vÀ¨‹ã‚~@µ–4ÇPÀü³ê¡hdÀ$ºÃëCœ2ÀÕLnÕL@/ûð " B@Êܳeéà@m:ĵÚv@ìÊÓaVL<À ìJ§·àLÀÇÊ€*-3@}5¼JìhÀU ÿõ°To@ŧã/É@ÀfŠréUÀbçÛÒª™"À2—âzH @Táp@˜Ï -g?@¼—à¼c@±Löf@€²êQÄ÷1À'—$#¶QÀ võnH[;@LÎXÙèdlÀ*öH,Kão@×”DfAÀk< "¹ WÀ¿›. GÎ*Àîw²­§?@vúk”cžH@Áø\cV@|ÃÂê?Vf@S¦¥-¥2ÀemJy›úBÀÜ'é2@6—Ï ^ÀQ@ÎPc`@Ê*ºxï1Àí"@c†­HÀÓjWú.À„%:öÐ@@-Ü@@žcïFÔb@e‰n0Í“V@âæ/”ËZ#À£ñXê÷ŒDÀâ~/Õ8@§s{×5Ð_ÀÜ2s3—Ù`@ž¾%ò¾Ç2À«9ýSâfJÀê"ætaÀ”hóñP@ï³d½E@áè :JŒ@ êY¬ÓV@zUl$ÀÖ¦b7FÀæ|?@<[´Õ`À ƒ—\ýSa@é>¶_Ƨ3Àì+¯ùç5LÀŠõyé%±ÀÊHªhÕ%@™©#º7AJ@Ý@vÖ@#-m_åW@Ôhj@çá$ÀáÕ(úgÀ„Dú+vc@L›TvŠÏÀfÞ|ºÇÑ@(Y™9ÐŽTÀ ÕS6-nÀb<]c<À%éÙè`V?@­Ÿ´o@«GÃ÷…C*@LÇÊzZw@*ó‹µEÀ&I{ÔiÀw8H9õ–g@G\’YöÔ‚ÀëÅXtðQ‚@^âY5¾{UÀlÊK pÀÉrõ\b<À“E¹’þtB@xƒ]% r@ 9ŒBÂ×+@\be¡w@D°ë:ö“FÀPò®oX\KÀø—¢ôŽØÀ”rCÌbLiÀzIæb${l@9#qµ;ÀRòsìPÀ=§ô0À Їã ï¿$Fâ8åî7À~ fôq@ÜÚñoEe@îtûF>3ÀÎŽðuàá=À•ÿëf·ùô?•ì¡1¥ZÀ¤ÍB33]@T7t±-À ½t€#;BÀJpû18!ÀòõUq– Ü?ö/Bðo ÀÀ×h›Òc @Hê.tyU@PÂXÔš»#Àç‰ o2H`Àt¼5ñ°2@DÍ(Q|Àº1Ó-<õ}@ÝÇîfNÀÚ¿ï:œcÀªµí~AÀºØÂ49ò@ãy«9G3@¬¹î,fi*@`êòÅ®u@Ó}ÆlDÀªÉNDJµQÀ$)¬‹ö$1@ÐÇ+ßšmÀ¤v/gÁn@†éxÁÖ?À^@µcUÀÊCò-Æ1ÀSiŽñþ@‚Ïb6µ:@¬)T …@`H÷}æe@’°ru!$5ÀdÆ·v‚9SÀŸ7Ø@o:@?;×9oÀ²—o@îg¬@ÀÖmÈ‹”˜VÀ! ÿá2À,ÀY‡›@1Œ"IF@H§Ü’¹@8r®] f@ÊÓGä5ÀKý­ ÖdÀ ¦@)R@«ö)y€ÀêîŽZñ;€@<ù9›ÿtQÀoºÞO›5hÀS\Æñ¼^BÀZ¡2t^n3@tP« Ô_@h4'Á` .@ZO_w\v@Þ‹Á‰5®FÀ¼ÓpÝ‹fÀQ~UòW@O¬7íaÀø«ìF»°€@–wØÓ:FRÀlD·ŸèiÀÌÖµM°BÀ7=š_‘¥8@œ[±\d@œÂ™4w/@ý̾ښv@ïäÕ®GÀ•œZ3¯[HÀôQdt>@Fõo£·WbÀ´«>qÇ)a@h_$óf3ÀÓΈÅ°KÀx;Ÿ'#À¢KzIg:@̪û*ÀH@`ã˜Ђ@$wÖ’ÛV@#„Ö‘Ô_(Àš@ôÄEJÀ¯ü@DeÝB@u€ZcÀxJ7Öl¦a@·$ø=óÿ3À¶pÃoMÀ±Eœbä`#À{:Æü"@µƒM@–“žl‚[@~=<†¤W@žê>7rI)ÀN¥ØËIlÀqÚDÿèf@øE „h„ÀÝcÒ»%‚@äár¤úæTÀÑØ<oÀó/'ÝÁCÀ`{d÷LE@Tù^B‹0q@¾7šû®F2@~ZäÄ dw@mf¢K?JÀær¼ºzs@ÿv”ÎÑ%À¿iMºa4=À‡[€û%À¿UMfØÍxs@“âkO}8@ÀŸòwK%Á¿KÔ®ÃÀ\ÖÀÕ À&†ã潓S@Kg¯0½0¤¿¬H¥’!À*Û( ­Åê?‘çuŸ¯hù?ñ £g:@Ž´¯Rñ0¤¿ÏJk9õ‘S@¬SÝáGÇ!ÀEµ5“–eÕ¿ È6ÀÓ”ë3À»ß<Ä­S@â“æÏèM¨¿wèQT,}#ÀýÐi@`ú?×î!¼ ‘ @ò¾2{©Ÿ)@¥Ÿ@‘'N¨¿ÇGæ3i«S@¥\óG^#À,Q¤|‘Mó¿|„„Ï~(Àÿ¶.6ÀÛ›UÍÆc@–À†ç{W¼¿Õ§ÎÖs6À¢è)‹èy@Àrt€Ï$@r@ C@Ž¡ÅW¼¿á͹í0Åc@I¸) Áý4À@•©_+À®»>“.?ÀðqáôMÀ¡§øaÒàs@3µ®%rпÜuþÍÓ’HÀ¤y…Ò|Œ)@ª«d•¶ó<@d®¾Y@}E ›пÁ’†œTßs@îjÔÝþ¥FÀj’¶J¯ÀÀÆyÙÓŠ2À*è €ÚöBÀ 7å–<ûc@nVì-»Á¿P@QÄ1;À/…Ö/‚e@vk)hûÜ2@Ðw Bï P@þ%Ç´[»Á¿7šÝùc@‹Eµ¬VW8ÀÛ÷ö'} À8ú„è†5Àœ7n> GÀ¾K—«d@øà6ÿº³~ ÍÞ=À¤CŒ»C"@ YE:¤“7@°hÀü€fS@`Òóhÿ®zÖd@fõL(:Ài СDÀ8˜KÄ97ÀkÎ(JK>KÀÑ@„1d@C„\оçÿ4¢ÈCM@Àö)€0%@tå,‘z <@,HÂ×°V@&¾âïñçÿÂ%ÊK0d@f˜OáÖ;Àî,êp oÀÞ&Ôaî8Àôßü ºŠOÀo6WU‚Md@Xn0§!Ä¿ZqfíвAÀ·Gz^#¿'@$ß$A@[dzÊýY@ã¸z+Û!Ä¿hq‹ËHLd@w…(Šû¥=À^¦ð€[CÀÈï"B†0*À‚ ŸÊ§ùAÀûÿgÆ4jT@Z€9K‘³¿%¬g„p 3ÀÈ&¨ÏÄ+@4Ùèä3@ýèã¦OM@À)ο}‘³¿†ÓBÞhT@ÐK €/À°©J‡0B@{Œ#uë@Á3,9E¯:À;ô;‚Us@ó>ûægà¿¿ø¨JØÓ:ÀvU®"×À­"¤e•ž¿9˜Å~:-S@£`åº2$ÀXŸÏÆL‡#@\{£@â0t/ÚPÀÍH¥Is@ãÕi°yÿî$ÕÅ´(=ÀÀ9  …9À4GÆ™M@ ¼i”ŽÀ{Ê0³âyÿÿËgŠ—Es@³ÒÁšÀEÀöëϰ׳@з):0‡ñ¿ +aÄ‘4ÀQg =bS@m\.s‚©§¿¼~„ó Àè—:7ÍÀ¸­x·Q” @vɈn…Ï@¦Ö Œ¿©§¿”ÓC^S@AÏrÙ‹V'À>$Y"£@œ»9òr(À†¡”§C_XÀÑ]Êa@{s@/'Éqj³Ë¿Â–ðl¹^CÀjØòTþš4À ®õ»cØ5@»%åÚ{fG@:œAø±³Ë¿ú ÏçEws@!ÖTJÒôHÀˆ=ù… ¸@Ã]ÎEnX3À8ªÐÖ¶E\À5|‹_–”s@fH9GijÏ¿Ò þ^ÖEÀ\Bæbˆ2À n$C}‚>@i-…¾¨ùQ@† 9eºjÏ¿»‘ÀK§s@EüüX»›JÀøºè¹N:ó?­I5¾¸)Àû†"PÀײa{K®c@©ÍaüSMÁ¿ù,}‚åZ8À<ȪIÌ• Àe¼˜æ3@Yy°-GH@Å-©€MÁ¿/î~Tqªc@–"ÆÞK<À‰–—Äæ¦¿toÃ?TÀI¾&õ.BÀ£s nÈS@4õ„„²¿³æUÌì*À®1ÓfíŠ ÀfãÚñ¸Þ(@ü?M Ú›>@¨‰a賄²¿ÆRƒ×®ÄS@0¯ß¤Û.ÀP-›džø¿§w¥B2ÀÕɺ€HTÀE’¶Kãc@Îï([9ÿ@EtAÅá{R@QW-ÌŒ9ÿ£Uxëkßc@.tFÝâÇ?Àè6Ç…~5À“À³hDÀ´ÍM…ofÀg/)³>þs@Œ2°g_FÓ¿Í3Íî„PÀ(CÄkß 'À÷sÙ&õèQ@½w #­e@‰Š,‘FÓ¿8ïœûµús@¸ù"Ý—ÊPÀ8=·ºÀÇ ¼Ñ¤5À¼Ñ˜2g¤XÀ÷2(Þd@jÛ_Ô¿ߤØB]|AÀn#Xm¯]À«·ÊWéD@ÈPÖ2ÚâX@J³û(‚¿ÔðÚ›d@.MP§¶AÀs’š"lÃ0@ŸßMǨò3@£¶Q%Ä®SÀ¶,Pë" s@ÈV¤~¼¿ßÚin=@6À¿þo¤ÿDÀa÷$°Dñ¿Š‰˜ìäÑDÀ/X 6Y~¼¿Mø¼_s@1VC•mFÀ-k»C¬.@ £èž=#%@4 ŸŽgw¿6,b^ s@¡Ê‹½¦GÀD['ïF@žéPMû¡í?¡b¤KÀ“¦3²½=c@uAOK´§¶¿LðÿÁUw/ÀšÛ|ß13ÀÖwÊß§@¬ÓhÊò @ur€Êî§¶¿Ôei®8c@7Oh <9ÀÅäVNüO'@tùVA¯¹À4çáyØ^ÀFá«cpVs@"”„Ž¡©Ê¿ [•~åBÀÆW‹7BÀª±CãÀ6@Ž“ýÔ?@\J·fæ©Ê¿.«úÉUQs@!rä¢ÙJÀ—€1†Å@¬­c Û À0e<Ž-`AÀre„ÈsoS@ éç*äO®¿8E”ýA†$ÀÌÚ¢tj!À2Ÿ[Ûþ@;±Ã D,@Ïko2P®¿Y¬¿J^jS@+h"Ì,ÀŒ ú D@–*÷ó4À(@K˜s`cÀŠ@ÊÓˆs@uÂÿ[³Ð¿Àÿø-þFÀ¶±K›®@Àr*yáêCD@ºÐÞ†UT@:©: †³Ð¿uw\уs@5+íÒà.NÀÑ“6Aµ‚@¯687sõ9À×<’bmeÀ›àž¢s@[õŒžÙÑ¿x>óÅ$ƒIÀ$–+Œ´@À_Å÷ÎZI@FÑ bÐZ@ÛD•&ÌÙÑ¿@ïò¹s@Qð˜©CçOÀ JŠÅÇ?ÆÆU*,À”•F£R‡GÀÑïFEâ¼S@ó=Ãy²¿Yîq±,Àüü^ÛÀ+o1³Æ.@ØÚÌyh@@{2ÆÑ¾y²¿eÞr<$¸S@å9°Õ±Ô0À(P{½ÅAö¿E•žÝئ1À‹ŒñI¡®YÀ£¹ç±×c@´ÛËn¿Uf çp¶>À¦´b°“Ó-ÀñŽí+EB@ÌL€ŒS@¼0b@n¿]ä)´Óc@c¯åÞºAÀˆÍ¶¤–ú¿¾ÀËŠ_#ÀB%²ãKÀÿÞµ óS@Sò8‘䱿Š!è$ ³0ÀɤÕôÀU>ÂUT5@kƒXÀ ´F@X¹ºäޱ¿¡m34µîS@X\Ho¦2À»¼¦xYß&@íö@1p*@øI°ÛwJÀ«uߨéb@üŠÝÙ°±©¿ áctå $ÀÞý0AZp<ÀœN»ŽñÙë¿èv;J®;ÀïÕÝ1󱩿Sab#äb@qA8Yðñ7À‰îB,@ÇJ¾›Ÿç@o§è¿àª=À±3»S@kUG¡¿<#Dä‡À_¯C“s¬+ÀFó¸Ï"—ö?noú¯YÀæ%`H¡¿Œ™±ÜÉûR@<õŒ} ~)À7u«ß2#@œ=qŒ  @=†ý{²PÀ^OÛc@©C¤Ø‹?µ¿éH(-Àùu˜Ú±ø:ÀÆG5Ú5@…BKŽ÷ À>âµÂ?µ¿?©€PÂc@…|gA;ÀŠfïæ ñ@`}b5{©¿Fnðº$›BÀ¿q®Â?2S@;²Q 4©¿Z4Ú­ß ÀŠ`±¹U*ÀŽ”No&@øH´E÷@eè!X4©¿üC.›,S@":¨ª°,À-vzÉ @[pÐÏþèþ¿ßVN¹DÀÌÐ;vóJS@c”ð‘•Ĭ¿eõÈ?#ÀTÝÚ5Ä)À$×gƒ»K@¨&êWì¢$@ ~¿ÙßĬ¿Ÿ¼™ÉDS@@š)LxU.À„¯Šñ@쎼üËÀ¸uUPˆVÀœM´‘dc@ñÜa½¿¿ñãV‹Ñª5ÀàìÚD9ÀRĺ›Cˆ4@Sóa{k@@Á[ ³½¿¿d:ë]c@ñ†lùÚ@À€óZêÃ@[²L÷ˆ $À˜ZiåXÀA25-w}c@L¸ÌøñÀ¿ðGÂ>#8ÀS}ífØ8Àbi!V°¼9@,EKOê‹F@˳³×#òÀ¿¿0Œ„wc@ôê ›Ý@À$¦Ç–›@ÄÜu’†ó)ÀS¼Îù(¸ZÀšè./c—c@°Á–‚9{Á¿SOL.ë¨:ÀFr¥8ÀšŠ‘ºE?@AºÉϲL@·ä¥f{Á¿¬D'Ô¡‘c@a+éw4¾AÀ@·aƒè¿£ð €!ÀCn×àOÀazAµãÌS@‰S5нX°¿Kà]{Þ/ÀßB½#¤ (ÀcøÊ>e°5@RGQà"ŠD@ëóv¿çX°¿Üš2ÀŸÇS@C»öŽ3Àiíó8@¦[ €ñl @wc~'ÿ"@ÀàÄ9$ÇR@£i°ÕG–¿—h.¨8êÀXÆY"_ 2À H…XlZä¿£-!@1À Q8H–¿£=GˆÀR@EÎCμ)À?•ÙòB@Ëm8¯ +@èdž•õAÀè›±½ÞR@%1ñö߸ž¿»ùO´NÀ>¢ÏŠÄ1À®\çÃ/Qô?ö}`J®&Àí ˆJ/¹ž¿Ä€EÇÚ×R@Šo ÜÑH+ÀÙ›ç939@Æuþê<,@QŸgÓcÀ`/½’ör@ÛúT‹<}ÿI_ïíÈ:À³AIÿ2‡QÀí«¯þ‰*@eO¨'¥ 5ÀD»ØÝn}ÿïwïr@[Ôƒ¸ÜLÀj€&@ì't`ä@®cs½¼UÀ`u¨8«c@О† _·¿ß¿Y/À<Ú¬RAÀD)Ã9 &@Öv¥±šñ?lsDùV_·¿áÐ;ƒc@Ö•=µÉx>Àƒ“xÁ¯#@î³ûrýï¿ ©iôä±WÀ:º@ã'c@ƒ@¯\ãÔº¿„±„Î¥2À>´•ÕQ'AÀå/aÅäj/@š¿Ša*@V5“¤(Õº¿‰n•Åéc@:’³ª@ÀãõËçw‘ @ÑFëB ÀZõG,³YÀÒÔ0Ñ?c@èüÌ䫽¿ibÁ|`4ÀºRxK€AÀ§Œa,•´4@Lø?ƒÅ9@«Ûj«½¿Üi[¿8c@†AùšZå@ÀŒÜ6 tF @º¶Û84«À¶p8†çÀKÀ¶­G)õXS@mmX!Ÿ§¯¿ÌÂ;ÀÌ&À½r)œí0Àâ[6_*@k–Üû2@l·dÝ𧯿(ÔîRS@>Œ?Ó¦À1ÀòÈÍßÄ"@á’ãÂæ4ÀJ¡(JoÛmÀ"zÿ“Œrs@M᜿•Dпo@óEIÀø¤=½àPÀXoªLeªO@ÆN½*X@Ö›ÓÀ¿Dп¿ 'Õäks@&£SÁÇ RÀ ©òc1õ?nén×Ò³ÀŠT—ÑPÀI„_§ŒS@ gް¿n: j©Ì+ÀóѤLÝ0ÀžHþü0Ó2@6#Ð×~°>@È´s·°¿²™¥N†S@Bµþ§ü…3ÀÀ ÒDÁÛ?^ƒÆ¬*¶-À¤îm1aÀ?(j”W§c@Æ{æ ѽ¿eÿ,6‰a>À¿\µÌå@Àn[ÂÁþE@Ø eR@ü^tãVѽ¿tBB[¡c@",pŒpDÀOËF̹æ!@•-ÅÙ˜#@QP kˆ5CÀl{3…¥R@¯¼½fY’¿ÁÖ–l©À6¯üÓõ5ÀEµÿ¶àë¿%‚tïC¤4ÀÝ‘¶–Y’¿}ú“­ŽR@m’žvz+ÀÁ¤Ë @VúpÓb\@üIîEÀÊH|S¼R@œ²¹š¿cš$ÄI$ÀJæ`Ë5À8÷Ó*éuñ?˜"îlø¤-À"«Ì÷¹š¿ìî ’´R@j› Ü-ÀNéÍ6ø?@¼ÍÖ×@'4@ƒÓ !vçfÀ¸`çàÓr@óù&A›mÁ¿øÈ©®‰8Àâ×$ä©UÀqtÍE)@(èØ¸öAÀ‘5KAÈmÁ¿€êîòêËr@´‚ägÿ˜NÀªý*©WS<@ufR‡[+'@@ÆKiÑhÀ¬H̯ër@šaØ«7Å¿Îiö?Ì=ÀØù‚–ö‘UÀÒb‚t8Æ5@±ÄIl¦î(À3%J¡â7Å¿?‘ãr@±Ðú PÀi/cµ&A)@2• Zßfý?›q^ÇZÀi~ÞËc@oÅ'‡ò¸¿3#ê+ŠÊ0À¹zñ£ƒEÀ)O>b^/@Vý07(@ŸeÛí1ޏ¿jðg¿ûb@ýæTúë@Àæ üË á%@À7”¸†nü¿füdýÃÈ\ÀPJû³>c@‹BÝX0=»¿ñw÷ß3À_eYÑNEÀ°µ‡ÆÉ4@6@Ò¶ÀD@@ªúP ˆª¿‚•õˆç{S@ÄÁ(q€K5Àœ³”ÚME@uä Ö€¹F@h#“±;fÀº¯Æqƒr@Ÿ¤‡ñÿ«¿2¥ïOÀ™+À@à°D=÷YÀ/²-7;ÀXÄÄ“XÀnv¶Ó9¬¿¸èQŠ7{r@ݰ¸+MÀS‹ÑC$@Ñc{0Ô½!@³ê¦QÖHÀ‚ÖØP|šR@ô1]¼D–¿ª­¬†"ÀTå^\˜è9À•ë»Ûì?Ëi‹H2ÀÅÓžõD–¿E"kð‘R@Þ*›ÁE¶.Àñh”4§µ"@.¨ ¢e@äËRÒïIÀ$M G±R@Üù÷ŽÐ;ž¿Ý÷‚ñ%XÀ—ÕU@ã9ÀªQBÖ¬G@~ó®í;)ÀŸ¥Ÿ<ž¿Jþ¾î©R@ÕCuO$0À³3òã33A@ë…— c1@ÎB~€…ÙkÀÚáÊÆJÉr@Õ„x?AË¿­¤ä³Š½:ÀÆ—#‘çYÀ¼è‘Y5@d) ž@ ;Àz mÆqË¿\°ÛgqÀr@S Û²†ñPÀè`@§ã Ø—@h€­3¤ÏMÀ Å-~áR@ÓOCký¥¿6´õå9Àf˜2ìëõ9À¨SàG½&@3ø)¤äî¿Ýž— ¤ý¥¿ÆKØR@HÕÆ”ñÂ1ÀF ˜fv+@hŠ¡HÄðí?EŸ°Ñ_À%ýA}Gùb@¸|ó˜l¸¿Ç»—ªå1Àf3Ÿ»·JÀ}4SIJÈ4@M +<‡e#@.4Qß«¸¿©¡þR˜ðb@^Mz꽘BÀq L=o†@t³…– xó¿ˆ'jÿïPÀö—³NÑS@–Jzøª¿ fâ¯:$ÀÁµ^Nb2:À.» kóN*@µ÷©ëŠ^%@¬§àé;ª¿ãÚèdd S@!ñs3À¦§úC3@øô/‰Ë%À6+ZèsýqÀe±É*s@ù¦K“Ê¿äÌ¿Ú œFÀ§Ë³ø`aZÀä6!XP@{™èôˆŠP@0C®é^“Ê¿ñ‰Ê»"s@¢µøMRTÀœYsCÄR-@©ƒY¸10ÀbÉesÀÐÌ=Ds@CŒä…ä™É¿²¬Ì7P IÀd7¬1œZÀ4·•àP,S@ <ú1kV@vr &šÉ¿Šh×(¬À}|¬ò 'ä?ܦ o¹5Àþˆm¡t‘¿–ÌéöoR@-:I-0ÀàAUÀûE@iŒ@@MÎ* mêlÀÊ‹6r@mzÙ°A7¹¿1ž0‹54À²9ªÇ12^ÀRq¥ú˜¶&@þ&Ú PÀÏ·Ì‚7¹¿* ‘ÁÆr@ޤöPÀIØÍýs[$@§kûD…!@ÈV}›mÕNÀƒ-áªy§R@}|¨T—' ¿Ô58>†ÀRŒ‰RjR>À¼_'ZÅ@nFõ Á$À² Á' ¿FÏòR@Rü–ÙÂ1À‹“•2@-ª2wܺ@4[Y úe`Àå¿b@_ÙkUE1³¿ßƒñ†ì,À^ž¸}NÀ¨—ŠŠÆ.@~‡âP³"ÀѵÉãv1³¿×ùÏuµb@jeÕ“BÀx·2;§0@P'!|åÿ @A È(gaÀz’…èÖb@Á㪆µ¿ 9;ë“´0À§;Jô°²NÀ¼­)²4@˜'·6Â@' 1=8†µ¿>©¸žÍb@ÕÞ—Á.iCÀR¯Ph¹!=@€¡ûÅ£ Ó?èö¸knrÀÄý)ïr@áúXúìÆ¿Ñ¨í}þBÀ6Ç´’ó^Àn%L ŸQJ@äéŽìv(;@¿œ ‹5íÆ¿~ŠÛ0ær@Q#rCTÀÌù²Í&¡@¸b–qÅ÷¿º¤ ï{SÀаî-ÕS@Ù:Pî&§¿(BtxT%ÀÆZcn\@?Àüª,ñ"0@ÚS³rB)@â4»*'§¿QdPÿR@¯ö|Ò!5ÀŽgLÐìÉ#@Ð)†óÀ*õ ådÀ¼é+5û c@<ȾÙÖíµ¿u Ú<·7ÀÏJ¤Ýq™OÀV¶g©OFC@nü‹è-UB@ŽÄyv `š c@JÔþè•FÀrǦ2@¨éôD À²¹~ªeÀrȧüª:c@—¨Ž¥ô²¿u¸±þÖ&:ÀA¬lÿOÀ§ Ùã–F@ÜÇã7H"H@IÙ|€Öô²¿!†í›q3c@¢€þö­îFÀÅ+‘×riL@œÕ‡[GàL@3Q•Ë=$lÀÝæ„NùAr@z9­$šÏ‘¿ A«È#ÀÖÅX™aÀlç|¬žVÀ_ß|´^À¾WÙ!ÈÏ‘¿Ipµgt8r@ï»o!5PÀòºÏrÃõ*@·y~õ§Â'@= ·¤´ùMÀ¡\¨|XR@ pó–ÙÆˆ¿–»*4Hñ À2å0%42AÀ Ø{wqWÖ? yi‹E%9À3”Lj¿Í3ñN¦NR@MuÈi ù0À£¤â^9@³–Iï2@}núÚ_À§¡®¨:ob@Ãù…®è£¿4`€É "Àݵ‹ÜJQÀÄhܾ>Þ@¹)Ї«‘CÀä×íá裿'‹%)4eb@†°öküÁAÀn£S(¡7@á`âRÑ,@-ì½â`ÀS§±,:†b@LV µª¿e=xr`]&À Ú‚ÌÂhQÀí&à!y $@Õj|™ò;ÀxRµª¿X ‘Œ&|b@ï-,b[ŽBÀóÚ]ß½%@¨¬s’za@:/].ÞQÀÂÖ¨>ƒR@Bÿ•Л7 ¿4¬,W¯ÀÚ)ZŒAÀrdúãÝ>@ÉÆTÜ`¸ À JK°Å7 ¿ £«ù†“R@ËsÚUç^3À}ÛÈô'³C@$´¾ú))@Xç~ßrÀ¹…‰-µr@¶âÿÐEY¿Ü‰Î£?ÀåPu.#µaÀäåDZï†D@eÒâµäÒ%ÀaT¥1uY¿šc«è_«r@ÿÞÿ"Ï3TÀŠcP¯­1@ÁVrÎ&Ã@”a²ÎØæcÀ sô¢Íb@è0¨Ð;‡³¿×·qÊ1À'Õµ!äQÀ¼î餧>:@ Ã5­Qa@#ü@pásüZZð¿!§ÄÂhôtÀ¿C´¹{år@µLªñ‚ÿ.J~``DÀýËøp'bÀdeR’$P@ÙôÁ.A@S‰Œ $ƒÃ¿ÂØ•TªÜr@œeµJ‰ëUÀÚJÈ2@¨41D"û¿`YG^VÀŸˆ6VþR@4^¥¡O¢¿ $ƒ·¢l&ÀqÓ´‹«TBÀ޲T3@”㌎,@†©.~¢¿MÃ6öR@3yàÌÖÎ6ÀìŽsÆ¿Å@.íÀXÒ£ÀÚö9ì"WÀ{¾ò¶S@þ¨È~ß¿ç‹[^ÍÐ(À®³©rè–BÀÈHaƹ°6@’Ò™*Ûû3@öÖ+‘¿€‰ænS@¿ž¦Îw·7ÀÉF™YQr@Š›ÝÇÍ¿sÌE6ˆEÀ³LÂÝÇÍ¿ˆ“¸nÊNr@`ŒÃXõFÀè³&[Ò©¿EøC…àô ÀGž4•ªÀð ¸hR@¿4E˜°¿×`Rá&ÀPþO"ƒ[Ú?ô@Å‘ ø?_ ¼e{¨ @)Nâ;°¿ó¤eR@è`ÎÃ=)ÀX |ó×Ô¿¦Ñ`ú+Ñ,À¬¤?Iâ4À‡ÁÊm€b@{ð@RûòÀ¿¦¥ë@8ÀÍ%®ÞE÷?ÓoÏ3@®Žá0œa)@}FÅ'óÀ¿GÄzÖ|b@ÈM¿i’;À,Eí™ý²Õ¿ABåLx%Ày‹÷…T¨/À÷¿Vö‚˜R@e»%•t±¿,2u½F§)ÀtlÚ@-î?”ï1jqÈ@ôéf»Ò"@¯éâ7Ât±¿œËVän”R@7!)¶xó-À®­M—Ào¿Z€:‡LÀ‚K¯mTUÀᛇ±r@‡äv1zÑ¿Juab³KÀv¤.6[ä@{:“;@=¹Æ†ÎH@ÿB—^zÑ¿_Iö|¬r@;î{ì¹0PÀ¬ÔXJÏü¿žÖß™¼AÀ8q£±òJÀû9ZðÉb@?—P¤EæÀ¿Kÿà‰‰<À@kÙÏ,ý@7Ýz€,ÿ1@Ö€#½Ã¢>@ºGqæÀ¿§ƒÛNÅb@ðÐs°unAÀБé)&RÀrÊÓZ+EÀ™¦µãWPÀ8:]ãb@¨&ý˜0¿¿ÀüZ*>ÀP LУþ?VMT‰‡6@äžéú&B@ü+ß…é0¿¿tÝQ8Þb@ÐQÌ@³BÀ0-98Š‹Àä~la…XÀ`´GFcÀeê+íRýr@=bÊWÙÊ¿Ë &‹OÀÊ<‚Û¤@¸72éeK@—qÕŒCçT@ñÙÆÙÊ¿J«&X ør@ÎXvÿSÀ¸º"âéúÀn~Uºè;À(ÂŽÞýDFÀ"²‘>ÞS@£ˆ-=y¤¿4phØKŒ0ÀYƒs©¶Ù?"Ýÿð6M0@Zà}Ìj‘7@*÷» ry¤¿F«¼_¤S@}™<{S5ÀL¦)¹ÍÀ+y8é”6?ÀšŒö4‰TIÀ' 3S@ËÝY©x—¿Â†‹«´W1À{»œÏÑ­¿»4•üF3@ƒ€¢ƒ$:@cêÍCÊx—¿nú1M.S@ÿ½Ž«Á¯6À8 ŠLðk&@µÖæ="â(@HýþXc"1ÀH‡$ ’r@àÐ*~ŠÌ¿À’C¼ŠDÀ—• +`’2À„ªŸ¼—úó?"kæ¨ï2Àÿ®À.NŠÌ¿½Q‚ŽXr@3ŽŒÏ‡GÀÛmä^Þ@ðŠN‹{ß¿ÿù“£UÅ"Àˆ¥KS+R@¤Ì7ÖàÄ®¿ÂÂlfÅi%À-0J6ZÀ(Él—uáü?ÌKJ!Iûù¿œÿÌH0Å®¿ö6b–'R@”~„wÃ)Àu؇?UF%@ €Ë^>0ÀÔŽí.µ/MÀÅ´BgBr@ê½V;пð—V-,½FÀÜýÙh„0À>‚€í+@–êWd­@É:?,;пÔxÏ*>r@zœø’ª LÀ‘OÞ)·ö@­½Û¾aÀtß›Ïè3ÀªN‡ÕYR@rüÛB¸°¿Ï“ÿÿ(À<ª­PÀ¼¿Û{Ý@cºŒ@ß ân¸°¿6àV#UR@Ul×].Àb™²c=$@\¾‡'K06ÀÛÀ‹;VIÀû™t¦qb@×Ìí0ÁÀ¿£-ʼnw9ÀìwôX À@ª]Š’,@œHW Y"-@œáÂ[ÁÀ¿ï¡±èlb@Iêéñ¼^@ÀÌ[¹Çã•@ß=ª|ÏMÀ£u·Ûà^Àwˆº;ã‰r@ òÔ :п·€KßJÀx@ÍÈo0Àgª'‰›qB@‡¹Lé4D@˜© ðI:пáøXz„r@çªD•QÀ §JçOÍ @fž8âúAÀ¶‡úK½DRÀö¢žë•¢b@ݶ¯aB ¾¿b™ôAN<À„-kD!À9–ìâµê6@²¸Œ°9@UÓï ¾¿Á.úœb@pñ.-ÒBÀtJhçåò?>"‚°=]5ÀæÁ2Çx(EÀìÿ{É»R@ö¥t>Ìþ©¿cÜnBÏÄ-À’ˆÃG@À†ŒÌ˶+@CU*Ïê/@®C]ÿ©¿Gä¸ ¶R@[vŸYp4À $îĬõ?Ï$Y©µHÀDLdXÀ œæÖ‰Õb@B'fd] ´¿rúÕéÊC?ÀE”÷µ„N$ÀŒÑ0(8l@@ñƒPFÿB@TÒz(‘ ´¿ÞÐo!Ðb@A‰$8bEÀÀ„—µD¹?ñÎ|$<À)àù« KÀÙÛ|áãïR@•Lˆ8âÆ—¿¿Ÿ}Áe0ÀÍ}ó»ŒÀèPÉ3)3@ ƒöhÀŽ4@KI=Ç—¿UVP¸êR@¬^j¶ñµ6ÀFýDÞb]6@Lˆ%t`š8@A°ú¹ã@Àø¥1eÙq@•ñ¶…)˿͎ÆÒÀBÀPjÀëhBÀ~zIšØ@ÝB#ÎN¹BÀé½lØË)Ë¿ñáã‹Õq@ÚÊ ŒŠHÀ…Z¬š<&@O®«œ‡@>è*¶r÷:À˜«q1ïa@$[¹ÏG½¿Ýß«$¿4Àâ˜Úi%2ÀGÕ›EÈ@fÓ‹sb)À¤8TH½¿ èæ‰4ëa@°F‹@:ÀÞn…ÃÞ@¦*=šâ•ï¿e­{jþŸ2À`Êvµ R@¢7*kÛ䮿b×6ŒJ%À¤#Y Ê!À¶wÌx’ @¦·r’/ À<¬Q0+宿”=¿2R@ò ‰Õz,ÀGlb›C@Ž—ê¬OÀÔå¹Nß7Àñ‡CÐØR@ƒ³Ö¯¿#’ Yv˜&Àîœ6 DÅ!À"óÍÈÓ@4ãŒiרà¿à¡MÑÖ¯¿VÊÆ’R@ü@ÒœÀ.À!w²Ðh@º\¶­ûøÀ=>êµV:=ÀcÖºO4R@èTx,Òí¯¿EÜ­~Áì'À¾Ð¢ðô!À‡»Ä˜r@è"¡E@õÆ$×,“Sb.R@h—5‰0ÀvjS¶wL@˜s6jCã&Àé$çXAÀ{þÆ—KR@Šyäöö®¿pãA˹G)À毙;‰Y"ÀÒÒFgôÔ"@ª‡¢<6 @ØF÷®¿Xm¢°ER@£.ïa¸1À­œìì@ZÁèÏV·-À·m<#DÀÓ+˜™cR@0÷g¹ç¸¬¿r|—}´©*À:›¼@ö"À ¸?'@×Så )§@¶éã1¹¬¿N -†Ž]R@©ð¸î2À³_ðF@|¦Ö<2ÀF°å”üFÀ³+Óý|R@§ýÄêIõ¨¿ì â,À”RÀf¡Ì#ÀNú+@¾‹ÇÊv$@Ë N\Šõ¨¿Kû‹vR@fP?º*4ÀZ²›˜±² @bË-œ_’5À{>ë­aåIÀ9íï•R@ðºÃ¯Fh£¿ñR9„-À™q÷ÅÞ$À¤®§P3„0@ƒ©1.žn)@‚(Ìxh£¿ÍÔDR@uB*i–n5À`…€ÿ´B@ø´…UÞHÀ Ê´ Þ\ÀÎu?८b@"§Ú§¿IæWA¤ý>À“2Ÿë.6À$ÛŸa]6C@°…FÕU9>@GÙø‘§¿ÙÃÐG©b@òͺFÀ^ÄKáwº0@þ«áÅ)?2@GhDÒQú8ÀaºÂŸa@Ûœ’t(«¹¿À%z,-t1ÀvA`;Ààï()û?JÑHÇ;À\­´»j«¹¿ÔØUT›a@©À6ÒÔ’8À ¤X¦ƒ®0@ƒú‡¶¥9&@ÿ/'+wAÀJ¹þ]µa@à¥øW"®»¿æl¢U«2Àˆî£)I*;À1÷ª>£@ƒ »Deí5ÀÝåÍÐi®»¿Pq/Ðn°a@2åë‚¿µ:Às¶äT… @QC (@%zOÀçŠ6ÀüÀåCËQ@D /Ö7­¿ók¿è#ÀmÚVnÐ$+ÀÌ(ß<±h@¢6Êã5 À ¦•"8­¿µ¬\ÝÅQ@Ohnã,À¶ôæƒ> @%á:[tÅ÷¿ƒÃ¶†ü¸;À¿A{áQ@›Sª ®¿z’ά*%Àdù‹IQ+À tÉòÿ¬@TÞ²ÿDÀnK ø ®¿´wÖ«ÛQ@•k®G/ÀÆóh™»¯?@l¶¡ÅkÕ3ÀÖk`Àp&¬Â øq@ØeÀ¥–<ο"çÜRsFÀûài•b±KÀÜ"66>@ÎjªÌ$À÷ül¸ä<ο&Ovçñq@yCW§^°PÀàyTú£>@ ®Â¯yË@À)Ykk3cÀÏùÅûr@)„ªöZÍ¿èFX¬PÂGÀ¦|N2áFLÀý v6 *C@€tyXÅ?èÙÁçA[Í¿·Jäžr@úõ;§ØQÀò¤›I«U-@P B^š7À§(çcôUÀUm›T&b@* VF»¿¹V‰5÷9Àjùåû =À •‡è|…7@PE·Ô3Ø@3 Þ{œF»¿mKLâb@;)L‚DCÀFIæˆÄ;@j.)ÂVNÀa+tK?ÃhÀ‡ìZ!>r@ é\]LÄÇ¿çîRžtJÀŽf ™NÀš‹µ/L@æG.ÚZ4@Ôñd»‰ÄÇ¿B‰mÃ7r@¢¨b‘…Ó‚6F@T[þmö@@ á8JFVUÀ)’ì¬|q@ÍykÝ»üÉ¿]äÞ®bAÀ jŸÅRÀîçÕ•FL$@rµþCæõNÀáÈ/÷þüÉ¿ƒžùD5wq@§Ùêe]#KÀ=O­ãÔF@1‚mó/Ø3@O 4&ÚYZÀãwÓ’q@Ó©ùsË¿³D[Èë”BÀ~.¶•½)RÀûÈÆ σ0@Ì~Û8|jIÀÆP}Œ@t˿𼙌q@——l7ðDMÀœaŸPâÑE@UÙmʼn@t…¾w_À\ÞŠ«§q@µb7ö8TÌ¿Œ»Ô´ÌCÀùyÆî~WRÀ–²Ë¯¨j7@‚jn[DÀ½Pæ‚TÌ¿¼+»^¡q@©áBµMqOÀX²IíÐr5@L„pÏÀ¯Ÿ«ÅSWRÀî„Å—¥½a@eÛ¯$ t¼¿˜Æ;E 5À‰¾ÇVÞžBÀ[RŒöÞ.@ÖÛ¼Ò¤}-ÀNó¾œit¼¿mZ o ·a@~õš°qÔ@ÀAQä»ôD@âç‘lϨ5ÀLR2˜eÀcó­1ûÓq@¬Ùj¦Ë¿8«91ßMFÀv²Þž»SÀ°¦©qC@zâ*L}B3À%±Q}N¦Ë¿\vÏ3Íq@$"7 öQÀ!]*²VD@žWˆ×AÀÕ+ëd¶·gÀÅü´êq@Q(öÙË·É¿z-¡­Ì—GÀÈ¢‘‹~SÀE¨¾G@œÏs:¬"À6ºA¸É¿ìFz½ããq@!ì  ÖSÀà›“¼´—C@œ6‡ •UHÀ¨Í°%}jÀD . Úr@7à+I«rÆ¿Æ2ã3`èHÀ'/²o¬TÀ€-lŸsXL@€yÛå5Ñ?%fl?årÆ¿´†@-ûq@X½XLTÀÄSž´¶"@v€lÿú.ÀGüŒQMÀ½ÈiwR@³V_G›¡¿/\÷«õ?*À¤ÙåýÁÎ4À¬Ò•² 0@øø/ê+@Ð ½L›¡¿r,Cì"R@ô?鿀5À (êš²A@ï>ݵÆRÀ !ÕkpÀDàe”1r@8!ևᵿ<ý¿BóžKÀiT]¤UÀìçc²ü=S@VÖœZw2@K'TÀᵿt|gîØ+r@k…à¿ç¼VÀxö ¸K@k3Oœœ¿M@6f4­æ>TÀÍÊià0q@øž.¸gÆ¿¬Œ ´Å >À©¬¨e!lVÀuß´_s@iD¬&¤§VÀv)îñgÆ¿Høã.h+q@ñ„ m ~IÀ}o%:‰µK@}ätþ¬¯F@3U0>YÀOçAnEq@>­ÜÕ,8È¿Y³Š;ÿ'@ÀO¡fjôVÀ¶·°AzÓ%@Ê»NOæSÀŽ1_k8È¿½²y?q@ -ÝNî‰KÀOš"˜\—;@²è*RÔ[/@3RNÀ$ˆU˜?Za@ä«Ó%¡ïði4P1À‚V}m–«FÀo[¯1 9!@×W  Ñ5AÀÎJ0ž¹¿X š6ÛSa@ú`a^ÍŸ=À^ŒG?²\+@v™kѲu@ÅŸ§:jAÀ´±ú¡ZoQ@ë2lœùuª¿=š®ô³}"À )èÐï6À>ôÓx0@V ÿ’--À4ß=ï=vª¿ô²×™hQ@…¯YDÀ/ÀîB*F·;@_G`/pý?Ü…´å¢ TÀârÏ Å„a@¦¯Hûr™º¿­ÓI<µ°3Àæq¾vMGÀèöeLål/@Ôø} ¸8Àγ©·™º¿óÌh:Á}a@«Â(¢õ@À|rzŽŽJ@¬†±5ô#ÀÃcòÁfÀ@… ™‡šq@oΔ4yÝÉ¿]CÒvéDÀ”TteÅWÀ¼T׃¬C@±™ŸkCÀíÁ¡ý»ÝÉ¿a–kø^“q@9ÖXÝRÀ7ZÊêNùI@Ú~W7Àˆf½`ÞniÀ¿Re6¨°q@|T3þÈ¿âÆ;(FÀ\Ÿ0Œ†XXÀÀùëQëG@Éá¨/¤<ÀÐë\<È¿—ç[‚©q@'ÌÞ2SÀK$B=DI@çër–sBÀÄ9 bš*lÀQªÓ/Çq@ð°-Y¢Å¿b*‹RmGÀK”ÑYÀDD.tuL@æÜÙ¢sZ3À|Ux£ØÅ¿­¸?´:Àq@ ëÎ.UYTÀ9ly΢mH@>P`ÞIÀc—RÚ›ônÀ£X2‚'Þq@®ÎøÖ”€À¿4Ÿž¹HÀœ‘ü…KÔYÀœ¹cð¥P@¢}‘É$ÀѦs¿€À¿”ƃٚ×q@§½º*‡UÀŸ–uG@(4Åñú£OÀ¼s»£¨æpÀ™‰Ë™õq@ºµ8€ôˆ´¿ýÊ‘ÛÔ JÀ\ƒ ¿ZÀ2£;)9S@€¥TBhü¿L†)‰´¿ ½Ãõïq@ç 3¸Ú»VÀÞ~‡m”@@Ë8Yg¨A@~m:²÷GÀÀÛ`„û`@@**–W«´¿”Ïpi†Á+Àús¾ƒ­JÀQã(ÎÔJ@2~ØSgæJÀA¼ôŒ«´¿ü¢À>—õ`@ ;µTé9À®1†“•@@¼e,¸™I<@TªÖù4ÄLÀÀé‹“a@C2N²d¶¿åG'¶õ-À*ét1×JÀë÷£"×(@Äü«­9HÀ7záëd¶¿ ¶bî+ a@ˆN",áé;ÀªpºÆ<‰@@†3–P5@°þ6FÔPÀÌvclã#a@¨¿Gº·¿¾ôž+0Àž€KÀ¨û[XÕ!@z{ûAEÀHX8‹@º·¿/ϵa@È>Vpô=ÀôÅOFo@@:6›'éÊ,@mÈn¿¤RSÀºÄšsy8a@©4YЏ¿Áõ„tÛ<1À, {6rKÀ»Ö™ ì˜(@_ë8ÔCÀ/¼’˜Š¸¿<ž½OP1a@±ØI‡Œ@ÀŸåøF@@‘lÎÖ#@K€N­‚ÝUÀâ} [Ma@¹1Æ(±¸¿l=ȳËe2À£Õ^m%åKÀ}³Á¼â/@±ÔLÖô™@ÀЇh±¸¿óç¢öEa@ƒ‹ïX AÀÛ69cP@$ðM÷kq÷?Í"3h1uhÀZŒÿ†bq@ÁØé&È¿FV­26”CÀ_-ô(r\ÀÒRÃEÛC@’¿SgLÀ”ù dÈ¿ÉÕÉ[q@%.¿ð+)RÀ,ñ†a2’O@ ))‡ÿ(Àâë¸kÀ¤wgWxq@»º¦%]Æ¿$n¢h[ÈDÀ]ù¾%]À¡q·% H@vh÷dJÁGÀw>DäX]Æ¿ÜÛü$­pq@ ÞÝÜíCSÀ¤¤îoæN@€t¥$¹_9À†:˜hbÌmÀ9…{åŽq@bœNËمÿå iƒFÀP0Þ]À¼Äj+†L@ ÊpBHCCÀös4 †Ã¿W ëgÛ†q@‡=M«dTÀ%T­x‚N@à? 2µLCÀ?›iwRFpÀ†âg¯j¤q@¬^Vsì—¾¿Ÿ­ýBGÀ§á7}ô¾^ÀñF5/Ÿ¥P@s6µÝ=À²5Øq;˜¾¿ÃÇN¦¬q@C»/²‹UÀÃ%Ã\-M@âÁ²-ØIÀo9½­qÀ°¥Gä8»q@F~—ð­í²¿¹!¢ß!ŠHÀ©¬ÖÞÞ½_ÀFú£Ž/S@f5Í—N‹5ÀînÐÞí²¿æ=Ã_3µq@œ–I|V¹VÀƒ)ÄrôG3@|Â: ?a4@þÝ<—;ÀÓv;zÇP@I›d{⢿½wº}‘ÀÊ6'¤_Ü>Àéog0Äù?t¶ÔÆ?Àpô&¬â¢¿D…¤"ÁP@ßânM*Àj}¾ƒ~KS@QŠ-®™âP@·I‹\ž*`À§Î(ëÛp@âj!5†Ä¿®¢.0³;À¡l÷ø_À¯¡ý†ÊN(@FKç’çu\Àrˆ j†Ä¿й…@Ôp@\ cCLÀè¿qåAS@«hð„ÙÔJ@Ë)vÁ=•bÀ(Ð{ãîp@';¯/ÌÅ¿`\0Þ=Àî™4Òq_Àšƒ¯…÷Y2@R$qކíYÀéSq÷gÌÅ¿fc.L­çp@­ÊHY@é¤ N¬ZÀ9 .,a@Y=w$¶¿ü¬OM2ÀÛݽðÛƒPÀ£ŒÊþ3@Ù!W½BÀÿ`WB°$¶¿¬tRv:$a@G µº+?BÀß/4•zR@ð×8ÔV迲泹lÀ‰P¯ Aq@ìÖÚ°äšÄ¿²±À¯ÒÏ.GØ£¿YÜ£³P@"À´¡Œ.ÀÆ·Íàvá5@qsNc,a)@¨ZÁ„C¹FÀ@÷Ï+ÏÎP@ÓkÑš¤¿£ØúZÅÀt¸EíÌBÀ•²Åáh@îTŸêÁ;ÀèR›¤¿¯ôÑõÆP@Þ°ˆE0À¬§`Gè¿5@ja¿ñ“"@ðúp4IÀU3žÍ°âP@è.C &Ȥ¿=mã3¯ñÀo†ü,iBÀyí³ÕD @^y¯õn9À9h6¶[Ȥ¿A\‡0ªÚP@pþ`¶I1ÀþdfinU@¤¥|žF¨7@~¬O¸íºkÀ¿Ù£•Ýöp@ Û k<Ä¿_o½ýAÀ0ÅŠÎaÃbÀÎ4ªõøD@Ýl°]/.WÀ=LLŸ<Ŀ외ëÍîp@ SRÀ—ýb R5@ýİ5‹@1®O]NNÀwïeÙ[ Q@›"Ö4Т¿°—ñSX4"Àf?ÉÜ*CÀdR¸,(@N[Ô"F5À;“ÉÀТ¿¢× nQ@1Çs«a3ÀæUJ5@PÛA¥û翸RÛRwPÀ¶ C}2 Q@›yýÿY ¿´å’&Z#Àhh¡  CÀàˆ,@&ÄBªñå2À”Ñû5*Z ¿4øÅ-™Q@ŽhŽìu4Àd^¶)Cª4@Î~Ô%Àè 4ÎQÀ{Žúh5Q@5· U™¿ Áƒ¬…$À½•)7#DÀ‚z~•0@ÓïÓôß0ÀëäLU™¿/×ð^.Q@Íèq5Àйc^Á>4@/n¡d,ÀMûŠŸ+SÀ#ÏeKQ@ –ÎôÙ@Ž¿=¬º8·%ÀÄß\ʵDÀfóÝxä 3@Wvç–5Þ-Àµ}(AŽ¿\Òÿ\ÐDQ@Ò¬D^°6ÀÑ> T¿ŸX@Α̵ݧY@Uá´JGaÀBD+cp@s¦ØÉºr¾¿Á‚ú}u5ÀÛæ:”‚cÀp² ­@ðÍ‘Ž¸cÀƒùPh s¾¿Bü¯ê\p@×UøýüKÀôÂá¨X@˜­É#œ2V@k)oä>˜cÀ*pŒÙÛup@³'–F¶À¿>,´tu7À.ÀÓ6µcÀøƒ’_c*@ƒ\ƒVbÀWNì¼q¶À¿½*½\np@¨Ãê4íåLÀµM3ªå£8@ 0lÅCÃ2@ðºÂEôEÀÈøHlňP@"›¶þà¡¿xs-M~À¬ÚÎ}óCÀ'BVë« @Ctä‰$AÀÛ²É*,á¡¿Sæç€P@O)ì’ºÐ.À­hhë’H@>2î´>@<é†Üž[XÀË39Tì›`@Á•KÏö²¿)Dáõ+À Æ´€Þ=TÀŽõšX°)@ÕUµöOÀqNá&ž²¿²ì["Ê“`@Šz”[b@ÀçØ\èÃt8@w¡ÝÂfî'@Ìr•’ÎJÀÙÉŒU¯P@Ý­ž±Î¢¿ÛBigĪÀkGz>”DÀ’Yó €^ @ÈV¯µ=ÀMƒ.â΢¿íúã §P@v¨Úãa1À ^†‡I8@ý"+`â5!@6¹jMMÀþ zˆÃP@ê¿;²œQ¢¿„§mëÏÀ8?IVú÷DÀ«^ %$@FÉWÜ¥†;À vÿËQ¢¿*tiǽºP@ñy(wÙd2À&aœe8@³ôZY@¼³a–vØOÀlð=×P@ÁYö¡¿b²6­þ À?Ë!hEÀÉl•-(@”-0bEj9À"3ñ!¡¿ºw:ÈçÎP@`§ÔãÂm3ÀâÐ]ÇG@~Œ-Ær@Id8aÀGIª&Xë`@̦Ì_o­¿õk$A2À›MƒjÇæUÀÆ€e z<@^úXöBaGÀºkrÍ«o­¿Öºw™ã`@²m›|DÀ —a…pW@ô‘_ÂIýÀ\©7ä@ŠrÀÅ4:Hq@ã o±Ž¶¿ç6”†ÆÃAÀ3·ÌkK¬UÀ–̃Ç~@Ò%Ÿ9]QÀxæU_hÀ±-œ…H€@KÂ+ÝMD#@Úü@h‚Ú1×@‡[ØÀ é5@+=VÚ„@G„ ŸŒßd@ ]!‡'S3ÀÌ(fËû¬ÀßX)ˆ°ã1À5)rkFÀ†e˜D¿£_@Ãu±½iÄ1Àøèw“òâIÀ"Î?@l’èçkˆ@^„ÉÍËj,@³Êx´Ï @À¼ÊÝ6òT@f]E(&À·¼â<3ÀAó½;pFÀª‹ˈ\À¶I1Ø p@H} !±÷AÀfÉ‘zέZÀþþv5>ö@ï‘Î G{*@ÔibºÙ>A@ŽÏ,"@`ÉÑ\‚e@RçFÕ9À>áZðGÀ±aç”Ð[À¿™ŸifqÀ@@M€E€@d¤Ù˜¹*RÀ^7ŒÍ~kÀîa«Gè)@M“¾c@@.~WpT@ß!üÌŒ’5@Î Btvu@ ÷°‡ LÀ¨¤÷ëôLÀ?ƒÝó¼_ÀÛ#£E§tÀˆh™ÅH€€@èà€]RÀaÄ#1õUlÀ À8Ë*@¹93–·C@@@£øŸV@åÎõÌ9@;2).u@ùÄÀÙ26OÀ¨„Y¬&1À.{äŒBÀ*fèS XÀËó’ Ž¼`@3¼ÀJ 2À 3<3MÀö(qIÅ @x”½þ•;'@cîüv ñ8@Ò'ÀÃ@J 7ösCU@ `Cáª61À¬”MÏ—þSÀSNÙapdÀ°%]ÄQ}{ÀàE$Ö­ù€@½¿¡ÊZÂRÀœd̆nÀlé¬0()@ +ÝŸžñJ@3ù >ãÿZ@ü„ÝG@@˜Þöˆ‰Yu@2´Â\¶ßRÀ»´°@@n:ˆcÅ!@‚f@ó³ä(ÀÀiŽçòm@¯¾ôu(@ÀË µí”±UÀB )9N#À_J«â®—ð?çrÒûÇ%À0CœI=@ÊÅ)@Ÿú¿6úþà2Ãü?ïÄ ‡èLT@6˜B\³À ãFM0¾õ?—®^cà Àò†.SÂLKÀú Þ½ØÛm@9}^l‹@À^ÖVà WÀðcM“QÀú»ÁHr@ÄEŒ:ª @A¼T÷@ª&oí´]d@BÕùNm1À ¹ÖœŽ´À’>Ì3G1AÀ~5‡R/cÀx™šCËC~@1Âügº¼PÀoŒXð¾gÀ–•¦17'ÀÒõšŠä1@Ìoý¥)T4@orSÀÅ)@‡Þ̵ ot@$`[í±DÀìlF0ÀoëÈêN:ÀÃÏ3;]çXÀæ˜VÐ`®n@Q§à+Üí@À·"v‚(xXÀÚšBÀz³=œ&@`ñy+K0@‰5Ð7Ï@  ÎOô€d@¢º¿ËÐ6À¤ãhU˜O$À¤wbVqAÀ5DPéÐ^À¤f³É‹o@šøÈAÀc{B'8YÀP”ƒÐнÀ½ÚdC‡Š,@bâh˜6@ƒSŒ]ù #@æV?v“d@»…˜¢9ÀŒ`–‰=ÀKÜ÷ØèUÀX‚íg·vrÀâÉ«6‹@“Ç,yOQÀï)½çýiÀœ‹«1zu À‚W#(¼gA@ÜÖÔFCK@¹>´úM6@Îy³û˜¦t@äy‹LÀÖ!Ø•0?3À»æÙ 2gJÀˆBlÀ¬‡" åsp@„ øàAÀC;Ÿs\Àã*{øÇ À ÊÔ¡ÿâ;@Ïè-D@¢w¨ºGn0@|Z„˜ äd@êHL}ëBÀDcܧ¿|@5íŒu«N!@½ã’(õ0(À6&ïäw=\@+`»oÑ.ÀjغÁ„DÀ÷Ï­ U¯"ÀDkͱTð?À̆@ô"W±ŠÔÀ{ˆÞ@1þ€¼×âS@« ¸kÀÀÂü3f–2@`3È­ Ñé?ý êéL`ÀB†•Zôû|@Ñ¢¿1ŽOÀf5™ÈÿÉeÀÛSYtÙ[@ÀT—õLÿx+@¶W”r¾|-Àï÷K<&@7*Ò'úòs@ <K3BÀ —is‡à@¨^`1G ÀƬ Q®UÀ4ìãN!_m@úǵ=ì?ÀrÆ=otVÀÊ‘uµL/ÀÐ÷¹p‚#@¬h‹|<ó¿Þ›ÐY Ð@uÔ RŸd@º3<ËÃ4ÀðËŒoG,ó?™–ýë½ À’±‡Wa=KÀOæíÄ]@‘ÎíÐá$0ÀÀü3N$GÀŠRHýó¼À±ÊËØ/š@´µxL@@Ÿž­Î@ÖÀÎT@ ëžúëg'ÀÀëý­úÀ^ìÄ{gIÀÅ£é}pÀ²`üT-~@ƒ„óÌ€SPÀ»ömÃÙgÀ8„ÐAí<À‚ÉkÓ‚>@S"ÅÐÕà3@z›‡ƒqÑ3@)Ô#Y&t@÷ýÈž JÀp©.4®*Àt÷»ˆð1À»[6D­uSÀ¶‚"*G˜^@3êžtä0À±û†Lñ”HÀÛæ‚a˜À/ôé÷÷_"@¦ÌïÅ‹½@+¼0ó@ewv/é8T@÷< ìÛî,Àxf&YŒÝÀj'Í9s5ÀãÿàφVÀ´H,>³_@¿šs °0ÀÜëÈóUIÀ£r•ÅÀÐ}¥©$ª%@@·!£™X#@“z$E4@úû|ãKT@B“j Ó/ÀèÛœD¸>=À? 8"ÝYÀmy'ì²yÀäêI;{u@‘nbrîÝPÀéU‹ÛjÀŒPöbpy=Àt+Gíw!I@Ø©šaXG@2§¾Þ•=@Öh…_t@: æ«õgQÀèÇÛŸCÀ—Ê M^ÀÂ%ÆMø|Àµk¨wç@î[@î˜ QÀé±°‚²éjÀÒIြ>À¦Ú¢J¦ÇL@Ñ2“¾O×J@Ó†ËË@@y±´«Õst@E†Ö(]òRÀx©+wísF@kPâOØLI@~3"Ÿ¤QÀŠÿqôq{@ Š ÛjMÀ%U >kcÀ%Š”؉KÀÆþq~K@z)¸FÈNÀj,á±€U@qº®mns@ íVIL<À¿›jÌC@èVzï=A@ÚÌÞÂv[À“©dË{@_§UßÄMÀ¢>´ldÀ€Bï ñqJÀ™åÚh%@ÒÜÇÀ+]+©?UÀ_€†Ú8ÀŸ®*Ê£ð$@Jkþ¸k(À*–qLº§@°8!6õœc@Ðb?#b5Àpsÿ’ú@È{¹ÈÀ%‘1¿>pMÀ`Åjç\@¶f<Ñ.À¬ç´êåEÀ½#Ù°»_(Àñ¶+‚@YAV Àâµ|Ùœ@<Éáhs­S@?Öž©‡ï'Àˆt$ÎÀ @(Žêš*g Àr•k©‚QÀô~»ÏºJ]@y¼xšN*/À/I®Â|‘FÀì{/K(ÀjÐ0¬S2 @^¿ÔÇ…së¿&æØ@ÅÌF’{¾S@Ó¥¬l*Àði 1êÙ@˜;¹±Ýê8ÀEšxÎddÀi#ý°m@ë±@¢‚?Àãò…BWÀUF²`ø8Àðã¥üŒL3@ä ©A@Z9gnñƒ'@JÖþ*Ðc@_^i¾E=Àÿkޤãï¿Z´Xgp¾@Àt™ôd_gÀ½ñÄÂn@Ýp¸sÚ?Àý(ùWÀ,Á'u³R8À¢‹ªB‘6@›jðSW@¿ Ø_*¤*@h…>©Gâc@ö÷˜À9@ÀPôhnˆÀW’óAI5À(xv»9sZÀ/ÐLËø„^@!m³2ß0ÀŸÿT~µHÀ@šìšÎ(ÀIDÞ*@hÊLr˜@L¸Clã@°7j^õS@êa©½Áx1ÀÐW#p\"$Àhç~²†dIÀìÿ W¡mÀ¯'¸ƒòn@ïÉ—DD@À6ò–ЛwYÀÂsbü9À@ xýîŸ=@‘¦Bø ,@tQ =¡0@.ÃbM”d@u F:ôôBÀ3 ÷¯h-@€ÜµÙ€r0@nµ¹ÖÚã6ÀÖŠ¹åذZ@k»v6,À¸Ñj/cBÀãæ˜Ì 2À:˜d´•˜ÿ?ª ™ËË<4ÀGÔ<>ìi@B»”S@¡Ê÷ÄàÀ˜¶¡e÷òJ@^ jÖÛH@S©Ï+J:`À2ºGxû{@ä¬S+fqLÀ—‡VòbÀi§…’@”QÀ¥{Iè&)@-ÃÃ/!QÀØë42%@ÖX»}€s@JÄ|w¸5AÀ»–(_€I8@qsÃ&Ã0@‡~)UÀLެ]k@\µÂ Ç<Àli*£þ…SÀ B;æ15AÀ¯ ÔK‰!@Ò Æc<ÀòbH9 )@ëëEf+c@ Ÿå‹3À:‘FÞÅi%@+ùŽG:@ÆçÉ AJÀÁúðÄ¢·[@»Xõ i-ÀŽQ#óVDÀ Ⱦ¹ï0ÀŠ G0tÉ@ÕÊ•ð×ß&À?yÁP@¥ECÀ:S@ž§–Eñ%À¬XsEQ2@Mr`Ö1Ú?O,‚‘Ђ_À«OÌ?9l@ƒ´jíhq=Àþ<ê2Œ»TÀ[DF Å@À¡órÒU,@Iô%×Í»1ÀuŒUÒU"@ø˜e•Jc@™êKi8Àø©;ßvù@­¡¬hÀLÁuExRÀèÐ?5Xs\@ôHAéøÅ-ÀÊÕ! Ê]EÀø'™N¶0À†ñ|Ž7!@Mð£ÍøÀ÷ª&"þ@?žTgíZS@óò_có*À<7WÓ&@6‹Ž4+0ÀšÀ©$T":VÀfÚMgîÄ@À˜AJ¾-4@Ú©?|BM!À4´S®(@fÛànÏkc@—ฑ=ÀðúÈÅjS@ìâ ’Š8ÀÊ:Ü=e*hÀ£!js*9m@ÖÍðP‘m>À£ 5²VÀšƒµ…Lò@À“µU¯l7@ü¢ÅaîþÀ½d‡ç+@èm]íB}c@Ÿ¢t„!@Ààæ°&²Øû?êEáÜ{0À*“Ô¡'[ÀwºYÌÍŸ]@}ú‰À.ÀE•›CdGÀ"Šé?1ÀÝy®YÖ*@TúváÒä¿nÉ^Ó«!@k/fEOS@<}6…1À€;ÞÝü¿uÒ®¹TÀÖê70þ=~ÀF£K³×~@¬FW¥õOÀ]¨»RhÀ Ã’t[¯QÀ1?c“-lN@¨GZÍžµ @~0+û”¯@@'áh§û¡s@êƒ_©ÏóRÀ²_®_R@ÂèÖÔIT@&ªkÝ÷Û[À×òÓT“ùy@}= CôáJÀƒ2O¹kaÀE¸œ}.VÀ0vddãh#@Í΋£ÀóXÀï+’Cv"@x° þ¹±r@žÏ!©ÏS?Àð{JÎì@@ž¾ @@?Æ:—RÀÈQŽœJj@tßÂÚ3;Àôêû•9óQÀòÛ9ÊEÀ¯—\bÀ@Ó2¶`FÀ¢F_2ˆ@½ ¥¿b@û:XYÝ1À_¦˜Œa?@.I‹DTW8@/òzRFeWÀýˆR¯ÿj@è{A¬Š…;ÀâÁùUô~RÀ–øKÕÚ}EÀ"Q¤¶R#@kþsŸ7CÀîiÙ@ýŸ•a÷Íb@˜plÖ 4ÀÀÔ­ ¶,@¢^²ÐÅ_ @κRZLÀóHöÈóZ@w+õNíÖ+À€ý7¢CÀUf„J5À^* Ž@êÓ剛0À,b±}g@øe;e·ÜR@𫺨šr&ÀÊOõB¼Ô9@ÿúµ @Ü:“Û»`ÀõÞ{Lk@!q®‡í'<À5ðfqÍ£SÀçPT1EÀŠÐŽ4.@T\ô÷“\<À-Ÿ\Ôú"@à;òëëb@ðêÐâìÕ8À¼ùÕäº&@€ÛdrÞÁ?¨.Zˆ_SÀÃ&2©³¦[@Jͪixx,ÀTRE=DÀ0Âêi}35ÀbYÑHó!@! báSä'Àáž'§§@ÜàêœûR@zì„ ÇJ+Àªªn;·e3@ˆ—GYfÀ«³ÄÿfÀ'à-žàl@|oÙþ}È<ÀZÔ$<¨ÛTÀÇÍ'FREÀQàX>Ê5@_ci'Ó3À .Yo(@ÞÏ c@ÛæÒ=À8 žc‰¤?@D³êÇ]@À~Žù]éxÀ˜èÏz‰c|@¡Õ!'òMÀ[î›eÀ¾/rˆ UÀõUED²6PÀ˜óú7@.HÞDHÀRå:‘“Ð{ÀŸ‘©Å|@7ÿƒ™ÍfMÀçï%XÐ'fÀŽTÂ8ëUÀ…›P.8ŸK@Ö¾­Âõ9À?±¯ÕäQ>@Ÿ[7Û-s@ü{ÔMQÀáš„æ‘@ºÄ‚IPG@Àe‰RÜLÐnÀ‰ÐÃ{6*m@³}¹ µ=À€¸FÛÕVÀzƒPÀ‡½ãŠO/JÀ/Pð}0â@+ Ú¸tŠMÀF¯<õS@´ü N?Yb@ÎmY),T0Àò`I;BD@Q;nÑÕ¦C@0€ô{!ÔTÀ8Á"ð·˜i@±’/Ͳ :À„—`#ÕQÀu-dÖÝIÀÓ[26 @…œ`‚¼JÀ²áRÚ™Ä@O(‘K¤fb@¥ø“õ”v2À•K–EC@ûÂ5¢Ž?@΋ւYÀkDâÝèi@h/~½¨X:ÀüŒh6&ˆQÀÍJvJH¢IÀºƒ7ì%@껎Í@HÀ@. ð@_@&Ë5ajtb@HP“@n§4À×ìjàQ@ZN«göÂG@à…ãi½VnÀ7ûfÏ9z@¢÷L¦JÀ›Ÿ1D™bÀÔH­EüYÀ'èÜ>:@¤“§¨ŸUÀ*ð;Ô 1@(¶…Û—‚r@aœfiçFÀt±P˜D‰P@›†¯Ô?@%™ùﬨqÀô¡~Ûz@™_§j‡óJÀÃÄÅmZbÀgËã?wYÀ¯e–'Á½?@˜½ÎÐTSÀÀKs¡3@ qlV3‘r@ñævVA7IÀ0r7 Ž/.@, £Ø @:–&×:TÀ–ÞeKäZ@Å_0§G@+À;z±•.CÀ%KÁ+9‰9À.%m·Ã"@ݰŸøî91Àîýt @³C R@Ô%pº—+ÀxжlK@ƒñÓ[Á?ìÉ÷-yàvÀâU4%={@ ðñ{ŒKÀ 8UvÄcÀ ¬@žå¾yÐr@2µ€žŽ’QÀç¢uU0@½õÓ)8À›’ïòYoÀêhGHVl@蟧`m<Àè0=®Ž£UÀñ…ãõJÀ±ÚíèÈá?@*©*£Ù¼5À‰ttCº0@?eê·¥áb@³i9èBÀê³ß…RÀö÷Ä´J¦h@SãÙŽ½©8À¿í›ROÀ¸¯w$÷NÀio8@”›"QÀœ³î@/v·¾Zb@¤Wšßƒð0Àr†µ{G@–+M¬G@ c‡& ôVÀÚÆiÀïh@!©æ¼uô8À"ü¥Àü"PÀe/ÃÄÆÎMÀ«°wùÁ!@p3‰øWOÀÇaò:/O@÷ÓÆ @b@1{g–±3À9ÇÂ>[lV@jÙÇ×7S@ ¹>:„kÀMfÉ [;y@UÉ1%ì>IÀ3Wà` `À[VY¤]À$ž÷ø¬6@bãÛÕ\Àjbî|X¿.@CF ­€r@º©i–"EÀTx,2ÿEE@ {CÇmÍ>@N+;üQ`Àت *‰i@BˆD€ ‰9ÀXФ!QÀ’«Ð M’MÀ&^ÔâÛ+@ôy¢1~JÀcBÁ=¿¬!@»eà¸",b@n „ÙP7À8nCƒT@ÁxêôG@¥oêõˆrÀ«•Ç_:Ùy@6 —»ÒIÀÔ¼šò¦aÀ@½éuÀ>ªÛž—+z@´³4ÅëJÀn™°5v0bÀôz…gÕ¹]Àª;ƒ¹‰C@ØX…ÈWVÀraÅŠ6@ùÉè¤Hr@á@0DÛKÀþ÷a Y=A@lgª¨q@`²·ôœgÀ>«R]K€j@ ªû‰d:ÀèsXSZ¾RÀ÷ÏèÕçõMÀkC6âd6@ÚƒCªDÀ€! ’)@N—Æ£’Wb@ì³Âç8>À´¬0+^?@1tùê'Ì¿\BDÜEjÀúW®¢\×j@˜´ÛZ†¬:À»aÀ-ÉPSÀæC>>}NNÀêk*»9@ó@ÍõBÀÇf¶iFÈ+@å9™àüfb@, ½ðS@ÀP§í@ L@I™Œ–30ÀÎ9@l}À¯rlYÏ0{@ â1(×óJÀbz’ëçcÀ锇!êÄ^Àºu¤JM@ó÷EÌw”QÀžox'FŽ>@¦Æ•Öêvr@{6è[‚”QÀHy¨Qjr8@dW£‰0ÀJ›øÿmÙoÀïy§£Œk@K‹u:;À[ýçƒTÀþ¶ú‹˜ZOÀ~e>”àE@@!²Â¡ªk@À:¼ ›Ç·0@é©Åc‡b@ð÷a–ÞBÀv4a¼dK@'™{{ëM@TfÐf¦TÀE.h2 h@àyh%I¨7ÀB‰àbL¸MÀÑŽÑ&éPÀÇŒéá©j@ºe–½=.SÀº q?Ø’@Ÿ‰Ó²a@¾[#€1À 3΄›Z@Ûª=¦V8Z@ð U+ôøhÀJ†Ú+Ox@2‰Y_¿ïGÀ€e†±4Ÿ^À˜«ka›Ð`Àÿ`rW3@´Ø³féaÀÖ2"ÄË´+@çJsÒ>¿q@ÖÖ,dÖ‚CÀu!™ïŸ9@÷ÎÖ…N€6@„^àelMÀpX“q0—X@À2…î6(À‚_8 ?ÀBÝAOOÃ@ÀcW³R<@e\͸@À¶Ì4Ûªü@ÿËÿqÌQ@,†“’%ÀVC(H@€7R¶ÂB@<Œ#k aÀ+i-Oáh@§½´‰À}8ÀÇîbAPÀY[vOºÁPÀR^íwe-@),ðcï8OÀg"‰ß96"@rç½ÖÙa@´Þæõ¯7ÀÚ7´AQÀp³)îºãPÀˆA'/‚E4@)°NÃÖMKÀ׿>úå&@×cÅê„ôa@N£ÿ­O<À„–R¦›ÎT@FP%°a›=@-e`OxÀ¶0gÎÌy@Û‡¢Ú:OIÀÄWSUÈaÀ}îË>haÀYºj,nEG@\}ƒ¸ ŸYÀbcØGë_9@I§ÊÛr@2º3Õ­`NÀŒ/•TP[S@¸Þ Kf‹,@ÆZÜ–ãåzÀ[ø^5Ôz@Ͱ_ Ô“IÀshÃ#ÌRbÀÂc2,ý:aÀ´ÒàÖòjJ@ZC†o"XÀ´±öñ;@òhz¹¨r@ª‚EÀ]PÀÒ’ÓIÌQ@ÀÈïº9Œò¿Î®Wi5‘}À ³aH*uz@ªËñ¹×IÀ®pdÈìábÀpæ |aÀà°¸£·M@ÿQH¾iÚVÀàm$>@tCÎò r@\Š•È“QÀÔv># P@Ìí¶l °0ÀûCÿ )€À|ZTUÔÌz@‘Î2áJÀEæÕë¥ucÀB6*ëuÌaÀ>1ÿ@t•P@g=Ý~ÉUÀâ+ˆÁ9±@@@$i1Á0r@uy_ØÒRÀ*¨†b|vN@ Rh¤Ë¬VÀ}ä¹8Èsg@‰Í¦ض6Àç´g}6LÀP.@ºú»RÀ_öÀu= @îœbY'MUÀFªòEû@\ #…sda@0U¥ 2À,á5¢=@0ã$É‚I=@Š;;ÖäJÀ–Ŧ¶w¶W@7XiAû&À®!Z=ÀïJ¥ «BÀBöÞÉÚ@ùiz½äDÀÚßÖã¯ø @•6lkpQ@>G¤ø#Àû‚~Fй<@ ș芣9@”ùjt (À®´­1a@À#) ÚBÀmS¿®J÷$@¼Î9 @ÀÖs²Oj5@ßõŒ/­£Q@‹Ÿ1±I,À ×.$5@8@ŒÍˆ¸«%@…Š‚•øXÀY*"Y@36ƒ³5K(À˜"Òâ—à@ÀD òCÀ²#{´Hñ'@Û¸<,j‰>À96輦@S›t±Q@C§¸.À2HiÄ.æF@ðî <ÒP,@Ü)“òu}kÀú`ÍRqi@|rF¤Œ8Àt÷ÏûdQÀ¼¢˜]k=SÀµœº¦;@‡Y@ޱ%MÀ–=0”½,@Þ¾ñ«¿a@,µ°d@Àže7QçqE@äz=•e@UÉ`RnÀò¹ï¸Âi@^vn:WÍ8ÀÈNÄ¡ëQÀÑÎÓù„SÀÊHXkT>@=´W?õKÀ:~Ôe£.@*a3ZÎa@Þs³AÀ„¶C âC@à#&{ªð¿·^PöapÀ7À»I`j@ͦþfÀt…x.$`@&üxp‚*ÀÚ"ôNÌ]À¿ ]î*À°rFgÀ`@ÕHû£5f^ÀÖ3bE@¥«-Ìr‚PÀ’:õ×–â)@)î JÜGÀØÎmþ^^@ïØÛ2KÀ@\‰•}‡h@hX¡÷[ùÀßÝ ·¦fÀö²2¤ùÀŠðM‡kh@"+ÌæÏgÀ”zò¹T@V&•C_ÀE©|æ:9@qôžØ,ªVÀ‚´™l¬kl@=KË&ŠYÀmrcal-2.4.1/test/data/test-optimizer-callback-ref-J-3.npy000066400000000000000000012315101456301662300230770ustar00rootroot00000000000000“NUMPYv{'descr': 'NÇLrã¿=;ä«@™4ý3îÊÀÿÑemào@ŒÏÍ|5‘BÀ¸¹…çVÀ€.>E£ç¾¿à?–@·,5gÀKžª«dÀTØÓo“‹@¬aoŠš¿wÀi^5‹ibÀ&­$ºg@=,{‘"e@C„ v˜Òb@l%ê9=á?r®cûíð¿´€Ù#Í2@dÈØìc%ÀàÏiãƒg@È“W#" $@2«ÀÝÞ?à?9÷H+Eˆ@ÅIßPAÀ†@wÛ<¥m8xÀ/ºLª —¢@_!0p¯S…@ï"«ãˆÀêmÑ„DT‡À”zfÖnÞ…ÀT{á œæô¿îå7à0@º2èËà+ÀB%ssq`p@¸ƒ2‚CÀ1M |¸WÀE¨F¿¾¿à?Rv4 5hÀ'Psz$±fÀ`¯`ÐŒ@wÛ<¥m8xÀ8h[Å„EeÀv¢ðšˆÒh@Òl«\ÅDg@ XèÏe@6‚ðø·ñ?´ïè‘E$ÀÆžèÖ|C@üâî«T&ÀYhbÈg@„#˜­$@J!³) Óï?ð?ÂW(Õ6š@c°[ÎÚ™@)—¦BаˆÀÝÌ«tœ³@UÁP³ €™@nMÈ>÷šÀ ÀFד˜šÀr¨û5;šÀ"ÿÊ™¡ÒÀØ•éšëI@KÙ2o¿EÀ‰YèybÕ€@ÂúB Š{TÀZðÙŽcmiÀc((N>—οð?@7pÓÄ:yÀq§´ü2âxÀ¶r Ìž@)—¦BаˆÀ”-¥ØŠxÀÉx¦óóy@žF·×˜y@üS û>y@ƒÀHj&Q @œž.Û=À¢ºk'‚Ü\@BÌW\)»6À6qå˜<x@^º4@E^ÒhMhÐ?Ð?Gj©>VI|@2²nPX}@á/,3Û'iÀÄÇ{ÓÈ­”@0Ò±ƒnq~@v—|Ê82}Àcû5õéI~ÀX²lÀ”0 ‘% ø¿¼ŸŠ«©˜2@ÁzpØ'.À¤ß"`¢Na@Ø“kL|5À¶V¾¤å7KÀ̧¥žto®¿Ð?Èêéÿ‚EZÀ˜4¶/A[Àˆ•ر;w@á/,3Û'iÀ ^gGF\ÀÐ.жÎ[@ñ)î{“!\@ÓþÅ/]@¶QMD}·ò?lUñ!D-ÀXÕ©¥¨xC@ó¾éÁ•YÀ“ÐYpXX@ k>üÅ@Ÿ ÐxêÐ?Ð?X‰¸›Â}~@—Hû«¡€@sAÓIžiÀÁ&ÝŽË•@»úC·$‚@diÜüÉ•À†ïq j:À—õèWË‚À€4‰ø‡Àô“ø8@‚ ñÒÿ–3Àù5×’Ëa@à> hƒ6À…2ÿºÖMÀékÛ—ÈG®¿Ð?¡Á½rlT[ÀnþÃ(oÐ]Àñu5¬q€@sAÓIžiÀÞ•óu!C`À@\žôjO\@s`Ÿº>â^@¦ÄœD{Ø`@†¯æ ø? ‡ávã9ÀR‰s¸¢H@:IŠ4èÀr ;Òð£X@xLˆùöÌ@]§EÊmpÑ?Ð?ÐÞ¤6xj€@¼=?‰’Ó‚@ôpñ½jÀ&j½4Pö–@ªƒ™ÚJ—…@. ௽À¬éÿ h“ƒÀNV½Ks†ÀôÂ){»™À"ðc²’@@„t$8j8À•RlÜMKb@9‚`òŽ7À^dp OÀw š½ ®¿Ð?çæof\À¢îbKI`À¥Åž0@ôpñ½jÀ†1\7­bÀî.é¹Ò‡]@”úöî`@"¯~†kc@¡H%—¤ý? 0›Ÿ>À ÿUöíM@Æ ˜`Àõòv¥ñX@¾µxŸË@÷ìòT@úá?à?L²W#±§‘@ϨûÇG•@ æ…²ˆzÀÑ Âu¢.¨@È1<†q¦™@o½Iá;n’À㬫77–ÀbiýAåÆšÀD¯x[¨ŸÀqæÅŠô T@Äÿ1 MÀ/‹ª€žÌr@(úLHÀ±_UŠ`ÀfôŸ ø½¿à?©Uí;zmÀÛÇ÷æÃqÀz7ºš÷‘@ æ…²ˆzÀ__ÕÖÇiuÀŒýµºÅn@÷²9…®‹r@oèšÝ•Zv@íÒÃäÂ@8Ž,R1À&xð­a@Φ,ï0»(À:” ÿfAi@½´Ú[½$@]*?@ú‡Ò?Ð?&^%E–ö‚@‚ èÒnˆ@%”–sMûjÀŒ Ðu™@׋»pkŽ@*V¼¹±àƒÀųX:ï,‰À§Ékè£âÀ.#£(À‘]8†ÔtH@q«,g~AÀŽ­tiéMc@m°´½¥9À=´uÿ,–QÀV_ɀϭ¿Ð?F6ÑC5Ž^ÀO_ç~YcÀäå‹?}È‚@%”–sMûjÀÄÌ“è²hÀôÞ{¶`@\•^Hd@qðóÂ=°i@p¡k‡w×@p` ®ÝÀ<%/3€tT@Ô0v9ïÀÕÏénü’Y@8'Í!ˆœ@pg˜Ó?Ð?¥ØëV„@QYžÇ‹@ûô®©/mkÀMÿ‹kÊš@â8 Q°’@Gy÷òi…À'l¢ÞŽ|ŒÀ^jôL[ó’ÀiB&šÀË]9ûKM@šœ‰ÀYDÀÃå(×Íc@$ް$«:Àœ…Õ£¨RÀ(P'‰ ¦­¿Ð?l–éÃl _À4bˆ eÀØÆú,£ƒ@ûô®©/mkÀ6N7þkÀ}g^¥`@åÇ7»%f@Ü[O‘Œwm@ó ȸ@öòRJÐÀᜠÄ:MW@Œ>\¬òÀvŸêæY@lWFYb@m³8ÍIÊì?ð?Ï;sÒ”@'›*kž@ñÚÐtå#…ÀÑg3º´d°@nnxÙt‹@Ayîi}”ÀÚ¶fŒìÀi¬£õ‹À–ßrÂ-ÀŒž–ò#Ü¿¬úPÎŒ8HÀ® @rž¶~@—'?…º&QÀɯuŒYdÀý·ç+`Ì¿ð?ù?™dÆÚsÀ~á½6fpÀ€!¶¬U™@ñÚÐtå#…ÀTm0kÀW2Íö8t@pBA½O³p@AÃÓ[Œ–k@˜ùðáÜï?8z_H‹ª´?Ü™dÿ Àm|©¯[†0ÀYbA©w@¨[ŸA«Æ*@­ZTuc°Ý?à? šÚ´þÈ…@àË'dô‚@?8F¼(ŠuÀÓ«3~P¡@gt,cb}€@ZRôŒ>†À@º“ßYZƒÀÌí‘]Ö€À)ùçÊÁÚ ÀÚ•4>*ñ@7R–Psn?ÀÆo¡‰o@tlF¶3BÀlKÄG™UÀ<ã–¿/¼¿à??ÏÇ’lµdÀuø{SbÀ¥sÚ›Š@?8F¼(ŠuÀà˜Y_Àµ1GÀŽŽwtÿ«¿Ð?#LÖlå”UÀ¿—Wi_ÅSÀ|È!¶Ñ·{@Bæy<ïeÀ_PëϼRÀ©Ã=µœV@‹Cô>T@L?Ä_ŒR@UÙ€€è?,#þcÚüã¿¸ÒÆ2@ÎoAGÀ»ÅŸÝ‚W@¨-¢51< @Áè­%Ï?Ð?ëÍ)ê.xy@?Ù,„x@_]_•SfÀX~y—èH“@4á&¯w@}Gz‚)zÀn|xÖƒ:yÀ´¹2r TxÀäˆ8 óJÀl¡% /ý(@)â!+TÇ7ÀÏuÇæ°¦`@½£ëâ3ÀûÌWú"ÞHÀö´V6:Ï«¿Ð?x¸±xVÀ%L£vi«UÀ¢%"îþ|@_]_•SfÀéÙiuåTÀOÒ\%W@‹6‡IHBV@ˆ˜®¸ñvU@L7ÑËš»ð?¨”‹îí¿Å¦bÃÕ;@R£ß0X"ÀÌÅ`¦ÂÇW@Чô¸=õ @¢ÔŽ3EÐ?Ð?Zü©þã{@•K·‹µç{@`]/\oµfÀÎ?â§{V”@¹úo Q|@_{áXW|ÀqDôVÂ|ÀÕš×é.}Àö¡Ë>xiÀ@…bžü1@Ðc)—C<ÀÌüù“Œa@ôáÔùÜ4Ào{²Û¤ JÀ ·ÇŽúž«¿Ð?¬ú]-`WÀËz6Nm¸WÀ$ £•U~@`]/\oµfÀ]§QiúXÀñEARX@FãjsErX@]®¾+ÎX@BÝ/tõ?4pcØËó¿êõ›ãB@ã%¨ÌÀ[ŠX@è."D¨ @/}¥ øÅð?ð?[mÏÛA©@,6п©Ÿ@Ê)fW‡À:µ‘×4X@Üsyÿkˆ`ÀÐ1S_š@Í¡óþÌÝUÀ|yRÞÈxlÀ:ß7—nË¿ð?ó¿¹ÍJxÀ‰xEîyÀi" v¼Ÿ@Ê)fW‡Àü.(øN®{ÀØâ¯Ây@݃š”Ñz@Tµ™õ |@Ë ‹l@PÈ$ quÀĺ7d9úg@OŒ8@ 3ÀèØ¾,ŸXx@SBÃ=P)@ã‰êãJá?à?bÃy8õ@ŽHçìWð‘@-Ïñw¡uwÀl óké–¦@‚¹ËÚ#”@v‚¥'w–À©£PŸ’À䔟œ è”Àh¯.”ÂB0À£v»]w0O@nXÌ!SÀ5CÕ_r@û"¹ÒãFÀv€Uef^ÀhXZkè=»¿à?3Ûç“Þ6iÀÝ…Ð&—NlÀŸ^OG#š@-Ïñw¡uwÀ´y¯zkÇoÀù¸|öÍ,j@Çdϰbm@#¡îJ±~p@¸íV£@hm¼:ç À\xm1]@P˜}/7e#À2ÞD¢€¤h@€å ˜Ñæ@ÕzB€àÒá?à?mæb562‘@ÿ–~L”@cðFc-ÓwÀ—Æ~xÝʧ@v?C*õ—@RÝÔë‘À¢#œ 2'•Àš°ËJÅ÷˜ÀDxxD2À:Qù–2~S@^N[ ÐUÀzòò¨všr@žÌ£êìGÀ¤ùØ(3`ÀaGH» »¿à?Ý;é#jÀòëÍ•¹ÚnÀ$U"Àã^‘@cðFc-ÓwÀëÜ­r–5rÀÝea>k@¡éLEãp@‡ÕKà$úr@œ„øÈ•Œ@ØyUÚš‡Àñ7<“XDa@ù½uB¥#À×D%Œòh@hª d@P‡=o(_Ò?Ð?¡ßóŽ{‚@îö²È?î†@¾ ÞäØ.hÀ$KÙA ™@eáÓÊùrŒ@S©)WƒÀî[j´þ‡À½fŠÿÄÀ@Ô!5ül$ÀàãþÄÐG@¥Í’r°HÀ·s‘.c@tMÙÝGö8À›ã-ófm@#—4Ì*s@BWŒGüx@Ø<º¥½^@œÞêãÀPN(®AÎf@N+º¿¸#ÀË N Z”i@ø·³Fžê@†UÿõÀÌ?Ð?Öæz{ÿ†s@Œ•n‚u„o@ߨ:IJ cÀ’'·£û@ –¡ØNoi@Ä{.åÝsÀºþ»pÀ­Ð(g}ßiÀ>£žL[WÀ|!šOA7ο0{A+ú7À¸Î"f^@~Øi#Vª0ÀØèíg8£CÀÄ‘ër¸©¿Ð?5Žçe›QÀTïÒ^kLÀÕ}«PZx@ߨ:IJ cÀš'RìüîFÀ½ôSéQ@OÅHHYèL@zON#TG@P£s dKÆ?ØPZ"–?¾o翉 ø¿ Ät…?þÀÆ|•ÿÁV@Ðõ7Ñöˆù?Ob:sÝ?à?¥‰'!â'…@²ÐHaþ@QÈa“;asÀsäÒ=¡¡@Pµõ±š~@Bè&ês“…Àó¹â‘ŽY‚ÀŠò¥„N6À¤:‹ÑÉ/Àu‰ä4~@:Ô;´ÔKÀÃ*Í–5o@®RÚÒMƒAÀŽ¿¦ôUÀ[œžnž€¹¿à?däÒfèWbÀƒ2on€3_À± 6¿t€‰@QÈa“;asÀ-{+‰ZÀ»_ó_-µb@’m}ô%Ò_@Ë\Ô[@hñÖìÅ”é?ÀfOAíпl^Bº§.@¦)60hÐÀf½6pÿf@ȷϸN@h((Ž]Þ?à?æÛ ­(æ†@‹™E6„„@ʓڨ ³sÀµ÷$éù¡@Òpºa‚@ˆTõ\k‡À§r¬{Žû„ÀÀ´ì§Ì‚À›ºØÃJÃ1ÀÌjW-@ÒÿTòøOÀ+_ÍA•p@űíÃ]eBÀDö§¾¯VÀ<øË¦H¹¿à?Úà·ÓÜcÀÑïæJaÀÒ—)²´Š@ʓڨ ³sÀNÆËC§^À,`~œí†c@[b Ì~a@ÖäÙy“Y_@|œs5,mô?8‰ÞUàFá¿)9ãíA@ü ó¾À;v4T@g@ ~Ç6ò@÷?2ÀÃx@÷PŽ«;]w@± àdÀÄ7ªGø’@+ÒÏp v@uZmæfyÀ sw¥÷wÀ¥*v%"vÀ§$YytÊ#Àº²Ö4# (@¾Xð?_5BÀ}{Ny`@rhÿ”7P3À…Ô†® THÀ˜m“Ú{©¿Ð?×—ÅUÄÚSÀ•ž:·»RÀÆô¤£÷{@± àdÀ8à¬QÀQŒw1ü]T@npEù…7S@úeþ°!R@„QÐ*¢}ì?p«]}Ù¿d; ñZœ:@̦£Tš^ ÀØV ƒW@`¶FCÄõ?jšÃë"Ð?Ð?ï(ùzÀz@Dò¼z’z@ +;A QdÀ¸¥œ4”@ÞepšÉdz@ð$Xrˆ{Àkδÿ»X{À 7ñôµ){À•ÅIü%ÀéF­¿H`1@¢ýqb±–DÀ±\u¯ï`@j‘1ØJC4À‘ö-q¥JÀßC“ب¿Ð?3Z„R TÀ¸Ö"‹|TÀDâÙËëI}@ +;A QdÀ€†.ïPYTÀx{³pä9U@½C¥dU@$Ûœ#ñT@´§y½~ò?U  ‚ß¿ó*(»¤4B@b¿<— Àv­ypÈW@@êò*¶gô?úº S¢Ð?Ð?=Ô*qß|@º÷Wb.~@ïTÐÝúœdÀ“ž˜1•@P×6Œ@T€*ÏÐ}À¦;½½*À5ôå÷,J€ÀFÔÍZ(À/2r¹p7@| JŒ¥!GÀZ‘©Cja@Äâ>³=5Àçîÿ½ùÞKÀšÝÁø,Ÿ¨¿Ð?U-é[×fUÀX¶ÒÓ&_VÀj't›5¬~@ïTÐÝúœdÀÈ›'H·bWÀ=Ÿ_¡V@4¹vW@oìæËƒ&X@šG–ϸöö?Àõœshvâ¿C¯8G@°°a㥠ÀqD‹)X@@ècŽrðò?0xt%ñ?ð?mñüú Ÿ@ÄIñ¡f¡@zEq´¬æ„ÀMÚFrÄ:¶@ží‹òfÒ¢@Gåÿk! À«¿jJ½¡À‰8VE=‚£ÀêþΕçJÀ´äõLC^@]ЬÏÖiÀTBFYè@4ˬ›%>VÀÏüå¹ÄmÀåX5äÆeÈ¿ð?tt¥‘[.vÀC‰Ê¬·dxÀóö§uš @zEq´¬æ„ÀÏœçÓzÀ•当ýv@“…QàšHy@Ú«Ü.Î{@NìVy¦@0ÁQ`À—9‹ñr[l@¶¦Q›-À“&Ïô6Zx@ð®&qS@ôÕ™h¬ñ?ð?“zd @"KwÄb£@20‹ü-…Àø£—zj·@½ ?dk¦@2á`Òo¡À™t +¤À½6,6ÍS§ÀŽé!‡£MÀÿ¦4=|ñb@V¤5âµlÀ^PhÎõh‚@óâ6KÕBWÀ²3 àì¾oÀ´ˆë¯¦+È¿ð?†þ:…xõvÀ<À#b"ŽzÀÂå6~ÓÑ @20‹ü-…ÀP„C^·~À.‹ußxãw@8ÆY¹j¡{@]È·±jõ@¸­ŽmoF @0À[ÓãfÀž¤¯ßøÎp@Ssz^-ÀKd4õƒ¦x@€czßP@{ ô`B7Ò?Ð?`Œ[ð‚@`z¨12ë…@\¬ÉÁreÀø=èâ觘@¢–m!¨Š@²ö_O!Ô‚À¾ŒÖôå†ÀÉØ°çôØ‹Àøû2ŸHG0À\Óo,G@]üÁÇ`½OÀËífÆêb@xÉ ]I8À’"{¦ßåPÀh·lÏ’ð§¿Ð?ª”oÁâºWÀ5×éÛ\Àct3†)@\¬ÉÁreÀÂèC:^ŒaÀ"h8j]ÊX@ü„ùœ&^@Õ T_ Ub@ÎV’ØÝÓ@°B‹X忇¯ÆA{€S@žÕíj Às"nºíôX@€‘9zÞê?Áh|߯ò?ð?[B…[£@×#B÷ྨ@™ÁóPÑ´…ÀáNw¬ó¹@2ívã-¢¯@pø@h•N¤À¥}EC™õ©Àhµ¥–±—°À°5©ÓQÀg!Â…™Õk@ê+>("uqÀÿÐallƒ@Éôpí NYÀ;A¹$ôqÀÆ«8ZE´Ç¿ð?Ë©,}xÀÄóNÀtÙ zr¢@™ÁóPÑ´…À亿`„À®às3‘°y@yÎ’k€@—@:4 ý„@eØKÌy%@P™9±ñÀWK¿Œ€Bv@0›‹›'--Àó޾@Ey@ ™äÿv@[¬/6VÌ?Ð?)Ð 3÷r@Žwa1ïm@ ò56aÀЇ| ³@¿ÄÕ Ÿg@c„B» FsÀ ßJx knÀjD‘ÞhÀ6Cb:‹Æ$À T^| 3Ø¿¿¼ŸècÎAÀ*3£\^@eáÈ‘Ñ30À?¥V^r4CÀ ©pܧ¿Ð?Š/äÍ‚õNÀöF "nHÀòÝɲÓrw@ ò56aÀýáï˜9GCÀW”Ø·uO@×™MÓH@ªUwL—C@àñÆ6Ë¿qb×]kp?Lõ©‘ú5ÀÈâ¼cK6Àˆ°Ôà€„V@’°šæ,¼¿}‡*Ðõ7Ý?à?žBw„@×À×W@nablxDqÀÇJüôh¿ @æSº"uw|@Ö•Aò„À‘³Oï_mÀ{7ýdöÿ|ÀxDÂY7ÀïP~"Ô-@ü$4uÚSÀÈã\(Hän@‹³<]AÀâÚJ©TÀÎÚäÎÜÙ¶¿à?º,/`À¤4€mËZÀ>ܨˆ•ˆ@nablxDqÀêK[@@!L!¶V@0ó¿ÀÞ7XP¢?˜H/ÏÐ*@ö2…ÂÀa4Áf@€2T1·&Ý¿ßÐ×ç¢î?ð?$$"¤eD–@´ïNˆ“@ŸuI8ƒÀù÷ž*|¯±@sú%Z‹‘@9f¿Ú¿–À oˆUò“ÀÜ—*Ù}‘À ÔŠ“rIÀeþamMî;@Ú‹… fÀR5ëTbº@3 ·>õßQÀˆÏäH 1fÀe(¡•wšÆ¿ð?÷•Òý»pÀil±XmÀ[[,ð*Æ™@ŸuI8ƒÀ‰’¼iÀì’0¸q@ÿ‡ Púm@¤©QÃIj@2êé¯ç?@ñbf6Ì?ÐxS‰“…O@’iY¦óG"À\À@ñíÿv@ Å,•Oö¿bï Ö Ï?Ð?ìð¹x@ry-¹=Bv@vS#Ÿ'ÀaÀw17t{ª’@,úL1~t@4ò+¯xÀŒX ÎvÀoèèžuÀ4ÇÛ,À¬h›Ðk'@X2MÁ…fHÀBðU?M`@4ÑJ,jÃ2À¢ÊFçýÎGÀÓvŒ›Z¦¿Ð?ázД–^QÀA‹ùŒ PÀü ÓR{@vS#Ÿ'ÀaÀ|nêmЦMÀNÀ1æËQ@³÷ uàpP@ïR>ÿ`N@° ú¬Ù?À0­ä¤o¾?3]쮄49@Tç®ÖÁÀUÙÛAW@€`)bGRÞ¿FEœnà?à?ÊUœZÔ Š@=}tÊV‰@±ÀIšLúqÀR‘"Þ°£@‡Ä[ƒœ§ˆ@@ÙÄŠÀþ<°ù ŠÀn¼;îV‰ÀÍ `ŠÝ>Àÿ¿12£Ã@@¢HùŠ!êZÀž»3Âp@«,QS¯CÀÔpÌYÀö‘ƒP2¶¿à?~Š¸È•bÀbhæ†aÀþdLU SŒ@±ÀIšLúqÀµ/’4í aÀ02Ý‹§‚b@p ìx¯b@?2‚,†a@Àì[ög!ô?@2Á*¤½Ú?oj?)tnQ@4á™Ö{*À*‰$°–„g@ÀµIDA[ó¿NöÎ à?à?X(øŒ@šé\OÎŒ@ÎSôÆ1rÀ öœ!ä@owkmë@Ö´_.À&Í?Ù´À–ížÃnŽÀØ92âsð@À/8ßÀ®F@¼C…+“˜]Àø®GXQ;q@øŒ”Çþ¢DÀf¡j1]J[À°(ItÙµ¿à?RôohÖ¦bÀV;rS"cÀb=_­»±@ÎSôÆ1rÀV¯c_C’cÀedD¢Àì<¹WRÀ±¯ç[»W]@ôÖ‹f99pÀäEìU¸@nðQª^UÀe^œW(mÀ†ã)?—Å¿ð?¹5‚¿}JsÀ”NVwÌtÀÉ~†ÂU Ÿ@°dð$mf‚À³¬8›kvÀ/`â:÷s@o\Aœ9†u@V/ÖØ]4w@”~…à ì@aÍíÞF¾þ?`‘ô«mk@JÕô«#À¡R!™µx@0_:ã¶“ ÀŠLÓ†Ñ?Ð?Íên^BW€@.0è}¸ˆ‚@™Ö*˜bÀt¯e-a —@LøFŠ…@n¤ÛÒ ú€Àb}°3[AƒÀh9¾ôÖ…À…:LåE4ÀÇ:måìeB@—ÞT»»QÀ¸'ÅA8b@¿=>Ióœ6ÀÉ:7¨OÀ™êfT¥¿Ð?qR·Ã‰ìSÀìaw™VÀ/G²YP€@™Ö*˜bÀ$æ7Б¡YÀÔæ ³T@˜_`àå’@¶ÅO+´—@§ÉL¡ñrÀÑ—H­©@ÑeÈqU»@±Ïþ* Ë“ÀÄ]¾Ó˜À£WSñà#ŸÀï£Ó†³HÀOó–/"[@/àty½ýdÀm軡;s@¯³ì¢HÀ(£‹ÁœaÀ:ÄgîÊ´¿à?°NˆÆä&eÀÜuí‡jÀëSŽ’Ië‘@§ÉL¡ñrÀÔ u’£pÀ×™Óód'f@c½µô§Ék@^õ†Xmq@1Îx)žÿ@èˆ+´üö@˜€£kªe@–%?À\VÚgÏøh@ÐcëŽîÀÑácóuì?ð?æÙgÐp’@àŽOƒ,zŒ@/P^¼8~À‘;ÛB0¯@ç Žèý…@©U$tÉ·’ÀØ!¬SéŒÀgƒ€S†Àó-¾ŽKÀîç‹^x&ÀJ~‘ƒgÀp>J`=Í}@SÛç…OÀº \ŽÒÉbÀõ Žz Ä¿ð?‹8nACíjÀ³?ÄÎcËdÀ­PT%­ž–@/P^¼8~À4·ÓF `ÀJÆ0DVk@\`ÆRe@峊M`@Â<ÒW· Àø†N zÀ¿‹ˆ=M‡Á-Àœz—ÐbÀÚ[eFAJv@0æ‘æ`ÀìFÕI¸ýÌ?Ð?E½Xsÿs@ÿ^öF„Jp@zé1Èg^À::7ùÂz@°À›¡óŠj@á`ôúYtÀ3±8D”pÀÄm0kÀòO>ˆâÖ-ÀaVú ]%@~XÒu­IÀìc‚p¬•^@ O20À>íL(ˆ7DÀØïRœ;¤¿Ð?Ö]¹ßœóKÀëù}FBÅFÀa¬J¾w@zé1Èg^ÀLOg‰ÁŒBÀTw"&rL@k32+W,G@f<»àB@(A2ºÿÒç¿ Ë¤o„Â?bO>9Ò@ BÙªòó¿cž Á%…V@È÷v‘ãþ¿¡1ãÍ?Ð? û•g«u@Ã¥èœr@¼U6qÀ^À~ÒÀ¸g‘@à ˆ\9úo@¹ð-)‚vÀ±EY@þrÀ,vióPpÀ6øDfüe0À-‹^¤×{@úkÎR~þKÀpûǬOh_@à²]b`1ÀQ }ãá¸EÀª‘†ô£¿Ð?; ðjûLÀÌ—ÇåHÀ×ë»O¬ëx@¼U6qÀ^À”Ôèq]bEÀ2ͱ’M@!l vgI@XºAûÑE@XtARâ¿ ®ÑEÿšÖ? „8(¢,@p€¶´qô¿;ÙÜB@ÂV@1%üd½À ¬ÉœâÎÞ?à?7ØðDVu‡@œ×ñ<…@táÏ oÀ½äýãq_¢@hàöW:ƒ@d9[VkˆÀ1•åáû…ÀÃÕæ)­ƒÀX9›(üAÀ²Ú™ö!6@2|á¤x^Àºgø ‡"p@¾è:¬olÀÆ@Z…²Ýo@´¸ ,7en@úåLÇþl@ “>™Ìùì¿€Ô„-ì @%a%›‘`@lظ¢—À\ÑŒZCw@'Ñ49}#À&äu{]à?à?ÞËS©h‹@,A<­ˆ‹@5ìÀˤ¨oÀ²‚vžq¤@PŠÖ¨‹@2Ì"í‡:ŒÀGï°ù€[ŒÀ|ŒÀOï¯Q€EÀ·w¹o)ìE@QvST÷aÀ,¾Ÿµ• q@)ÙõlÈ DÀº§×ÖݺZÀJÀ¸ä³¿à?¯¹é.`ÀÐ=ªÛè`Àб“ãlÌŒ@5ìÀˤ¨oÀˆÃî­¸-`ÀÆä‹§ð‚`@ hsý9–`@¢\zÚ™©`@€I\a±~±¿ht„kÉ@(DPÚnU@0â{/À£6,­p‡g@<ˆúaü÷Àà\èÝÐ?Ð?`¡Ìˆ„”}@ ‚T™H@ȇüéè_ÀIxП⋕@Il>劀@V‚¯ù›’~Àd#‰7©*€ÀÔ³a¹þÀT!>åp7ÀÌÔ*Èm<@áÈ×=5vSÀäâëg‰a@¾µÚ¶5À&VÒ“‚‘LÀÃe«žêÑ¢¿Ð?ûÅYçˆPÀhÍ 7ª|QÀ^UpÀ˜•ÂÓ9¿ð?L<»˜¬€qÀl’âÅ~tÀ§­,Œ  @wª;’¹)€Àw®v¯ÛÿwÀàΤ:r@ÞÊŠXu@c¶„Ûþx@HŸ= @õ²uC#@G@¿ƒ[r@lYr²òÆÀ¨ ÑDÉax@H€ò *ÀlAcvò?ð?ÚûÉé‡u¢@¡¯ùÉ»¦@ra–p>€ÀhðÄ5"+¹@­Ð#Éoÿ«@zï1ÖM£ÀqcMÆ.ƧÀÉ€À’ð"={À°µ¶ùÒÇr@>Oc#!w@ãµ2A||@¨L£ Ç9 @\6H f'@½úßyu@)"@̈À0ÿ ïx@ȹ4á´,À{„>%—çÛ?à?µp¢Mð@Í~=²c#{@·0ª—) jÀœÍ£iº±ž@A¬¦¹‡t@U<Í•þ1‚À™¶>äņ{ÀРˢLÒtÀÈÑŽáwŽ@À:"\ýá±ö¿ˆ£’]ÀaX´Ã¶„m@”›p}ý®>À[©lþ$cRÀg~Ö¬¬ð±¿à?ÝbáÞËWÀ§ÚæKyQÀ›¯hÒYÝ…@·0ª—) jÀO¯Ï[oJÀÈŠÀëdnW@Z‡ªI¹Q@¤†vì)ÐJ@(Èuáó ÀŒÕëgõGƿᅮ·èK$Àð%:ß×`㿵!d2f@¦‹T-À„qã9¸Äì?ð?aI‰çŠw“@=cPO¤@Cc’i+\zÀÅ-²»8°@+f0´¸Ïˆ@›ÎÅ+ÖÊ“À,4g¯ ™ÀG35 â9‰ÀÁ\Ò.»-RÀ¿ÃP5B$@[È~ÙdoÀÌKÒŸ·I~@"Y•PÀ´ÜVi5ÊcÀ›5È…¤Á¿ð?LüŽ“égÀsWÌÍcÀÛkà!4ú–@Cc’i+\zÀt,À0z^ÀR+äOh@þ(5%{hc@†¼D˜ü^@§\ˆ=>À@í³º Ìï?>YÙˆÐ-@0”ßRü‹ó¿^P§zKv@ˆÌÝ ì»,Àþ.ŒPܧí?ð?Áœîá•@\.jš½Å‘@|»ÏÁ‘zÀDö˜Œ"±@îd@Í î@vdPhƒ•ÀÒ`¸´Â’ÀxIÔÞ‚ŽÀ×^x $êSÀÝÄ;âøÿ8@¢½¢ŽóépÀœ¡|ë@I)‡xæPÀ×¥£·˜DeÀêµðüuVÁ¿ð??8o7&¸hÀîñ6çÐdÀ ‘q[¬$˜@|»ÏÁ‘zÀÎÕžgq‡aÀ¶“2i@T&5ÿ7e@Ó{­øAÞa@\ gÚ_hÀ§_t°î@Œ»ÙdjI@׬dó¿|æGí†v@°€>T`X.Àê yS‘î?ð?¾Õ’ÈÛ–@¾“Á®ØK”@qS’ÀzÀê |G²@åý¿”Àáx\råk’Àß4›:ƒÅUÀ‰£ÐM¬(E@·»N? 6rÀÖIÁEJò@@÷(»QÀvÕ€DÓfÀAãå°ìÁ¿ð?k=Ò€r„iÀÑüž6¨fÀ†r KV]™@qS’ÀzÀEldÀ$Jz‡j@s (e)g@¤·ÜËod@XÔÕÕrÀ€¤ž¨ô@ÐÛiNàU@`çX˜Íò¿7­¬žÄv@ ~Q…0ÀL¤0#mï?ð?j?½ª»˜@ÖV!G%—@ÅE[ÅBèzÀtßÀ°³@¸3Äåø¨•@ÖÖÍé[™Àí™î.=»—À—œ¾ðN5–ÀâxÁWÀ™Iy‡lO@bsÒêQ™sÀ’:ÒÈj€@ê´§Ì|˜RÀØÜôvwhÀxE¥-P¸À¿ð?”ÿð@?MjÀ§æGhÀÔ8/ͤš@ÅE[ÅBèzÀYÀ1¨gÀD*¨÷j@|V^0Ž_@ TaG¬¤ñ¿ã¹?žw@Óô]â0ÀÉ[æ;<ð?ð?äÜ=Æß»š@¡Ø]‚p[š@ÝXq‰o{Àu„ ÌÑ!´@¦Œ]ü™@œQ=˜ì›À°Øð"º›Àág°€íºšÀÓCØæ¿ßYÀ“Ýl—Ð*U@™ 3°uÀoòòëá€@@Ž(~SÀoØãA_0jÀ¶Z ^ƒgÀ¿ð?¶z.˜&kÀy ¸ƒ¯jÀå?‡+´û›@ÝXq‰o{Ày AOjÀ_ +Ȥ×k@>Åæ5sk@ö•ÒM1k@˜}ä5B-À("× @â7ƒ¤hd@@ûœÚG…ï¿Ásvý÷Fw@¢f48aÍ1ÀèçL[»ð?ð?·ú}ÊÝœ@¨Äàø@˜ì± {À‡ \^ù8µ@°óÉ66Ÿ@7þGµËÀ@Ô¦¨´ïžÀN3Îp À|Ž$B!\À]Un…[@Dýu£vÀöýꨡ[@U…gNkTÀ¿­˜„ÿkÀ _+öcÀ¿ð?ö ñÏÎkÀ-ª›ßlÀ‘ô–½¶b@˜ì± {À(ˉ÷úmÀ“šì³l@ÞëV6Ím@Ä<8Dñn@ÈHYqðàÀ2OJ€$@+âfÞMi@à¥;põé¿Æè•±‹w@†h“˜„Å2À/`Ê 7>á?à?GFËÌé!@æµC®‘@F Ù0kÀh²ñ¬\¦@ÓÁ䘒@{z.‚ À˜c.– ‘À9â‡eD“ÀknÞs·†NÀ(‚ã“yRQ@2!,N^JhÀ‡Õf­Ùq@(}>y$_EÀˆý ä]À9Z™±“ƒ¯¿à?޼)¯ƒ\À ,æÅÇ*_À3è=A‰ÚŽ@F Ù0kÀj\NÖ†aÀO¼‘¤Š]@µ=‰ã%`@ó]6r›¥a@ØrüS5ùþ¿LNU£wi@ÚiÛ éO^@€ü&±Ø4Ò¿ö- îÈÒg@Œ*ƒ Í#Àx8èÄÑ?Ð?$*ÂÄ€@aß«ÌIƒ@A“¢µ7[À;Úïíx—@¤¯;Ä/†@%ïc¨pÀžº[}‡„À{\;+5‡À>ö$.ˆ@À´ÔJE@£*ÊùäZÀßðTö@Zb@D›´*X6Àxì[x4ÝOÀ7H Ùž¿Ð?¥2IÜv.MÀgkkˆÈPÀP=K¼ô1€@A“¢µ7[ÀÅÀþNSÀÄÜYN@†iT/ŒtQ@AŽ:êT@ VÉ&ê¿ e-ËsÑ@Psèá·Q@€ ú•L¯¿3dD2X@Êbá†æÀ±<¤\€Oâ?à?ëý&lh ’@Îûéî«Ô•@¥íŠ5kÀw%ñ˨@ü_Â:Æjš@¶Ø hÔÖ’Àßúñ$ Ì–Àл%g–›À›Ë;ÛÞQÀËkëò®Y@åÒ71ÚkÀ##ÃQÜr@¡ŽojTGÀJÐ: tô`À!}VìÈ*®¿à? ïÇ—œÌ]Àh±î‰£bÀó¿ãÏÿ@¥íŠ5kÀáƒwRÑeÀõÐY¸E_@‘Y%ðÓb@{ñ]ŠÈf@¨Y;áRøô¿ä}$/^c"@rƒœÝ!Wd@U»…«¶?ÚMýÔgh@N%GÜå&ÀK D]Õ±ë?ð?ÐÞ]2 x‘@ ó ‘è‰@Yn(À£MvÀÀé´õè7®@;¥:q6ƒ@–m’BP´‘À9—«õAŠÀ2Dˆ»xƒÀñIÿmNpSÀî(ÑsDº Àcì—ĨOqÀòž>ñ¶>}@ûÖAbâMÀ/Î7bÀ–|›¤Öξ¿ð?âwcÀ¦RMLmÞ\ÀE$7Ä[.•@Yn(À£MvÀÉ(×phUÀ˜J 1ºc@D‰ìÊB]@Zû*;N²U@vúb ø)À\fûÆ$‹ä¿:ëØt¿T:À@ÆÃVt@®~øá3Üu@º¢•î3À÷~ö¿çŒÌ?Ð?ÿru÷r@_g•Õ(³m@¸.7*¡gVÀQ×À­Ðñ@´Ó#™ä@g@\ðtCDsÀKA.n+nÀs<ŸgÀ˵†L5À}¤³o¦Ç@¬ð™ RÀˆ,”b[^@2õæH—Z/ÀßI-˜å`CÀü<œ¹(ž¿Ð?½9”õDÀñ‡‡m?ÀÒÝÄHv@¸.7*¡gVÀÉ Ø?›8À±inû;cD@–ú]EÌì?@Ã,äþ8@l¨p‘‘À$v×Õ?”EábP½@X˜÷yaã?»òIŽõV@æÿáßÚÀµáG ämí?ð?"›Ô‹’”@f…Šsÿ@XÁ ×CzvÀžÐŠæß°@i”­;¸Œ@ªˆÅYó”À,´1woO‘Às®"r䚌ÀÀ”HWÀxiOmœz7@ë àÇsÀ¼Pn„+Ì~@GáJ0rPÀ‡6h¢“ÔdÀšþëÑß½¿ð?½e]©dÀ¶qsaÀæùN´¦p—@XÁ ×CzvÀ8+âv5\À¿BH e@žÃ,ìaba@¦Ï!Ä3º\@ØBjƒè(À/¸Uí° @Þe -8áE@ðã\€@Áá£õÕMv@2·9¦ïÏ5Àû"Æ;UÞ?à?\~¾JÆJ†@>™“mƒ@}SP,+…fÀ‚žŸ>YÑ¡@f &“î€@³’ëšÃ†À‰BôtáÖƒÀzG¦þYJÀ@¹¨ïSfIÀ ¡·r,4@xdràê"eÀMXüê-¢o@[=#i?AÀê³²@\VÀÍ]K>ÊÔ¬¿à?f.l/:;UÀë0ŒDê€RÀ3÷ÑP•¦ˆ@}SP,+…fÀàzÁBR PÀ«¾¬ïN®U@M Ûî5åR@Ñá$»wP@0­0ö–ÀœH+®<3@oÉ_¿í÷C@@W±éÞõ?mlÈê‰f@øP6BñÎ&ÀÒP!ÚBß?à??¹!”!ˆ@:dƒ],†@÷ þCñ‡fÀd§I¹²Í¢@U(tÐ_„@~€Õ·ˆÀÂﺆ¼µ†À™eŸ Þ„ÀkRŸââ¨KÀÆ2Ó¸—Ö=@Þ)G÷Z•fÀrj©¾Ap@YØ\³rBÀjqƒ:ÄøWÀü\û '¬¿à?Ï\Ù1ÇUÀD+4ÚTÀ•™à?à?}«@1F0Œ@UþõhÁŒ@bû.ÈesfÀ¶öùè¤@o.:ÿvU@í’ÆÀàDT’g¥À„v~ >ŽÀ%ì“PPÀÇo=œžJ@˜*rý‰ÀiÀgM…‘ /q@îô1ÚCÀ“áÛE~r[Àö¥²•ª¿à? PÁÆVÀÜá -ôW@ôçŸÎ“oX@ÊSe ÆÀz1iàK?@è ÖŸÊX@hPü`á ü?g×ßýKg@š#9šO*ÀŽŽÓŸ#ñ?ð?[,îÍ€jž@믕&V @Ù÷*[vÀ¶áwå¶@(¹é½{Œ¡@ˆœ×LÄxŸÀ¢3áÕNç Àqcj(¢Àª–Éq¬aÀ®xk0›Ê`@l¸°'—y{À:Ú\oø«@¿Z$Ñ ÇTÀÞ |ÖOmÀLÆ~K º¿ð?Xf&27gÀ ˆ#1ðhÀdÄ4ž@Ù÷*[vÀ €è–ÀÉjÀçâ^Nh@½lÐæœÍi@l}›Ç·k@¶*5Û %À®{‚z¤d1@+Íã m@ˆ6ü‚@=B±g‘w@L´ÐÝL;À­ aá á?à?¨¾(íc@—ô…ˆ’@Öéë§û8fÀ_•î4¸5§@áëþ‹Öô”@ \.‘ÀÛôôü?“ÀuáHKÄ•ÀnA[vSÀ5Ø7~¬T@àáRœImÀ+\.ý¿+r@½¯—{þºEÀ5å¦B_ÀâND¸-P©¿à?´Ž?ršWÀQƒ×Üu°ZÀO¯•øœ@Öéë§û8fÀûßÃ-^À¹\¶„X@Âă2«¸[@áGƒf„X_@dÌ}u4vÀLã Ô–ò$@DÛKp a@LB*?°U@AŠH/+Ùg@¨°Ð–[–,ÀrѵO¾)Ò?Ð?ÒóçYj¤@rwÎý„@óâ†.R VÀ™ç2p˜@2¶öùˆ@Ô_pàe‚À@»"‡þã…À±o›Ù ŠÀÜßl•ôŸDÀI€eñ´ùH@DÑaD//_À£„{,­b@¸m†>¥²6ÀF ™9¸£PÀHµ×˜¿Ð?üʲ´ßîGÀq©þyLÀviPµnš€@óâ†.R VÀJªFõðPÀ‰ÜÓ¿QõH@ó>¤B²M@À‘]x»ªQ@&ù}$ËÀ3aá\­Ð@~עלS@ZE—7~ó?ÞÜB,6#X@È´ öBõÀš@¨Ë#}ë?ð?¿e<¤ø‘@…C¸¶Çˆ@à­£jrÀ |W‰®Â­@ÿ5”‚@é.QCh>‘Àê~‚@I*Œüin|@<”O1ÔˆbÀ­¸è%wŸ@úµ¶;Úu@ø3-ÛèÅ‚Àë %¡‹Û|Àoœ†Ñý-vÀqP¹íBHHÀ1ÕóNå@‹Ñ3BCeÀî÷A¤‡¹m@áfEµ)Š>ÀÙ˜tgûRÀíäYÍü©¿à? *–bÁhPÀì{zšP9IÀ, ×”~©…@<”O1ÔˆbÀ2ùcœcCÀƒ—òª½§P@ží„"šI@ý'ŸÏp­C@ÿSjqœ"ÀìO•S`Óè?H‘a’Èã?(ˆ0NÏ@aÄà—wÞe@^£Œ®ó1+À4«ù° 5í?ð?)uâ”@‰[ I@…€…9UyrÀ{ÃÈB´Ÿ°@ô4;—mŠ@:àO:ùk”Àf݈ö‘ÀëŒ5oÕãŠÀt-µÎµZÀ?=òŒªë5@ê•(~o—vÀ¨‹ã‚~@µ–4ÇPÀü³ê¡hdÀQlPAa¸¿ð?UA½ˆÊ`ÀPD£à>[ÀÖ›ãLÏ–@…€…9UyrÀšgFÛdVÀXÁª<a@"ÇäFݸ[@uœã2`~V@$ºÃëCœ2ÀÕLnÕL@/ûð " B@Êܳeéà@m:ĵÚv@ìÊÓaVL<À»Ýñä(Þ?à?ËáY±Â…@¬ÿmú× ‚@bኼ+abÀZ£þ&Ž¡@öö*3Ïå@%¸ÐY2†Àae÷µ=ƒÀ£7¿oE€À ìJ§·àLÀÇÊ€*-3@}5¼JìhÀU ÿõ°To@ŧã/É@ÀfŠréUÀÁ¯–Ü’¨§¿à?S’¨Î#QÀ÷ÜìYYMÀûPeý¢ˆ@bኼ+abÀ¤]J ¦ IÀÖ¨›€|Q@Úc‚ã9ñM@ G¾°­¢I@bçÛÒª™"À2—âzH @TádÀh£ñ!¾b@;Ú\qÌÍc@@7VOìd@F¡èT„2À{š©Mß5@ÈV²¢a¯k@û VÈxk @¢T^yRw@,T4J)OAÀU¶^è|Ñ?Ð?I»8œ€@†qy EÕ@ã@ÇÝlVQÀE›Vá–@/ÇÙ\Öƒ@׎–Ùl¡€ÀApë‚À·ª0”„À¯û,âY—EÀßS…D@ÛÐ×â=`À—Œ‚Ñ<þa@zœ¦ÿ"5ÀÕ«Á®«NÀ,/Í©JØ“¿Ð?½äŠã@BÀÐWÞwNDÀïBê£ê~@ã@ÇÝlVQÀf"J–FÀÞ;HnïB@_ò¨ü`E@#wMnnG@ð).«€À»uwK0A@ž`šŸPP@˜B^ÿW•@ó• ˜W@8ê̺i "À‰0ËÓÒ?Ð?^§®PsC@ÿñ¹1<6„@Æ*ˆàVQÀ`Þí€>˜@Ôîè^í©‡@M&»ÑúÀ*Ú¶Ãë …À^Å5RG¥ˆÀ~˃6ùFGÀ¤¤4óVGH@Šìâ:aÀÿ1“Qb@JO³;6ÀôŸÞTUPÀå›9«K“¿Ð?#NEà-MBÀö±ÎXmEÀ<?€@Æ*ˆàVQÀ}@™?,IÀ}­Í’C@¹)úïðPF@¾½i"£ J@5½ãÀŒ8 äü@’J»Ù ØR@ëø@†©è@c²Õ$áW@ÆÁÆÒ"À"Ô›AvIÛ?à?”‘ ¢Ôœ€@Ólnü¾w@18ÞÄÍ]ÀMd‰íQ@åà7餸p@ÅåôÏ€ÀÜÄ‚xÀ²<8ÖÞ,qÀUÏ?o›ÕHÀÅj׌±ÀwÉé[³­fÀx-ºl@¶Û¹Høe<ÀX5­mÙDQÀ¥³0&Ò¤¿à?“9×ò>hIÀ,¾Ê®“(BÀÈöŽw€„@18ÞÄÍ]ÀœH4ªô9Àûü@±n¶I@™nLét`B@Í7rŠD:@y­Ý®¾)Àá8^‚œ=ç¿Äý+Nî4Àgˆº±Ê@­ô¨Èîue@„󸡻0À”Húú  ì?ð?ÎÒ»¤ ’@lÐ8·fD‹@N·HZ~mÀÖëbK¯@[Æpd€—„@pôWÿoO’ÀcV§PƧ‹À„†ÃŒâ„À#5 ÒO$[ÀJºÝN¹@pqm§ÃùwÀ8B+u}@}¹6û^ÃMÀVW‹™bÀ«epOè´¿ð?èŠáx?ÔYÀ´ß®0zSÀÄS“ì•@N·HZ~mÀ„Nf7vMÀ6‘ž\a2Z@Ìèr”ÈS@‡SŽ`áM@§Ð±:Àm?•Ì$û?.€ïæÀÞÀ”ò´¿"@?ÕÍrãªu@¼å•q°²@À\Ž…ýÌ?Ð? -²J™s@Ì»MwßBo@ª‹À™­MÀÿÃ™Ïæa@B·B†îh@¶öÄÅììsÀ}îOÉEÈoÀDÓD"êXiÀZ½¯¦8™=Àëns S@¬ÜRž[YÀöJc:^@/bòó1/À…¾¡Î“DÀèg/²rP“¿Ð?<‰ŠÅo.:ÀÕ£ zcá4ÀÑj0“?v@ª‹À™­MÀÅ”l§0À«Ÿ–Ë(ž:@Ψv }:5@¥Œ /*î0@ùa’ÖDÀXx¼ #Tô?¨¥^“8Ö@Y5̨͇@%eÞáU@. vÔQ!À…n¹óqàÝ?à?A…@põÏÇwä@þÞ Äܧ\À'qØlM¡@>|ܵ¹~@ì—1Ùiª…Àç¼==‚ÀB&š×Ç´~À–-ôfPÀªr£¶*2@ÿ ÁìXÔjÀ"Î!mÈ o@)®&a¾W@À×YÄþzUÀ›5[Њ¢¿à?2ƒDCUtJÀ+¢[˜üDFÀÔùGq‡@þÞ Äܧ\À[~B¿BÀ=æë7;÷J@P§$u-³F@éÜÙ{áC@%.æȈ*À4©É>p@˜Ï -g?@¼—à¼c@±Löf@€²êQÄ÷1À×|ìy·ÉÞ?à?ägG ó‡@_­fÖGs„@ùª§œú\Àô ºµ‹C¢@(Ísn)‚@eÂF{ñ‰‡À}\ ¢ç„À‰;Æ‹¿‚À'—$#¶QÀ võnH[;@LÎXÙèdlÀ*öH,Kão@×”DfAÀk< "¹ WÀŽoÐÁ¡¿à?Ýmäˆ=£JÀŸßÂ#¨GÀ‘ïçΰˆ@ùª§œú\ÀkcÐÜnEÀíçöÅ:K@+Ñ‹'·.H@bøóyE@¿›. GÎ*Àîw²­§?@vúk”cžH@Áø\cV@|ÃÂê?Vf@S¦¥-¥2À8â#¾¤¹Ï?Ð? ŒÑëx@3VE—›Vw@¦ùyN KÀhkAϵD“@Iµl¶"Ûu@3ÚåàyÀ…ð}‰îwÀ›ëÆühvÀemJy›úBÀÜ'é2@6—Ï ^ÀQ@ÎPc`@Ê*ºxï1Àí"@c†­HÀýª.ó¿Ð?¬ünì;¸:ÀzjIÈ9ÀJ˜¾••ÿy@¦ùyN KÀîóé«ìn7ÀNj §e;@8˜‡®/¨9@÷¹p8@ÓjWú.À„%:öÐ@@-Ü@@žcïFÔb@e‰n0Í“V@âæ/”ËZ#À~ýúBXÐ?Ð?÷ùÊ´)ñz@¥FI÷ñ—z@ù„Á” ÍJÀÖ´QcQ”@gNÞªá?z@óÎvÿF·{À|œ95[{Àº$Xç{À£ñXê÷ŒDÀâ~/Õ8@§s{×5Ð_ÀÜ2s3—Ù`@ž¾%ò¾Ç2À«9ýSâfJÀS.iâ!¿Ð?;Cý (°:À‹ÒÑ’ÇW:À÷½€Éú]{@ù„Á” ÍJÀ(’ãÁ‹:ÀõžRgt;@F8§û|;@áÔï´¿¿:@ê"ætaÀ”hóñP@ï³d½E@áè :JŒ@ êY¬ÓV@zUl$ÀÃ[ñóP×Ð?Ð?ä­o+}@Eêº×‹A~@ä×EçåJÀYµ¿‚j•@é,ÃËv@Ë–þ~À<ɦüû;ÀŠMðÓ=€ÀÖ¦b7FÀæ|?@<[´Õ`À ƒ—\ýSa@é>¶_Ƨ3Àì+¯ùç5LÀ„ÑpÌg—Ž¿Ð?ùäʇ:ÀdKïyÇ–;À;Ë¢]«Ì|@ä×EçåJÀ$•¼Åİ<À~÷Éò5c;@Ø(${<@Iâ>?ž=@Šõyé%±ÀÊHªhÕ%@™©#º7AJ@Ý@vÖ@#-m_åW@Ôhj@çá$Àð5cZñ?ð?Ò”õêÐaŸ@tlÈ1/¡@i$˜qiÀ_ŒQ%H¶@y;3âÜÑ¢@q6B À±‹uSΡÀB v‰#€£ÀáÕ(úgÀ„Dú+vc@L›TvŠÏÀfÞ|ºÇÑ@(Y™9ÐŽTÀ ÕS6-nÀGµýôUᬿð?è"ñ ÿ:ZÀñ<…ëº\ÀÍ‘]Lž@i$˜qiÀÒ*dðu_Àë(þºå-[@àÞeÄ]@ùæ<ù¢L`@b<]c<À%éÙè`V?@­Ÿ´o@«GÃ÷…C*@LÇÊzZw@*ó‹µEÀ2k`»àñ?ð?ÿn‚ fç @ZÕ] }£@fCwá{!hÀW-ÛÖÁ·@øÍ=gÞw¦@¥ìcÙ}•¡ÀeEóÔÂE¤Àñ"ÿC_§À&I{ÔiÀw8H9õ–g@G\’YöÔ‚ÀëÅXtðQ‚@^âY5¾{UÀlÊK pÀ’óÌÝÔ «¿ð?bëR!yÆYÀÍÖoú]·]À[H2ÏÝŸ@fCwá{!hÀR‚snB!aÀ65åÄíÏZ@熵ié^@I½Ç‡­Ña@Érõ\b<À“E¹’þtB@xƒ]% r@ 9ŒBÂ×+@\be¡w@D°ë:ö“FÀÆ‘1ÁÛ?à?:ñ\9€@•*Ȧ³Ìv@EAö£VÀ—Ý䨇åœ@øM—z%p@N”8¤h€À®¥3ÀUTêìË?Ð?‰±Í»`£q@+­»FF3j@\¼Ø3FÀ>ê!>Ž@>éK—uc@."†àqÀ1O®0ŽjÀ$ÚÿÔ ¹cÀÎŽðuàá=À•ÿëf·ùô?•ì¡1¥ZÀ¤ÍB33]@T7t±-À ½t€#;BÀ^Ûæªd7Ž¿Ð?™›+Å$3ÀH>‡?¿o,ÀM 'Ó›Ÿt@\¼Ø3FÀ°CQUÆ%Àcãtp"g3@ÄÄh¼SÒ,@4>¡×ýg%@Jpû18!ÀòõUq– Ü?ö/Bðo ÀÀ×h›Òc @Hê.tyU@PÂXÔš»#ÀvRß¹Çì?ð?~ðšÒ'“@Ï£<9Ž@Ä•V_qeÀ<÷èn&°@;ÀDÉ•‡@ ã›òÝu“À²žÒh±‰ŽÀɦàõ‡Àç‰ o2H`Àt¼5ñ°2@DÍ(Q|Àº1Ó-<õ}@ÝÇîfNÀÚ¿ï:œcÀÌã’¢¼™¬¿ð?ÏÑ[SÀš@ŸÁøMÀ#|`J–Á•@Ä•V_qeÀKæ»w(„GÀI¤f^RgS@(¯_BÞrN@ „ÔøãG@ªµí~AÀºØÂ49ò@ãy«9G3@¬¹î,fi*@`êòÅ®u@Ó}ÆlDÀY½Øoè§Ý?à?ÏA<¼(È„@©d~Y7@Fí,¦¹TÀj¡@ÜŒÒO†|@îKŸ§¦*…ÀâkÓQñˆÀÔu Ê }ÀªÉNDJµQÀ$)¬‹ö$1@ÐÇ+ßšmÀ¤v/gÁn@†éxÁÖ?À^@µcUÀç-‘”Kôš¿à?‰ãôBÀ¸ýh?ÀgÞl/;ñ†@Fí,¦¹TÀ>ü!@ò:ÀÄw}rºNC@µˆwZý?@r&Ì•B€:@ÊCò-Æ1ÀSiŽñþ@‚Ïb6µ:@¬)T …@`H÷}æe@’°ru!$5À ÕÍ Þ?à?T‰w×…†@<Éu¢°ƒ@»‘D„ ìSÀïì˜à?¢@dpEm£6@¶ÁÎ'ç‡À=a8B7„Àk¤B¢°”ÀdÆ·v‚9SÀŸ7Ø@o:@?;×9oÀ²—o@îg¬@ÀÖmÈ‹”˜VÀÍan’‘F™¿à?¨ü#ö´BÀòbp›ÞY@Àe«º¸/ˆ@»‘D„ ìSÀ9 ÉÙÄ–<ÀÒBÄlKC@ýj‘5³@@|¶áù2=@! ÿá2À,ÀY‡›@1Œ"IF@H§Ü’¹@8r®] f@ÊÓGä5À¤÷/Á|ï?ð?q¬EwIb˜@›÷ùzû{–@ïD/…cÀ#)ÀÏF³@{"/»”@Û•ëªú˜ÀEïç}—À „V =•ÀKý­ ÖdÀ ¦@)R@«ö)y€ÀêîŽZñ;€@<ù9›ÿtQÀoºÞO›5hÀ6ïù§¿ð?ÃüDì"TRÀRú蘘æPÀªzØ{™@ïD/…cÀ7µÐõ+OÀ¶˜õ"­ÆR@ª£w6PQ@¥e¦ï×íO@S\Æñ¼^BÀZ¡2t^n3@tP« Ô_@h4'Á` .@ZO_w\v@Þ‹Á‰5®FÀ $-©8ð?ð?môÎÖ^š@íØ×E­¢™@€UpÜú bÀýçtñ§ ´@¯Ãë˜@{3³ö›Àš_|±–XšÀMê‡všœ™À¼ÓpÝ‹fÀQ~UòW@O¬7íaÀø«ìF»°€@–wØÓ:FRÀlD·ŸèiÀ¼]Ð¥¿ð?ÓÙ¯ïÈÑQÀyº|†£RQÀÙÒ Øš@€UpÜú bÀUfU ×PÀ{´Ó;PR@ Èû+ÍQ@> KâˆNQ@ÌÖµM°BÀ7=š_‘¥8@œ[±\d@œÂ™4w/@ý̾ښv@ïäÕ®GÀ1àÐi„¶Ð?Ð?Ö¹¦µ||@ìÀ.}@ÂH‰9Eõ@ÀføÎMß•@¥„&%å}@¶ŠW¹`}À5—sKV~Àt¢}×nÔ~À•œZ3¯[HÀôQdt>@Fõo£·WbÀ´«>qÇ)a@h_$óf3ÀÓΈÅ°KÀíÁÇþ„¿Ð?ÒR4ħ)1Àœ‹]ì”1ÀlïêdhD|@ÂH‰9Eõ@ÀbƒdÏ2À Xq³1@:Ñ#¢¦!2@vÎ~7ù’2@x;Ÿ'#À¢KzIg:@̪û*ÀH@`ã˜Ђ@$wÖ’ÛV@#„Ö‘Ô_(À9gå8Ñ?Ð?4è×Oï¼~@zsà}•€@Ì€ZŠ?À”(Bo@–@µ•Tå@/´xŸ·ÐÀ w"H*À5œ¨…‚Àš@ôÄEJÀ¯ü@DeÝB@u€ZcÀxJ7Öl¦a@·$ø=óÿ3À¶pÃoMÀpÄ~81‚¿Ð?!É„31X0À™NÑ õ¢1À~"’›Á}@Ì€ZŠ?À¡‹ÉÞ3Àb˜åÕê0@œ;u1A2@éž/Y²3@±Eœbä`#À{:Æü"@µƒM@–“žl‚[@~=<†¤W@žê>7rI)Àâ ó2n½ñ?ð?ªµ¸Û% @-fÄ»gÑ¢@A <Ôò\ÀQeâàn·@ì¸6@a¥@8ʹ5¡ÀLôß—…£ÀOWLSú6¦ÀN¥ØËIlÀqÚDÿèf@øE „h„ÀÝcÒ»%‚@äár¤úæTÀÑØ<oÀ×ú¯pþP ¿ð?+@k³NÀ-1=ÿ³pQÀCQ±dPŸ@A <Ôò\À‰vˆÐSÀÜ­sÝRæO@Á°x R@jP‹Yœ–T@ó/'ÝÁCÀ`{d÷LE@Tù^B‹0q@¾7šû®F2@~ZäÄ dw@mf¢K?JÀU˜»ŒÜý·?ð?P¼¸ÿSï @X6Ó¢L°?q àó2A@ÚZê cP@ÀÐŽ«Ä|T?zbâ›úë À8cMG‡J°¿ÒÓô^zT¿ær¼ºzs@ÿv”ÎÑ%À¿iMºa4=À¿‹/N5§º?ð?ÎH£gRÑ @k[q²?*^R¢ù3R@²µ¾H 3A@Û’i÷¿ÃV?¿5¶™Í À  a²¿ ÒaÏÀV¿‡[€û%À¿UMfØÍxs@“âkO}8@À¨8îIÓ›?Ð?5Ü·Á’ðò?òLüæ‘ú?eªÂ%@AÓùbÈõ¿H.…ö¶G¿ŸòwK%Á¿KÔ®ÃÀ\ÖÀÕ À&†ã潓S@Kg¯0½0¤¿¬H¥’!À|ô?Ð?ÐFãÉó?Áìõæ‹RŸ?¿Ø5£A6@»¸Ø?Â%@™dÙ8ÊH?ÿj:TºÆó¿Íebu‹MŸ¿ÐÑŸØÆH¿*Û( ­Åê?‘çuŸ¯hù?ñ £g:@Ž´¯Rñ0¤¿ÏJk9õ‘S@¬SÝáGÇ!À‡+ôl_²Ÿ?Ð?/rMÏŸú?ñyÈNîþ©?ém‡,ß*@¿mʃ]ó:@è bY?6ìûì™ú¿A`êù©¿zÛ@ª]Y¿Eµ5“–eÕ¿ È6ÀÓ”ë3À»ß<Ä­S@â“æÏèM¨¿wèQT,}#ÀIc|Ç_Ÿ?Ð?<ö§|wú?~G·¨HØ©?!q LË:@€»ŽYß*@Ò{+ÕÒ“.?ÀðqáôMÀ¡§øaÒàs@3µ®%rпÜuþÍÓ’HÀÕE³\s~ã?Ĥí%J@µ(è8ýª\@ÞvWΣ?Ud .ò#ÀÏS|Ãwã¿aó€sG£¿Û÷ö'} À8ú„è†5Àœ7n> GÀ¾K—«d@øà6ÿº³~ ÍÞ=Àɵ¾KÄ´?à?ÛÂ|q!@&sT?á?¿Ýì Y@M+œ¥jJ@aC ?>$Çk!Àš'ƒB1á¿o`ÞÜÙ— ¿¤CŒ»C"@ YE:¤“7@°hÀü€fS@`Òóhÿ®zÖd@fõL(:À„çS˜çÒ¹?à?>?ÖºY)@S{€º_Tì? ›¢/›±N@À&Oº!À`@ž 6a«ý¯?Ò…–ÏÆ )Àp*¢ Iì¿ë·vñ¯¿i СDÀ8˜KÄ97ÀkÎ(JK>KÀÑ@„1d@C„\оçÿ4¢ÈCM@ÀåW@J¶?à?Vîæ o%@Ö»¾ 24è?º@_Fd¦\@âÐtpê±N@S˜µýT«?ƒÑ]êÞf%ÀÃVσõ*è¿ÿ~J«¿ö)€0%@tå,‘z <@,HÂ×°V@&¾âïñçÿÂ%ÊK0d@f˜OáÖ;À¨ ¦E®á»?à?bUakÿ/@6þä-#ô?~Y©¯×Q@úëlcc@ðX’£Ýº?bi{ù/Àz„ ½ô¿¦± Ðî º¿î,êp oÀÞ&Ôaî8Àôßü ºŠOÀo6WU‚Md@Xn0§!Ä¿ZqfíвAÀ§\·?à?¹³[à *@Í`èá àð?ÅKuUE`@Þ ŽQ@ÂÅ|N~Þµ?ƒR"ö*ÀIQ:ŽÙð¿ G½‘TÕµ¿·Gz^#¿'@$ß$A@[dzÊýY@ã¸z+Û!Ä¿hq‹ËHLd@w…(Šû¥=ÀÛ^Äß!ö­?Ð?e.`8#@ ê\|ì?`[ïC@-xJ*@V@ï%jñ!¹´?“Ç‹”ý"Àn¯»ì¿"ž˜¸¯´¿^¦ð€[CÀÈï"B†0*À‚ ŸÊ§ùAÀûÿgÆ4jT@Z€9K‘³¿%¬g„p 3À*ˆÚvÜ­¨?Ð?sä×'!Z@¾$t1Q#ç?8D^R@õÖÓGïC@:ëÏn±?Íh«äKÀ`QiÏç¿8W­ ±¿È&¨ÏÄ+@4Ùèä3@ýèã¦OM@À)ο}‘³¿†ÓBÞhT@ÐK €/ÀñšÆ3¶?ð?Cz¶Ñ8 @®BÝF;²?º?á¢ÊB@ú}P@8KÇ\¯¹X?ÚÐW¸$5 À7ƒ°)µþ±¿Èq 8¶X¿°©J‡0B@{Œ#uë@Á3,9E¯:À;ô;‚Us@ó>ûægà¿¿ø¨JØÓ:À!(-ö~2¾?ð?c Ö@æ‘]~¸?göÿû¶U@¢¸3ùB@(õÛmÑ`?DS‰ÓÀPà ¥îz¸¿KqìTÏ`¿vUó?üD * ?å…ÎÓPÏ&@ Y€¿FÊ4@ý)©(~K?ÛMV 󿨮A¾Þ' ¿² *yyK¿ŠV}/Iàñ?¨ám€õ–⿊j!÷‘$À4òLOnS@ª9»bB¤¿rco‘Àó=çEN ?Ð?¿o>Ì‘Ú÷?¨¨êålH¤?rدõC:@o1G¹‹Ï&@Ûê‘ ?Q?ÄmáÖ÷¿ b,÷÷D¤¿*òF0@éF7.@#,@¾UÎGÁ`?i_ùI5ÿ¿#Å­„²)°¿)(úß½`¿ê@-ª~ÿ¿Œ¸—@ @+ ­z="@Ïã58á9¨¿ðl ‚„S@›[õÔ'b%ÀĘՠÆÙÀ?ð?3ò¾Î&"@t[~tlÖ?XvÑnQ@ÔÁ¢ZÒ2`@~Mè¦"ä‹?'oHÛ"ÀWFö}gÖ¿»¢·‘}Ý‹¿¬¶wÎ…oÿ?‡¹YQ;T2À(œÖÉQÀù®[³ s@Và”FÌ¿ï/°Ox«DÀÌmL×ÁÂ?ð?“y=æ©$@ýq`Æœ÷Ø?Sñ•Èb@ÇÛn^;Q@v,÷•?Àôæ¦á $À £ªñØ¿‡?$‹ª¿,Q ˜µÓÀðy² @l5@åpzÒïN@!,@•\FÌ¿œ.iäs@Š*‹bGÀÜoW%ÎÂ?ð?**u/Ü'@ØQšgé˜á?U3vH¨AT@J#6êc@q™áàíô™?EAcv Õ'Àç7”Ὲ1éWË홿  ”~Ò?"M<9À299ï±®UÀvL7!_ºs@a… ¤aп½1iRÈ/GÀDãœÚÄ?ð?R£Y'c)@´øÐEB¹â?_™a€´ìd@W¦%–ÜAT@ÍýÃÇ@ž›?ùª§â,\)Àþç·´â¿ÉqU©–›¿*‹-4W=ÀÜðNùÂÔ=@þ(|ØU@^6ÿŠпÿ5ù)¤·s@]«æ«¨HÀyñGŽÇÄ?ð?ì“gÄ>í.@„w Áê?ÚÞ ÌW@êÂa‡g@%k %§?—Ž"”ã.ÀE;ë8¸¸ê¿/ŒÌ§¿èˆµ©åú¿«ïÍHEa?Àø×§¬YÀè}áÚlÔs@+.9%í¦Ñ¿§Ç…ÛNÁIÀBiUìdCÅ?ð?aþ‰çø§/@4!Sçbë?´ÐA–kh@oP¨QÞÌW@¹º*Áۧ?r¸ÂØž/ÀëÛ‹˜Zë¿«Û^©§¿ÀeqÿBÌ¿GKòLoC@NMO¯“@\@¯L^¹§Ñ¿‹ÍÊÑs@r¬/ePYJÀ×­,ãƦ?Ð?ɱ’ph°@Sä¦}ÉÓ?}Þ?½RЦUªê¿JCyv=”¿>_´à¹>¿È(jë;Ð@Þsã÷Á @Y®:¶Gv*Àg»» 1S@ÑÔò¬•ž¿éÄÅÀÉ´M |Ø ?Ð?qþ»àÍÿõ?·¸D"IJ ?  US·9@êÜbDâ…"@Ï rpYI? í6lüõ¿äR€3° ¿¦”ôŠUI¿¢·÷ú·ŠÀ½x3«i¿>®"×À­"¤e•ž¿9˜Å~:-S@£`åº2$ÀûàÍÅ1¸?ð?°“χÕ7@K­§?¯¿Á?nã:ƒG@ ¿”T@ˆÏ7Kdp?î™Ã`N4À±“¶%m¼Á¿‰x3ãHap¿XŸÏÆL‡#@\{£@â0t/ÚPÀÍH¥Is@ãÕi°yÿî$ÕÅ´(=À»\N Â?ð?ð7Ö¯p¯@>oy÷ý}Ê?œÒ ¾É?^@bœ°3PG@¸êØHxwx?åW²Ÿ,ªÀÄ{†ø yÊ¿ªJÊyúrx¿À9  …9À4GÆ™M@ ¼i”ŽÀ{Ê0³âyÿÿËgŠ—Es@³ÒÁšÀEÀç¥wHý›?Ð?øcÔÏ€¶ú?Ëóô•¤­?Jb¥T¸-@Îõ\{©Î9@ ñ)Cìq`?m+r¼°ú¿i£ìc±­¿‰ƒ€a_n`¿öëϰ׳@з):0‡ñ¿ +aÄ‘4ÀQg =bS@m\.s‚©§¿¼~„ó ÀŠ”÷9lE£?Ð?þ&ûÉ­e@C¥°Äëi´?46ˆ¶Ã¡A@“bL -@Ÿ¢û¿¦f?ZÙµaÀ·Ùe´¿ÔÙ­Ü¡f¿è—:7ÍÀ¸­x·Q” @vɈn…Ï@¦Ö Œ¿©§¿”ÓC^S@AÏrÙ‹V'ÀÉöKÒ¿?ð?xR*âM "@ K6_$Å×?s‚?‰xQ@³§¦zŠÂ_@€’ãÄšS?ž;üwÊ"ÀKøÎ¦1¿×¿)FúÃK¿>$Y"£@œ»9òr(À†¡”§C_XÀÑ]Êa@{s@/'Éqj³Ë¿Â–ðl¹^CÀÌ éMç€Ä?ð?qÆÉÌ?'@Kª¸ß£Þ?Ø^ ,cd@õ]iã¥Q@@X ¬·0”?´÷Poû9'À¹¬_°4œÞ¿þ#Fª+”¿jØòTþš4À ®õ»cØ5@»%åÚ{fG@:œAø±³Ë¿ú ÏçEws@!ÖTJÒôHÀvç­—€ØÁ?ð? â¿ ”Ç'@ÆÙÅkâ?ì¼QçT@ŸSDîý:c@VÙ¥ªˆœ?¥*NjÆÀ'ÀdöQ¾Íe⿹ÃêÜœ¿ˆ=ù… ¸@Ã]ÎEnX3À8ªÐÖ¶E\À5|‹_–”s@fH9GijÏ¿Ò þ^ÖEÀöݺ¤Ñ¿Å?ð?=‡v^ý,@}Tø%tæ? Dsûfg@ÅžJQçT@Áïä’+d¡?2iú#õ,ÀÎ&¹mæ¿Ã€BÄ1_¡¿\Bæbˆ2À n$C}‚>@i-…¾¨ùQ@† 9eºjÏ¿»‘ÀK§s@EüüX»›JÀصé‡Î̳?à?Jÿz¹@D‡*¶Û?{ /–ŠH@ßVf÷V@å^Tcþ˜?]½ “¯À<µH+­Û¿Í¨ƒQö˜¿øºè¹N:ó?­I5¾¸)Àû†"PÀײa{K®c@©ÍaüSMÁ¿ù,}‚åZ8À2#?·?à?<¸·qÛ!@”vý+à? †i׋¬Z@†AÕŠH@66 ?~V.½Õ!À ~Xøà¿@5>;¿<ȪIÌ• Àe¼˜æ3@Yy°-GH@Å-©€MÁ¿/î~Tqªc@–"ÆÞK<À¡«8,Æ¥?Ð?kzœB‚@µÑÄ„kQÔ?!ÜêP}<@yÌ~·K@Î5a5,)•?Jו<{À+º…èJÔ¿¥êOì!•¿‰–—Äæ¦¿toÃ?TÀI¾&õ.BÀ£s nÈS@4õ„„²¿³æUÌì*À}Âc/EH¨?Ð?íÛêbÃ@’3V1|ªÖ?U—¿«8N@äóâyš}<@#â²t+›—?hé»À©þ/S¢Ö¿ °Ì«’—¿®1ÓfíŠ ÀfãÚñ¸Þ(@ü?M Ú›>@¨‰a賄²¿ÆRƒ×®ÄS@0¯ß¤Û.Àü¢ÎºÄ·?à?/ë5Ÿ!h(@ÈW¬ý•!í?Ò˜9-å`P@'3@p¤_@³Ñá“b±?yb5{s^(À|J´'í¿$,°®[±¿P-›džø¿§w¥B2ÀÕɺ€HTÀE’¶Kãc@Îï([9ÿ@EtAÅá{R@QW-ÌŒ9ÿ£Uxëkßc@.tFÝâÇ?À‰/e2™ÈÉ?ð?r’OQ#>@~*|ýx@Ûh{±L­b@çÏH"¸Mr@â»R`ÐË?›ÚúL>À<âÎ &pÀö¶:]ÄË¿è6Ç…~5À“À³hDÀ´ÍM…ofÀg/)³>þs@Œ2°g_FÓ¿Í3Íî„PÀ>•¡·{ßÊ?ð?¿WÀç;l?@•¡W?lX@ßc$ds@ÎAë|­b@¥3îÿÌ?]ç¢Ò©^?À'9kP4OÀ#ßhóÌ¿(CÄkß 'À÷sÙ&õèQ@½w #­e@‰Š,‘FÓ¿8ïœûµús@¸ù"Ý—ÊPÀJ¥¯ïÑ»?à?3+ˆCþd2@¢ßØ“ƒEü?¦Â}ý6%U@"[Æïe@1‹Ù‚Þ¹Å?žaãzq\2À1#‹ƒ_8ü¿{É}Můſ8=·ºÀÇ ¼Ñ¤5À¼Ñ˜2g¤XÀ÷2(Þd@jÛ_Ô¿ߤØB]|AÀ )#â0¼?à?chKš¥2@AöBßШü?m» µJe@ºo¾–m%U@5Œ„6.Æ?¤àÍzïœ2À½xç¦~›ü¿ô¤ÈˆñûÅ¿n#Xm¯]À«·ÊWéD@ÈPÖ2ÚâX@J³û(‚¿ÔðÚ›d@.MP§¶AÀ:Å2W%±²?ð?(<>, @ü\¿ªö¶?'–ø"­B@ ¯'ÁSP@~>(u#hc?•/Gw' À0‚cÆò¶¿@wøkÙdc¿s’š"lÃ0@ŸßMǨò3@£¶Q%Ä®SÀ¶,Pë" s@ÈV¤~¼¿ßÚin=@6ÀùE= |‘Â?ð?SE"õÿ@”˜8ËbÑÆ?*a;º/^@a®Æ1S­B@ÓÀ¼¡Hs?ÔЉ¥aûÀ‚ÃñÀ„ÍÆ¿eZš ]Es¿¿þo¤ÿDÀa÷$°Dñ¿Š‰˜ìäÑDÀ/X 6Y~¼¿Mø¼_s@1VC•mFÀˆ—ºÿi¶?ð?NY¶M{@A—)ú÷¯Ã?…n¨æÚG@Ps–ª©T@o„Ñœ0ås?œL.×mwÀTu¦¡ ¬Ã¿%¼¥®;ás¿-k»C¬.@ £èž=#%@4 ŸÆÃ?ð?h€û³21!@-艬_Ñ?Yuza@Ÿ§Ò@$ÛG@a,u¤Ž?¹EeÇ-!Àgöü7\Ñ¿ íJ&‹¿(¹1WÄDÀƒQé/WB@Îú¿á@1Àss>Žgw¿6,b^ s@¡Ê‹½¦GÀ ‹x[,ª?à?å<ï ëó @ ­‰§"À?0²T ”=@Œ¯»°I@ž‚˜§Qs?¢æ´í ÀúåæïÀ¿ò–k33Ms¿D['ïF@žéPMû¡í?¡b¤KÀ“¦3²½=c@uAOK´§¶¿LðÿÁUw/À\…7ÐHþ´?à?øbï_= @“ÁúÈ‘äÉ?i˜Â®…T@½Ë2´Y”=@ê?¡ôk?ß`·Ì@›Àº¡¼U™ÞÉ¿{ ïEù~¿šÛ|ß13ÀÖwÊß§@¬ÓhÊò @ur€Êî§¶¿Ôei®8c@7Oh <9Àg›É¼_÷½?ð?‚Õk‡Õ"@H ÿè&zÙ?]1¹kîQ@`nNÉ8n_@ÿqà é‘?ü "À¹<ÞksÙ¿ßT–Nä‘¿ÅäVNüO'@tùVA¯¹À4çáyØ^ÀFá«cpVs@"”„Ž¡©Ê¿ [•~åBÀa‚«9Æ?ð?‘5-ã*@æ”/{Çæâ?AWàÕíùf@äðšîQ@£¹/ÒE“š?‡¦zÇýÛ*À®`(Éáâ¿'5ý‚@Œš¿ÆW‹7BÀª±CãÀ6@Ž“ýÔ?@\J·fæ©Ê¿.«úÉUQs@!rä¢ÙJÀq¤×â æ ?Ð?!“¯ íÌ@ÇÁQ@æ{Ã?e¦‰©Ö\5@®ÖÊóB@­ö’Úæ?ld²2ÎÅÀBP0þvÿˆ«ŸÝ¿—€1†Å@¬­c Û À0e<Ž-`AÀre„ÈsoS@ éç*äO®¿8E”ýA†$ÀV5Œéwx§?Ð?8>ù;€ˆ@§î3ÅË?1Æü1 J@^jÒ ]5@kkÈø(†?ÅL ùƒÀÙ–ãû« Ë¿›¹J‘W"†¿ÌÚ¢tj!À2Ÿ[Ûþ@;±Ã D,@Ïko2P®¿Y¬¿J^jS@+h"Ì,À·8ß!oÕÂ?ð?5ÈMù½¦.@EæKoþì?ÂøŠgY@ZB=‘f@¥ÇZQm«?äÙ'myœ.À Ïâ¸ô쿞·[âc«¿Œ ú D@–*÷ó4À(@K˜s`cÀŠ@ÊÓˆs@uÂÿ[³Ð¿Àÿø-þFÀñ‘±lúÈ?ð?(·/C!4@„ëlš ó?¢Ký9¡~m@¥L”1ÑY@À‘÷&²?2&ê„4ÀFŸ€9ó¿œdE‡úü±¿¶±K›®@Àr*yáêCD@ºÐÞ†UT@:©: †³Ð¿uw\уs@5+íÒà.NÀpº¶ÉÄ?ð?Êt%ah3@¨–›”Âõ?R‚÷ ]@ÿ´Ÿãa’j@"¯'8Û¶?eýÜ.a3À‡ÎR€òõ¿+ ‘½Ò¶¿Ñ“6Aµ‚@¯687sõ9À×<’bmeÀ›àž¢s@[õŒžÙÑ¿x>óÅ$ƒIÀš"K£Ê?ð?)ÿÐH8@?iˆª”Zú?/‡×@”p@_¸B!]@G ¥}™¼?u¯lÎ?8ÀëêÄÎPú¿Füæºá޼¿$–+Œ´@À_Å÷ÎZI@FÑ bÐZ@ÛD•&ÌÙÑ¿@ïò¹s@Qð˜©CçOÀ‘yrOæ?Ð?˜¨JÅ8@t¼>•õÝ?ýûFŠÀ½@@é#(úCúN@Ï")‡¢?qò­Ìí.À² BòhéÝ¿mêaå¡¢¿ JŠÅÇ?ÆÆU*,À”•F£R‡GÀÑïFEâ¼S@ó=Ãy²¿Yîq±,À™³¾3/J«?Ð?Wý½lâ @)îùG@÷á?hXMÄ€ŒR@´"ZÄë½@@—Ëų8¦?…­À`/f„óïá¿ÜÍX¬/¦¿üü^ÛÀ+o1³Æ.@ØÚÌyh@@{2ÆÑ¾y²¿eÞr<$¸S@å9°Õ±Ô0ÀB¸èW¯Á¸?à?çPÔQïØ-@¥­Ë–éô?ÒˆpÞÜS@¾uŸæa@7PÙ„ðM½?ÇbSsËË-À¿$…éaàô¿—ßm× A½¿(P{½ÅAö¿E•žÝئ1À‹ŒñI¡®YÀ£¹ç±×c@´ÛËn¿Uf çp¶>ÀØ—¼?à?äMþ=1@ŒƒK)ø?ÐNrIæ©d@ rt#S@]€;!³íÀ?¤UöEg61ÀQaÿ§ø¿åRŒ??æÀ¿¦´b°“Ó-ÀñŽí+EB@ÌL€ŒS@¼0b@n¿]ä)´Óc@c¯åÞºAÀzƒ¢w¦Åª?Ð?&†Û8/"@åawtñµì?Ÿð2N#—E@ÒV2…T@fE6ÄDª¶?còå£&"À}Uõìe¨ì¿O"´d“Ÿ¶¿ˆÍ¶¤–ú¿¾ÀËŠ_#ÀB%²ãKÀÿÞµ óS@Sò8‘䱿Š!è$ ³0ÀŒ µè­?Ð?o©Çš½R$@{ÐJŸ3 ð? àcÆ_íV@²ª› [—E@ø‹¬ ³T¹? 'I$ÀGñ¡ð¿tl¹Ì¿H¹¿É¤ÕôÀU>ÂUT5@kƒXÀ ´F@X¹ºäޱ¿¡m34µîS@X\Ho¦2Àˆ‡¬ÐLø ?à?TÙaû?ÕLª?y a~g‚2@ȆBs½Ý@@HJë”X?Üý„‚8‹û¿çm`lª¿ »pÚX¿»¼¦xYß&@íö@1p*@øI°ÛwJÀ«uߨéb@üŠÝÙ°±©¿ áctå $À©²÷)jD´?à?fJ­w@Zi².¿?VQU‚˜Q@çÄ:I—‚2@wöT]m?X?-btÀûÂeˆ½¿¿%ÿçyœWm¿Þý0AZp<ÀœN»ŽñÙë¿èv;J®;ÀïÕÝ1󱩿Sab#äb@qA8Yðñ7ÀÃ\©»¨”?Ð?êd•Á¼ó? Ãë¥?¯î3à'@Ì_îŒ5@´B¸uYX?1]η󿞉Sg祿 ûú¼2TX¿‰îB,@ÇJ¾›Ÿç@o§è¿àª=À±3»S@kUG¡¿<#Dä‡À’ÖŸy¥?Ð?úÞü}…@ž3d³ƒË¶?¾L©³RD@!¾pà'@É54Ri?cDÀ¤õµ–ƶ¿£`ôƒ‡Li¿_¯C“s¬+ÀFó¸Ï"—ö?noú¯YÀæ%`H¡¿Œ™±ÜÉûR@<õŒ} ~)Àïàbý¸`¨?à?Ìf-T:9 @„ʼŽ"¬Á?•÷ép}È=@ž‘þUÜI@BDhÃñv?^QO€2 ÀÖé̱ħÁ¿\kôìv¿7u«ß2#@œ=qŒ  @=†ý{²PÀ^OÛc@©C¤Ø‹?µ¿éH(-ÀðÆY° ±¶?à?En£B>Y@º{¤|ŒtÐ?8ç,¨YÌV@a”ÐWÊÈ=@ý¬;º9]…?^àO×úRÀgÝ{pпùìÙWòW…¿ùu˜Ú±ø:ÀÆG5Ú5@…BKŽ÷ À>âµÂ?µ¿?©€PÂc@…|gA;ÀS„øDž"œ?Ð?ŠÆ*ßö=@FáÖ>€»?~vdÀ»2@-Šie?@àKUt?–UÜ8À ²]3]x»¿<ƒ·ýµ´t¿Šfïæ ñ@`}b5{©¿Fnðº$›BÀ¿q®Â?2S@;²Q 4©¿Z4Ú­ß À¹ÉöˆNì§?Ð?†õôA@mìç.dÇ? àˆÉI@ÖùwŒê2@HöjŽ¡?4Åã’ÿÀØDû…ƒ]Ç¿kY”_Ÿœ¿Š`±¹U*ÀŽ”No&@øH´E÷@eè!X4©¿üC.›,S@":¨ª°,À¦ô»ŽàíŸ?Ð?äÍ.Äêá@#ç+ÄÄ?¯7@¢¼¤5@4 ‚ŒÓB@µÑ„‚?p>* lÚÀ¨Ž?ˆ§½Ä¿“¹iÙ‚¿-vzÉ @[pÐÏþèþ¿ßVN¹DÀÌÐ;vóJS@c”ð‘•Ĭ¿eõÈ?#À®8¶·ù*©?Ð?»Š•ÉÞÔ@ÒK8€×_Ð?QÌM@˜òÅ„ô¤5@Áºž=ÇyŒ?KZÛõÎÀñ Uú³ZпƦŠ~×pŒ¿TÝÚ5Ä)À$×gƒ»K@¨&êWì¢$@ ~¿ÙßĬ¿Ÿ¼™ÉDS@@š)LxU.ÀPÏSOYá±?à?<·V`ª@&B(qÌÞ?ûÁr®uI@ñ³®v9SV@ªa—c“wž?«HË”jŸÀ“o3w%†Þ¿¯2ò3õlž¿„¯Šñ@쎼üËÀ¸uUPˆVÀœM´‘dc@ñÜa½¿¿ñãV‹Ñª5Àjÿ<\mº?à?@g>c«&@yDݦc˜æ?ìé¶V‘D`@)Ë kÃuI@‡æ*Z¾…¦?¸“Óû1£&À~£Wăæ¿^J)÷ä}¦¿àìÚD9ÀRĺ›Cˆ4@Sóa{k@@Á[ ³½¿¿d:ë]c@ñ†lùÚ@ÀÁ2È¥г?à?S¤«]#@øIò–þå?ûÇe``”M@mk¦ó©4Z@Yf«û¨?§ÙÜœU#ÀûÕ(ö忺ÏöDò¨¿€óZêÃ@[²L÷ˆ $À˜ZiåXÀA25-w}c@L¸ÌøñÀ¿ðGÂ>#8Àä/XÕ²»?à?>³î¾+@ Mw Áî?dãµÍÎ'b@cò¼À¬”M@/½Í·¾w±?/%¨^ +À k³B×µî¿P¯— q±¿S}ífØ8Àbi!V°¼9@,EKOê‹F@˳³×#òÀ¿¿0Œ„wc@ôê ›Ý@À(>˜óĵ?à?1[•Z¬(@þ˜rfï?×Vý âQ@g±_Ôz^@;ÍöûËø³?Á|(À¡8,ûî¿`˜þvð³¿$¦Ç–›@ÄÜu’†ó)ÀS¼Îù(¸ZÀšè./c—c@°Á–‚9{Á¿SOL.ë¨:À=߃3ü¼?à? \iÊ?0@W3Ÿd¬ªô?m2fÞ°.d@¾û Q@;Û«šº?°*Þ 0ÀðÜ2 ¢ô¿è&–º¿Fr¥8ÀšŠ‘ºE?@AºÉϲL@·ä¥f{Á¿¬D'Ô¡‘c@a+éw4¾AÀ#IÞ„c¾§?Ð?ÄØÌ)Õ¤@++ê‚å?X•þìcC@s e”Q@wD¸ ¶5¯?0rª—ÀºñNZxå¿wcš»­'¯¿@·aƒè¿£ð €!ÀCn×àOÀazAµãÌS@‰S5нX°¿Kà]{Þ/ÀbX õRš¯?Ð?¿™áÄz$&@'o²ò?W/·Ôß«X@ѪuWïE@œ˜¾AhW½?É{YÜ&ÀFu÷^ýñ¿pÝ\VI½¿ßB½#¤ (ÀcøÊ>e°5@RGQà"ŠD@ëóv¿çX°¿Üš2ÀŸÇS@C»öŽ3À‘pÁÌωŽ?Ð?3fÕ<“¼ë?.ö¤Á—J?æ²V¡"@o±Aœ§ª1@tÉëîN?—~7×¶ë¿[r‰D¿}|“†èN¿iíó8@¦[ €ñl @wc~'ÿ"@ÀàÄ9$ÇR@£i°ÕG–¿—h.¨8êÀSømpñ¥?Ð?–àûhð@üQ%yµ?€Sã|:D@ɤçÏ"@+VA¢ÏŠÄ1À®\çÃ/Qô?ö}`J®&Àí ˆJ/¹ž¿Ä€EÇÚ×R@Šo ÜÑH+À†Eú¢>›¶?ð?Ž…AþMu@(1~ cÓ?ÆQib©M@îuž™NZ@? b`‹?(L%@nÀÊW|#í]Ó¿õ.ÜY‹¿Ù›ç939@Æuþê<,@QŸgÓcÀ`/½’ör@ÛúT‹<}ÿI_ïíÈ:ÀÝ ”Ù]È?ð?˜§Öò\›-@+öoçä?a[øÎÝ´i@ùå¥ÿ®©M@4‘åÍ„?›2]ƒ“-À}:2åáä¿t™Kú|¿³AIÿ2‡QÀí«¯þ‰*@eO¨'¥ 5ÀD»ØÝn}ÿïwïr@[Ôƒ¸ÜLÀºhÑiÞSª?à?i çש]@X=­–ÎÉÍ?Æ Áõ#&B@¸†™¥O@t2K(ˆ?ÑÉ5XÀVjFöÀÍ¿-r)Ð!ˆ¿j€&@ì't`ä@®cs½¼UÀ`u¨8«c@О† _·¿ß¿Y/À¤4Þý˜¹?à?SÜSCöÜ!@IdB§ùÜ?øÖ$™Ï\@‡«_ÒR&B@¨FÅÇ—?)Ll¨×!À°=.RuðÜ¿›ËÁx—¿<Ú¬RAÀD)Ã9 &@Öv¥±šñ?lsDùV_·¿áÐ;ƒc@Ö•=µÉx>ÀÔփ粮?à?Ñò©Òý@¯÷?)<Ö?²¶G—ÀE@8BgºØR@x8ö¾œ”?@ú7lõÀ%Ç…ãÓ4Ö¿_ŽœN•”¿ƒ“xÁ¯#@î³ûrýï¿ ©iôä±WÀ:º@ã'c@ƒ@¯\ãÔº¿„±„Î¥2ÀÙZ>ւ׺?à?ÊÃVi%@äñÐBwØã?Yö$[š`@(1(rÏÀE@S’Ϋe¢?Çð˜b%ÀñÚ4¦ëÑã¿LÁ∠_¢¿>´•ÕQ'AÀå/aÅäj/@š¿Ša*@V5“¤(Õº¿‰n•Åéc@:’³ª@À¤üÕôvð°?à? Á夈¹@uè5wê1à?¶vµC¦I@×_lIÅ;V@fbÿ¡?¨Š¡_®ÀAÊ$‰,à¿äërj ¡¿ãõËçw‘ @ÑFëB ÀZõG,³YÀÒÔ0Ñ?c@èüÌ䫽¿ibÁ|`4À=žŒ2¼?à?„UL~)@ '³Ñàê?Á"’¸Ôäa@”3=…¦I@·ÎZ:åT¬?}È·‰ u)ÀÇ“&Ç?Öê¿3>¾šJ¬¿ºRxK€AÀ§Œa,•´4@Lø?ƒÅ9@«Ûj«½¿Üi[¿8c@†AùšZå@Àžôš´âÚ¢?Ð?P‚úoéZ@+w­O ×? µsÙ=@S!$OµþI@¨øŒBŽ›?öÂc¦Œ?Ó¦À1À0& :ÊÄ?ð?óhã? 8@®S@y)@J†ÁE.a@ˆžÉËl$n@ï.쀹Å?ê~î8À_YÁ"Àý;㽯ſòÈÍßÄ"@á’ãÂæ4ÀJ¡(JoÛmÀ"zÿ“Œrs@M᜿•Dпo@óEIÀ)aÒ5¨Î?ð?S­d;¼A@ÿ‹ŠíÖ@îþ›¯ëu@ "r.a@+µû‡ØÐ?ÛÊù•‚´AÀ«Êx³ÌÀ#!’ËñýÏ¿ø¤=½àPÀXoªLeªO@ÆN½*X@Ö›ÓÀ¿Dп¿ 'Õäks@&£SÁÇ RÀ쓹󜾦?Ð?*ƒà.@]âkÞÓ=æ?¸ëv„™C@?œp²ôWQ@’`X;İ?ˆç\ŠsÀò’4š3æ¿vï•…¼°¿ ©òc1õ?nén×Ò³ÀŠT—ÑPÀI„_§ŒS@ gް¿n: j©Ì+À¹ÿK"õ¯?Ð?°äT%¼$@W9rCï?c›ew%X@%z®4™C@îñàG[‘·?°Ñwö²$À_4˜¿!5ï¿9FâU…†·¿óѤLÝ0ÀžHþü0Ó2@6#Ð×~°>@È´s·°¿²™¥N†S@Bµþ§ü…3À(Âc.¸¸?à?’°yÃvè1@´l#³ð'þ?å?¿)5.V@Ch‡œ"Òc@$dø‰ðcÉ?Ö¡´¹ß1Àvb£9þ¿¡nËŒWÉ¿À ÒDÁÛ?^ƒÆ¬*¶-À¤îm1aÀ?(j”W§c@Æ{æ ѽ¿eÿ,6‰a>ÀGÆõ¢À?à?«wxÀy8@]ã%ÑÝM@Q#Ðý„j@²?:on.V@ioÑ?².¤Oµ8Àß°€põCÀíBÉÜÑ¿¿\µÌå@Àn[ÂÁþE@Ø eR@ü^tãVѽ¿tBB[¡c@",pŒpDÀÆiɤ-‹?Ð?ÊÅ5”ë?7>Ï'&E ?uÊô5ÊB!@ïƒÕ:ð·2@mÜýn2S?É63îë¿x|æÅqA ¿Ùƒÿ.S¿OËF̹æ!@•-ÅÙ˜#@QP kˆ5CÀl{3…¥R@¯¼½fY’¿ÁÖ–l©ÀTª„›¶˜§?Ð? é¿[ô@[$t.ÆC¼?Ë©TJG@¿ïŠÇöB!@®äbø¸¬p?|…†ïÀªOE¢V=¼¿–1í¨p¿6¯üÓõ5ÀEµÿ¶àë¿%‚tïC¤4ÀÝ‘¶–Y’¿}ú“­ŽR@m’žvz+À”qÔkÅ4‘?Ð?e8ÆÓÄõó?øM§/Ïëª?‚Ç)ëú&@¯ÍI¿Š6@M0q«'b?Œ<­ðó¿í䮬ð䪿¨ @‹ #b¿Á¤Ë @VúpÓb\@üIîEÀÊH|S¼R@œ²¹š¿cš$ÄI$ÀeûO/ͨ?Ð?¨ö³=‡È @@ß\N(iÃ?Xq×ÃØI@‰2ã>?ú&@Iq^Ñ(.z?Q- /Á ÀtÇ®`4dÿ^A~²z'z¿Jæ`Ë5À8÷Ó*éuñ?˜"îlø¤-À"«Ì÷¹š¿ìî ’´R@j› Ü-ÀdŠÔ•nÛ´?ð?±B¤S˜@, G 9Õ?NçÖVë9M@!çà‡Ì[@~gFqR?Ö«XzÀ´ºoÁÿ2Õ¿¸w¤ÌM¿NéÍ6ø?@¼ÍÖ×@'4@ƒÓ !vçfÀ¸`çàÓr@óù&A›mÁ¿øÈ©®‰8À‰J×>âÊ?ð?.¢ •%81@5¤p|ê?™u×ÏÑl@°-Í6:M@F bT´^¤?R¿,›?31À¿mâËçtê¿ñéèX¤¿â×$ä©UÀqtÍE)@(èØ¸öAÀ‘5KAÈmÁ¿€êîòêËr@´‚ägÿ˜NÀŒ27øŠ¸?ð?¿út–u"@6gMÙà#à?Çö6”IR@»)sZÁ`@üZ’…9œ?ÛüñÄo"ÀñÿzzÊà¿#ÁG 0œ¿ªý*©WS<@ufR‡[+'@@ÆKiÑhÀ¬H̯ër@šaØ«7Å¿Îiö?Ì=À%Þà?Ë?ð?]+ ߀4@ÈBP kíñ?=¢‰Õíp@÷u×xR@ƒ~O'¢Y¯?¾ ¢hz4ÀUÃütÄçñ¿W&xÀO¯¿Øù‚–ö‘UÀÒb‚t8Æ5@±ÄIl¦î(À3%J¡â7Å¿?‘ãr@±Ðú PÀ÷òSC¬?à?ËãFt@Ù†ÐÛ×?îæÌ»²E@nÉ´ßS@Ë%½L¡—?gÖ“« Àà}èrÓÒ׿‚ l™—¿i/cµ&A)@2• Zßfý?›q^ÇZÀi~ÞËc@oÅ'‡ò¸¿3#ê+ŠÊ0Àv§o >~¼?à?# ¥†ûI(@%ÖŠÊ!è?©„JÁa@)ÔÀQ²E@ᨥÖÔ§?j!岎A(À¬ ¢`Éè¿i  t’̧¿¹zñ£ƒEÀ)O>b^/@Vý07(@ŸeÛí1ޏ¿jðg¿ûb@ýæTúë@Àç^”²°?à?l6ˆ.ÀË@e&Úµ6á?Ä*"¦•«I@´µÎÑ^IV@Ðz_\>£?5 ÷ïÀÀà»<00á¿–Âr7£¿æ üË á%@À7”¸†nü¿füdýÃÈ\ÀPJû³>c@‹BÝX0=»¿ñw÷ß3Àõ-7À½?à?O5͸©Ÿ,@|ìÂÿï?Õp÷žc@-^î׫I@x–e×ßâ±?»€/Ñ”,À!¸>¢óï¿ãáVÚܱ¿_eYÑNEÀ°µ‡ÆÉ4@Š‡Ù¸÷ÀQ,”=œÞ࿾éxjH¿§¿¤ÔZ\Z @&Y¹âÄÀ)tù»ÆxPÀý ClZNS@D±¸­¿«º‡pì'ÀÀòº61'°?Ð?Åø=üp’#@g9N`+ë?ÖÁ_‹VÂW@ùç¢DA@º7z^Zd³?ä’,͉#À\1£™ë¿á¸*¿Ê[³¿’ Å G–5À7Æí¹õ/@Ï"§kÏ4@Ãy`Ûý¸­¿û+míFS@Dvˆ±·|3À²•P Cµ?à?A•À~Lh-@Æûk®÷?_´¾ ·S@ƒ„¤ÓÝ/a@pÕÄïÈ#Â? ßBÁvZ-À‹™ÁÐ ÷¿«c<@¿ˆ§#7a§@f“´±™ï$Àd—Ź®ŒaÀÎÆ.h hc@ܪó‰ü¼¿ (“c¼f:Àå@ÍÀ?à?´ìîP*¸6@ãòVû×@×iž_* j@‘¸Ü ÷S@eÓëTÌ?¯òœz­6À•®M–ÏÀŒåž<%úË¿\­sþ{²EÀõ‡óC@¶–žŽ‰J@¥:áÓü¼¿¬¾‘Ôac@h¤„!paDÀ[gÊ̶§?Ð?Í®ùè{Ñ!@ý×a³ï?mRãOdUF@Cµ½n˜S@.ñ»Eû,»?®g±¢È!ÀÇÐþ=ï¿Á!Yt{»¿ „T)‘†ô?`1—ì6À9ö ÑQ§RÀØ¿Ew‚S@ÿ$ûÏÛ‡ª¿d§¦ƒÛî,Àb"šÔu±?Ð?[à߆ @*@΋€Ôfìö?ãŠ'“w\@ö\‹úUF@ºíÂE Ä?“@]3*Àûø Ááö¿Úl!©®úÿÈLìOÚ5Àlÿ~>6@Ò¶ÀD@@ªúP ˆª¿‚•õˆç{S@ÄÁ(q€K5ÀE„/ÝÑÛ§?ð?dEÈåý @3­Õ¨×¿Á?òØ)\¶3@@C¸_(T@í1¿€®Xw?dNKÚFö À Ÿ~h»Á¿Ñ]aÙRw¿œ³”ÚME@uä Ö€¹F@h#“±;fÀº¯Æqƒr@Ÿ¤‡ñÿ«¿2¥ïOÀ™+À4ªFœe:É?ð?ò™îH©,@>(ÆÿTÇâ?müÅ4Þ0j@p¦Ï1à3@@J¸/WB³˜?:âN&‡†,ÀDW ¤Ââ¿—Õ¢­˜¿@à°D=÷YÀ/²-7;ÀXÄÄ“XÀnv¶Ó9¬¿¸èQŠ7{r@ݰ¸+MÀyxôEz?Ð?- |ØÑó?ë^ÜS8q­?ádâЉ&@“ ÍÇo­7@P3#iIÞe?»:¬]Ìó¿@Q’ri­¿xš­š=Øe¿S‹ÑC$@Ñc{0Ô½!@³ê¦QÖHÀ‚ÖØP|šR@ô1]¼D–¿ª­¬†"À¾Ðؽnª?Ð?%Í=Oìä@ØíÍ8±É?/ò‹ M@ ÅÔÂ&@¬jNô£‚?”@àÀe´•îÀÉ¿‹öÌž‚¿Tå^\˜è9À•ë»Ûì?Ëi‹H2ÀÅÓžõD–¿E"kð‘R@Þ*›ÁE¶.Àg ä#!“?Ð?„™×l­“û?3¬‹Ùù·?eÁg},@°«2jWü;@‹¹—B]s?M»›E‹û¿?©6£î·¿?‰H-¨Ws¿ñh”4§µ"@.¨ ¢e@äËRÒïIÀ$M G±R@Üù÷ŽÐ;ž¿Ý÷‚ñ%XÀÑ4Þ‰L¦«?Ð?pú‹‡jð@šï+ñyµÐ?M‡›…P@ ±—h},@\,mŒ?‡¯VêÀ_&b°Ð¿ÜõÊHyø‹¿—ÕU@ã9ÀªQBÖ¬G@~ó®í;)ÀŸ¥Ÿ<ž¿Jþ¾î©R@ÕCuO$0ÀNb™IÄǶ?ð?HuT7~"@ý„^Áxsá?±c[ô¼¸Q@þ•§ÐOz`@×àûìw ?W…Ø=Øw"ÀÑ›é¢má¿ì=)Õjr ¿³3òã33A@ë…— c1@ÎB~€…ÙkÀÚáÊÆJÉr@Õ„x?AË¿­¤ä³Š½:À—FºJ#áÌ?ð?·-!>;t7@º%ñ|'"ö?ª}S`»q@%7~¶ê¸Q@³¶êîã´?â'ìˆcl7À sÂÓÀö¿ë?ô Ü´¿Æ—#‘çYÀ¼è‘Y5@d) ž@ ;Àz mÆqË¿\°ÛgqÀr@S Û²†ñPÀ niMwš?Ð?†¥„_#@k’öDÖÉ?Û Å|áz5@¹U@7šMC@mV® Ñ ‹?0¾ ³CÀ1]GnÉ¿§¬"ì‹¿è`@§ã Ø—@h€­3¤ÏMÀ Å-~áR@ÓOCký¥¿6´õå9Àœ½Æ#U®?Ð?Ì+þ ã{@Õ*­n#Ý?yÐ-ã…S@xœ7ó{5@}`ÒeÑãž?È2ÝÜqÀ[µHã~Ý¿Ôб3Øž¿f˜2ìëõ9À¨SàG½&@3ø)¤äî¿Ýž— ¤ý¥¿ÆKØR@HÕÆ”ñÂ1ÀÃ=þ‚î/®?à?QßÁ,Ø@“±ÎQâ?átãp$‡I@:+U —zV@¯À„¤=Á¥?íxÍûËÀñ1›IáI⿎+;¤¸¥¿F ˜fv+@hŠ¡HÄðí?EŸ°Ñ_À%ýA}Gùb@¸|ó˜l¸¿Ç»—ªå1À”b¨µö`¿?à?ÁŒÄ 0@ŽHÔd ó?LmÜåqe@áà[f‡I@[\¸ªŸ¶?SÅm0À2ÉAIÝó¿²€ÒŸ–¶¿f3Ÿ»·JÀ}4SIJÈ4@M +<‡e#@.4Qß«¸¿©¡þR˜ðb@^Mz꽘BÀ‰;•Ìíø ?Ð?D$ ±&_@þ«©¼³Ù?4Ù_ûÀß=@Ü‹hìJ@¨,Òþ ¡?„ƒéVÀ£øø¨Ù¿p:û‚¡¿q L=o†@t³…– xó¿ˆ'jÿïPÀö—³NÑS@–Jzøª¿ fâ¯:$ÀTdâ3S°?Ð?=à ›ý£"@HeÏ$»ºè? .a%€W@`Xà=@UhŽàOg°?„¾›œ"À;°6°è¿eE:uU`°¿Áµ^Nb2:À.» kóN*@µ÷©ëŠ^%@¬§àé;ª¿ãÚèdd S@!ñs3Àª®³¦ÞÂ?ð?âœõü7@J‚𿈷@¹wƒCa@¨h1ˆUìm@÷:¸ÙŠ,Ê?ç„×ì8ñ7ÀmƃÔ{¯À6ÿ)¦ Ê¿¦§úC3@øô/‰Ë%À6+ZèsýqÀe±É*s@ù¦K“Ê¿äÌ¿Ú œFÀ­ªMr÷Ð?ð?*G[a“E@P˵6îß@G*’±y@"6 °Ca@“´‚‹×?>D–“‰EÀíàÙcrÑÀöV¶Öπ׿§Ë³ø`aZÀä6!XP@{™èôˆŠP@0C®é^“Ê¿ñ‰Ê»"s@¢µøMRTÀ´ÿ¿8@ÉÄ?ð?>¸Ó]U=@¹Z9<@üÑ­¿c@œ»ÎTq@m235ºÓ?ëGø‚>G=À¾if§À¬êÒµ°Ó¿œYsCÄR-@©ƒY¸10ÀbÉesÀÐÌ=Ds@CŒä…ä™É¿²¬Ì7P IÀgÝ~í±Ñ?ð?á©Ç;ßH@D†ÿwe@µÿzW|@Z)Ïà¿c@)ÃFuý¹à?#ßšÝÓHÀß¼+¦[ÀNòîï±à¿d7¬1œZÀ4·•àP,S@ <ú1kV@vr &šÉ¿Šh×(¬½?ó6Ö+¶!ÀÁŸð¿s@BôÄ/½¿tñôq m@líÛ™»Àõ‡ ],TÀrö“U?^S@÷E@%䦿=ÅïÆ†+À“L²ÜE²?Ð?‰¥÷蘎,@éz®ˆéëù?Ÿ›ËЈ‚^@i®>×eF@S“1~‡Ç?Ùj:(€,ÀÈÎÞù¿Je”Y˜{Ç¿!O\ã:ÀÙ♀×p6@jÂÓîHQ<@5,`䦿„Q~dDWS@¬àØ 6Àü¶ƒß”¤?ð?†:O½Þ @ÕÿîýèÂ?ÙKœ;-¼=@‹O9Îÿ‰U@Àki1¥{?{ î6®× ÀBåYÕã¿cwõO¦{¿Œù­ÌgÎH@()ÉkˆÑI@ v4ÐÑ5iÀ û6obr@­é$Wòª¢¿zŽ4òy¤'À+1(¤ÖÊ?ð?ƫꗴá0@*}¢G®è?ýi“1vm@¼¶·z¼=@üÚøøB ¢??Ý\Ý0À,û£SL§è¿ðu§ÒV¢¿#:jE›^À¦õÎ[ ÀkÛÕ%^[À¾r­Š"«¢¿A& ЃYr@y€ÊÐNÀ!·oÁÑ­‹?Ð?^ÏKCRqó?Ÿ±ƒa¯?”ùeæ$@²¡›ƒ 9@*öý·mði?<ûëíƒkó¿@¦Pœå¸¯¿,¿®èi¿¤%< w'@|™[¶šÄ$@j:¢¦ KÀ³2c5yR@È›îst‘¿w}v~óÀ~HÑØ ¬?Ð? *„¾­µ@W STÐ?¹£Lƒ6P@ê™u]Ææ$@²¡l KŠ?œ+mÿʯÀN’´6пQÑØ7ÆCŠ¿Î  >À}|¬ò 'ä?ܦ o¹5Àþˆm¡t‘¿–ÌéöoR@-:I-0À‚%e07l±?ð?Ÿ~¸FÚY@B:…)§õØ?|\ 5ÞuK@ôІÅÃ2]@ @øúÆ–?ve¢ŽðPÀò\ñ„íØ¿Bí™ÎŽ¿–¿àAUÀûE@iŒ@@MÎ* mêlÀÊ‹6r@mzÙ°A7¹¿1ž0‹54ÀOáom@BÍ?ð?¢ ¤Xzú6@ÙÔÎL&øô?”½CÐq@‘?­%vK@û>ƒÊ"³?׆àfýò6Àmú/öPñô¿™ƒý޳¿²9ªÇ12^ÀRq¥ú˜¶&@þ&Ú PÀÏ·Ì‚7¹¿* ‘ÁÆr@ޤöPÀVŒŽÔ •?Ð?É8£Üo@Po8E?ÈÂ?T4C²úG1@lQ\M2ÿ@@ò¦I"ƒ?Å6ÛTiÀa5Ð.˜Á¿3È¢‚ƒ¿IØÍýs[$@§kûD…!@ÈV}›mÕNÀƒ-áªy§R@}|¨T—' ¿Ô58>†À#Õ•Âì|®?Ð?>W§»@h¿Òä%;Û?WÝn†>‰S@Ï”?Q'H1@ã+±½›?ˆ"ŒI‰±Àƒ6´€1Û¿üڔݳ›¿RŒ‰RjR>À¼_'ZÅ@nFõ Á$À² Á' ¿FÏòR@Rü–ÙÂ1À×(ºÅ°¨?à?5gÔ[Z@Ð ,È cÛ?Éoù–wE@qÉËQ™ºS@uáyNŸ?G«×Àõ>®¢XÛ¿ÉãVd Ÿ¿‹“•2@-ª2wܺ@4[Y úe`Àå¿b@_ÙkUE1³¿ßƒñ†ì,ÀžÃ2ñº¿?à?y¿/@ã1R›ñ?Á…â<_be@ê×£®E@õõ9,þ³?-BâÞö.ÀÜÛ)Y“”ñ¿§„Zƒö³¿^ž¸}NÀ¨—ŠŠÆ.@~‡âP³"ÀѵÉãv1³¿×ùÏuµb@jeÕ“BÀyÿ[.a`¬?à?r:å™àÖ@U®»…°zã?¿p…:I@4F€ÎV@9[TØ‹›¨?©4±S+ÊÀÅ꣩rã¿·Ç"÷g‘¨¿x·2;§0@P'!|åÿ @A È(gaÀz’…èÖb@Á㪆µ¿ 9;ë“´0À‹(1~À?à? ôâ›éî1@(oz’§ö?|"¥š\g@j ¼3Æ:I@+5pž¼?²ÌÐ…ç1À¤DýŸ<žö¿ G%,¥’¼¿§;Jô°²NÀ¼­)²4@˜'·6Â@' 1=8†µ¿>©¸žÍb@ÕÞ—Á.iCÀ³.(‘ À?ð?/DSnÌ\3@šp<*â&û?¶yÎU¤]@ûË^V4Õ–¼¿ÆZcn\@?Àüª,ñ"0@ÚS³rB)@â4»*'§¿QdPÿR@¯ö|Ò!5À‹‡G|Ó³?à?t(€\¥C-@¼ïºGùù?žê8²S@r,B˜a@¬=1ä‡Å?f4î;5-ÀMí©œ ù¿îª]¼I}Å¿ŽgLÐìÉ#@Ð)†óÀ*õ ådÀ¼é+5û c@<ȾÙÖíµ¿u Ú<·7À9€ÀkÂ?à?{¸~Â)3;@—ꥪT@XÑön@ÿÎñÅk²S@M‚øÔ?M[—Ä%;ÀûÉçE-IÀVŒÆÿ5ùÓ¿ÏJ¤Ýq™OÀV¶g©OFC@nü‹è-UB@ŽÄyv `š c@JÔþè•FÀ'7+UE¾µ?à?­DÃÝû®1@\‰ôöç¶@:{zÅ_V@hÏPÌÖ`c@e˜Ø˜Ï?I‚ÝÌâ¥1À¹8î‡N®ÀkÍ?ù–ˆÏ¿rǦ2@¨éôD À²¹~ªeÀrȧüª:c@—¨Ž¥ô²¿u¸±þÖ&:ÀJb$Ã?à?Ÿh"åÕ ?@ªÝIÄYW @GzFkRp@ÿ;ð?ÿ_V@y‡Öñº»Û?Bô¹]Ýú>ÀSYÏIAH À 8$=v­Û¿A¬lÿOÀ§ Ùã–F@ÜÇã7H"H@IÙ|€Öô²¿!†í›q3c@¢€þö­îFÀ…¸!!V¡?ð?å.'ES¶È3ÀTÂóð¿gá»ï©¿ÖÅX™aÀlç|¬žVÀ_ß|´^À¾WÙ!ÈÏ‘¿Ipµgt8r@ï»o!5PÀb¬nK_ˆ?Ð?ðÝÎ^Èò?Ò—úˆìÔ°?Z1r€½r#@Ë}ÐÌ…¨:@¿Ûµ*n?ÔDÐUÂò¿$³„ϰ¿íxs!n¿òºÏrÃõ*@·y~õ§Â'@= ·¤´ùMÀ¡\¨|XR@ pó–ÙÆˆ¿–»*4Hñ À½Æ:覡­?Ð?]ÓÜ,Ú@ߨ2„zÔ?¼Ÿ&Æ ÿQ@õÕÛ·ïr#@zvZ¦ùY’?ÆI: ÕÒÀ•´µïsÔ¿ÐÞ@¹)Ї«‘CÀä×íá裿'‹%)4eb@†°öküÁAÀs¦Î{ÜQ£?à?… y©D@~)˜Ô?’¡Ál²@@,º:3£Q@Ðn䟼–?ƒ6ת=À¦²9ƒ Կ㮀y –¿n£S(¡7@á`âRÑ,@-ì½â`ÀS§±,:†b@LV µª¿e=xr`]&Àó;/k² À?à?͇U‰ÆX.@þ[óÝ­ð?G>ÿqne@A[ÔÝ—²@@ã˶™U²?"žÓjM.À+ò ^Ÿ§ð¿Ä1~¼N²¿ Ú‚ÌÂhQÀí&à!y $@Õj|™ò;ÀxRµª¿X ‘Œ&|b@ï-,b[ŽBÀ>}ÈÑï–?Ð?ãQ]@÷Èö!2Í?þñcÃQ˜4@š! GD@µxáZØÁ‘?°¥¸öÀ}ƒR@Bÿ•Л7 ¿4¬,W¯ÀpwÙœ¨°?Ð?oÿ“q!@Û‡gÅe7å?zG¿ÇUW@Dª×ð†˜4@iÌçdÝΩ?̯לj!À"¹äß.å¿ÊKwæ~Ä©¿Ú)ZŒAÀrdúãÝ>@ÉÆTÜ`¸ À JK°Å7 ¿ £«ù†“R@ËsÚUç^3ÀÒrÌ]•–º?ð?½³ˆ–‡À.@«ãv¬ô?BLx,9ÇX@?2¼v‡Bg@QV¼¼Ê»?TX V³.ÀÞ, '£ô¿¶—Qо»¿}ÛÈô'³C@$´¾ú))@Xç~ßrÀ¹…‰-µr@¶âÿÐEY¿Ü‰Î£?ÀªËP¨£æù@”a^kˆk@áGªç˜AM@m®†w/É?-·˜ðCØ6À­ëœ+òÀs%G£þ#É¿'Õµ!äQÀ¼î餧>:@ Ã5­Qa@#ü@pásüZZð¿!§ÄÂhôtÀ¿C´¹{år@µLªñ‚ÿ.J~``DÀd͇åÈÒ?ð?„^­ ·J@§Ä¦ V@ìyñÛ·Õ}@¾Ô1’a@ÕõlÍoá?…î*JÀÐeÛúËKÀÃx2£fá¿ýËøp'bÀdeR’$P@ÙôÁ.A@S‰Œ $ƒÃ¿ÂØ•TªÜr@œeµJ‰ëUÀ›Ûáà¢?Ð?,Ô8Ó.@Ø“…V7ê?ðNs¯C@„:¡àï)Q@¶Åžd£Œ·?ïL!# À}—êè)꿪 ¢(É€·¿ÚJÈ2@¨41D"û¿`YG^VÀŸˆ6VþR@4^¥¡O¢¿ $ƒ·¢l&ÀXÝÏ5³?Ð?ë b42¶-@xÃ0µ°ú?/àkû†#`@£ùu27C@°¬¦}àùÇ?ïâú=§-ÀMªäCF£ú¿?ô»FÏíÇ¿qÓ´‹«TBÀ޲T3@”㌎,@†©.~¢¿MÃ6öR@3yàÌÖÎ6À›býñƤ?Ð?8—¹ž!@½õèÆ]ñ?:èá¶DF@RKºlaS@$š1ÄÁ?¬m‚•!ÀÃ9Êã±Tñ¿!4¦ÐÁ¿ìŽsÆ¿Å@.íÀXÒ£ÀÚö9ì"WÀ{¾ò¶S@þ¨È~ß¿ç‹[^ÍÐ(Àhþß¿ݳ?Ð?”J§DLÛ0@1ÝB|*@†ÇÚÁna@ñðw“ïDF@p·í_Ð?5N(|{Ò0À"U2z”Àghs]Wп®³©rè–BÀÈHaƹ°6@’Ò™*Ûû3@öÖ+‘¿€‰ænS@¿ž¦Îw·7À¸÷ÙvÌÎÂ?ð?p0E˜3ï'@à bËb´á?ÂñIþAPT@¨q›ª*³c@û(Z1š?ð„´?›è'Àãæ¯á¿¸g€"*š¿ÉF™YQr@Š›ÝÇÍ¿sÌE6ˆEÀ'irþ‹Ä?ð?´Ñkð‡)@IU³F¼ââ?àûƒ:e@ d¬qvPT@ÙœN¨ð›?×ò¦rç€)À‡ø|ˆÝ⿜×Áeõ蛿³LÂÝÇÍ¿ˆ“¸nÊNr@`ŒÃXõFÀX&iS¾â£?Ð?tváEå\ @­Ók3É?8syVÙ€7@CcúçÆtF@‘޹¨ø …?nYWÆS À+}øÚ—+É¿œ«½@š…¿è³&[Ò©¿EøC…àô ÀGž4•ªÀð ¸hR@¿4E˜°¿×`Rá&ÀÃÿUñ¥?Ð?0¡ÛÆy4@dc£¦èÐË?A UÓÓÇH@*öX7@ÒÕY(߇?åb (q/À¦¯ì¸DÈË¿ø™«Á%؇¿PþO"ƒ[Ú?ô@Å‘ ø?_ ¼e{¨ @)Nâ;°¿ó¤eR@è`ÎÃ=)ÀˆDEù´?à?˜ê¡ ¥Ð!@”9R2—á?e|O­·òJ@ƒÊÙ nY@ÅÔ(Åx^¡?¾¿ûîzÊ!À?yÏ‘á¿âmßvX¡¿X |ó×Ô¿¦Ñ`ú+Ñ,À¬¤?Iâ4À‡ÁÊm€b@{ð@RûòÀ¿¦¥ë@8Àï’)Ù·?à?©êkÎC$@î'.[8ä?LyÃÞ¥é\@9à8BýòJ@Ï›„ ²Á£?‚<«<$À‡qÏÔKûã¿ñ¯ nܺ£¿Í%®ÞE÷?ÓoÏ3@®Žá0œa)@}FÅ'óÀ¿GÄzÖ|b@ÈM¿i’;ÀŽ1 ݦ?Ð?©j2¡4h@/ÿ„»Ç"Ø?ëˆïµ§>@VCÓE¢L@ä2]g6›?€Áu‘ `ÀÏ œ_”Ø¿Y Ã,›¿,Eí™ý²Õ¿ABåLx%Ày‹÷…T¨/À÷¿Vö‚˜R@e»%•t±¿,2u½F§)ÀUVÍD Æ©?Ð?o³G<2@„•L2Ü?'ž]‹ÃµP@‡»T¨>@L<ÁÀnÊŸ?é^Àµ©øÀ„…õŒ'Ü¿›3_P¾Ÿ¿tlÚ@-î?”ï1jqÈ@ôéf»Ò"@¯éâ7Ât±¿œËVän”R@7!)¶xó-ÀFhèÍ(-Ç?ð?*+›áª9@ö«8–ÀM@ƒP|ÞPa@ôòèê³p@ëàÅnXÙÄ?¶Gu9ÀKº¨ÍúFÀàüpJ¯ÐÄ¿®­M—Ào¿Z€:‡LÀ‚K¯mTUÀᛇ±r@‡äv1zÑ¿Juab³KÀA–ÑX¸Ë?ð?¿¥+™D‚>@g$GéÖ@ŸN3x3(s@8ž@2 Qa@H‚6òÈ?þÈL3˜u>ÀãµUv¼yÀÿ´n³çÈ¿v¤.6[ä@{:“;@=¹Æ†ÎH@ÿB—^zÑ¿_Iö|¬r@;î{ì¹0PÀiÄG K¸?à?v ’".@ÿ®ËÚ­¸õ?CéçcqS@©zÈÜÞa@°~à‡ÃP¿?fÝí .À7¨àUó®õ¿ÿ€·ú¼B¿¿¬ÔXJÏü¿žÖß™¼AÀ8q£±òJÀû9ZðÉb@?—P¤EæÀ¿Kÿà‰‰<À€j+œò¯½?à?c­EðVk2@œy{L Žú?I¹­p§Íe@#ÓN•qS@ÒÜšðT$Ã?hiÅc2ÀΖ'‚ú¿)b-Âÿ@kÙÏ,ý@7Ýz€,ÿ1@Ö€#½Ã¢>@ºGqæÀ¿§ƒÛNÅb@ðÐs°unAÀß¾÷î‘k¹?à?êºq4 ­1@ΗÃ@Óü?cüT#n¶U@†ÿ8}Ôc@nm Ç?Ãö¢é-¥1À6&ƒÝ†ü¿S1¥>ǿБé)&RÀrÊÓZ+EÀ™¦µãWPÀ8:]ãb@¨&ý˜0¿¿ÀüZ*>Àpb­¿?à? Ç#± 6@ÿ$çóÏ@¹P³±§h@z,Š3¦¶U@}ì)½@ËÌ?Óa™š)ÿ5À¸Þ¬5qÇÀ•ƒ±Ö~½Ì¿P LУþ?VMT‰‡6@äžéú&B@ü+ß…é0¿¿tÝQ8Þb@ÐQÌ@³BÀu…Z"ØŽÊ?ð?p¤žÝ¬›D@ Õi$¸•@ì™Ö !h@£ÜÒ:êu@9gƒ„Âà? ÞêH‘DÀî¾WYŒÀêP:*ºà¿0-98Š‹Àä~la…XÀ`´GFcÀeê+íRýr@=bÊWÙÊ¿Ë &‹OÀ½!Hì×Ð?ð?ÿÍ}ÿ¹&J@£wVgs•@Î΋ò·{@Aæ¡#L!h@”…M„´Då?Õ÷¨“ŠJÀæ(`‰À~ _Xû9å¿Ê<‚Û¤@¸72éeK@—qÕŒCçT@ñÙÆÙÊ¿J«&X ør@ÎXvÿSÀ!xµXó´«?Ð?irªÑ¯á'@ŒA.ì÷?ßx¾Y²J@È™àÙ!X@ÃS²öÇ?¯þ¥¡Õ'À\ÛÏç˜ß÷¿é!RÈêÇ¿¸º"âéúÀn~Uºè;À(ÂŽÞýDFÀ"²‘>ÞS@£ˆ-=y¤¿4phØKŒ0ÀH‡~9ܱ?Ð?XÃ9þ‘Í.@ÛËY{Ûþ?¼2ºâ_@R:/­ž²J@Æ8vëªèÎ?Äb§®]½.ÀÞ6¶ àÊþ¿n? ZhØÎ¿Yƒs©¶Ù?"Ýÿð6M0@Zà}Ìj‘7@*÷» ry¤¿F«¼_¤S@}™<{S5À¾@Rýݬ?Ð?ÿÎÛ{†+@oå¹x€þ?1ÓÒskM@)Mb{Z@Y÷çmæÐ?¨uôŸŽw+ÀXõ\Fîoþ¿lÂ'»CÝпL¦)¹ÍÀ+y8é”6?ÀšŒö4‰TIÀ' 3S@ËÝY©x—¿Â†‹«´W1À»¼:‡ã²?Ð?K›Nõü2@†0óÿÒ÷@|éiñ@a@qî|¿kM@‘HZeš Ö?×­°b7û1À¶žëéþìÀ…Õ?‹šÖ¿{»œÏÑ­¿»4•üF3@ƒ€¢ƒ$:@cêÍCÊx—¿nú1M.S@ÿ½Ž«Á¯6À Ÿ:vÌÁ?ð?$¥ý0ÀÔŽí.µ/MÀÅ´BgBr@ê½V;пð—V-,½FÀýCoø“È?ð?È©:žº4@è ÁÛPô?!Ú5S›Ãm@¯÷°ãbZ@üòÝ4é³?);ã'|³4À¹+îÞIô¿HÓÚZ⳿ÜýÙh„0À>‚€í+@–êWd­@É:?,;пÔxÏ*>r@zœø’ª LÀ¯"‚°=]5ÀæÁ2Çx(EÀìÿ{É»R@ö¥t>Ìþ©¿cÜnBÏÄ-Àê•o²&±?Ð?6›AÆ^*@¡½ë`ËŒ÷?ýðQþ‘)\@Õaê±G@ô'ÍPÅ?¢æ¢‰Q*Àù†7)ù€÷¿hÁ¾xýÄ¿’ˆÃG@À†ŒÌ˶+@CU*Ïê/@®C]ÿ©¿Gä¸ ¶R@[vŸYp4ÀZóÆóˆº?à?Ýïn£6@¤}q@æƒ×‹ýY@Í»UWD"g@ŒT¨W@Ö?Fý¼2—6ÀFhmDºeÀ3Œs!®4Ö¿ $îĬõ?Ï$Y©µHÀDLdXÀ œæÖ‰Õb@B'fd] ´¿rúÕéÊC?Àa) Þ'Â?à?ý{×áý>@ÈY<¥º@[-rƒùno@rÕlóÎýY@œ'GºvÞ?9³\—£í>À‡(÷è©ÀfÚX¨ÂfÞ¿E”÷µ„N$ÀŒÑ0(8l@@ñƒPFÿB@TÒz(‘ ´¿ÞÐo!Ðb@A‰$8bEÀØj»S¬«?Ð?¹G.*@Ts¾íœü?¤ã L@J¯‰ÁahY@;=c~]Ï?ßVË´ *ÀIí0€sü¿ŒÖöЇLÏ¿À„—µD¹?ñÎ|$<À)àù« KÀÙÛ|áãïR@•Lˆ8âÆ—¿¿Ÿ}Áe0ÀáùÍö+³?Ð?£8Ù¾¡2@Ì]K#Õ@7XFSva@±ztû_ L@%h ½Õ?a\ØÔØ 2Àò8piÊÀÎ`ν±Õ¿Í}ó»ŒÀèPÉ3)3@ ƒöhÀŽ4@KI=Ç—¿UVP¸êR@¬^j¶ñµ6ÀqeyûÏÀ?ð?¹(¿ª.%@0ÆR.©ß?ÁµhxŠS@_‡]p¯a@ØåëÝݸ–?CÆÈà(%À\Qo†.þÞ¿Å+¨²–¿FýDÞb]6@Lˆ%t`š8@A°ú¹ã@Àø¥1eÙq@•ñ¶…)˿͎ÆÒÀBÀo±:ì•Å?ð?Jk¢–*3+@;ZìΆëã?ÍXå÷LŸf@²S-ìOŠS@ºí@3Z-?%Ïž»++Àà ¡'æã¿©e.å`%¿PjÀëhBÀ~zIšØ@ÝB#ÎN¹BÀé½lØË)Ë¿ñáã‹Õq@ÚÊ ŒŠHÀ‘"øÑLÚ±?à?»±¦ï{@üR¿±%Ö?Ëc>‡F@P†0´CT@Ž}Å¢¤Í’?ð÷$‹s À•´1˜<Ö¿š¤ÚÇ’¿…Z¬š<&@O®«œ‡@>è*¶r÷:À˜«q1ïa@$[¹ÏG½¿Ýß«$¿4Àœ/›¡Dm·?à?åf§ç!@*€}8lÝ?ëØ~}xZ@µViN‡F@ ʳ’®˜?©=¢!Àu9xÝ¿Ùj¢‹ø¦˜¿â˜Úi%2ÀGÕ›EÈ@fÓ‹sb)À¤8TH½¿ èæ‰4ëa@°F‹@:ÀY2h:Ùæ¢?Ð??Ié¤.½@‘oæ¬ÑùÎ?LJ¾…OÁ9@ÊRä˜Ø G@± î9';Ž?Ë;„K²À£Ö1ïο>›þƒÈ0Ž¿Þn…ÃÞ@¦*=šâ•ï¿e­{jþŸ2À`Êvµ R@¢7*kÛ䮿b×6ŒJ%ÀU»ëòFJ©?Ð?‰ Ø|=@‘«äs¿ºÔ?éï2‰$ªN@O£’Á9@£ Î&;”?™‡¨36À@.£³Ô¿—¢<64”¿¤#Y Ê!À¶wÌx’ @¦·r’/ À<¬Q0+宿”=¿2R@ò ‰Õz,ÀÚ‡ê­õ£?Ð?< /Xs@–Á´YGÕ?¶èw:=@»+7T J@9xí„ò¯—?õ̼:À¼SøÙO?Õ¿|U»ÿ¦—¿Glb›C@Ž—ê¬OÀÔå¹Nß7Àñ‡CÐØR@ƒ³Ö¯¿#’ Yv˜&ÀE·J0,«?Ð?»”Ý–5@L–ˆ‹úÜ?xJó$œQ@¼¨ÕïÊ:=@í5ÿ!! ?F›4 `þÀm™ïÜ¿Ëʦ  ¿îœ6 DÅ!À"óÍÈÓ@4ãŒiרà¿à¡MÑÖ¯¿VÊÆ’R@ü@ÒœÀ.À€(RØ¥?Ð?ŽÐ[ºZÐ@¨°D×`ÅÜ?~±:;1z@@nÐ+ß©CM@á+•N$¢?u}1ÉöÆÀç~u/‰¹Ü¿>ÈñÖ¢¿!w²Ðh@º\¶­ûøÀ=>êµV:=ÀcÖºO4R@èTx,Òí¯¿EÜ­~Áì'À£5m1­?Ð?·ã׆Ύ@ Q3t*æã?´½‡šT@èKÜÆ[z@@ƒ1žX©?Z»7ÑÀ =U¦ùÝã¿n‚¶L©¿¾Ð¢ðô!À‡»Ä˜r@è"¡E@õÆ$×,“Sb.R@h—5‰0À‡N|Yi¦?Ð?ÿÌ"zS@Xv&Ÿ,ã?}©6ÔbxB@c&¥¡4ZP@;d_x:«?)x*/WõÀ{í–$ã¿ô È·b.«¿vjS¶wL@˜s6jCã&Àé$çXAÀ{þÆ—KR@Šyäöö®¿pãA˹G)ÀÄ8B‘(ÿ®?Ð?kj/@vñ"@à~êuæê?²»ÀÛ¹V@ÌA2…’xB@T ½ë‹³?Š´»ò é"Àª!ñ‹…Úê¿‹ïëÓ³¿æ¯™;‰Y"ÀÒÒFgôÔ"@ª‡¢<6 @ØF÷®¿Xm¢°ER@£.ïa¸1ÀÝQEr0§?Ð?UðÏÛçº@•J§ë:é?÷o`ØD@¯ò¹0R@Æ)òèÍ´?YË8¡à«Àzâˆø.é¿ýstM´¿­œìì@ZÁèÏV·-À·m<#DÀÓ+˜™cR@0÷g¹ç¸¬¿r|—}´©*À Í<ø:x°?Ð?ÒÁˆÕ”‹&@DDmDíñ?(\´]`“Y@î÷ñ÷˜D@YÍ/„M‚¼?/oŸAç€&Àk;ÓÆäñ¿Cð×Ìt¼¿:›¼@ö"À ¸?'@×Så )§@¶éã1¹¬¿N -†Ž]R@©ð¸î2ÀŸh]I¨?Ð?{7Þå„"@ôxÃp5hð?Ï:GÜF@ö &­S$T@©€J-£½?QÑAÔz"Àdq§¬`ð¿Z„‚/½¿³_ðF@|¦Ö<2ÀF°å”üFÀ³+Óý|R@§ýÄêIõ¨¿ì â,À,o#Ý“s±?Ð?+ð)¸‘Ÿ*@x¹STL—÷?–d€« \@MÊA‚ÜF@×ZšqçÄ?¹ËpÜ@’*ÀÓÙšº‹÷¿¥â:ŒüÜÄ¿”RÀf¡Ì#ÀNú+@¾‹ÇÊv$@Ë N\Šõ¨¿Kû‹vR@fP?º*4À¡÷ö;8d©?Ð?¶Á\gz%@»i@õ?)£Ò¬îCI@Ä()Å7V@ÑyÒάÁÄ?éÍ..o%À Qÿ7õ¿Ò “Ô¶Ä¿Z²›˜±² @bË-œ_’5À{>ë­aåIÀ9íï•R@ðºÃ¯Fh£¿ñR9„-ÀAGæC²q²?Ð?’{ЍÄ7/@¥T_°þ?ôs¦7Lã_@h·ké/DI@%’[:E+Î?;êÿ3u'/À[V þ¿P¸û ‚ο™q÷ÅÞ$À¤®§P3„0@ƒ©1.žn)@‚(Ìxh£¿ÍÔDR@uB*i–n5ÀÅrèw!‚º?à?CrŒö‡Æ8@ó…)4é @Ô‰ %ÀÐ[@½åjTPkh@$›·þ:Ý?e!¬ñ)¹8À³w¨1¯Ú ÀN3`9+Ý¿`…€ÿ´B@ø´…UÞHÀ Ê´ Þ\ÀÎu?८b@"§Ú§¿IæWA¤ý>À÷ÿ6«rÃ?à?ù?Þ)‹/B@›¾¼êÏÀ@²à‰q®q@–€D÷Ñ[@èßW­ªtå?ƒ¿mU»%BÀ¬Z¬–'¶À"›0iå¿“2Ÿë.6À$ÛŸa]6C@°…FÕU9>@GÙø‘§¿ÙÃÐG©b@òͺFÀ³ b?²¯?à?6PÓQHý@b7ÊéŸOÍ?Ä—•ú C@™àAÙP@©m+e}…?ÚóóŠÐ÷ÀS æ`›GÍ¿öXq;„w…¿^ÄKáwº0@þ«áÅ)?2@GhDÒQú8ÀaºÂŸa@Ûœ’t(«¹¿À%z,-t1À!ódaQ¶?à?^Œ–|(@¶Ó&¥Ô?þÒ’³Þ€W@^®ªÃ+ C@2(éΖEŽ?{C±­Í À톮}`ŸÔ¿›þN=Ž¿vA`;Ààï()û?JÑHÇ;À\­´»j«¹¿ÔØUT›a@©À6ÒÔ’8À©NÇÜÞ°?à?t¬}í¤@ûP3äÁìÔ?*‚SðE@+¹PçƒXS@)¨íJÄ‘?KtÏ]VÀ&MPæÔ¿¼‰oÒ¾‘¿ ¤X¦ƒ®0@ƒú‡¶¥9&@ÿ/'+wAÀJ¹þ]µa@à¥øW"®»¿æl¢U«2ÀÂÏÀ>y$¸?à?ʳ’„¡£!@Ìîª9ôÝ?×Ï1 Åb[@þÉ'ŒðE@ò/içn™?’x¼¸2ž!Àùƒ«áÿêÝ¿åg™¿ˆî£)I*;À1÷ª>£@ƒ »Deí5ÀÝåÍÐi®»¿Pq/Ðn°a@2åë‚¿µ:À†b^ƒÁæ¡?Ð?È­GFa@ýÞÍ7EÍ?1#k—9@›ü F@Œq„ˆŒ?!©üîü ÀKî%ü:Í¿i×ù¼~Œ¿s¶äT… @QC (@%zOÀçŠ6ÀüÀåCËQ@D /Ö7­¿ók¿è#ÀÇK1Cü©?Ð?ª:Ë¥Ì@Õ~KÝA@Õ?¨TmÜ:œO@ècNQ9@Z¨f·”?Éΰ%-ÅÀ‰gdUù8Õ¿G†÷oL°”¿mÚVnÐ$+ÀÌ(ß<±h@¢6Êã5 À ¦•"8­¿µ¬\ÝÅQ@Ohnã,À2ý°HÚð¢?Ð?ã(bv@Öý­ÇœÔ?{OBNÏl<@ß3eòH@ã4-˜T–?ÿš”s¢ÀqXÏ’Ô¿Ãû+L–¿¶ôæƒ> @%á:[tÅ÷¿ƒÃ¶†ü¸;À¿A{áQ@›Sª ®¿z’ά*%ÀÒQר«?Ð?¢¡­ž@²(—e‘Ý?ç”1­çR@QŸm³m<@ijÙk ?¹íB£”À™Ù>†Ý¿ñЃó§e ¿dù‹IQ+À tÉòÿ¬@TÞ²ÿDÀnK ø ®¿´wÖ«ÛQ@•k®G/ÀyÔ4ýÃ?ð?nJA[ž5@^m&%-û?ON I`@a©ÿ´Ýl@e]É®ÚÁ?Ʋ±z•5ÀÞUÕšû!û¿í•×˜Ö Á¿Æóh™»¯?@l¶¡ÅkÕ3ÀÖk`Àp&¬Â øq@ØeÀ¥–<ο"çÜRsFÀ–k:PºÍ?ð?Ηõ@@ò¢‡õ[7@"Fì·t@_¤F`@Õ$CÛiÉ?+”Z@ÀK\˜A/ÀÿÐòåj_É¿ûài•b±KÀÜ"66>@ÎjªÌ$À÷ül¸ä<ο&Ovçñq@yCW§^°PÀ%ßV*à Å?ð?3)lj›9@L[y|'@Jõî£òa@@ òHeo@ÈNáÈšÉ?2/uü9Àô‹[}#Àùç¡DrÉ¿àyTú£>@ ®Â¯yË@À)Ykk3cÀÏùÅûr@)„ªöZÍ¿èFX¬PÂGÀ-|cË Ï?ð?îóþ¶?C@¥_ú88 @éNÿ7w@çúù3òa@§x»8=?Ó?ˆ1_{17CÀoø«>t, À£§ë·6Ó¿¦|N2áFLÀý v6 *C@€tyXÅ?èÙÁçA[Í¿·Jäžr@úõ;§ØQÀBL}ºì¶?à?s9÷¨.@:~êÐ÷?phdT@™ ¬ya@ýQá0i×Â?´)èp .ÀêÄjÔªÅ÷¿>l÷‚οò¤›I«U-@P B^š7À§(çcôUÀUm›T&b@* VF»¿¹V‰5÷9À¥Tc 4ÆÀ?à? €5ú—Ø6@ ° õ@â›Óæj@(Ê/ 8T@Éx§ü˜Ì? 03ˆÍÍ6ÀÃ`Ü™k À¨}£6z‹Ì¿jùåû =À •‡è|…7@PE·Ô3Ø@3 Þ{œF»¿mKLâb@;)L‚DCÀ9 l0Ç?ð?ûð½P“A@^l¿(xö@–r"½2f@›=?^s@h½&Ž FÛ?XBƒ™ŒŠAÀÂ÷¤çÀÑns8Û¿FIæˆÄ;@j.)ÂVNÀa+tK?ÃhÀ‡ìZ!>r@ é\]LÄÇ¿çîRžtJÀÚ½ŽS¤¾Ñ?ð?º¯åìéJ@‡Q%Ü@´@¼àj#Ç}@uqt >2f@úè¦õ<áä?ý/PÖ¤ÛJÀ6E,n¨ÀÛÛ“äÒÖ俎f ™NÀš‹µ/L@æG.ÚZ4@Ôñd»‰ÄÇ¿B‰mÃ7r@¢¨b‘…Ó‚6F@T[þmö@@ á8JFVUÀ)’ì¬|q@ÍykÝ»üÉ¿]äÞ®bAÀÞÝÍÝh×È?ð?¨3ZÜU52@œÐbï? èÙ½œXl@E—1JU@ˆÈ²9lª?íÈŠ¶/2À÷Ô€Z~ûî¿êè¾^dª¿ jŸÅRÀîçÕ•FL$@rµþCæõNÀáÈ/÷þüÉ¿ƒžùD5wq@§Ùêe]#KÀ[zE\ìÀ?ð?ƒ×uÏún,@?c¡Y(Äë?T¦PX@§¢Ûì3&e@‹P~&X«?eŸÖ8e,À›Ü ¡ºë¿(Ž÷ «¿=O­ãÔF@1‚mó/Ø3@O 4&ÚYZÀãwÓ’q@Ó©ùsË¿³D[Èë”BÀ½óO¥ªÊ?ð?Ku«th6@¨N XÕáõ?h§ùivLp@ÂVNPX@áÑ~Ì^^µ?¸9Ä`6ÀÀʲíRÚõ¿¹ú“ Wµ¿~.¶•½)RÀûÈÆ σ0@Ì~Û8|jIÀÆP}Œ@t˿𼙌q@——l7ðDMÀ{osàñÁ?ð?š@$Øk'1@ æ»t‘ó?ŒÅ'tH‘[@ó Ä|ög@0çz%ú-µ?ÍØ ó 1ÀÇV}`ó¿ó~&Šü%µ¿œaŸPâÑE@UÙmʼn@t…¾w_À\ÞŠ«§q@µb7ö8TÌ¿Œ»Ô´ÌCÀoñŽ!wÌ?ð?0·JƒB;@®$=Jþ?Onq Á˜r@l3~¢‘[@¤ßÑÔÀ?¼]3o:8;À-ÏdžÏ>þ¿bG\u¿ÍÀ¿ùyÆî~WRÀ–²Ë¯¨j7@‚jn[DÀ½Pæ‚TÌ¿¼+»^¡q@©áBµMqOÀyÿû’ù²?à?ug´©Ü€$@ÓMiÌ`Àé?G”Ø=O@FŠáVûZ@¡Fä+°?Þ/n rx$ÀZN­Îµé¿­<A%°¿X²IíÐr5@L„pÏÀ¯Ÿ«ÅSWRÀî„Å—¥½a@eÛ¯$ t¼¿˜Æ;E 5ÀCïÆJž]¾?à? DþÓ—i0@\žû ô?,1ïtue@ôñ+ ŽO@ýÍÉùÆã¹?nÛb0À°9‚Ë•”ô¿Rï¹R&Ù¹¿‰¾ÇVÞžBÀ[RŒöÞ.@ÖÛ¼Ò¤}-ÀNó¾œit¼¿mZ o ·a@~õš°qÔ@Àù¢ùÄÄ?ð?ÿž‹åL8@#>Y¦‘%@õнÊea@>š*Ç/6n@1ÅËò´2È? )Áü&B8Àˆ=WÏüÀKÎZø(È¿AQä»ôD@âç‘lϨ5ÀLR2˜eÀcó­1ûÓq@¬Ùj¦Ë¿8«91ßMFÀ¢i#UÐ?ð?n‡ï°}•C@$Q’Þ4£ @ìj  åºw@U怩÷ea@#rpab€Ó?=<üÔŒCÀV;n”ü– ÀÍÃwÓ¿v²Þž»SÀ°¦©qC@zâ*L}B3À%±Q}N¦Ë¿\vÏ3Íq@$"7 öQÀP€{¼Å?ð? f£6•<@F½^E}Š@åý fdc@‚¦¦—AÔp@¿ÉÎÆÑ?A´¦—‡<À`9cÜÀ{ίUl¾Ñ¿!]*²VD@žWˆ×AÀÕ+ëd¶·gÀÅü´êq@Q(öÙË·É¿z-¡­Ì—GÀeˆ”Ñ\Ñ?ð?%Ä·£-G@ÖdxG@bÉ=¶n“z@OÕkw3dc@–Ç<ÈÔÜ?zEèµ"GÀX AÚ>Àÿ’hæ/ÇܿȢ‘‹~SÀE¨¾G@œÏs:¬"À6ºA¸É¿ìFz½ããq@!ì  ÖSÀ–÷¶#TÆ?ð?)iâç²±@@an×­I @´Öx¸#ƒe@ãÈ—áë©r@åL¸bß°Ù?Ìã¬wc©@À¼è¼; À8ö§n¤Ù¿à›“¼´—C@œ6‡ •UHÀ¨Í°%}jÀD . Úr@7à+I«rÆ¿Æ2ã3`èHÀYEÉöÒ?ð?¶GB0;K@sÑýB ã@<„G}y}@À{>D[ƒe@ÖöM ôä?õý¢-KÀÙº£4'×Àíc9éä¿'/²o¬TÀ€-lŸsXL@€yÛå5Ñ?%fl?årÆ¿´†@-ûq@X½XLTÀiž×X[/§?Ð?Åx‘×5a#@™à>&‚Óò?™z0æÄG@~wޏàœT@ÖÚIÂ?ém!W#À-*7p·Éò¿8þˆrW@¿ÄSž´¶"@v€lÿú.ÀGüŒQMÀ½ÈiwR@³V_G›¡¿/\÷«õ?*À+^&5³?Ð?×UÉÆÇ/@ÂîÂqfßþ?|¨d=m`@65¶CWÄG@ rÜ©ýÍ?¬>·/À¿¼:¿WÏþ¿†Å’îÍ¿¤ÙåýÁÎ4À¬Ò•² 0@øø/ê+@Ð ½L›¡¿r,Cì"R@ô?鿀5À‚¼ ræBÈ?ð?zí Gš^F@4¶,Uø@ÈåªÆÓ'j@ ÌíÄð­v@·?4·`¯é?Ï#—”RFÀÙZ©rëÀQ!\E’¡é¿ (êš²A@ï>ݵÆRÀ !ÕkpÀDàe”1r@8!ևᵿ<ý¿BóžKÀòª§]+ûÓ?ð?:ƒ5ÀÅnR@QÏo¾dÀ#@ìtÀöù%‚@G´O(j@Ço’¾+*õ?^ 5HÝdRÀâkËÆµ#ÀÝxTËõ¿iT]¤UÀìçc²ü=S@VÖœZw2@K'TÀᵿt|gîØ+r@k…à¿ç¼VÀìûÙîÏö»?ð?´~åoêÝ!@úzïŠÍŠÚ?É]9ÍßQ@·^¥†÷^@I.K¼·“?›NÝÏùØ!À…hßvƒÚ¿I.CM“±“¿xö ¸K@k3Oœœ¿M@6f4­æ>TÀÍÊià0q@øž.¸gÆ¿¬Œ ´Å >ÀAtv¬½Ç?ð?í÷ñX.@Îÿûbê‰æ?®Ià fi@û9:¨ûßQ@\ý ?u6H£O.Àå}¯ƒæ¿›: g"¹ ¿©¬¨e!lVÀuß´_s@iD¬&¤§VÀv)îñgÆ¿Høã.h+q@ñ„ m ~IÀÉ4A¶Ôð½?ð?JžÅ‰@&@1¢a&·ëâ?Æi^(•T@C––šÄÓa@ ïòd’7 ?TШúf &À„€*Øåâ¿ñóø-Š2 ¿}o%:‰µK@}ätþ¬¯F@3U0>YÀOçAnEq@>­ÜÕ,8È¿Y³Š;ÿ'@Àï2Ó3>†É?ð?”\ð—[Ó2@ÑqmÞ±"ð? Dë…©Xm@j–³ƒ]•T@ò[Nzਫ?ùì*„Í2ÀÒˆÕ!°ð¿Ý öOK «¿O¡fjôVÀ¶·°AzÓ%@Ê»NOæSÀŽ1_k8È¿½²y?q@ -ÝNî‰KÀ]bËàî¯?à? ¥ë¹ñ@ ïy‡ŠmÚ?}Q½™b‚G@mÐøÀ× ±bhÒ¿^ßåì²*”¿^ŒG?²\+@v™kѲu@ÅŸ§:jAÀ´±ú¡ZoQ@ë2lœùuª¿=š®ô³}"À–´,9&­?Ð?äÄ!¤ãó@æq,U%ß?J5tES@Tº$<©:@ú‹ðZ¡?™;èŒRéÀ> ß¿Ûcôº„S¡¿ )èÐï6À>ôÓx0@V ÿ’--À4ß=ï=vª¿ô²×™hQ@…¯YDÀ/ÀãÒ íµû±?à?A|nàt#@w•ÄŠÈwè?Ü­=¥m N@xÑñU.Z@Aí®Å®?”seâl#À(ÛÞ »mè¿üuq{¸®¿îB*F·;@_G`/pý?Ü…´å¢ TÀârÏ Å„a@¦¯Hûr™º¿­ÓI<µ°3Àé.ý¾?à?r¥ã—YÅ0@f µ?,õ?Å; V™e@Åf6» N@”›ŽÑ…º?¼¾y¶u¾0À*¯I ‚õ¿wýéìzº¿æq¾vMGÀèöeLål/@Ôø} ¸8Àγ©·™º¿óÌh:Á}a@«Â(¢õ@ÀGÈùOÃ?ð?aH€7@ NaÊiG@2²¤,Ô`@2«+Óü%m@ ‰G±øÆ?ù´\7ÀJ‚žE7@ÀåDÞF‰îÆ¿|rzŽŽJ@¬†±5ô#ÀÃcòÁfÀ@… ™‡šq@oΔ4yÝÉ¿]CÒvéDÀSÙulÐ?ð?íh*8ÊòC@ÜBÉlB& @ DâÂ'Bx@²¥ªXÔ`@Ì’%¬lÜÓ?[¼ï`øéCÀÿ`[Ð ÀS¸¤ÓÓ¿”TteÅWÀ¼T׃¬C@±™ŸkCÀíÁ¡ý»ÝÉ¿a–kø^“q@9ÖXÝRÀ,È^ Ä?ð?5?Φ«&;@‚i7b@æm-Âb@A©yÏ>p@¾í¡c×Ð?I ¦®à;Àc~R$XÀ)À8tÏп7ZÊêNùI@Ú~W7Àˆf½`ÞniÀ¿Re6¨°q@|T3þÈ¿âÆ;(FÀFô²ãÇ\Ñ?ð?ü4üj«ŠG@€§}Š@˜á­ {@—,™Ü]Âb@âÇò~4Ý?¡ГGÀB¬»;ÁÀŒíö^»&Ý¿\Ÿ0Œ†XXÀÀùëQëG@Éá¨/¤<ÀÐë\<È¿—ç[‚©q@'ÌÞ2SÀŸ€n6yÅ?ð?ÌVÆ¿º?@°™›rà @sÃ3Ðd@%«Er@6bO¹ KØ?Ͻä ùª?À>p2¤µ À-m€‰ø>Ø¿K$B=DI@çër–sBÀÄ9 bš*lÀQªÓ/Çq@ð°-Y¢Å¿b*‹RmGÀN07OÒ?ð?S]AlÕ•K@·.­¢##@YêVS^"~@Åå%ñEÐd@ÏãÏõÆå?W@˜1ˆKÀµ“íJ#ÀR *¥Få¿K”ÑYÀDD.tuL@æÜÙ¢sZ3À|Ux£ØÅ¿­¸?´:Àq@ ëÎ.UYTÀCÚp«Æ?ð?£DߟhlB@‚DT³eÕ@@$Æø²þf@ò†`i"ês@- ß‘8Cá?ÛšêÖbBÀD$m"ÌÀê«8A:á¿9ly΢mH@>P`ÞIÀc—RÚ›ônÀ£X2‚'Þq@®ÎøÖ”€À¿4Ÿž¹HÀ× MEÓ?ð?öw˜ËP@ÆÝbY@À‘àÝC®€@¨–—Xîþf@eÆJ‰î?Y*qtPÀt—~Ï3À—Æè‘ü…KÔYÀœ¹cð¥P@¢}‘É$ÀѦs¿€À¿”ƃٚ×q@§½º*‡UÀ˜2GJ-Ç?ð?\ GN³EE@á>5Áð@»;ÙöúNi@?`iv-ëu@5ÊÌ4è?9èíæG:EÀЍ°r•¤À¥˜˜ '迟–uG@(4Åñú£OÀ¼s»£¨æpÀ™‰Ë™õq@ºµ8€ôˆ´¿ýÊ‘ÛÔ JÀ8"=Ô?ð?áEòzÞ•R@ôÊ€_Ó#@†¡&ðýd‚@ä ùO 9wâgZ@öòtL&4A@•M_`Ò‘?’;öfàŠÀFó¼9 ²×¿ÓŸ.CÍ‘¿ús¾ƒ­JÀQã(ÎÔJ@2~ØSgæJÀA¼ôŒ«´¿ü¢À>—õ`@ ;µTé9À u:Lø¬?à?–’…Æç@;€¶XJÒ?‘oÔåÒC@éÕ¸ö6Q@â€R†8E?¯Œö >áÀË3¢ ¤Ò¿ÂþÂòr;¿®1†“•@@¼e,¸™I<@TªÖù4ÄLÀÀé‹“a@C2N²d¶¿åG'¶õ-ÀÇÐ!1º?à?Z¨xõñ}#@¦ÕÞ_Ûà?êùŽXb^@®ñÄÓC@Ùk!þ'?Á{¦¢Úw#À•º¹WÖ࿯ުá¿*ét1×JÀë÷£"×(@Äü«­9HÀ7záëd¶¿ ¶bî+ a@ˆN",áé;ÀMúi®?à?… !ï‰@e༇Â8Ù?nºó‘ ¨F@k"šË ¬S@GïÛð—è˜?ð…dÀ MÓâ0Ù¿*¼¯ ùߘ¿ªpºÆ<‰@@†3–P5@°þ6FÔPÀÌvclã#a@¨¿Gº·¿¾ôž+0À¿9’^õù»?à?X§äd÷Æ'@ݽ@.d{ç?'t]^Wa@°E¨F@¦È.Á0§?Œ$¯»¼¾'À3Mþ¬Csç¿·‘žº(§¿ž€KÀ¨û[XÕ!@z{ûAEÀHX8‹@º·¿/ϵa@È>Vpô=ÀÈå2 ‘°?à?<Âê“Ü@\›á°…Gá?-;ffÓ´I@R¨œ…—QV@£<Ü“rY£?f‹»ÞÐÀÿÂ’÷@á¿Î•mR£¿ôÅOFo@@:6›'éÊ,@mÈn¿¤RSÀºÄšsy8a@©4YЏ¿Áõ„tÛ<1À´i’Cǽ?à?ÁÇè²,@—&M¸…ð?TÚ•{¨c@)Á~ƵI@| /‚Oþ±?CÃmÞ¨,À1d\4m 𿟻? |÷±¿, {6rKÀ»Ö™ ì˜(@_ë8ÔCÀ/¼’˜Š¸¿<ž½OP1a@±ØI‡Œ@ÀÆB±ïc±?à?˜¦ü‹¹w"@5üC·Mç?e¶ý ·úL@ŸSö²¡(Y@½-î)f­?Áf÷p"À¶ê°pC翣ŠZ­¿ŸåøF@@‘lÎÖ#@K€N­‚ÝUÀâ} [Ma@¹1Æ(±¸¿l=ȳËe2ÀAù$™¿?à?X\b‰=(1@¼u´¿¥õ?Ï÷ç·T$f@Rx‘ÞûL@Öf bP»?Ÿ"-!1À‘ú!õÕœõ¿DèCyÚD»¿£Õ^m%åKÀ}³Á¼â/@±ÔLÖô™@ÀЇh±¸¿óç¢öEa@ƒ‹ïX AÀ»ç7MÂ?ð?»g9&ˆé5@@‚"ô¤ùþ?Uœ…œ=`@¶`b…2l@ôzt®äÅ?ÈŠ_Õß5ÀþKïëþ¿ž0ˆfýÚÅ¿Û69cP@$ðM÷kq÷?Í"3h1uhÀZŒÿ†bq@ÁØé&È¿FV­26”CÀ'0WÚ·Ð?ð?vºN¯”WD@ѱ›rÁ @ûC'gÍx@_ƒ¹÷Å=`@Yf˜‘SÔ? iàÏ“NDÀ'û}é·´ ÀYsˆ°JÔ¿_-ô(r\ÀÒRÃEÛC@’¿SgLÀ”ù dÈ¿ÉÕÉ[q@%.¿ð+)RÀúóâZÃ?ð?%n_Ì9@èÐéÊbS@ùîç§òb@S|@õ¿po@²,C)—Ð?R7À9ÀyS)›ÎIÀv¨PøÏ¿,ñ†a2’O@ ))‡ÿ(Àâë¸kÀ¤wgWxq@»º¦%]Æ¿$n¢h[ÈDÀg¸í†¥Ñ?ð?׬˛ïG@ÞI‹ðÁÛ@´©‘î¤{@¡.5j!b@MÝI·Ý?«û TäGÀð@FÆÞÒÀ–ÉÀËH©Ý¿]ù¾%]À¡q·% H@vh÷dJÁGÀw>DäX]Æ¿ÜÛü$­pq@ ÞÝÜíCSÀ“èk6œ Ä?ð?²~ÅÑV)>@Éζ‚ ^ @Q:¥+-d@ú°S“Krq@φ¿êî ×?¾VY>ÀÊqÂðP À1š+z׿¤¤îoæN@€t¥$¹_9À†:˜hbÌmÀ9…{åŽq@bœNËمÿå iƒFÀ&˜û¨¨•Ò?ð?µ¿ï±àøK@µôÿt@Ì0«~@|Îad@|-+Ÿ›`å?ûzÂùêKÀäm]ÁîgÀü¥eÀûUå¿P0Þ]À¼Äj+†L@ ÊpBHCCÀös4 †Ã¿W ëgÛ†q@‡=M«dTÀ»Ü!Å?ð?O:Pü„A@o1´ÞOì@rôëó6f@bQ\iÄGs@Y…áæÕXà?ÇX ´ä{AÀž~~‡ãÀË6)ZPà¿%T­x‚N@à? 2µLCÀ?›iwRFpÀ†âg¯j¤q@¬^Vsì—¾¿Ÿ­ýBGÀUz2PˆÓ?ð?9ßE1>P@•£þVIa@sÁÓ¡3ñ€@á?ØMY6f@\A3ÓOî?"³©BÃ5PÀRK=QÀørÔ@î¿§á7}ô¾^ÀñF5/Ÿ¥P@s6µÝ=À²5Øq;˜¾¿ÃÇN¦¬q@C»/²‹UÀ"þÆ?ð??$Àéog0Äù?t¶ÔÆ?Àpô&¬â¢¿D…¤"ÁP@ßânM*ÀŒÏ+ùLº?ð?\òAmzÊ#@¼7Ð7Pá?óÁ_,(S@»º½Ý:±`@6“`nJž? áâ<Ä#À컎Já¿%c«vv@ž¿j}¾ƒ~KS@QŠ-®™âP@·I‹\ž*`À§Î(ëÛp@âj!5†Ä¿®¢.0³;Àÿ¿~A:ØÊ?ð?j ðÞC54@8@ Dn­ñ?r‘„°&to@uú@FYS@$WÙ#rí®?ñ/ϧä.4ÀÈLÂRÛ§ñ¿ ǵ£±ã®¿¡l÷ø_À¯¡ý†ÊN(@FKç’çu\Àrˆ j†Ä¿й…@Ôp@\ cCLÀµÊÌw]:¼?ð?Nðm3(@“ïUXuè?‡`ËôÁU@l¼iÎc@µ¹8Ú ¨?Ë·£!þ*(À©vÇ è¿ r‘/¨¿è¿qåAS@«hð„ÙÔJ@Ë)vÁ=•bÀ(Ð{ãîp@';¯/ÌÅ¿`\0Þ=Àˆ¡ËÁIœÌ?ð? +8±ñ‰8@;w3¯tø?];å(ãq@Ç}Xù,ÂU@~sà~_¸?Ëþï«d8ÀKwv)lø¿Õ ¦W¸¿î™4Òq_Àšƒ¯…÷Y2@R$qކíYÀéSq÷gÌÅ¿fc.L­çp@­ÊH’!@ºWÙHæ?ÇuKx³V@Ì¿ˆ<á;@5TÉ(C¬?QèuüŠ!ÀT<k¤?æ¿õÃo7¬¿ŸõPH3@Àw‰Ü¢ @ˆR¼ò­5ÀÓF߯¿¦¿H4Ž4žQ@¥|¬)01À˜ø ±?à?ʱFê<Ï$@o›Êׄí?«Ò ;EO@ÏË7 5Z[@$J*Íï´?(ßtÆ$À÷wñÀwí¿Mã çƒæ´¿$ýå«~ÒB@7‚&P>Y@é¤ N¬ZÀ9 .,a@Y=w$¶¿ü¬OM2À^•"“Á?à?Ky´ÎÃ4@T2Tà tý?x[^µL\i@Ì¦ŠøQEO@ÞDsMäÄ?`Sˆô˜º4ÀŒ!ØVgý¿^ÖèÛÄ¿ÛݽðÛƒPÀ£ŒÊþ3@Ù!W½BÀÿ`WB°$¶¿¬tRv:$a@G µº+?BÀ”Å´± Â?ð?¤ß°Efƒ8@žïËGâY@S¶Þ¢²qa@Ç:€n@Øò]åRÎ?€?ܸÕw8Àj”Ê.ÁPÀZ é~οß/4•zR@ð×8ÔV迲泹lÀ‰P¯ Aq@ìÖÚ°äšÄ¿²±_Õ^c@"fƒèíp@’ÚHMðÕ?IÂBé<À´ª0èÿ ÀÞ¡riåÕ¿{š¬ìJ?R@zB&,Àˆ.‡ÃèboÀ8 PkVq@7)o’?Ô{&Ž(ÀÖЩjè\׿+дà?’¿€ •ýoöU@K¿d¬ W@| ƒñŠ_ÀŸ¬a¯µ”p@ÓQs¾¹Á¿Ûô}jx7ÀPѱzÀÉ?ð?zÌ•*1@äÉF3¼˜ê?Þ—Ñí†l@¸¤ñÝkO@C’‹š¤?í@ï@¬%1À|¿â‘ê¿ZC¦”¤¿üÙ‘|aÀ²í^&‹ã@|ô8ÅaÀÙÄÎåÁ¿6©øØýp@!½µ«JÀÏVCx‰˜?Ð?·S^’Ý·@ñYØ—™À?3´¹QÒ)2@½ª^P6A@@‰;ŸÏ_q}?©ÍªWæ±À4rìqM”À¿jŽ}ýg}¿\Íçn]ü5@œ%^ƒ·‘3@£³I,çAÀ§ìp©Ö§P@^Uƒ0N ¢¿–| #‰Àƒÿ/¬{«?Ð?”ª`Òjù@Cj AÉ™Ò?+gü“GP@¯Ù7*2@2Ésïê~?Œ›ð„»òÀ<¨ˆœÛ“Ò¿s| ©y¿ˆÒðÞâ¥AÀLíg™G @ï]Ó#èM@À³ñ‘H~ ¢¿Ûá"ú© P@O¼µdƒ—,ÀoOf!énš?Ð?¡ÄE%zê@ù[`É"Ç?aʲüÐ4@+š8§ ’B@3yxf&F‡?|š@ÕlâÀˆ-MnÇ¿\0`àø=‡¿VoÐ&~õ5@ÿF¨·ñ0@ÔÑ8jJDÀ¹Oã2»P@Á3½ñØ£¿{5*X™¢ÀgÒŒƒ;­?Ð?âL ¸$Z@J¹Hû§ŒÙ?c/îð¶rR@ƒ„r2Ñ4@ïaã¿™?Œ:DÀ¯ÒÏ.GØ£¿YÜ£³P@"À´¡Œ.Àêÿ"Xœ?Ð?µÞ޼#¾ @4Õs{Ï?·…’­“¬7@%åËNŽE@“88Ìô‘?vÝh³ À1ñÕa_„Ï¿Z8øèí‘¿Æ·Íàvá5@qsNc,a)@¨ZÁ„C¹FÀ@÷Ï+ÏÎP@ÓkÑš¤¿£ØúZÅÀ2)tDÃþ®?Ð?±ƒÛðY@VÅŒ;#Dá?_óÜÇT@ÃZÎЬ7@)º=¥£?ÐúíKNÀÆïÅsƒ=á¿”Å<}£¿t¸EíÌBÀ•²Åáh@îTŸêÁ;ÀèR›¤¿¯ôÑõÆP@Þ°ˆE0À/1z Ež?Ð?BD­v› @5´à0£;Õ?3Á­ï½:@èÍËè½G@·FRÂ>›?o…så´™À3õ%NÓ2Õ¿Ä þ›¿¬§`Gè¿5@ja¿ñ“"@ðúp4IÀU3žÍ°âP@è.C &Ȥ¿=mã3¯ñÀS°ãÛjc°?Ð?ãæ‹™R"@S/'Öšç?¹Ï_OEW@Èaº4¾:@¾±Ý­_­?ôÀÑØû!ÀÏÇö÷æ¿MP}S­¿o†ü,iBÀyí³ÕD @^y¯õn9À9h6¶[Ȥ¿A\‡0ªÚP@pþ`¶I1ÀÄ•ççúÀ?ð?5«/`Á3@ø•ï®~*ü?C7ÓÅs^@ÑUÇS›j@Ä7Ç#Ä?Ü:Î+–¸3ÀQöÀöü¿æÛçð4 Ä¿þdfinU@¤¥|žF¨7@~¬O¸íºkÀ¿Ù£•Ýöp@ Û k<Ä¿_o½ýAÀ÷Ô±IÑ?ð?à †d7E@Õí$ľ?@m‡¿‰ˆîy@wW·LÁ^@ÝÓ» GÕ?ÂÝôô-EÀó c—I2Àî?7¯†Õ¿0ÅŠÎaÃbÀÎ4ªõøD@Ýl°]/.WÀ=LLŸ<Ŀ외ëÍîp@ SRÀÒÄöym¡?Ð?{•¹òBI@who—râ?ÇÇÃ@@òw@š ªM@\r 9­?!ßåVA>À Š'­ai⿲à,;+­¿—ýb R5@ýİ5‹@1®O]NNÀwïeÙ[ Q@›"Ö4Т¿°—ñSX4"ÀUþ]$C2²?Ð?J9¯.ÏÐ(@ ²“ÑA¨ó?¾ÿ¡ÆóÃ\@À¼¥QòÃ@@ÙÅßi$¿?t(äÅ(ÀþˆN÷žó¿I,°±¿¿f?ÉÜ*CÀdR¸,(@N[Ô"F5À;“ÉÀТ¿¢× nQ@1Çs«a3À]2cGî¢?Ð?Í!áˆ@@—ØRâç?†¤ \¡B@‡A¡±uP@Äû«î´?ôÜø2À[HÒ£oÖç¿>Q•@ä´¿æUJ5@PÛA¥û翸RÛRwPÀ¶ C}2 Q@›yýÿY ¿´å’&Z#Àðì–}.³?Ð?ÄÜšÓ•×,@’nPGù? '”4ÌÆ_@ck$Œ¡B@“Àg\S'Æ?• ºÓ;É,ÀsÝ_}:ù¿6ƒq]MÆ¿hh¡  CÀàˆ,@&ÄBªñå2À”Ñû5*Z ¿4øÅ-™Q@ŽhŽìu4ÀòšKŒ£?Ð?à¼:]Ú¯@âéËÉØšî?éá–»œD@ÝpT0R@+¸ÊL½?žãÓ«hŸÀmœgÙöŠî¿Ëy¥²õ½¿d^¶)Cª4@Î~Ô%Àè 4ÎQÀ{Žúh5Q@5· U™¿ Áƒ¬…$Àâ@wƒ ´?Ð?~Ö#šª0@®»Ác@þÃ+|a@øßôÎðœD@ç2Þ^Ï?æây³k¡0ÀSìt À¹´KN<Ï¿½•)7#DÀ‚z~•0@ÓïÓôß0ÀëäLU™¿/×ð^.Q@Íèq5ÀN¯HÕW¤?Ð?ͽ'I(P"@ïêÓN6ló?ÝiL}®¶F@ʯ“ŸT@•òMz™Ä?;½WF"Àd†Íaó¿ÿÔ9pŽÄ¿Ð¹c^Á>4@/n¡d,ÀMûŠŸ+SÀ#ÏeKQ@ –ÎôÙ@Ž¿=¬º8·%ÀäuPSú´?Ð?G‘‹§'3@2ÃÁ$ÄP@ËÜñ,c@w»)#é¶F@\>á‹Õ?#ÿ[c3À+ËßàEÀ"jøU€Õ¿Äß\ʵDÀfóÝxä 3@Wvç–5Þ-Àµ}(AŽ¿\Òÿ\ÐDQ@Ò¬D^°6À ©ã÷ëô´?ð?FÙ6xju@¬ÅÆðvÖ?Ûj’ QÊM@Íg§.¢[@l@})©»‘?Pvü¼%mÀÆÍËßipÖ¿‚,C1‚¶‘¿Ñ> T¿ŸX@Α̵ݧY@Uá´JGaÀBD+cp@s¦ØÉºr¾¿Á‚ú}u5À¨<ÛádÊ?ð?µÃ4ë¿í1@Æ.«.Nì??AŽƒ¡m@–i0÷ÊM@¬ÿåW¦?IheŠè1À:´·àÜEì¿´”8gQ¦¿Ûæ:”‚cÀp² ­@ðÍ‘Ž¸cÀƒùPh s¾¿Bü¯ê\p@×UøýüKÀÚ‡϶?ð?ܲ,ªÓ¬!@Y± `„Øß?^Zj¶DQ@Ÿ+rLË_@KÍnQ°œ?†öϧ!À²Fˆ>Îß¿Z5[ì§œ¿ôÂá¨X@˜­É#œ2V@k)oä>˜cÀ*pŒÙÛup@³'–F¶À¿>,´tu7ÀK<|šÌ?ð?”›åiqÊ5@ •Y³l¡ó?,;¾±×p@¼#çãDQ@ü«åÈ:¯±?*÷¡iÃ5ÀYçèV›ó¿- :(†©±¿.ÀÓ6µcÀøƒ’_c*@ƒ\ƒVbÀWNì¼q¶À¿½*½\np@¨Ãê4íåLÀÐ œ\Õ¬˜?Ð?3FJÃÄ«@‘êÏŸüÆ? âÑGíÕ3@Bµ$¸‹%B@))¿£–†?8‹Á¤À 1#Æ¿Û{*8 Ž†¿µM3ªå£8@ 0lÅCÃ2@ðºÂEôEÀÈøHlňP@"›¶þà¡¿xs-M~À2î´>@<é†Üž[XÀË39Tì›`@Á•KÏö²¿)Dáõ+Àw–ìŠ|•¿?à?½‘Ê!ÞA/@X¸®~øñ?T¿ü°[e@Ù5'HšF@žèö9ç©´?Òy[É5/ÀÇÏ•Œññ¿5¹×¤ê¡´¿ Æ´€Þ=TÀŽõšX°)@ÕUµöOÀqNá&ž²¿²ì["Ê“`@Šz”[b@Àxl4sœ?Ð?…Eçß.…@[KfÓKÔ?K€×fb’9@d_+æÉ+G@;Ã/I#š?Ñ.rxÀ([CÔ¿Æ¢È`š¿çØ\èÃt8@w¡ÝÂfî'@Ìr•’ÎJÀÙÉŒU¯P@Ý­ž±Î¢¿ÛBigĪÀ‘ÍÙh¬°?Ð?Wþrh{"@·~3Íç?,ÖÔý­ÚW@…þn¤’9@9jÿÿð¦®?Œr«ï±s"À£?¨HDÃ翳a5Q&š®¿kGz>”DÀ’Yó €^ @ÈV¯µ=ÀMƒ.â΢¿íúã §P@v¨Úãa1ÀC`^\ž?Ð?ï¥þá½@ô3z\åÚ?NP©?À<@äÝk oôI@•³O†ˆL£?lZ¢ƒµÀd£ YÙÚ¿XGÕéC£¿ ^†‡I8@ý"+`â5!@6¹jMMÀþ zˆÃP@ê¿;²œQ¢¿„§mëÏÀ¯È5ÐD±?Ð?—ëÉ÷=²%@$R"½Ì"ï?ºã÷ЃZ@‡]íå‰À<@Ú_paW¶?7¾¿)¨%ÀÎzË“äï¿#½ùßfM¶¿8?IVú÷DÀ«^ %$@FÉWÜ¥†;À vÿËQ¢¿*tiǽºP@ñy(wÙd2ÀkVI Y$ ?Ð?ýàn@º@ÅÞ)Ù˜á?˜‹L‚@@_Ú“8íL@(¥IÅ?¬?˜(…2@À2*|b‚á¿Ü0nùõ«¿&aœe8@³ôZY@¼³a–vØOÀlð=×P@ÁYö¡¿b²6­þ À¤(½a_v²?Ð?ÇŸiBÔL)@Cõ7#ô?ôÒ.³@X]@K­uÌ«@@Æ÷IÀ?McþÖ@)À:þKû¬ô¿Ç¹}-aÿ¿¿?Ë!hEÀÉl•-(@”-0bEj9À"3ñ!¡¿ºw:ÈçÎP@`§ÔãÂm3À¼µÿ®±?à?‹šUä)@Í*ÄB»Ãö?TWz‰ áQ@8úe `@" $Ä?‘JB×)ÀÖ]ƒc¸ö¿¼ý¼ŽúÿâÐ]ÇG@~Œ-Ær@Id8aÀGIª&Xë`@̦Ì_o­¿õk$A2Àƒ ׯ^Ã?à?xÐ2îR=@½ç ˜…È @àħ—,p@M‹µ³;áQ@ HfŽ«Ö?‹wËëPD=À,ú9¬» À!¡?2B Ö¿›MƒjÇæUÀÆ€e z<@^úXöBaGÀºkrÍ«o­¿Öºw™ã`@²m›|DÀ–²ˆo Â?ð?1Í;>@?Ïò2% @ÃuR|Ìc@¿ i‚¹q@Œ^¹Âx3Ü?ª©`>À»’ / À ”½‡Ó$Ü¿ —a…pW@ô‘_ÂIýÀ\©7ä@ŠrÀÅ4:Hq@ã o±Ž¶¿ç6”†ÆÃAÀ3·ÌkK¬UÀ–̃Ç~@Ò%Ÿ9]QÀxæU_hÀmñýÛÛᲿð?×÷L[®_Àr”}’߯_ÀÀ×VÒá›@+óÔá ŽoÀ“¨`Ñvß_Àøªl P`@\¶4«\`@]ÚšˆTi`@±-œ…H€@KÂ+ÝMD#@Úü@h‚Ú1×@‡[ØÀ é5@+=VÚ„@G„ ŸŒßd@ ]!‡'S3À=¹ê5QçÐ?Ð?I§IZ T}@\ƒ-Òê¦~@Òc§Ó§ŽAÀl榋•@Å…9€@H*é§J~À Uçh§ÀÕ"”¸?Š€ÀÌ(fËû¬ÀßX)ˆ°ã1À5)rkFÀ†e˜D¿£_@Ãu±½iÄ1Àøèw“òâIÀ˜h’~Ž„¿Ð?ªXÍEï1Àq¶‰¾2Àã»[@ÔÖ|@Òc§Ó§ŽAÀÿ¤¸ÊK–3À´C—FX…2@¦£‹ªõZ3@ñmÕ2:4@"Î?@l’èçkˆ@^„ÉÍËj,@³Êx´Ï @À¼ÊÝ6òT@f]E(&Ài+2¤™á?à?Ô~mHûEŽ@[ÅFç(@‚ zµ|_DÀq{MP¦@&ãXÓ„@‘@6уiOÀ‰Œ“–¶ÀLS^¹ÇבÀ·¼â<3ÀAó½;pFÀª‹ˈ\À¶I1Ø p@H} !±÷AÀfÉ‘zέZÀP[ÞÛ†‡¿à?Ô£L×p5À¥oÓŸçl6ÀgWT÷,g@‚ zµ|_DÀ[<Û|ïð7À‚ÓôÚœ¹5@$°e†17@«ôiØÂ8@þþv5>ö@ï‘Î G{*@ÔibºÙ>A@ŽÏ,"@`ÉÑ\‚e@RçFÕ9ÀÍ%Ð+áVñ?ð?’z)J,BŸ@]³¬ê ¡@ƒLêPx4ÀÒiKœ„¶@|\œ¢@ønM£³0 À×-Œ ª¡À•©·JG£À>áZðGÀ±aç”Ð[À¿™ŸifqÀ@@M€E€@d¤Ù˜¹*RÀ^7ŒÍ~kÀNƒ£¼v¿ð?Ì@E‰”O%À\ š A'Àü¥>Dºž@ƒLêPx4ÀáÝxÙ_)Ày1g&@wše¸¶(@iL I*@îa«Gè)@M“¾c@@.~WpT@ß!üÌŒ’5@Î Btvu@ ÷°‡ LÀ  Ù#/ñ?ð?ûîÎÂÀ$ @öâ ‡•¢@´¨ŒƒUE@o¨i£·@Ï HÏä¤@¼¨ÔÝ=À À~±¢Àø&9€Û¤À¨¤÷ëôLÀ?ƒÝó¼_ÀÛ#£E§tÀˆh™ÅH€€@èà€]RÀaÄ#1õUlÀ”„ aÌÚˆ?ð?$µz~Ûo6@³a÷èZ 9@÷r ýµž@´¨ŒƒUE@ËA…õï;@£%öG7À;­Éaú9À[ y ý<À À8Ë*@¹93–·C@@@£øŸV@åÎõÌ9@;2).u@ùÄÀÙ26OÀ#qŒŠÊÑ?Ð?jßì"®€@Âôök ƒ@íÏ}pŸþ:@΀Œ—@”l“ª½…@–uCŠVÀ%ÌáÒP˃À¡t´‰*™†À¨„Y¬&1À.{äŒBÀ*fèS XÀËó’ Ž¼`@3¼ÀJ 2À 3<3MÀŠH¹2Ñ~?Ð?7Tü4°,@ç~ÞM`0@Žïzu@íÏ}pŸþ:@‚ù¯2²2@°ûiÙÑ-ÀC’`¤1À]$Íþôn3Àö(qIÅ @x”½þ•;'@cîüv ñ8@Ò'ÀÃ@J 7ösCU@ `Cáª61À-±Ðçùò?ð?¥;{y[=¡@+ ‰‡%¤@–¯Ë¾ðe@KDY‹O¸@†*O¶.‹§@@deUÌó¡À{Ug®»ú¤À+V„¨À¬”MÏ—þSÀSNÙapdÀ°%]ÄQ}{ÀàE$Ö­ù€@½¿¡ÊZÂRÀœd̆nÀaG V¿¨?ð?[HÝⲑW@|×¥‹[@j£öÞ" @–¯Ë¾ðe@§4 `@2¬±1‹XÀÔºÏ÷‘®\À(îé’TÂ`Àlé¬0()@ +ÝŸžñJ@3ù >ãÿZ@ü„ÝG@@˜Þöˆ‰Yu@2´Â\¶ßRÀ5)vm†ß?à?‘”sоžˆ@7S·é†@6Xü„QdÀçì%á£@R,qÆQ…@Q¬¸“<‰Àðz{‡À ì—…Ú…À»´°@@n:ˆcÅ!@‚f@ó³ä(ÀÀiŽçòm@¯¾ôu(@ÀË µí”±UÀ ͤ\85©¿à?¤¨¬+«»SÀÖ$•Ý\RÀ++ Š@6Xü„QdÀJúN^lQÀ-B§ðÆ9T@ŸºÆx7ÒR@ -ƒ ƒQ@B )9N#À_J«â®—ð?çrÒûÇ%À0CœI=@ÊÅ)@ŸÀ2»IEA@K3¿a@@¨æ=ªÔ?@±*ïW#À¦¹ê£§ýú?ønùŒ>ú¿6úþà2Ãü?ïÄ ‡èLT@6˜B\³ÀïBÁ8û'à?à?,>Ã&Š@‚÷#ïK‰@ºË£›ï[À^õ"nè£@"Âñçxˆ@ÁC ÷‚ÝŠÀR|¿eý‰À/,Ç–$‰À ãFM0¾õ?—®^cà Àò†.SÂLKÀú Þ½ØÛm@9}^l‹@À^ÖVà WÀz:1Ó­ø ¿à?[Dˆã¿KÀëEÂÈÓ©JÀv¯^íYÙŠ@ºË£›ï[À¢«¹eËIÀ^ÛQL@¤ÿàdK@vv†Z€J@ðcM“QÀú»ÁHr@ÄEŒ:ª @A¼T÷@ª&oí´]d@BÕùNm1À@Ï­ ¤[ð?ð?Mèø¬÷š@°R™pŸš@üN`‹h?eÀåÖùç%W´@ó÷¥íTHš@|×” ¾›À]ß$Gc›ÀG7‰´ª ›À ¹ÖœŽ´À’>Ì3G1AÀ~5‡R/cÀx™šCËC~@1Âügº¼PÀoŒXð¾gÀ _ Î׉©¿ð?¼¨¬% %UÀ´š# ÚßTÀ/l¬\JK›@üN`‹h?eÀß$R›TÀ½c×’“ÀU@~” gyU@åíi$3U@–•¦17'ÀÒõšŠä1@Ìoý¥)T4@orSÀÅ)@‡Þ̵ ot@$`[í±DÀ½ÞV¨0à?à?ðœgÓ‹@ž[UÚ Œ@îo¯€ó¦LÀ°:Isɤ@=7%$EŒ@„ ǹ©ŒÀÑ=¬FäŒÀäÄêñIÀìlF0ÀoëÈêN:ÀÃÏ3;]çXÀæ˜VÐ`®n@Q§à+Üí@À·"v‚(xXÀó[¥Ce‘¿à?z‹xH4Æ<À±Íö½ú=Àx Ë‹@îo¯€ó¦LÀÚŠÝA9<=Àxc>¤=@@‹¶Êà=@‹5Þ®Ñ>@ÚšBÀz³=œ&@`ñy+K0@‰5Ð7Ï@  ÎOô€d@¢º¿ËÐ6Àª?¹«¨Åà?à?¬$m¸Œ@Z{•jô’@‹Zd½Ä¨<ÀÌ  j?¥@PG¬núsŽ@~/5ý Àl+n‚ŽÀMtX%’jÀ¤ãhU˜O$À¤wbVqAÀ5DPéÐ^À¤f³É‹o@šøÈAÀc{B'8YÀÙjn)ÿ¿€¿à?CHËÔ-À(‰–íë-ÀOM cüXŒ@‹Zd½Ä¨<À€ëg€˜Ï.ÀÛÆ … ú-@!Ž7Þ.@/×½É/@P”ƒÐнÀ½ÚdC‡Š,@bâh˜6@ƒSŒ]ù #@æV?v“d@»…˜¢9À#H«üð?ð?;4 9¨@o…Æô£6Ÿ@B†´‡,ÿ?Ù›÷0<¸µ@"–ûl @kð±I¤žÀ,ñe÷ À;y$ý–ø ÀŒ`–‰=ÀKÜ÷ØèUÀX‚íg·vrÀâÉ«6‹@“Ç,yOQÀï)½çýiÀ9ºŸO3I?ð?W_³¬Íï?5B·vv¼ð?0xÚù¦õœ@B†´‡,ÿ?2ž`rLñ?Ëueœýmð¿`dµJñ¿é %R3ò¿œ‹«1zu À‚W#(¼gA@ÜÖÔFCK@¹>´úM6@Îy³û˜¦t@äy‹LÀÇÀáy3á?à?I}§¸¢Ž@¢éñu|@–7Ì’žœ?@mwqZç4¦@]#}à_¾‘@ ^[2´À¸LgÀÝ%"±\’ÀÖ!Ø•0?3À»æÙ 2gJÀˆ`š1@¡Å³G¡@–7Ì’žœ?@©¸o ò2@©Û(øñì0ÀÑ4Np72ÀqKòó#›3ÀrÁQç–6ÀÌjF·4@&DHì@@*à—~±)@?ÄNËcºd@„ T‹?À€‘yLàkñ?ð?ÇåD8¨Ÿ@ÍTÀP%ÄÜM!À/ÊBÔ4H@)ÿÁy«.R@5Û—46=@íðÒ‘ÝÎt@´8Ü!%RQÀ-»ÜP¥á?à?Ìð0×\@ ‚ hôp’@OŽ²Ç¡X@MžF9§@Cx*óÉ”@É´:gfýÀÂö>O&“À‡÷ì¶••À‰<õЗ=Àè¤D_ɺQÀíb >BlÀ¬‡" åsp@„ øàAÀC;Ÿs\ÀïµÐê|›?à?œÁÑ dI@z9‘9ŸL@ST¸(@OŽ²Ç¡X@jB|8!P@ÛTY^JÀú?Hˆy¸MÀjN½Ø¿PÀã*{øÇ À ÊÔ¡ÿâ;@Ïè-D@¢w¨ºGn0@|Z„˜ äd@êHL}ëBÀ¹‰ÜìÎ?Ð?â¿zþ]w@Õ\=kÎût@üº/L˜sRÀ“ |Ol’@öýU7Ü×r@Ž–OT´æwÀh¶|X’vuÀ[Ò]FsÀDcܧ¿|@5íŒu«N!@½ã’(õ0(À6&ïäw=\@+`»oÑ.ÀjغÁ„DÀ*pE=—¿Ð?¯3NµšAÀ5ûäž?À¨ý°$y@üº/L˜sRÀ7 â¢cd<Àã2¢ò³B@JÔ?•~+@@—¹ • =@÷Ï­ U¯"ÀDkͱTð?@B wŸÈ;@{*¸¯¶n9@@«§¿ l!Àâ>À̆@ô"W±ŠÔÀ{ˆÞ@1þ€¼×âS@« ¸kÀȽ\¯ï?ð? PSjÈј@(£% ,—@喇М‰hÀ%_.BŒ8³@ì‡}=¢•@#w¬q™Àk툢IÁ—À<!îš-–ÀÀÂü3f–2@`3È­ Ñé?ý êéL`ÀB†•Zôû|@Ñ¢¿1ŽOÀf5™ÈÿÉeÀ Œ¬lC®¿ð?‰7)‡¿ÊWÀÇ-p6VÀ¡·þ„tß™@喇М‰hÀöâLA÷¼TÀ’£µdX@j²e¡ˆÅV@ïZÉBU@ÛSYtÙ[@ÀT—õLÿx+@¶W”r¾|-Àï÷K<&@7*Ò'úòs@ <K3BÀa­Òû´ à?à?þšòù˜‰@N˜â_cˆ@aUjUÔRÀ°s?¦0££@ã„Í;g<‡@Uœä&FŠÀ—Ê]^‰ÀBÞ"šÙ‡À —is‡à@¨^`1G ÀƬ Q®UÀ4ìãN!_m@úǵ=ì?ÀrÆ=otVÀÐl6tþ•¿à?±x\£AÀA6ÞßÎ@Àɇ PŠ@aUjUÔRÀ7¡ùyÇ@À²Ù¯_°B@³†¸?A@Yq‰o@@Ê‘uµL/ÀÐ÷¹p‚#@¬h‹|<ó¿Þ›ÐY Ð@uÔ RŸd@º3<ËÃ4Àƒ,]”<Ð?Ð?dìáÁuiz@ˆ¯íÕ˜±y@°!‚…™6ÀÏýò%ô”@ÛÃoÙ»þx@âЕ0%{ÀíwÏ8hzÀFMd°yÀðËŒoG,ó?™–ýë½ À’±‡Wa=KÀOæíÄ]@‘ÎíÐá$0ÀÀü3N$GÀ»×ŠP9{¿Ð?· ȬP&ÀñŸÓTµ%Àò„xFÎz@°!‚…™6ÀÌ<E6%ÀÔËÖIï&@x¬Ùþ O&@ö_RP´%@ŠRHýó¼À±ÊËØ/š@´µxL@@Ÿž­Î@ÖÀÎT@ ëžúëg'À8L:žRpð?ð?Àˆ”€‘C›@ËJÖfR›@2jfü‡[AÀùßë´@4?æWíš@ÍŠ¿ ;œÀ'D¡â¸â›Àå[U}¶›ÀÀëý­úÀ^ìÄ{gIÀÅ£é}pÀ²`üT-~@ƒ„óÌ€SPÀ»ömÃÙgÀ\ÊP]Dt„¿ð?¨"1çÅN1À;UÕ½Q31À²ÌtM»Y›@2jfü‡[AÀ‚‘§ 1ÀX—%áÐ1@Ê›B£Î³1@¬ÒÚ6º—1@8„ÐAí<À‚ÉkÓ‚>@S"ÅÐÕà3@z›‡ƒqÑ3@)Ô#Y&t@÷ýÈž JÀQFJHø¤Ð?Ð?(—’ž'|@>«ß‚L™|@¼þRÛ@o“º—-ö”@’£úrÅ }@ÞDóµ}À³å~”ày}Àåï3Jäð}Àp©.4®*Àt÷»ˆð1À»[6D­uSÀ¶‚"*G˜^@3êžtä0À±û†Lñ”HÀä/&¡ \?Ð?BÊ×£1@67°h(c@˜ƒÀÒ®ó{@¼þRÛ@ìñˆ–Á@⃩ÿºÀR7qÙÏÀ“<4‚#|ÀÛæ‚a˜À/ôé÷÷_"@¦ÌïÅ‹½@+¼0ó@ewv/é8T@÷< ìÛî,ÀËP~ŒÚÐ?Ð?zmà¬í}@ìnDrc6~@Ñe²E—4@´Ê“ÄÏm•@qÀÉ b@&ñ~ÀtØ9hÕ/À ]ô2€Àxf&YŒÝÀj'Í9s5ÀãÿàφVÀ´H,>³_@¿šs °0ÀÜëÈóUIÀ‡?¤=*x?Ð?¾©Neôö$@E/]ºßÆ%@úLCXOœ|@Ñe²E—4@ Ùž&@Q™ló ¤%À¶hòð«z&Àõ08œY'À£r•ÅÀÐ}¥©$ª%@@·!£™X#@“z$E4@úû|ãKT@B“j Ó/Àó±qŸñ?ð?7¯eÍž@ºë}™ñŸ@q9D‘ûa@´Úéèµ@hçîNù @ Q῟À™Q×pƒ À¬ýE}ªŒ¡ÀèÛœD¸>=À? 8"ÝYÀmy'ì²yÀäêI;{u@‘nbrîÝPÀéU‹ÛjÀœÐ’ûÉ¥?ð?»M¢ƒR@iÜ×GX¬S@ûü QT@q9D‘ûa@¡LàQèT@ά?–»#SÀ´RJ#WTÀžU¿ÓUÀŒPöbpy=Àt+Gíw!I@Ø©šaXG@2§¾Þ•=@Öh…_t@: æ«õgQÀèE‡ÖHñ?ð?Oë—‡Ÿ@5ÏÛuæ @‡ÍØñäìi@(‘SÜ’g¶@eQÀOb¢@ÑU€ À3 Áº€¡À3'vk £ÀèÇÛŸCÀ—Ê M^ÀÂ%ÆMø|Àµk¨wç@î[@î˜ QÀé±°‚²éjÀ­;Nª ®?ð?Ùž2þZ@Y†âä\]@ñ‰ïG}ž@‡ÍØñäìi@S‰ŠêÛð_@¹wŠ„˜ô[ÀŒýÅkíh^Àjbh6Š`ÀÒIြ>À¦Ú¢J¦ÇL@Ñ2“¾O×J@Ó†ËË@@y±´«Õst@E†Ö(]òRÀ‡.õ.´Wî?ð?}·ÖL1–@c( >“@ >ü舱pÀn#»ͱ@¹N="¯@æéž#¨–Àì^ÁÀcuÿ _‘Àx©+wísF@kPâOØLI@~3"Ÿ¤QÀŠÿqôq{@ Š ÛjMÀ%U >kcÀŒZÓZ†Wµ¿ð?D@zUL_À$nA¼&#[ÀŒ‹yǸ9˜@ >ü舱pÀ™Ïª¿“‡WÀÔS઼ó_@IÄ?¢L´[@\ÅmX@%Š”؉KÀÆþq~K@z)¸FÈNÀj,á±€U@qº®mns@ íVIL<Àš«  µî?ð?¨[ÔãÝ–@ö)F6”@G“ï°wkÀ0ÁtRç-²@‘'í :Ý‘@Såtf^—ÀñV:.¬§”À‰¨ÐgŸA’À¿›jÌC@èVzï=A@ÚÌÞÂv[À“©dË{@_§UßÄMÀ¢>´ldÀ†Ië?3`±¿ð?tr¶ôYÀö]ËVñVÀ ÉÄX˜@G“ï°wkÀ¥¦ÔH GTÀÕ^Úv•†Z@ÝR$ÄrW@ñ ߸ÿ¸T@€Bï ñqJÀ™åÚh%@ÒÜÇ&ÃR@ŽØ”!êP@ S›ŒIÀü% 'Y/@?‚f BÀü~j{K(@¬ÉšùŒs@Ï´ŽXçBÀaUþþuß?à?×ËLÔPˆ@²ÍR^†@¬Ä¯DËNÀ½—ðø¢@iç+[”„@칈Ó2çˆÀã"AVé†Àù ^}@…ÀhZÓÙ\­+@ úüf®øÜ?pUÖ¯XÀ¦gmè…l@i2HHx>À+]+©?UÀæ¯;}”’¿à?ý ´ß<ÀŽ3×¹‹:À¡Ï\Qzb‰@¬Ä¯DËNÀŒýV­ªp8À-¤?S%“=@s…Š)£5;@t¯Ž9@_€†Ú8ÀŸ®*Ê£ð$@Jkþ¸k(À*–qLº§@°8!6õœc@Ðb?#b5À[pJŒØÏ?Ð? Þ5Zy@È:‘w@¹>sœwí0À,`ñá…a“@Æï®#v@« ~‰iºyÀ kY+xÀü€w´vÀpsÿ’ú@È{¹ÈÀ%‘1¿>pMÀ`Åjç\@¶f<Ñ.À¬ç´êåEÀð )íc©t¿Ð?àóeäžo À*lè,_áÀW¨óåÁÞy@¹>sœwí0À39"eÀ‚$çÛÛ @•úÉP«@2‹VÀ@½#Ù°»_(Àñ¶+‚@YAV Àâµ|Ùœ@<Éáhs­S@?Öž©‡ï'À_P7™aÐ?Ð?S³'ˆÊåy@bÅ$Ÿ¥Úx@¨†êý…" Àd¹rÔΓ@ù!¶hDÚw@|xÛs˜zÀiÉ »…yÀ ±æ—u~xÀˆt$ÎÀ @(Žêš*g Àr•k©‚QÀô~»ÏºJ]@y¼xšN*/À/I®Â|‘FÀM®á£Õ‰O¿Ð?#¬0ªœú¿AŠÝ&Šù¿X:ô bhz@¨†êý…" ÀÕ?³‚ø¿å»«ðÙSû?첆ùô9ú?ášuÜk+ù?ì{/K(ÀjÐ0¬S2 @^¿ÔÇ…së¿&æØ@ÅÌF’{¾S@Ó¥¬l*ÀýG#cXQà?à?‚J›ì»¾Š@@Ò̘0<Š@T¨E?15@mÞ7À=¤@¸Åv"¼‰@¶]6Ù‘€‹ÀHÃeTúŠÀ,V-.¦vŠÀði 1êÙ@˜;¹±Ýê8ÀEšxÎddÀi#ý°m@ë±@¢‚?Àãò…BWÀcõø z?à?· Ÿ%@JR@fš$@­¢{YÆÿŠ@T¨E?15@ ()Œ5$@7å?Ö˜%Àu㧨k/%ÀtœÈ$ÀUF²`ø8Àðã¥üŒL3@ä ©A@Z9gnñƒ'@JÖþ*Ðc@_^i¾E=ÀWó= 2…à?à?Ö†•³~¡‹@AZóÀ“·‹@'¸ü©f I@ef¢¦°¤@\&+tºÍ‹@Í ü^tŒÀo+ÿ‹ŒÀ· ~R졌Àÿkޤãï¿Z´Xgp¾@Àt™ôd_gÀ½ñÄÂn@Ýp¸sÚ?Àý(ùWÀx†;E 3Ž?à?ûLõa9@óg?p,9@h5u]¥‹@'¸ü©f I@8ÆŽ@9@s}/Fè×9Àª » ì9ÀÙˆÝ|G:À,Á'u³R8À¢‹ªB‘6@›jðSW@¿ Ø_*¤*@h…>©Gâc@ö÷˜À9@À`¯:éõ¹Ð?Ð?)1z¢aŽ|@«ü%Í¢N}@— ¾4ýC@Üö/>Ù&•@ÁGŽRò~@ ÓPQås}Àœ¶Ð°/:~À•w(±ÀPôhnˆÀW’óAI5À(xv»9sZÀ/ÐLËø„^@!m³2ß0ÀŸÿT~µHÀ©tË$£Ñ‡?Ð?Ÿ`ƒ­@4@tö—_É4@.u šY|@— ¾4ýC@Ú 7÷T5@€v³Jtã4À.’ p5À.]šj6À@šìšÎ(ÀIDÞ*@hÊLr˜@L¸Clã@°7j^õS@êa©½Áx1Àjñ E«ïà?à?ÇË<±…@äÔÕM@&¨g¼”²[@Ö¥ÿo ¥@êÆ·²J@Ám•†’ŽÀåH9¥æÀjÉuü÷ÓÀÐW#p\"$Àhç~²†dIÀìÿ W¡mÀ¯'¸ƒòn@ïÉ—DD@À6ò–ЛwYÀôë§EU ?à?ÛõÚ4)dL@ÒµNe'ÓM@£AÃò@&¨g¼”²[@Ö×ýn­TO@qfxTMÀ($S{˜ÏNÀ"Óî.PÀÂsbü9À@ xýîŸ=@‘¦Bø ,@tQ =¡0@.ÃbM”d@u F:ôôBÀ3óNìÈÍ?Ð?ã`º Bu@ë6Òœªq@ÎçžÞNÀCj]z5‘@$Ý ›˜m@çÍI=~uÀ4LžßrÀÄ/Á)nÀ3 ÷¯h-@€ÜµÙ€r0@nµ¹ÖÚã6ÀÖŠ¹åذZ@k»v6,À¸Ñj/cBÀM³Àä‚“¿Ð? ˜è’´;À_]Ë«þ47ÀN³â„Q[w@ÎçžÞNÀ ‚… dp3À|;S0Ú;<@º€O¦7@ð‡NÏ3@ãæ˜Ì 2À:˜d´•˜ÿ?ª ™ËË<4ÀGÔ<>ìi@B»”S@¡Ê÷ÄàÀi+Q×$î?ð?Ív@{i»•@ù<ÈW³Ž’@ ü»8NhÀÀ˜èˆ ’±@Þ½kl±@E!È+–À_Ñûî’À¨ÂÚ,&*À˜¶¡e÷òJ@^ jÖÛH@S©Ï+J:`À2ºGxû{@ä¬S+fqLÀ—‡VòbÀÛÜ‹„5¯¿ð?ŠMDqU“VÀì‰r‚GSÀJ‡8ò±—@ ü»8NhÀɼù(vPÀJ°fZW@Ð5"µ&ªS@CÁÊP@i§…’@”QÀ¥{Iè&)@-ÃÃ/!QÀØë42%@ÖX»}€s@JÄ|w¸5AÀKøsž€Þ?à?Fˆjg†@F7n‘ƒƒ@jœ×`WRÀËÅ­zò¡@ÅG7É(ÿ€@‘î2+ªà†À¾d¸‡-íƒÀHÏšU%[À»–(_€I8@qsÃ&Ã0@‡~)UÀLެ]k@\µÂ Ç<Àli*£þ…SÀJãH’L—¿à?›\eÉd/AÀu¯Î7Çï=À+vA=}ˆ@jœ×`WRÀ«¾uE.:À þ_afŒA@³ X·Ë‘>@½7švL :@ B;æ15AÀ¯ ÔK‰!@Ò Æc<ÀòbH9 )@ëëEf+c@ Ÿå‹3À|n€¢ÞÎ?Ð?Ƨ $‘w@ÏÙÜJoŠt@Á$¡yZ8À~†_U’@¯[¥ÚLBr@ôñËSŸwÀ…'SøŽÿtÀö†”ÉiªrÀ:‘FÞÅi%@+ùŽG:@ÆçÉ AJÀÁúðÄ¢·[@»Xõ i-ÀŽQ#óVDÀFœL(r‘~¿Ð?¾u:¤c'À²ššx$À"‰?e¦x@Á$¡yZ8Àp)<[2"À_¸]>³Š'@å/9í$@^±|Aš"@ Ⱦ¹ï0ÀŠ G0tÉ@ÕÊ•ð×ß&À?yÁP@¥ECÀ:S@ž§–Eñ%ÀDY·*>ß?à?ò¢ê_-؇@ÆÂ'ýš¤…@¥*]ÓÂ77À-N3¸‘º¢@‡hyÒ¥ƒ@®ÿ±zgˆÀñ»TP­&†ÀUüùÛ „À¬XsEQ2@Mr`Ö1Ú?O,‚‘Ђ_À«OÌ?9l@ƒ´jíhq=Àþ<ê2Œ»TÀïó ]Mª|¿à?’ªèØ+&ÀùȬ@Ò$ÀËVDh[üˆ@¥*]ÓÂ77ÀòÖ"-D"Ào±&@la÷Ę$@€êvZô±"@[DF Å@À¡órÒU,@Iô%×Í»1ÀuŒUÒU"@ø˜e•Jc@™êKi8À™‚Â&EŸÏ?Ð?2y:ßx@Ð}‘yÓv@¼Ydúfêø?†R ]ó"“@z˄۱*u@ÄK†9yÀϱNxdwÀ¶•“;аuÀø©;ßvù@­¡¬hÀLÁuExRÀèÐ?5Xs\@ôHAéøÅ-ÀÊÕ! Ê]EÀa&ØO–ó@?Ð?ŸîÛq è?N iÉ!Jæ?Ÿ% _ÿƒy@¼Ydúfêø?cNÇòU«ä?—3Ñ¿¡è¿OÒôq]׿¿QhJWM.å¿ø'™N¶0À†ñ|Ž7!@Mð£ÍøÀ÷ª&"þ@?žTgíZS@óò_có*ÀKà?à?¢£I l‰@·{¬,ˆˆ@h‹p¬ŒP>@œßZƒRŽ£@¹iÃÖ†@ºÑÆàŠÀ÷X¨×‰¹ˆÀß}Ã2_o‡À<7WÓ&@6‹Ž4+0ÀšÀ©$T":VÀÜÖƒ/Ë‚?à?“Æíu-@ȘÞf,@Eó™øŠ@h‹p¬ŒP>@îXhDŽ*@”h¢T.À,ýò›¿,À^j¶?+ÀfÚMgîÄ@À˜AJ¾-4@Ú©?|BM!À4´S®(@fÛànÏkc@—ฑ=ÀêÝ 53à?à?;ÎÙCŠ@¨·®]u‰@U`Œ2ß3M@e¾¢õÂü£@±Ðyn8­ˆ@)|# óüŠÀ—ÁåÇ(ŠÀÐP º [‰ÀðúÈÅjS@ìâ ’Š8ÀÊ:Ü=e*hÀ£!js*9m@ÖÍðP‘m>À£ 5²VÀÛœ+E|Ù‘?à?Ó!ùOÑÊ<@„ô>)wè;@,Ì;¿°»Š@U`Œ2ß3M@mÁÞ} ;@à¿õǺ•=ÀÙõ l%­<ÀíTu‰´Ë;Àšƒµ…Lò@À“µU¯l7@ü¢ÅaîþÀ½d‡ç+@èm]íB}c@Ÿ¢t„!@ÀžK ÐHfÐ?Ð?f›™=a%{@WQëÁ¨ëz@‘£á*4ÚE@½)ÌYn”@d–‚k²z@ ì0+ï{À"Ѥų{ÀŸMdÞx{Ààæ°&²Øû?êEáÜ{0À*“Ô¡'[ÀwºYÌÍŸ]@}ú‰À.ÀE•›CdGÀá€MçkŠ?Ð?÷ɘKË5@bHéSôœ5@æ pê”l{@‘£á*4ÚE@ôbî—ÿn5@a uMm6Àò³kU=6Àx¼üR6À"Šé?1ÀÝy®YÖ*@TúváÒä¿nÉ^Ó«!@k/fEOS@<}6…1Àp $šBšð?ð?´Ï_çœ@M4ƒ†6}œ@óúÄ"xVm@—²ñ)ã´@ Hp§'ëœ@ŸÉ­ôìœÀs«Œ•\À× ž(äÍÀ€;ÞÝü¿uÒ®¹TÀÖê70þ=~ÀF£K³×~@¬FW¥õOÀ]¨»RhÀdRm^ñޱ?ð?ʺ™*¿›]@È™ ^@ño3Í,œ@óúÄ"xVm@ùBâý^@gì²=äƒ^À2.Œþ¦ù^ÀÃ^G20q_À Ã’t[¯QÀ1?c“-lN@¨GZÍžµ @~0+û”¯@@'áh§û¡s@êƒ_©ÏóRÀ²–Ái?í?ð?CMgrŽ”@JÇÄ =@s§¦XójÀ¬.u餰@£8Χ‚KŠ@Á×ÔÒg”ÀÞüš—d…Àû_´Ž‰ÀŠÀ²_®_R@ÂèÖÔIT@&ªkÝ÷Û[À×òÓT“ùy@}= CôáJÀƒ2O¹kaÀ‹á8X_¾±¿ð?ï¦oCgXÀùQtuÂSÀõà¢È§ˆ–@s§¦XójÀ¶²KþOÀ°fþMßÓX@ù,^ñT@Íœ'WFP@E¸œ}.VÀ0vddãh#@Í΋£ÀóXÀï+’Cv"@x° þ¹±r@žÏ!©ÏS?À %Dgê—Ý?à?eiÑɪ„@µÈ¡)@ߺ•ÏÁSUÀ;‹¡þ @Y._È])|@’ÈÀ&Æ …À¶Suã(_À€â˜„…­|Àð{JÎì@@ž¾ @@?Æ:—RÀÈQŽœJj@tßÂÚ3;Àôêû•9óQÀVîÕ®áÉ›¿à?Në3tyCÀ\g°ð@ÀcëmÞ†@ߺ•ÏÁSUÀ EO‰:À?ÿܬ×ÔC@òßö‚^@@žÆeŽÖ;@òÛ9ÊEÀ¯—\bÀ@Ó2¶`FÀ¢F_2ˆ@½ ¥¿b@û:XYÝ1À¯iT~ÁñÝ?à?ð™Ë~N…@?'eâ‡ð@ÅÃxJOÀL%ƒyîZ¡@fÿç5~@5Ã=ú·…ÀbEXI‚Àß¾½EË~À_¦˜Œa?@.I‹DTW8@/òzRFeWÀýˆR¯ÿj@è{A¬Š…;ÀâÁùUô~RÀ–›`¼ºþ“¿à?ô·Å•—<À þ]ér8ÀïÎEI«?‡@ÅÃxJOÀÁ6Á‘›D4ÀÔßí›$=@Ä24Ÿ‰8@ËîS°ò¨4@–øKÕÚ}EÀ"Q¤¶R#@kþsŸ7CÀîiÙ@ýŸ•a÷Íb@˜plÖ 4À[®åûLÎ?Ð?Íʲê÷ùu@+÷¦„âr@8Ç83À~ûE'⹑@'¹Vh:p@¾«ÝËlvÀ#«;1EsÀ5W7P3pÀÀÔ­ ¶,@¢^²ÐÅ_ @κRZLÀóHöÈóZ@w+õNíÖ+À€ý7¢CÀæÎ¾5x¿Ð?Ù)û6U±!ÀEœ‹pOhÀ±ë^¼¸¬w@8Ç83ÀZïE:!ÀÒ§1Ç "@9ºÓ0@3³ý©@Uf„J5À^* Ž@êÓ剛0À,b±}g@øe;e·ÜR@𫺨šr&ÀÛívh¤©Þ?à?ú+뀭†@œ¬Eæƒ@ ‹®Á¾y*À†ƒö-¢@69–f+v@8é\g›*‡À:ž0þ T„À=dújÖÀÊOõB¼Ô9@ÿúµ @Ü:“Û»`ÀõÞ{Lk@!q®‡í'<À5ðfqÍ£SÀÂ+ãù rp¿à?G›¾lÞÀ 6ìñxÒÀí‰bîñ%ˆ@ ‹®Á¾y*ÀrœÃ&ÀU¬—g@xø ÛJ@»£#µ@çPT1EÀŠÐŽ4.@T\ô÷“\<À-Ÿ\Ôú"@à;òëëb@ðêÐâìÕ8ÀÔðéÊÏ?Ð?0kÄwfiw@¾.ýt@ƒ]_üÄ@°K×€’@‘mDvòÐr@³ôÑËñwÀ$]¨ƒYwuÀ]HÖ‘>sÀ¼ùÕäº&@€ÛdrÞÁ?¨.Zˆ_SÀÃ&2©³¦[@Jͪixx,ÀTRE=DÀéŸ8Maá_?Ð?e*—‚@åI’@©5tµ«x@ƒ]_üÄ@È€Ecå@ÇaÏ)w À`}¾µ\ŽÀ¯ª%H3SÀ0Âêi}35ÀbYÑHó!@! báSä'Àáž'§§@ÜàêœûR@zì„ ÇJ+À…J@r|gß?à?ΧÕõ-ˆ@=’ÝiK(†@eú†—kC@#¿Pç¢@­ƒÔëM„@Ÿ iˆÀé5CP¦°†ÀLxßÊ„Àªªn;·e3@ˆ—GYfÀ«³ÄÿfÀ'à-žàl@|oÙþ}È<ÀZÔ$<¨ÛTÀjƒ{Ç`ˆ?à?âmž„J¢2@¤›'Z1@Iidèd>‰@eú†—kC@‘GäŒK/@=b`ö3À·¢%o|1ÀÇ—Z 0ÀÇÍ'FREÀQàX>Ê5@_ci'Ó3À .Yo(@ÞÏ c@ÛæÒ=ÀRmÇÈï?ð?®Zlz|û˜@«B3Ègi—@z%j¨‰`@·îº|ŒQ³@Ð(þhšð•@5¼Uoæ™À‡¬(Á›˜Àœ(ý¼<–À8 žc‰¤?@D³êÇ]@À~Žù]éxÀ˜èÏz‰c|@¡Õ!'òMÀ[î›eÀÖ‚—â ¤?ð?¦/Šy^ P@-Kö'N@È eÞ™@z%j¨‰`@-%% 0L@Ôy³tPÀŸ}˜Â³×NÀÅ ¶MçLÀ¾/rˆ UÀõUED²6PÀ;zñ‰Üð?ð?Ž•GÒ™@;w–ÓöÁ˜@J•œ•g@•ç޺ɾ³@íxBðݼ—@ 9A¦ ƒšÀ0Ü‚l™ÀLy!dç_˜À˜óú7@.HÞDHÀRå:‘“Ð{ÀŸ‘©Å|@7ÿƒ™ÍfMÀçï%XÐ'fÀªÛ€ï¬?ð?ìÃðQÛ'W@K¿x§3V@<ùéÊŒš@J•œ•g@CÆÅƒIU@í©:UåÆWÀ+Úq=$ÌVÀUJ¡·ÛUÀŽTÂ8ëUÀ…›P.8ŸK@Ö¾­Âõ9À?±¯ÕäQ>@Ÿ[7Û-s@ü{ÔMQÀjYYZ0Hà?à?so0u£²Š@ÌŽ¡3Š@AÚ&<Û^@*kI{/¤@ì9íÚû¶‰@kjß´Zt‹Àp•#A¿ñŠÀÓ‰R!‘qŠÀáš„æ‘@ºÄ‚IPG@Àe‰RÜLÐnÀ‰ÐÃ{6*m@³}¹ µ=À€¸FÛÕVÀ NïÆ½¢?à?jDþ¬©N@‰¼TÎN@T‹úG‹@AÚ&<Û^@’¬¼š¥ˆM@ü£B8)ˆOÀ ï_%(òNÀ¶qú¬ð^NÀ­›‡XÀ÷ oü @3b[—fw@™eBôDcƒÀ?tu*\~À¬°I,\ÅwÀ£IòèPE@콈Æ8€G@Uc&IPÀÖ6Òÿ’Ki@胭€¼9ÀÖ%@>zƒPÀO¼U  ¿à?‹¨CÓ ^EÀôÿøïº@ÀD‚½ûøÀ…@¹>­›‡XÀ•‹SÏ2:ÀÆCÜ©´E@©ž±þ@@üG×{èœ:@‡½ãŠO/JÀ/Pð}0â@+ Ú¸tŠMÀF¯<õS@´ü N?Yb@ÎmY),T0ÀƒHD ÛÝ?à?§.l€Äªƒ@ìKCf@Ñd1'…RÀÊ«‹°uq @~6?~¿y@DOJ¶éþƒÀâ ¹îšìÀÖ Â~ý{yÀò`I;BD@Q;nÑÕ¦C@0€ô{!ÔTÀ8Á"ð·˜i@±’/Ͳ :À„—`#ÕQÀ÷?°{˜¿à?¹<×ü @Àá¿ÊbŒ:À¥šÞ^†@Ñd1'…RÀàñ.z15À-US"è@@t­$þ:@Áͺ 'Œ5@u-dÖÝIÀÓ[26 @…œ`‚¼JÀ²áRÚ™Ä@O(‘K¤fb@¥ø“õ”v2À%`Å¢hÝ?à?’‹¢)®F„@R„Ëì‚€@z ¨?£¶IÀ¥UhÊ @]#86äz@Ûk1k_¢„ÀƒMš —Í€À|ˆjóÑ]{À•K–EC@ûÂ5¢Ž?@΋ւYÀkDâÝèi@h/~½¨X:ÀüŒh6&ˆQÀ —©²×Í¿à?âR‰^L7À¿ɬõø2Àm³¯Oèv†@z ¨?£¶IÀìÝÍ×Sæ.ÀY ºµ7@ A.ÈÁN3@Þr/@ÍJvJH¢IÀºƒ7ì%@껎Í@HÀ@. ð@_@&Ë5ajtb@HP“@n§4ÀÏ¿‹ê±Àí?ð?ù- þé”@ʼnRøa‘@££í‡LÀF®íúã%±@²Ç1û.åŒ@9 îþM•ÀTÛnµ‘À|¦“YoÀ×ìjàQ@ZN«göÂG@à…ãi½VnÀ7ûfÏ9z@¢÷L¦JÀ›Ÿ1D™bÀؓź¡’¿ð?¼\lŸ\¤9À|ZƒÖ÷O5ÀktAêâ–@££í‡LÀEYº¶1À€ùø:@CiBàµ5@0[ym 2@ÔH­EüYÀ'èÜ>:@¤“§¨ŸUÀ*ð;Ô 1@(¶…Û—‚r@aœfiçFÀp»¯q¡î?ð?!áä4ý”•@ «ÁaQ’@zkªS\õÀ”3Ó´øƒ±@ŒZ?^N@T›Nñ#–À¼›­d®’À–Ä‘µÀt±P˜D‰P@›†¯Ô?@%™ùﬨqÀô¡~Ûz@™_§j‡óJÀÃÄÅmZbÀU48 ¹b¿ð?‰ä߇œ Àû:ÛVTHÀ4ÛM¼Z—@zkªS\õÀaŽ6µ)œÀ_Ó]í·, @©ÈŠ#Ã@ C7f@gËã?wYÀ¯e–'Á½?@˜½ÎÐTSÀÀKs¡3@ qlV3‘r@ñævVA7IÀ?Œ«,úuÎ?Ð?á8IfõGv@û¬ŸWRs@Ó\ú%'%@H- ·ä‘@n¹ÑZÁp@pkÜ,¿vÀ$ãßf¹¹sÀ²¢VqÀ0r7 Ž/.@, £Ø @:–&×:TÀ–ÞeKäZ@Å_0§G@+À;z±•.CÀq:•G?k?Ð?¯&Q!÷­@Ä=¶åÎ@æçlʸÞw@Ó\ú%'%@±W”™ @Ãú$CÀµ!‰lÀ¦‡ 7m7À%KÁ+9‰9À.%m·Ã"@ݰŸøî91Àîýt @³C R@Ô%pº—+Àw+TiÉÒî?ð?3(\‡1—@c·f”@þj_eögW@ßy 0H²@WƤ’@fCÆ™z…—ÀïÍ&›Ù”ÀVäˆõf{’ÀxжlK@ƒñÓ[Á?ìÉ÷-yàvÀâU4%={@ ðñ{ŒKÀ 8UvÄcÀƒüwõÆ?ð?p×+~F@­µ•[Ø—C@2 ­è@žå¾yÐr@2µ€žŽ’QÀ꘎B‡òß?à?“œ!voi‰@Äv‘M ˆ@„MºÑ`!`@Av)¿¬ƒ£@pËy’Òç†@¢ÄBKéŠÀ}ùh'ˆÀû "|‡Àç¢uU0@½õÓ)8À›’ïòYoÀêhGHVl@蟧`m<Àè0=®Ž£UÀF$™pâ£?à?“î ‹5’O@~…fMùM@Q§ÇoŠ@„MºÑ`!`@±.AbuL@Ä0|˜3PÀ ^ãaÂNÀÑè€ý3MÀñ…ãõJÀ±ÚíèÈá?@*©*£Ù¼5À‰ttCº0@?eê·¥áb@³i9èBÀÏÐñ÷:Ü?à?ßT‹a,‚@Ý_Ö;Õˆ{@|ÀÅ?:8UÀ³†p˜.Ÿ@( JïÙÛt@´¸,;o‚À½Eôöî{À¤ F”(uÀê³ß…RÀö÷Ä´J¦h@SãÙŽ½©8À¿í›ROÀÎxWÅÄœ¿à?ù;·Ûp“BÀ÷yé¦ú$<À])ÃÊ‘…@|ÀÅ?:8UÀŠÚ³×#R5À¥ zÅ×B@±6ùÁŒ<@§ÌÐL‘ 5@¸¯w$÷NÀio8@”›"QÀœ³î@/v·¾Zb@¤Wšßƒð0ÀȽn¦–ŽÜ?à?2SR¶/º‚@‰(î|@ÿXÓ¬¿OÀ„Î2§gÕŸ@!5¥*—Xv@$¢µŠƒÀm`9˜Ñ^}À[A«¨œ¯vÀr†µ{G@–+M¬G@ c‡& ôVÀÚÆiÀïh@!©æ¼uô8À"ü¥Àü"PÀ“ À-CI•¿à?€”`'Å<ÀµÖþh§5Àé ºgžX…@ÿXÓ¬¿OÀ~ÙZJɹ0Àÿ eñu<@1ú%€¼û5@‰€Ú²ëú0@e/ÃÄÆÎMÀ«°wùÁ!@p3‰øWOÀÇaò:/O@÷ÓÆ @b@1{g–±3Àδ|±gãì?ð?îôä}ÆN“@íi£Û¶mŽ@Ùø%´TÀW@É2z@°@uúz`7ú‡@U.óŸhž“Àìþ6ëŽÀ£*à]ˆÀ9ÇÂ>[lV@jÙÇ×7S@ ¹>:„kÀMfÉ [;y@UÉ1%ì>IÀ3Wà` `À ÉáÚœo›¿ð?ðNm{õsBÀÛ~/.Ý=À½»ìš~¸•@Ùø%´TÀ ÏNzê6Àc9ÀB@]þÏŒ=@ ¼4/þH7@[VY¤]À$ž÷ø¬6@bãÛÕ\Àjbî|X¿.@CF ­€r@º©i–"EÀž.¼žv9Ý?à?_×ÐTjêƒ@ñÍ…¨´€@Í(³ùB›2À‘È®˜ @`–ÙyÄy@sšÿpA„À/.TB³J€ÀOÕq5zÀTx,2ÿEE@ {CÇmÍ>@N+;üQ`Àت *‰i@BˆD€ ‰9ÀXФ!QÀ$¥6dñ;x¿à?®&ï|.¿ À¸jÝqðÀ½8«ƒ#†@Í(³ùB›2À,œ ãàªÀ…Êë[!@§œ6Õ(f@9ò½Ž @’«Ð M’MÀ&^ÔâÛ+@ôy¢1~JÀcBÁ=¿¬!@»eà¸",b@n „ÙP7À—¹fÏí?ð?Zaba”@Ézñ¤á@Ûæ“ûµ#@ö`·¥^ó°@øw轂»‹@BðDqŒì”Àû2”¼Ð/‘À®@·í;ŒÀ8nCƒT@ÁxêôG@¥oêõˆrÀ«•Ç_:Ùy@6 —»ÒIÀÔ¼šò¦aÀnŒJ¤”k?ð?å•€ì@_Bér @/ü^š–@Ûæ“ûµ#@·ü?µ/@ ñû–?À:¿oú À¸Ž´ŸÀ@½éuÀ>ªÛž—+z@´³4ÅëJÀn™°5v0bÀË Ü:D“?ð?—·$[Ú:@¬ÞÙNO‰6@A¿>N—@ÏÒš6M@ïRæé2@†E£&^;À™ä®5ë÷6À‘7ºF3Àôz…gÕ¹]Àª;ƒ¹‰C@ØX…ÈWVÀraÅŠ6@ùÉè¤Hr@á@0DÛKÀ÷[gCÞ?à?€?t-eê…@WëÌŠ<Í‚@«¸{cS"K@ ½o±t°¡@aâ‡ÆW!€@k¾ÿi\†À= G /ƒÀÀ&:Cu€Àþ÷a Y=A@lgª¨q@`²·ôœgÀ>«R]K€j@ ªû‰d:ÀèsXSZ¾RÀ);r÷~‘?à?ÜÂHŽ=99@¼c ÁÁ£5@TºÍª‡@«¸{cS"K@ö‡9…¢2@ÿ†3x¼9ÀùñW6ÀÕôº8ñ2À÷ÏèÕçõMÀkC6âd6@ÚƒCªDÀ€! ’)@N—Æ£’Wb@ì³Âç8>Àü½,uŸÞ?à?½¨ª¥†@–G{WNÞƒ@éæýµ'T@Ú"Àú¢@Bʂغn@3ç!‡ÀÜ¥AâK„À/fkßÎÀ´¬0+^?@1tùê'Ì¿\BDÜEjÀúW®¢\×j@˜´ÛZ†¬:À»aÀ-ÉPSÀE椆¼Œ™?à?½âRëÖB@­æîÓè†@@¾ÆÌ^»Eˆ@éæýµ'T@^ò€h=@ŸÊÒnú=CÀå~Náâ@À7Vã$[ =ÀæC>>}NNÀêk*»9@ó@ÍõBÀÇf¶iFÈ+@å9™àüfb@, ½ðS@ÀÕ‘òüî?ð?$ïh—@48_3N•@î}%ŽÝ°j@ÃÇ@¬>x²@P]#0Ý’@EOb%îð—Àæ|›í&~•À·ãѾxK“ÀP§í@ L@I™Œ–30ÀÎ9@l}À¯rlYÏ0{@ â1(×óJÀbz’ëçcÀpŸûUçÚ°?ð?s%‰fjhY@u{Šü<ÏV@ý]p–í˜@î}%ŽÝ°j@&ÆÉåzT@ÿ€¥ËôüYÀ±©¹—–TWÀ¼žlgÌñTÀ锇!êÄ^Àºu¤JM@ó÷EÌw”QÀžox'FŽ>@¦Æ•Öêvr@{6è[‚”QÀf…ÛuœZß?à?®Y«‡è3ˆ@­Ùq§=†@3ÝöÊÇ`@gýíõQà¢@©‘Op„@ÁÂG@âɈÀ³hvâxdžÀÕVÉÂî„ÀHy¨Qjr8@dW£‰0ÀJ›øÿmÙoÀïy§£Œk@K‹u:;À[ýçƒTÀJc<ªŠý¤?à?3Ä×,P@ç&£çä¹M@F¿¤µ¢‰@3ÝöÊÇ`@Ÿ±àQK@ŸÆ\wÑPÀ(ŸîrNÀq•ÇþIúKÀþ¶ú‹˜ZOÀ~e>”àE@@!²Â¡ªk@À:¼ ›Ç·0@é©Åc‡b@ð÷a–ÞBÀʃ;0{¿Û?à?ºÐ²M¹P@ìÂM{ey@³éu—RÀÊbxñò2ž@"t!QŸr@J½ü¹uŠÀ ۲ȹyÀd¾)iÝrÀv4a¼dK@'™{{ëM@TfÐf¦TÀE.h2 h@àyh%I¨7ÀB‰àbL¸MÀ7F‡O ‘™¿à?çïƒû@À«TÌÒ*z7ÀB–¾ÌO„@³éu—RÀ‰¼dN71Àï—ÒJ[7@@€`8sÈ7@kÎ϶p1@ÑŽÑ&éPÀÇŒéá©j@ºe–½=.SÀº q?Ø’@Ÿ‰Ó²a@¾[#€1ÀÁzsÖì?ð?“ƒ÷ב@o³±T¯Š@/Ct>^ÀZÀ‘ÍTòÓ®@›13õôƒ@43®’À(À¾ ‹À€nsz­:„À 3΄›Z@Ûª=¦V8Z@ð U+ôøhÀJ†Ú+Ox@2‰Y_¿ïGÀ€e†±4Ÿ^ÀiQ$ì1¢¿ð?á5ó,=GÀA©ôÈt`AÀJ* †¤”@/Ct>^ÀZÀ;L›ü9Àu=HeG@þ²‘ˆïA@Ö_sbŒX:@˜«ka›Ð`Àÿ`rW3@´Ø³féaÀÖ2"ÄË´+@çJsÒ>¿q@ÖÖ,dÖ‚CÀèÂÝScÌ?Ð?œþ¦Ü«er@\ê–Æl@ÿ8@÷/À¤˜Žµ|y@°(8Øie@N}ºFªrÀà óœ/{lÀ[õögBºeÀu!™ïŸ9@÷ÎÖ…N€6@„^àelMÀpX“q0—X@À2…î6(À‚_8 ?À[-óªÃ @ |•d´z@ ÿ‡Õ“„À£#÷2¸€ÀQÿ‡Ñv,{ÀÀê'F@e{±Al6@‚ÜïçåÌeÀV»¥|i@ý- ®ù 9À7:>´AQÀcõBòîaˆ?à?ljN>Ú«0@ËŒÍe+@rVÒ»Èc†@iÂy”lB@’º¯Q¿&@Ìòù£Ïö0Àæ…â¯9’+À³7k¡¿g&Àp³)îºãPÀˆA'/‚E4@)°NÃÖMKÀ׿>úå&@×cÅê„ôa@N£ÿ­O<À'ÒÚc€¹í?ð?­Î;Vâ”@ì(ÍjY‘@77 7Ÿ^@ÄŠ¾©±@~ð‘œSÓŒ@m~p©F•Àv—»C¬‘ÀïÊ Ôù\À„–R¦›ÎT@FP%°a›=@-e`OxÀ¶0gÎÌy@Û‡¢Ú:OIÀÄWSUÈaÀ$>Vt¤?ð?§ýf˜ÃL@O2ì5]HG@c¬ÊGð–@77 7Ÿ^@ªU°mƒWC@¼ltù˜ŒLÀwþý‚‹·GÀÖIò3à³CÀ}îË>haÀYºj,nEG@\}ƒ¸ ŸYÀbcØGë_9@I§ÊÛr@2º3Õ­`NÀ2º> Uî?ð?X+zO”•@J%Ôv®U’@ ™¿:t™e@G&˜ä¤~±@]ëõiä'@§]ñc¿–À nKª²’À¿…ÚåÅÀŒ/•TP[S@¸Þ Kf‹,@ÆZÜ–ãåzÀ[ø^5Ôz@Ͱ_ Ô“IÀshÃ#ÌRbÀJÆÏÛró«?ð?ž9ŠT@£YóbÿP@4ïól눗@ ™¿:t™e@ø^–³áL@yÙ„fTÀ¥©O¯DUQÀj w,tMÀÂc2,ý:aÀ´ÒàÖòjJ@ZC†o"XÀ´±öñ;@òhz¹¨r@ª‚EÀ]PÀDmKº“lî?ð?ŸÇQZN–@HÅ*Xd“@ ´žl@ôy!“?à±@ùžÚªËÛ@b%Þ{Æ–À|ãÈÌ“ÀÖ¼¸–6‘ÀÒ’ÓIÌQ@ÀÈïº9Œò¿Î®Wi5‘}À ³aH*uz@ªËñ¹×IÀ®pdÈìábÀçJ;Úâý±?ð?X8j„+TZ@!3öŸãV@¢ÁÏ.˜@ ´žl@ŒF<‡æS@ô²:÷áZÀ£¾må^WÀÁ†ÏHHQTÀpæ |aÀà°¸£·M@ÿQH¾iÚVÀàm$>@tCÎò r@\Š•È“QÀP2TIÈî?ð?»ºÕ¿—@<|Í·†”@ƒozÚ¾aq@Oß-JŠD²@.iÿ>D’@71¥”—Àðäü”ÀCiÈ4³¬’ÀÔv># P@Ìí¶l °0ÀûCÿ )€À|ZTUÔÌz@‘Î2áJÀEæÕë¥ucÀœ3¹¤¶?ð?œâ `@Ÿô¶Ó_]@èe‡ø à˜@ƒozÚ¾aq@gžîþ#Z@ЦB¤gß`À1YäÈË^À–í»Ðy¹ZÀB6*ëuÌaÀ>1ÿ@t•P@g=Ý~ÉUÀâ+ˆÁ9±@@@$i1Á0r@uy_ØÒRÀR‹w¼$HÛ?à? l‹ÿ‚€@¥ãfrw@B`X·PÀ¨RëÊWB@EãP빦p@b™ë—г€À:Ë(Œ¹wÀe`G-ñØpÀ*¨†b|vN@ Rh¤Ë¬VÀ}ä¹8Èsg@‰Í¦ض6Àç´g}6LÀ^—áÛ¨w–¿à?f<ÉùI;Àx›^;a3ÀS÷ú¥ƒ@B`X·PÀŽb¹´¢†+Ào‚¥Eœ;@JÖ⬛3@ýNç¥Ù+@P.@ºú»RÀ_öÀu= @îœbY'MUÀFªòEû@\ #…sda@0U¥ 2ÀŒ;žœX—Ë?Ð?d»O£q@¤Šfõ£h@Xµcòd 6ÀÂ/`ÔÝ@¬ò|F>Øa@|Z­9qÀ÷÷®qóhÀ"hšp|bÀ,á5¢=@0ã$É‚I=@Š;;ÖäJÀ–Ŧ¶w¶W@7XiAû&À®!Z=À?qÔìIc~¿Ð?"SyùÕ"À[¡^-HÀwŠÂZ|ùs@Xµcòd 6Àh å_öÁÀø‹ée#@AÍr±Ÿ@ÑÃzW@ïJ¥ «BÀBöÞÉÚ@ùiz½äDÀÚßÖã¯ø @•6lkpQ@>G¤ø#ÀÿÆUiŸçË?Ð?ÓÉjóVŠq@¦@,·çëi@¤;2Ž'Àë‰/V­}Ž@Q™T'c@,FßQ4ÆqÀéiªÒ_DjÀÁù5s³hcÀû‚~Fй<@ ș芣9@”ùjtW¿2ÀøMj±îâ,ÀHSU¢#A&ÀFÑe¼bÀuoØ!!B@”JÀð`Àš‰¶è4@±´¢ïN–q@œTo„’ JÀ]ͪ>OßÌ?Ð?qø ~Gs@ãŠ0wàZn@"$|ÞQ6@¼Ëè÷6<@ƒ¼=)”åg@û‚ˆWË–sÀ‚èóŸ¼×nÀ8[®ÃßGhÀ±£[_;9@@œM`#-@ŒÂ6×ñ†VÀûU“ 5ÕX@â±¶> (À®´­1a@À8>vW$‚}?Ð?V—åøÙš#@îF¾ïÞ@¸ªç™‰´u@"$|ÞQ6@Ø|'çL@ZgŽ&~ë#À° ö]À€ÐƒÃÛ°À#) ÚBÀmS¿®J÷$@¼Î9 @ÀÖs²Oj5@ßõŒ/­£Q@‹Ÿ1±I,Àêh³M4Í?Ð?”ë?Wàés@f¥¤çäp@Ê¡å$fñ@@Wé`Ïc•@´º†7Ìi@=u¯ó AtÀÅ_ MpÀ‘[ %=jÀ ×.$5@8@ŒÍˆ¸«%@…Š‚•øXÀY*"Y@36ƒ³5K(À˜"Òâ—à@À3Þ@;µw†?Ð?9L:†Š.@ëÖ¹s‰”(@¥†­«*?v@Ê¡å$fñ@@©DÊbÈ#@Qì7/Àyœ")ÀÒNMÌû$ÀD òCÀ²#{´Hñ'@Û¸<,j‰>À96輦@S›t±Q@C§¸.ÀPšÒ—ŠÝ?à?‘´Q§²“„@ä€èÌ6ð€@u.@ÔW@â‘ñ @bÇ»Pãâ{@?HÚ‹ó„ÀÌÎþ?ÀànœÈd|À2HiÄ.æF@ðî <ÒP,@Ü)“òu}kÀú`ÍRqi@|rF¤Œ8Àt÷ÏûdQÀ´,÷Fž?à?î—0)H E@Ï.N5ÔQA@¤6p•Õ†@u.@ÔW@Z±Ph˜ƒ<@±íîºIlEÀˆ†L4¢AÀ°vEIj=À¼¢˜]k=SÀµœº¦;@‡Y@ޱ%MÀ–=0”½,@Þ¾ñ«¿a@,µ°d@ÀT«µ7âÝ?à?VTг9E…@±ðüˆê@J”s`]@?îa(O¡@ÿÛƒ.~@âPµ§£®…À_]SC‚ÀÞOHÄ~Àže7QçqE@äz=•e@UÉ`RnÀò¹ï¸Âi@^vn:WÍ8ÀÈNÄ¡ëQÀÚdÒУ?à? ¿[—t!K@ƒ_S/ÚF@“\ x‡@J”s`]@ÅP®S¢?C@©Â>†é§KÀi)7pKGÀN‹Q'ŸCÀÑÎÓù„SÀÊHXkT>@=´W?õKÀ:~Ôe£.@*a3ZÎa@Þs³AÀÝîë<<;Þ?à?ÙÆÝØºþ…@oî÷‚@žûó"ða@ä<ÃÔÞ¯¡@$­x CZ€@ׯ½2®r†ÀN[?c [ƒÀ×Ú£w°€À„¶C âC@à#&{ªð¿·^PöapÀ7À»I`j@ͦþfÀ¬ÿ»ê?š™™™™™é?rê!¶qú @8=-¼¯@ÁPú ‘¤@gºMn|V´@Àÿx”„¨½@wtÏ_B ¢À>®ܰÀõ!uUƒ¿Àt…x.$`@&üxp‚*ÀÚ"ôNÌ]À½ ÒÙ˜ê?š™™™™™é? ÿ+³_¡@34Ò\­<°@~€ÇÂÏ´@ÅH&œÕ‘¤@ ËGèdY¾@wì~ÊØu¢À²1rðŸ@±À§*‡¿¢ÀÀ¿ ]î*À°rFgÀ`@ÕHû£5f^À6l–=ø?ÍÌÌÌÌÌì?NÃí `¨@ÒEÅš»xÏ@ê…ICôº@ú§ÑVXIÔ@EwC™(Qô@P›â¤À¯‰C¸wÊÀW½ß-ñÀÖ3bE@¥«-Ìr‚PÀ’:õ×–â)@{Cd"tê?ÍÌÌÌÌÌì?zžG` ¹š@È [@Á@ÔÂìUÙ_Ç@ê…ICôº@HU¿Fæ@ªéÏTy–ÀO̰ƒQ½ÀíFÓ£y»âÀ)î JÜGÀØÎmþ^^@ïØÛ2KÀ+DäP(5õ?ÍÌÌÌÌÌô?DQ«@|[âº@ˆV²ŒÚȰ@ûè#­£›À@I¥t1¡lÈ@-Ž#Áot­ÀbmãUW¥»À+ίòÉÀ@\‰•}‡h@hX¡÷[ùÀßÝ ·¦fÀõž?£õ?ÍÌÌÌÌÌô?öNC?T¬@ž®¯Ù–º@Ñ|þ:øÀ@a»oãɰ@‹dßÎôÈ@À÷k¡©®ÀAÖs6{?¼ÀÒ*¸A\ƒÊÀö²2¤ùÀŠðM‡kh@"+ÌæÏgÀ"Òð€+@ÍÌÌÌÌÌü?¢²·±[¸@OõDËdß@ó1h†¿Ë@¶Ýó-ä@ûtŠ7:A¼žbŸï€´À:ÀwalÚÀk/“¢­Á”zò¹T@V&•C_ÀE©|æ:9@pöÇ1•Ðú?ÍÌÌÌÌÌü?æÏo «@¹{+›kÑ@ ÿ=£x×@ó1h†¿Ë@0¨ä(sö@da¯úÎÁ¦Àdü‚ÎSÍÀ)½fµåòÀqôžØ,ªVÀ‚´™l¬kl@=KË&ŠYÀ–¹N¬ÖÆ?–¹N¬ÖÆ?–¹N¬ÖÆ?–¹N¬ÖÆ?–¹N¬ÖÆ?üg"'WŒì?üg"'WŒì?üg"'WŒì?–¹N¬ÖÆ?–¹N¬ÖÆ?–¹N¬ÖÆ?–¹N¬ÖÆ?–¹N¬ÖÆ?üg"'WŒì?üg"'WŒì?üg"'WŒì?°YÅþbW?°YÅþbW?°YÅþbW?°YÅþbW?mrcal-2.4.1/test/data/test-optimizer-callback-ref-J-4.npy000066400000000000000000013574501456301662300231140ustar00rootroot00000000000000“NUMPYv{'descr': 'NÇLrã¿=;ä«@™4ý3îÊÀÿÑemào@ŒÏÍ|5‘BÀ¸¹…çVÀ¯B»Ç=À€.>E£ç¾¿à?–@·,5gÀKžª«dÀTØÓo“‹@¬aoŠš¿wÀi^5‹ibÀ&­$ºg@=,{‘"e@C„ v˜Òb@¨ß1€±ÚÀ[Õ§$ß²VÀ¼“ ,n@«èÌmiÀB}chÆÑf@F.¹ŽÅG@l%ê9=á?r®cûíð¿´€Ù#Í2@dÈØìc%ÀàÏiãƒg@È“W#" $@ø£­­ñM@2«ÀÝÞ?à?9÷H+Eˆ@ÅIßPAÀ†@wÛ<¥m8xÀ/ºLª —¢@_!0p¯S…@ï"«ãˆÀêmÑ„DT‡À”zfÖnÞ…ÀËJtKšwc@y[íËP@–@°VŸ¾Â<,@`ªµ†Ži@©Þ®å•À‰`èÕ(hÀT{á œæô¿îå7à0@º2èËà+ÀB%ssq`p@¸ƒ2‚CÀ1M |¸WÀ€ÓÜÁâyKÀE¨F¿¾¿à?Rv4 5hÀ'Psz$±fÀ`¯`ÐŒ@wÛ<¥m8xÀ8h[Å„EeÀv¢ðšˆÒh@Òl«\ÅDg@ XèÏe@Õ "ˆ— ŽÀ.⃭âWÀi-iXp@©Þ®å•ÀÆêDHg@ÏüBzÝ H@6‚ðø·ñ?´ïè‘E$ÀÆžèÖ|C@üâî«T&ÀYhbÈg@„#˜­$@_¢C¨=‘@J!³) Óï?ð?ÂW(Õ6š@c°[ÎÚ™@)—¦BаˆÀÝÌ«tœ³@UÁP³ €™@nMÈ>÷šÀ ÀFד˜šÀr¨û5;šÀ±8årjt@C³R §@”Ô#%î.@*';ïõz@õÿU¨¶%ÀAš¼…SyÀ"ÿÊ™¡ÒÀØ•éšëI@KÙ2o¿EÀ‰YèybÕ€@ÂúB Š{TÀZðÙŽcmiÀrwcÀc((N>—οð?@7pÓÄ:yÀq§´ü2âxÀ¶r Ìž@)—¦BаˆÀ”-¥ØŠxÀÉx¦óóy@žF·×˜y@üS û>y@<Õ-t<žÀÄÚ¿¼ÌiÀVêø­@õÿU¨¶%ÀP‘Qr Yw@´ªÁÀlQX@ƒÀHj&Q @œž.Û=À¢ºk'‚Ü\@BÌW\)»6À6qå˜<x@^º4@.ÝØæc2@E^ÒhMhÐ?Ð?Gj©>VI|@2²nPX}@á/,3Û'iÀÄÇ{ÓÈ­”@0Ò±ƒnq~@v—|Ê82}Àcû5õéI~ÀX²lÀx¶âçs§T@X6÷´ì߇@àގΛÞ?‡&?"—Z@RÕ›0ÅÀx!½« ‹ZÀ”0 ‘% ø¿¼ŸŠ«©˜2@ÁzpØ'.À¤ß"`¢Na@Ø“kL|5À¶V¾¤å7KÀ¢BÕ>´ÜFÀ̧¥žto®¿Ð?Èêéÿ‚EZÀ˜4¶/A[Àˆ•ر;w@á/,3Û'iÀ ^gGF\ÀÐ.жÎ[@ñ)î{“!\@ÓþÅ/]@Qãµ:;p~ÀaȸE=JÀ€*Eq c@UÕ›0ÅÀú“î¼W W@!.©5L˜8@¶QMD}·ò?lUñ!D-ÀXÕ©¥¨xC@ó¾éÁ•YÀ“ÐYpXX@ k>üÅ@{ åFu@Ÿ ÐxêÐ?Ð?X‰¸›Â}~@—Hû«¡€@sAÓIžiÀÁ&ÝŽË•@»úC·$‚@diÜüÉ•À†ïq j:À—õèWË‚À¹ÄPè†7U@¼ù§ªÀˆ@D}I§ŠÛÀ¡Iƒfï[@\]¢Ò˹Àäçc‰Ð[À€4‰ø‡Àô“ø8@‚ ñÒÿ–3Àù5×’Ëa@à> hƒ6À…2ÿºÖMÀ‰Ù2_f™HÀékÛ—ÈG®¿Ð?¡Á½rlT[ÀnþÃ(oÐ]Àñu5¬q€@sAÓIžiÀÞ•óu!C`À@\žôjO\@s`Ÿº>â^@¦ÄœD{Ø`@òÙôÕ¥~À(H&¨ZaKÀ2#AÓpd@Z]¢Ò˹ÀΛïéW@ð3~çFÞ8@†¯æ ø? ‡ávã9ÀR‰s¸¢H@:IŠ4èÀr ;Òð£X@xLˆùöÌ@bƒ"ûx@]§EÊmpÑ?Ð?ÐÞ¤6xj€@¼=?‰’Ó‚@ôpñ½jÀ&j½4Pö–@ªƒ™ÚJ—…@. ௽À¬éÿ h“ƒÀNV½Ks†ÀZÂþ¾U@×´R µ«‰@8â–-JÀoÑ>¸à©[@;žôƒ‹À"ÿíç!!]ÀôÂ){»™À"ðc²’@@„t$8j8À•RlÜMKb@9‚`òŽ7À^dp OÀ×£¦ü£ÅGÀw š½ ®¿Ð?çæof\À¢îbKI`À¥Åž0@ôpñ½jÀ†1\7­bÀî.é¹Ò‡]@”úöî`@"¯~†kc@8l›á Ý~Àû"` fyLÀÎ@CÉ‚àe@:žôƒ‹ÀD1ß5X@Œ²yû×!9@¡H%—¤ý? 0›Ÿ>À ÿUöíM@Æ ˜`Àõòv¥ñX@¾µxŸË@ùáz]h@÷ìòT@úá?à?L²W#±§‘@ϨûÇG•@ æ…²ˆzÀÑ Âu¢.¨@È1<†q¦™@o½Iá;n’À㬫77–ÀbiýAåÆšÀªëʰ´:f@ŽE›„¶Ÿš@wP÷|¶5À²ø]63l@g; ðþ/ÀȾ°©{nÀD¯x[¨ŸÀqæÅŠô T@Äÿ1 MÀ/‹ª€žÌr@(úLHÀ±_UŠ`À,F‚¦KÏSÀfôŸ ø½¿à?©Uí;zmÀÛÇ÷æÃqÀz7ºš÷‘@ æ…²ˆzÀ__ÕÖÇiuÀŒýµºÅn@÷²9…®‹r@oèšÝ•Zv@Ò(€GéÀ}²Ÿ-¹]ÀKcεYw@f; ðþ/ÀD`„„h@G1ŸaI@íÒÃäÂ@8Ž,R1À&xð­a@Φ,ï0»(À:” ÿfAi@½´Ú[½$@äíÜg@]*?@ú‡Ò?Ð?&^%E–ö‚@‚ èÒnˆ@%”–sMûjÀŒ Ðu™@׋»pkŽ@*V¼¹±àƒÀųX:ï,‰À§Ékè£âÀº@¶ô¦V@ÈóÕš½š‹@I°h²¨þ-Àñw+Ðî¸\@q€"› Àx¥¯ —Ý_À.#£(À‘]8†ÔtH@q«,g~AÀŽ­tiéMc@m°´½¥9À=´uÿ,–QÀSéº38ÀV_ɀϭ¿Ð?F6ÑC5Ž^ÀO_ç~YcÀäå‹?}È‚@%”–sMûjÀÄÌ“è²hÀôÞ{¶`@\•^Hd@qðóÂ=°i@Qó yêOÀÔ8 zmNÀŠK|‰Üh@t€"› ÀWto¾rÔX@HâuüÔ™9@p¡k‡w×@p` ®ÝÀ<%/3€tT@Ô0v9ïÀÕÏénü’Y@8'Í!ˆœ@èX?8@pg˜Ó?Ð?¥ØëV„@QYžÇ‹@ûô®©/mkÀMÿ‹kÊš@â8 Q°’@Gy÷òi…À'l¢ÞŽ|ŒÀ^jôL[ó’À¬!uJvÿV@Ì2¤ôšŒ@qVªîJI3ÀåEË‹8]@½?¥\ÝÀ À<ØÖD¶¡`ÀiB&šÀË]9ûKM@šœ‰ÀYDÀÃå(×Íc@$ް$«:Àœ…Õ£¨RÀ(P'‰ ¦­¿Ð?l–éÃl _À4bˆ eÀØÆú,£ƒ@ûô®©/mkÀ6N7þkÀ}g^¥`@åÇ7»%f@Ü[O‘Œwm@¨àúÊŠÀ Á5Š:OÀ+sqij@»?¥\ÝÀ À—H™Ç&Y@‘ó8BÉ9@ó ȸ@öòRJÐÀᜠÄ:MW@Œ>\¬òÀvŸêæY@lWFYb@m³8ÍIÊì?ð?Ï;sÒ”@'›*kž@ñÚÐtå#…ÀÑg3º´d°@nnxÙt‹@Ayîi}”ÀÚ¶fŒìÀi¬£õ‹ÀëéYp@Ær :n›¤@îuÇ×!@Ï*Õ…bx@§Ë'Ó& Àiò÷X uÀ–ßrÂ-ÀŒž–ò#Ü¿¬úPÎŒ8HÀ® @rž¶~@—'?…º&QÀɯuŒYdÀ:9\— JÀý·ç+`Ì¿ð?ù?™dÆÚsÀ~á½6fpÀ€!¶¬U™@ñÚÐtå#…ÀTm0kÀW2Íö8t@pBA½O³p@AÃÓ[Œ–k@ב–Úý^ÀBUe5—zbÀå-CHÎ,{@ªË'Ó& Àõô«;Ýhv@ÎsqÖ>KU@˜ùðáÜï?8z_H‹ª´?Ü™dÿ Àm|©¯[†0ÀYbA©w@¨[ŸA«Æ*@ö¸/ø˜@­ZTuc°Ý?à? šÚ´þÈ…@àË'dô‚@?8F¼(ŠuÀÓ«3~P¡@gt,cb}€@ZRôŒ>†À@º“ßYZƒÀÌí‘]Ö€Àî’—œ`@o=q­J•@1SgR–ø¿úÁ³6ˆÙh@ÐA’b:ÀUû¡¤ªfÀ)ùçÊÁÚ ÀÚ•4>*ñ@7R–Psn?ÀÆo¡‰o@tlF¶3BÀlKÄG™UÀåðÝÉçF<ÀåðÝÉçF<À<ã–¿/¼¿à??ÏÇ’lµdÀuø{SbÀ¥sÚ›Š@?8F¼(ŠuÀà˜Y_Àµ§œwSÀz†lc6®m@ÑA’b:À…æÍϧf@øºìÍeE@âÕ´Fºð?ø]d9A–ã¿öNÙA1@rãƒ!À˜¾[S@g@g—@±¬M˜Z@±¬M˜Z@¶zèœÎ?Ð?v´Ã÷ûw@ö×UeÕ–u@Bæy<ïeÀ ŒW·G’@õˆÅ%Çs@Zðh»ç!xÀ ‘´—˜vÀ ud‰Å@tÀõ¦¿ö¨Q@_.‚Ž–†@Ð×}ÆW¨ÀZ‚0ÑUY@I1[ÕHÀ…oÛÜwÂWÀ ÖdrÀÈìu©:·@ Ëè_¢™3Àp«l§U3`@&CŒ¿ð2ÀíBíè>1GÀ@@ˆoÍ:À’’R6¶¡.ÀŽŽwtÿ«¿Ð?#LÖlå”UÀ¿—Wi_ÅSÀ|È!¶Ñ·{@Bæy<ïeÀ_PëϼRÀ©Ã=µœV@‹Cô>T@L?Ä_ŒR@Bæ~º}À)cÆõtDÀD-áú’`@I1[ÕHÀÚmÑz éV@/4~×µ5@UÙ€€è?,#þcÚüã¿¸ÒÆ2@ÎoAGÀ»ÅŸÝ‚W@¨-¢51< @fqŽ¢y@u8~wKõ?Áè­%Ï?Ð?ëÍ)ê.xy@?Ù,„x@_]_•SfÀX~y—èH“@4á&¯w@}Gz‚)zÀn|xÖƒ:yÀ´¹2r TxÀœZcä—”Q@ÆvØ[N̆@êþÅFs]ÀÏýƒNåÖY@®¹Þ~MÀŽ¿µ»üçXÀäˆ8 óJÀl¡% /ý(@)â!+TÇ7ÀÏuÇæ°¦`@½£ëâ3ÀûÌWú"ÞHÀêÁbëÚŸBÀ%­íŽ0Àö´V6:Ï«¿Ð?x¸±xVÀ%L£vi«UÀ¢%"îþ|@_]_•SfÀéÙiuåTÀOÒ\%W@‹6‡IHBV@ˆ˜®¸ñvU@Ú³ê}ÀÑmðHœpEÀò2VÝ,pa@­¹Þ~MÀϤŚ ,W@U»ù·»ë5@L7ÑËš»ð?¨”‹îí¿Å¦bÃÕ;@R£ß0X"ÀÌÅ`¦ÂÇW@Чô¸=õ @[Öêz@hmG¢ ßô?¢ÔŽ3EÐ?Ð?Zü©þã{@•K·‹µç{@`]/\oµfÀÎ?â§{V”@¹úo Q|@_{áXW|ÀqDôVÂ|ÀÕš×é.}Àl M R@YŒ’=Åž‡@U5)µŸÚ%À’hþÂ\Z@:´ÆÉBÀAÿ£ŒZÀö¡Ë>xiÀ@…bžü1@Ðc)—C<ÀÌüù“Œa@ôáÔùÜ4Ào{²Û¤ JÀr!†drRFÀ[´Ñ¶ŽÛ1À ·ÇŽúž«¿Ð?¬ú]-`WÀËz6Nm¸WÀ$ £•U~@`]/\oµfÀ]§QiúXÀñEARX@FãjsErX@]®¾+ÎX@m%~Àj©RµûgFÀá¯U/DÉb@8´ÆÉBÀ—‡ ›rW@»è@"6@BÝ/tõ?4pcØËó¿êõ›ãB@ã%¨ÌÀ[ŠX@è."D¨ @!æÕÄaÄ @´QÞô?/}¥ øÅð?ð?[mÏÛA©@,6п©Ÿ@Ê)fW‡À:µ‘×4X@Üsyÿkˆ`ÀÐ1S_š@Í¡óþÌÝUÀ|yRÞÈxlÀm¤í²hÀ$Pñ[9SÀ:ß7—nË¿ð?ó¿¹ÍJxÀ‰xEîyÀi" v¼Ÿ@Ê)fW‡Àü.(øN®{ÀØâ¯Ây@݃š”Ñz@Tµ™õ |@0à “QžÀ‚ÀŸÚ×WgÀ>u7.+„@LìOè)"%ÀÏõÐê»w@TÔ‚bXV@Ë ‹l@PÈ$ quÀĺ7d9úg@OŒ8@ 3ÀèØ¾,ŸXx@SBÃ=P)@`•ÀOóh)@æÝfÙõS@ã‰êãJá?à?bÃy8õ@ŽHçìWð‘@-Ïñw¡uwÀl óké–¦@‚¹ËÚ#”@v‚¥'w–À©£PŸ’À䔟œ è”À[›qtäb@Bþ¾×>e™@'á䈵BÀ¨Îº|]nk@\¥@üãÀAWƒ Õ§lÀh¯.”ÂB0À£v»]w0O@nXÌ!SÀ5CÕ_r@û"¹ÒãFÀv€Uef^ÀÞ1˜ k@¡éLEãp@‡ÕKà$úr@V%Ž>쿎Àœ«À)YÀfÍÕR™ w@#ÅwÀ=*O'þRh@S@ÕǼF@œ„øÈ•Œ@ØyUÚš‡Àñ7<“XDa@ù½uB¥#À×D%Œòh@hª d@åhŽLÈ%@OSÇéä˜@P‡=o(_Ò?Ð?¡ßóŽ{‚@îö²È?î†@¾ ÞäØ.hÀ$KÙA ™@eáÓÊùrŒ@S©)WƒÀî[j´þ‡À½fŠÿÄÀQ˜©úS@­üªŽuQ‹@–¥aLC;À5éíâ!€\@±!p ¤êÀÀÉ|uÀ^_À@Ô!5ül$ÀàãþÄÐG@¥Í’r°HÀ·s‘.c@tMÙÝGö8À›ã-ófm@#—4Ì*s@BWŒGüx@è¤y'4ÀÝ®MÙ~nZÀÝ]öz@hËÏ\ZÀ87Bôh@”Û/yG@Ø<º¥½^@œÞêãÀPN(®AÎf@N+º¿¸#ÀË N Z”i@ø·³Fžê@ͧ+8v{@†UÿõÀÌ?Ð?Öæz{ÿ†s@Œ•n‚u„o@ߨ:IJ cÀ’'·£û@ –¡ØNoi@Ä{.åÝsÀºþ»pÀ­Ð(g}ßiÀ$ cL@Ö§¸i„@]© !| ÀÉ4‡‰Ô.X@˜ &iü¿û˜’tÄGUÀ>£žL[WÀ|!šOA7ο0{A+ú7À¸Î"f^@~Øi#Vª0ÀØèíg8£CÀ~ñÑ76ÀÄ‘ër¸©¿Ð?5Žçe›QÀTïÒ^kLÀÕ}«PZx@ߨ:IJ cÀš'RìüîFÀ½ôSéQ@OÅHHYèL@zON#TG@'éü}À‡-:Ô€?Àcµy’RÅZ@— &iü¿4$-BV@ÑÈ‚É$3@P£s dKÆ?ØPZ"–?¾o翉 ø¿ Ät…?þÀÆ|•ÿÁV@Ðõ7Ñöˆù?¡Ó88ó?Ob:sÝ?à?¥‰'!â'…@²ÐHaþ@QÈa“;asÀsäÒ=¡¡@Pµõ±š~@Bè&ês“…Àó¹â‘ŽY‚ÀŠò¥„N6ÀŸ²‘ä\@„u¶8 •@ʾ=Ô6ÀïïT÷¤h@‡¹ûa=QÀ?ö'NMfÀ¤:‹ÑÉ/Àu‰ä4~@:Ô;´ÔKÀÃ*Í–5o@®RÚÒMƒAÀŽ¿¦ôUÀ@ í†Í”;À8ìÖ3"HÀ[œžnž€¹¿à?däÒfèWbÀƒ2on€3_À± 6¿t€‰@QÈa“;asÀ-{+‰ZÀ»_ó_-µb@’m}ô%Ò_@Ë\Ô[@°5˜yOEÀµ ËÈ[PÀ'Oñu?m@ˆ¹ûa=QÀíÅ]îÉf@øyê’EJC@hñÖìÅ”é?ÀfOAíпl^Bº§.@¦)60hÐÀf½6pÿf@ȷϸN@ÇIµ`Ìô?ÎûŸžÔ2@h((Ž]Þ?à?æÛ ­(æ†@‹™E6„„@ʓڨ ³sÀµ÷$éù¡@Òpºa‚@ˆTõ\k‡À§r¬{Žû„ÀÀ´ì§Ì‚À4aÇG¤]@9ƞ̕@ö—žú*=Àø´”¡i@Îô˜Í;À¿|1¯_gÀ›ºØÃJÃ1ÀÌjW-@ÒÿTòøOÀ+_ÍA•p@űíÃ]eBÀDö§¾¯VÀ2h’š'JÀ2h’š'JÀ<øË¦H¹¿à?Úà·ÓÜcÀÑïæJaÀÒ—)²´Š@ʓڨ ³sÀNÆËC§^À,`~œí†c@[b Ì~a@ÖäÙy“Y_@ŒÁx¨rÀŽÎA÷´'QÀVþÖ·Èo@Ïô˜Í;À@š†Ë¿f@Ù©æÖpC@|œs5,mô?8‰ÞUàFá¿)9ãíA@ü ó¾À;v4T@g@ ~Ç6ò@ çQUlO@ çQUlO@÷?2ÀÃx@÷PŽ«;]w@± àdÀÄ7ªGø’@+ÒÏp v@uZmæfyÀ sw¥÷wÀ¥*v%"vÀ)$>‘]N@]ư½†@.¤ÿlõY2À$z^Ð:žY@kÛiÿÀsÂÏê€XÀ§$YytÊ#Àº²Ö4# (@¾Xð?_5BÀ}{Ny`@rhÿ”7P3À…Ô†® THÀç‘.BÀ4©KÐoH<À˜m“Ú{©¿Ð?×—ÅUÄÚSÀ•ž:·»RÀÆô¤£÷{@± àdÀ8à¬QÀQŒw1ü]T@npEù…7S@úeþ°!R@‹½»¢}Àƒçõ¦¸ðAÀ_»XÜé0a@nÛiÿÀѱð&W@¬S^õ—3@„QÐ*¢}ì?p«]}Ù¿d; ñZœ:@̦£Tš^ ÀØV ƒW@`¶FCÄõ?€ËÙ õ?*×Å]½eð?jšÃë"Ð?Ð?ï(ùzÀz@Dò¼z’z@ +;A QdÀ¸¥œ4”@ÞepšÉdz@ð$Xrˆ{Àkδÿ»X{À 7ñôµ){À›ùÏ’1 O@|¼ÛGD_‡@P{<;!6ÀƒUž8"Z@ÑÈ?hÙÀìD‡‡$®YÀ•ÅIü%ÀéF­¿H`1@¢ýqb±–DÀ±\u¯ï`@j‘1ØJC4À‘ö-q¥JÀxý|ÍEÀ–Hk‰…>ÀßC“ب¿Ð?3Z„R TÀ¸Ö"‹|TÀDâÙËëI}@ +;A QdÀ€†.ïPYTÀx{³pä9U@½C¥dU@$Ûœ#ñT@ž9ê‡Ó}À2'ï´BÀ‡?i…À…b@ÑÈ?hÙÀo>?]ëFW@;ªZTð¾3@´§y½~ò?U  ‚ß¿ó*(»¤4B@b¿<— Àv­ypÈW@@êò*¶gô?§Í¯¦àö?·ìÂOãî?úº S¢Ð?Ð?=Ô*qß|@º÷Wb.~@ïTÐÝúœdÀ“ž˜1•@P×6Œ@T€*ÏÐ}À¦;½½*À5ôå÷,J€À¢wÓTÓ¯O@S?àê":ˆ@àràö˜:À†¿Ò)¹©Z@ò~ª À9:‚7éZÀFÔÍZ(À/2r¹p7@| JŒ¥!GÀZ‘©Cja@Äâ>³=5Àçîÿ½ùÞKÀÍóìzGÀÇÂ\Ý¥o@ÀšÝÁø,Ÿ¨¿Ð?U-é[×fUÀX¶ÒÓ&_VÀj't›5¬~@ïTÐÝúœdÀÈ›'H·bWÀ=Ÿ_¡V@4¹vW@oìæËƒ&X@ùŒßŸ~Àˆ$-ÑjpCÀÛBí6ãc@ñ~ª Àº1¬Ó"ŽW@"`\ìæä3@šG–ϸöö?Àõœshvâ¿C¯8G@°°a㥠ÀqD‹)X@@ècŽrðò?ý.÷œô?b¿sÀ‘Úì?0xt%ñ?ð?mñüú Ÿ@ÄIñ¡f¡@zEq´¬æ„ÀMÚFrÄ:¶@ží‹òfÒ¢@Gåÿk! À«¿jJ½¡À‰8VE=‚£À~=½Â p@"† ©@.5õì¨Q^ÀRM …3{@É´+¨½N#ÀOv¬¾1|ÀêþΕçJÀ´äõLC^@]ЬÏÖiÀTBFYè@4ˬ›%>VÀÏüå¹ÄmÀô@-ïö¶fÀ\ÀªaÀåX5äÆeÈ¿ð?tt¥‘[.vÀC‰Ê¬·dxÀóö§uš @zEq´¬æ„ÀÏœçÓzÀ•当ýv@“…QàšHy@Ú«Ü.Î{@òß¶…<žÀ“ÀqKÖ dÀu\”ö›I…@É´+¨½N#ÀcŒÐ×w@¼=eÀT@NìVy¦@0ÁQ`À—9‹ñr[l@¶¦Q›-À“&Ïô6Zx@ð®&qS@Gu‡ @‹]ùî`¤ @ôÕ™h¬ñ?ð?“zd @"KwÄb£@20‹ü-…Àø£—zj·@½ ?dk¦@2á`Òo¡À™t +¤À½6,6ÍS§ÀlzIÜÖ^p@˜‹ohª@ª9WÀG\aÀ€&3<¾{@Æ,’=Ü#ÀÃ8'—C…}ÀŽé!‡£MÀÿ¦4=|ñb@V¤5âµlÀ^PhÎõh‚@óâ6KÕBWÀ²3 àì¾oÀX‘€óbÀX‘€óbÀ´ˆë¯¦+È¿ð?†þ:…xõvÀ<À#b"ŽzÀÂå6~ÓÑ @20‹ü-…ÀP„C^·~À.‹ußxãw@8ÆY¹j¡{@]È·±jõ@*Oo#ásžÀ#ÏW¦ÁdÀ‡†2¹†@Æ,’=Ü#Àßhúî#x@€7$)T@¸­ŽmoF @0À[ÓãfÀž¤¯ßøÎp@Ssz^-ÀKd4õƒ¦x@€czßP@Hÿî‚/@Hÿî‚/@{ ô`B7Ò?Ð?`Œ[ð‚@`z¨12ë…@\¬ÉÁreÀø=èâ觘@¢–m!¨Š@²ö_O!Ô‚À¾ŒÖôå†ÀÉØ°çôØ‹À$ #PP@X<#W¶‹@9yk^ŧCÀ£­?ëG\@ÍçÃ-Í@ÀÖÓw.9â^Àøû2ŸHG0À\Óo,G@]üÁÇ`½OÀËífÆêb@xÉ ]I8À’"{¦ßåPÀêZñhä.7ÀŠ/ÓÛIDÀh·lÏ’ð§¿Ð?ª”oÁâºWÀ5×éÛ\Àct3†)@\¬ÉÁreÀÂèC:^ŒaÀ"h8j]ÊX@ü„ùœ&^@Õ T_ Ub@´^½³ó¬~À¢xH®ßMEÀËåÕ8*2h@ÎçÃ-Í@ÀJ±…mrX@EowrD4@ÎV’ØÝÓ@°B‹X忇¯ÆA{€S@žÕíj Às"nºíôX@€‘9zÞê?¤ÍŽ'vØ?íó|'bgå?Áh|߯ò?ð?[B…[£@×#B÷ྨ@™ÁóPÑ´…ÀáNw¬ó¹@2ívã-¢¯@pø@h•N¤À¥}EC™õ©Àhµ¥–±—°Àq©@º¯p@ÖUAÆÀ¬@`QÚÕ7fÀáIDW&Ì|@„ Cus$Àæm…ë"€À°5©ÓQÀg!Â…™Õk@ê+>("uqÀÿÐallƒ@Éôpí NYÀ;A¹$ôqÀ—ÖØn©eÀÆ«8ZE´Ç¿ð?Ë©,}xÀÄóNÀtÙ zr¢@™ÁóPÑ´…À亿`„À®às3‘°y@yÎ’k€@—@:4 ý„@ً슂çžÀÔO%ð¤¿eÀbä•H´‰@‚ Cus$À*Ïþè-Ãx@ ©51½XT@eØKÌy%@P™9±ñÀWK¿Œ€Bv@0›‹›'--Àó޾@Ey@ ™äÿv@×2¿íd3@[¬/6VÌ?Ð?)Ð 3÷r@Žwa1ïm@ ò56aÀЇ| ³@¿ÄÕ Ÿg@c„B» FsÀ ßJx knÀjD‘ÞhÀP¤ëÛ},H@<$Nîy8„@äÏžwëŠ2Àì¼¥1ÎüW@cƒgŽ#¾ø¿wåBvòTÀ6Cb:‹Æ$À T^| 3Ø¿¿¼ŸècÎAÀ*3£\^@eáÈ‘Ñ30À?¥V^r4CÀ0}CÛ;À ©pܧ¿Ð?Š/äÍ‚õNÀöF "nHÀòÝɲÓrw@ ò56aÀýáï˜9GCÀW”Ø·uO@×™MÓH@ªUwL—C@ï¢#ì]Ý|À–Ñ9Àî/b/IYZ@dƒgŽ#¾ø¿СY V@‹$qçî 1@àñÆ6Ë¿qb×]kp?Lõ©‘ú5ÀÈâ¼cK6Àˆ°Ôà€„V@’°šæ,¼¿ ŒÚ³±?}‡*Ðõ7Ý?à?žBw„@×À×W@nablxDqÀÇJüôh¿ @æSº"uw|@Ö•Aò„À‘³Oï_mÀ{7ýdöÿ|ÀP'†¹X@ð‰’ö)á”@ô¤Œ™ÏáEÀöÌìã'ph@Š} g À–Ù®FÃòeÀxDÂY7ÀïP~"Ô-@ü$4uÚSÀÈã\(Hän@‹³<]AÀâÚJ©TÀ~꫚zé:ÀÐgî©FNÀÎÚäÎÜÙ¶¿à?º,/`À¤4€mËZÀ>ܨˆ•ˆ@nablxDqÀêK[@@!L!¶V@%glZ´À*óÛÛW¼JÀ eµq.Ìl@‰} g ÀäÚß›Yf@;È‘,I%A@0ó¿ÀÞ7XP¢?˜H/ÏÐ*@ö2…ÂÀa4Áf@€2T1·&Ý¿ÍO~l9m¡¿Çšàš³¿ßÐ×ç¢î?ð?$$"¤eD–@´ïNˆ“@ŸuI8ƒÀù÷ž*|¯±@sú%Z‹‘@9f¿Ú¿–À oˆUò“ÀÜ—*Ù}‘Àa‹ã|>@i@®´•@j•¥@vóÛõßQÀˆÏäH 1fÀï¼äó‡YÀ¿0 ¯i`Àe(¡•wšÆ¿ð?÷•Òý»pÀil±XmÀ[[,ð*Æ™@ŸuI8ƒÀ‰’¼iÀì’0¸q@ÿ‡ Púm@¤©QÃIj@—UÞ}4À‹Ûq‘ó[ÀõîgÊM@ZZ­À˜é„¯p˜v@"å³³7=Q@2êé¯ç?@ñbf6Ì?ÐxS‰“…O@’iY¦óG"À\À@ñíÿv@ Å,•Oö¿òÿ˜ c Ý¿É=ш¬â¿bï Ö Ï?Ð?ìð¹x@ry-¹=Bv@vS#Ÿ'ÀaÀw17t{ª’@,úL1~t@4ò+¯xÀŒX ÎvÀoèèžuÀYÓß%D¾I@Í`I•|U†@>·îðM,=ÀÝ×ÜgY@µ˜•-™ý¿F›i*²XÀ4ÇÛ,À¬h›Ðk'@X2MÁ…fHÀBðU?M`@4ÑJ,jÃ2À¢ÊFçýÎGÀpÛ‡6wÁAÀpÛ‡6wÁAÀÓvŒ›Z¦¿Ð?ázД–^QÀA‹ùŒ PÀü ÓR{@vS#Ÿ'ÀaÀ|nêmЦMÀNÀ1æËQ@³÷ uàpP@ïR>ÿ`N@ÛÜ·—b}À¨SÏË>"=À‘.Ypkï`@µ˜•-™ý¿žÒÐîÙV@|™ØBU1@° ú¬Ù?À0­ä¤o¾?3]쮄49@Tç®ÖÁÀUÙÛAW@€`)bGRÞ¿«Vxrп«VxrпFEœnà?à?ÊUœZÔ Š@=}tÊV‰@±ÀIšLúqÀR‘"Þ°£@‡Ä[ƒœ§ˆ@@ÙÄŠÀþ<°ù ŠÀn¼;îV‰ÀbŒ$,1Z@ ü]=x!—@YSÉ‘PÀñ$¢³éi@‚ûÙmƒÀ[e&Û¾DiÀÍ `ŠÝ>Àÿ¿12£Ã@@¢HùŠ!êZÀž»3Âp@«,QS¯CÀÔpÌYÀeéøŠLUÀÏAàI+SÀö‘ƒP2¶¿à?~Š¸È•bÀbhæ†aÀþdLU SŒ@±ÀIšLúqÀµ/’4í aÀ02Ý‹§‚b@p ìx¯b@?2‚,†a@#DÅÛ#“ÀÔ–Ó±[DNÀ{ø$Æ@r@‚ûÙmƒÀÀËlj5g@«ÁõÒÐlA@Àì[ög!ô?@2Á*¤½Ú?oj?)tnQ@4á™Ö{*À*‰$°–„g@ÀµIDA[ó¿n7 Žkê¿ä±£ÌàÚç¿NöÎ à?à?X(øŒ@šé\OÎŒ@ÎSôÆ1rÀ öœ!ä@owkmë@Ö´_.À&Í?Ù´À–ížÃnŽÀЇ[–Z@jûú :ù—@4¶x#i©RÀ†m %¢ÀÖ¿~Zéj@¾U«pTܨ@b‚pßÜdÀBê• ‰ùz@ söèÍ À.lYú¾{Àì<¹WRÀ±¯ç[»W]@ôÖ‹f99pÀäEìU¸@nðQª^UÀe^œW(mÀ;Ò&(6fÀ;Ò&(6fÀ†ã)?—Å¿ð?¹5‚¿}JsÀ”NVwÌtÀÉ~†ÂU Ÿ@°dð$mf‚À³¬8›kvÀ/`â:÷s@o\Aœ9†u@V/ÖØ]4w@5ÈGB¥úÀ}@Í‘'`ÀQ´ºÉÑú„@söèÍ À¹‰ÍvÓ«w@kÐ@—Q@”~…à ì@aÍíÞF¾þ?`‘ô«mk@JÕô«#À¡R!™µx@0_:ã¶“ À¹&Œ !ÿÀ¹&Œ !ÿÀŠLÓ†Ñ?Ð?Íên^BW€@.0è}¸ˆ‚@™Ö*˜bÀt¯e-a —@LøFŠ…@n¤ÛÒ ú€Àb}°3[AƒÀh9¾ôÖ…Àòö¦Ö@'K@°¸¥ùòɉ@un޵K+GÀƒ;ÓÙ!„[@¶ã0¢XIÀôønŒ…]À…:LåE4ÀÇ:måìeB@—ÞT»»QÀ¸'ÅA8b@¿=>Ióœ6ÀÉ:7¨OÀÓø¼ê”ŠBÀÇöòv¿ÖGÀ™êfT¥¿Ð?qR·Ã‰ìSÀìaw™VÀ/G²YP€@™Ö*˜bÀ$æ7Б¡YÀÔæ ³T@˜_`àå’@¶ÅO+´—@§ÉL¡ñrÀÑ—H­©@ÑeÈqU»@±Ïþ* Ë“ÀÄ]¾Ó˜À£WSñà#ŸÀã­ßTP[@Rmt;Þ¾›@‹Û‰\ÀC—¼¸•l@NÌX#eÐÀ¦øËîÔÉoÀï£Ó†³HÀOó–/"[@/àty½ýdÀm軡;s@¯³ì¢HÀ(£‹ÁœaÀG‰{–H[À:ÄgîÊ´¿à?°NˆÆä&eÀÜuí‡jÀëSŽ’Ië‘@§ÉL¡ñrÀÔ u’£pÀ×™Óód'f@c½µô§Ék@^õ†Xmq@Œ ä ¤ŽÀ)Yæ¤B/QÀ‚oþŸWy@NÌX#eÐÀ"hÿ?”h@¡ÿ5þºA@1Îx)žÿ@èˆ+´üö@˜€£kªe@–%?À\VÚgÏøh@ÐcëŽîÀ%Ï7ánÀÑácóuì?ð?æÙgÐp’@àŽOƒ,zŒ@/P^¼8~À‘;ÛB0¯@ç Žèý…@©U$tÉ·’ÀØ!¬SéŒÀgƒ€S†ÀH¨ÞÔ_d@¨ € ¤@ÈZ¼è­\ÀÄ.×MjÌw@AðF tJÀî¿ZO tÀó-¾ŽKÀîç‹^x&ÀJ~‘ƒgÀp>J`=Í}@SÛç…OÀº \ŽÒÉbÀv)×êd2^Àõ Žz Ä¿ð?‹8nACíjÀ³?ÄÎcËdÀ­PT%­ž–@/P^¼8~À4·ÓF `ÀJÆ0DVk@\`ÆRe@峊M`@¨e‚RÁ¨œÀtKå-ŽTÀ¢ òèy@BðF tJÀ_°¶D@“!|ý®„@ñëÕ@À¥ý0žæ=X@úÍÅ2~´ö¿(û½Ð›UÀòO>ˆâÖ-ÀaVú ]%@~XÒu­IÀìc‚p¬•^@ O20À>íL(ˆ7DÀƒÝèŸD*ÀsJñãj@ÀØïRœ;¤¿Ð?Ö]¹ßœóKÀëù}FBÅFÀa¬J¾w@zé1Èg^ÀLOg‰ÁŒBÀTw"&rL@k32+W,G@f<»àB@ÃoVPÒ|ÀÑá©Lû4ÀxwA ŸT\@üÍÅ2~´ö¿VmÉô,5V@yT.#.@(A2ºÿÒç¿ Ë¤o„Â?bO>9Ò@ BÙªòó¿cž Á%…V@È÷v‘ãþ¿‹äP·„Zå¿­%å%±ú¿¡1ãÍ?Ð? û•g«u@Ã¥èœr@¼U6qÀ^À~ÒÀ¸g‘@à ˆ\9úo@¹ð-)‚vÀ±EY@þrÀ,vióPpÀ¼$|ÔRE@9bœ~ö_…@¢#óeãñAÀèEg÷´X@»N§ç*ø¿ûü¡æ†¤VÀ6øDfüe0À-‹^¤×{@úkÎR~þKÀpûǬOh_@à²]b`1ÀQ }ãá¸EÀaJ³lKî8À³Y)ÈÎAÀª‘†ô£¿Ð?; ðjûLÀÌ—ÇåHÀ×ë»O¬ëx@¼U6qÀ^À”Ôèq]bEÀ2ͱ’M@!l vgI@XºAûÑE@JÒÝ÷íý|ÀwºàÞøÓ5Àþ~Ø›Î^@¼N§ç*ø¿¸ZãrV@ñÌȼ2.@XtARâ¿ ®ÑEÿšÖ? „8(¢,@p€¶´qô¿;ÙÜB@ÂV@1%üd½Àö’¾tô¿„&`>9ý¿ ¬ÉœâÎÞ?à?7ØðDVu‡@œ×ñ<…@táÏ oÀ½äýãq_¢@hàöW:ƒ@d9[VkˆÀ1•åáû…ÀÃÕæ)­ƒÀrL×è|IU@dØU¸–@i+9VèSÀ þ‡ãX1i@€ò¡¥§i À îæ^ѺgÀX9›(üAÀ²Ú™ö!6@2|á¤x^Àºgø ‡"p@¾è:¬oѤÈESÀêæ!6­³¿à?ÿk)¦^Àõ¯ig,[Àjþ4h'Š@táÏ oÀ)ÃyÎý™XÀ [gSá¶^@¡ÖÏ«Î[@Þdaxæ,Y@Öj5ª+ÀŠÎù‡g¡FÀ­x\+Ыp@€ò¡¥§i Àé‘rï²f@5ÃîÙ™E>@°Èl,꿘ÙÛ9 ó?Ú^ÚÏŸG@¸ÒßãŸ×Àñ Õ”¢g@¼Õ®qŽÀãOê'™¨ À‹Ê žÆ×ÀÈŸViÁï?ð?©!´}§^™@ŒøX6ì2˜@ÕÔÇÙ‘aÀNäq~cb³@¨á—@­ÚÈ šÀåîµ%טÀ…¶¡‰œ±—Àt±'·ã€e@/þŒ jå¦@ä+pKûeÀWË —•²y@×ÞLé+¨À|LóÞÞxÀ ­Š¯SÀ2ÁR¢&P@AÃvAÎŽpÀã|È•€@Ñ[ª¸!SÀîÏcuøùhÀ†$×­¥ÐdÀ†$×­¥ÐdÀ”Іeÿð?5ëì oÀK¹«VœmÀ9›”Ýr›@ÕÔÇÙ‘aÀnu‹€>lÀÆ@Z…²Ýo@´¸ ,7en@úåLÇþl@-Æ^Ð[À·‚ry¶_WÀ14–ø1ø@ØÞLé+¨ÀEÿjeõv@~'ßôªVN@ “>™Ìùì¿€Ô„-ì @%a%›‘`@lظ¢—À\ÑŒZCw@'Ñ49}#ÀQ\¢˜CI!ÀQ\¢˜CI!À&äu{]à?à?ÞËS©h‹@,A<­ˆ‹@5ìÀˤ¨oÀ²‚vžq¤@PŠÖ¨‹@2Ì"í‡:ŒÀGï°ù€[ŒÀ|ŒÀÏžäâ¨U@e[jþ¹—@á‘¡D3+XÀ{ªÚû7j@FIæ•äÉ ÀèίL›jÀOï¯Q€EÀ·w¹o)ìE@QvST÷aÀ,¾Ÿµ• q@)ÙõlÈ DÀº§×ÖݺZÀÙ¡.ÞàoVÀÙ¡.ÞàoVÀJÀ¸ä³¿à?¯¹é.`ÀÐ=ªÛè`Àб“ãlÌŒ@5ìÀˤ¨oÀˆÃî­¸-`ÀÆä‹§ð‚`@ hsý9–`@¢\zÚ™©`@Ðökò§À8rOh‰ HÀÅž“ºÌLs@FIæ•äÉ À‚D‚U:g@oítŸd>@€I\a±~±¿ht„kÉ@(DPÚnU@0â{/À£6,­p‡g@<ˆúaü÷À=X˜öÜ·À=X˜öÜ·Àà\èÝÐ?Ð?`¡Ìˆ„”}@ ‚T™H@ȇüéè_ÀIxП⋕@Il>劀@V‚¯ù›’~Àd#‰7©*€ÀÔ³a¹þÀªYwsw¾E@E;e šˆ@žKáõôwJÀ}KÀZ@×ÑÓžâÅü¿·sáX˜O[ÀT!>åp7ÀÌÔ*Èm<@áÈ×=5vSÀäâëg‰a@¾µÚ¶5À&VÒ“‚‘LÀ¤h«¹EÀWi}¢#HÀÃe«žêÑ¢¿Ð?ûÅYçˆPÀhÍ 7ª|QÀ^UpÀ£AÙ+œ8VÀ ’Ï6ÃÆkÀ˜•ÂÓ9¿ð?L<»˜¬€qÀl’âÅ~tÀ§­,Œ  @wª;’¹)€Àw®v¯ÛÿwÀàΤ:r@ÞÊŠXu@c¶„Ûþx@ØožÕÕ0žÀøOzz=]YÀ:¢‡@ÿZö1#ÀÍŠ¥Ix@ÂËà·jN@HŸ= @õ²uC#@G@¿ƒ[r@lYr²òÆÀ¨ ÑDÉax@H€ò *ÀN?OŒïÝÀcok•'ÀlAcvò?ð?ÚûÉé‡u¢@¡¯ùÉ»¦@ra–p>€ÀhðÄ5"+¹@­Ð#Éoÿ«@zï1ÖM£ÀqcMÆ.ƧÀÉ€À’ð"={À°µ¶ùÒÇr@>Oc#!w@ãµ2A||@Mj=kžÀþ4{Ý6|YÀ ¢§¾o÷ˆ@è`5ôlÀÚ@P=gx@ÊKÖ+XN@¨L£ Ç9 @\6H f'@½úßyu@)"@̈À0ÿ ïx@ȹ4á´,À! a¥Lw)À{„>%—çÛ?à?µp¢Mð@Í~=²c#{@·0ª—) jÀœÍ£iº±ž@A¬¦¹‡t@U<Í•þ1‚À™¶>äņ{ÀРˢLÒtÀÚ £\¨¶P@•y³#Ü“@ÅÔâ‘TSÀFŽmޤg@àÅk¤ À ¿h§.QdÀÈÑŽáwŽ@À:"\ýá±ö¿ˆ£’]ÀaX´Ã¶„m@”›p}ý®>À[©lþ$cRÀH¡ìä\xMÀg~Ö¬¬ð±¿à?ÝbáÞËWÀ§ÚæKyQÀ›¯hÒYÝ…@·0ª—) jÀO¯Ï[oJÀÈŠÀëdnW@Z‡ªI¹Q@¤†vì)ÐJ@ý–Í{ŒÀcÅ“õMÐ=À†7â]ˆti@áÅk¤ À3F‘÷×e@ôõ•::@(Èuáó ÀŒÕëgõGƿᅮ·èK$Àð%:ß×`㿵!d2f@¦‹T-À(KÀy†À„qã9¸Äì?ð?aI‰çŠw“@=cPO¤@Cc’i+\zÀÅ-²»8°@+f0´¸Ïˆ@›ÎÅ+ÖÊ“À,4g¯ ™ÀG35 â9‰Àí<•jÙ`@ÅY’£~¤@ ›÷ôÏ(eÀ&Ú½D x@ÚSw7À¬Ž¾s HuÀÁ\Ò.»-RÀ¿ÃP5B$@[È~ÙdoÀÌKÒŸ·I~@"Y•PÀ´ÜVi5ÊcÀ„žçÖî¥IÀÃPFµ`À›5È…¤Á¿ð?LüŽ“égÀsWÌÍcÀÛkà!4ú–@Cc’i+\zÀt,À0z^ÀR+äOh@þ(5%{hc@†¼D˜ü^@åÿJȤœÀ\§ž°*âNÀŰÙ{@ÚSw7ÀÞ­ev@:îHŽJ@§\ˆ=>À@í³º Ìï?>YÙˆÐ-@0”ßRü‹ó¿^P§zKv@ˆÌÝ ì»,ÀL!EkÔÀ¡Ÿi† *Àþ.ŒPܧí?ð?Áœîá•@\.jš½Å‘@|»ÏÁ‘zÀDö˜Œ"±@îd@Í î@vdPhƒ•ÀÒ`¸´Â’ÀxIÔÞ‚ŽÀn†r¬ñ`@ ìLW>,¥@¡ÆEIvgÀbFIñ†‚x@ÉbºÕPZÀª÷V ôKvÀ×^x $êSÀÝÄ;âøÿ8@¢½¢ŽóépÀœ¡|ë@I)‡xæPÀ×¥£·˜DeÀU^ZXÀoêÏeaÀêµðüuVÁ¿ð??8o7&¸hÀîñ6çÐdÀ ‘q[¬$˜@|»ÏÁ‘zÀÎÕžgq‡aÀ¶“2i@T&5ÿ7e@Ó{­øAÞa@;`ÓÖÏœÀû¶ùGÜOÀú™[ËeK~@ÈbºÕPZÀîg¬' Ov@ÅÞiæJ@\ gÚ_hÀ§_t°î@Œ»ÙdjI@׬dó¿|æGí†v@°€>T`X.À§¤} ÈQ#À}³Àg™+Àê yS‘î?ð?¾Õ’ÈÛ–@¾“Á®ØK”@qS’ÀzÀê |G²@åý¿”Àáx\råk’ÀJp>cý`@Uþ5í¶å¥@f:§$iÀ]#É6ýx@¸ Ú;oÀ«´6¥W]wÀß4›:ƒÅUÀ‰£ÐM¬(E@·»N? 6rÀÖIÁEJò@@÷(»QÀvÕ€DÓfÀý¥;ó`ÀRñ ^ÕbÀAãå°ìÁ¿ð?k=Ò€r„iÀÑüž6¨fÀ†r KV]™@qS’ÀzÀEldÀ$Jz‡j@s (e)g@¤·ÜËod@2« ± ýœÀ!ÒsË\PÀ±4f€@· Ú;oÀ˜Sø1Žv@!E¨n}ÿI@XÔÕÕrÀ€¤ž¨ô@ÐÛiNàU@`çX˜Íò¿7­¬žÄv@ ~Q…0ÀÈ´Ê1L*À¿=R78-ÀL¤0#mï?ð?j?½ª»˜@ÖV!G%—@ÅE[ÅBèzÀtßÀ°³@¸3Äåø¨•@ÖÖÍé[™Àí™î.=»—À—œ¾ðN5–À“ÇVDšú`@î3«¦@ðá\CNkÀNTí|y@ÆÖN‡pÀ=­¿ßu|xÀâxÁWÀ™Iy‡lO@bsÒêQ™sÀ’:ÒÈj€@ê´§Ì|˜RÀØÜôvwhÀØï²BYdÀØï²BYdÀxE¥-P¸À¿ð?”ÿð@?MjÀ§æGhÀÔ8/ͤš@ÅE[ÅBèzÀYÀ1¨gÀD*¨÷j@|V^0Ž_@ TaG¬¤ñ¿ã¹?žw@Óô]â0ÀlÆgàxè.ÀlÆgàxè.ÀÉ[æ;<ð?ð?äÜ=Æß»š@¡Ø]‚p[š@ÝXq‰o{Àu„ ÌÑ!´@¦Œ]ü™@œQ=˜ì›À°Øð"º›Àág°€íºšÀ>äÚˆÝæ`@xXªx|§@†ÛÊNÇ•mÀ»-T²z@﬛G·WÀ–31R©yÀÓCØæ¿ßYÀ“Ýl—Ð*U@™ 3°uÀoòòëá€@@Ž(~SÀoØãA_0jÀç0€dñeÀç0€dñeÀ¶Z ^ƒgÀ¿ð?¶z.˜&kÀy ¸ƒ¯jÀå?‡+´û›@ÝXq‰o{Ày AOjÀ_ +Ȥ×k@>Åæ5sk@ö•ÒM1k@-Õ’ê^Àý3ߥÿPÀ"×› “þ‚@﬛G·WÀ&‘„¾Aw@ Eø?eãI@˜}ä5B-À("× @â7ƒ¤hd@@ûœÚG…ï¿Ásvý÷Fw@¢f48aÍ1À!Xé”V0À!Xé”V0ÀèçL[»ð?ð?·ú}ÊÝœ@¨Äàø@˜ì± {À‡ \^ù8µ@°óÉ66Ÿ@7þGµËÀ@Ô¦¨´ïžÀN3Îp À׹̠¿`@<„´êŠY¨@7³RQ+ûoÀ\ê8‘·ˆz@—áu€ÀÑ+OŸãzÀ|Ž$B!\À]Un…[@Dýu£vÀöýꨡ[@U…gNkTÀ¿­˜„ÿkÀËpAeÀÄÙ$à žgÀ _+öcÀ¿ð?ö ñÏÎkÀ-ª›ßlÀ‘ô–½¶b@˜ì± {À(ˉ÷úmÀ“šì³l@ÞëV6Ím@Ä<8Dñn@…U[Î ’ÀFv8ØÛ+QÀvƈ W„@—áu€ÀaÏŽ£¥Yw@­%¼8+ÎI@ÈHYqðàÀ2OJ€$@+âfÞMi@à¥;põé¿Æè•±‹w@†h“˜„Å2Àoí³ /ÀK¹*çD1À/`Ê 7>á?à?GFËÌé!@æµC®‘@F Ù0kÀh²ñ¬\¦@ÓÁ䘒@{z.‚ À˜c.– ‘À9â‡eD“À-?ÆO˜P@B|„JÄA™@ŸÙ{Ø>aÀÒIŸê®k@¾LÛ Â¹Àe»_S¢*lÀknÞs·†NÀ(‚ã“yRQ@2!,N^JhÀ‡Õf­Ùq@(}>y$_EÀˆý ä]À¼Œ¢²ˆÂQÀÄ6èl _YÀ9Z™±“ƒ¯¿à?޼)¯ƒ\À ,æÅÇ*_À3è=A‰ÚŽ@F Ù0kÀj\NÖ†aÀO¼‘¤Š]@µ=‰ã%`@ó]6r›¥a@Á(}¨8ÈÀ^†wZ8AÀ´)‡dY¸u@ºLÛ Â¹À¹è>™¢g@Ú!²9@ØrüS5ùþ¿LNU£wi@ÚiÛ éO^@€ü&±Ø4Ò¿ö- îÈÒg@Œ*ƒ Í#Àd¡ÿôŠŽÀl¼ÿ®>A"Àx8èÄÑ?Ð?$*ÂÄ€@aß«ÌIƒ@A“¢µ7[À;Úïíx—@¤¯;Ä/†@%ïc¨pÀžº[}‡„À{\;+5‡ÀI:·Ü÷)@@æ[ñ&'4Š@–§vÖRÀñŽU[@Iƈ“#ù¿ƒËß=}]À>ö$.ˆ@À´ÔJE@£*ÊùäZÀßðTö@Zb@D›´*X6Àxì[x4ÝOÀ ºŽ îÂ5À‹hrŽ©3KÀ7H Ùž¿Ð?¥2IÜv.MÀgkkˆÈPÀP=K¼ô1€@A“¢µ7[ÀÅÀþNSÀÄÜYN@†iT/ŒtQ@AŽ:êT@çtš~À“úÈ} 1ÀAÊè‚"g@Lƈ“#ù¿gˆîW@ñÛÐ$)@ VÉ&ê¿ e-ËsÑ@Psèá·Q@€ ú•L¯¿3dD2X@Êbá†æÀˆZ…_!ãþ¿“X³ÛôMÀ±<¤\€Oâ?à?ëý&lh ’@Îûéî«Ô•@¥íŠ5kÀw%ñ˨@ü_Â:Æjš@¶Ø hÔÖ’Àßúñ$ Ì–Àл%g–›À½]µ’jO@ÅÔÖv,/›@Ú9ˆz"écÀmÈý…“&l@ C^ýVQ Àw÷ùÈ ÙnÀ›Ë;ÛÞQÀËkëò®Y@åÒ71ÚkÀ##ÃQÜr@¡ŽojTGÀJÐ: tô`ÀZȃ+]]À!}VìÈ*®¿à? ïÇ—œÌ]Àh±î‰£bÀó¿ãÏÿ@¥íŠ5kÀáƒwRÑeÀõÐY¸E_@‘Y%ðÓb@{ñ]ŠÈf@Ó:üd;ŽÀT å Ù@ÀRìÓ<Ó•x@C^ýVQ ÀÄ',¥ ñ¶>}@ûÖAbâMÀ/Î7bÀ°ýNê£äYÀ–|›¤Öξ¿ð?âwcÀ¦RMLmÞ\ÀE$7Ä[.•@Yn(À£MvÀÉ(×phUÀ˜J 1ºc@D‰ìÊB]@Zû*;N²U@rÐ2Ü,VœÀ„+à{ ÒCÀùôyËAüx@º³‹þ ÀŸÜ‹w¹·u@ÊämW =F@vúb ø)À\fûÆ$‹ä¿:ëØt¿T:À@ÆÃVt@®~øá3Üu@º¢•î3ÀwIÁ~0À÷~ö¿çŒÌ?Ð?ÿru÷r@_g•Õ(³m@¸.7*¡gVÀQ×À­Ðñ@´Ó#™ä@g@\ðtCDsÀKA.n+nÀs<ŸgÀÂÃ^ÒÎ?:@y¬„À¦O„@É‹€o'JÀ»æ<ÞW@z¨žj.Û￘™“mƒ@}SP,+…fÀ‚žŸ>YÑ¡@f &“î€@³’ëšÃ†À‰BôtáÖƒÀzG¦þYJÀ*õç`2°I@yb lt°•@DåÀ3L^À id¤Êh@&s"th¨Àº!ÒT,gÀ@¹¨ïSfIÀ ¡·r,4@xdràê"eÀMXüê-¢o@[=#i?AÀê³²@\VÀt<§È‘PÀt<§È‘PÀÍ]K>ÊÔ¬¿à?f.l/:;UÀë0ŒDê€RÀ3÷ÑP•¦ˆ@}SP,+…fÀàzÁBR PÀ«¾¬ïN®U@M Ûî5åR@Ñá$»wP@7™¼TÖŒÀ>Ò£7z¢4Àlײp@&s"th¨ÀW[ Éjf@DïiÖ5@0­0ö–ÀœH+®<3@oÉ_¿í÷C@@W±éÞõ?mlÈê‰f@øP6BñÎ&Ào´.ý"Ào´.ý"ÀÒP!ÚBß?à??¹!”!ˆ@:dƒ],†@÷ þCñ‡fÀd§I¹²Í¢@U(tÐ_„@~€Õ·ˆÀÂﺆ¼µ†À™eŸ Þ„ÀÄwõ9I@‚—ø”r–@¥ÊåE`ÀŸl–?ÄHi@'+´´kÀ,yPphÀkRŸââ¨KÀÆ2Ó¸—Ö=@Þ)G÷Z•fÀrj©¾Ap@YØ\³rBÀjqƒ:ÄøWÀí@9æSÀ¼´ÓöÌèQÀü\û '¬¿à?Ï\Ù1ÇUÀD+4ÚTÀ•™à?à?}«@1F0Œ@UþõhÁŒ@bû.ÈesfÀ¶öùè¤@o.:ÿvU@í’ÆÀàDT’g¥À„v~ >ŽÀ®¤KíÕG@4ÿÖ[¢˜@õƒa…ͳbÀP0ÅRj@Bpض‡£ÀKr{jÀ%ì“PPÀÇo=œžJ@˜*rý‰ÀiÀgM…‘ /q@îô1ÚCÀ“áÛE~r[À±v”_ÍTÀ±v”_ÍTÀö¥²•ª¿à? PÁÆVÀÜá -ôW@ôçŸÎ“oX@ê¹&L¢jÀ¶ÞYöÒó3Àôo´Žnt@Epض‡£À~øTS3g@Îõ®úM5@ÊSe ÆÀz1iàK?@è ÖŸÊX@hPü`á ü?g×ßýKg@š#9šO*ÀëñªÃ#Ò%ÀëñªÃ#Ò%ÀŽŽÓŸ#ñ?ð?[,îÍ€jž@믕&V @Ù÷*[vÀ¶áwå¶@(¹é½{Œ¡@ˆœ×LÄxŸÀ¢3áÕNç Àqcj(¢À¬ÑëÂàV@lÀÕ!ôÿ¨@,ÓFH˜tÀ62d£iÛz@º0äCÐ À;ÍŒ“Ÿ½{Àª–Éq¬aÀ®xk0›Ê`@l¸°'—y{À:Ú\oø«@¿Z$Ñ ÇTÀÞ |ÖOmÀ¿bƦlcaÀÑ5HB[fÀLÆ~K º¿ð?Xf&27gÀ ˆ#1ðhÀdÄ4ž@Ù÷*[vÀ €è–ÀÉjÀçâ^Nh@½lÐæœÍi@l}›Ç·k@&iö³¿ ÀÞ,xÙð@CÀ2ÙH&à^…@»0äCÐ À“ï=D{w@™¯©E@¶*5Û %À®{‚z¤d1@+Íã m@ˆ6ü‚@=B±g‘w@L´ÐÝL;ÀÓ!ªçŽÈ1À¢tHJÝ6À­ aá á?à?¨¾(íc@—ô…ˆ’@Öéë§û8fÀ_•î4¸5§@áëþ‹Öô”@ \.‘ÀÛôôü?“ÀuáHKÄ•ÀE‘—¿ÁµE@¡e+Ìï™@<Çì5¶]eÀ.ÔPñek@ã‚âã´HÀÆ0‘ mÀnA[vSÀ5Ø7~¬T@àáRœImÀ+\.ý¿+r@½¯—{þºEÀ5å¦B_ÀŒP†ÉìPEÀœ·b ûWÀâND¸-P©¿à?´Ž?ršWÀQƒ×Üu°ZÀO¯•øœ@Öéë§û8fÀûßÃ-^À¹\¶„X@Âă2«¸[@áGƒf„X_@KWö.ÙÀѧDzA2À>×›¾Äv@å‚âã´HÀ(Ó¸±ËÅg@Ô ãcWÐ4@dÌ}u4vÀLã Ô–ò$@DÛKp a@LB*?°U@AŠH/+Ùg@¨°Ð–[–,À;ó“RNÀ_¢qæø'ÀrѵO¾)Ò?Ð?ÒóçYj¤@rwÎý„@óâ†.R VÀ™ç2p˜@2¶öùˆ@Ô_pàe‚À@»"‡þã…À±o›Ù ŠÀJt¥²6ÀF ™9¸£PÀ.VŒŠ’«IÀHµ×˜¿Ð?üʲ´ßîGÀq©þyLÀviPµnš€@óâ†.R VÀJªFõðPÀ‰ÜÓ¿QõH@ó>¤B²M@À‘]x»ªQ@ ¯@‘Ü~À@mU, ê ÀµÍlV2h@ré\Sô¿2{´âX@ ^#Ô]‚$@&ù}$ËÀ3aá\­Ð@~עלS@ZE—7~ó?ÞÜB,6#X@È´ öBõÀä¦[ï¥$Àš@¨Ë#}ë?ð?¿e<¤ø‘@…C¸¶Çˆ@à­£jrÀ |W‰®Â­@ÿ5”‚@é.QCh>‘Àê~‚@I*Œüin|@<”O1ÔˆbÀ­¸è%wŸ@úµ¶;Úu@ø3-ÛèÅ‚Àë %¡‹Û|Àoœ†Ñý-vÀíØEºšC@Ü/êþg"”@þ¨œË_À :ò˰g@CNÒ/ˆ¨ù¿ti܆©dÀqP¹íBHHÀ1ÕóNå@‹Ñ3BCeÀî÷A¤‡¹m@áfEµ)Š>ÀÙ˜tgûRÀ$ŒOa×y8ÀŸš%uœjEÀíäYÍü©¿à? *–bÁhPÀì{zšP9IÀ, ×”~©…@<”O1ÔˆbÀ2ùcœcCÀƒ—òª½§P@ží„"šI@ý'ŸÏp­C@ˆ_ú_ŒÀ@ä#Àœ[Ë[ÀÖ›ãLÏ–@…€…9UyrÀšgFÛdVÀXÁª<a@"ÇäFݸ[@uœã2`~V@>ÒAXŠœÀÌ£›h†3Àé'°²9}@í…Ný’ö Àû[4­% v@!=UB@$ºÃëCœ2ÀÕLnÕL@/ûð " B@Êܳeéà@m:ĵÚv@ìÊÓaVL<ÀàUíFo2ÀàUíFo2À»Ýñä(Þ?à?ËáY±Â…@¬ÿmú× ‚@bኼ+abÀZ£þ&Ž¡@öö*3Ïå@%¸ÐY2†Àae÷µ=ƒÀ£7¿oE€À–0)…¯A@àµz•ê|•@×ß_+°aÀÅ4Õa¤™h@#nÜò’&ü¿8ŒÕ4¬fÀ ìJ§·àLÀÇÊ€*-3@}5¼JìhÀU ÿõ°To@ŧã/É@ÀfŠréUÀœ2Ššç3PÀ)kóÓK4IÀÁ¯–Ü’¨§¿à?S’¨Î#QÀ÷ÜìYYMÀûPeý¢ˆ@bኼ+abÀ¤]J ¦ IÀÖ¨›€|Q@Úc‚ã9ñM@ G¾°­¢I@”í¼Ù8·ŒÀL„x…Ôó!À;\JÆÄªo@#nÜò’&ü¿ë¼ˆµ%If@žKr…:É1@bçÛÒª™"À2—âzH @Tá餢Ê-Àg« ¥Ú$ÀïElxà?à?ǯ;A7Œ‹@ÕªDx¹¡‹@óÃAàaÀ2šNwÍ›¤@RQozL·‹@ÿjOl^ŒÀåä-¦’tŒÀ?ŠHÊŠŒÀ~@«ÿáü<@àoÝ—@½?Œ×-_eÀTHKÏj@é|(°þ¿ Õ‹gÝjÀÈà›yRÀÒ·’;¹I@¤,XÏlÀ[ A³q@ §ñI]NCÀk?6SêZÀø2ÏÕ^]TÀHOB÷¯­OÀÑE›¤„j¥¿à?EסöQÀ°¬¿¦RÀš86V¹ö‹@óÃAàaÀØHªžRÀNÉkR@þ'èrR@Ú•Àû›R@­þDfKÀÕ¿ö™&ÀFà}ö«s@í|(°þ¿¡pìÀg@cÎçÑë0@'ôŒ½¬‰"ÀØÈXnÏ!@ÎÙÆxÙV@ˆ|Mè Í@Ü9Ë®g@î›CÓøœ0À÷XŒÚïò+ÀkÓqó¼%Àc¤;&Ùøð?ð?»5‚€­¼@ côèäjŸ@H(‘hà qÀͧ¸µ@äûk5¶˜ @’5ýÍŒ»žÀa¡“Å< À&ÒÝaõ&¡À)×cV J@ržt¿¨@Ú0Ë)¹vÀë°§D¥z@SßÓªÀ.â!¤îS{À0¶£gýcÀ#öÿSòC`@‘·j²™~Àˆ#+e@Ñ,¼A+5TÀ2Z/vÀlÀ¼Ù†aÀ¼Ù†aÀÛ_áí’£´¿ð?Dg/)#bÀ6¸7€)cÀº°Bh@H(‘hà qÀW‡Ž Ê>dÀh£ñ!¾b@;Ú\qÌÍc@@7VOìd@Á©”ŸÀ({ñæ@5"ÀÚü/¢…@SßÓªÀ¿ÛÕ¸Uw@øžÄ“@@F¡èT„2À{š©Mß5@ÈV²¢a¯k@û VÈxk @¢T^yRw@,T4J)OAÀŽ9UŠ«6ÀŽ9UŠ«6ÀU¶^è|Ñ?Ð?I»8œ€@†qy EÕ@ã@ÇÝlVQÀE›Vá–@/ÇÙ\Öƒ@׎–Ùl¡€ÀApë‚À·ª0”„À%"¨ Ø&@e Ï笉@3¿"XÀÞ Í¥m/[@—#¥ãÉ)ᅩëØç@ž\À¯û,âY—EÀßS…D@ÛÐ×â=`À—Œ‚Ñ<þa@zœ¦ÿ"5ÀÕ«Á®«NÀZÞ4T”â4ÀŒB®ÉAFBÀ,/Í©JØ“¿Ð?½äŠã@BÀÐWÞwNDÀïBê£ê~@ã@ÇÝlVQÀf"J–FÀÞ;HnïB@_ò¨ü`E@#wMnnG@ßYHUFº}À ”'ïö¿D3å›écf@›#¥ãÉ)ï¿Ê)¨¯LŸW@dj†¬{2 @ð).«€À»uwK0A@ž`šŸPP@˜B^ÿW•@ó• ˜W@8ê̺i "ÀRãÇ‘  ÀåæŽ_(¦À‰0ËÓÒ?Ð?^§®PsC@ÿñ¹1<6„@Æ*ˆàVQÀ`Þí€>˜@Ôîè^í©‡@M&»ÑúÀ*Ú¶Ãë …À^Å5RG¥ˆÀéƒÛ'#@ÜUöª£Š@ }, ˜YÀ¾²µŠ}¹[@'bú±†ëî¿æÅþPó]À~˃6ùFGÀ¤¤4óVGH@Šìâ:aÀÿ1“Qb@JO³;6ÀôŸÞTUPÀÕ²¬ðL’CÀå›9«K“¿Ð?#NEà-MBÀö±ÎXmEÀ<?€@Æ*ˆàVQÀ}@™?,IÀ}­Í’C@¹)úïðPF@¾½i"£ J@G¸=Mõ}À€K øªâÓ¿÷<áúÍg@'bú±†ëî¿°i2ôxëW@åM…Å@5½ãÀŒ8 äü@’J»Ù ØR@ëø@†©è@c²Õ$áW@ÆÁÆÒ"ÀÒ’§Ü°¯À"Ô›AvIÛ?à?”‘ ¢Ôœ€@Ólnü¾w@18ÞÄÍ]ÀMd‰íQ@åà7餸p@ÅåôÏ€ÀÜÄ‚xÀ²<8ÖÞ,qÀ˜a zB:@Ø”üK]“@½´g×$ð`ÀqY`Åg@Ë„#2âò¿!1ΰtcÀUÏ?o›ÕHÀÅj׌±ÀwÉé[³­fÀx-ºl@¶Û¹Høe<ÀX5­mÙDQÀ|r7¢ô5À¥³0&Ò¤¿à?“9×ò>hIÀ,¾Ê®“(BÀÈöŽw€„@18ÞÄÍ]ÀœH4ªô9Àûü@±n¶I@™nLét`B@Í7rŠD:@@_첌À RBê)ùí¿Ã.þ¼Üh@Ë„#2âò¿©_Íd{e@_3çS¬¢-@y­Ý®¾)Àá8^‚œ=ç¿Äý+Nî4Àgˆº±Ê@­ô¨Èîue@„󸡻0Àh’r¼$ À”Húú  ì?ð?ÎÒ»¤ ’@lÐ8·fD‹@N·HZ~mÀÖëbK¯@[Æpd€—„@pôWÿoO’ÀcV§PƧ‹À„†ÃŒâ„ÀT8æCCH@ƃn²·ö£@›P´³‹öqÀ €†ê„w@;A0K~ÑÀmaz‰^tÀ#5 ÒO$[ÀJºÝN¹@pqm§ÃùwÀ8B+u}@}¹6û^ÃMÀVW‹™bÀyÅùÝëGÀ|ÅùÝëGÀ«epOè´¿ð?èŠáx?ÔYÀ´ß®0zSÀÄS“ì•@N·HZ~mÀ„Nf7vMÀ6‘ž\a2Z@Ìèr”ÈS@‡SŽ`áM@ôîHœÀÿ~hÆÙ·¿­(ªw×Oz@A…@põÏÇwä@þÞ Äܧ\À'qØlM¡@>|ܵ¹~@ì—1Ùiª…Àç¼==‚ÀB&š×Ç´~À¿9;!ê3@ÖG$YK•@üCÔóœ0dÀñG56jh@·ë©_[õ¿cN{OUXfÀ–-ôfPÀªr£¶*2@ÿ ÁìXÔjÀ"Î!mÈ o@)®&a¾W@À×YÄþzUÀ¤òµß²OÀ@»¡8-<À›5[Њ¢¿à?2ƒDCUtJÀ+¢[˜üDFÀÔùGq‡@þÞ Äܧ\À[~B¿BÀ=æë7;÷J@P§$u-³F@éÜÙ{áC@Þ‚&zhŸŒÀ€iÙ,@ÁŸÔª²o@¶ë©_[õ¿Ñ°®*)f@ÉXÀî«+@%.æȈ*À4©É>p@˜Ï -g?@¼—à¼c@±Löf@€²êQÄ÷1ÀoW?+E.À£íèÀ×|ìy·ÉÞ?à?ägG ó‡@_­fÖGs„@ùª§œú\Àô ºµ‹C¢@(Ísn)‚@eÂF{ñ‰‡À}\ ¢ç„À‰;Æ‹¿‚À3ñnˆF1@œŽ\ƾ–@'_Á“neeÀî)Òåh@ ™8Kéõ¿¥a”e6igÀ'—$#¶QÀ võnH[;@LÎXÙèdlÀ*öH,Kão@×”DfAÀk< "¹ WÀ*{ ‡ SÀ®Ž^šrz>ÀŽoÐÁ¡¿à?Ýmäˆ=£JÀŸßÂ#¨GÀ‘ïçΰˆ@ùª§œú\ÀkcÐÜnEÀíçöÅ:K@+Ñ‹'·.H@bøóyE@5 ?ƒÎŒÀPo°ê&î @>,ùÅp@ ™8Kéõ¿gØÉ}gf@€[#Oï*@¿›. GÎ*Àîw²­§?@vúk”cžH@Áø\cV@|ÃÂê?Vf@S¦¥-¥2ÀzI³âv1ÀùÛÁiñÀ8â#¾¤¹Ï?Ð? ŒÑëx@3VE—›Vw@¦ùyN KÀhkAϵD“@Iµl¶"Ûu@3ÚåàyÀ…ð}‰îwÀ›ëÆühvÀB…’@–(æbΆ@;XI½ªVÀf9@ÍdY@‡f~´”Iæ¿þÇ rƇXÀemJy›úBÀÜ'é2@6—Ï ^ÀQ@ÎPc`@Ê*ºxï1Àí"@c†­HÀôërDÀm¦)#s0Àýª.ó¿Ð?¬ünì;¸:ÀzjIÈ9ÀJ˜¾••ÿy@¦ùyN KÀîóé«ìn7ÀNj §e;@8˜‡®/¨9@÷¹p8@F(6a}Àx6:Ë@¢”Þ b@‡f~´”Iæ¿9ɳhi¨V@4hnxq%@ÓjWú.À„%:öÐ@@-Ü@@žcïFÔb@e‰n0Í“V@âæ/”ËZ#À–ƒÎæa$"ÀÂä  À~ýúBXÐ?Ð?÷ùÊ´)ñz@¥FI÷ñ—z@ù„Á” ÍJÀÖ´QcQ”@gNÞªá?z@óÎvÿF·{À|œ95[{Àº$Xç{ÀäXÊìºÔ@"Gø¡‡@•^£@XÀ ãÕàèY@cÜÇk>uæ¿2Ñß´YÀ£ñXê÷ŒDÀâ~/Õ8@§s{×5Ð_ÀÜ2s3—Ù`@ž¾%ò¾Ç2À«9ýSâfJÀ©×|ŸOñCÀC£ã º1ÀS.iâ!¿Ð?;Cý (°:À‹ÒÑ’ÇW:À÷½€Éú]{@ù„Á” ÍJÀ(’ãÁ‹:ÀõžRgt;@F8§û|;@áÔï´¿¿:@‹€Xˆ4}À º‰'–¬ @ƒÉÍSc@cÜÇk>uæ¿åŽØËÜëV@HdäânL@ê"ætaÀ”hóñP@ï³d½E@áè :JŒ@ êY¬ÓV@zUl$À>¥²¦÷ ÀX5Bè *ÀÃ[ñóP×Ð?Ð?ä­o+}@Eêº×‹A~@ä×EçåJÀYµ¿‚j•@é,ÃËv@Ë–þ~À<ɦüû;ÀŠMðÓ=€À l% Q‡ @fºòS;ˆ@X'ófYÀ-oVpZ@Mˆ€ÔJeæ¿I@ ŒíZÀÖ¦b7FÀæ|?@<[´Õ`À ƒ—\ýSa@é>¶_Ƨ3Àì+¯ùç5LÀÜi>¾Å®@ÀÚ/þýá3À„ÑpÌg—Ž¿Ð?ùäʇ:ÀdKïyÇ–;À;Ë¢]«Ì|@ä×EçåJÀ$•¼Åİ<À~÷Éò5c;@Ø(${<@Iâ>?ž=@w§Ã/‹j}À‘ܾõ[@™# +µ¦d@Oˆ€ÔJe濘úGÔæ1W@ ÑUx5b@Šõyé%±ÀÊHªhÕ%@™©#º7AJ@Ý@vÖ@#-m_åW@Ôhj@çá$ÀI1eMpÀê\Y*Æ[Àð5cZñ?ð?Ò”õêÐaŸ@tlÈ1/¡@i$˜qiÀ_ŒQ%H¶@y;3âÜÑ¢@q6B À±‹uSΡÀB v‰#€£Àðì9¸Ö@@±¡3k©@Û>š€nÛzÀê¦|aêùz@âÑ$ÇÀ· ¢3|ÀáÕ(úgÀ„Dú+vc@L›TvŠÏÀfÞ|ºÇÑ@(Y™9ÐŽTÀ ÕS6-nÀÎãÛÚwTÀÎãÛÚwTÀGµýôUᬿð?è"ñ ÿ:ZÀñ<…ëº\ÀÍ‘]Lž@i$˜qiÀÒ*dðu_Àë(þºå-[@àÞeÄ]@ùæ<ù¢L`@×ä»k•£ÀᓘS…8@§Ò” †@äÑ$ÇÀEÁˆÈzw@Ògd7@b<]c<À%éÙè`V?@­Ÿ´o@«GÃ÷…C*@LÇÊzZw@*ó‹µEÀ¾÷õêÀN0À¾÷õêÀN0À2k`»àñ?ð?ÿn‚ fç @ZÕ] }£@fCwá{!hÀW-ÛÖÁ·@øÍ=gÞw¦@¥ìcÙ}•¡ÀeEóÔÂE¤Àñ"ÿC_§À@¾fy~˜ ÀOÙð.ß_ª@Ô«Á_|ÀÜ':ñƒ{@ £WMxÀƒé×ë„}À&I{ÔiÀw8H9õ–g@G\’YöÔ‚ÀëÅXtðQ‚@^âY5¾{UÀlÊK pÀºî„¤GîUÀ’óÌÝÔ «¿ð?bëR!yÆYÀÍÖoú]·]À[H2ÏÝŸ@fCwá{!hÀR‚snB!aÀ65åÄíÏZ@熵ié^@I½Ç‡­Ña@vbÍßÀLú‚a>@X¥ªf‡@ £WMxÀÚ6HF×Åw@¿ó=)2Q6@Érõ\b<À“E¹’þtB@xƒ]% r@ 9ŒBÂ×+@\be¡w@D°ë:ö“FÀ¥×SJJø0ÀÆ‘1ÁÛ?à?:ñ\9€@•*Ȧ³Ìv@EAö£VÀ—Ý䨇åœ@øM—z%p@N”8¤h€À®¥3ÀUTêìË?Ð?‰±Í»`£q@+­»FF3j@\¼Ø3FÀ>ê!>Ž@>éK—uc@."†àqÀ1O®0ŽjÀ$ÚÿÔ ¹cÀpøïÚ¬½@‹¹‘˜‰Ìƒ@ª:‡m[TÀ¹˜XÄZW@™ ¾Ä Ü¿vÓÁ<TÀÎŽðuàá=À•ÿëf·ùô?•ì¡1¥ZÀ¤ÍB33]@T7t±-À ½t€#;BÀÍùÌéb'À^Ûæªd7Ž¿Ð?™›+Å$3ÀH>‡?¿o,ÀM 'Ó›Ÿt@\¼Ø3FÀ°CQUÆ%Àcãtp"g3@ÄÄh¼SÒ,@4>¡×ýg%@»$ótÜ6|Àš#íy.ÿ@ÿ{Ó‘éÅY@ž ¾Ä Ü¿!Ÿ—i –U@&HÛ®@Jpû18!ÀòõUq– Ü?ö/Bðo ÀÀ×h›Òc @Hê.tyU@PÂXÔš»#À{¢nBš ÀvRß¹Çì?ð?~ðšÒ'“@Ï£<9Ž@Ä•V_qeÀ<÷èn&°@;ÀDÉ•‡@ ã›òÝu“À²žÒh±‰ŽÀɦàõ‡Àvy7,0@5Óƒ[ n¤@ÊÛz¢ñyuÀh¹œ £Èw@,åK¨^ý¿;-þeuÀç‰ o2H`Àt¼5ñ°2@DÍ(Q|Àº1Ó-<õ}@ÝÇîfNÀÚ¿ï:œcÀ*t4Uà>VÀÌã’¢¼™¬¿ð?ÏÑ[SÀš@ŸÁøMÀ#|`J–Á•@Ä•V_qeÀKæ»w(„GÀI¤f^RgS@(¯_BÞrN@ „ÔøãG@ƒ"Ó˜aœÀ¨1@h6@–lûð|@+åK¨^ý¿4Ej+Ïu@D¤ÑØ4@ªµí~AÀºØÂ49ò@ãy«9G3@¬¹î,fi*@`êòÅ®u@Ó}ÆlDÀ˜|Æ#Ó:ÀY½Øoè§Ý?à?ÏA<¼(È„@©d~Y7@Fí,¦¹TÀj¡@ÜŒÒO†|@îKŸ§¦*…ÀâkÓQñˆÀÔu Ê }ÀðŦÍé@ž¨“:ß•@¶ðÉÎ]¨fÀÞrÇ Vü!@ò:ÀÄw}rºNC@µˆwZý?@r&Ì•B€:@“°z›ŽŒÀµÛ–Š*B*@¢ÔQU{n@vm#·ÓÔí¿OR ¦V f@ òã¹›ö#@ÊCò-Æ1ÀSiŽñþ@‚Ïb6µ:@¬)T …@`H÷}æe@’°ru!$5Àˆ÷SÅãÜ1À ÕÍ Þ?à?T‰w×…†@<Éu¢°ƒ@»‘D„ ìSÀïì˜à?¢@dpEm£6@¶ÁÎ'ç‡À=a8B7„Àk¤B¢°”ÀÀ­‘JaMø?rcB¸eÓ•@|Üß<çgÀêGïÌwµh@PVãchúí¿eœ¡AÏgÀdÆ·v‚9SÀŸ7Ø@o:@?;×9oÀ²—o@îg¬@ÀÖmÈ‹”˜VÀèÿX剥RÀÍan’‘F™¿à?¨ü#ö´BÀòbp›ÞY@Àe«º¸/ˆ@»‘D„ ìSÀ9 ÉÙÄ–<ÀÒBÄlKC@ýj‘5³@@|¶áù2=@©Yý½ŒÀvâ㌖.@XÉW!up@PVãchúí¿P2€ôGf@¹šåý»#@! ÿá2À,ÀY‡›@1Œ"IF@H§Ü’¹@8r®] f@ÊÓGä5Àg©¸4À¤÷/Á|ï?ð?q¬EwIb˜@›÷ùzû{–@ïD/…cÀ#)ÀÏF³@{"/»”@Û•ëªú˜ÀEïç}—À „V =•À@ŸáfÓ’ÀXÅ£aÖ—¦@qÉæì6yÀ‰¶ðȪ3y@õ‹Ë«XÄý¿º «Ç-xÀKý­ ÖdÀ ¦@)R@«ö)y€ÀêîŽZñ;€@<ù9›ÿtQÀoºÞO›5hÀ“óP+!#dÀ6ïù§¿ð?ÃüDì"TRÀRú蘘æPÀªzØ{™@ïD/…cÀ7µÐõ+OÀ¶˜õ"­ÆR@ª£w6PQ@¥e¦ï×íO@OȪ5×ïœÀnÂó훸A@.Lô«Ì³@ø‹Ë«XÄý¿ÝrÀˆv@–#‰{”2@S\Æñ¼^BÀZ¡2t^n3@tP« Ô_@h4'Á` .@ZO_w\v@Þ‹Á‰5®FÀñažsúPEÀ $-©8ð?ð?môÎÖ^š@íØ×E­¢™@€UpÜú bÀýçtñ§ ´@¯Ãë˜@{3³ö›Àš_|±–XšÀMê‡všœ™Àxx §fJ*Àùо KâˆNQ@w÷^Û;$À;0¡5"oD@( ƒ­ú‚@ÒrA‰(ý¿' o’”Êv@Ià.k÷0@ÌÖµM°BÀ7=š_‘¥8@œ[±\d@œÂ™4w/@ý̾ښv@ïäÕ®GÀZʰ›¡äCÀ1àÐi„¶Ð?Ð?Ö¹¦µ||@ìÀ.}@ÂH‰9Eõ@ÀføÎMß•@¥„&%å}@¶ŠW¹`}À5—sKV~Àt¢}×nÔ~À¨7‡Ê†ÀþÂ#!fDˆ@ä“9è\ÀÌb7K°@Fõo£·WbÀ´«>qÇ)a@h_$óf3ÀÓΈÅ°KÀÞ4æY@ÀíÁÇþ„¿Ð?ÒR4ħ)1Àœ‹]ì”1ÀlïêdhD|@ÂH‰9Eõ@ÀbƒdÏ2À Xq³1@:Ñ#¢¦!2@vÎ~7ù’2@…ÈnÃ8[}Àò Bu'@ܶƒ–,Hd@Øìœ=ÇÜ¿á*á½W@R ã¨@x;Ÿ'#À¢KzIg:@̪û*ÀH@`ã˜Ђ@$wÖ’ÛV@#„Ö‘Ô_(Àœ Bú À9gå8Ñ?Ð?4è×Oï¼~@zsà}•€@Ì€ZŠ?À”(Bo@–@µ•Tå@/´xŸ·ÐÀ w"H*À5œ¨…‚ÀÊ+…ƒ&j À‚wãÍ+‰@»¼&˜WŠ]À;->ÅZ@J»ý%uœÚ¿Úx7;Ì[Àš@ôÄEJÀ¯ü@DeÝB@u€ZcÀxJ7Öl¦a@·$ø=óÿ3À¶pÃoMÀÌå—–®4ÀpÄ~81‚¿Ð?!É„31X0À™NÑ õ¢1À~"’›Á}@Ì€ZŠ?À¡‹ÉÞ3Àb˜åÕê0@œ;u1A2@éž/Y²3@¸g­Ó”}À‹dÊðÍÐ*@º‹‘ž’že@J»ý%uœÚ¿€y˜…WW@âø´¶£9 @±Eœbä`#À{:Æü"@µƒM@–“žl‚[@~=<†¤W@žê>7rI)ÀŸ™Ô6Á Àâ ó2n½ñ?ð?ªµ¸Û% @-fÄ»gÑ¢@A <Ôò\ÀQeâàn·@ì¸6@a¥@8ʹ5¡ÀLôß—…£ÀOWLSú6¦À`ß…e FÀšðÆ…ª@â$±¥ÀT¬Ó€@O{@+mPdŸø¿xQßýš}ÀN¥ØËIlÀqÚDÿèf@øE „h„ÀÝcÒ»%‚@äár¤úæTÀÑØ<oÀ×ú¯pþP ¿ð?+@k³NÀ-1=ÿ³pQÀCQ±dPŸ@A <Ôò\À‰vˆÐSÀÜ­sÝRæO@Á°x R@jP‹Yœ–T@2L‡EÑÀ¼\F _ˆN@ø§,‹ý†@.mPdŸø¿½í˜Vð¡w@•Ô‚ü{*@ó/'ÝÁCÀ`{d÷LE@Tù^B‹0q@¾7šû®F2@~ZäÄ dw@mf¢K?JÀU˜»ŒÜý·?ð?P¼¸ÿSï @X6Ó¢L°?q àó2A@ÚZê cP@ÀÐŽ«Ä|T?zbâ›úë À8cMG‡J°¿ÒÓô^zT¿ær¼ºzs@ÿv”ÎÑ%À¿iMºa4=À¿‹/N5§º?ð?ÎH£gRÑ @k[q²?*^R¢ù3R@²µ¾H 3A@Û’i÷¿ÃV?¿5¶™Í À  a²¿ ÒaÏÀV¿‡[€û%À¿UMfØÍxs@“âkO}8@À¨8îIÓ›?Ð?5Ü·Á’ðò?òLüæ‘ú?eªÂ%@AÓùbÈõ¿H.…ö¶G¿ŸòwK%Á¿KÔ®ÃÀ\ÖÀÕ À&†ã潓S@Kg¯0½0¤¿¬H¥’!Àü=¦¿§~&@|ô?Ð?ÐFãÉó?Áìõæ‹RŸ?¿Ø5£A6@»¸Ø?Â%@™dÙ8ÊH?ÿj:TºÆó¿Íebu‹MŸ¿ÐÑŸØÆH¿*Û( ­Åê?‘çuŸ¯hù?ñ £g:@Ž´¯Rñ0¤¿ÏJk9õ‘S@¬SÝáGÇ!À ô›O$À‡+ôl_²Ÿ?Ð?/rMÏŸú?ñyÈNîþ©?ém‡,ß*@¿mʃ]ó:@è bY?6ìûì™ú¿A`êù©¿zÛ@ª]Y¿Eµ5“–eÕ¿ È6ÀÓ”ë3À»ß<Ä­S@â“æÏèM¨¿wèQT,}#ÀWþ‡0£3@Ic|Ç_Ÿ?Ð?<ö§|wú?~G·¨HØ©?!q LË:@€»ŽYß*@Ò{+ÕÒ“.?ÀðqáôMÀ¡§øaÒàs@3µ®%rпÜuþÍÓ’HÀ©ÕZvY@ÕE³\s~ã?Ĥí%J@µ(è8ýª\@ÞvWΣ?Ud .ò#ÀÏS|Ãwã¿aó€sG£¿Û÷ö'} À8ú„è†5Àœ7n> GÀ¾K—«d@øà6ÿº³~ ÍÞ=ÀÈ÷Îk$Çk!Àš'ƒB1á¿o`ÞÜÙ— ¿¤CŒ»C"@ YE:¤“7@°hÀü€fS@`Òóhÿ®zÖd@fõL(:Às‡¦sJÀ„çS˜çÒ¹?à?>?ÖºY)@S{€º_Tì? ›¢/›±N@À&Oº!À`@ž 6a«ý¯?Ò…–ÏÆ )Àp*¢ Iì¿ë·vñ¯¿i СDÀ8˜KÄ97ÀkÎ(JK>KÀÑ@„1d@C„\оçÿ4¢ÈCM@À¹‘Þk®?@åW@J¶?à?Vîæ o%@Ö»¾ 24è?º@_Fd¦\@âÐtpê±N@S˜µýT«?ƒÑ]êÞf%ÀÃVσõ*è¿ÿ~J«¿ö)€0%@tå,‘z <@,HÂ×°V@&¾âïñçÿÂ%ÊK0d@f˜OáÖ;À‡þ¡¦*EÀ¨ ¦E®á»?à?bUakÿ/@6þä-#ô?~Y©¯×Q@úëlcc@ðX’£Ýº?bi{ù/Àz„ ½ô¿¦± Ðî º¿î,êp oÀÞ&Ôaî8Àôßü ºŠOÀo6WU‚Md@Xn0§!Ä¿ZqfíвAÀQ¦»k P1@§\·?à?¹³[à *@Í`èá àð?ÅKuUE`@Þ ŽQ@ÂÅ|N~Þµ?ƒR"ö*ÀIQ:ŽÙð¿ G½‘TÕµ¿·Gz^#¿'@$ß$A@[dzÊýY@ã¸z+Û!Ä¿hq‹ËHLd@w…(Šû¥=À²iâ8ÀÛ^Äß!ö­?Ð?e.`8#@ ê\|ì?`[ïC@-xJ*@V@ï%jñ!¹´?“Ç‹”ý"Àn¯»ì¿"ž˜¸¯´¿^¦ð€[CÀÈï"B†0*À‚ ŸÊ§ùAÀûÿgÆ4jT@Z€9K‘³¿%¬g„p 3À*ˆÚvÜ­¨?Ð?sä×'!Z@¾$t1Q#ç?8D^R@õÖÓGïC@:ëÏn±?Íh«äKÀ`QiÏç¿8W­ ±¿È&¨ÏÄ+@4Ùèä3@ýèã¦OM@À)ο}‘³¿†ÓBÞhT@ÐK €/ÀñšÆ3¶?ð?Cz¶Ñ8 @®BÝF;²?º?á¢ÊB@ú}P@8KÇ\¯¹X?ÚÐW¸$5 À7ƒ°)µþ±¿Èq 8¶X¿°©J‡0B@{Œ#uë@Á3,9E¯:À;ô;‚Us@ó>ûægà¿¿ø¨JØÓ:À/¹Ê7^G@!(-ö~2¾?ð?c Ö@æ‘]~¸?göÿû¶U@¢¸3ùB@(õÛmÑ`?DS‰ÓÀPà ¥îz¸¿KqìTÏ`¿vUó?üD * ?å…ÎÓPÏ&@ Y€¿FÊ4@ý)©(~K?ÛMV 󿨮A¾Þ' ¿² *yyK¿ŠV}/Iàñ?¨ám€õ–⿊j!÷‘$À4òLOnS@ª9»bB¤¿rco‘À 0n~%´&@ 0n~%´&@ó=çEN ?Ð?¿o>Ì‘Ú÷?¨¨êålH¤?rدõC:@o1G¹‹Ï&@Ûê‘ ?Q?ÄmáÖ÷¿ b,÷÷D¤¿*òF0@éF7.@#,@¾UÎGÁ`?i_ùI5ÿ¿#Å­„²)°¿)(úß½`¿ê@-ª~ÿ¿Œ¸—@ @+ ­z="@Ïã58á9¨¿ðl ‚„S@›[õÔ'b%À!ã˜õÌÏ2Àß÷ªÅ%ÀĘՠÆÙÀ?ð?3ò¾Î&"@t[~tlÖ?XvÑnQ@ÔÁ¢ZÒ2`@~Mè¦"ä‹?'oHÛ"ÀWFö}gÖ¿»¢·‘}Ý‹¿¬¶wÎ…oÿ?‡¹YQ;T2À(œÖÉQÀù®[³ s@Và”FÌ¿ï/°Ox«DÀâ!ˆÂÿW@:¬UE@ÌmL×ÁÂ?ð?“y=æ©$@ýq`Æœ÷Ø?Sñ•Èb@ÇÛn^;Q@v,÷•?Àôæ¦á $À £ªñØ¿‡?$‹ª¿,Q ˜µÓÀðy² @l5@åpzÒïN@!,@•\FÌ¿œ.iäs@Š*‹bGÀÛSYÏãXÀmƒrÔFÀÜoW%ÎÂ?ð?**u/Ü'@ØQšgé˜á?U3vH¨AT@J#6êc@q™áàíô™?EAcv Õ'Àç7”Ὲ1éWË홿  ”~Ò?"M<9À299ï±®UÀvL7!_ºs@a… ¤aп½1iRÈ/GÀªÃ÷þÊÇY@"6Ƙ՟D@DãœÚÄ?ð?R£Y'c)@´øÐEB¹â?_™a€´ìd@W¦%–ÜAT@ÍýÃÇ@ž›?ùª§â,\)Àþç·´â¿ÉqU©–›¿*‹-4W=ÀÜðNùÂÔ=@þ(|ØU@^6ÿŠпÿ5ù)¤·s@]«æ«¨HÀX†jKÑs\ÀßÑîÕ ÃFÀyñGŽÇÄ?ð?ì“gÄ>í.@„w Áê?ÚÞ ÌW@êÂa‡g@%k %§?—Ž"”ã.ÀE;ë8¸¸ê¿/ŒÌ§¿èˆµ©åú¿«ïÍHEa?Àø×§¬YÀè}áÚlÔs@+.9%í¦Ñ¿§Ç…ÛNÁIÀÁ‡[7àX@Óâi’æC@BiUìdCÅ?ð?aþ‰çø§/@4!Sçbë?´ÐA–kh@oP¨QÞÌW@¹º*Áۧ?r¸ÂØž/ÀëÛ‹˜Zë¿«Û^©§¿ÀeqÿBÌ¿GKòLoC@NMO¯“@\@¯L^¹§Ñ¿‹ÍÊÑs@r¬/ePYJÀ_…ÁïC]ÀÑÑšŒiGÀ×­,ãƦ?Ð?ɱ’ph°@Sä¦}ÉÓ?}Þ@ÖÀHÀ%„¡¬:Óª?Ð?±]Š@6‰P 5ä?°Ò_ÇU+B@ÆÊ¿jÌR@:©ÞÙ„½ª?è`<e}À $5v,ä¿ã $h)²ª¿^J@ìèÀ~²Kƒ~&ÀmóŽë!CÀøº-‚%T@zèL"Ù³¿J¤xºPå0ÀÄ[¿¡!@Â[¿¡!@7µ¨ß!©?Ð?S7ð¯ž@Mµ<;¹ïâ?þ‡¥£žQ@î h±„+B@½‚Å1©?m –!ˆ’ÀÛ8™K®çâ¿ꯗ`©¿ˆw e4ù?´<°Ò}1@|ü*Ì;ÓG@ÙmbRÙ³¿EŒ¸”#T@=±È}¥/Àô³hbèq)Àñ³hbèq)ÀJ~tœâ¼?à?rð8†q«2@<º®ge ü?ü?½RЦUªê¿JCyv=”¿>_´à¹>¿È(jë;Ð@Þsã÷Á @Y®:¶Gv*Àg»» 1S@ÑÔò¬•ž¿éÄÅÀÀ,Ð?œ4@É´M |Ø ?Ð?qþ»àÍÿõ?·¸D"IJ ?  US·9@êÜbDâ…"@Ï rpYI? í6lüõ¿äR€3° ¿¦”ôŠUI¿¢·÷ú·ŠÀ½x3«i¿>®"×À­"¤e•ž¿9˜Å~:-S@£`åº2$À3ºž<2ÀûàÍÅ1¸?ð?°“χÕ7@K­§?¯¿Á?nã:ƒG@ ¿”T@ˆÏ7Kdp?î™Ã`N4À±“¶%m¼Á¿‰x3ãHap¿XŸÏÆL‡#@\{£@â0t/ÚPÀÍH¥Is@ãÕi°yÿî$ÕÅ´(=Àå ½ŸçF@È|E1« T@»\N Â?ð?ð7Ö¯p¯@>oy÷ý}Ê?œÒ ¾É?^@bœ°3PG@¸êØHxwx?åW²Ÿ,ªÀÄ{†ø yÊ¿ªJÊyúrx¿À9  …9À4GÆ™M@ ¼i”ŽÀ{Ê0³âyÿÿËgŠ—Es@³ÒÁšÀEÀ-ïÔqEÀHчùúÂRÀç¥wHý›?Ð?øcÔÏ€¶ú?Ëóô•¤­?Jb¥T¸-@Îõ\{©Î9@ ñ)Cìq`?m+r¼°ú¿i£ìc±­¿‰ƒ€a_n`¿öëϰ׳@з):0‡ñ¿ +aÄ‘4ÀQg =bS@m\.s‚©§¿¼~„ó À9úÈìu3@9úÈìu3@Š”÷9lE£?Ð?þ&ûÉ­e@C¥°Äëi´?46ˆ¶Ã¡A@“bL -@Ÿ¢û¿¦f?ZÙµaÀ·Ùe´¿ÔÙ­Ü¡f¿è—:7ÍÀ¸­x·Q” @vɈn…Ï@¦Ö Œ¿©§¿”ÓC^S@AÏrÙ‹V'À]f®pïK3À]f®pïK3ÀÉöKÒ¿?ð?xR*âM "@ K6_$Å×?s‚?‰xQ@³§¦zŠÂ_@€’ãÄšS?ž;üwÊ"ÀKøÎ¦1¿×¿)FúÃK¿>$Y"£@œ»9òr(À†¡”§C_XÀÑ]Êa@{s@/'Éqj³Ë¿Â–ðl¹^CÀˆæ {îAX@¾Ï'`òÝR@Ì éMç€Ä?ð?qÆÉÌ?'@Kª¸ß£Þ?Ø^ ,cd@õ]iã¥Q@@X ¬·0”?´÷Poû9'À¹¬_°4œÞ¿þ#Fª+”¿jØòTþš4À ®õ»cØ5@»%åÚ{fG@:œAø±³Ë¿ú ÏçEws@!ÖTJÒôHÀ jÂñÛ‚YÀ|6—ŸŽ×SÀvç­—€ØÁ?ð? â¿ ”Ç'@ÆÙÅkâ?ì¼QçT@ŸSDîý:c@VÙ¥ªˆœ?¥*NjÆÀ'ÀdöQ¾Íe⿹ÃêÜœ¿ˆ=ù… ¸@Ã]ÎEnX3À8ªÐÖ¶E\À5|‹_–”s@fH9GijÏ¿Ò þ^ÖEÀº¸%»Z@µgš¨BR@öݺ¤Ñ¿Å?ð?=‡v^ý,@}Tø%tæ? Dsûfg@ÅžJQçT@Áïä’+d¡?2iú#õ,ÀÎ&¹mæ¿Ã€BÄ1_¡¿\Bæbˆ2À n$C}‚>@i-…¾¨ùQ@† 9eºjÏ¿»‘ÀK§s@EüüX»›JÀúòùæ#]Àâö®ÑíeTÀصé‡Î̳?à?Jÿz¹@D‡*¶Û?{ /–ŠH@ßVf÷V@å^Tcþ˜?]½ “¯À<µH+­Û¿Í¨ƒQö˜¿øºè¹N:ó?­I5¾¸)Àû†"PÀײa{K®c@©ÍaüSMÁ¿ù,}‚åZ8À·Èob3I@šd ø£A@2#?·?à?<¸·qÛ!@”vý+à? †i׋¬Z@†AÕŠH@66 ?~V.½Õ!À ~Xøà¿@5>;¿<ȪIÌ• Àe¼˜æ3@Yy°-GH@Å-©€MÁ¿/î~Tqªc@–"ÆÞK<ÀýÔ4!YóMÀKÈqÊ$÷DÀ¡«8,Æ¥?Ð?kzœB‚@µÑÄ„kQÔ?!ÜêP}<@yÌ~·K@Î5a5,)•?Jו<{À+º…èJÔ¿¥êOì!•¿‰–—Äæ¦¿toÃ?TÀI¾&õ.BÀ£s nÈS@4õ„„²¿³æUÌì*À,éºÝ5@cé˜üÉ1@}Âc/EH¨?Ð?íÛêbÃ@’3V1|ªÖ?U—¿«8N@äóâyš}<@#â²t+›—?hé»À©þ/S¢Ö¿ °Ì«’—¿®1ÓfíŠ ÀfãÚñ¸Þ(@ü?M Ú›>@¨‰a賄²¿ÆRƒ×®ÄS@0¯ß¤Û.ÀˆßÔV³;À…X'N‹5Àü¢ÎºÄ·?à?/ë5Ÿ!h(@ÈW¬ý•!í?Ò˜9-å`P@'3@p¤_@³Ñá“b±?yb5{s^(À|J´'í¿$,°®[±¿P-›džø¿§w¥B2ÀÕɺ€HTÀE’¶Kãc@Îï([9ÿ@EtAÅá{R@QW-ÌŒ9ÿ£Uxëkßc@.tFÝâÇ?À€†É‡"FÀ€†É‡"FÀ‰/e2™ÈÉ?ð?r’OQ#>@~*|ýx@Ûh{±L­b@çÏH"¸Mr@â»R`ÐË?›ÚúL>À<âÎ &pÀö¶:]ÄË¿è6Ç…~5À“À³hDÀ´ÍM…ofÀg/)³>þs@Œ2°g_FÓ¿Í3Íî„PÀ •ðA@ôêòeO@>•¡·{ßÊ?ð?¿WÀç;l?@•¡W?lX@ßc$ds@ÎAë|­b@¥3îÿÌ?]ç¢Ò©^?À'9kP4OÀ#ßhóÌ¿(CÄkß 'À÷sÙ&õèQ@½w #­e@‰Š,‘FÓ¿8ïœûµús@¸ù"Ý—ÊPÀÝ ‘ŃüIÀ¾lßLó¼VÀJ¥¯ïÑ»?à?3+ˆCþd2@¢ßØ“ƒEü?¦Â}ý6%U@"[Æïe@1‹Ù‚Þ¹Å?žaãzq\2À1#‹ƒ_8ü¿{É}Můſ8=·ºÀÇ ¼Ñ¤5À¼Ñ˜2g¤XÀ÷2(Þd@jÛ_Ô¿ߤØB]|AÀáâ]N >@ )#â0¼?à?chKš¥2@AöBßШü?m» µJe@ºo¾–m%U@5Œ„6.Æ?¤àÍzïœ2À½xç¦~›ü¿ô¤ÈˆñûÅ¿n#Xm¯]À«·ÊWéD@ÈPÖ2ÚâX@J³û(‚¿ÔðÚ›d@.MP§¶AÀ#}Òƒ¶ZGÀ:Å2W%±²?ð?(<>, @ü\¿ªö¶?'–ø"­B@ ¯'ÁSP@~>(u#hc?•/Gw' À0‚cÆò¶¿@wøkÙdc¿s’š"lÃ0@ŸßMǨò3@£¶Q%Ä®SÀ¶,Pë" s@ÈV¤~¼¿ßÚin=@6À ‚/HŸ³Z@ùE= |‘Â?ð?SE"õÿ@”˜8ËbÑÆ?*a;º/^@a®Æ1S­B@ÓÀ¼¡Hs?ÔЉ¥aûÀ‚ÃñÀ„ÍÆ¿eZš ]Es¿¿þo¤ÿDÀa÷$°Dñ¿Š‰˜ìäÑDÀ/X 6Y~¼¿Mø¼_s@1VC•mFÀvFì XÀˆ—ºÿi¶?ð?NY¶M{@A—)ú÷¯Ã?…n¨æÚG@Ps–ª©T@o„Ñœ0ås?œL.×mwÀTu¦¡ ¬Ã¿%¼¥®;ás¿-k»C¬.@ £èž=#%@4 ŸÆÃ?ð?h€û³21!@-艬_Ñ?Yuza@Ÿ§Ò@$ÛG@a,u¤Ž?¹EeÇ-!Àgöü7\Ñ¿ íJ&‹¿(¹1WÄDÀƒQé/WB@Îú¿á@1Àss>Žgw¿6,b^ s@¡Ê‹½¦GÀöùdSÐúEÀ6™Ñ]*ºXÀ ‹x[,ª?à?å<ï ëó @ ­‰§"À?0²T ”=@Œ¯»°I@ž‚˜§Qs?¢æ´í ÀúåæïÀ¿ò–k33Ms¿D['ïF@žéPMû¡í?¡b¤KÀ“¦3²½=c@uAOK´§¶¿LðÿÁUw/ÀC^XiZ¤C@Åq‡AI@\…7ÐHþ´?à?øbï_= @“ÁúÈ‘äÉ?i˜Â®…T@½Ë2´Y”=@ê?¡ôk?ß`·Ì@›Àº¡¼U™ÞÉ¿{ ïEù~¿šÛ|ß13ÀÖwÊß§@¬ÓhÊò @ur€Êî§¶¿Ôei®8c@7Oh <9À®!“ÄCÀP+½·iIÀg›É¼_÷½?ð?‚Õk‡Õ"@H ÿè&zÙ?]1¹kîQ@`nNÉ8n_@ÿqà é‘?ü "À¹<ÞksÙ¿ßT–Nä‘¿ÅäVNüO'@tùVA¯¹À4çáyØ^ÀFá«cpVs@"”„Ž¡©Ê¿ [•~åBÀœÔ >¯X@œÔ >¯X@a‚«9Æ?ð?‘5-ã*@æ”/{Çæâ?AWàÕíùf@äðšîQ@£¹/ÒE“š?‡¦zÇýÛ*À®`(Éáâ¿'5ý‚@Œš¿ÆW‹7BÀª±CãÀ6@Ž“ýÔ?@\J·fæ©Ê¿.«úÉUQs@!rä¢ÙJÀ$d0«ZÀ$d0«ZÀq¤×â æ ?Ð?!“¯ íÌ@ÇÁQ@æ{Ã?e¦‰©Ö\5@®ÖÊóB@­ö’Úæ?ld²2ÎÅÀBP0þvÿˆ«ŸÝ¿—€1†Å@¬­c Û À0e<Ž-`AÀre„ÈsoS@ éç*äO®¿8E”ýA†$À‹TáMŠa:@Kÿ}¬/¾7@V5Œéwx§?Ð?8>ù;€ˆ@§î3ÅË?1Æü1 J@^jÒ ]5@kkÈø(†?ÅL ùƒÀÙ–ãû« Ë¿›¹J‘W"†¿ÌÚ¢tj!À2Ÿ[Ûþ@;±Ã D,@Ïko2P®¿Y¬¿J^jS@+h"Ì,Àròô%Î=ÀµD@)"Ó:À·8ß!oÕÂ?ð?5ÈMù½¦.@EæKoþì?ÂøŠgY@ZB=‘f@¥ÇZQm«?äÙ'myœ.À Ïâ¸ô쿞·[âc«¿Œ ú D@–*÷ó4À(@K˜s`cÀŠ@ÊÓˆs@uÂÿ[³Ð¿Àÿø-þFÀΪŠu”ƒY@S3clöV@ñ‘±lúÈ?ð?(·/C!4@„ëlš ó?¢Ký9¡~m@¥L”1ÑY@À‘÷&²?2&ê„4ÀFŸ€9ó¿œdE‡úü±¿¶±K›®@Àr*yáêCD@ºÐÞ†UT@:©: †³Ð¿uw\уs@5+íÒà.NÀ›,´Æìœ^À&(¢;[Àpº¶ÉÄ?ð?Êt%ah3@¨–›”Âõ?R‚÷ ]@ÿ´Ÿãa’j@"¯'8Û¶?eýÜ.a3À‡ÎR€òõ¿+ ‘½Ò¶¿Ñ“6Aµ‚@¯687sõ9À×<’bmeÀ›àž¢s@[õŒžÙÑ¿x>óÅ$ƒIÀ^5¡\E*V@^5¡\E*V@š"K£Ê?ð?)ÿÐH8@?iˆª”Zú?/‡×@”p@_¸B!]@G ¥}™¼?u¯lÎ?8ÀëêÄÎPú¿Füæºá޼¿$–+Œ´@À_Å÷ÎZI@FÑ bÐZ@ÛD•&ÌÙÑ¿@ïò¹s@Qð˜©CçOÀaq¸K\Àaq¸K\À‘yrOæ?Ð?˜¨JÅ8@t¼>•õÝ?ýûFŠÀ½@@é#(úCúN@Ï")‡¢?qò­Ìí.À² BòhéÝ¿mêaå¡¢¿ JŠÅÇ?ÆÆU*,À”•F£R‡GÀÑïFEâ¼S@ó=Ãy²¿Yîq±,À½~uQ›0@«—™Y5@™³¾3/J«?Ð?Wý½lâ @)îùG@÷á?hXMÄ€ŒR@´"ZÄë½@@—Ëų8¦?…­À`/f„óïá¿ÜÍX¬/¦¿üü^ÛÀ+o1³Æ.@ØÚÌyh@@{2ÆÑ¾y²¿eÞr<$¸S@å9°Õ±Ô0Às žZ?˜6À¹Ÿ¦½ã =ÀB¸èW¯Á¸?à?çPÔQïØ-@¥­Ë–éô?ÒˆpÞÜS@¾uŸæa@7PÙ„ðM½?ÇbSsËË-À¿$…éaàô¿—ßm× A½¿(P{½ÅAö¿E•žÝئ1À‹ŒñI¡®YÀ£¹ç±×c@´ÛËn¿Uf çp¶>À„bPöª<2@ÓnU@„D@Ø—¼?à?äMþ=1@ŒƒK)ø?ÐNrIæ©d@ rt#S@]€;!³íÀ?¤UöEg61ÀQaÿ§ø¿åRŒ??æÀ¿¦´b°“Ó-ÀñŽí+EB@ÌL€ŒS@¼0b@n¿]ä)´Óc@c¯åÞºAÀ¤,rv‚:À–!r@ÅÒMÀzƒ¢w¦Åª?Ð?&†Û8/"@åawtñµì?Ÿð2N#—E@ÒV2…T@fE6ÄDª¶?còå£&"À}Uõìe¨ì¿O"´d“Ÿ¶¿ˆÍ¶¤–ú¿¾ÀËŠ_#ÀB%²ãKÀÿÞµ óS@Sò8‘䱿Š!è$ ³0À«ù¡êª3@Œ µè­?Ð?o©Çš½R$@{ÐJŸ3 ð? àcÆ_íV@²ª› [—E@ø‹¬ ³T¹? 'I$ÀGñ¡ð¿tl¹Ì¿H¹¿É¤ÕôÀU>ÂUT5@kƒXÀ ´F@X¹ºäޱ¿¡m34µîS@X\Ho¦2À× Wïœ>Àˆ‡¬ÐLø ?à?TÙaû?ÕLª?y a~g‚2@ȆBs½Ý@@HJë”X?Üý„‚8‹û¿çm`lª¿ »pÚX¿»¼¦xYß&@íö@1p*@øI°ÛwJÀ«uߨéb@üŠÝÙ°±©¿ áctå $À%¹§ •âM@©²÷)jD´?à?fJ­w@Zi².¿?VQU‚˜Q@çÄ:I—‚2@wöT]m?X?-btÀûÂeˆ½¿¿%ÿçyœWm¿Þý0AZp<ÀœN»ŽñÙë¿èv;J®;ÀïÕÝ1󱩿Sab#äb@qA8Yðñ7Àlu:IaKÀÃ\©»¨”?Ð?êd•Á¼ó? Ãë¥?¯î3à'@Ì_îŒ5@´B¸uYX?1]η󿞉Sg祿 ûú¼2TX¿‰îB,@ÇJ¾›Ÿç@o§è¿àª=À±3»S@kUG¡¿<#Dä‡À$/¶ãÙH'@íº£\=@’ÖŸy¥?Ð?úÞü}…@ž3d³ƒË¶?¾L©³RD@!¾pà'@É54Ri?cDÀ¤õµ–ƶ¿£`ôƒ‡Li¿_¯C“s¬+ÀFó¸Ï"—ö?noú¯YÀæ%`H¡¿Œ™±ÜÉûR@<õŒ} ~)ÀJ»9€&ÀjfÇ <Àïàbý¸`¨?à?Ìf-T:9 @„ʼŽ"¬Á?•÷ép}È=@ž‘þUÜI@BDhÃñv?^QO€2 ÀÖé̱ħÁ¿\kôìv¿7u«ß2#@œ=qŒ  @=†ý{²PÀ^OÛc@©C¤Ø‹?µ¿éH(-À•ÉîÑC@gãŒ0>OL@ðÆY° ±¶?à?En£B>Y@º{¤|ŒtÐ?8ç,¨YÌV@a”ÐWÊÈ=@ý¬;º9]…?^àO×úRÀgÝ{pпùìÙWòW…¿ùu˜Ú±ø:ÀÆG5Ú5@…BKŽ÷ À>âµÂ?µ¿?©€PÂc@…|gA;À™Çžg-8DÀ¶A¾ŠâLÀS„øDž"œ?Ð?ŠÆ*ßö=@FáÖ>€»?~vdÀ»2@-Šie?@àKUt?–UÜ8À ²]3]x»¿<ƒ·ýµ´t¿Šfïæ ñ@`}b5{©¿Fnðº$›BÀ¿q®Â?2S@;²Q 4©¿Z4Ú­ß ÀXþ´¿8@SW;@¹ÉöˆNì§?Ð?†õôA@mìç.dÇ? àˆÉI@ÖùwŒê2@HöjŽ¡?4Åã’ÿÀØDû…ƒ]Ç¿kY”_Ÿœ¿Š`±¹U*ÀŽ”No&@øH´E÷@eè!X4©¿üC.›,S@":¨ª°,ÀÛüÆx±:À˜ü¿¨=À¦ô»ŽàíŸ?Ð?äÍ.Äêá@#ç+ÄÄ?¯7@¢¼¤5@4 ‚ŒÓB@µÑ„‚?p>* lÚÀ¨Ž?ˆ§½Ä¿“¹iÙ‚¿-vzÉ @[pÐÏþèþ¿ßVN¹DÀÌÐ;vóJS@c”ð‘•Ĭ¿eõÈ?#Àïq þHª:@ïq þHª:@®8¶·ù*©?Ð?»Š•ÉÞÔ@ÒK8€×_Ð?QÌM@˜òÅ„ô¤5@Áºž=ÇyŒ?KZÛõÎÀñ Uú³ZпƦŠ~×pŒ¿TÝÚ5Ä)À$×gƒ»K@¨&êWì¢$@ ~¿ÙßĬ¿Ÿ¼™ÉDS@@š)LxU.ÀÇêËmÕr>ÀÇêËmÕr>ÀPÏSOYá±?à?<·V`ª@&B(qÌÞ?ûÁr®uI@ñ³®v9SV@ªa—c“wž?«HË”jŸÀ“o3w%†Þ¿¯2ò3õlž¿„¯Šñ@쎼üËÀ¸uUPˆVÀœM´‘dc@ñÜa½¿¿ñãV‹Ñª5À´'ÅëÐI@´'ÅëÐI@jÿ<\mº?à?@g>c«&@yDݦc˜æ?ìé¶V‘D`@)Ë kÃuI@‡æ*Z¾…¦?¸“Óû1£&À~£Wăæ¿^J)÷ä}¦¿àìÚD9ÀRĺ›Cˆ4@Sóa{k@@Á[ ³½¿¿d:ë]c@ñ†lùÚ@Àd¸š ð@OÀd¸š ð@OÀÁ2È¥г?à?S¤«]#@øIò–þå?ûÇe``”M@mk¦ó©4Z@Yf«û¨?§ÙÜœU#ÀûÕ(ö忺ÏöDò¨¿€óZêÃ@[²L÷ˆ $À˜ZiåXÀA25-w}c@L¸ÌøñÀ¿ðGÂ>#8À†€.òtF@>«3ÔÊòH@ä/XÕ²»?à?>³î¾+@ Mw Áî?dãµÍÎ'b@cò¼À¬”M@/½Í·¾w±?/%¨^ +À k³B×µî¿P¯— q±¿S}ífØ8Àbi!V°¼9@,EKOê‹F@˳³×#òÀ¿¿0Œ„wc@ôê ›Ý@À¤~ê ÞLÀ[F‚› PÀ(>˜óĵ?à?1[•Z¬(@þ˜rfï?×Vý âQ@g±_Ôz^@;ÍöûËø³?Á|(À¡8,ûî¿`˜þvð³¿$¦Ç–›@ÄÜu’†ó)ÀS¼Îù(¸ZÀšè./c—c@°Á–‚9{Á¿SOL.ë¨:À—IôÖÓ×@@DïéÀH@=߃3ü¼?à? \iÊ?0@W3Ÿd¬ªô?m2fÞ°.d@¾û Q@;Û«šº?°*Þ 0ÀðÜ2 ¢ô¿è&–º¿Fr¥8ÀšŠ‘ºE?@AºÉϲL@·ä¥f{Á¿¬D'Ô¡‘c@a+éw4¾AÀ‘¼`Ý GÀ±† žétPÀ#IÞ„c¾§?Ð?ÄØÌ)Õ¤@++ê‚å?X•þìcC@s e”Q@wD¸ ¶5¯?0rª—ÀºñNZxå¿wcš»­'¯¿@·aƒè¿£ð €!ÀCn×àOÀazAµãÌS@‰S5нX°¿Kà]{Þ/ÀC\¨æA:6@bX õRš¯?Ð?¿™áÄz$&@'o²ò?W/·Ôß«X@ѪuWïE@œ˜¾AhW½?É{YÜ&ÀFu÷^ýñ¿pÝ\VI½¿ßB½#¤ (ÀcøÊ>e°5@RGQà"ŠD@ëóv¿çX°¿Üš2ÀŸÇS@C»öŽ3À+;(ÇnRAÀ‘pÁÌωŽ?Ð?3fÕ<“¼ë?.ö¤Á—J?æ²V¡"@o±Aœ§ª1@tÉëîN?—~7×¶ë¿[r‰D¿}|“†èN¿iíó8@¦[ €ñl @wc~'ÿ"@ÀàÄ9$ÇR@£i°ÕG–¿—h.¨8êÀÑ1Ÿ‹ï>@Sømpñ¥?Ð?–àûhð@üQ%yµ?€Sã|:D@ɤçÏ"@+VA¢ÏŠÄ1À®\çÃ/Qô?ö}`J®&Àí ˆJ/¹ž¿Ä€EÇÚ×R@Šo ÜÑH+Àjµ’'ÀÅ"–v]Á<À†Eú¢>›¶?ð?Ž…AþMu@(1~ cÓ?ÆQib©M@îuž™NZ@? b`‹?(L%@nÀÊW|#í]Ó¿õ.ÜY‹¿Ù›ç939@Æuþê<,@QŸgÓcÀ`/½’ör@ÛúT‹<}ÿI_ïíÈ:Àº£¶&üS@ 3——ÈŒ\@Ý ”Ù]È?ð?˜§Öò\›-@+öoçä?a[øÎÝ´i@ùå¥ÿ®©M@4‘åÍ„?›2]ƒ“-À}:2åáä¿t™Kú|¿³AIÿ2‡QÀí«¯þ‰*@eO¨'¥ 5ÀD»ØÝn}ÿïwïr@[Ôƒ¸ÜLÀqB}¨¤¨TÀ¢Ìi^4ƒ]ÀºhÑiÞSª?à?i çש]@X=­–ÎÉÍ?Æ Áõ#&B@¸†™¥O@t2K(ˆ?ÑÉ5XÀVjFöÀÍ¿-r)Ð!ˆ¿j€&@ì't`ä@®cs½¼UÀ`u¨8«c@О† _·¿ß¿Y/Àe–TúH@ÆQ#ÏÀK@¤4Þý˜¹?à?SÜSCöÜ!@IdB§ùÜ?øÖ$™Ï\@‡«_ÒR&B@¨FÅÇ—?)Ll¨×!À°=.RuðÜ¿›ËÁx—¿<Ú¬RAÀD)Ã9 &@Öv¥±šñ?lsDùV_·¿áÐ;ƒc@Ö•=µÉx>ÀÝa·v€AKÀôúY ÇHNÀÔփ粮?à?Ñò©Òý@¯÷?)<Ö?²¶G—ÀE@8BgºØR@x8ö¾œ”?@ú7lõÀ%Ç…ãÓ4Ö¿_ŽœN•”¿ƒ“xÁ¯#@î³ûrýï¿ ©iôä±WÀ:º@ã'c@ƒ@¯\ãÔº¿„±„Î¥2Àa˜‚œmðJ@a˜‚œmðJ@ÙZ>ւ׺?à?ÊÃVi%@äñÐBwØã?Yö$[š`@(1(rÏÀE@S’Ϋe¢?Çð˜b%ÀñÚ4¦ëÑã¿LÁ∠_¢¿>´•ÕQ'AÀå/aÅäj/@š¿Ša*@V5“¤(Õº¿‰n•Åéc@:’³ª@Àán£.7OÀán£.7OÀ¤üÕôvð°?à? Á夈¹@uè5wê1à?¶vµC¦I@×_lIÅ;V@fbÿ¡?¨Š¡_®ÀAÊ$‰,à¿äërj ¡¿ãõËçw‘ @ÑFëB ÀZõG,³YÀÒÔ0Ñ?c@èüÌ䫽¿ibÁ|`4ÀÉËL»…J@ÉËL»…J@=žŒ2¼?à?„UL~)@ '³Ñàê?Á"’¸Ôäa@”3=…¦I@·ÎZ:åT¬?}È·‰ u)ÀÇ“&Ç?Öê¿3>¾šJ¬¿ºRxK€AÀ§Œa,•´4@Lø?ƒÅ9@«Ûj«½¿Üi[¿8c@†AùšZå@ÀWSVš¦ßOÀWSVš¦ßOÀžôš´âÚ¢?Ð?P‚úoéZ@+w­O ×? µsÙ=@S!$OµþI@¨øŒBŽ›?öÂc¦Œ?Ó¦À1À–›¸Ql=ÀoVØÊžX@À0& :ÊÄ?ð?óhã? 8@®S@y)@J†ÁE.a@ˆžÉËl$n@ï.쀹Å?ê~î8À_YÁ"Àý;㽯ſòÈÍßÄ"@á’ãÂæ4ÀJ¡(JoÛmÀ"zÿ“Œrs@M᜿•Dпo@óEIÀv¸„Q@ˆ „™cX@)aÒ5¨Î?ð?S­d;¼A@ÿ‹ŠíÖ@îþ›¯ëu@ "r.a@+µû‡ØÐ?ÛÊù•‚´AÀ«Êx³ÌÀ#!’ËñýÏ¿ø¤=½àPÀXoªLeªO@ÆN½*X@Ö›ÓÀ¿Dп¿ 'Õäks@&£SÁÇ RÀRƒ‡ô5xWÀ¨ó@”Ã`À쓹󜾦?Ð?*ƒà.@]âkÞÓ=æ?¸ëv„™C@?œp²ôWQ@’`X;İ?ˆç\ŠsÀò’4š3æ¿vï•…¼°¿ ©òc1õ?nén×Ò³ÀŠT—ÑPÀI„_§ŒS@ gް¿n: j©Ì+À¦TþÍ"@ÍéýD€7@¹ÿK"õ¯?Ð?°äT%¼$@W9rCï?c›ew%X@%z®4™C@îñàG[‘·?°Ñwö²$À_4˜¿!5ï¿9FâU…†·¿óѤLÝ0ÀžHþü0Ó2@6#Ð×~°>@È´s·°¿²™¥N†S@Bµþ§ü…3ÀDû:G+À½M„Ì0AÀ(Âc.¸¸?à?’°yÃvè1@´l#³ð'þ?å?¿)5.V@Ch‡œ"Òc@$dø‰ðcÉ?Ö¡´¹ß1Àvb£9þ¿¡nËŒWÉ¿À ÒDÁÛ?^ƒÆ¬*¶-À¤îm1aÀ?(j”W§c@Æ{æ ѽ¿eÿ,6‰a>ÀN^µÁÊ—F@GÆõ¢À?à?«wxÀy8@]ã%ÑÝM@Q#Ðý„j@²?:on.V@ioÑ?².¤Oµ8Àß°€põCÀíBÉÜÑ¿¿\µÌå@Àn[ÂÁþE@Ø eR@ü^tãVѽ¿tBB[¡c@",pŒpDÀ\››`c QÀÆiɤ-‹?Ð?ÊÅ5”ë?7>Ï'&E ?uÊô5ÊB!@ïƒÕ:ð·2@mÜýn2S?É63îë¿x|æÅqA ¿Ùƒÿ.S¿OËF̹æ!@•-ÅÙ˜#@QP kˆ5CÀl{3…¥R@¯¼½fY’¿ÁÖ–l©ÀѸ%íÂC;@Tª„›¶˜§?Ð? é¿[ô@[$t.ÆC¼?Ë©TJG@¿ïŠÇöB!@®äbø¸¬p?|…†ïÀªOE¢V=¼¿–1í¨p¿6¯üÓõ5ÀEµÿ¶àë¿%‚tïC¤4ÀÝ‘¶–Y’¿}ú“­ŽR@m’žvz+ÀdêF:+Ã9À”qÔkÅ4‘?Ð?e8ÆÓÄõó?øM§/Ïëª?‚Ç)ëú&@¯ÍI¿Š6@M0q«'b?Œ<­ðó¿í䮬ð䪿¨ @‹ #b¿Á¤Ë @VúpÓb\@üIîEÀÊH|S¼R@œ²¹š¿cš$ÄI$ÀHבý¢'@°ãD]—:@eûO/ͨ?Ð?¨ö³=‡È @@ß\N(iÃ?Xq×ÃØI@‰2ã>?ú&@Iq^Ñ(.z?Q- /Á ÀtÇ®`4dÿ^A~²z'z¿Jæ`Ë5À8÷Ó*éuñ?˜"îlø¤-À"«Ì÷¹š¿ìî ’´R@j› Ü-ÀÒ2öA~'À-ù4ŠÔm:ÀdŠÔ•nÛ´?ð?±B¤S˜@, G 9Õ?NçÖVë9M@!çà‡Ì[@~gFqR?Ö«XzÀ´ºoÁÿ2Õ¿¸w¤ÌM¿NéÍ6ø?@¼ÍÖ×@'4@ƒÓ !vçfÀ¸`çàÓr@óù&A›mÁ¿øÈ©®‰8ÀÀí- ©%T@fŸ_GçY@‰J×>âÊ?ð?.¢ •%81@5¤p|ê?™u×ÏÑl@°-Í6:M@F bT´^¤?R¿,›?31À¿mâËçtê¿ñéèX¤¿â×$ä©UÀqtÍE)@(èØ¸öAÀ‘5KAÈmÁ¿€êîòêËr@´‚ägÿ˜NÀúl¤0’UÀ±°eõ»[ÀŒ27øŠ¸?ð?¿út–u"@6gMÙà#à?Çö6”IR@»)sZÁ`@üZ’…9œ?ÛüñÄo"ÀñÿzzÊà¿#ÁG 0œ¿ªý*©WS<@ufR‡[+'@@ÆKiÑhÀ¬H̯ër@šaØ«7Å¿Îiö?Ì=ÀPlÇ‹i3Y@PlÇ‹i3Y@%Þà?Ë?ð?]+ ߀4@ÈBP kíñ?=¢‰Õíp@÷u×xR@ƒ~O'¢Y¯?¾ ¢hz4ÀUÃütÄçñ¿W&xÀO¯¿Øù‚–ö‘UÀÒb‚t8Æ5@±ÄIl¦î(À3%J¡â7Å¿?‘ãr@±Ðú PÀóBÝûÌ[ÀóBÝûÌ[À÷òSC¬?à?ËãFt@Ù†ÐÛ×?îæÌ»²E@nÉ´ßS@Ë%½L¡—?gÖ“« Àà}èrÓÒ׿‚ l™—¿i/cµ&A)@2• Zßfý?›q^ÇZÀi~ÞËc@oÅ'‡ò¸¿3#ê+ŠÊ0ÀÍ˃4K@´k7¬{H@v§o >~¼?à?# ¥†ûI(@%ÖŠÊ!è?©„JÁa@)ÔÀQ²E@ᨥÖÔ§?j!岎A(À¬ ¢`Éè¿i  t’̧¿¹zñ£ƒEÀ)O>b^/@Vý07(@ŸeÛí1ޏ¿jðg¿ûb@ýæTúë@À\"]WŒ¬OÀ!ÒÓ±LÀç^”²°?à?l6ˆ.ÀË@e&Úµ6á?Ä*"¦•«I@´µÎÑ^IV@Ðz_\>£?5 ÷ïÀÀà»<00á¿–Âr7£¿æ üË á%@À7”¸†nü¿füdýÃÈ\ÀPJû³>c@‹BÝX0=»¿ñw÷ß3À÷n€cJ@àf§–ó¿G@õ-7À½?à?O5͸©Ÿ,@|ìÂÿï?Õp÷žc@-^î׫I@x–e×ßâ±?»€/Ñ”,À!¸>¢óï¿ãáVÚܱ¿_eYÑNEÀ°µ‡ÆÉ4@Š‡Ù¸÷ÀQ,”=œÞ࿾éxjH¿§¿¤ÔZ\Z @&Y¹âÄÀ)tù»ÆxPÀý ClZNS@D±¸­¿«º‡pì'À(BðJ.K1@4ž¢ò<6@Àòº61'°?Ð?Åø=üp’#@g9N`+ë?ÖÁ_‹VÂW@ùç¢DA@º7z^Zd³?ä’,͉#À\1£™ë¿á¸*¿Ê[³¿’ Å G–5À7Æí¹õ/@Ï"§kÏ4@Ãy`Ûý¸­¿û+míFS@Dvˆ±·|3À‘´ÿÔâ7Àâ•ÃHíµ>À²•P Cµ?à?A•À~Lh-@Æûk®÷?_´¾ ·S@ƒ„¤ÓÝ/a@pÕÄïÈ#Â? ßBÁvZ-À‹™ÁÐ ÷¿«c<@¿ˆ§#7a§@f“´±™ï$Àd—Ź®ŒaÀÎÆ.h hc@ܪó‰ü¼¿ (“c¼f:ÀÒ·Þ|3@EÌŽz¬sE@å@ÍÀ?à?´ìîP*¸6@ãòVû×@×iž_* j@‘¸Ü ÷S@eÓëTÌ?¯òœz­6À•®M–ÏÀŒåž<%úË¿\­sþ{²EÀõ‡óC@¶–žŽ‰J@¥:áÓü¼¿¬¾‘Ôac@h¤„!paDÀâéØ_”ú;ÀÔëæyOÀ[gÊ̶§?Ð?Í®ùè{Ñ!@ý×a³ï?mRãOdUF@Cµ½n˜S@.ñ»Eû,»?®g±¢È!ÀÇÐþ=ï¿Á!Yt{»¿ „T)‘†ô?`1—ì6À9ö ÑQ§RÀØ¿Ew‚S@ÿ$ûÏÛ‡ª¿d§¦ƒÛî,Àxˆ3¹¦4@b"šÔu±?Ð?[à߆ @*@΋€Ôfìö?ãŠ'“w\@ö\‹úUF@ºíÂE Ä?“@]3*Àûø Ááö¿Úl!©®úÿÈLìOÚ5Àlÿ~>6@Ò¶ÀD@@ªúP ˆª¿‚•õˆç{S@ÄÁ(q€K5À©Ä£!@ÀE„/ÝÑÛ§?ð?dEÈåý @3­Õ¨×¿Á?òØ)\¶3@@C¸_(T@í1¿€®Xw?dNKÚFö À Ÿ~h»Á¿Ñ]aÙRw¿œ³”ÚME@uä Ö€¹F@h#“±;fÀº¯Æqƒr@Ÿ¤‡ñÿ«¿2¥ïOÀ™+Àd¸ú~QWU@4ªFœe:É?ð?ò™îH©,@>(ÆÿTÇâ?müÅ4Þ0j@p¦Ï1à3@@J¸/WB³˜?:âN&‡†,ÀDW ¤Ââ¿—Õ¢­˜¿@à°D=÷YÀ/²-7;ÀXÄÄ“XÀnv¶Ó9¬¿¸èQŠ7{r@ݰ¸+MÀ×j¡…úsTÀyxôEz?Ð?- |ØÑó?ë^ÜS8q­?ádâЉ&@“ ÍÇo­7@P3#iIÞe?»:¬]Ìó¿@Q’ri­¿xš­š=Øe¿S‹ÑC$@Ñc{0Ô½!@³ê¦QÖHÀ‚ÖØP|šR@ô1]¼D–¿ª­¬†"À>s=™Í'@ÖÄuúåÓ4@¾Ðؽnª?Ð?%Í=Oìä@ØíÍ8±É?/ò‹ M@ ÅÔÂ&@¬jNô£‚?”@àÀe´•îÀÉ¿‹öÌž‚¿Tå^\˜è9À•ë»Ûì?Ëi‹H2ÀÅÓžõD–¿E"kð‘R@Þ*›ÁE¶.Àlàä3÷'À^DÈ Lø4Àg ä#!“?Ð?„™×l­“û?3¬‹Ùù·?eÁg},@°«2jWü;@‹¹—B]s?M»›E‹û¿?©6£î·¿?‰H-¨Ws¿ñh”4§µ"@.¨ ¢e@äËRÒïIÀ$M G±R@Üù÷ŽÐ;ž¿Ý÷‚ñ%XÀ^¸­M4@^¸­M4@Ñ4Þ‰L¦«?Ð?pú‹‡jð@šï+ñyµÐ?M‡›…P@ ±—h},@\,mŒ?‡¯VêÀ_&b°Ð¿ÜõÊHyø‹¿—ÕU@ã9ÀªQBÖ¬G@~ó®í;)ÀŸ¥Ÿ<ž¿Jþ¾î©R@ÕCuO$0À[*@!5À[*@!5ÀNb™IÄǶ?ð?HuT7~"@ý„^Áxsá?±c[ô¼¸Q@þ•§ÐOz`@×àûìw ?W…Ø=Øw"ÀÑ›é¢má¿ì=)Õjr ¿³3òã33A@ë…— c1@ÎB~€…ÙkÀÚáÊÆJÉr@Õ„x?AË¿­¤ä³Š½:Àì8×vjY@ðÖæQ•ÄS@—FºJ#áÌ?ð?·-!>;t7@º%ñ|'"ö?ª}S`»q@%7~¶ê¸Q@³¶êîã´?â'ìˆcl7À sÂÓÀö¿ë?ô Ü´¿Æ—#‘çYÀ¼è‘Y5@d) ž@ ;Àz mÆqË¿\°ÛgqÀr@S Û²†ñPÀWÆ+^#T\ÀÑ}>IVÀ niMwš?Ð?†¥„_#@k’öDÖÉ?Û Å|áz5@¹U@7šMC@mV® Ñ ‹?0¾ ³CÀ1]GnÉ¿§¬"ì‹¿è`@§ã Ø—@h€­3¤ÏMÀ Å-~áR@ÓOCký¥¿6´õå9À1ïj–Yu;@;tä‚‹83@œ½Æ#U®?Ð?Ì+þ ã{@Õ*­n#Ý?yÐ-ã…S@xœ7ó{5@}`ÒeÑãž?È2ÝÜqÀ[µHã~Ý¿Ôб3Øž¿f˜2ìëõ9À¨SàG½&@3ø)¤äî¿Ýž— ¤ý¥¿ÆKØR@HÕÆ”ñÂ1À.ø3 !@ÀAY[â§”6ÀÃ=þ‚î/®?à?QßÁ,Ø@“±ÎQâ?átãp$‡I@:+U —zV@¯À„¤=Á¥?íxÍûËÀñ1›IáI⿎+;¤¸¥¿F ˜fv+@hŠ¡HÄðí?EŸ°Ñ_À%ýA}Gùb@¸|ó˜l¸¿Ç»—ªå1À¥°‡¢ø¨J@rÈ+Øz©B@”b¨µö`¿?à?ÁŒÄ 0@ŽHÔd ó?LmÜåqe@áà[f‡I@[\¸ªŸ¶?SÅm0À2ÉAIÝó¿²€ÒŸ–¶¿f3Ÿ»·JÀ}4SIJÈ4@M +<‡e#@.4Qß«¸¿©¡þR˜ðb@^Mz꽘BÀÁÚÁø‡PÀÿ¨ÂŠ#GÀ‰;•Ìíø ?Ð?D$ ±&_@þ«©¼³Ù?4Ù_ûÀß=@Ü‹hìJ@¨,Òþ ¡?„ƒéVÀ£øø¨Ù¿p:û‚¡¿q L=o†@t³…– xó¿ˆ'jÿïPÀö—³NÑS@–Jzøª¿ fâ¯:$À+ä8·†B7@ÌžUL2@Tdâ3S°?Ð?=à ›ý£"@HeÏ$»ºè? .a%€W@`Xà=@UhŽàOg°?„¾›œ"À;°6°è¿eE:uU`°¿Áµ^Nb2:À.» kóN*@µ÷©ëŠ^%@¬§àé;ª¿ãÚèdd S@!ñs3À¯¸ýj{>À¬‰Rµ7Àª®³¦ÞÂ?ð?âœõü7@J‚𿈷@¹wƒCa@¨h1ˆUìm@÷:¸ÙŠ,Ê?ç„×ì8ñ7ÀmƃÔ{¯À6ÿ)¦ Ê¿¦§úC3@øô/‰Ë%À6+ZèsýqÀe±É*s@ù¦K“Ê¿äÌ¿Ú œFÀB°ÚxæQ@B°ÚxæQ@­ªMr÷Ð?ð?*G[a“E@P˵6îß@G*’±y@"6 °Ca@“´‚‹×?>D–“‰EÀíàÙcrÑÀöV¶Öπ׿§Ë³ø`aZÀä6!XP@{™èôˆŠP@0C®é^“Ê¿ñ‰Ê»"s@¢µøMRTÀ¿®›JXÀ¿®›JXÀ´ÿ¿8@ÉÄ?ð?>¸Ó]U=@¹Z9<@üÑ­¿c@œ»ÎTq@m235ºÓ?ëGø‚>G=À¾if§À¬êÒµ°Ó¿œYsCÄR-@©ƒY¸10ÀbÉesÀÐÌ=Ds@CŒä…ä™É¿²¬Ì7P IÀÉËÛè SC@NRÀË,éP@gÝ~í±Ñ?ð?á©Ç;ßH@D†ÿwe@µÿzW|@Z)Ïà¿c@)ÃFuý¹à?#ßšÝÓHÀß¼+¦[ÀNòîï±à¿d7¬1œZÀ4·•àP,S@ <ú1kV@vr &šÉ¿Šh×(¬½?ó6Ö+¶!ÀÁŸð¿s@BôÄ/½¿tñôq m@líÛ™»Àõ‡ ],TÀrö“U?^S@÷E@%䦿=ÅïÆ†+À§îÌlÿL0@“L²ÜE²?Ð?‰¥÷蘎,@éz®ˆéëù?Ÿ›ËЈ‚^@i®>×eF@S“1~‡Ç?Ùj:(€,ÀÈÎÞù¿Je”Y˜{Ç¿!O\ã:ÀÙ♀×p6@jÂÓîHQ<@5,`䦿„Q~dDWS@¬àØ 6À.ô±øX}9Àü¶ƒß”¤?ð?†:O½Þ @ÕÿîýèÂ?ÙKœ;-¼=@‹O9Îÿ‰U@Àki1¥{?{ î6®× ÀBåYÕã¿cwõO¦{¿Œù­ÌgÎH@()ÉkˆÑI@ v4ÐÑ5iÀ û6obr@­é$Wòª¢¿zŽ4òy¤'À5ãäç‰H@+1(¤ÖÊ?ð?ƫꗴá0@*}¢G®è?ýi“1vm@¼¶·z¼=@üÚøøB ¢??Ý\Ý0À,û£SL§è¿ðu§ÒV¢¿#:jE›^À¦õÎ[ ÀkÛÕ%^[À¾r­Š"«¢¿A& ЃYr@y€ÊÐNÀŸ)$méÕGÀ!·oÁÑ­‹?Ð?^ÏKCRqó?Ÿ±ƒa¯?”ùeæ$@²¡›ƒ 9@*öý·mði?<ûëíƒkó¿@¦Pœå¸¯¿,¿®èi¿¤%< w'@|™[¶šÄ$@j:¢¦ KÀ³2c5yR@È›îst‘¿w}v~óÀñR궪ö'@ôR궪ö'@~HÑØ ¬?Ð? *„¾­µ@W STÐ?¹£Lƒ6P@ê™u]Ææ$@²¡l KŠ?œ+mÿʯÀN’´6пQÑØ7ÆCŠ¿Î  >À}|¬ò 'ä?ܦ o¹5Àþˆm¡t‘¿–ÌéöoR@-:I-0ÀF ~X©l(ÀI ~X©l(À‚%e07l±?ð?Ÿ~¸FÚY@B:…)§õØ?|\ 5ÞuK@ôІÅÃ2]@ @øúÆ–?ve¢ŽðPÀò\ñ„íØ¿Bí™ÎŽ¿–¿àAUÀûE@iŒ@@MÎ* mêlÀÊ‹6r@mzÙ°A7¹¿1ž0‹54À¶z¾ DtT@¯gGÄM`G@Oáom@BÍ?ð?¢ ¤Xzú6@ÙÔÎL&øô?”½CÐq@‘?­%vK@û>ƒÊ"³?׆àfýò6Àmú/öPñô¿™ƒý޳¿²9ªÇ12^ÀRq¥ú˜¶&@þ&Ú PÀÏ·Ì‚7¹¿* ‘ÁÆr@ޤöPÀNlP|åUÀé[˜DIÀVŒŽÔ •?Ð?É8£Üo@Po8E?ÈÂ?T4C²úG1@lQ\M2ÿ@@ò¦I"ƒ?Å6ÛTiÀa5Ð.˜Á¿3È¢‚ƒ¿IØÍýs[$@§kûD…!@ÈV}›mÕNÀƒ-áªy§R@}|¨T—' ¿Ô58>†ÀOù©“Ÿ9@dO%¼Æ&@#Õ•Âì|®?Ð?>W§»@h¿Òä%;Û?WÝn†>‰S@Ï”?Q'H1@ã+±½›?ˆ"ŒI‰±Àƒ6´€1Û¿üڔݳ›¿RŒ‰RjR>À¼_'ZÅ@nFõ Á$À² Á' ¿FÏòR@Rü–ÙÂ1À²¥ð-×<ÀèH“€Ó¢)À×(ºÅ°¨?à?5gÔ[Z@Ð ,È cÛ?Éoù–wE@qÉËQ™ºS@uáyNŸ?G«×Àõ>®¢XÛ¿ÉãVd Ÿ¿‹“•2@-ª2wܺ@4[Y úe`Àå¿b@_ÙkUE1³¿ßƒñ†ì,À’ˆ2©¸žÍb@ÕÞ—Á.iCÀs'xÕDÏPÀ‰¥&ï:å:À³.(‘ À?ð?/DSnÌ\3@šp<*â&û?¶yÎU¤]@ûË^V4$@ñ¦Oóı?Ð?Ö%«°âÀ'@‘_d‘qò?Iâ½Z¸[@òH»D.A@ÚÚì 9¤¼?7 7ãǵ'À6ú!òhò¿^½>Õ–¼¿ÆZcn\@?Àüª,ñ"0@ÚS³rB)@â4»*'§¿QdPÿR@¯ö|Ò!5ÀBßA®8ÀD¹#²Ü4,À‹‡G|Ó³?à?t(€\¥C-@¼ïºGùù?žê8²S@r,B˜a@¬=1ä‡Å?f4î;5-ÀMí©œ ù¿îª]¼I}Å¿ŽgLÐìÉ#@Ð)†óÀ*õ ådÀ¼é+5û c@<ȾÙÖíµ¿u Ú<·7Ào¿¬¨‰“3@o¿¬¨‰“3@9€ÀkÂ?à?{¸~Â)3;@—ꥪT@XÑön@ÿÎñÅk²S@M‚øÔ?M[—Ä%;ÀûÉçE-IÀVŒÆÿ5ùÓ¿ÏJ¤Ýq™OÀV¶g©OFC@nü‹è-UB@ŽÄyv `š c@JÔþè•FÀŒ‡Œâ<ÀŒ‡Œâ<À'7+UE¾µ?à?­DÃÝû®1@\‰ôöç¶@:{zÅ_V@hÏPÌÖ`c@e˜Ø˜Ï?I‚ÝÌâ¥1À¹8î‡N®ÀkÍ?ù–ˆÏ¿rǦ2@¨éôD À²¹~ªeÀrȧüª:c@—¨Ž¥ô²¿u¸±þÖ&:À‡ö@¡ä2@Jb$Ã?à?Ÿh"åÕ ?@ªÝIÄYW @GzFkRp@ÿ;ð?ÿ_V@y‡Öñº»Û?Bô¹]Ýú>ÀSYÏIAH À 8$=v­Û¿A¬lÿOÀ§ Ùã–F@ÜÇã7H"H@IÙ|€Öô²¿!†í›q3c@¢€þö­îFÀ”×…Õñ’=À…¸!!V¡?ð?å.'ES¶È3ÀTÂóð¿gá»ï©¿ÖÅX™aÀlç|¬žVÀ_ß|´^À¾WÙ!ÈÏ‘¿Ipµgt8r@ï»o!5PÀb¬nK_ˆ?Ð?ðÝÎ^Èò?Ò—úˆìÔ°?Z1r€½r#@Ë}ÐÌ…¨:@¿Ûµ*n?ÔDÐUÂò¿$³„ϰ¿íxs!n¿òºÏrÃõ*@·y~õ§Â'@= ·¤´ùMÀ¡\¨|XR@ pó–ÙÆˆ¿–»*4Hñ ÀWÂéŸE(@½Æ:覡­?Ð?]ÓÜ,Ú@ߨ2„zÔ?¼Ÿ&Æ ÿQ@õÕÛ·ïr#@zvZ¦ùY’?ÆI: ÕÒÀ•´µïsÔ¿ÐÞ@¹)Ї«‘CÀä×íá裿'‹%)4eb@†°öküÁAÀô‰ šËHFÀs¦Î{ÜQ£?à?… y©D@~)˜Ô?’¡Ál²@@,º:3£Q@Ðn䟼–?ƒ6ת=À¦²9ƒ Կ㮀y –¿n£S(¡7@á`âRÑ,@-ì½â`ÀS§±,:†b@LV µª¿e=xr`]&À&3Ã[×ÒI@ó;/k² À?à?͇U‰ÆX.@þ[óÝ­ð?G>ÿqne@A[ÔÝ—²@@ã˶™U²?"žÓjM.À+ò ^Ÿ§ð¿Ä1~¼N²¿ Ú‚ÌÂhQÀí&à!y $@Õj|™ò;ÀxRµª¿X ‘Œ&|b@ï-,b[ŽBÀhæ‰QVMÀ>}ÈÑï–?Ð?ãQ]@÷Èö!2Í?þñcÃQ˜4@š! GD@µxáZØÁ‘?°¥¸öÀ}ƒR@Bÿ•Л7 ¿4¬,W¯À–ûö^+ñ;@pwÙœ¨°?Ð?oÿ“q!@Û‡gÅe7å?zG¿ÇUW@Dª×ð†˜4@iÌçdÝΩ?̯לj!À"¹äß.å¿ÊKwæ~Ä©¿Ú)ZŒAÀrdúãÝ>@ÉÆTÜ`¸ À JK°Å7 ¿ £«ù†“R@ËsÚUç^3À6‡Ù¯@ÀÒrÌ]•–º?ð?½³ˆ–‡À.@«ãv¬ô?BLx,9ÇX@?2¼v‡Bg@QV¼¼Ê»?TX V³.ÀÞ, '£ô¿¶—Qо»¿}ÛÈô'³C@$´¾ú))@Xç~ßrÀ¹…‰-µr@¶âÿÐEY¿Ü‰Î£?Àæ]&ÛÒ,[@ªËP¨£æù@”a^kˆk@áGªç˜AM@m®†w/É?-·˜ðCØ6À­ëœ+òÀs%G£þ#É¿'Õµ!äQÀ¼î餧>:@ Ã5­Qa@#ü@pásüZZð¿!§ÄÂhôtÀ¿C´¹{år@µLªñ‚ÿ.J~``DÀv<ØéQ@d͇åÈÒ?ð?„^­ ·J@§Ä¦ V@ìyñÛ·Õ}@¾Ô1’a@ÕõlÍoá?…î*JÀÐeÛúËKÀÃx2£fá¿ýËøp'bÀdeR’$P@ÙôÁ.A@S‰Œ $ƒÃ¿ÂØ•TªÜr@œeµJ‰ëUÀšé“fYÀ›Ûáà¢?Ð?,Ô8Ó.@Ø“…V7ê?ðNs¯C@„:¡àï)Q@¶Åžd£Œ·?ïL!# À}—êè)꿪 ¢(É€·¿ÚJÈ2@¨41D"û¿`YG^VÀŸˆ6VþR@4^¥¡O¢¿ $ƒ·¢l&Àî•4&PÑ#@XÝÏ5³?Ð?ë b42¶-@xÃ0µ°ú?/àkû†#`@£ùu27C@°¬¦}àùÇ?ïâú=§-ÀMªäCF£ú¿?ô»FÏíÇ¿qÓ´‹«TBÀ޲T3@”㌎,@†©.~¢¿MÃ6öR@3yàÌÖÎ6À›ôæ‰P-À›býñƤ?Ð?8—¹ž!@½õèÆ]ñ?:èá¶DF@RKºlaS@$š1ÄÁ?¬m‚•!ÀÃ9Êã±Tñ¿!4¦ÐÁ¿ìŽsÆ¿Å@.íÀXÒ£ÀÚö9ì"WÀ{¾ò¶S@þ¨È~ß¿ç‹[^ÍÐ(Àhþß¿ݳ?Ð?”J§DLÛ0@1ÝB|*@†ÇÚÁna@ñðw“ïDF@p·í_Ð?5N(|{Ò0À"U2z”Àghs]Wп®³©rè–BÀÈHaƹ°6@’Ò™*Ûû3@öÖ+‘¿€‰ænS@¿ž¦Îw·7À¸÷ÙvÌÎÂ?ð?p0E˜3ï'@à bËb´á?ÂñIþAPT@¨q›ª*³c@û(Z1š?ð„´?›è'Àãæ¯á¿¸g€"*š¿ÉF™YQr@Š›ÝÇÍ¿sÌE6ˆEÀ'irþ‹Ä?ð?´Ñkð‡)@IU³F¼ââ?àûƒ:e@ d¬qvPT@ÙœN¨ð›?×ò¦rç€)À‡ø|ˆÝ⿜×Áeõ蛿³LÂÝÇÍ¿ˆ“¸nÊNr@`ŒÃXõFÀX&iS¾â£?Ð?tváEå\ @­Ók3É?8syVÙ€7@CcúçÆtF@‘޹¨ø …?nYWÆS À+}øÚ—+É¿œ«½@š…¿è³&[Ò©¿EøC…àô ÀGž4•ªÀð ¸hR@¿4E˜°¿×`Rá&ÀÏÏzË%5@ÃÿUñ¥?Ð?0¡ÛÆy4@dc£¦èÐË?A UÓÓÇH@*öX7@ÒÕY(߇?åb (q/À¦¯ì¸DÈË¿ø™«Á%؇¿PþO"ƒ[Ú?ô@Å‘ ø?_ ¼e{¨ @)Nâ;°¿ó¤eR@è`ÎÃ=)ÀuOE¨™#ÀˆDEù´?à?˜ê¡ ¥Ð!@”9R2—á?e|O­·òJ@ƒÊÙ nY@ÅÔ(Åx^¡?¾¿ûîzÊ!À?yÏ‘á¿âmßvX¡¿X |ó×Ô¿¦Ñ`ú+Ñ,À¬¤?Iâ4À‡ÁÊm€b@{ð@RûòÀ¿¦¥ë@8À^Z rE{R@ï’)Ù·?à?©êkÎC$@î'.[8ä?LyÃÞ¥é\@9à8BýòJ@Ï›„ ²Á£?‚<«<$À‡qÏÔKûã¿ñ¯ nܺ£¿Í%®ÞE÷?ÓoÏ3@®Žá0œa)@}FÅ'óÀ¿GÄzÖ|b@ÈM¿i’;À³Ç®)¤AÀŽ1 ݦ?Ð?©j2¡4h@/ÿ„»Ç"Ø?ëˆïµ§>@VCÓE¢L@ä2]g6›?€Áu‘ `ÀÏ œ_”Ø¿Y Ã,›¿,Eí™ý²Õ¿ABåLx%Ày‹÷…T¨/À÷¿Vö‚˜R@e»%•t±¿,2u½F§)ÀÄÛúL»G@UVÍD Æ©?Ð?o³G<2@„•L2Ü?'ž]‹ÃµP@‡»T¨>@L<ÁÀnÊŸ?é^Àµ©øÀ„…õŒ'Ü¿›3_P¾Ÿ¿tlÚ@-î?”ï1jqÈ@ôéf»Ò"@¯éâ7Ât±¿œËVän”R@7!)¶xó-À›fÌS7ÀFhèÍ(-Ç?ð?*+›áª9@ö«8–ÀM@ƒP|ÞPa@ôòèê³p@ëàÅnXÙÄ?¶Gu9ÀKº¨ÍúFÀàüpJ¯ÐÄ¿®­M—Ào¿Z€:‡LÀ‚K¯mTUÀᛇ±r@‡äv1zÑ¿Juab³KÀØQêC_Uj@A–ÑX¸Ë?ð?¿¥+™D‚>@g$GéÖ@ŸN3x3(s@8ž@2 Qa@H‚6òÈ?þÈL3˜u>ÀãµUv¼yÀÿ´n³çÈ¿v¤.6[ä@{:“;@=¹Æ†ÎH@ÿB—^zÑ¿_Iö|¬r@;î{ì¹0PÀra5av¦ZÀiÄG K¸?à?v ’".@ÿ®ËÚ­¸õ?CéçcqS@©zÈÜÞa@°~à‡ÃP¿?fÝí .À7¨àUó®õ¿ÿ€·ú¼B¿¿¬ÔXJÏü¿žÖß™¼AÀ8q£±òJÀû9ZðÉb@?—P¤EæÀ¿Kÿà‰‰<À<¤ðKLZ@€j+œò¯½?à?c­EðVk2@œy{L Žú?I¹­p§Íe@#ÓN•qS@ÒÜšðT$Ã?hiÅc2ÀΖ'‚ú¿)b-Âÿ@kÙÏ,ý@7Ýz€,ÿ1@Ö€#½Ã¢>@ºGqæÀ¿§ƒÛNÅb@ðÐs°unAÀ Òa+eKÀß¾÷î‘k¹?à?êºq4 ­1@ΗÃ@Óü?cüT#n¶U@†ÿ8}Ôc@nm Ç?Ãö¢é-¥1À6&ƒÝ†ü¿S1¥>ǿБé)&RÀrÊÓZ+EÀ™¦µãWPÀ8:]ãb@¨&ý˜0¿¿ÀüZ*>À5¸5\3¢W@pb­¿?à? Ç#± 6@ÿ$çóÏ@¹P³±§h@z,Š3¦¶U@}ì)½@ËÌ?Óa™š)ÿ5À¸Þ¬5qÇÀ•ƒ±Ö~½Ì¿P LУþ?VMT‰‡6@äžéú&B@ü+ß…é0¿¿tÝQ8Þb@ÐQÌ@³BÀ†^ùÔVIÀu…Z"ØŽÊ?ð?p¤žÝ¬›D@ Õi$¸•@ì™Ö !h@£ÜÒ:êu@9gƒ„Âà? ÞêH‘DÀî¾WYŒÀêP:*ºà¿0-98Š‹Àä~la…XÀ`´GFcÀeê+íRýr@=bÊWÙÊ¿Ë &‹OÀ£¼Zb@½!Hì×Ð?ð?ÿÍ}ÿ¹&J@£wVgs•@Î΋ò·{@Aæ¡#L!h@”…M„´Då?Õ÷¨“ŠJÀæ(`‰À~ _Xû9å¿Ê<‚Û¤@¸72éeK@—qÕŒCçT@ñÙÆÙÊ¿J«&X ør@ÎXvÿSÀŒ"Õm@TÀ!xµXó´«?Ð?irªÑ¯á'@ŒA.ì÷?ßx¾Y²J@È™àÙ!X@ÃS²öÇ?¯þ¥¡Õ'À\ÛÏç˜ß÷¿é!RÈêÇ¿¸º"âéúÀn~Uºè;À(ÂŽÞýDFÀ"²‘>ÞS@£ˆ-=y¤¿4phØKŒ0ÀÏ ξñ4@H‡~9ܱ?Ð?XÃ9þ‘Í.@ÛËY{Ûþ?¼2ºâ_@R:/­ž²J@Æ8vëªèÎ?Äb§®]½.ÀÞ6¶ àÊþ¿n? ZhØÎ¿Yƒs©¶Ù?"Ýÿð6M0@Zà}Ìj‘7@*÷» ry¤¿F«¼_¤S@}™<{S5À-×P£‹Æ'À¾@Rýݬ?Ð?ÿÎÛ{†+@oå¹x€þ?1ÓÒskM@)Mb{Z@Y÷çmæÐ?¨uôŸŽw+ÀXõ\Fîoþ¿lÂ'»CÝпL¦)¹ÍÀ+y8é”6?ÀšŒö4‰TIÀ' 3S@ËÝY©x—¿Â†‹«´W1À»¼:‡ã²?Ð?K›Nõü2@†0óÿÒ÷@|éiñ@a@qî|¿kM@‘HZeš Ö?×­°b7û1À¶žëéþìÀ…Õ?‹šÖ¿{»œÏÑ­¿»4•üF3@ƒ€¢ƒ$:@cêÍCÊx—¿nú1M.S@ÿ½Ž«Á¯6À Ÿ:vÌÁ?ð?$¥ý0ÀÔŽí.µ/MÀÅ´BgBr@ê½V;пð—V-,½FÀfš¶<†Yb@¾Bõi™øT@ýCoø“È?ð?È©:žº4@è ÁÛPô?!Ú5S›Ãm@¯÷°ãbZ@üòÝ4é³?);ã'|³4À¹+îÞIô¿HÓÚZ⳿ÜýÙh„0À>‚€í+@–êWd­@É:?,;пÔxÏ*>r@zœø’ª LÀ^pö}QÀ5Ù[‡´DÀ¯"‚°=]5ÀæÁ2Çx(EÀìÿ{É»R@ö¥t>Ìþ©¿cÜnBÏÄ-ÀÌó\I6;B@ !æôÕ4@ê•o²&±?Ð?6›AÆ^*@¡½ë`ËŒ÷?ýðQþ‘)\@Õaê±G@ô'ÍPÅ?¢æ¢‰Q*Àù†7)ù€÷¿hÁ¾xýÄ¿’ˆÃG@À†ŒÌ˶+@CU*Ïê/@®C]ÿ©¿Gä¸ ¶R@[vŸYp4À§Œ‚˜²4À3•@û&ÀZóÆóˆº?à?Ýïn£6@¤}q@æƒ×‹ýY@Í»UWD"g@ŒT¨W@Ö?Fý¼2—6ÀFhmDºeÀ3Œs!®4Ö¿ $îĬõ?Ï$Y©µHÀDLdXÀ œæÖ‰Õb@B'fd] ´¿rúÕéÊC?À¾Pù¡BÎD@¼Pù¡BÎD@a) Þ'Â?à?ý{×áý>@ÈY<¥º@[-rƒùno@rÕlóÎýY@œ'GºvÞ?9³\—£í>À‡(÷è©ÀfÚX¨ÂfÞ¿E”÷µ„N$ÀŒÑ0(8l@@ñƒPFÿB@TÒz(‘ ´¿ÞÐo!Ðb@A‰$8bEÀ­ã«¬ ™7Àªã«¬ ™7ÀØj»S¬«?Ð?¹G.*@Ts¾íœü?¤ã L@J¯‰ÁahY@;=c~]Ï?ßVË´ *ÀIí0€sü¿ŒÖöЇLÏ¿À„—µD¹?ñÎ|$<À)àù« KÀÙÛ|áãïR@•Lˆ8âÆ—¿¿Ÿ}Áe0À^h[ðMÆ4@áùÍö+³?Ð?£8Ù¾¡2@Ì]K#Õ@7XFSva@±ztû_ L@%h ½Õ?a\ØÔØ 2Àò8piÊÀÎ`ν±Õ¿Í}ó»ŒÀèPÉ3)3@ ƒöhÀŽ4@KI=Ç—¿UVP¸êR@¬^j¶ñµ6À÷FnM:(ÀqeyûÏÀ?ð?¹(¿ª.%@0ÆR.©ß?ÁµhxŠS@_‡]p¯a@ØåëÝݸ–?CÆÈà(%À\Qo†.þÞ¿Å+¨²–¿FýDÞb]6@Lˆ%t`š8@A°ú¹ã@Àø¥1eÙq@•ñ¶…)˿͎ÆÒÀBÀmÁQÒAb@o±:ì•Å?ð?Jk¢–*3+@;ZìΆëã?ÍXå÷LŸf@²S-ìOŠS@ºí@3Z-?%Ïž»++Àà ¡'æã¿©e.å`%¿PjÀëhBÀ~zIšØ@ÝB#ÎN¹BÀé½lØË)Ë¿ñáã‹Õq@ÚÊ ŒŠHÀ'Æ’š‹PÀ‘"øÑLÚ±?à?»±¦ï{@üR¿±%Ö?Ëc>‡F@P†0´CT@Ž}Å¢¤Í’?ð÷$‹s À•´1˜<Ö¿š¤ÚÇ’¿…Z¬š<&@O®«œ‡@>è*¶r÷:À˜«q1ïa@$[¹ÏG½¿Ýß«$¿4ÀC¤¤ ØD@Zïð =R@œ/›¡Dm·?à?åf§ç!@*€}8lÝ?ëØ~}xZ@µViN‡F@ ʳ’®˜?©=¢!Àu9xÝ¿Ùj¢‹ø¦˜¿â˜Úi%2ÀGÕ›EÈ@fÓ‹sb)À¤8TH½¿ èæ‰4ëa@°F‹@:ÀÍÙ€óo3À“¾¸ôAÀY2h:Ùæ¢?Ð??Ié¤.½@‘oæ¬ÑùÎ?LJ¾…OÁ9@ÊRä˜Ø G@± î9';Ž?Ë;„K²À£Ö1ïο>›þƒÈ0Ž¿Þn…ÃÞ@¦*=šâ•ï¿e­{jþŸ2À`Êvµ R@¢7*kÛ䮿b×6ŒJ%ÀlûjE 8B@lûjE 8B@U»ëòFJ©?Ð?‰ Ø|=@‘«äs¿ºÔ?éï2‰$ªN@O£’Á9@£ Î&;”?™‡¨36À@.£³Ô¿—¢<64”¿¤#Y Ê!À¶wÌx’ @¦·r’/ À<¬Q0+宿”=¿2R@ò ‰Õz,À…¯ ¸rz1À…¯ ¸rz1ÀÚ‡ê­õ£?Ð?< /Xs@–Á´YGÕ?¶èw:=@»+7T J@9xí„ò¯—?õ̼:À¼SøÙO?Õ¿|U»ÿ¦—¿Glb›C@Ž—ê¬OÀÔå¹Nß7Àñ‡CÐØR@ƒ³Ö¯¿#’ Yv˜&À~ú”¯ïeG@a¦åÝÖ2B@E·J0,«?Ð?»”Ý–5@L–ˆ‹úÜ?xJó$œQ@¼¨ÕïÊ:=@í5ÿ!! ?F›4 `þÀm™ïÜ¿Ëʦ  ¿îœ6 DÅ!À"óÍÈÓ@4ãŒiרà¿à¡MÑÖ¯¿VÊÆ’R@ü@ÒœÀ.À½ŠÞœ7Àv­$õ1À€(RØ¥?Ð?ŽÐ[ºZÐ@¨°D×`ÅÜ?~±:;1z@@nÐ+ß©CM@á+•N$¢?u}1ÉöÆÀç~u/‰¹Ü¿>ÈñÖ¢¿!w²Ðh@º\¶­ûøÀ=>êµV:=ÀcÖºO4R@èTx,Òí¯¿EÜ­~Áì'ÀF¿ßº÷I@Kü86i-B@£5m1­?Ð?·ã׆Ύ@ Q3t*æã?´½‡šT@èKÜÆ[z@@ƒ1žX©?Z»7ÑÀ =U¦ùÝã¿n‚¶L©¿¾Ð¢ðô!À‡»Ä˜r@è"¡E@õÆ$×,“Sb.R@h—5‰0Àʦ¼ÄßY:À'ÛP£r2À‡N|Yi¦?Ð?ÿÌ"zS@Xv&Ÿ,ã?}©6ÔbxB@c&¥¡4ZP@;d_x:«?)x*/WõÀ{í–$ã¿ô È·b.«¿vjS¶wL@˜s6jCã&Àé$çXAÀ{þÆ—KR@Šyäöö®¿pãA˹G)À—*mE«ïI@i7™°Ä'B@Ä8B‘(ÿ®?Ð?kj/@vñ"@à~êuæê?²»ÀÛ¹V@ÌA2…’xB@T ½ë‹³?Š´»ò é"Àª!ñ‹…Úê¿‹ïëÓ³¿æ¯™;‰Y"ÀÒÒFgôÔ"@ª‡¢<6 @ØF÷®¿Xm¢°ER@£.ïa¸1ÀºÚóÂ;ÀixåÝnñ2ÀÝQEr0§?Ð?UðÏÛçº@•J§ë:é?÷o`ØD@¯ò¹0R@Æ)òèÍ´?YË8¡à«Àzâˆø.é¿ýstM´¿­œìì@ZÁèÏV·-À·m<#DÀÓ+˜™cR@0÷g¹ç¸¬¿r|—}´©*À¯›wA,PG@‡•@ˆé!B@ Í<ø:x°?Ð?ÒÁˆÕ”‹&@DDmDíñ?(\´]`“Y@î÷ñ÷˜D@YÍ/„M‚¼?/oŸAç€&Àk;ÓÆäñ¿Cð×Ìt¼¿:›¼@ö"À ¸?'@×Så )§@¶éã1¹¬¿N -†Ž]R@©ð¸î2ÀˆY(¾Ò9Àb"2s3ÀŸh]I¨?Ð?{7Þå„"@ôxÃp5hð?Ï:GÜF@ö &­S$T@©€J-£½?QÑAÔz"Àdq§¬`ð¿Z„‚/½¿³_ðF@|¦Ö<2ÀF°å”üFÀ³+Óý|R@§ýÄêIõ¨¿ì â,Àñ5£Ã×B@ñ5£Ã×B@,o#Ý“s±?Ð?+ð)¸‘Ÿ*@x¹STL—÷?–d€« \@MÊA‚ÜF@×ZšqçÄ?¹ËpÜ@’*ÀÓÙšº‹÷¿¥â:ŒüÜÄ¿”RÀf¡Ì#ÀNú+@¾‹ÇÊv$@Ë N\Šõ¨¿Kû‹vR@fP?º*4À¼ O€÷3À¼ O€÷3À¡÷ö;8d©?Ð?¶Á\gz%@»i@õ?)£Ò¬îCI@Ä()Å7V@ÑyÒάÁÄ?éÍ..o%À Qÿ7õ¿Ò “Ô¶Ä¿Z²›˜±² @bË-œ_’5À{>ë­aåIÀ9íï•R@ðºÃ¯Fh£¿ñR9„-Àš¹Þ¼ìª4@dâB%B@AGæC²q²?Ð?’{ЍÄ7/@¥T_°þ?ôs¦7Lã_@h·ké/DI@%’[:E+Î?;êÿ3u'/À[V þ¿P¸û ‚ο™q÷ÅÞ$À¤®§P3„0@ƒ©1.žn)@‚(Ìxh£¿ÍÔDR@uB*i–n5ÀfAãËók'À7ÙfRu~4ÀÅrèw!‚º?à?CrŒö‡Æ8@ó…)4é @Ô‰ %ÀÐ[@½åjTPkh@$›·þ:Ý?e!¬ñ)¹8À³w¨1¯Ú ÀN3`9+Ý¿`…€ÿ´B@ø´…UÞHÀ Ê´ Þ\ÀÎu?८b@"§Ú§¿IæWA¤ý>À^ÙR@÷ÿ6«rÃ?à?ù?Þ)‹/B@›¾¼êÏÀ@²à‰q®q@–€D÷Ñ[@èßW­ªtå?ƒ¿mU»%BÀ¬Z¬–'¶À"›0iå¿“2Ÿë.6À$ÛŸa]6C@°…FÕU9>@GÙø‘§¿ÙÃÐG©b@òͺFÀac8H2EÀ³ b?²¯?à?6PÓQHý@b7ÊéŸOÍ?Ä—•ú C@™àAÙP@©m+e}…?ÚóóŠÐ÷ÀS æ`›GÍ¿öXq;„w…¿^ÄKáwº0@þ«áÅ)?2@GhDÒQú8ÀaºÂŸa@Ûœ’t(«¹¿À%z,-t1À;ìþq˜MW@!ódaQ¶?à?^Œ–|(@¶Ó&¥Ô?þÒ’³Þ€W@^®ªÃ+ C@2(éΖEŽ?{C±­Í À톮}`ŸÔ¿›þN=Ž¿vA`;Ààï()û?JÑHÇ;À\­´»j«¹¿ÔØUT›a@©À6ÒÔ’8À"Oè©31EÀ©NÇÜÞ°?à?t¬}í¤@ûP3äÁìÔ?*‚SðE@+¹PçƒXS@)¨íJÄ‘?KtÏ]VÀ&MPæÔ¿¼‰oÒ¾‘¿ ¤X¦ƒ®0@ƒú‡¶¥9&@ÿ/'+wAÀJ¹þ]µa@à¥øW"®»¿æl¢U«2Àôו´±D@ƒò’(ëGW@ÂÏÀ>y$¸?à?ʳ’„¡£!@Ìîª9ôÝ?×Ï1 Åb[@þÉ'ŒðE@ò/içn™?’x¼¸2ž!Àùƒ«áÿêÝ¿åg™¿ˆî£)I*;À1÷ª>£@ƒ »Deí5ÀÝåÍÐi®»¿Pq/Ðn°a@2åë‚¿µ:À¢-ö›¢Z3ÀWótïöÅEÀ†b^ƒÁæ¡?Ð?È­GFa@ýÞÍ7EÍ?1#k—9@›ü F@Œq„ˆŒ?!©üîü ÀKî%ü:Í¿i×ù¼~Œ¿s¶äT… @QC (@%zOÀçŠ6ÀüÀåCËQ@D /Ö7­¿ók¿è#Àû—AìÝB@1 ÂøAG@ÇK1Cü©?Ð?ª:Ë¥Ì@Õ~KÝA@Õ?¨TmÜ:œO@ècNQ9@Z¨f·”?Éΰ%-ÅÀ‰gdUù8Õ¿G†÷oL°”¿mÚVnÐ$+ÀÌ(ß<±h@¢6Êã5 À ¦•"8­¿µ¬\ÝÅQ@Ohnã,À2•Õe1À¯\-7e]6À2ý°HÚð¢?Ð?ã(bv@Öý­ÇœÔ?{OBNÏl<@ß3eòH@ã4-˜T–?ÿš”s¢ÀqXÏ’Ô¿Ãû+L–¿¶ôæƒ> @%á:[tÅ÷¿ƒÃ¶†ü¸;À¿A{áQ@›Sª ®¿z’ά*%ÀBBåÁ;G@BBåÁ;G@ÒQר«?Ð?¢¡­ž@²(—e‘Ý?ç”1­çR@QŸm³m<@ijÙk ?¹íB£”À™Ù>†Ý¿ñЃó§e ¿dù‹IQ+À tÉòÿ¬@TÞ²ÿDÀnK ø ®¿´wÖ«ÛQ@•k®G/ÀYvˆÌ’÷6ÀYvˆÌ’÷6ÀyÔ4ýÃ?ð?nJA[ž5@^m&%-û?ON I`@a©ÿ´Ýl@e]É®ÚÁ?Ʋ±z•5ÀÞUÕšû!û¿í•×˜Ö Á¿Æóh™»¯?@l¶¡ÅkÕ3ÀÖk`Àp&¬Â øq@ØeÀ¥–<ο"çÜRsFÀó9qƒkÉi@õ€)G5g@–k:PºÍ?ð?Ηõ@@ò¢‡õ[7@"Fì·t@_¤F`@Õ$CÛiÉ?+”Z@ÀK\˜A/ÀÿÐòåj_É¿ûài•b±KÀÜ"66>@ÎjªÌ$À÷ül¸ä<ο&Ovçñq@yCW§^°PÀÙÀQ3ZÀÍ©`–”WÀ%ßV*à Å?ð?3)lj›9@L[y|'@Jõî£òa@@ òHeo@ÈNáÈšÉ?2/uü9Àô‹[}#Àùç¡DrÉ¿àyTú£>@ ®Â¯yË@À)Ykk3cÀÏùÅûr@)„ªöZÍ¿èFX¬PÂGÀ#È_•íÁi@»Ío‰.g@-|cË Ï?ð?îóþ¶?C@¥_ú88 @éNÿ7w@çúù3òa@§x»8=?Ó?ˆ1_{17CÀoø«>t, À£§ë·6Ó¿¦|N2áFLÀý v6 *C@€tyXÅ?èÙÁçA[Í¿·Jäžr@úõ;§ØQÀ½Ëd åZÀxÀ¶Z‰4XÀBL}ºì¶?à?s9÷¨.@:~êÐ÷?phdT@™ ¬ya@ýQá0i×Â?´)èp .ÀêÄjÔªÅ÷¿>l÷‚οò¤›I«U-@P B^š7À§(çcôUÀUm›T&b@* VF»¿¹V‰5÷9Àsn£È‡'W@sn£È‡'W@¥Tc 4ÆÀ?à? €5ú—Ø6@ ° õ@â›Óæj@(Ê/ 8T@Éx§ü˜Ì? 03ˆÍÍ6ÀÃ`Ü™k À¨}£6z‹Ì¿jùåû =À •‡è|…7@PE·Ô3Ø@3 Þ{œF»¿mKLâb@;)L‚DCÀ)™7ˆ×HÀ)™7ˆ×HÀ9 l0Ç?ð?ûð½P“A@^l¿(xö@–r"½2f@›=?^s@h½&Ž FÛ?XBƒ™ŒŠAÀÂ÷¤çÀÑns8Û¿FIæˆÄ;@j.)ÂVNÀa+tK?ÃhÀ‡ìZ!>r@ é\]LÄÇ¿çîRžtJÀ{G¦üa@x0üC g@Ú½ŽS¤¾Ñ?ð?º¯åìéJ@‡Q%Ü@´@¼àj#Ç}@uqt >2f@úè¦õ<áä?ý/PÖ¤ÛJÀ6E,n¨ÀÛÛ“äÒÖ俎f ™NÀš‹µ/L@æG.ÚZ4@Ôñd»‰ÄÇ¿B‰mÃ7r@¢¨b‘…Ó‚6F@T[þmö@@ á8JFVUÀ)’ì¬|q@ÍykÝ»üÉ¿]äÞ®bAÀ€Äqó¸‹T@¡5N0§®i@ÞÝÍÝh×È?ð?¨3ZÜU52@œÐbï? èÙ½œXl@E—1JU@ˆÈ²9lª?íÈŠ¶/2À÷Ô€Z~ûî¿êè¾^dª¿ jŸÅRÀîçÕ•FL$@rµþCæõNÀáÈ/÷þüÉ¿ƒžùD5wq@§Ùêe]#KÀ›Û@«çDCÀ–!XÀ[zE\ìÀ?ð?ƒ×uÏún,@?c¡Y(Äë?T¦PX@§¢Ûì3&e@‹P~&X«?eŸÖ8e,À›Ü ¡ºë¿(Ž÷ «¿=O­ãÔF@1‚mó/Ø3@O 4&ÚYZÀãwÓ’q@Ó©ùsË¿³D[Èë”BÀæ/ûõa@_ÿh‹¨i@½óO¥ªÊ?ð?Ku«th6@¨N XÕáõ?h§ùivLp@ÂVNPX@áÑ~Ì^^µ?¸9Ä`6ÀÀʲíRÚõ¿¹ú“ Wµ¿~.¶•½)RÀûÈÆ σ0@Ì~Û8|jIÀÆP}Œ@t˿𼙌q@——l7ðDMÀâç†tOQÀDKMv¦ºXÀ{osàñÁ?ð?š@$Øk'1@ æ»t‘ó?ŒÅ'tH‘[@ó Ä|ög@0çz%ú-µ?ÍØ ó 1ÀÇV}`ó¿ó~&Šü%µ¿œaŸPâÑE@UÙmʼn@t…¾w_À\ÞŠ«§q@µb7ö8TÌ¿Œ»Ô´ÌCÀïrçïg@ÏFÀ'¢i@oñŽ!wÌ?ð?0·JƒB;@®$=Jþ?Onq Á˜r@l3~¢‘[@¤ßÑÔÀ?¼]3o:8;À-ÏdžÏ>þ¿bG\u¿ÍÀ¿ùyÆî~WRÀ–²Ë¯¨j7@‚jn[DÀ½Pæ‚TÌ¿¼+»^¡q@©áBµMqOÀ Ë¦QØVÀ@âœË!bYÀyÿû’ù²?à?ug´©Ü€$@ÓMiÌ`Àé?G”Ø=O@FŠáVûZ@¡Fä+°?Þ/n rx$ÀZN­Îµé¿­<A%°¿X²IíÐr5@L„pÏÀ¯Ÿ«ÅSWRÀî„Å—¥½a@eÛ¯$ t¼¿˜Æ;E 5À¬–Ô”z›Y@¬–Ô”z›Y@CïÆJž]¾?à? DþÓ—i0@\žû ô?,1ïtue@ôñ+ ŽO@ýÍÉùÆã¹?nÛb0À°9‚Ë•”ô¿Rï¹R&Ù¹¿‰¾ÇVÞžBÀ[RŒöÞ.@ÖÛ¼Ò¤}-ÀNó¾œit¼¿mZ o ·a@~õš°qÔ@ÀXH >¬ JÀXH >¬ JÀù¢ùÄÄ?ð?ÿž‹åL8@#>Y¦‘%@õнÊea@>š*Ç/6n@1ÅËò´2È? )Áü&B8Àˆ=WÏüÀKÎZø(È¿AQä»ôD@âç‘lϨ5ÀLR2˜eÀcó­1ûÓq@¬Ùj¦Ë¿8«91ßMFÀþ?ž¥†”i@þ?ž¥†”i@¢i#UÐ?ð?n‡ï°}•C@$Q’Þ4£ @ìj  åºw@U怩÷ea@#rpab€Ó?=<üÔŒCÀV;n”ü– ÀÍÃwÓ¿v²Þž»SÀ°¦©qC@zâ*L}B3À%±Q}N¦Ë¿\vÏ3Íq@$"7 öQÀ¤—fYaºZÀ¤—fYaºZÀP€{¼Å?ð? f£6•<@F½^E}Š@åý fdc@‚¦¦—AÔp@¿ÉÎÆÑ?A´¦—‡<À`9cÜÀ{ίUl¾Ñ¿!]*²VD@žWˆ×AÀÕ+ëd¶·gÀÅü´êq@Q(öÙË·É¿z-¡­Ì—GÀlôÆ`*ÿf@[ù‡Ki@eˆ”Ñ\Ñ?ð?%Ä·£-G@ÖdxG@bÉ=¶n“z@OÕkw3dc@–Ç<ÈÔÜ?zEèµ"GÀX AÚ>Àÿ’hæ/ÇܿȢ‘‹~SÀE¨¾G@œÏs:¬"À6ºA¸É¿ìFz½ããq@!ì  ÖSÀF¦´ëo­XÀicsé_k[À–÷¶#TÆ?ð?)iâç²±@@an×­I @´Öx¸#ƒe@ãÈ—áë©r@åL¸bß°Ù?Ìã¬wc©@À¼è¼; À8ö§n¤Ù¿à›“¼´—C@œ6‡ •UHÀ¨Í°%}jÀD . Úr@7à+I«rÆ¿Æ2ã3`èHÀŽÌUˆ¦Ýa@Û UÉ…i@YEÉöÒ?ð?¶GB0;K@sÑýB ã@<„G}y}@À{>D[ƒe@ÖöM ôä?õý¢-KÀÙº£4'×Àíc9éä¿'/²o¬TÀ€-lŸsXL@€yÛå5Ñ?%fl?årÆ¿´†@-ûq@X½XLTÀž`uÚ¯SÀLŠ^Ê\Àiž×X[/§?Ð?Åx‘×5a#@™à>&‚Óò?™z0æÄG@~wޏàœT@ÖÚIÂ?ém!W#À-*7p·Éò¿8þˆrW@¿ÄSž´¶"@v€lÿú.ÀGüŒQMÀ½ÈiwR@³V_G›¡¿/\÷«õ?*À‡]4­Ìd4@ætØÿ}I@+^&5³?Ð?×UÉÆÇ/@ÂîÂqfßþ?|¨d=m`@65¶CWÄG@ rÜ©ýÍ?¬>·/À¿¼:¿WÏþ¿†Å’îÍ¿¤ÙåýÁÎ4À¬Ò•² 0@øø/ê+@Ð ½L›¡¿r,Cì"R@ô?鿀5À32+Æ'À¼þµ7Ç×<À‚¼ ræBÈ?ð?zí Gš^F@4¶,Uø@ÈåªÆÓ'j@ ÌíÄð­v@·?4·`¯é?Ï#—”RFÀÙZ©rëÀQ!\E’¡é¿ (êš²A@ï>ݵÆRÀ !ÕkpÀDàe”1r@8!ևᵿ<ý¿BóžKÀB¯}îui@òª§]+ûÓ?ð?:ƒ5ÀÅnR@QÏo¾dÀ#@ìtÀöù%‚@G´O(j@Ço’¾+*õ?^ 5HÝdRÀâkËÆµ#ÀÝxTËõ¿iT]¤UÀìçc²ü=S@VÖœZw2@K'TÀᵿt|gîØ+r@k…à¿ç¼VÀ¦„ès“]ÀìûÙîÏö»?ð?´~åoêÝ!@úzïŠÍŠÚ?É]9ÍßQ@·^¥†÷^@I.K¼·“?›NÝÏùØ!À…hßvƒÚ¿I.CM“±“¿xö ¸K@k3Oœœ¿M@6f4­æ>TÀÍÊià0q@øž.¸gÆ¿¬Œ ´Å >À!\Z°…i@Atv¬½Ç?ð?í÷ñX.@Îÿûbê‰æ?®Ià fi@û9:¨ûßQ@\ý ?u6H£O.Àå}¯ƒæ¿›: g"¹ ¿©¬¨e!lVÀuß´_s@iD¬&¤§VÀv)îñgÆ¿Høã.h+q@ñ„ m ~IÀT0Ù»f\WÀÉ4A¶Ôð½?ð?JžÅ‰@&@1¢a&·ëâ?Æi^(•T@C––šÄÓa@ ïòd’7 ?TШúf &À„€*Øåâ¿ñóø-Š2 ¿}o%:‰µK@}ätþ¬¯F@3U0>YÀOçAnEq@>­ÜÕ,8È¿Y³Š;ÿ'@ÀuIPefT@Ó[¤¾¤i@ï2Ó3>†É?ð?”\ð—[Ó2@ÑqmÞ±"ð? Dë…©Xm@j–³ƒ]•T@ò[Nzਫ?ùì*„Í2ÀÒˆÕ!°ð¿Ý öOK «¿O¡fjôVÀ¶·°AzÓ%@Ê»NOæSÀŽ1_k8È¿½²y?q@ -ÝNî‰KÀc÷$TÑ.CÀ<5.©…úWÀ]bËàî¯?à? ¥ë¹ñ@ ïy‡ŠmÚ?}Q½™b‚G@mÐøÀ× ±bhÒ¿^ßåì²*”¿^ŒG?²\+@v™kѲu@ÅŸ§:jAÀ´±ú¡ZoQ@ë2lœùuª¿=š®ô³}"À=N}èF@CÚ¬tI@–´,9&­?Ð?äÄ!¤ãó@æq,U%ß?J5tES@Tº$<©:@ú‹ðZ¡?™;èŒRéÀ> ß¿Ûcôº„S¡¿ )èÐï6À>ôÓx0@V ÿ’--À4ß=ï=vª¿ô²×™hQ@…¯YDÀ/À¹t_ç¸6À>Hø9?9ÀãÒ íµû±?à?A|nàt#@w•ÄŠÈwè?Ü­=¥m N@xÑñU.Z@Aí®Å®?”seâl#À(ÛÞ »mè¿üuq{¸®¿îB*F·;@_G`/pý?Ü…´å¢ TÀârÏ Å„a@¦¯Hûr™º¿­ÓI<µ°3À™•´ÁìmY@™•´ÁìmY@é.ý¾?à?r¥ã—YÅ0@f µ?,õ?Å; V™e@Åf6» N@”›ŽÑ…º?¼¾y¶u¾0À*¯I ‚õ¿wýéìzº¿æq¾vMGÀèöeLål/@Ôø} ¸8Àγ©·™º¿óÌh:Á}a@«Â(¢õ@À=Õ„$ýåIÀ=Õ„$ýåIÀGÈùOÃ?ð?aH€7@ NaÊiG@2²¤,Ô`@2«+Óü%m@ ‰G±øÆ?ù´\7ÀJ‚žE7@ÀåDÞF‰îÆ¿|rzŽŽJ@¬†±5ô#ÀÃcòÁfÀ@… ™‡šq@oΔ4yÝÉ¿]CÒvéDÀäܘ{gi@äܘ{gi@SÙulÐ?ð?íh*8ÊòC@ÜBÉlB& @ DâÂ'Bx@²¥ªXÔ`@Ì’%¬lÜÓ?[¼ï`øéCÀÿ`[Ð ÀS¸¤ÓÓ¿”TteÅWÀ¼T׃¬C@±™ŸkCÀíÁ¡ý»ÝÉ¿a–kø^“q@9ÖXÝRÀæJêÓZÀæJêÓZÀ,È^ Ä?ð?5?Φ«&;@‚i7b@æm-Âb@A©yÏ>p@¾í¡c×Ð?I ¦®à;Àc~R$XÀ)À8tÏп7ZÊêNùI@Ú~W7Àˆf½`ÞniÀ¿Re6¨°q@|T3þÈ¿âÆ;(FÀ½½×f@qÆ`i@Fô²ãÇ\Ñ?ð?ü4üj«ŠG@€§}Š@˜á­ {@—,™Ü]Âb@âÇò~4Ý?¡ГGÀB¬»;ÁÀŒíö^»&Ý¿\Ÿ0Œ†XXÀÀùëQëG@Éá¨/¤<ÀÐë\<È¿—ç[‚©q@'ÌÞ2SÀ¸* “ƒXÀç¯.DÜ<[ÀŸ€n6yÅ?ð?ÌVÆ¿º?@°™›rà @sÃ3Ðd@%«Er@6bO¹ KØ?Ͻä ùª?À>p2¤µ À-m€‰ø>Ø¿K$B=DI@çër–sBÀÄ9 bš*lÀQªÓ/Çq@ð°-Y¢Å¿b*‹RmGÀz,^Äܾa@A­ÏªÍYi@N07OÒ?ð?S]AlÕ•K@·.­¢##@YêVS^"~@Åå%ñEÐd@ÏãÏõÆå?W@˜1ˆKÀµ“íJ#ÀR *¥Få¿K”ÑYÀDD.tuL@æÜÙ¢sZ3À|Ux£ØÅ¿­¸?´:Àq@ ëÎ.UYTÀÇzà¿sŒSÀ°Ae¤7í[ÀCÚp«Æ?ð?£DߟhlB@‚DT³eÕ@@$Æø²þf@ò†`i"ês@- ß‘8Cá?ÛšêÖbBÀD$m"ÌÀê«8A:á¿9ly΢mH@>P`ÞIÀc—RÚ›ônÀ£X2‚'Þq@®ÎøÖ”€À¿4Ÿž¹HÀ÷b€ BT@²;àRi@× MEÓ?ð?öw˜ËP@ÆÝbY@À‘àÝC®€@¨–—Xîþf@eÆJ‰î?Y*qtPÀt—~Ï3À—Æè‘ü…KÔYÀœ¹cð¥P@¢}‘É$ÀѦs¿€À¿”ƃٚ×q@§½º*‡UÀKÆD<çFÀ3øU ¡\À˜2GJ-Ç?ð?\ GN³EE@á>5Áð@»;ÙöúNi@?`iv-ëu@5ÊÌ4è?9èíæG:EÀЍ°r•¤À¥˜˜ '迟–uG@(4Åñú£OÀ¼s»£¨æpÀ™‰Ë™õq@ºµ8€ôˆ´¿ýÊ‘ÛÔ JÀ4"1ªKi@8"=Ô?ð?áEòzÞ•R@ôÊ€_Ó#@†¡&ðýd‚@ä ùO 9wâgZ@öòtL&4A@•M_`Ò‘?’;öfàŠÀFó¼9 ²×¿ÓŸ.CÍ‘¿ús¾ƒ­JÀQã(ÎÔJ@2~ØSgæJÀA¼ôŒ«´¿ü¢À>—õ`@ ;µTé9À¤1X;ðDÀ u:Lø¬?à?–’…Æç@;€¶XJÒ?‘oÔåÒC@éÕ¸ö6Q@â€R†8E?¯Œö >áÀË3¢ ¤Ò¿ÂþÂòr;¿®1†“•@@¼e,¸™I<@TªÖù4ÄLÀÀé‹“a@C2N²d¶¿åG'¶õ-À™Xš8ä@D@­£­¿ÉV@ÇÐ!1º?à?Z¨xõñ}#@¦ÕÞ_Ûà?êùŽXb^@®ñÄÓC@Ùk!þ'?Á{¦¢Úw#À•º¹WÖ࿯ުá¿*ét1×JÀë÷£"×(@Äü«­9HÀ7záëd¶¿ ¶bî+ a@ˆN",áé;À¿C½^m3À8ì” {{EÀMúi®?à?… !ï‰@e༇Â8Ù?nºó‘ ¨F@k"šË ¬S@GïÛð—è˜?ð…dÀ MÓâ0Ù¿*¼¯ ùߘ¿ªpºÆ<‰@@†3–P5@°þ6FÔPÀÌvclã#a@¨¿Gº·¿¾ôž+0À-«—Ç%µQ@„·0%UÄV@¿9’^õù»?à?X§äd÷Æ'@ݽ@.d{ç?'t]^Wa@°E¨F@¦È.Á0§?Œ$¯»¼¾'À3Mþ¬Csç¿·‘žº(§¿ž€KÀ¨û[XÕ!@z{ûAEÀHX8‹@º·¿/ϵa@È>Vpô=ÀÎ8ß“#AÀ/’¤Õ+ FÀÈå2 ‘°?à?<Âê“Ü@\›á°…Gá?-;ffÓ´I@R¨œ…—QV@£<Ü“rY£?f‹»ÞÐÀÿÂ’÷@á¿Î•mR£¿ôÅOFo@@:6›'éÊ,@mÈn¿¤RSÀºÄšsy8a@©4YЏ¿Áõ„tÛ<1ÀËÙ} n¿V@ËÙ} n¿V@´i’Cǽ?à?ÁÇè²,@—&M¸…ð?TÚ•{¨c@)Á~ƵI@| /‚Oþ±?CÃmÞ¨,À1d\4m 𿟻? |÷±¿, {6rKÀ»Ö™ ì˜(@_ë8ÔCÀ/¼’˜Š¸¿<ž½OP1a@±ØI‡Œ@À$† Ù`™FÀ$† Ù`™FÀÆB±ïc±?à?˜¦ü‹¹w"@5üC·Mç?e¶ý ·úL@ŸSö²¡(Y@½-î)f­?Áf÷p"À¶ê°pC翣ŠZ­¿ŸåøF@@‘lÎÖ#@K€N­‚ÝUÀâ} [Ma@¹1Æ(±¸¿l=ȳËe2ÀvÖi/Æ@Y@žÚx÷KºV@Aù$™¿?à?X\b‰=(1@¼u´¿¥õ?Ï÷ç·T$f@Rx‘ÞûL@Öf bP»?Ÿ"-!1À‘ú!õÕœõ¿DèCyÚD»¿£Õ^m%åKÀ}³Á¼â/@±ÔLÖô™@ÀЇh±¸¿óç¢öEa@ƒ‹ïX AÀ‘pQ¿IÀPåOQ/,GÀ»ç7MÂ?ð?»g9&ˆé5@@‚"ô¤ùþ?Uœ…œ=`@¶`b…2l@ôzt®äÅ?ÈŠ_Õß5ÀþKïëþ¿ž0ˆfýÚÅ¿Û69cP@$ðM÷kq÷?Í"3h1uhÀZŒÿ†bq@ÁØé&È¿FV­26”CÀdÂÑ:i@AÞaNï´f@'0WÚ·Ð?ð?vºN¯”WD@ѱ›rÁ @ûC'gÍx@_ƒ¹÷Å=`@Yf˜‘SÔ? iàÏ“NDÀ'û}é·´ ÀYsˆ°JÔ¿_-ô(r\ÀÒRÃEÛC@’¿SgLÀ”ù dÈ¿ÉÕÉ[q@%.¿ð+)RÀˆ| ôleZÀH#¢Û®ÁWÀúóâZÃ?ð?%n_Ì9@èÐéÊbS@ùîç§òb@S|@õ¿po@²,C)—Ð?R7À9ÀyS)›ÎIÀv¨PøÏ¿,ñ†a2’O@ ))‡ÿ(Àâë¸kÀ¤wgWxq@»º¦%]Æ¿$n¢h[ÈDÀ$ñ^X¯f@$ñ^X¯f@g¸í†¥Ñ?ð?׬˛ïG@ÞI‹ðÁÛ@´©‘î¤{@¡.5j!b@MÝI·Ý?«û TäGÀð@FÆÞÒÀ–ÉÀËH©Ý¿]ù¾%]À¡q·% H@vh÷dJÁGÀw>DäX]Æ¿ÜÛü$­pq@ ÞÝÜíCSÀ0ú¾ùYXÀ0ú¾ùYXÀ“èk6œ Ä?ð?²~ÅÑV)>@Éζ‚ ^ @Q:¥+-d@ú°S“Krq@φ¿êî ×?¾VY>ÀÊqÂðP À1š+z׿¤¤îoæN@€t¥$¹_9À†:˜hbÌmÀ9…{åŽq@bœNËمÿå iƒFÀ*æÍÈL a@ÉÞQK‡©f@&˜û¨¨•Ò?ð?µ¿ï±àøK@µôÿt@Ì0«~@|Îad@|-+Ÿ›`å?ûzÂùêKÀäm]ÁîgÀü¥eÀûUå¿P0Þ]À¼Äj+†L@ ÊpBHCCÀös4 †Ã¿W ëgÛ†q@‡=M«dTÀq±:\iSÀ$ä&8-õXÀ»Ü!Å?ð?O:Pü„A@o1´ÞOì@rôëó6f@bQ\iÄGs@Y…áæÕXà?ÇX ´ä{AÀž~~‡ãÀË6)ZPà¿%T­x‚N@à? 2µLCÀ?›iwRFpÀ†âg¯j¤q@¬^Vsì—¾¿Ÿ­ýBGÀ‰ÖѨŠT@Xìý{£f@Uz2PˆÓ?ð?9ßE1>P@•£þVIa@sÁÓ¡3ñ€@á?ØMY6f@\A3ÓOî?"³©BÃ5PÀRK=QÀørÔ@î¿§á7}ô¾^ÀñF5/Ÿ¥P@s6µÝ=À²5Øq;˜¾¿ÃÇN¦¬q@C»/²‹UÀºæTGì»FÀƒ?Ði“YÀ"þÆ?ð??$Àéog0Äù?t¶ÔÆ?Àpô&¬â¢¿D…¤"ÁP@ßânM*ÀVøÒ·70ÀŒÏ+ùLº?ð?\òAmzÊ#@¼7Ð7Pá?óÁ_,(S@»º½Ý:±`@6“`nJž? áâ<Ä#À컎Já¿%c«vv@ž¿j}¾ƒ~KS@QŠ-®™âP@·I‹\ž*`À§Î(ëÛp@âj!5†Ä¿®¢.0³;Àþª$fT@ž`y˜a@ÿ¿~A:ØÊ?ð?j ðÞC54@8@ Dn­ñ?r‘„°&to@uú@FYS@$WÙ#rí®?ñ/ϧä.4ÀÈLÂRÛ§ñ¿ ǵ£±ã®¿¡l÷ø_À¯¡ý†ÊN(@FKç’çu\Àrˆ j†Ä¿й…@Ôp@\ cCLÀÌÍÎiÈCÀô”\¡PÀµÊÌw]:¼?ð?Nðm3(@“ïUXuè?‡`ËôÁU@l¼iÎc@µ¹8Ú ¨?Ë·£!þ*(À©vÇ è¿ r‘/¨¿è¿qåAS@«hð„ÙÔJ@Ë)vÁ=•bÀ(Ð{ãîp@';¯/ÌÅ¿`\0Þ=À‹ò¤j7•a@‹ò¤j7•a@ˆ¡ËÁIœÌ?ð? +8±ñ‰8@;w3¯tø?];å(ãq@Ç}Xù,ÂU@~sà~_¸?Ëþï«d8ÀKwv)lø¿Õ ¦W¸¿î™4Òq_Àšƒ¯…÷Y2@R$qކíYÀéSq÷gÌÅ¿fc.L­çp@­ÊH’!@ºWÙHæ?ÇuKx³V@Ì¿ˆ<á;@5TÉ(C¬?QèuüŠ!ÀT<k¤?æ¿õÃo7¬¿ŸõPH3@Àw‰Ü¢ @ˆR¼ò­5ÀÓF߯¿¦¿H4Ž4žQ@¥|¬)01Àk‚Ã9³˜9Àät¢Ûãê1À˜ø ±?à?ʱFê<Ï$@o›Êׄí?«Ò ;EO@ÏË7 5Z[@$J*Íï´?(ßtÆ$À÷wñÀwí¿Mã çƒæ´¿$ýå«~ÒB@7‚&P>Y@é¤ N¬ZÀ9 .,a@Y=w$¶¿ü¬OM2ÀñríŠY@BP .ŠQ@^•"“Á?à?Ky´ÎÃ4@T2Tà tý?x[^µL\i@Ì¦ŠøQEO@ÞDsMäÄ?`Sˆô˜º4ÀŒ!ØVgý¿^ÖèÛÄ¿ÛݽðÛƒPÀ£ŒÊþ3@Ù!W½BÀÿ`WB°$¶¿¬tRv:$a@G µº+?BÀžÒ36;JÀ­nñ¥\BÀ”Å´± Â?ð?¤ß°Efƒ8@žïËGâY@S¶Þ¢²qa@Ç:€n@Øò]åRÎ?€?ܸÕw8Àj”Ê.ÁPÀZ é~οß/4•zR@ð×8ÔV迲泹lÀ‰P¯ Aq@ìÖÚ°äšÄ¿²±_Õ^c@"fƒèíp@’ÚHMðÕ?IÂBé<À´ª0èÿ ÀÞ¡riåÕ¿{š¬ìJ?R@zB&,Àˆ.‡ÃèboÀ8 PkVq@7)o’?Ô{&Ž(ÀÖЩjè\׿+дà?’¿€ •ýoöU@K¿d¬ W@| ƒñŠ_ÀŸ¬a¯µ”p@ÓQs¾¹Á¿Ûô}jx7ÀâQàîúS@PѱzÀÉ?ð?zÌ•*1@äÉF3¼˜ê?Þ—Ñí†l@¸¤ñÝkO@C’‹š¤?í@ï@¬%1À|¿â‘ê¿ZC¦”¤¿üÙ‘|aÀ²í^&‹ã@|ô8ÅaÀÙÄÎåÁ¿6©øØýp@!½µ«JÀ‹¿›QtBÀÏVCx‰˜?Ð?·S^’Ý·@ñYØ—™À?3´¹QÒ)2@½ª^P6A@@‰;ŸÏ_q}?©ÍªWæ±À4rìqM”À¿jŽ}ýg}¿\Íçn]ü5@œ%^ƒ·‘3@£³I,çAÀ§ìp©Ö§P@^Uƒ0N ¢¿–| #‰ÀΊ–˜ ÷3@Њ–˜ ÷3@ƒÿ/¬{«?Ð?”ª`Òjù@Cj AÉ™Ò?+gü“GP@¯Ù7*2@2Ésïê~?Œ›ð„»òÀ<¨ˆœÛ“Ò¿s| ©y¿ˆÒðÞâ¥AÀLíg™G @ï]Ó#èM@À³ñ‘H~ ¢¿Ûá"ú© P@O¼µdƒ—,À¾2îê"À¾2îê"ÀoOf!énš?Ð?¡ÄE%zê@ù[`É"Ç?aʲüÐ4@+š8§ ’B@3yxf&F‡?|š@ÕlâÀˆ-MnÇ¿\0`àø=‡¿VoÐ&~õ5@ÿF¨·ñ0@ÔÑ8jJDÀ¹Oã2»P@Á3½ñØ£¿{5*X™¢ÀX÷1TžuA@ù¬]©"ô3@gÒŒƒ;­?Ð?âL ¸$Z@J¹Hû§ŒÙ?c/îð¶rR@ƒ„r2Ñ4@ïaã¿™?Œ:DÀ¯ÒÏ.GØ£¿YÜ£³P@"À´¡Œ.À?†tB%÷0À“âòK˜c#Àêÿ"Xœ?Ð?µÞ޼#¾ @4Õs{Ï?·…’­“¬7@%åËNŽE@“88Ìô‘?vÝh³ À1ñÕa_„Ï¿Z8øèí‘¿Æ·Íàvá5@qsNc,a)@¨ZÁ„C¹FÀ@÷Ï+ÏÎP@ÓkÑš¤¿£ØúZÅÀåðMƒnF@êGŶtð3@2)tDÃþ®?Ð?±ƒÛðY@VÅŒ;#Dá?_óÜÇT@ÃZÎЬ7@)º=¥£?ÐúíKNÀÆïÅsƒ=á¿”Å<}£¿t¸EíÌBÀ•²Åáh@îTŸêÁ;ÀèR›¤¿¯ôÑõÆP@Þ°ˆE0ÀÀ\_M,Z6ÀW‹ÆD`Þ#À/1z Ež?Ð?BD­v› @5´à0£;Õ?3Á­ï½:@èÍËè½G@·FRÂ>›?o…så´™À3õ%NÓ2Õ¿Ä þ›¿¬§`Gè¿5@ja¿ñ“"@ðúp4IÀU3žÍ°âP@è.C &Ȥ¿=mã3¯ñÀ”Ð~ñ¼çH@ߦ˜'—ì3@S°ãÛjc°?Ð?ãæ‹™R"@S/'Öšç?¹Ï_OEW@Èaº4¾:@¾±Ý­_­?ôÀÑØû!ÀÏÇö÷æ¿MP}S­¿o†ü,iBÀyí³ÕD @^y¯õn9À9h6¶[Ȥ¿A\‡0ªÚP@pþ`¶I1À]çkÿ-r9Àæ…‰ÿW[$ÀÄ•ççúÀ?ð?5«/`Á3@ø•ï®~*ü?C7ÓÅs^@ÑUÇS›j@Ä7Ç#Ä?Ü:Î+–¸3ÀQöÀöü¿æÛçð4 Ä¿þdfinU@¤¥|žF¨7@~¬O¸íºkÀ¿Ù£•Ýöp@ Û k<Ä¿_o½ýAÀÞc ë¬âh@€é¡UŠèS@÷Ô±IÑ?ð?à †d7E@Õí$ľ?@m‡¿‰ˆîy@wW·LÁ^@ÝÓ» GÕ?ÂÝôô-EÀó c—I2Àî?7¯†Õ¿0ÅŠÎaÃbÀÎ4ªõøD@Ýl°]/.WÀ=LLŸ<Ŀ외ëÍîp@ SRÀI¤n^8ZÀ×é¾~“ÚDÀÒÄöym¡?Ð?{•¹òBI@who—râ?ÇÇÃ@@òw@š ªM@\r 9­?!ßåVA>À Š'­ai⿲à,;+­¿—ýb R5@ýİ5‹@1®O]NNÀwïeÙ[ Q@›"Ö4Т¿°—ñSX4"ÀœvSVØ`F@â…Ÿ…Nä3@Uþ]$C2²?Ð?J9¯.ÏÐ(@ ²“ÑA¨ó?¾ÿ¡ÆóÃ\@À¼¥QòÃ@@ÙÅßi$¿?t(äÅ(ÀþˆN÷žó¿I,°±¿¿f?ÉÜ*CÀdR¸,(@N[Ô"F5À;“ÉÀТ¿¢× nQ@1Çs«a3ÀZ  ®8ÀPí(\%À]2cGî¢?Ð?Í!áˆ@@—ØRâç?†¤ \¡B@‡A¡±uP@Äû«î´?ôÜø2À[HÒ£oÖç¿>Q•@ä´¿æUJ5@PÛA¥û翸RÛRwPÀ¶ C}2 Q@›yýÿY ¿´å’&Z#Àò·˜bçcA@„deÞãß3@ðì–}.³?Ð?ÄÜšÓ•×,@’nPGù? '”4ÌÆ_@ck$Œ¡B@“Àg\S'Æ?• ºÓ;É,ÀsÝ_}:ù¿6ƒq]MÆ¿hh¡  CÀàˆ,@&ÄBªñå2À”Ñû5*Z ¿4øÅ-™Q@ŽhŽìu4À€¸¾*$3ÀL®'Ù0à%ÀòšKŒ£?Ð?à¼:]Ú¯@âéËÉØšî?éá–»œD@ÝpT0R@+¸ÊL½?žãÓ«hŸÀmœgÙöŠî¿Ëy¥²õ½¿d^¶)Cª4@Î~Ô%Àè 4ÎQÀ{Žúh5Q@5· U™¿ Áƒ¬…$ÀŠ‹$_JÛ3@Š‹$_JÛ3@â@wƒ ´?Ð?~Ö#šª0@®»Ác@þÃ+|a@øßôÎðœD@ç2Þ^Ï?æây³k¡0ÀSìt À¹´KN<Ï¿½•)7#DÀ‚z~•0@ÓïÓôß0ÀëäLU™¿/×ð^.Q@Íèq5Àâ*'vÆf&Àâ*'vÆf&ÀN¯HÕW¤?Ð?ͽ'I(P"@ïêÓN6ló?ÝiL}®¶F@ʯ“ŸT@•òMz™Ä?;½WF"Àd†Íaó¿ÿÔ9pŽÄ¿Ð¹c^Á>4@/n¡d,ÀMûŠŸ+SÀ#ÏeKQ@ –ÎôÙ@Ž¿=¬º8·%À‡¬ÖÔÖ3@äuPSú´?Ð?G‘‹§'3@2ÃÁ$ÄP@ËÜñ,c@w»)#é¶F@\>á‹Õ?#ÿ[c3À+ËßàEÀ"jøU€Õ¿Äß\ʵDÀfóÝxä 3@Wvç–5Þ-Àµ}(AŽ¿\Òÿ\ÐDQ@Ò¬D^°6Àñ{pÞð&À ©ã÷ëô´?ð?FÙ6xju@¬ÅÆðvÖ?Ûj’ QÊM@Íg§.¢[@l@})©»‘?Pvü¼%mÀÆÍËßipÖ¿‚,C1‚¶‘¿Ñ> T¿ŸX@Α̵ݧY@Uá´JGaÀBD+cp@s¦ØÉºr¾¿Á‚ú}u5À¨<ÛádÊ?ð?µÃ4ë¿í1@Æ.«.Nì??AŽƒ¡m@–i0÷ÊM@¬ÿåW¦?IheŠè1À:´·àÜEì¿´”8gQ¦¿Ûæ:”‚cÀp² ­@ðÍ‘Ž¸cÀƒùPh s¾¿Bü¯ê\p@×UøýüKÀÚ‡϶?ð?ܲ,ªÓ¬!@Y± `„Øß?^Zj¶DQ@Ÿ+rLË_@KÍnQ°œ?†öϧ!À²Fˆ>Îß¿Z5[ì§œ¿ôÂá¨X@˜­É#œ2V@k)oä>˜cÀ*pŒÙÛup@³'–F¶À¿>,´tu7ÀU>H2™ÓS@K<|šÌ?ð?”›åiqÊ5@ •Y³l¡ó?,;¾±×p@¼#çãDQ@ü«åÈ:¯±?*÷¡iÃ5ÀYçèV›ó¿- :(†©±¿.ÀÓ6µcÀøƒ’_c*@ƒ\ƒVbÀWNì¼q¶À¿½*½\np@¨Ãê4íåLÀè¿w¸èÓBÀÐ œ\Õ¬˜?Ð?3FJÃÄ«@‘êÏŸüÆ? âÑGíÕ3@Bµ$¸‹%B@))¿£–†?8‹Á¤À 1#Æ¿Û{*8 Ž†¿µM3ªå£8@ 0lÅCÃ2@ðºÂEôEÀÈøHlňP@"›¶þà¡¿xs-M~À Uœ÷[VA@2î´>@<é†Üž[XÀË39Tì›`@Á•KÏö²¿)Dáõ+ÀHYû·¬FV@w–ìŠ|•¿?à?½‘Ê!ÞA/@X¸®~øñ?T¿ü°[e@Ù5'HšF@žèö9ç©´?Òy[É5/ÀÇÏ•Œññ¿5¹×¤ê¡´¿ Æ´€Þ=TÀŽõšX°)@ÕUµöOÀqNá&ž²¿²ì["Ê“`@Šz”[b@Àtüu[’:FÀxl4sœ?Ð?…Eçß.…@[KfÓKÔ?K€×fb’9@d_+æÉ+G@;Ã/I#š?Ñ.rxÀ([CÔ¿Æ¢È`š¿çØ\èÃt8@w¡ÝÂfî'@Ìr•’ÎJÀÙÉŒU¯P@Ý­ž±Î¢¿ÛBigĪÀ=k]:à»H@‘ÍÙh¬°?Ð?Wþrh{"@·~3Íç?,ÖÔý­ÚW@…þn¤’9@9jÿÿð¦®?Œr«ï±s"À£?¨HDÃ翳a5Q&š®¿kGz>”DÀ’Yó €^ @ÈV¯µ=ÀMƒ.â΢¿íúã §P@v¨Úãa1À*ÊK9ÀC`^\ž?Ð?ï¥þá½@ô3z\åÚ?NP©?À<@äÝk oôI@•³O†ˆL£?lZ¢ƒµÀd£ YÙÚ¿XGÕéC£¿ ^†‡I8@ý"+`â5!@6¹jMMÀþ zˆÃP@ê¿;²œQ¢¿„§mëÏÀ$T :·H@¯È5ÐD±?Ð?—ëÉ÷=²%@$R"½Ì"ï?ºã÷ЃZ@‡]íå‰À<@Ú_paW¶?7¾¿)¨%ÀÎzË“äï¿#½ùßfM¶¿8?IVú÷DÀ«^ %$@FÉWÜ¥†;À vÿËQ¢¿*tiǽºP@ñy(wÙd2Àç‡ç7{ç9ÀkVI Y$ ?Ð?ýàn@º@ÅÞ)Ù˜á?˜‹L‚@@_Ú“8íL@(¥IÅ?¬?˜(…2@À2*|b‚á¿Ü0nùõ«¿&aœe8@³ôZY@¼³a–vØOÀlð=×P@ÁYö¡¿b²6­þ Àß.Ë«:F@¤(½a_v²?Ð?ÇŸiBÔL)@Cõ7#ô?ôÒ.³@X]@K­uÌ«@@Æ÷IÀ?McþÖ@)À:þKû¬ô¿Ç¹}-aÿ¿¿?Ë!hEÀÉl•-(@”-0bEj9À"3ñ!¡¿ºw:ÈçÎP@`§ÔãÂm3À ©ß7À¼µÿ®±?à?‹šUä)@Í*ÄB»Ãö?TWz‰ áQ@8úe `@" $Ä?‘JB×)ÀÖ]ƒc¸ö¿¼ý¼ŽúÿâÐ]ÇG@~Œ-Ær@Id8aÀGIª&Xë`@̦Ì_o­¿õk$A2ÀßQªFQ@ƒ ׯ^Ã?à?xÐ2îR=@½ç ˜…È @àħ—,p@M‹µ³;áQ@ HfŽ«Ö?‹wËëPD=À,ú9¬» À!¡?2B Ö¿›MƒjÇæUÀÆ€e z<@^úXöBaGÀºkrÍ«o­¿Öºw™ã`@²m›|DÀíÉù2CÀ–²ˆo Â?ð?1Í;>@?Ïò2% @ÃuR|Ìc@¿ i‚¹q@Œ^¹Âx3Ü?ª©`>À»’ / À ”½‡Ó$Ü¿ —a…pW@ô‘_ÂIýÀ\©7ä@ŠrÀÅ4:Hq@ã o±Ž¶¿ç6”†ÆÃAÀ3·ÌkK¬UÀ–̃Ç~@Ò%Ÿ9]QÀxæU_hÀ(­A$ðj@mñýÛÛᲿð?×÷L[®_Àr”}’߯_ÀÀ×VÒá›@+óÔá ŽoÀ“¨`Ñvß_Àøªl P`@\¶4«\`@]ÚšˆTi`@…\°¦<«À@,¯evù?Jê„3†@EÑÇtõ]À*Iý¿Øt@?9ÂxÅø:@±-œ…H€@KÂ+ÝMD#@Úü@h‚Ú1×@‡[ØÀ é5@+=VÚ„@G„ ŸŒßd@ ]!‡'S3À¸2Œ®à£DÀ=¹ê5QçÐ?Ð?I§IZ T}@\ƒ-Òê¦~@Òc§Ó§ŽAÀl榋•@Å…9€@H*é§J~À Uçh§ÀÕ"”¸?Š€À ¨ô@é¿DígAßY‰@Ð"_%S[À.uV¨½X@aLoãÚ¿8nu3µ¢XÀÌ(fËû¬ÀßX)ˆ°ã1À5)rkFÀ†e˜D¿£_@Ãu±½iÄ1Àøèw“òâIÀÓ´ ŽS@˜h’~Ž„¿Ð?ªXÍEï1Àq¶‰¾2Àã»[@ÔÖ|@Òc§Ó§ŽAÀÿ¤¸ÊK–3À´C—FX…2@¦£‹ªõZ3@ñmÕ2:4@ÞåDË}ÀõÄÇ(@ÓÚaÆxôf@`LoãÚ¿ˆU‚µÑ U@¯•wÒÔ @"Î?@l’èçkˆ@^„ÉÍËj,@³Êx´Ï @À¼ÊÝ6òT@f]E(&À}aï+7Ài+2¤™á?à?Ô~mHûEŽ@[ÅFç(@‚ zµ|_DÀq{MP¦@&ãXÓ„@‘@6уiOÀ‰Œ“–¶ÀLS^¹ÇבÀ GÖ’Ì2Àkä¸Ú¶™@¼&:ºê0nÀ¹REëP^h@%N™º9¾Ý¿»Wƒ,iÀ·¼â<3ÀAó½;pFÀª‹ˈ\À¶I1Ø p@H} !±÷AÀfÉ‘zέZÀf1¦Ò¶c@P[ÞÛ†‡¿à?Ô£L×p5À¥oÓŸçl6ÀgWT÷,g@‚ zµ|_DÀ[<Û|ïð7À‚ÓôÚœ¹5@$°e†17@«ôiØÂ8@šBdÙRãÀËjs-®ÙB@O1îrýiw@%N™º9¾Ý¿ó„f Ge@CÁ“^Ô+@þþv5>ö@ï‘Î G{*@ÔibºÙ>A@ŽÏ,"@`ÉÑ\‚e@RçFÕ9À?l§»žOGÀÍ%Ð+áVñ?ð?’z)J,BŸ@]³¬ê ¡@ƒLêPx4ÀÒiKœ„¶@|\œ¢@ønM£³0 À×-Œ ª¡À•©·JG£Àq1¹ã0RÀ&R?_ª@ÐVê½€À±cnç x@@á÷³®òÀ¿ 7zºyÀ>áZðGÀ±aç”Ð[À¿™ŸifqÀ@@M€E€@d¤Ù˜¹*RÀ^7ŒÍ~kÀ~‘åfãq@Nƒ£¼v¿ð?Ì@E‰”O%À\ š A'Àü¥>Dºž@ƒLêPx4ÀáÝxÙ_)Ày1g&@wše¸¶(@iL I*@!€žÀé®k~¢Y@}G<ßö݇@Dá÷³®òÀ¿K*;Žnu@Üçf‹^@îa«Gè)@M“¾c@@.~WpT@ß!üÌŒ’5@Î Btvu@ ÷°‡ LÀäT—Ë&UÀ  Ù#/ñ?ð?ûîÎÂÀ$ @öâ ‡•¢@´¨ŒƒUE@o¨i£·@Ï HÏä¤@¼¨ÔÝ=À À~±¢Àø&9€Û¤ÀûÚÁp^ˆ[ÀèW(pRxª@‚ݽ@ˆ‚À„33@Wäx@£»íºæ?ÀüKzÀ¨¤÷ëôLÀ?ƒÝó¼_ÀÛ#£E§tÀˆh™ÅH€€@èà€]RÀaÄ#1õUlÀ7 –° l@”„ aÌÚˆ?ð?$µz~Ûo6@³a÷èZ 9@÷r ýµž@´¨ŒƒUE@ËA…õï;@£%öG7À;­Éaú9À[ y ý<ÀV²áåß%žÀn•ÎX``@†Á6äKPˆ@£»íºæ?m °ch—u@ªZ‰ywÙÀ À8Ë*@¹93–·C@@@£øŸV@åÎõÌ9@;2).u@ùÄÀÙ26OÀ‹wî –PÀ#qŒŠÊÑ?Ð?jßì"®€@Âôök ƒ@íÏ}pŸþ:@΀Œ—@”l“ª½…@–uCŠVÀ%ÌáÒP˃À¡t´‰*™†ÀNõ­ª¨BÀp£E ÜŠ@N›„åé—cÀë/(m(Y@G¤± ÅÙ? 린ÁßZÀ¨„Y¬&1À.{äŒBÀ*fèS XÀËó’ Ž¼`@3¼ÀJ 2À 3<3MÀéœ',(@@ŠH¹2Ñ~?Ð?7Tü4°,@ç~ÞM`0@Žïzu@íÏ}pŸþ:@‚ù¯2²2@°ûiÙÑ-ÀC’`¤1À]$Íþôn3Àê¢D»P~ÀRPV;D@F­YäÀh@H¤± ÅÙ?[Qûû¥ÁU@*à 5eÀö(qIÅ @x”½þ•;'@cîüv ñ8@Ò'ÀÃ@J 7ösCU@ `Cáª61Àü°¾¨#À-±Ðçùò?ð?¥;{y[=¡@+ ‰‡%¤@–¯Ë¾ðe@KDY‹O¸@†*O¶.‹§@@deUÌó¡À{Ug®»ú¤À+V„¨ÀÖõžÇgÀ6 æB«@@ÇÃÎæ(…ÀÙ æêly@2åN3s5@6[kšÃw{À¬”MÏ—þSÀSNÙapdÀ°%]ÄQ}{ÀàE$Ö­ù€@½¿¡ÊZÂRÀœd̆nÀaG V¿¨?ð?[HÝⲑW@|×¥‹[@j£öÞ" @–¯Ë¾ðe@§4 `@2¬±1‹XÀÔºÏ÷‘®\À(îé’TÂ`Àžò‚g[‚žÀ…r“.Ìh@µãÿZ@ü„ÝG@@˜Þöˆ‰Yu@2´Â\¶ßRÀ5)vm†ß?à?‘”sоžˆ@7S·é†@6Xü„QdÀçì%á£@R,qÆQ…@Q¬¸“<‰Àðz{‡À ì—…Ú…À³\×˨êI@#!KÞ‚—@mµ+=Üó`À$_‰0‘f@uÕ¨¯ý¿\§ï®eÀ»´°@@n:ˆcÅ!@‚f@ó³ä(ÀÀiŽçòm@¯¾ôu(@ÀË µí”±UÀ­ÔG4ŸM@ ͤ\85©¿à?¤¨¬+«»SÀÖ$•Ý\RÀ++ Š@6Xü„QdÀJúN^lQÀ-B§ðÆ9T@ŸºÆx7ÒR@ -ƒ ƒQ@n/´i;~Àð0öúŸ-À<§h?Ømt@sÕ¨¯ý¿¾ç2;.d@2‘áq\N1@B )9N#À_J«â®—ð?çrÒûÇ%À0CœI=@ÊÅ)@ŸÀ2»IEA@K3¿a@@¨æ=ªÔ?@Í`gñ‚}À˜‡Tv¥rÀÇt Säd@³ÞÜAg`é¿Ûô#•œNT@È^ IË;@±*ïW#À¦¹ê£§ýú?ønùŒ>ú¿6úþà2Ãü?ïÄ ‡èLT@6˜B\³ÀP)Ð ñ°!ÀP)Ð ñ°!ÀïBÁ8û'à?à?,>Ã&Š@‚÷#ïK‰@ºË£›ï[À^õ"nè£@"Âñçxˆ@ÁC ÷‚ÝŠÀR|¿eý‰À/,Ç–$‰ÀѰzf`8@—¼}£ª"˜@HÄGfÀƒD/ý~g@s‡Qãi¾ô¿Å¿Å’Í›fÀ ãFM0¾õ?—®^cà Àò†.SÂLKÀú Þ½ØÛm@9}^l‹@À^ÖVà WÀTå?‡TZ@6áÿuN@z:1Ó­ø ¿à?[Dˆã¿KÀëEÂÈÓ©JÀv¯^íYÙŠ@ºË£›ï[À¢«¹eËIÀ^ÛQL@¤ÿàdK@vv†Z€J@›X(deŒÀÀ ’’@üèﱨYu@u‡Qãi¾ô¿Ù~pd@P&S²Ø¯'@ðcM“QÀú»ÁHr@ÄEŒ:ª @A¼T÷@ª&oí´]d@BÕùNm1ÀD:ш™7?Àwà Ö1À@Ï­ ¤[ð?ð?Mèø¬÷š@°R™pŸš@üN`‹h?eÀåÖùç%W´@ó÷¥íTHš@|×” ¾›À]ß$Gc›ÀG7‰´ª ›ÀE,&ÇL.3@‰-c€v¨@ ¹22ÊxÀ¹²†¸;Cw@Ær“‘„‹ÿ¿äuú~wÀ ¹ÖœŽ´À’>Ì3G1AÀ~5‡R/cÀx™šCËC~@1Âügº¼PÀoŒXð¾gÀœ3vCîq@÷éCÍ5U^@ _ Î׉©¿ð?¼¨¬% %UÀ´š# ÚßTÀ/l¬\JK›@üN`‹h?eÀß$R›TÀ½c×’“ÀU@~” gyU@åíi$3U@i·®‘ÓšÀ¨ ÷æokA@>!¹ÁÍ…@Ér“‘„‹ÿ¿eŽ˜(w’t@±L½ÖÒö1@–•¦17'ÀÒõšŠä1@Ìoý¥)T4@orSÀÅ)@‡Þ̵ ot@$`[í±DÀ0ûžéè;TÀGßpA]üAÀ½ÞV¨0à?à?ðœgÓ‹@ž[UÚ Œ@îo¯€ó¦LÀ°:Isɤ@=7%$EŒ@„ ǹ©ŒÀÑ=¬FäŒÀäÄêñIÀÉìÎ/¥ÃÀ¡°4uù̘@ï·cÈu…kÀ¦’ìJg@ØB«úZçä¿— ¥ØÆ–gÀìlF0ÀoëÈêN:ÀÃÏ3;]çXÀæ˜VÐ`®n@Q§à+Üí@À·"v‚(xXÀ%ªsqc@ÿ;¹è“N@ó[¥Ce‘¿à?z‹xH4Æ<À±Íö½ú=Àx Ë‹@îo¯€ó¦LÀÚŠÝA9<=Àxc>¤=@@‹¶Êà=@‹5Þ®Ñ>@ØÒŸy®À¹cº…¹K=@Ä‚å…@v@ØB«úZçä¿¶ýK ¶d@P—ô@@ÚšBÀz³=œ&@`ñy+K0@‰5Ð7Ï@  ÎOô€d@¢º¿ËÐ6À`æa+»ªFÀ€ëçU/"2Àª?¹«¨Åà?à?¬$m¸Œ@Z{•jô’@‹Zd½Ä¨<ÀÌ  j?¥@PG¬núsŽ@~/5ý Àl+n‚ŽÀMtX%’jÀÆOq«j?6ÀEéB &™@ÊB³jäPnÀ¶ð×t™Àg@;‚l)]Ó¿?$™¯hÀ¤ãhU˜O$À¤wbVqAÀ5DPéÐ^À¤f³É‹o@šøÈAÀc{B'8YÀÆmUÕ$Dc@>I""nÓN@Ùjn)ÿ¿€¿à?CHËÔ-À(‰–íë-ÀOM cüXŒ@‹Zd½Ä¨<À€ëg€˜Ï.ÀÛÆ … ú-@!Ž7Þ.@/×½É/@!ÜÓ@˜ÇÀð9¯6ãD@#*V:ܱv@<‚l)]ӿлZËËÚd@o%Ñ„Ô@P”ƒÐнÀ½ÚdC‡Š,@bâh˜6@ƒSŒ]ù #@æV?v“d@»…˜¢9ÀBSØ-ÚFÀ›B4­$H2À#H«üð?ð?;4 9¨@o…Æô£6Ÿ@B†´‡,ÿ?Ù›÷0<¸µ@"–ûl @kð±I¤žÀ,ñe÷ À;y$ý–ø À‘]Så­SÀµÝýèÀ©@Y[–€À[ɼ9x@}ø]CÄ?šÚßK; xÀŒ`–‰=ÀKÜ÷ØèUÀX‚íg·vrÀâÉ«6‹@“Ç,yOQÀï)½çýiÀ^€V! {q@¥(tž_@9ºŸO3I?ð?W_³¬Íï?5B·vv¼ð?0xÚù¦õœ@B†´‡,ÿ?2ž`rLñ?Ëueœýmð¿`dµJñ¿é %R3ò¿#å*sæÀ¤ „p[@ˆ*PX«!‡@}ø]CÄ?²}oÆu@JžÇ¿}òÕ¿œ‹«1zu À‚W#(¼gA@ÜÖÔFCK@¹>´úM6@Îy³û˜¦t@äy‹LÀéˆ ¼TÀ$þ\ PnBÀÇÀáy3á?à?I}§¸¢Ž@¢éñu|@–7Ì’žœ?@mwqZç4¦@]#}à_¾‘@ ^[2´À¸LgÀÝ%"±\’Àî>`ÞŒ¦LÀCe×™õß™@ô¦Š‡œ rÀXìCI‰Bh@}uòd­Þ?aIÅûg*iÀÖ!Ø•0?3À»æÙ 2gJÀˆ`š1@¡Å³G¡@–7Ì’žœ?@©¸o ò2@©Û(øñì0ÀÑ4Np72ÀqKòó#›3À-•<P ŽÀŸ­=/(Q@ç©zéÙw@}uòd­Þ?rÇ‹ø(e@ŒÀÞâh ÀrÁQç–6ÀÌjF·4@&DHì@@*à—~±)@?ÄNËcºd@„ T‹?Àߨù0B@ÀÛ—äAÊ”2À€‘yLàkñ?ð?ÇåD8¨Ÿ@ÍTÀɳv6žÀ^S ¢”Âd@Y<`+Oü‡@0e„Ô6Üü?´Ò)1 Pu@p[N`(+ÀP%ÄÜM!À/ÊBÔ4H@)ÿÁy«.R@5Û—46=@íðÒ‘ÝÎt@´8Ü!%RQÀ¹6@³»BÀŒ¹6@³»BÀ-»ÜP¥á?à?Ìð0×\@ ‚ hôp’@OŽ²Ç¡X@MžF9§@Cx*óÉ”@É´:gfýÀÂö>O&“À‡÷ì¶••À/ŒCÙóñWÀLêç)ƒ£š@Ý<é0–uÀÉfX êÇh@Þ/Þ›¤‰õ?WnNdIjÀ‰<õЗ=Àè¤D_ɺQÀíb >BlÀ¬‡" åsp@„ øàAÀC;Ÿs\Àf4çé)ÖO@ïµÐê|›?à?œÁÑ dI@z9‘9ŸL@ST¸(@OŽ²Ç¡X@jB|8!P@ÛTY^JÀú?Hˆy¸MÀjN½Ø¿PÀi™m­/hŽÀ~ý|ˆX@ÏÓófx@à/Þ›¤‰õ?Å´/˜ze@šÇl–‡$Àã*{øÇ À ÊÔ¡ÿâ;@Ïè-D@¢w¨ºGn0@|Z„˜ äd@êHL}ëBÀÏè©3ã2À¹‰ÜìÎ?Ð?â¿zþ]w@Õ\=kÎût@üº/L˜sRÀ“ |Ol’@öýU7Ü×r@Ž–OT´æwÀh¶|X’vuÀ[Ò]FsÀm¦±*Ñ6@îéoº- ‡@‰‚º ›eQÀEÅ_'V@ÂPÏâÜé¿ÉïáªìËTÀDcܧ¿|@5íŒu«N!@½ã’(õ0(À6&ïäw=\@+`»oÑ.ÀjغÁ„DÀéYI@*pE=—¿Ð?¯3NµšAÀ5ûäž?À¨ý°$y@üº/L˜sRÀ7 â¢cd<Àã2¢ò³B@JÔ?•~+@@—¹ • =@–nÕ!_}À„³&?vqÀÕʆÂÐc@ÀPÏâÜé¿¿ú¯ ÍS@QØïº½2@÷Ï­ U¯"ÀDkͱTð?@B wŸÈ;@{*¸¯¶n9@ ΈpÀ̆@ô"W±ŠÔÀ{ˆÞ@1þ€¼×âS@« ¸kÀçRz?Z!Àfï].ÀȽ\¯ï?ð? PSjÈј@(£% ,—@喇М‰hÀ%_.BŒ8³@ì‡}=¢•@#w¬q™Àk툢IÁ—À<!îš-–À×£‚5f=C@˺«‚€¤§@À EpvÀòå¶»wvv@œjãÎvÀKÙÿf¬uÀÀÂü3f–2@`3È­ Ñé?ý êéL`ÀB†•Zôû|@Ñ¢¿1ŽOÀf5™ÈÿÉeÀñF›A1¿i@ñF›A1¿i@ Œ¬lC®¿ð?‰7)‡¿ÊWÀÇ-p6VÀ¡·þ„tß™@喇М‰hÀöâLA÷¼TÀ’£µdX@j²e¡ˆÅV@ïZÉBU@5ËÃmðoÀ$‡ÿ6@Xa¦.š´„@œjãÎvÀ&X÷1l t@ÿÈ€Ñ[¤4@ÛSYtÙ[@ÀT—õLÿx+@¶W”r¾|-Àï÷K<&@7*Ò'úòs@ <K3BÀã êÞNÀã êÞNÀa­Òû´ à?à?þšòù˜‰@N˜â_cˆ@aUjUÔRÀ°s?¦0££@ã„Í;g<‡@Uœä&FŠÀ—Ê]^‰ÀBÞ"šÙ‡Àÿqf6!@­êlŃô—@³‰¦àú iÀ·ã·–»°f@{oÛž–‘é¿‘ÆÍw­!fÀ —is‡à@¨^`1G ÀƬ Q®UÀ4ìãN!_m@úǵ=ì?ÀrÆ=otVÀâØ·®`@7;™ßVóY@Ðl6tþ•¿à?±x\£AÀA6ÞßÎ@Àɇ PŠ@aUjUÔRÀ7¡ùyÇ@À²Ù¯_°B@³†¸?A@Yq‰o@@ËZivÀÜóÝ8Ió5@Ñï»$u@{oÛž–‘é¿$,Ž˜-d@oa6³<@Ê‘uµL/ÀÐ÷¹p‚#@¬h‹|<ó¿Þ›ÐY Ð@uÔ RŸd@º3<ËÃ4ÀjçØCÀÞrƒ7¡ß>Àƒ,]”<Ð?Ð?dìáÁuiz@ˆ¯íÕ˜±y@°!‚…™6ÀÏýò%ô”@ÛÃoÙ»þx@âЕ0%{ÀíwÏ8hzÀFMd°yÀ¬nCpÆÀo€!Gˆ@9 (âµ[Àlþ{\ìV@#{u¹/Ï¿À4÷+išVÀðËŒoG,ó?™–ýë½ À’±‡Wa=KÀOæíÄ]@‘ÎíÐá$0ÀÀü3N$GÀ%Bf^%¯R@Ã(„g(J@»×ŠP9{¿Ð?· ȬP&ÀñŸÓTµ%Àò„xFÎz@°!‚…™6ÀÌ<E6%ÀÔËÖIï&@x¬Ùþ O&@ö_RP´%@ãcwA ”}ÀqGž±¶0@÷–fΊ“e@#{u¹/Ï¿½aS{ÔOT@ gÇÕ@ŠRHýó¼À±ÊËØ/š@´µxL@@Ÿž­Î@ÖÀÎT@ ëžúëg'ÀÀ¢¢à×;6À§°ã ” /À8L:žRpð?ð?Àˆ”€‘C›@ËJÖfR›@2jfü‡[AÀùßë´@4?æWíš@ÍŠ¿ ;œÀ'D¡â¸â›Àå[U}¶›À9ã=ëŒIÀnç¢*Zœ¨@¾,°þ²n~ÀSÚç7M)w@D¥üi+<Ó¿˜Ú©wÀÀëý­úÀ^ìÄ{gIÀÅ£é}pÀ²`üT-~@ƒ„óÌ€SPÀ»ömÃÙgÀ󹨤Õr@¡ºj/M^j@\ÊP]Dt„¿ð?¨"1çÅN1À;UÕ½Q31À²ÌtM»Y›@2jfü‡[AÀ‚‘§ 1ÀX—%áÐ1@Ê›B£Î³1@¬ÒÚ6º—1@¡*Àê­À;ñ`&ù½V@îTϨð†@F¥üi+<Ó¿ýñž-st@ò/›mG @8„ÐAí<À‚ÉkÓ‚>@S"ÅÐÕà3@z›‡ƒqÑ3@)Ô#Y&t@÷ýÈž JÀx vXjVÀBÞ¤ ¯aOÀQFJHø¤Ð?Ð?(—’ž'|@>«ß‚L™|@¼þRÛ@o“º—-ö”@’£úrÅ }@ÞDóµ}À³å~”ày}Àåï3Jäð}ÀCº} þ4Àb‰N,ôˆ@?ûÇ¡!œ`ÀÔ¡=«{gW@7³£‚º?Á „w–WÀp©.4®*Àt÷»ˆð1À»[6D­uSÀ¶‚"*G˜^@3êžtä0À±û†Lñ”HÀm˜4˜Q@íÐÂì”J@ä/&¡ \?Ð?BÊ×£1@67°h(c@˜ƒÀÒ®ó{@¼þRÛ@ìñˆ–Á@⃩ÿºÀR7qÙÏÀ“<4‚#|ÀïâÊpYÍ}ÀÀ˜#@=@ ëkŠÓlf@7³£‚º?Ie µ±—T@^ÀûÜ—Oä¿Ûæ‚a˜À/ôé÷÷_"@¦ÌïÅ‹½@+¼0ó@ewv/é8T@÷< ìÛî,À3“e†V4ÀúÁVó £/ÀËP~ŒÚÐ?Ð?zmà¬í}@ìnDrc6~@Ñe²E—4@´Ê“ÄÏm•@qÀÉ b@&ñ~ÀtØ9hÕ/À ]ô2€ÀKõ¼ÿ›=À´q^ÜŽN‰@¶:uŸ bÀ`2žЦW@wRh´ÆÒ?¤k ÙXÀxf&YŒÝÀj'Í9s5ÀãÿàφVÀ´H,>³_@¿šs °0ÀÜëÈóUIÀ@lV%ÌJ@@lV%ÌJ@‡?¤=*x?Ð?¾©Neôö$@E/]ºßÆ%@úLCXOœ|@Ñe²E—4@ Ùž&@Q™ló ¤%À¶hòð«z&Àõ08œY'À^šò}À݉;ÛA@^6×f@wRh´ÆÒ?Gêhen½T@hKhˆ¢ŸÀ£r•ÅÀÐ}¥©$ª%@@·!£™X#@“z$E4@úû|ãKT@B“j Ó/Àp2›ïÇä/Àp2›ïÇä/Àó±qŸñ?ð?7¯eÍž@ºë}™ñŸ@q9D‘ûa@´Úéèµ@hçîNù @ Q῟À™Q×pƒ À¬ýE}ªŒ¡Àtö‘âQcÀ/J¿dr«©@à`\ÑF~ƒÀLëÛ+çw@ ×y§¤ÿ?”Ë xÀèÛœD¸>=À? 8"ÝYÀmy'ì²yÀäêI;{u@‘nbrîÝPÀéU‹ÛjÀ?%A‘Èß^@”Ïk@œÐ’ûÉ¥?ð?»M¢ƒR@iÜ×GX¬S@ûü QT@q9D‘ûa@¡LàQèT@ά?–»#SÀ´RJ#WTÀžU¿ÓUÀËKé¯óžÀïG}*Ve@i}H2«?‡@ ×y§¤ÿ?§æ×ùpät@÷é> hÀŸ¡.X¿ ª@”NV¨çû„À_ ìLi(x@4»mw¡š@FÇ(.B+yÀèÇÛŸCÀ—Ê M^ÀÂ%ÆMø|Àµk¨wç@î[@î˜ QÀé±°‚²éjÀ5-«…¼;k@­;Nª ®?ð?Ùž2þZ@Y†âä\]@ñ‰ïG}ž@‡ÍØñäìi@S‰ŠêÛð_@¹wŠ„˜ô[ÀŒýÅkíh^Àjbh6Š`Àró$­OžÀŠÖ¨wûh@&\æ†n¦‡@4»mw¡š@HÃËÆ u@®+ËȘü5ÀÒIြ>À¦Ú¢J¦ÇL@Ñ2“¾O×J@Ó†ËË@@y±´«Õst@E†Ö(]òRÀ3!5PÀ‡.õ.´Wî?ð?}·ÖL1–@c( >“@ >ü舱pÀn#»ͱ@¹N="¯@æéž#¨–Àì^ÁÀcuÿ _‘ÀŸÔ»ïŸ÷S@‹ Ïð›¦@f¹#2ÊÒqÀÿA«}u@&™óþYösÀx©+wísF@kPâOØLI@~3"Ÿ¤QÀŠÿqôq{@ Š ÛjMÀ%U >kcÀKáÚÞJåo@ŒZÓZ†Wµ¿ð?D@zUL_À$nA¼&#[ÀŒ‹yǸ9˜@ >ü舱pÀ™Ïª¿“‡WÀÔS઼ó_@IÄ?¢L´[@\ÅmX@ÍdºþwBÀ¬f³L: ÀüNîU9ƒ@%™´ldÀ†vòè‘\@¬b•p@†Ië?3`±¿ð?tr¶ôYÀö]ËVñVÀ ÉÄX˜@G“ï°wkÀ¥¦ÔH GTÀÕ^Úv•†Z@ÝR$ÄrW@ñ ߸ÿ¸T@ÈZÖÚIÀ@\v/ý%@ì £]¨ƒ@[fŽ ›ÀMÐŽs@šn0Cÿ6@€Bï ñqJÀ™åÚh%@ÒÜÇ&ÃR@ŽØ”!êP@Š7¸…²UÀèµúx?@mú똨„@ËîæÈý¿"8CÈÿ¬s@îPJL]Ñ1@ S›ŒIÀü% 'Y/@?‚f BÀü~j{K(@¬ÉšùŒs@Ï´ŽXçBÀ6Š#f= NÀ¶„x§QSÀaUþþuß?à?×ËLÔPˆ@²ÍR^†@¬Ä¯DËNÀ½—ðø¢@iç+[”„@칈Ó2çˆÀã"AVé†Àù ^}@…À´›Ùuì?z»ÅWy—@”:3<0IiÀ!^Lv´$f@,…û®I6ä¿¡øÚG:eÀhZÓÙ\­+@ úüf®øÜ?pUÖ¯XÀ¦gmè…l@i2HHx>À+]+©?UÀ•$ÐzQ`@•$ÐzQ`@æ¯;}”’¿à?ý ´ß<ÀŽ3×¹‹:À¡Ï\Qzb‰@¬Ä¯DËNÀŒýV­ªp8À-¤?S%“=@s…Š)£5;@t¯Ž9@U'1É5fÀäe¶:@Ñ;¥} ‚t@.…û®I6ä¿9½¨ËòÌc@Ð.·Pö@_€†Ú8ÀŸ®*Ê£ð$@Jkþ¸k(À*–qLº§@°8!6õœc@Ðb?#b5À:æHáŸzCÀ:æHáŸzCÀ[pJŒØÏ?Ð? Þ5Zy@È:‘w@¹>sœwí0À,`ñá…a“@Æï®#v@« ~‰iºyÀ kY+xÀü€w´vÀèÌ,¨”æÀ€:^/ȇ@lHénâ[À{çNä]V@UÝ,úÅ¿Ù8|ÁĬUÀpsÿ’ú@È{¹ÈÀ%‘1¿>pMÀ`Åjç\@¶f<Ñ.À¬ç´êåEÀ’²¿ª4FR@‡¬™brP@ð )íc©t¿Ð?àóeäžo À*lè,_áÀW¨óåÁÞy@¹>sœwí0À39"eÀ‚$çÛÛ @•úÉP«@2‹VÀ@~ê¸Xž{}Àqè?¡™2@ ®× íd@XÝ,úÅ¿rÀ&çíS@Švðèû?½#Ù°»_(Àñ¶+‚@YAV Àâµ|Ùœ@<Éáhs­S@?Öž©‡ï'Àú¦;f=Ò5À{IϨ£3À_P7™aÐ?Ð?S³'ˆÊåy@bÅ$Ÿ¥Úx@¨†êý…" Àd¹rÔΓ@ù!¶hDÚw@|xÛs˜zÀiÉ »…yÀ ±æ—u~xÀ‡E9s€,ÀM ¢Ÿ˜ˆ@A ‡(øŠ^ÀÙ¼#Dl˜V@($ažÜ„¿þ:ã'¤"VÀˆt$ÎÀ @(Žêš*g Àr•k©‚QÀô~»ÏºJ]@y¼xšN*/À/I®Â|‘FÀaâÇÛjkR@Wå3,à“P@M®á£Õ‰O¿Ð?#¬0ªœú¿AŠÝ&Šù¿X:ô bhz@¨†êý…" ÀÕ?³‚ø¿å»«ðÙSû?첆ùô9ú?ášuÜk+ù?ŒH Ü(–}À×–ŽÁ8m8@ôF†ˆÐVe@/$ažÜ„¿JX˜óéT@ °¨AúÎÔ?ì{/K(ÀjÐ0¬S2 @^¿ÔÇ…së¿&æØ@ÅÌF’{¾S@Ó¥¬l*À†œÃCØÿ5Ày¦É ©Ì3ÀýG#cXQà?à?‚J›ì»¾Š@@Ò̘0<Š@T¨E?15@mÞ7À=¤@¸Åv"¼‰@¶]6Ù‘€‹ÀHÃeTúŠÀ,V-.¦vŠÀà­Wš%FÀ?¿±•m˜@(á|4i¡pÀO˜h®@Ôf@ÃâììaÔ?碠!õ›fÀði 1êÙ@˜;¹±Ýê8ÀEšxÎddÀi#ý°m@ë±@¢‚?Àãò…BWÀK˜ø æµ`@K˜ø æµ`@cõø z?à?· Ÿ%@JR@fš$@­¢{YÆÿŠ@T¨E?15@ ()Œ5$@7å?Ö˜%Àu㧨k/%ÀtœÈ$ÀãxζÀÅÉ×KäŠN@4óʽ¿u@ÂâììaÔ?=eÄñ3d@Ý%‹^w;ÀUF²`ø8Àðã¥üŒL3@ä ©A@Z9gnñƒ'@JÖþ*Ðc@_^i¾E=À"=µÎõCÀ"=µÎõCÀWó= 2…à?à?Ö†•³~¡‹@AZóÀ“·‹@'¸ü©f I@ef¢¦°¤@\&+tºÍ‹@Í ü^tŒÀo+ÿ‹ŒÀ· ~R졌ÀïØ”[wlNÀ°" $Ę@Ú?ArÀæ¾Pg@•L Uwµå?èÓâRÂgÀÿkޤãï¿Z´Xgp¾@Àt™ôd_gÀ½ñÄÂn@Ýp¸sÚ?Àý(ùWÀMÖp.)4Z@éÒÚcØ`@x†;E 3Ž?à?ûLõa9@óg?p,9@h5u]¥‹@'¸ü©f I@8ÆŽ@9@s}/Fè×9Àª » ì9ÀÙˆÝ|G:À«<9N¤ÛÀK®Ã«zR@\-.:›%v@’L Uwµå?ÞÙk¡QWd@„¶#‰j6À,Á'u³R8À¢‹ªB‘6@›jðSW@¿ Ø_*¤*@h…>©Gâc@ö÷˜À9@À¾D+ÆÛL?À讑DÀ`¯:éõ¹Ð?Ð?)1z¢aŽ|@«ü%Í¢N}@— ¾4ýC@Üö/>Ù&•@ÁGŽRò~@ ÓPQås}Àœ¶Ð°/:~À•w(±À\â¥ÜÐŒCÀ‹tî;‰@ÜY¤š0qcÀRË|€ƒOW@ÍC£f÷à?/§Î™WÀPôhnˆÀW’óAI5À(xv»9sZÀ/ÐLËø„^@!m³2ß0ÀŸÿT~µHÀÅ8&z0>@ïµDûP@©tË$£Ñ‡?Ð?Ÿ`ƒ­@4@tö—_É4@.u šY|@— ¾4ýC@Ú 7÷T5@€v³Jtã4À.’ p5À.]šj6ÀZ Ò~À¬b•×E@º ©´ƒŠf@ÍC£f÷à?‚‡¡jÑ|T@ ³ôÚÀ@šìšÎ(ÀIDÞ*@hÊLr˜@L¸Clã@°7j^õS@êa©½Áx1À¹Î¼"À8H–³H4Àjñ E«ïà?à?ÇË<±…@äÔÕM@&¨g¼”²[@Ö¥ÿo ¥@êÆ·²J@Ám•†’ŽÀåH9¥æÀjÉuü÷ÓÀ6a g÷XÀ€X{Îx™@ôÈÅ\åtÀGã'¾Žg@{Ï{ln÷?A{!ÆÞhÀÐW#p\"$Àhç~²†dIÀìÿ W¡mÀ¯'¸ƒòn@ïÉ—DD@À6ò–ЛwYÀÌ>X.qa@ôë§EU ?à?ÛõÚ4)dL@ÒµNe'ÓM@£AÃò@&¨g¼”²[@Ö×ýn­TO@qfxTMÀ($S{˜ÏNÀ"Óî.PÀšK6¿Á8ŽÀ^Âwf]Y@߸1R¢ív@Ï{ln÷?‡Ì­H•£d@Òÿ7^M'ÀÂsbü9À@ xýîŸ=@‘¦Bø ,@tQ =¡0@.ÃbM”d@u F:ôôBÀá‰ß·¨rDÀ3óNìÈÍ?Ð?ã`º Bu@ë6Òœªq@ÎçžÞNÀCj]z5‘@$Ý ›˜m@çÍI=~uÀ4LžßrÀÄ/Á)nÀ”2o LY1@ÊøÜ1†@}§{Và;RÀ¤¡lÈôU@†?¶TcHã¿ õ@U-SÀ3 ÷¯h-@€ÜµÙ€r0@nµ¹ÖÚã6ÀÖŠ¹åذZ@k»v6,À¸Ñj/cBÀHÐÿ2>YQ@M³Àä‚“¿Ð? ˜è’´;À_]Ë«þ47ÀN³â„Q[w@ÎçžÞNÀ ‚… dp3À|;S0Ú;<@º€O¦7@ð‡NÏ3@æO ¢(}À€hvJ@ÂÖ?Ì4½™?§b@‡?¶TcHã¿Wü6•’S@ÏĪ@ãæ˜Ì 2À:˜d´•˜ÿ?ª ™ËË<4ÀGÔ<>ìi@B»”S@¡Ê÷ÄàÀé«P¨º4Ài+Q×$î?ð?Ív@{i»•@ù<ÈW³Ž’@ ü»8NhÀÀ˜èˆ ’±@Þ½kl±@E!È+–À_Ñûî’À¨ÂÚ,&*ÀȰûŸÇF@…)ÍÁu¦@AjqRœtÀ²ã™Ô”5u@£,zØ[nÿ¿Ý),+±sÀ˜¶¡e÷òJ@^ jÖÛH@S©Ï+J:`À2ºGxû{@ä¬S+fqLÀ—‡VòbÀxuG!ºö[@k©ÌT4zq@ÛÜ‹„5¯¿ð?ŠMDqU“VÀì‰r‚GSÀJ‡8ò±—@ ü»8NhÀɼù(vPÀJ°fZW@Ð5"µ&ªS@CÁÊP@—$‡ 0À¸éí3@’Fakƒ@£,zØ[nÿ¿ò"l™3s@)¦dƒ44@i§…’@”QÀ¥{Iè&)@-ÃÃ/!QÀØë42%@ÖX»}€s@JÄ|w¸5AÀgÀãU#¹@À°\+lçTÀKøsž€Þ?à?Fˆjg†@F7n‘ƒƒ@jœ×`WRÀËÅ­zò¡@ÅG7É(ÿ€@‘î2+ªà†À¾d¸‡-íƒÀHÏšU%[ÀøLy1ˆ$@S¬tœ¼–@zÃoì gÀ¹{l–ie@Iª7»ç¿Ûå‹÷cÀ»–(_€I8@qsÃ&Ã0@‡~)UÀLެ]k@\µÂ Ç<Àli*£þ…SÀå…Ø§X@ZÍãî›a@JãH’L—¿à?›\eÉd/AÀu¯Î7Çï=À+vA=}ˆ@jœ×`WRÀ«¾uE.:À þ_afŒA@³ X·Ë‘>@½7švL :@=•gE‚=ÀóÅOò°°3@üÅg¨y|s@Iª7»ç¿ßR!K{Qc@ ]Ùö€d@ B;æ15AÀ¯ ÔK‰!@Ò Æc<ÀòbH9 )@ëëEf+c@ Ÿå‹3ÀÅ+Z ¤‚=À±úd,EÀ|n€¢ÞÎ?Ð?Ƨ $‘w@ÏÙÜJoŠt@Á$¡yZ8À~†_U’@¯[¥ÚLBr@ôñËSŸwÀ…'SøŽÿtÀö†”ÉiªrÀ2 I×÷ö¿Š¼©Ç½‡@«öô¶"…YÀAV`úžU@½-lŠõßο¨çjm`TÀ:‘FÞÅi%@+ùŽG:@ÆçÉ AJÀÁúðÄ¢·[@»Xõ i-ÀŽQ#óVDÀ 3ÁRðO@Ýf¾Q@FœL(r‘~¿Ð?¾u:¤c'À²ššx$À"‰?e¦x@Á$¡yZ8Àp)<[2"À_¸]>³Š'@å/9í$@^±|Aš"@ÿjâëN}Àæò7O‘è-@„ååTåc@À-lŠõßο1o@DpS@yC)›þ@ Ⱦ¹ï0ÀŠ G0tÉ@ÕÊ•ð×ß&À?yÁP@¥ECÀ:S@ž§–Eñ%À•C¾Ð 3À3¾Øïç@5ÀDY·*>ß?à?ò¢ê_-؇@ÆÂ'ýš¤…@¥*]ÓÂ77À-N3¸‘º¢@‡hyÒ¥ƒ@®ÿ±zgˆÀñ»TP­&†ÀUüùÛ „ÀD‹ÔÈÀ¨0ÀŠÕ.±ìO—@îX4%ilÀ¿Ëž˜¾Õe@P—l×öÊ¿44¼üÌdÀ¬XsEQ2@Mr`Ö1Ú?O,‚‘Ђ_À«OÌ?9l@ƒ´jíhq=Àþ<ê2Œ»TÀVr•$˜áa@Vr•$˜áa@ïó ]Mª|¿à?’ªèØ+&ÀùȬ@Ò$ÀËVDh[üˆ@¥*]ÓÂ77ÀòÖ"-D"Ào±&@la÷Ę$@€êvZô±"@+eÀŠü‘üQD@Ñ÷^sæLt@P—l×öÊ¿ôh“Õc@¼™?Cá@[DF Å@À¡órÒU,@Iô%×Í»1ÀuŒUÒU"@ø˜e•Jc@™êKi8À&ÈpÄ¢mEÀ&ÈpÄ¢mEÀ™‚Â&EŸÏ?Ð?2y:ßx@Ð}‘yÓv@¼Ydúfêø?†R ]ó"“@z˄۱*u@ÄK†9yÀϱNxdwÀ¶•“;аuÀŠ€ÙYz /À¸H=Už‡@žÅì¼1¦^À9´{vÞ V@C”¥ëM¨?NÐûÉ@œßZƒRŽ£@¹iÃÖ†@ºÑÆàŠÀ÷X¨×‰¹ˆÀß}Ã2_o‡ÀY±µº&GÀJÒ]²Øí—@ÿ>ƒu¦pÀ=ëQGf@×’Bh¡‡Ú?vŽ!Lå¯eÀ<7WÓ&@6‹Ž4+0ÀšÀ©$T":VÀù¼}‡þX`@M'¨]þ)b@ÜÖƒ/Ë‚?à?“Æíu-@ȘÞf,@Eó™øŠ@h‹p¬ŒP>@îXhDŽ*@”h¢T.À,ýò›¿,À^j¶?+À^&_‡ Ày–É•ÝO@q«M8Íu@Ö’Bh¡‡Ú?ÝMYëˆÒc@bñƒªØ© ÀfÚMgîÄ@À˜AJ¾-4@Ú©?|BM!À4´S®(@fÛànÏkc@—ฑ=À|\FO­™CÀPJX2ÇEÀêÝ 53à?à?;ÎÙCŠ@¨·®]u‰@U`Œ2ß3M@e¾¢õÂü£@±Ðyn8­ˆ@)|# óüŠÀ—ÁåÇ(ŠÀÐP º [‰À²‰¯xOÀÂEž@˜@Hý]rÀ)ý ‚f@\t¦˜­,è?jÛ:`&fÀðúÈÅjS@ìâ ’Š8ÀÊ:Ü=e*hÀ£!js*9m@ÖÍðP‘m>À£ 5²VÀ{ò ð¡Y@¡ˆÝ–Ob@Ûœ+E|Ù‘?à?Ó!ùOÑÊ<@„ô>)wè;@,Ì;¿°»Š@U`Œ2ß3M@mÁÞ} ;@à¿õǺ•=ÀÙõ l%­<ÀíTu‰´Ë;Àþc)SÆÀö@íFtS@;’ þðzu@]t¦˜­,è?µ©H oõc@íUt„S€Àšƒµ…Lò@À“µU¯l7@ü¢ÅaîþÀ½d‡ç+@èm]íB}c@Ÿ¢t„!@Àr˜ƒ-¼>Àv‘‚ ôEÀžK ÐHfÐ?Ð?f›™=a%{@WQëÁ¨ëz@‘£á*4ÚE@½)ÌYn”@d–‚k²z@ ì0+ï{À"Ѥų{ÀŸMdÞx{ÀªÐ¹CÀЗü`안@G«+fdcÀ¥w—%ÿ½V@¢4´¸†ãá?¥Fì¬D VÀàæ°&²Øû?êEáÜ{0À*“Ô¡'[ÀwºYÌÍŸ]@}ú‰À.ÀE•›CdGÀ4¸‰—އ=@¶¹tR@á€MçkŠ?Ð?÷ɘKË5@bHéSôœ5@æ pê”l{@‘£á*4ÚE@ôbî—ÿn5@a uMm6Àò³kU=6Àx¼üR6Àæ­×ñ}ÀN&€ÙcHF@© ž½hÜe@¢4´¸†ãá?¤ß²µ}T@P£Ä3FÀ"Šé?1ÀÝy®YÖ*@TúváÒä¿nÉ^Ó«!@k/fEOS@<}6…1À¬{ñÈ4´!À•Ú-ûA!6Àp $šBšð?ð?´Ï_çœ@M4ƒ†6}œ@óúÄ"xVm@—²ñ)ã´@ Hp§'ëœ@ŸÉ­ôìœÀs«Œ•\À× ž(äÍÀNaDèhÀÜÞÿû»í¨@‚n…BVÏ„À–÷ä›ûv@ßáêiê @ç\‰˜wÀ€;ÞÝü¿uÒ®¹TÀÖê70þ=~ÀF£K³×~@¬FW¥õOÀ]¨»RhÀ‹˜t‹Çšr@dRm^ñޱ?ð?ʺ™*¿›]@È™ ^@ño3Í,œ@óúÄ"xVm@ùBâý^@gì²=äƒ^À2.Œþ¦ù^ÀÃ^G20q_Àúã–µY#žÀžŸH·Û¯i@SWŒO<†@ßáêiê @ÆoŽÂ>t@“zý+~8À Ã’t[¯QÀ1?c“-lN@¨GZÍžµ @~0+û”¯@@'áh§û¡s@êƒ_©ÏóRÀÈEIò±NVÀ²–Ái?í?ð?CMgrŽ”@JÇÄ =@s§¦XójÀ¬.u餰@£8Χ‚KŠ@Á×ÔÒg”ÀÞüš—d…Àû_´Ž‰ÀŠÀ ¥V?`ãM@8z3! Í¥@mJsC¡rÀSÄöâGŠt@sÇódÀŸ!¦Œºd@˜Õƒ£@꿤ç@ÎbÀð{JÎì@@ž¾ @@?Æ:—RÀÈQŽœJj@tßÂÚ3;Àôêû•9óQÀª Ì{+cK@ †_-ûa@VîÕ®áÉ›¿à?Në3tyCÀ\g°ð@ÀcëmÞ†@ߺ•ÏÁSUÀ EO‰:À?ÿܬ×ÔC@òßö‚^@@žÆeŽÖ;@ÈI‡:bÀúÛ×MÝ',@k iL‚r@˜Õƒ£@ê¿—WúÎÜb@*/é7·›!@òÛ9ÊEÀ¯—\bÀ@Ó2¶`FÀ¢F_2ˆ@½ ¥¿b@û:XYÝ1À(Þ!âDn0À²UªÖ‰DÀ¯iT~ÁñÝ?à?ð™Ë~N…@?'eâ‡ð@ÅÃxJOÀL%ƒyîZ¡@fÿç5~@5Ã=ú·…ÀbEXI‚Àß¾½EË~ÀÀÝÑMt@Žin+Q–@ j-ðRgÀ)tåèKìd@kHóã¿qeÄòL/cÀ_¦˜Œa?@.I‹DTW8@/òzRFeWÀýˆR¯ÿj@è{A¬Š…;ÀâÁùUô~RÀWÄŸ’ $X@Ѱ–R>a@–›`¼ºþ“¿à?ô·Å•—<À þ]ér8ÀïÎEI«?‡@ÅÃxJOÀÁ6Á‘›D4ÀÔßí›$=@Ä24Ÿ‰8@ËîS°ò¨4@‡ü™r8'À =Àó87@Œc9M¸èr@kHóã¿[UGå¡ùb@ûêÕ€…@–øKÕÚ}EÀ"Q¤¶R#@kþsŸ7CÀîiÙ@ýŸ•a÷Íb@˜plÖ 4À³ù7þ<Àû'÷ÔµDÀ[®åûLÎ?Ð?Íʲê÷ùu@+÷¦„âr@8Ç83À~ûE'⹑@'¹Vh:p@¾«ÝËlvÀ#«;1EsÀ5W7P3pÀH·7¼– Àß&Ó n–†@EmXN0¿YÀJ/Ð…UU@ã§LhÆ¿Ž-uó@“SÀÀÔ­ ¶,@¢^²ÐÅ_ @κRZLÀóHöÈóZ@w+õNíÖ+À€ý7¢CÀ þµ;VEO@xâÖËh_Q@æÎ¾5x¿Ð?Ù)û6U±!ÀEœ‹pOhÀ±ë^¼¸¬w@8Ç83ÀZïE:!ÀÒ§1Ç "@9ºÓ0@3³ý©@âr–q9}À, ?E¾±0@)¶>Nc@ ã§LhÆ¿wõ cOS@—‘è)ÿÿ?Uf„J5À^* Ž@êÓ剛0À,b±}g@øe;e·ÜR@𫺨šr&À³²Š8Ë2ÀT8arÌá4ÀÛívh¤©Þ?à?ú+뀭†@œ¬Eæƒ@ ‹®Á¾y*À†ƒö-¢@69–f+v@8é\g›*‡À:ž0þ T„À=dújÖÀôyÖà‹3Àbl›åÞ–@2¸quú8lÀæ'íúºSe@x^æbli¶¿²‘N©4úcÀÊOõB¼Ô9@ÿúµ @Ü:“Û»`ÀõÞ{Lk@!q®‡í'<À5ðfqÍ£SÀ6Ç´È:a@6Ç´È:a@Â+ãù rp¿à?G›¾lÞÀ 6ìñxÒÀí‰bîñ%ˆ@ ‹®Á¾y*ÀrœÃ&ÀU¬—g@xø ÛJ@»£#µ@°]ð%CPÀ ?¨ùâE@¨Ç¿u²s@x^æbli¶¿v5Іã5c@f0ƒÓ õ?çPT1EÀŠÐŽ4.@T\ô÷“\<À-Ÿ\Ôú"@à;òëëb@ðêÐâìÕ8À¡vž–½ EÀ¡vž–½ EÀÔðéÊÏ?Ð?0kÄwfiw@¾.ýt@ƒ]_üÄ@°K×€’@‘mDvòÐr@³ôÑËñwÀ$]¨ƒYwuÀ]HÖ‘>sÀØ&öp‡º0ÀG3.(‡@.è@ÍÀÀ^ÀPó‰z‰U@b²kOâ¸?§`«‰>dTÀ¼ùÕäº&@€ÛdrÞÁ?¨.Zˆ_SÀÃ&2©³¦[@Jͪixx,ÀTRE=DÀè:ÈÁ£Q@è:ÈÁ£Q@éŸ8Maá_?Ð?e*—‚@åI’@©5tµ«x@ƒ]_üÄ@È€Ecå@ÇaÏ)w À`}¾µ\ŽÀ¯ª%H3SÀý/̓åk}À<Èð"ôU;@& …tcd@c²kOâ¸?Ù8ÔjUS@qžû«Så¿0Âêi}35ÀbYÑHó!@! báSä'Àáž'§§@ÜàêœûR@zì„ ÇJ+À`ÀLU¬95À`ÀLU¬95À…J@r|gß?à?ΧÕõ-ˆ@=’ÝiK(†@eú†—kC@#¿Pç¢@­ƒÔëM„@Ÿ iˆÀé5CP¦°†ÀLxßÊ„ÀH’Á7?HÀ¨ÆE׿t—@(EuÁy«pÀ×!«°Àe@r¯œÅß?Aéü3sÑdÀªªn;·e3@ˆ—GYfÀ«³ÄÿfÀ'à-žàl@|oÙþ}È<ÀZÔ$<¨ÛTÀX®_’¹ÿ_@¾™QQõÆa@jƒ{Ç`ˆ?à?âmž„J¢2@¤›'Z1@Iidèd>‰@eú†—kC@‘GäŒK/@=b`ö3À·¢%o|1ÀÇ—Z 0ÀxºÄ퓌À]´öd®†P@}Íf¶Òvt@v¯œÅß?R¨†+òuc@þIe¶@ÀÇÍ'FREÀQàX>Ê5@_ci'Ó3À .Yo(@ÞÏ c@ÛæÒ=Àüo%áÜACÀû_› eEÀRmÇÈï?ð?®Zlz|û˜@«B3Ègi—@z%j¨‰`@·îº|ŒQ³@Ð(þhšð•@5¼Uoæ™À‡¬(Á›˜Àœ(ý¼<–À°²ËID¬_ÀCÈÐç@^é”ÿýÀåù±òøu@Ž/w_™6ú?ï;ÌäAuÀ8 žc‰¤?@D³êÇ]@À~Žù]éxÀ˜èÏz‰c|@¡Õ!'òMÀ[î›eÀë+Òi@:{ŒqÊêq@Ö‚—â ¤?ð?¦/Šy^ P@-Kö'N@È eÞ™@z%j¨‰`@-%% 0L@Ôy³tPÀŸ}˜Â³×NÀÅ ¶MçLÀ·‹sfŒ²À&Ì£ï…c@YÊÏ‹´Ö„@Ž/w_™6ú?lY¹©†—s@µêH‘O„+À¾/rˆ UÀõUED²6PÀi‚ €L2NÀ¸t[¤‘UÀ;zñ‰Üð?ð?Ž•GÒ™@;w–ÓöÁ˜@J•œ•g@•ç޺ɾ³@íxBðݼ—@ 9A¦ ƒšÀ0Ü‚l™ÀLy!dç_˜ÀýjˆØcÀ¬óedc¨@‘ßÂe%XƒÀx˜2v@ÙLêÂÑ›@07¢µuÀ˜óú7@.HÞDHÀRå:‘“Ð{ÀŸ‘©Å|@7ÿƒ™ÍfMÀçï%XÐ'fÀ_ƒ å\@’æf3r@ªÛ€ï¬?ð?ìÃðQÛ'W@K¿x§3V@<ùéÊŒš@J•œ•g@CÆÅƒIU@í©:UåÆWÀ+Úq=$ÌVÀUJ¡·ÛUÀ£RDÞÀ×)4Wªf@s‚Òï4…@ÙLêÂÑ›@[¾ù„5ºs@Ç™XÌ‘3ÀŽTÂ8ëUÀ…›P.8ŸK@Ö¾­Âõ9À?±¯ÕäQ>@Ÿ[7Û-s@ü{ÔMQÀŽV")¡dAÀ.ìjsɽUÀjYYZ0Hà?à?so0u£²Š@ÌŽ¡3Š@AÚ&<Û^@*kI{/¤@ì9íÚû¶‰@kjß´Zt‹Àp•#A¿ñŠÀÓ‰R!‘qŠÀ¶½_}© XÀ4í²­ui˜@ªÑ±ËºtÀµÇomf@pNèótø?r=ø3¶,fÀáš„æ‘@ºÄ‚IPG@Àe‰RÜLÐnÀ‰ÐÃ{6*m@³}¹ µ=À€¸FÛÕVÀyÎA4b@ NïÆ½¢?à?jDþ¬©N@‰¼TÎN@T‹úG‹@AÚ&<Û^@’¬¼š¥ˆM@ü£B8)ˆOÀ ï_%(òNÀ¶qú¬ð^NÀJ† ``ŽÀg¶¦HUôY@ŒïŽGk‘u@qNèótø?"†+Þ Þc@Ó,j:‘)À­›‡XÀ÷ oü @3b[—fw@™eBôDcƒÀ?tu*\~À¬°I,\ÅwÀzÎ3?$y9@%J35ìn•@Z¬»IcÀ\«4è.d@;ýÄo¼íë¿"Q—˜˜½aÀ£IòèPE@콈Æ8€G@Uc&IPÀÖ6Òÿ’Ki@胭€¼9ÀÖ%@>zƒPÀ53šÄnú]@O¼U  ¿à?‹¨CÓ ^EÀôÿøïº@ÀD‚½ûøÀ…@¹>­›‡XÀ•‹SÏ2:ÀÆCÜ©´E@©ž±þ@@üG×{èœ:@Ò_·´TùŒÀê+ÞÆgW"@ëäü ã‘q@>ýÄo¼íë¿ÀÛ(+\nb@忳BCÁ#@‡½ãŠO/JÀ/Pð}0â@+ Ú¸tŠMÀF¯<õS@´ü N?Yb@ÎmY),T0À¿ì`ÂÊBÀƒHD ÛÝ?à?§.l€Äªƒ@ìKCf@Ñd1'…RÀÊ«‹°uq @~6?~¿y@DOJ¶éþƒÀâ ¹îšìÀÖ Â~ý{yÀª~SDqÓ,@¥/Ï p¬•@ߤ´¯rHeÀÎ+ÉREd@“áÞí.¡å¿³êöbÀò`I;BD@Q;nÑÕ¦C@0€ô{!ÔTÀ8Á"ð·˜i@±’/Ͳ :À„—`#ÕQÀ/^rÖJ@÷)Y Ü0^@÷?°{˜¿à?¹<×ü @Àá¿ÊbŒ:À¥šÞ^†@Ñd1'…RÀàñ.z15À-US"è@@t­$þ:@Áͺ 'Œ5@?qúÀ[£ ‚øÜ1@Þ†­‡öq@”áÞí.¡å¿ ;-¨i‰b@´®ŸKa@u-dÖÝIÀÓ[26 @…œ`‚¼JÀ²áRÚ™Ä@O(‘K¤fb@¥ø“õ”v2Àr”bUã&0ÀçÀ¿+BÀ%`Å¢hÝ?à?’‹¢)®F„@R„Ëì‚€@z ¨?£¶IÀ¥UhÊ @]#86äz@Ûk1k_¢„ÀƒMš —Í€À|ˆjóÑ]{ÀÐ(æwy@Á¼®k%ì•@~¤UÁ™gÀÄú/Ãtd@Ð?´³k£Ý¿ ké·sbÀ•K–EC@ûÂ5¢Ž?@΋ւYÀkDâÝèi@h/~½¨X:ÀüŒh6&ˆQÀßúZñ·¦W@E°âZ£h^@ —©²×Í¿à?âR‰^L7À¿ɬõø2Àm³¯Oèv†@z ¨?£¶IÀìÝÍ×Sæ.ÀY ºµ7@ A.ÈÁN3@Þr/@ûŒ–,°ÀF=]ý:@òn¶©Zr@Ò?´³k£Ý¿Ñ¬Ï:¥b@1Ð@Þý@ÍJvJH¢IÀºƒ7ì%@껎Í@HÀ@. ð@_@&Ë5ajtb@HP“@n§4À+Ó7€<Àœ¾®5®RBÀÏ¿‹ê±Àí?ð?ù- þé”@ʼnRøa‘@££í‡LÀF®íúã%±@²Ç1û.åŒ@9 îþM•ÀTÛnµ‘À|¦“YoÀD-ÕϹ2Àú2£.¦@¥¯æ¼¤÷yÀ¶í˜†¥t@q)E—ÓßÝ¿ÆùEhìÑrÀ×ìjàQ@ZN«göÂG@à…ãi½VnÀ7ûfÏ9z@¢÷L¦JÀ›Ÿ1D™bÀ -UŽÀ¡n@ -UŽÀ¡n@ؓź¡’¿ð?¼\lŸ\¤9À|ZƒÖ÷O5ÀktAêâ–@££í‡LÀEYº¶1À€ùø:@CiBàµ5@0[ym 2@ÇFVަ%Às-,)åHR@| §u¼‚@l)E—Óßݿڵ³ÚÁr@I"W9ª@ÔH­EüYÀ'èÜ>:@¤“§¨ŸUÀ*ð;Ô 1@(¶…Û—‚r@aœfiçFÀÌéè“yRÀÌéè“yRÀp»¯q¡î?ð?!áä4ý”•@ «ÁaQ’@zkªS\õÀ”3Ó´øƒ±@ŒZ?^N@T›Nñ#–À¼›­d®’À–Ä‘µÀ–'vÝ-!FÀ8î`r¦@ûtŽb|Àø#Mjž×t@êÛ¬¬Ìœ?Úv£–3sÀt±P˜D‰P@›†¯Ô?@%™ùﬨqÀô¡~Ûz@™_§j‡óJÀÃÄÅmZbÀ·NÞý$q@AÁó\/Ün@U48 ¹b¿ð?‰ä߇œ Àû:ÛVTHÀ4ÛM¼Z—@zkªS\õÀaŽ6µ)œÀ_Ó]í·, @©ÈŠ#Ã@ C7f@â+¨ =ÀíŽ>¥¥OW@‹»)•ƒ@êÛ¬¬Ìœ?”¼ïTßr@€21ä8æ?gËã?wYÀ¯e–'Á½?@˜½ÎÐTSÀÀKs¡3@ qlV3‘r@ñævVA7IÀr6D²TÀ¬°wp RÀ?Œ«,úuÎ?Ð?á8IfõGv@û¬ŸWRs@Ó\ú%'%@H- ·ä‘@n¹ÑZÁp@pkÜ,¿vÀ$ãßf¹¹sÀ²¢VqÀÕ/#8Â1ÀQéí ¹†@ dÍnïÚ^À‚¹¶€ U@Uº7ýìÁ?¼ý:.˜SÀ0r7 Ž/.@, £Ø @:–&×:TÀ–ÞeKäZ@Å_0§G@+À;z±•.CÀÏùÊ–+FQ@C[mèO@q:•G?k?Ð?¯&Q!÷­@Ä=¶åÎ@æçlʸÞw@Ó\ú%'%@±W”™ @Ãú$CÀµ!‰lÀ¦‡ 7m7Àk’î%Y}À±žƒ•<@Šê§\}c@Uº7ýìÁ?\ô‡•µýR@þVÉxw´ñ¿%KÁ+9‰9À.%m·Ã"@ݰŸøî91Àîýt @³C R@Ô%pº—+ÀãIÍìiÝ4ÀM…»EÇ2Àw+TiÉÒî?ð?3(\‡1—@c·f”@þj_eögW@ßy 0H²@WƤ’@fCÆ™z…—ÀïÍ&›Ù”ÀVäˆõf{’ÀCgO’ÎÆXÀq> §@3Qªœ°€ÀGRtÌ?u@1%N!ò?æZÊÿsÀxжlK@ƒñÓ[Á?ìÉ÷-yàvÀâU4%={@ ðñ{ŒKÀ 8UvÄcÀâƒû§ßTo@âƒû§ßTo@ƒüwõÆ?ð?p×+~F@­µ•[Ø—C@2 ­è@žå¾yÐr@2µ€žŽ’QÀJºér¿AÀ’ñFa×;SÀ꘎B‡òß?à?“œ!voi‰@Äv‘M ˆ@„MºÑ`!`@Av)¿¬ƒ£@pËy’Òç†@¢ÄBKéŠÀ}ùh'ˆÀû "|‡À±š(t§ôWÀëü™9Ôë—@ЂܥtÀ›R¢Æåe@çÙIþJ²ø?-Œ— vIeÀç¢uU0@½õÓ)8À›’ïòYoÀêhGHVl@蟧`m<Àè0=®Ž£UÀjȾBK `@F$™pâ£?à?“î ‹5’O@~…fMùM@Q§ÇoŠ@„MºÑ`!`@±.AbuL@Ä0|˜3PÀ ^ãaÂNÀÑè€ý3MÀ ²vÒÀüÀ„’C4,Z@ cñ)ít@åÙIþJ²ø?‹÷œ5c@CrÄáŠ*Àñ…ãõJÀ±ÚíèÈá?@*©*£Ù¼5À‰ttCº0@?eê·¥áb@³i9èBÀ̾ƒ7ßbCÀÏÐñ÷:Ü?à?ßT‹a,‚@Ý_Ö;Õˆ{@|ÀÅ?:8UÀ³†p˜.Ÿ@( JïÙÛt@´¸,;o‚À½Eôöî{À¤ F”(uÀ‹<¶×ÿk5@îG*p•@˜4³Z?bcÀ,BÞ­`©c@52º'pç¿óüÓJOaÀê³ß…RÀö÷Ä´J¦h@SãÙŽ½©8À¿í›ROÀ!¹“WÎÜV@ÎxWÅÄœ¿à?ù;·Ûp“BÀ÷yé¦ú$<À])ÃÊ‘…@|ÀÅ?:8UÀŠÚ³×#R5À¥ zÅ×B@±6ùÁŒ<@§ÌÐL‘ 5@ÃHr²äŒÀ®±÷A_Ô)@ w\q@42º'pç¿Çsågb@çÑ€\!@¸¯w$÷NÀio8@”›"QÀœ³î@/v·¾Zb@¤Wšßƒð0Àï*¹C‘;ÀȽn¦–ŽÜ?à?2SR¶/º‚@‰(î|@ÿXÓ¬¿OÀ„Î2§gÕŸ@!5¥*—Xv@$¢µŠƒÀm`9˜Ñ^}À[A«¨œ¯vÀú7µ_„%@2V‘þO•@ì°a•ššeÀ [?jÕc@×’ÂoY„á¿úëÆ9jaÀr†µ{G@–+M¬G@ c‡& ôVÀÚÆiÀïh@!©æ¼uô8À"ü¥Àü"PÀ!F,;OJ@C½ÆSW@“ À-CI•¿à?€”`'Å<ÀµÖþh§5Àé ºgžX…@ÿXÓ¬¿OÀ~ÙZJɹ0Àÿ eñu<@1ú%€¼û5@‰€Ú²ëú0@f X"ë¿¿`f¦Œ¥@g¹ß> ÞwÀ¢. ¶t@½#“÷œ8æ¿ú/ £ÁqÀ9ÇÂ>[lV@jÙÇ×7S@ ¹>:„kÀMfÉ [;y@UÉ1%ì>IÀ3Wà` `À&@‹ß.g@&@‹ß.g@ ÉáÚœo›¿ð?ðNm{õsBÀÛ~/.Ý=À½»ìš~¸•@Ùø%´TÀ ÏNzê6Àc9ÀB@]þÏŒ=@ ¼4/þH7@SØüÆÿœÀvÇ,ÇF1N@éܤòCÐ@¾#“÷œ8æ¿Ví€)Tr@€ ,eÆ @[VY¤]À$ž÷ø¬6@bãÛÕ\Àjbî|X¿.@CF ­€r@º©i–"EÀæÂíøfLÀæÂíøfLÀž.¼žv9Ý?à?_×ÐTjêƒ@ñÍ…¨´€@Í(³ùB›2À‘È®˜ @`–ÙyÄy@sšÿpA„À/.TB³J€ÀOÕq5zÀ¸š>¥L(Àbñ=wË•@Ä+Ÿé¼.jÀÃÐ_I1d@y1\÷tÂÀ¿=_ÂB£bÀTx,2ÿEE@ {CÇmÍ>@N+;üQ`Àت *‰i@BˆD€ ‰9ÀXФ!QÀ]c±›H^@¹i¦\qYW@$¥6dñ;x¿à?®&ï|.¿ À¸jÝqðÀ½8«ƒ#†@Í(³ùB›2À,œ ãàªÀ…Êë[!@§œ6Õ(f@9ò½Ž @3¨ÃuiÀµv¹¸¼C@qY~­«/r@{1\÷tÂÀ¿Äƒy›°ob@7Åqà®ý?’«Ð M’MÀ&^ÔâÛ+@ôy¢1~JÀcBÁ=¿¬!@»eà¸",b@n „ÙP7ÀÛ'7r¤+BÀ6ÌU\ãC<À—¹fÏí?ð?Zaba”@Ézñ¤á@Ûæ“ûµ#@ö`·¥^ó°@øw轂»‹@BðDqŒì”Àû2”¼Ð/‘À®@·í;ŒÀ4sˆqHÀ¡Ô>€ ¦@n’ýÞ^‹|ÀÄC(at@]­‘Ÿ.Ê?DÞ½jRxrÀ8nCƒT@ÁxêôG@¥oêõˆrÀ«•Ç_:Ùy@6 —»ÒIÀÔ¼šò¦aÀ~²¶¼Ìp@±ÆÿY…g@nŒJ¤”k?ð?å•€ì@_Bér @/ü^š–@Ûæ“ûµ#@·ü?µ/@ ñû–?À:¿oú À¸Ž´ŸÀ9-C]+ÀU6מäšX@¬ÌAÖ‚@\­‘Ÿ.Ê?J±CÀŒr@dtºM ñ¿@½éuÀ>ªÛž—+z@´³4ÅëJÀn™°5v0bÀ-e(E•ìp@¥8DZg@Ë Ü:D“?ð?—·$[Ú:@¬ÞÙNO‰6@A¿>N—@ÏÒš6M@ïRæé2@†E£&^;À™ä®5ë÷6À‘7ºF3À‰šì5ÖGÀ™:üj¤µ]@WšÞ¶­ê‚@´‘Vd°›æ?jÓ–4g©r@¦‡èV8Àôz…gÕ¹]Àª;ƒ¹‰C@ØX…ÈWVÀraÅŠ6@ùÉè¤Hr@á@0DÛKÀòˆÅÄR…TÀìòz§ºLÀ÷[gCÞ?à?€?t-eê…@WëÌŠ<Í‚@«¸{cS"K@ ½o±t°¡@aâ‡ÆW!€@k¾ÿi\†À= G /ƒÀÀ&:Cu€ÀËwªJkIÀ°Ûoðo•–@˜Ddù÷µpÀY>†ÏÄd@€ ÓPØíã?Œ©‰ê:cÀþ÷a Y=A@lgª¨q@`²·ôœgÀ>«R]K€j@ ªû‰d:ÀèsXSZ¾RÀŒÍ_"<±^@4õfÅ.ßW@);r÷~‘?à?ÜÂHŽ=99@¼c ÁÁ£5@TºÍª‡@«¸{cS"K@ö‡9…¢2@ÿ†3x¼9ÀùñW6ÀÕôº8ñ2ÀÆ#o¿ iÀJÙ{×À‡Q@:«Fs@‚ ÓPØíã?‘ÑÜ–Çb@tÐÔPÀ÷ÏèÕçõMÀkC6âd6@ÚƒCªDÀ€! ’)@N—Æ£’Wb@ì³Âç8>ÀD1„žBÀK÷xóõ<Àü½,uŸÞ?à?½¨ª¥†@–G{WNÞƒ@éæýµ'T@Ú"Àú¢@Bʂغn@3ç!‡ÀÜ¥AâK„À/fkßÎÀpi{?PÀÁåHnÝ–@T÷u^øqÀa‹ØÎ–ød@9×g¨+í?Äè‡y`ŸcÀ´¬0+^?@1tùê'Ì¿\BDÜEjÀúW®¢\×j@˜´ÛZ†¬:À»aÀ-ÉPSÀqç² X@qç² X@E椆¼Œ™?à?½âRëÖB@­æîÓè†@@¾ÆÌ^»Eˆ@éæýµ'T@^ò€h=@ŸÊÒnú=CÀå~Náâ@À7Vã$[ =ÀKJÂ…7À7 å†UT@í䌠s@:×g¨+í?÷”·æb@þ» ç¬i ÀæC>>}NNÀêk*»9@ó@ÍõBÀÇf¶iFÈ+@å9™àüfb@, ½ðS@À­²Å‹;1=À­²Å‹;1=ÀÕ‘òüî?ð?$ïh—@48_3N•@î}%ŽÝ°j@ÃÇ@¬>x²@P]#0Ý’@EOb%îð—Àæ|›í&~•À·ãѾxK“ÀÃOãpiôcÀ•ªGÒ'§@hŠb=äAƒÀæÍbS¦-u@« 4µ+†@ZÅ0v¬tÀP§í@ L@I™Œ–30ÀÎ9@l}À¯rlYÏ0{@ â1(×óJÀbz’ëçcÀèìñ ޳[@H¯Ó\=h@pŸûUçÚ°?ð?s%‰fjhY@u{Šü<ÏV@ý]p–í˜@î}%ŽÝ°j@&ÆÉåzT@ÿ€¥ËôüYÀ±©¹—–TWÀ¼žlgÌñTÀZæÎ–ºÀs*nEg@H>è‘Wøƒ@­ 4µ+†@›”¼Øs@ª?ÇÔ5À锇!êÄ^Àºu¤JM@ó÷EÌw”QÀžox'FŽ>@¦Æ•Öêvr@{6è[‚”QÀfg˜}PÐ@Àï´ÊÛŒlMÀf…ÛuœZß?à?®Y«‡è3ˆ@­Ùq§=†@3ÝöÊÇ`@gýíõQà¢@©‘Op„@ÁÂG@âɈÀ³hvâxdžÀÕVÉÂî„À Øap%ÖWÀ8ó!™¡t—@ßÂo½’tÀ¤§"¾öce@|Ö¦ùÉø?t@<sdÀHy¨Qjr8@dW£‰0ÀJ›øÿmÙoÀïy§£Œk@K‹u:;À[ýçƒTÀ/†_mX@Jc<ªŠý¤?à?3Ä×,P@ç&£çä¹M@F¿¤µ¢‰@3ÝöÊÇ`@Ÿ±àQK@ŸÆ\wÑPÀ(ŸîrNÀq•ÇþIúKÀFZNfëÀ£ ¾XZ@Tü#õNt@~Ö¦ùÉø?üía¿(c@+OÅ&3k+Àþ¶ú‹˜ZOÀ~e>”àE@@!²Â¡ªk@À:¼ ›Ç·0@é©Åc‡b@ð÷a–ÞBÀ(døÌú§=Àʃ;0{¿Û?à?ºÐ²M¹P@ìÂM{ey@³éu—RÀÊbxñò2ž@"t!QŸr@J½ü¹uŠÀ ۲ȹyÀd¾)iÝrÀ^ŠFŸ´1@'_þÜÀ”@Ô€VÚd¾cÀD£¬”@c@οŠm´oã¿"ªÍÑqv`Àv4a¼dK@'™{{ëM@TfÐf¦TÀE.h2 h@àyh%I¨7ÀB‰àbL¸MÀœl0ó¡I@7F‡O ‘™¿à?çïƒû@À«TÌÒ*z7ÀB–¾ÌO„@³éu—RÀ‰¼dN71Àï—ÒJ[7@@€`8sÈ7@kÎ϶p1@£ «ö±ÑŒÀTb ×^0@÷ÍÛ+wŽp@οŠm´oã¿FÈAö½Òa@t{^w @@ÑŽÑ&éPÀÇŒéá©j@ºe–½=.SÀº q?Ø’@Ÿ‰Ó²a@¾[#€1À“_v/ÀÁzsÖì?ð?“ƒ÷ב@o³±T¯Š@/Ct>^ÀZÀ‘ÍTòÓ®@›13õôƒ@43®’À(À¾ ‹À€nsz­:„À¨î¦ø©­-@ÑðpBø¤@j¿ÎzêuÀ»ížjs@®»Å?·½ë¿—ž¾×!ÇpÀ 3΄›Z@Ûª=¦V8Z@ð U+ôøhÀJ†Ú+Ox@2‰Y_¿ïGÀ€e†±4Ÿ^À•¨+EÎY@˜¨+EÎY@iQ$ì1¢¿ð?á5ó,=GÀA©ôÈt`AÀJ* †¤”@/Ct>^ÀZÀ;L›ü9Àu=HeG@þ²‘ˆïA@Ö_sbŒX:@ÍMGÏÞœÀVqBŒH@êGeLDí€@°»Å?·½ë¿{(Ljìq@öà¯+ª%@˜«ka›Ð`Àÿ`rW3@´Ø³féaÀÖ2"ÄË´+@çJsÒ>¿q@ÖÖ,dÖ‚CÀ¬Ü¨•nC?À¯Ü¨•nC?ÀèÂÝScÌ?Ð?œþ¦Ü«er@\ê–Æl@ÿ8@÷/À¤˜Žµ|y@°(8Øie@N}ºFªrÀà óœ/{lÀ[õögBºeÀà!¨z’æú¿£á1¶^2…@)G¹`Ã!XÀpÀIsÝ•S@•Eae‚_¿¿Þkݯ*QÀu!™ïŸ9@÷ÎÖ…N€6@„^àelMÀpX“q0—X@À2…î6(À‚_8 ?À«)]C¼F@½U³ºû9@[-óªKa@›Eae‚_¿¿iîÍóR@´ßH±ù?BÝAOOÃ@ÀcW³R<@e\͸@À¶Ì4Ûªü@ÿËÿqÌQ@,†“’%À~Î°Ž•+À*Ù¢îY†À ¯Eaþ¶Ü?à?›#ÿú‚@ÔµAè2Ž}@ø²Œz#ÀoøX× @Kñ5òów@˜…PÂEƒÀ²ÇËw ~ÀUšªB·_wÀ´ø6îìS-ÀÝi?1n•@ȹk¶©djÀƒ@Y®XÂc@äU¸/m:¥¿Š7¿ä£oaÀVC(H@€7R¶ÂB@<Œ#k aÀ+i-Oáh@§½´‰À}8ÀÇîbAPÀœl|Ÿo]@‹`àT*J@<`îȹti¿à?I Äí—@À°àÓ•Þ À4IüÜm…@ø²Œz#Àeî}ìÀv“Ýõ`…@ ëy¶I @Êú°Zê?@©ð›ÀßÎOE@4áÚÏ—§q@ãU¸/m:¥¿C:U?Ÿ b@ìÌcrAî?Y[vOºÁPÀR^íwe-@),ðcï8OÀg"‰ß96"@rç½ÖÙa@´Þæõ¯7ÀVA9$,áAÀF;‚2É/ÀêÕHaá í?ð?º§m•“@ÍBŒ{&@,ø?Ôb:@"WæWRi°@ËðEƈ@X»ybkè“ÀQU…Ž]ªÀlôž2þ.‰ÀÔ…1É‚JÀè±¢?$¬¥@0{T˜³|ÀS¸ðs@qglh[ÓÖ?š;¥ÇqÀÚ7à@ |•d´z@ ÿ‡Õ“„À£#÷2¸€ÀQÿ‡Ñv,{Àƒô{ÁuCÀP€mVFì•@ŒÞüoÀ©!ÙFd@))äDÙÚ?¦ÓK¥E"bÀÀê'F@e{±Al6@‚ÜïçåÌeÀV»¥|i@ý- ®ù 9À7:>´AQÀz LØ–`@,­óŠJ@cõBòîaˆ?à?ljN>Ú«0@ËŒÍe+@rVÒ»Èc†@iÂy”lB@’º¯Q¿&@Ìòù£Ïö0Àæ…â¯9’+À³7k¡¿g&Àþ OÛ7À$Y sò¸N@Ã}]r@*)äDÙÚ?ËHcLXb@õþý AÀp³)îºãPÀˆA'/‚E4@)°NÃÖMKÀ׿>úå&@×cÅê„ôa@N£ÿ­O<ÀýVŸ!1DÀ™EL±M'0À'ÒÚc€¹í?ð?­Î;Vâ”@ì(ÍjY‘@77 7Ÿ^@ÄŠ¾©±@~ð‘œSÓŒ@m~p©F•Àv—»C¬‘ÀïÊ Ôù\ÀpGUöYÀÕ¦6¥.¦@ˆ—-¡»€À¸$Y\Ot@îJm^Ÿmõ?n±˜œrÀ„–R¦›ÎT@FP%°a›=@-e`OxÀ¶0gÎÌy@Û‡¢Ú:OIÀÄWSUÈaÀtÇn@“[Ûñ¼Z@$>Vt¤?ð?§ýf˜ÃL@O2ì5]HG@c¬ÊGð–@77 7Ÿ^@ªU°mƒWC@¼ltù˜ŒLÀwþý‚‹·GÀÖIò3à³CÀLIÈÅBYÀ³b)”‹óa@R¦ͳµ‚@îJm^Ÿmõ?#Ç‚Õdur@ä&JGÿ(À}îË>haÀYºj,nEG@\}ƒ¸ ŸYÀbcØGë_9@I§ÊÛr@2º3Õ­`NÀq¥ÙÛ©QRÀ‚¯Oü–H@À2º> Uî?ð?X+zO”•@J%Ôv®U’@ ™¿:t™e@G&˜ä¤~±@]ëõiä'@§]ñc¿–À nKª²’À¿…ÚåÅÀ8¯Úà c`Àb¸Ls¦@?¼šylöÀ¬¶7ïê€t@¡Þü—€*þ?FKgÀßrÀŒ/•TP[S@¸Þ Kf‹,@ÆZÜ–ãåzÀ[ø^5Ôz@Ͱ_ Ô“IÀshÃ#ÌRbÀ®—N’g@]õ>5ðZ@JÆÏÛró«?ð?ž9ŠT@£YóbÿP@4ïól눗@ ™¿:t™e@ø^–³áL@yÙ„fTÀ¥©O¯DUQÀj w,tMÀsf$ÆxÀëvä*ªd@Y…Mä ƒ@£Þü—€*þ?ób¹c“r@?<Ä®·”1ÀÂc2,ý:aÀ´ÒàÖòjJ@ZC†o"XÀ´±öñ;@òhz¹¨r@ª‚EÀ]PÀ†Í~;¹LÀ—¾ÚœØi@ÀDmKº“lî?ð?ŸÇQZN–@HÅ*Xd“@ ´žl@ôy!“?à±@ùžÚªËÛ@b%Þ{Æ–À|ãÈÌ“ÀÖ¼¸–6‘ÀÕFÅC-ôcÀØOÈ¢Gº¦@gh¿8ƒÀ$k «¾³t@ëtŸ%BÂ@,IÅBsÀÒ’ÓIÌQ@ÀÈïº9Œò¿Î®Wi5‘}À ³aH*uz@ªËñ¹×IÀ®pdÈìábÀÏßm*$[@Ïßm*$[@çJ;Úâý±?ð?X8j„+TZ@!3öŸãV@¢ÁÏ.˜@ ´žl@ŒF<‡æS@ô²:÷áZÀ£¾må^WÀÁ†ÏHHQTÀiMï´·ªÀWéÕšg@ûµzâ€bƒ@ìtŸ%BÂ@O\U²r@æ©GÅ;Ñ6Àpæ |aÀà°¸£·M@ÿQH¾iÚVÀàm$>@tCÎò r@\Š•È“QÀåƒU‹@ÀåƒU‹@ÀP2TIÈî?ð?»ºÕ¿—@<|Í·†”@ƒozÚ¾aq@Oß-JŠD²@.iÿ>D’@71¥”—Àðäü”ÀCiÈ4³¬’ÀŽIMKA°gÀí*‹ž§@T nÓ€„ÀöÄ|Óçt@ÇNâÀ'À@—9¨sÀÔv># P@Ìí¶l °0ÀûCÿ )€À|ZTUÔÌz@‘Î2áJÀEæÕë¥ucÀbL… OY[@œ3¹¤¶?ð?œâ `@Ÿô¶Ó_]@èe‡ø à˜@ƒozÚ¾aq@gžîþ#Z@ЦB¤gß`À1YäÈË^À–í»Ðy¹ZÀN¬ÿ’<ÛÀ>÷Úò{j@/£7Öp¶ƒ@ÇNâÀ'À@âænAFÒr@èöPØ÷6<ÀB6*ëuÌaÀ>1ÿ@t•P@g=Ý~ÉUÀâ+ˆÁ9±@@@$i1Á0r@uy_ØÒRÀ<6Ì^¬@ÀR‹w¼$HÛ?à? l‹ÿ‚€@¥ãfrw@B`X·PÀ¨RëÊWB@EãP빦p@b™ë—г€À:Ë(Œ¹wÀe`G-ñØpÀ:üx˜,@)Eçp”@e|\uòdÀ´– DƒÜb@a íeÃß¿=¯65¬À_À*¨†b|vN@ Rh¤Ë¬VÀ}ä¹8Èsg@‰Í¦ض6Àç´g}6LÀ^—áÛ¨w–¿à?f<ÉùI;Àx›^;a3ÀS÷ú¥ƒ@B`X·PÀŽb¹´¢†+Ào‚¥Eœ;@JÖ⬛3@ýNç¥Ù+@b=i2ÀŒÀ°l5&3@^öZyÞp@a íeÃß¿K£z2‰a@“>/@P.@ºú»RÀ_öÀu= @îœbY'MUÀFªòEû@\ #…sda@0U¥ 2ÀŒ;žœX—Ë?Ð?d»O£q@¤Šfõ£h@Xµcòd 6ÀÂ/`ÔÝ@¬ò|F>Øa@|Z­9qÀ÷÷®qóhÀ"hšp|bÀ|ÿ{@(:ÿ¥„@LUm›C8VÀsýK¦S@ÉoážêKÅ¿T7ê-PÀ,á5¢=@0ã$É‚I=@Š;;ÖäJÀ–Ŧ¶w¶W@7XiAû&À®!Z=À%ÈAëR9@?qÔìIc~¿Ð?"SyùÕ"À[¡^-HÀwŠÂZ|ùs@Xµcòd 6Àh å_öÁÀø‹ée#@AÍr±Ÿ@ÑÃzW@ègÍ|ÀzáxCÿ}+@I0Cún`@ÉoážêKÅ¿èÇ/ ¡¡Q@¾]V`!¼@ïJ¥ «BÀBöÞÉÚ@ùiz½äDÀÚßÖã¯ø @•6lkpQ@>G¤ø#À­ÛœÇÀÿÆUiŸçË?Ð?ÓÉjóVŠq@¦@,·çëi@¤;2Ž'Àë‰/V­}Ž@Q™T'c@,FßQ4ÆqÀéiªÒ_DjÀÁù5s³hcÀ0]˜TLÀ§ìKwÝ„@]‡WcXÀp'²Rò-S@î9.è@賿;Adþ{PÀû‚~Fй<@ ș芣9@”ùjtK8Í`À²J=fó¼K@-}á^øE@—<†xÚaÀD£](¹Ah@Dõ†ƒ7ÀÊÚ§«ÛNÀA>¦[sà\@úåH=R9¿à?ÉmèW¿2ÀøMj±îâ,ÀHSU¢#A&Àâó§üþ Àpø S±×Z@ Š0r¯|@CÒµ„'ß? n·Ôôîq@~ë$ƒFÀFÑe¼bÀuoØ!!B@”JÀð`Àš‰¶è4@±´¢ïN–q@œTo„’ JÀFÞž·SÀ]ͪ>OßÌ?Ð?qø ~Gs@ãŠ0wàZn@"$|ÞQ6@¼Ëè÷6<@ƒ¼=)”åg@û‚ˆWË–sÀ‚èóŸ¼×nÀ8[®ÃßGhÀÀäü&4Àµ ^Ž…@·>”ÿ )_Àƒ7¼Â ±S@% Ø/ßÍ?H‹ìdêvQÀ±£[_;9@@œM`#-@ŒÂ6×ñ†VÀûU“ 5ÕX@â±¶> (À®´­1a@À¡ÀêÊDP@8>vW$‚}?Ð?V—åøÙš#@îF¾ïÞ@¸ªç™‰´u@"$|ÞQ6@Ø|'çL@ZgŽ&~ë#À° ö]À€ÐƒÃÛ°À¼›×ê)}Àª³=<ס?@®ÞÕ Ôa@% Ø/ßÍ?xY{a5 R@{è‡LŒìÀ#) ÚBÀmS¿®J÷$@¼Î9 @ÀÖs²Oj5@ßõŒ/­£Q@‹Ÿ1±I,ÀWBáÒ’à3Àêh³M4Í?Ð?”ë?Wàés@f¥¤çäp@Ê¡å$fñ@@Wé`Ïc•@´º†7Ìi@=u¯ó AtÀÅ_ MpÀ‘[ %=jÀÖÚZYj:Àî1›c\Í…@ÛNÀ¤Á`Àùù;A2ßS@byY› Ö?OdzÏQÀ ×.$5@8@ŒÍˆ¸«%@…Š‚•øXÀY*"Y@36ƒ³5K(À˜"Òâ—à@ÀD5s•~M@3Þ@;µw†?Ð?9L:†Š.@ëÖ¹s‰”(@¥†­«*?v@Ê¡å$fñ@@©DÊbÈ#@Qì7/Àyœ")ÀÒNMÌû$À»li…«J}ÀM]Æ SB@F å1*b@byY› Ö?Ëb×E&R@˜»—DLz ÀD òCÀ²#{´Hñ'@Û¸<,j‰>À96輦@S›t±Q@C§¸.À˦ȃ2ÀPšÒ—ŠÝ?à?‘´Q§²“„@ä€èÌ6ð€@u.@ÔW@â‘ñ @bÇ»Pãâ{@?HÚ‹ó„ÀÌÎþ?ÀànœÈd|À³ñFtº|PÀm-›Ñ–@½=å0!õqÀü:ûPšd@Õ8Á¢ãî?ÔSž=Ý*bÀ2HiÄ.æF@ðî <ÒP,@Ü)“òu}kÀú`ÍRqi@|rF¤Œ8Àt÷ÏûdQÀV¤Üf—W@´,÷Fž?à?î—0)H E@Ï.N5ÔQA@¤6p•Õ†@u.@ÔW@Z±Ph˜ƒ<@±íîºIlEÀˆ†L4¢AÀ°vEIj=À-jpãpÀmß:âóT@\Š›4Î~r@×8Á¢ãî?Ïêí‹/Cb@Ų´4ܧ"À¼¢˜]k=SÀµœº¦;@‡Y@ޱ%MÀ–=0”½,@Þ¾ñ«¿a@,µ°d@ÀÞZžhF<ÀT«µ7âÝ?à?VTг9E…@±ðüˆê@J”s`]@?îa(O¡@ÿÛƒ.~@âPµ§£®…À_]SC‚ÀÞOHÄ~À¦ª‹ ÇëSÀ”nj †R–@Ü$©¥;/sÀ½äÏ2B?d@œntpnÞó?À<æˆbÀže7QçqE@äz=•e@UÉ`RnÀò¹ï¸Âi@^vn:WÍ8ÀÈNÄ¡ëQÀöbpâÈšJ@ÚdÒУ?à? ¿[—t!K@ƒ_S/ÚF@“\ x‡@J”s`]@ÅP®S¢?C@©Â>†é§KÀi)7pKGÀN‹Q'ŸCÀùùîúû›À]Z²“³W@멯XÝÑr@œntpnÞó?âR¥ab@vCé3¸'ÀÑÎÓù„SÀÊHXkT>@=´W?õKÀ:~Ôe£.@*a3ZÎa@Þs³AÀ•û¡’ÞH0ÀÝîë<<;Þ?à?ÙÆÝØºþ…@oî÷‚@žûó"ða@ä<ÃÔÞ¯¡@$­x CZ€@ׯ½2®r†ÀN[?c [ƒÀ×Ú£w°€Àže¶÷ƒWÀ£Ô Åƒ˜–@ÃÒçI)ptÀP‚Ù(qd@š`Oir™ø?_òÊ¿ébÀ„¶C âC@à#&{ªð¿·^PöapÀ7À»I`j@ͦþfÀ¬ÿ»ê?š™™™™™é?rê!¶qú @8=-¼¯@ÁPú ‘¤@gºMn|V´@Àÿx”„¨½@wtÏ_B ¢À>®ܰÀõ!uUƒ¿Àt…x.$`@&üxp‚*ÀÚ"ôNÌ]À½ ÒÙ˜ê?š™™™™™é? ÿ+³_¡@34Ò\­<°@~€ÇÂÏ´@ÅH&œÕ‘¤@ ËGèdY¾@wì~ÊØu¢À²1rðŸ@±À§*‡¿¢ÀÀ¿ ]î*À°rFgÀ`@ÕHû£5f^À6l–=ø?ÍÌÌÌÌÌì?NÃí `¨@ÒEÅš»xÏ@ê…ICôº@ú§ÑVXIÔ@EwC™(Qô@P›â¤À¯‰C¸wÊÀW½ß-ñÀSÜ¥¢E°ƒ@‘±|@"v}†Wù“ÀÃVEœ¿E@¨¶ ³PÀ¹Ó¢C\]0ÀÖ3bE@¥«-Ìr‚PÀ’:õ×–â)@{Cd"tê?ÍÌÌÌÌÌì?zžG` ¹š@È [@Á@ÔÂìUÙ_Ç@ê…ICôº@HU¿Fæ@ªéÏTy–ÀO̰ƒQ½ÀíFÓ£y»âÀ§Ær=˜ÀÔí?iâdÀ“گߠ@¨¶ ³PÀ?YkÖ`_@ñKî‘'¦!À)î JÜGÀØÎmþ^^@ïØÛ2KÀ+DäP(5õ?ÍÌÌÌÌÌô?DQ«@|[âº@ˆV²ŒÚȰ@ûè#­£›À@I¥t1¡lÈ@-Ž#Áot­ÀbmãUW¥»À+ίòÉÀ@\‰•}‡h@hX¡÷[ùÀßÝ ·¦fÀõž?£õ?ÍÌÌÌÌÌô?öNC?T¬@ž®¯Ù–º@Ñ|þ:øÀ@a»oãɰ@‹dßÎôÈ@À÷k¡©®ÀAÖs6{?¼ÀÒ*¸A\ƒÊÀö²2¤ùÀŠðM‡kh@"+ÌæÏgÀ"Òð€+@ÍÌÌÌÌÌü?¢²·±[¸@OõDËdß@ó1h†¿Ë@¶Ýó-ä@ûtŠ7:A¼žbŸï€´À:ÀwalÚÀk/“¢­Áòòð±¡ü“@¢K @òæŒ@L†ÄeE¤ÀçP$FÄT@•xÖTW^À4@ÃÙ~‚>À”zò¹T@V&•C_ÀE©|æ:9@pöÇ1•Ðú?ÍÌÌÌÌÌü?æÏo «@¹{+›kÑ@ ÿ=£x×@ó1h†¿Ë@0¨ä(sö@da¯úÎÁ¦Àdü‚ÎSÍÀ)½fµåòÀül˜Kr;¨À½©\±³HuÀÒ9¯eñ°@¡xÖTW^À˜#Oº]m@Ìò‚ ¥0ÀqôžØ,ªVÀ‚´™l¬kl@=KË&ŠYÀmrcal-2.4.1/test/data/test-optimizer-callback-ref-J-5.npy000066400000000000000000013574501456301662300231150ustar00rootroot00000000000000“NUMPYv{'descr': '÷šÀ ÀFד˜šÀr¨û5;šÀ±8årjt@C³R §@”Ô#%î.@*';ïõz@õÿU¨¶%ÀAš¼…SyÀ"ÿÊ™¡ÒÀØ•éšëI@KÙ2o¿EÀ‰YèybÕ€@ÂúB Š{TÀZðÙŽcmiÀrwcÀc((N>—οð?@7pÓÄ:yÀq§´ü2âxÀ¶r Ìž@)—¦BаˆÀ”-¥ØŠxÀÉx¦óóy@žF·×˜y@üS û>y@<Õ-t<žÀÄÚ¿¼ÌiÀVêø­@õÿU¨¶%ÀP‘Qr Yw@´ªÁÀlQX@ƒÀHj&Q @œž.Û=À¢ºk'‚Ü\@BÌW\)»6À6qå˜<x@^º4@.ÝØæc2@E^ÒhMhÐ?Ð?Gj©>VI|@2²nPX}@á/,3Û'iÀÄÇ{ÓÈ­”@0Ò±ƒnq~@v—|Ê82}Àcû5õéI~ÀX²lÀx¶âçs§T@X6÷´ì߇@àގΛÞ?‡&?"—Z@RÕ›0ÅÀx!½« ‹ZÀ”0 ‘% ø¿¼ŸŠ«©˜2@ÁzpØ'.À¤ß"`¢Na@Ø“kL|5À¶V¾¤å7KÀ¢BÕ>´ÜFÀ̧¥žto®¿Ð?Èêéÿ‚EZÀ˜4¶/A[Àˆ•ر;w@á/,3Û'iÀ ^gGF\ÀÐ.жÎ[@ñ)î{“!\@ÓþÅ/]@Qãµ:;p~ÀaȸE=JÀ€*Eq c@UÕ›0ÅÀú“î¼W W@!.©5L˜8@¶QMD}·ò?lUñ!D-ÀXÕ©¥¨xC@ó¾éÁ•YÀ“ÐYpXX@ k>üÅ@{ åFu@Ÿ ÐxêÐ?Ð?X‰¸›Â}~@—Hû«¡€@sAÓIžiÀÁ&ÝŽË•@»úC·$‚@diÜüÉ•À†ïq j:À—õèWË‚À¹ÄPè†7U@¼ù§ªÀˆ@D}I§ŠÛÀ¡Iƒfï[@\]¢Ò˹Àäçc‰Ð[À€4‰ø‡Àô“ø8@‚ ñÒÿ–3Àù5×’Ëa@à> hƒ6À…2ÿºÖMÀ‰Ù2_f™HÀékÛ—ÈG®¿Ð?¡Á½rlT[ÀnþÃ(oÐ]Àñu5¬q€@sAÓIžiÀÞ•óu!C`À@\žôjO\@s`Ÿº>â^@¦ÄœD{Ø`@òÙôÕ¥~À(H&¨ZaKÀ2#AÓpd@Z]¢Ò˹ÀΛïéW@ð3~çFÞ8@†¯æ ø? ‡ávã9ÀR‰s¸¢H@:IŠ4èÀr ;Òð£X@xLˆùöÌ@bƒ"ûx@]§EÊmpÑ?Ð?ÐÞ¤6xj€@¼=?‰’Ó‚@ôpñ½jÀ&j½4Pö–@ªƒ™ÚJ—…@. ௽À¬éÿ h“ƒÀNV½Ks†ÀZÂþ¾U@×´R µ«‰@8â–-JÀoÑ>¸à©[@;žôƒ‹À"ÿíç!!]ÀôÂ){»™À"ðc²’@@„t$8j8À•RlÜMKb@9‚`òŽ7À^dp OÀ×£¦ü£ÅGÀw š½ ®¿Ð?çæof\À¢îbKI`À¥Åž0@ôpñ½jÀ†1\7­bÀî.é¹Ò‡]@”úöî`@"¯~†kc@8l›á Ý~Àû"` fyLÀÎ@CÉ‚àe@:žôƒ‹ÀD1ß5X@Œ²yû×!9@¡H%—¤ý? 0›Ÿ>À ÿUöíM@Æ ˜`Àõòv¥ñX@¾µxŸË@ùáz]h@÷ìòT@úá?à?L²W#±§‘@ϨûÇG•@ æ…²ˆzÀÑ Âu¢.¨@È1<†q¦™@o½Iá;n’À㬫77–ÀbiýAåÆšÀªëʰ´:f@ŽE›„¶Ÿš@wP÷|¶5À²ø]63l@g; ðþ/ÀȾ°©{nÀD¯x[¨ŸÀqæÅŠô T@Äÿ1 MÀ/‹ª€žÌr@(úLHÀ±_UŠ`À,F‚¦KÏSÀfôŸ ø½¿à?©Uí;zmÀÛÇ÷æÃqÀz7ºš÷‘@ æ…²ˆzÀ__ÕÖÇiuÀŒýµºÅn@÷²9…®‹r@oèšÝ•Zv@Ò(€GéÀ}²Ÿ-¹]ÀKcεYw@f; ðþ/ÀD`„„h@G1ŸaI@íÒÃäÂ@8Ž,R1À&xð­a@Φ,ï0»(À:” ÿfAi@½´Ú[½$@äíÜg@]*?@ú‡Ò?Ð?&^%E–ö‚@‚ èÒnˆ@%”–sMûjÀŒ Ðu™@׋»pkŽ@*V¼¹±àƒÀųX:ï,‰À§Ékè£âÀº@¶ô¦V@ÈóÕš½š‹@I°h²¨þ-Àñw+Ðî¸\@q€"› Àx¥¯ —Ý_À.#£(À‘]8†ÔtH@q«,g~AÀŽ­tiéMc@m°´½¥9À=´uÿ,–QÀSéº38ÀV_ɀϭ¿Ð?F6ÑC5Ž^ÀO_ç~YcÀäå‹?}È‚@%”–sMûjÀÄÌ“è²hÀôÞ{¶`@\•^Hd@qðóÂ=°i@Qó yêOÀÔ8 zmNÀŠK|‰Üh@t€"› ÀWto¾rÔX@HâuüÔ™9@p¡k‡w×@p` ®ÝÀ<%/3€tT@Ô0v9ïÀÕÏénü’Y@8'Í!ˆœ@èX?8@pg˜Ó?Ð?¥ØëV„@QYžÇ‹@ûô®©/mkÀMÿ‹kÊš@â8 Q°’@Gy÷òi…À'l¢ÞŽ|ŒÀ^jôL[ó’À¬!uJvÿV@Ì2¤ôšŒ@qVªîJI3ÀåEË‹8]@½?¥\ÝÀ À<ØÖD¶¡`ÀiB&šÀË]9ûKM@šœ‰ÀYDÀÃå(×Íc@$ް$«:Àœ…Õ£¨RÀ(P'‰ ¦­¿Ð?l–éÃl _À4bˆ eÀØÆú,£ƒ@ûô®©/mkÀ6N7þkÀ}g^¥`@åÇ7»%f@Ü[O‘Œwm@¨àúÊŠÀ Á5Š:OÀ+sqij@»?¥\ÝÀ À—H™Ç&Y@‘ó8BÉ9@ó ȸ@öòRJÐÀᜠÄ:MW@Œ>\¬òÀvŸêæY@lWFYb@m³8ÍIÊì?ð?Ï;sÒ”@'›*kž@ñÚÐtå#…ÀÑg3º´d°@nnxÙt‹@Ayîi}”ÀÚ¶fŒìÀi¬£õ‹ÀëéYp@Ær :n›¤@îuÇ×!@Ï*Õ…bx@§Ë'Ó& Àiò÷X uÀ–ßrÂ-ÀŒž–ò#Ü¿¬úPÎŒ8HÀ® @rž¶~@—'?…º&QÀɯuŒYdÀ:9\— JÀý·ç+`Ì¿ð?ù?™dÆÚsÀ~á½6fpÀ€!¶¬U™@ñÚÐtå#…ÀTm0kÀW2Íö8t@pBA½O³p@AÃÓ[Œ–k@ב–Úý^ÀBUe5—zbÀå-CHÎ,{@ªË'Ó& Àõô«;Ýhv@ÎsqÖ>KU@˜ùðáÜï?8z_H‹ª´?Ü™dÿ Àm|©¯[†0ÀYbA©w@¨[ŸA«Æ*@ö¸/ø˜@­ZTuc°Ý?à? šÚ´þÈ…@àË'dô‚@?8F¼(ŠuÀÓ«3~P¡@gt,cb}€@ZRôŒ>†À@º“ßYZƒÀÌí‘]Ö€Àî’—œ`@o=q­J•@1SgR–ø¿úÁ³6ˆÙh@ÐA’b:ÀUû¡¤ªfÀ)ùçÊÁÚ ÀÚ•4>*ñ@7R–Psn?ÀÆo¡‰o@tlF¶3BÀlKÄG™UÀåðÝÉçF<ÀåðÝÉçF<À<ã–¿/¼¿à??ÏÇ’lµdÀuø{SbÀ¥sÚ›Š@?8F¼(ŠuÀà˜Y_Àµ§œwSÀz†lc6®m@ÑA’b:À…æÍϧf@øºìÍeE@âÕ´Fºð?ø]d9A–ã¿öNÙA1@rãƒ!À˜¾[S@g@g—@±¬M˜Z@±¬M˜Z@¶zèœÎ?Ð?v´Ã÷ûw@ö×UeÕ–u@Bæy<ïeÀ ŒW·G’@õˆÅ%Çs@Zðh»ç!xÀ ‘´—˜vÀ ud‰Å@tÀõ¦¿ö¨Q@_.‚Ž–†@Ð×}ÆW¨ÀZ‚0ÑUY@I1[ÕHÀ…oÛÜwÂWÀ ÖdrÀÈìu©:·@ Ëè_¢™3Àp«l§U3`@&CŒ¿ð2ÀíBíè>1GÀ@@ˆoÍ:À’’R6¶¡.ÀŽŽwtÿ«¿Ð?#LÖlå”UÀ¿—Wi_ÅSÀ|È!¶Ñ·{@Bæy<ïeÀ_PëϼRÀ©Ã=µœV@‹Cô>T@L?Ä_ŒR@Bæ~º}À)cÆõtDÀD-áú’`@I1[ÕHÀÚmÑz éV@/4~×µ5@UÙ€€è?,#þcÚüã¿¸ÒÆ2@ÎoAGÀ»ÅŸÝ‚W@¨-¢51< @fqŽ¢y@u8~wKõ?Áè­%Ï?Ð?ëÍ)ê.xy@?Ù,„x@_]_•SfÀX~y—èH“@4á&¯w@}Gz‚)zÀn|xÖƒ:yÀ´¹2r TxÀœZcä—”Q@ÆvØ[N̆@êþÅFs]ÀÏýƒNåÖY@®¹Þ~MÀŽ¿µ»üçXÀäˆ8 óJÀl¡% /ý(@)â!+TÇ7ÀÏuÇæ°¦`@½£ëâ3ÀûÌWú"ÞHÀêÁbëÚŸBÀ%­íŽ0Àö´V6:Ï«¿Ð?x¸±xVÀ%L£vi«UÀ¢%"îþ|@_]_•SfÀéÙiuåTÀOÒ\%W@‹6‡IHBV@ˆ˜®¸ñvU@Ú³ê}ÀÑmðHœpEÀò2VÝ,pa@­¹Þ~MÀϤŚ ,W@U»ù·»ë5@L7ÑËš»ð?¨”‹îí¿Å¦bÃÕ;@R£ß0X"ÀÌÅ`¦ÂÇW@Чô¸=õ @[Öêz@hmG¢ ßô?¢ÔŽ3EÐ?Ð?Zü©þã{@•K·‹µç{@`]/\oµfÀÎ?â§{V”@¹úo Q|@_{áXW|ÀqDôVÂ|ÀÕš×é.}Àl M R@YŒ’=Åž‡@U5)µŸÚ%À’hþÂ\Z@:´ÆÉBÀAÿ£ŒZÀö¡Ë>xiÀ@…bžü1@Ðc)—C<ÀÌüù“Œa@ôáÔùÜ4Ào{²Û¤ JÀr!†drRFÀ[´Ñ¶ŽÛ1À ·ÇŽúž«¿Ð?¬ú]-`WÀËz6Nm¸WÀ$ £•U~@`]/\oµfÀ]§QiúXÀñEARX@FãjsErX@]®¾+ÎX@m%~Àj©RµûgFÀá¯U/DÉb@8´ÆÉBÀ—‡ ›rW@»è@"6@BÝ/tõ?4pcØËó¿êõ›ãB@ã%¨ÌÀ[ŠX@è."D¨ @!æÕÄaÄ @´QÞô?/}¥ øÅð?ð?[mÏÛA©@,6п©Ÿ@Ê)fW‡À:µ‘×4X@Üsyÿkˆ`ÀÐ1S_š@Í¡óþÌÝUÀ|yRÞÈxlÀm¤í²hÀ$Pñ[9SÀ:ß7—nË¿ð?ó¿¹ÍJxÀ‰xEîyÀi" v¼Ÿ@Ê)fW‡Àü.(øN®{ÀØâ¯Ây@݃š”Ñz@Tµ™õ |@0à “QžÀ‚ÀŸÚ×WgÀ>u7.+„@LìOè)"%ÀÏõÐê»w@TÔ‚bXV@Ë ‹l@PÈ$ quÀĺ7d9úg@OŒ8@ 3ÀèØ¾,ŸXx@SBÃ=P)@`•ÀOóh)@æÝfÙõS@ã‰êãJá?à?bÃy8õ@ŽHçìWð‘@-Ïñw¡uwÀl óké–¦@‚¹ËÚ#”@v‚¥'w–À©£PŸ’À䔟œ è”À[›qtäb@Bþ¾×>e™@'á䈵BÀ¨Îº|]nk@\¥@üãÀAWƒ Õ§lÀh¯.”ÂB0À£v»]w0O@nXÌ!SÀ5CÕ_r@û"¹ÒãFÀv€Uef^ÀÞ1˜ k@¡éLEãp@‡ÕKà$úr@V%Ž>쿎Àœ«À)YÀfÍÕR™ w@#ÅwÀ=*O'þRh@S@ÕǼF@œ„øÈ•Œ@ØyUÚš‡Àñ7<“XDa@ù½uB¥#À×D%Œòh@hª d@åhŽLÈ%@OSÇéä˜@P‡=o(_Ò?Ð?¡ßóŽ{‚@îö²È?î†@¾ ÞäØ.hÀ$KÙA ™@eáÓÊùrŒ@S©)WƒÀî[j´þ‡À½fŠÿÄÀQ˜©úS@­üªŽuQ‹@–¥aLC;À5éíâ!€\@±!p ¤êÀÀÉ|uÀ^_À@Ô!5ül$ÀàãþÄÐG@¥Í’r°HÀ·s‘.c@tMÙÝGö8À›ã-ófm@#—4Ì*s@BWŒGüx@è¤y'4ÀÝ®MÙ~nZÀÝ]öz@hËÏ\ZÀ87Bôh@”Û/yG@Ø<º¥½^@œÞêãÀPN(®AÎf@N+º¿¸#ÀË N Z”i@ø·³Fžê@ͧ+8v{@†UÿõÀÌ?Ð?Öæz{ÿ†s@Œ•n‚u„o@ߨ:IJ cÀ’'·£û@ –¡ØNoi@Ä{.åÝsÀºþ»pÀ­Ð(g}ßiÀ$ cL@Ö§¸i„@]© !| ÀÉ4‡‰Ô.X@˜ &iü¿û˜’tÄGUÀ>£žL[WÀ|!šOA7ο0{A+ú7À¸Î"f^@~Øi#Vª0ÀØèíg8£CÀ~ñÑ76ÀÄ‘ër¸©¿Ð?5Žçe›QÀTïÒ^kLÀÕ}«PZx@ߨ:IJ cÀš'RìüîFÀ½ôSéQ@OÅHHYèL@zON#TG@'éü}À‡-:Ô€?Àcµy’RÅZ@— &iü¿4$-BV@ÑÈ‚É$3@P£s dKÆ?ØPZ"–?¾o翉 ø¿ Ät…?þÀÆ|•ÿÁV@Ðõ7Ñöˆù?¡Ó88ó?Ob:sÝ?à?¥‰'!â'…@²ÐHaþ@QÈa“;asÀsäÒ=¡¡@Pµõ±š~@Bè&ês“…Àó¹â‘ŽY‚ÀŠò¥„N6ÀŸ²‘ä\@„u¶8 •@ʾ=Ô6ÀïïT÷¤h@‡¹ûa=QÀ?ö'NMfÀ¤:‹ÑÉ/Àu‰ä4~@:Ô;´ÔKÀÃ*Í–5o@®RÚÒMƒAÀŽ¿¦ôUÀ@ í†Í”;À8ìÖ3"HÀ[œžnž€¹¿à?däÒfèWbÀƒ2on€3_À± 6¿t€‰@QÈa“;asÀ-{+‰ZÀ»_ó_-µb@’m}ô%Ò_@Ë\Ô[@°5˜yOEÀµ ËÈ[PÀ'Oñu?m@ˆ¹ûa=QÀíÅ]îÉf@øyê’EJC@hñÖìÅ”é?ÀfOAíпl^Bº§.@¦)60hÐÀf½6pÿf@ȷϸN@ÇIµ`Ìô?ÎûŸžÔ2@h((Ž]Þ?à?æÛ ­(æ†@‹™E6„„@ʓڨ ³sÀµ÷$éù¡@Òpºa‚@ˆTõ\k‡À§r¬{Žû„ÀÀ´ì§Ì‚À4aÇG¤]@9ƞ̕@ö—žú*=Àø´”¡i@Îô˜Í;À¿|1¯_gÀ›ºØÃJÃ1ÀÌjW-@ÒÿTòøOÀ+_ÍA•p@űíÃ]eBÀDö§¾¯VÀ2h’š'JÀ2h’š'JÀ<øË¦H¹¿à?Úà·ÓÜcÀÑïæJaÀÒ—)²´Š@ʓڨ ³sÀNÆËC§^À,`~œí†c@[b Ì~a@ÖäÙy“Y_@ŒÁx¨rÀŽÎA÷´'QÀVþÖ·Èo@Ïô˜Í;À@š†Ë¿f@Ù©æÖpC@|œs5,mô?8‰ÞUàFá¿)9ãíA@ü ó¾À;v4T@g@ ~Ç6ò@ çQUlO@ çQUlO@÷?2ÀÃx@÷PŽ«;]w@± àdÀÄ7ªGø’@+ÒÏp v@uZmæfyÀ sw¥÷wÀ¥*v%"vÀ)$>‘]N@]ư½†@.¤ÿlõY2À$z^Ð:žY@kÛiÿÀsÂÏê€XÀ§$YytÊ#Àº²Ö4# (@¾Xð?_5BÀ}{Ny`@rhÿ”7P3À…Ô†® THÀç‘.BÀ4©KÐoH<À˜m“Ú{©¿Ð?×—ÅUÄÚSÀ•ž:·»RÀÆô¤£÷{@± àdÀ8à¬QÀQŒw1ü]T@npEù…7S@úeþ°!R@‹½»¢}Àƒçõ¦¸ðAÀ_»XÜé0a@nÛiÿÀѱð&W@¬S^õ—3@„QÐ*¢}ì?p«]}Ù¿d; ñZœ:@̦£Tš^ ÀØV ƒW@`¶FCÄõ?€ËÙ õ?*×Å]½eð?jšÃë"Ð?Ð?ï(ùzÀz@Dò¼z’z@ +;A QdÀ¸¥œ4”@ÞepšÉdz@ð$Xrˆ{Àkδÿ»X{À 7ñôµ){À›ùÏ’1 O@|¼ÛGD_‡@P{<;!6ÀƒUž8"Z@ÑÈ?hÙÀìD‡‡$®YÀ•ÅIü%ÀéF­¿H`1@¢ýqb±–DÀ±\u¯ï`@j‘1ØJC4À‘ö-q¥JÀxý|ÍEÀ–Hk‰…>ÀßC“ب¿Ð?3Z„R TÀ¸Ö"‹|TÀDâÙËëI}@ +;A QdÀ€†.ïPYTÀx{³pä9U@½C¥dU@$Ûœ#ñT@ž9ê‡Ó}À2'ï´BÀ‡?i…À…b@ÑÈ?hÙÀo>?]ëFW@;ªZTð¾3@´§y½~ò?U  ‚ß¿ó*(»¤4B@b¿<— Àv­ypÈW@@êò*¶gô?§Í¯¦àö?·ìÂOãî?úº S¢Ð?Ð?=Ô*qß|@º÷Wb.~@ïTÐÝúœdÀ“ž˜1•@P×6Œ@T€*ÏÐ}À¦;½½*À5ôå÷,J€À¢wÓTÓ¯O@S?àê":ˆ@àràö˜:À†¿Ò)¹©Z@ò~ª À9:‚7éZÀFÔÍZ(À/2r¹p7@| JŒ¥!GÀZ‘©Cja@Äâ>³=5Àçîÿ½ùÞKÀÍóìzGÀÇÂ\Ý¥o@ÀšÝÁø,Ÿ¨¿Ð?U-é[×fUÀX¶ÒÓ&_VÀj't›5¬~@ïTÐÝúœdÀÈ›'H·bWÀ=Ÿ_¡V@4¹vW@oìæËƒ&X@ùŒßŸ~Àˆ$-ÑjpCÀÛBí6ãc@ñ~ª Àº1¬Ó"ŽW@"`\ìæä3@šG–ϸöö?Àõœshvâ¿C¯8G@°°a㥠ÀqD‹)X@@ècŽrðò?ý.÷œô?b¿sÀ‘Úì?0xt%ñ?ð?mñüú Ÿ@ÄIñ¡f¡@zEq´¬æ„ÀMÚFrÄ:¶@ží‹òfÒ¢@Gåÿk! À«¿jJ½¡À‰8VE=‚£À~=½Â p@"† ©@.5õì¨Q^ÀRM …3{@É´+¨½N#ÀOv¬¾1|ÀêþΕçJÀ´äõLC^@]ЬÏÖiÀTBFYè@4ˬ›%>VÀÏüå¹ÄmÀô@-ïö¶fÀ\ÀªaÀåX5äÆeÈ¿ð?tt¥‘[.vÀC‰Ê¬·dxÀóö§uš @zEq´¬æ„ÀÏœçÓzÀ•当ýv@“…QàšHy@Ú«Ü.Î{@òß¶…<žÀ“ÀqKÖ dÀu\”ö›I…@É´+¨½N#ÀcŒÐ×w@¼=eÀT@NìVy¦@0ÁQ`À—9‹ñr[l@¶¦Q›-À“&Ïô6Zx@ð®&qS@Gu‡ @‹]ùî`¤ @ôÕ™h¬ñ?ð?“zd @"KwÄb£@20‹ü-…Àø£—zj·@½ ?dk¦@2á`Òo¡À™t +¤À½6,6ÍS§ÀlzIÜÖ^p@˜‹ohª@ª9WÀG\aÀ€&3<¾{@Æ,’=Ü#ÀÃ8'—C…}ÀŽé!‡£MÀÿ¦4=|ñb@V¤5âµlÀ^PhÎõh‚@óâ6KÕBWÀ²3 àì¾oÀX‘€óbÀX‘€óbÀ´ˆë¯¦+È¿ð?†þ:…xõvÀ<À#b"ŽzÀÂå6~ÓÑ @20‹ü-…ÀP„C^·~À.‹ußxãw@8ÆY¹j¡{@]È·±jõ@*Oo#ásžÀ#ÏW¦ÁdÀ‡†2¹†@Æ,’=Ü#Àßhúî#x@€7$)T@¸­ŽmoF @0À[ÓãfÀž¤¯ßøÎp@Ssz^-ÀKd4õƒ¦x@€czßP@Hÿî‚/@Hÿî‚/@{ ô`B7Ò?Ð?`Œ[ð‚@`z¨12ë…@\¬ÉÁreÀø=èâ觘@¢–m!¨Š@²ö_O!Ô‚À¾ŒÖôå†ÀÉØ°çôØ‹À$ #PP@X<#W¶‹@9yk^ŧCÀ£­?ëG\@ÍçÃ-Í@ÀÖÓw.9â^Àøû2ŸHG0À\Óo,G@]üÁÇ`½OÀËífÆêb@xÉ ]I8À’"{¦ßåPÀêZñhä.7ÀŠ/ÓÛIDÀh·lÏ’ð§¿Ð?ª”oÁâºWÀ5×éÛ\Àct3†)@\¬ÉÁreÀÂèC:^ŒaÀ"h8j]ÊX@ü„ùœ&^@Õ T_ Ub@´^½³ó¬~À¢xH®ßMEÀËåÕ8*2h@ÎçÃ-Í@ÀJ±…mrX@EowrD4@ÎV’ØÝÓ@°B‹X忇¯ÆA{€S@žÕíj Às"nºíôX@€‘9zÞê?¤ÍŽ'vØ?íó|'bgå?Áh|߯ò?ð?[B…[£@×#B÷ྨ@™ÁóPÑ´…ÀáNw¬ó¹@2ívã-¢¯@pø@h•N¤À¥}EC™õ©Àhµ¥–±—°Àq©@º¯p@ÖUAÆÀ¬@`QÚÕ7fÀáIDW&Ì|@„ Cus$Àæm…ë"€À°5©ÓQÀg!Â…™Õk@ê+>("uqÀÿÐallƒ@Éôpí NYÀ;A¹$ôqÀ—ÖØn©eÀÆ«8ZE´Ç¿ð?Ë©,}xÀÄóNÀtÙ zr¢@™ÁóPÑ´…À亿`„À®às3‘°y@yÎ’k€@—@:4 ý„@ً슂çžÀÔO%ð¤¿eÀbä•H´‰@‚ Cus$À*Ïþè-Ãx@ ©51½XT@eØKÌy%@P™9±ñÀWK¿Œ€Bv@0›‹›'--Àó޾@Ey@ ™äÿv@×2¿íd3@[¬/6VÌ?Ð?)Ð 3÷r@Žwa1ïm@ ò56aÀЇ| ³@¿ÄÕ Ÿg@c„B» FsÀ ßJx knÀjD‘ÞhÀP¤ëÛ},H@<$Nîy8„@äÏžwëŠ2Àì¼¥1ÎüW@cƒgŽ#¾ø¿wåBvòTÀ6Cb:‹Æ$À T^| 3Ø¿¿¼ŸècÎAÀ*3£\^@eáÈ‘Ñ30À?¥V^r4CÀ0}CÛ;À ©pܧ¿Ð?Š/äÍ‚õNÀöF "nHÀòÝɲÓrw@ ò56aÀýáï˜9GCÀW”Ø·uO@×™MÓH@ªUwL—C@ï¢#ì]Ý|À–Ñ9Àî/b/IYZ@dƒgŽ#¾ø¿СY V@‹$qçî 1@àñÆ6Ë¿qb×]kp?Lõ©‘ú5ÀÈâ¼cK6Àˆ°Ôà€„V@’°šæ,¼¿ ŒÚ³±?}‡*Ðõ7Ý?à?žBw„@×À×W@nablxDqÀÇJüôh¿ @æSº"uw|@Ö•Aò„À‘³Oï_mÀ{7ýdöÿ|ÀP'†¹X@ð‰’ö)á”@ô¤Œ™ÏáEÀöÌìã'ph@Š} g À–Ù®FÃòeÀxDÂY7ÀïP~"Ô-@ü$4uÚSÀÈã\(Hän@‹³<]AÀâÚJ©TÀ~꫚zé:ÀÐgî©FNÀÎÚäÎÜÙ¶¿à?º,/`À¤4€mËZÀ>ܨˆ•ˆ@nablxDqÀêK[@@!L!¶V@%glZ´À*óÛÛW¼JÀ eµq.Ìl@‰} g ÀäÚß›Yf@;È‘,I%A@0ó¿ÀÞ7XP¢?˜H/ÏÐ*@ö2…ÂÀa4Áf@€2T1·&Ý¿ÍO~l9m¡¿Çšàš³¿ßÐ×ç¢î?ð?$$"¤eD–@´ïNˆ“@ŸuI8ƒÀù÷ž*|¯±@sú%Z‹‘@9f¿Ú¿–À oˆUò“ÀÜ—*Ù}‘Àa‹ã|>@i@®´•@j•¥@vóÛõßQÀˆÏäH 1fÀï¼äó‡YÀ¿0 ¯i`Àe(¡•wšÆ¿ð?÷•Òý»pÀil±XmÀ[[,ð*Æ™@ŸuI8ƒÀ‰’¼iÀì’0¸q@ÿ‡ Púm@¤©QÃIj@—UÞ}4À‹Ûq‘ó[ÀõîgÊM@ZZ­À˜é„¯p˜v@"å³³7=Q@2êé¯ç?@ñbf6Ì?ÐxS‰“…O@’iY¦óG"À\À@ñíÿv@ Å,•Oö¿òÿ˜ c Ý¿É=ш¬â¿bï Ö Ï?Ð?ìð¹x@ry-¹=Bv@vS#Ÿ'ÀaÀw17t{ª’@,úL1~t@4ò+¯xÀŒX ÎvÀoèèžuÀYÓß%D¾I@Í`I•|U†@>·îðM,=ÀÝ×ÜgY@µ˜•-™ý¿F›i*²XÀ4ÇÛ,À¬h›Ðk'@X2MÁ…fHÀBðU?M`@4ÑJ,jÃ2À¢ÊFçýÎGÀpÛ‡6wÁAÀpÛ‡6wÁAÀÓvŒ›Z¦¿Ð?ázД–^QÀA‹ùŒ PÀü ÓR{@vS#Ÿ'ÀaÀ|nêmЦMÀNÀ1æËQ@³÷ uàpP@ïR>ÿ`N@ÛÜ·—b}À¨SÏË>"=À‘.Ypkï`@µ˜•-™ý¿žÒÐîÙV@|™ØBU1@° ú¬Ù?À0­ä¤o¾?3]쮄49@Tç®ÖÁÀUÙÛAW@€`)bGRÞ¿«Vxrп«VxrпFEœnà?à?ÊUœZÔ Š@=}tÊV‰@±ÀIšLúqÀR‘"Þ°£@‡Ä[ƒœ§ˆ@@ÙÄŠÀþ<°ù ŠÀn¼;îV‰ÀbŒ$,1Z@ ü]=x!—@YSÉ‘PÀñ$¢³éi@‚ûÙmƒÀ[e&Û¾DiÀÍ `ŠÝ>Àÿ¿12£Ã@@¢HùŠ!êZÀž»3Âp@«,QS¯CÀÔpÌYÀeéøŠLUÀÏAàI+SÀö‘ƒP2¶¿à?~Š¸È•bÀbhæ†aÀþdLU SŒ@±ÀIšLúqÀµ/’4í aÀ02Ý‹§‚b@p ìx¯b@?2‚,†a@#DÅÛ#“ÀÔ–Ó±[DNÀ{ø$Æ@r@‚ûÙmƒÀÀËlj5g@«ÁõÒÐlA@Àì[ög!ô?@2Á*¤½Ú?oj?)tnQ@4á™Ö{*À*‰$°–„g@ÀµIDA[ó¿n7 Žkê¿ä±£ÌàÚç¿NöÎ à?à?X(øŒ@šé\OÎŒ@ÎSôÆ1rÀ öœ!ä@owkmë@Ö´_.À&Í?Ù´À–ížÃnŽÀЇ[–Z@jûú :ù—@4¶x#i©RÀ†m %¢ÀÖ¿~Zéj@¾U«pTܨ@b‚pßÜdÀBê• ‰ùz@ söèÍ À.lYú¾{Àì<¹WRÀ±¯ç[»W]@ôÖ‹f99pÀäEìU¸@nðQª^UÀe^œW(mÀ;Ò&(6fÀ;Ò&(6fÀ†ã)?—Å¿ð?¹5‚¿}JsÀ”NVwÌtÀÉ~†ÂU Ÿ@°dð$mf‚À³¬8›kvÀ/`â:÷s@o\Aœ9†u@V/ÖØ]4w@5ÈGB¥úÀ}@Í‘'`ÀQ´ºÉÑú„@söèÍ À¹‰ÍvÓ«w@kÐ@—Q@”~…à ì@aÍíÞF¾þ?`‘ô«mk@JÕô«#À¡R!™µx@0_:ã¶“ À¹&Œ !ÿÀ¹&Œ !ÿÀŠLÓ†Ñ?Ð?Íên^BW€@.0è}¸ˆ‚@™Ö*˜bÀt¯e-a —@LøFŠ…@n¤ÛÒ ú€Àb}°3[AƒÀh9¾ôÖ…Àòö¦Ö@'K@°¸¥ùòɉ@un޵K+GÀƒ;ÓÙ!„[@¶ã0¢XIÀôønŒ…]À…:LåE4ÀÇ:måìeB@—ÞT»»QÀ¸'ÅA8b@¿=>Ióœ6ÀÉ:7¨OÀÓø¼ê”ŠBÀÇöòv¿ÖGÀ™êfT¥¿Ð?qR·Ã‰ìSÀìaw™VÀ/G²YP€@™Ö*˜bÀ$æ7Б¡YÀÔæ ³T@˜_`àå’@¶ÅO+´—@§ÉL¡ñrÀÑ—H­©@ÑeÈqU»@±Ïþ* Ë“ÀÄ]¾Ó˜À£WSñà#ŸÀã­ßTP[@Rmt;Þ¾›@‹Û‰\ÀC—¼¸•l@NÌX#eÐÀ¦øËîÔÉoÀï£Ó†³HÀOó–/"[@/àty½ýdÀm軡;s@¯³ì¢HÀ(£‹ÁœaÀG‰{–H[À:ÄgîÊ´¿à?°NˆÆä&eÀÜuí‡jÀëSŽ’Ië‘@§ÉL¡ñrÀÔ u’£pÀ×™Óód'f@c½µô§Ék@^õ†Xmq@Œ ä ¤ŽÀ)Yæ¤B/QÀ‚oþŸWy@NÌX#eÐÀ"hÿ?”h@¡ÿ5þºA@1Îx)žÿ@èˆ+´üö@˜€£kªe@–%?À\VÚgÏøh@ÐcëŽîÀ%Ï7ánÀÑácóuì?ð?æÙgÐp’@àŽOƒ,zŒ@/P^¼8~À‘;ÛB0¯@ç Žèý…@©U$tÉ·’ÀØ!¬SéŒÀgƒ€S†ÀH¨ÞÔ_d@¨ € ¤@ÈZ¼è­\ÀÄ.×MjÌw@AðF tJÀî¿ZO tÀó-¾ŽKÀîç‹^x&ÀJ~‘ƒgÀp>J`=Í}@SÛç…OÀº \ŽÒÉbÀv)×êd2^Àõ Žz Ä¿ð?‹8nACíjÀ³?ÄÎcËdÀ­PT%­ž–@/P^¼8~À4·ÓF `ÀJÆ0DVk@\`ÆRe@峊M`@¨e‚RÁ¨œÀtKå-ŽTÀ¢ òèy@BðF tJÀ_°¶D@“!|ý®„@ñëÕ@À¥ý0žæ=X@úÍÅ2~´ö¿(û½Ð›UÀòO>ˆâÖ-ÀaVú ]%@~XÒu­IÀìc‚p¬•^@ O20À>íL(ˆ7DÀƒÝèŸD*ÀsJñãj@ÀØïRœ;¤¿Ð?Ö]¹ßœóKÀëù}FBÅFÀa¬J¾w@zé1Èg^ÀLOg‰ÁŒBÀTw"&rL@k32+W,G@f<»àB@ÃoVPÒ|ÀÑá©Lû4ÀxwA ŸT\@üÍÅ2~´ö¿VmÉô,5V@yT.#.@(A2ºÿÒç¿ Ë¤o„Â?bO>9Ò@ BÙªòó¿cž Á%…V@È÷v‘ãþ¿‹äP·„Zå¿­%å%±ú¿¡1ãÍ?Ð? û•g«u@Ã¥èœr@¼U6qÀ^À~ÒÀ¸g‘@à ˆ\9úo@¹ð-)‚vÀ±EY@þrÀ,vióPpÀ¼$|ÔRE@9bœ~ö_…@¢#óeãñAÀèEg÷´X@»N§ç*ø¿ûü¡æ†¤VÀ6øDfüe0À-‹^¤×{@úkÎR~þKÀpûǬOh_@à²]b`1ÀQ }ãá¸EÀaJ³lKî8À³Y)ÈÎAÀª‘†ô£¿Ð?; ðjûLÀÌ—ÇåHÀ×ë»O¬ëx@¼U6qÀ^À”Ôèq]bEÀ2ͱ’M@!l vgI@XºAûÑE@JÒÝ÷íý|ÀwºàÞøÓ5Àþ~Ø›Î^@¼N§ç*ø¿¸ZãrV@ñÌȼ2.@XtARâ¿ ®ÑEÿšÖ? „8(¢,@p€¶´qô¿;ÙÜB@ÂV@1%üd½Àö’¾tô¿„&`>9ý¿ ¬ÉœâÎÞ?à?7ØðDVu‡@œ×ñ<…@táÏ oÀ½äýãq_¢@hàöW:ƒ@d9[VkˆÀ1•åáû…ÀÃÕæ)­ƒÀrL×è|IU@dØU¸–@i+9VèSÀ þ‡ãX1i@€ò¡¥§i À îæ^ѺgÀX9›(üAÀ²Ú™ö!6@2|á¤x^Àºgø ‡"p@¾è:¬oѤÈESÀêæ!6­³¿à?ÿk)¦^Àõ¯ig,[Àjþ4h'Š@táÏ oÀ)ÃyÎý™XÀ [gSá¶^@¡ÖÏ«Î[@Þdaxæ,Y@Öj5ª+ÀŠÎù‡g¡FÀ­x\+Ыp@€ò¡¥§i Àé‘rï²f@5ÃîÙ™E>@°Èl,꿘ÙÛ9 ó?Ú^ÚÏŸG@¸ÒßãŸ×Àñ Õ”¢g@¼Õ®qŽÀãOê'™¨ À‹Ê žÆ×ÀÈŸViÁï?ð?©!´}§^™@ŒøX6ì2˜@ÕÔÇÙ‘aÀNäq~cb³@¨á—@­ÚÈ šÀåîµ%טÀ…¶¡‰œ±—Àt±'·ã€e@/þŒ jå¦@ä+pKûeÀWË —•²y@×ÞLé+¨À|LóÞÞxÀ ­Š¯SÀ2ÁR¢&P@AÃvAÎŽpÀã|È•€@Ñ[ª¸!SÀîÏcuøùhÀ†$×­¥ÐdÀ†$×­¥ÐdÀ”Іeÿð?5ëì oÀK¹«VœmÀ9›”Ýr›@ÕÔÇÙ‘aÀnu‹€>lÀÆ@Z…²Ýo@´¸ ,7en@úåLÇþl@-Æ^Ð[À·‚ry¶_WÀ14–ø1ø@ØÞLé+¨ÀEÿjeõv@~'ßôªVN@ “>™Ìùì¿€Ô„-ì @%a%›‘`@lظ¢—À\ÑŒZCw@'Ñ49}#ÀQ\¢˜CI!ÀQ\¢˜CI!À&äu{]à?à?ÞËS©h‹@,A<­ˆ‹@5ìÀˤ¨oÀ²‚vžq¤@PŠÖ¨‹@2Ì"í‡:ŒÀGï°ù€[ŒÀ|ŒÀÏžäâ¨U@e[jþ¹—@á‘¡D3+XÀ{ªÚû7j@FIæ•äÉ ÀèίL›jÀOï¯Q€EÀ·w¹o)ìE@QvST÷aÀ,¾Ÿµ• q@)ÙõlÈ DÀº§×ÖݺZÀÙ¡.ÞàoVÀÙ¡.ÞàoVÀJÀ¸ä³¿à?¯¹é.`ÀÐ=ªÛè`Àб“ãlÌŒ@5ìÀˤ¨oÀˆÃî­¸-`ÀÆä‹§ð‚`@ hsý9–`@¢\zÚ™©`@Ðökò§À8rOh‰ HÀÅž“ºÌLs@FIæ•äÉ À‚D‚U:g@oítŸd>@€I\a±~±¿ht„kÉ@(DPÚnU@0â{/À£6,­p‡g@<ˆúaü÷À=X˜öÜ·À=X˜öÜ·Àà\èÝÐ?Ð?`¡Ìˆ„”}@ ‚T™H@ȇüéè_ÀIxП⋕@Il>劀@V‚¯ù›’~Àd#‰7©*€ÀÔ³a¹þÀªYwsw¾E@E;e šˆ@žKáõôwJÀ}KÀZ@×ÑÓžâÅü¿·sáX˜O[ÀT!>åp7ÀÌÔ*Èm<@áÈ×=5vSÀäâëg‰a@¾µÚ¶5À&VÒ“‚‘LÀ¤h«¹EÀWi}¢#HÀÃe«žêÑ¢¿Ð?ûÅYçˆPÀhÍ 7ª|QÀ^UpÀ£AÙ+œ8VÀ ’Ï6ÃÆkÀ˜•ÂÓ9¿ð?L<»˜¬€qÀl’âÅ~tÀ§­,Œ  @wª;’¹)€Àw®v¯ÛÿwÀàΤ:r@ÞÊŠXu@c¶„Ûþx@ØožÕÕ0žÀøOzz=]YÀ:¢‡@ÿZö1#ÀÍŠ¥Ix@ÂËà·jN@HŸ= @õ²uC#@G@¿ƒ[r@lYr²òÆÀ¨ ÑDÉax@H€ò *ÀN?OŒïÝÀcok•'ÀlAcvò?ð?ÚûÉé‡u¢@¡¯ùÉ»¦@ra–p>€ÀhðÄ5"+¹@­Ð#Éoÿ«@zï1ÖM£ÀqcMÆ.ƧÀÉ€À’ð"={À°µ¶ùÒÇr@>Oc#!w@ãµ2A||@Mj=kžÀþ4{Ý6|YÀ ¢§¾o÷ˆ@è`5ôlÀÚ@P=gx@ÊKÖ+XN@¨L£ Ç9 @\6H f'@½úßyu@)"@̈À0ÿ ïx@ȹ4á´,À! a¥Lw)À{„>%—çÛ?à?µp¢Mð@Í~=²c#{@·0ª—) jÀœÍ£iº±ž@A¬¦¹‡t@U<Í•þ1‚À™¶>äņ{ÀРˢLÒtÀÚ £\¨¶P@•y³#Ü“@ÅÔâ‘TSÀFŽmޤg@àÅk¤ À ¿h§.QdÀÈÑŽáwŽ@À:"\ýá±ö¿ˆ£’]ÀaX´Ã¶„m@”›p}ý®>À[©lþ$cRÀH¡ìä\xMÀg~Ö¬¬ð±¿à?ÝbáÞËWÀ§ÚæKyQÀ›¯hÒYÝ…@·0ª—) jÀO¯Ï[oJÀÈŠÀëdnW@Z‡ªI¹Q@¤†vì)ÐJ@ý–Í{ŒÀcÅ“õMÐ=À†7â]ˆti@áÅk¤ À3F‘÷×e@ôõ•::@(Èuáó ÀŒÕëgõGƿᅮ·èK$Àð%:ß×`㿵!d2f@¦‹T-À(KÀy†À„qã9¸Äì?ð?aI‰çŠw“@=cPO¤@Cc’i+\zÀÅ-²»8°@+f0´¸Ïˆ@›ÎÅ+ÖÊ“À,4g¯ ™ÀG35 â9‰Àí<•jÙ`@ÅY’£~¤@ ›÷ôÏ(eÀ&Ú½D x@ÚSw7À¬Ž¾s HuÀÁ\Ò.»-RÀ¿ÃP5B$@[È~ÙdoÀÌKÒŸ·I~@"Y•PÀ´ÜVi5ÊcÀ„žçÖî¥IÀÃPFµ`À›5È…¤Á¿ð?LüŽ“égÀsWÌÍcÀÛkà!4ú–@Cc’i+\zÀt,À0z^ÀR+äOh@þ(5%{hc@†¼D˜ü^@åÿJȤœÀ\§ž°*âNÀŰÙ{@ÚSw7ÀÞ­ev@:îHŽJ@§\ˆ=>À@í³º Ìï?>YÙˆÐ-@0”ßRü‹ó¿^P§zKv@ˆÌÝ ì»,ÀL!EkÔÀ¡Ÿi† *Àþ.ŒPܧí?ð?Áœîá•@\.jš½Å‘@|»ÏÁ‘zÀDö˜Œ"±@îd@Í î@vdPhƒ•ÀÒ`¸´Â’ÀxIÔÞ‚ŽÀn†r¬ñ`@ ìLW>,¥@¡ÆEIvgÀbFIñ†‚x@ÉbºÕPZÀª÷V ôKvÀ×^x $êSÀÝÄ;âøÿ8@¢½¢ŽóépÀœ¡|ë@I)‡xæPÀ×¥£·˜DeÀU^ZXÀoêÏeaÀêµðüuVÁ¿ð??8o7&¸hÀîñ6çÐdÀ ‘q[¬$˜@|»ÏÁ‘zÀÎÕžgq‡aÀ¶“2i@T&5ÿ7e@Ó{­øAÞa@;`ÓÖÏœÀû¶ùGÜOÀú™[ËeK~@ÈbºÕPZÀîg¬' Ov@ÅÞiæJ@\ gÚ_hÀ§_t°î@Œ»ÙdjI@׬dó¿|æGí†v@°€>T`X.À§¤} ÈQ#À}³Àg™+Àê yS‘î?ð?¾Õ’ÈÛ–@¾“Á®ØK”@qS’ÀzÀê |G²@åý¿”Àáx\råk’ÀJp>cý`@Uþ5í¶å¥@f:§$iÀ]#É6ýx@¸ Ú;oÀ«´6¥W]wÀß4›:ƒÅUÀ‰£ÐM¬(E@·»N? 6rÀÖIÁEJò@@÷(»QÀvÕ€DÓfÀý¥;ó`ÀRñ ^ÕbÀAãå°ìÁ¿ð?k=Ò€r„iÀÑüž6¨fÀ†r KV]™@qS’ÀzÀEldÀ$Jz‡j@s (e)g@¤·ÜËod@2« ± ýœÀ!ÒsË\PÀ±4f€@· Ú;oÀ˜Sø1Žv@!E¨n}ÿI@XÔÕÕrÀ€¤ž¨ô@ÐÛiNàU@`çX˜Íò¿7­¬žÄv@ ~Q…0ÀÈ´Ê1L*À¿=R78-ÀL¤0#mï?ð?j?½ª»˜@ÖV!G%—@ÅE[ÅBèzÀtßÀ°³@¸3Äåø¨•@ÖÖÍé[™Àí™î.=»—À—œ¾ðN5–À“ÇVDšú`@î3«¦@ðá\CNkÀNTí|y@ÆÖN‡pÀ=­¿ßu|xÀâxÁWÀ™Iy‡lO@bsÒêQ™sÀ’:ÒÈj€@ê´§Ì|˜RÀØÜôvwhÀØï²BYdÀØï²BYdÀxE¥-P¸À¿ð?”ÿð@?MjÀ§æGhÀÔ8/ͤš@ÅE[ÅBèzÀYÀ1¨gÀD*¨÷j@|V^0Ž_@ TaG¬¤ñ¿ã¹?žw@Óô]â0ÀlÆgàxè.ÀlÆgàxè.ÀÉ[æ;<ð?ð?äÜ=Æß»š@¡Ø]‚p[š@ÝXq‰o{Àu„ ÌÑ!´@¦Œ]ü™@œQ=˜ì›À°Øð"º›Àág°€íºšÀ>äÚˆÝæ`@xXªx|§@†ÛÊNÇ•mÀ»-T²z@﬛G·WÀ–31R©yÀÓCØæ¿ßYÀ“Ýl—Ð*U@™ 3°uÀoòòëá€@@Ž(~SÀoØãA_0jÀç0€dñeÀç0€dñeÀ¶Z ^ƒgÀ¿ð?¶z.˜&kÀy ¸ƒ¯jÀå?‡+´û›@ÝXq‰o{Ày AOjÀ_ +Ȥ×k@>Åæ5sk@ö•ÒM1k@-Õ’ê^Àý3ߥÿPÀ"×› “þ‚@﬛G·WÀ&‘„¾Aw@ Eø?eãI@˜}ä5B-À("× @â7ƒ¤hd@@ûœÚG…ï¿Ásvý÷Fw@¢f48aÍ1À!Xé”V0À!Xé”V0ÀèçL[»ð?ð?·ú}ÊÝœ@¨Äàø@˜ì± {À‡ \^ù8µ@°óÉ66Ÿ@7þGµËÀ@Ô¦¨´ïžÀN3Îp À׹̠¿`@<„´êŠY¨@7³RQ+ûoÀ\ê8‘·ˆz@—áu€ÀÑ+OŸãzÀ|Ž$B!\À]Un…[@Dýu£vÀöýꨡ[@U…gNkTÀ¿­˜„ÿkÀËpAeÀÄÙ$à žgÀ _+öcÀ¿ð?ö ñÏÎkÀ-ª›ßlÀ‘ô–½¶b@˜ì± {À(ˉ÷úmÀ“šì³l@ÞëV6Ím@Ä<8Dñn@…U[Î ’ÀFv8ØÛ+QÀvƈ W„@—áu€ÀaÏŽ£¥Yw@­%¼8+ÎI@ÈHYqðàÀ2OJ€$@+âfÞMi@à¥;põé¿Æè•±‹w@†h“˜„Å2Àoí³ /ÀK¹*çD1À/`Ê 7>á?à?GFËÌé!@æµC®‘@F Ù0kÀh²ñ¬\¦@ÓÁ䘒@{z.‚ À˜c.– ‘À9â‡eD“À-?ÆO˜P@B|„JÄA™@ŸÙ{Ø>aÀÒIŸê®k@¾LÛ Â¹Àe»_S¢*lÀknÞs·†NÀ(‚ã“yRQ@2!,N^JhÀ‡Õf­Ùq@(}>y$_EÀˆý ä]À¼Œ¢²ˆÂQÀÄ6èl _YÀ9Z™±“ƒ¯¿à?޼)¯ƒ\À ,æÅÇ*_À3è=A‰ÚŽ@F Ù0kÀj\NÖ†aÀO¼‘¤Š]@µ=‰ã%`@ó]6r›¥a@Á(}¨8ÈÀ^†wZ8AÀ´)‡dY¸u@ºLÛ Â¹À¹è>™¢g@Ú!²9@ØrüS5ùþ¿LNU£wi@ÚiÛ éO^@€ü&±Ø4Ò¿ö- îÈÒg@Œ*ƒ Í#Àd¡ÿôŠŽÀl¼ÿ®>A"Àx8èÄÑ?Ð?$*ÂÄ€@aß«ÌIƒ@A“¢µ7[À;Úïíx—@¤¯;Ä/†@%ïc¨pÀžº[}‡„À{\;+5‡ÀI:·Ü÷)@@æ[ñ&'4Š@–§vÖRÀñŽU[@Iƈ“#ù¿ƒËß=}]À>ö$.ˆ@À´ÔJE@£*ÊùäZÀßðTö@Zb@D›´*X6Àxì[x4ÝOÀ ºŽ îÂ5À‹hrŽ©3KÀ7H Ùž¿Ð?¥2IÜv.MÀgkkˆÈPÀP=K¼ô1€@A“¢µ7[ÀÅÀþNSÀÄÜYN@†iT/ŒtQ@AŽ:êT@çtš~À“úÈ} 1ÀAÊè‚"g@Lƈ“#ù¿gˆîW@ñÛÐ$)@ VÉ&ê¿ e-ËsÑ@Psèá·Q@€ ú•L¯¿3dD2X@Êbá†æÀˆZ…_!ãþ¿“X³ÛôMÀ±<¤\€Oâ?à?ëý&lh ’@Îûéî«Ô•@¥íŠ5kÀw%ñ˨@ü_Â:Æjš@¶Ø hÔÖ’Àßúñ$ Ì–Àл%g–›À½]µ’jO@ÅÔÖv,/›@Ú9ˆz"écÀmÈý…“&l@ C^ýVQ Àw÷ùÈ ÙnÀ›Ë;ÛÞQÀËkëò®Y@åÒ71ÚkÀ##ÃQÜr@¡ŽojTGÀJÐ: tô`ÀZȃ+]]À!}VìÈ*®¿à? ïÇ—œÌ]Àh±î‰£bÀó¿ãÏÿ@¥íŠ5kÀáƒwRÑeÀõÐY¸E_@‘Y%ðÓb@{ñ]ŠÈf@Ó:üd;ŽÀT å Ù@ÀRìÓ<Ó•x@C^ýVQ ÀÄ',¥ ñ¶>}@ûÖAbâMÀ/Î7bÀ°ýNê£äYÀ–|›¤Öξ¿ð?âwcÀ¦RMLmÞ\ÀE$7Ä[.•@Yn(À£MvÀÉ(×phUÀ˜J 1ºc@D‰ìÊB]@Zû*;N²U@rÐ2Ü,VœÀ„+à{ ÒCÀùôyËAüx@º³‹þ ÀŸÜ‹w¹·u@ÊämW =F@vúb ø)À\fûÆ$‹ä¿:ëØt¿T:À@ÆÃVt@®~øá3Üu@º¢•î3ÀwIÁ~0À÷~ö¿çŒÌ?Ð?ÿru÷r@_g•Õ(³m@¸.7*¡gVÀQ×À­Ðñ@´Ó#™ä@g@\ðtCDsÀKA.n+nÀs<ŸgÀÂÃ^ÒÎ?:@y¬„À¦O„@É‹€o'JÀ»æ<ÞW@z¨žj.Û￘™“mƒ@}SP,+…fÀ‚žŸ>YÑ¡@f &“î€@³’ëšÃ†À‰BôtáÖƒÀzG¦þYJÀ*õç`2°I@yb lt°•@DåÀ3L^À id¤Êh@&s"th¨Àº!ÒT,gÀ@¹¨ïSfIÀ ¡·r,4@xdràê"eÀMXüê-¢o@[=#i?AÀê³²@\VÀt<§È‘PÀt<§È‘PÀÍ]K>ÊÔ¬¿à?f.l/:;UÀë0ŒDê€RÀ3÷ÑP•¦ˆ@}SP,+…fÀàzÁBR PÀ«¾¬ïN®U@M Ûî5åR@Ñá$»wP@7™¼TÖŒÀ>Ò£7z¢4Àlײp@&s"th¨ÀW[ Éjf@DïiÖ5@0­0ö–ÀœH+®<3@oÉ_¿í÷C@@W±éÞõ?mlÈê‰f@øP6BñÎ&Ào´.ý"Ào´.ý"ÀÒP!ÚBß?à??¹!”!ˆ@:dƒ],†@÷ þCñ‡fÀd§I¹²Í¢@U(tÐ_„@~€Õ·ˆÀÂﺆ¼µ†À™eŸ Þ„ÀÄwõ9I@‚—ø”r–@¥ÊåE`ÀŸl–?ÄHi@'+´´kÀ,yPphÀkRŸââ¨KÀÆ2Ó¸—Ö=@Þ)G÷Z•fÀrj©¾Ap@YØ\³rBÀjqƒ:ÄøWÀí@9æSÀ¼´ÓöÌèQÀü\û '¬¿à?Ï\Ù1ÇUÀD+4ÚTÀ•™à?à?}«@1F0Œ@UþõhÁŒ@bû.ÈesfÀ¶öùè¤@o.:ÿvU@í’ÆÀàDT’g¥À„v~ >ŽÀ®¤KíÕG@4ÿÖ[¢˜@õƒa…ͳbÀP0ÅRj@Bpض‡£ÀKr{jÀ%ì“PPÀÇo=œžJ@˜*rý‰ÀiÀgM…‘ /q@îô1ÚCÀ“áÛE~r[À±v”_ÍTÀ±v”_ÍTÀö¥²•ª¿à? PÁÆVÀÜá -ôW@ôçŸÎ“oX@ê¹&L¢jÀ¶ÞYöÒó3Àôo´Žnt@Epض‡£À~øTS3g@Îõ®úM5@ÊSe ÆÀz1iàK?@è ÖŸÊX@hPü`á ü?g×ßýKg@š#9šO*ÀëñªÃ#Ò%ÀëñªÃ#Ò%ÀŽŽÓŸ#ñ?ð?[,îÍ€jž@믕&V @Ù÷*[vÀ¶áwå¶@(¹é½{Œ¡@ˆœ×LÄxŸÀ¢3áÕNç Àqcj(¢À¬ÑëÂàV@lÀÕ!ôÿ¨@,ÓFH˜tÀ62d£iÛz@º0äCÐ À;ÍŒ“Ÿ½{Àª–Éq¬aÀ®xk0›Ê`@l¸°'—y{À:Ú\oø«@¿Z$Ñ ÇTÀÞ |ÖOmÀ¿bƦlcaÀÑ5HB[fÀLÆ~K º¿ð?Xf&27gÀ ˆ#1ðhÀdÄ4ž@Ù÷*[vÀ €è–ÀÉjÀçâ^Nh@½lÐæœÍi@l}›Ç·k@&iö³¿ ÀÞ,xÙð@CÀ2ÙH&à^…@»0äCÐ À“ï=D{w@™¯©E@¶*5Û %À®{‚z¤d1@+Íã m@ˆ6ü‚@=B±g‘w@L´ÐÝL;ÀÓ!ªçŽÈ1À¢tHJÝ6À­ aá á?à?¨¾(íc@—ô…ˆ’@Öéë§û8fÀ_•î4¸5§@áëþ‹Öô”@ \.‘ÀÛôôü?“ÀuáHKÄ•ÀE‘—¿ÁµE@¡e+Ìï™@<Çì5¶]eÀ.ÔPñek@ã‚âã´HÀÆ0‘ mÀnA[vSÀ5Ø7~¬T@àáRœImÀ+\.ý¿+r@½¯—{þºEÀ5å¦B_ÀŒP†ÉìPEÀœ·b ûWÀâND¸-P©¿à?´Ž?ršWÀQƒ×Üu°ZÀO¯•øœ@Öéë§û8fÀûßÃ-^À¹\¶„X@Âă2«¸[@áGƒf„X_@KWö.ÙÀѧDzA2À>×›¾Äv@å‚âã´HÀ(Ó¸±ËÅg@Ô ãcWÐ4@dÌ}u4vÀLã Ô–ò$@DÛKp a@LB*?°U@AŠH/+Ùg@¨°Ð–[–,À;ó“RNÀ_¢qæø'ÀrѵO¾)Ò?Ð?ÒóçYj¤@rwÎý„@óâ†.R VÀ™ç2p˜@2¶öùˆ@Ô_pàe‚À@»"‡þã…À±o›Ù ŠÀJt¥²6ÀF ™9¸£PÀ.VŒŠ’«IÀHµ×˜¿Ð?üʲ´ßîGÀq©þyLÀviPµnš€@óâ†.R VÀJªFõðPÀ‰ÜÓ¿QõH@ó>¤B²M@À‘]x»ªQ@ ¯@‘Ü~À@mU, ê ÀµÍlV2h@ré\Sô¿2{´âX@ ^#Ô]‚$@&ù}$ËÀ3aá\­Ð@~עלS@ZE—7~ó?ÞÜB,6#X@È´ öBõÀä¦[ï¥$Àš@¨Ë#}ë?ð?¿e<¤ø‘@…C¸¶Çˆ@à­£jrÀ |W‰®Â­@ÿ5”‚@é.QCh>‘Àê~‚@I*Œüin|@<”O1ÔˆbÀ­¸è%wŸ@úµ¶;Úu@ø3-ÛèÅ‚Àë %¡‹Û|Àoœ†Ñý-vÀíØEºšC@Ü/êþg"”@þ¨œË_À :ò˰g@CNÒ/ˆ¨ù¿ti܆©dÀqP¹íBHHÀ1ÕóNå@‹Ñ3BCeÀî÷A¤‡¹m@áfEµ)Š>ÀÙ˜tgûRÀ$ŒOa×y8ÀŸš%uœjEÀíäYÍü©¿à? *–bÁhPÀì{zšP9IÀ, ×”~©…@<”O1ÔˆbÀ2ùcœcCÀƒ—òª½§P@ží„"šI@ý'ŸÏp­C@ˆ_ú_ŒÀ@ä#Àœ[Ë[ÀÖ›ãLÏ–@…€…9UyrÀšgFÛdVÀXÁª<a@"ÇäFݸ[@uœã2`~V@>ÒAXŠœÀÌ£›h†3Àé'°²9}@í…Ný’ö Àû[4­% v@!=UB@$ºÃëCœ2ÀÕLnÕL@/ûð " B@Êܳeéà@m:ĵÚv@ìÊÓaVL<ÀàUíFo2ÀàUíFo2À»Ýñä(Þ?à?ËáY±Â…@¬ÿmú× ‚@bኼ+abÀZ£þ&Ž¡@öö*3Ïå@%¸ÐY2†Àae÷µ=ƒÀ£7¿oE€À–0)…¯A@àµz•ê|•@×ß_+°aÀÅ4Õa¤™h@#nÜò’&ü¿8ŒÕ4¬fÀ ìJ§·àLÀÇÊ€*-3@}5¼JìhÀU ÿõ°To@ŧã/É@ÀfŠréUÀœ2Ššç3PÀ)kóÓK4IÀÁ¯–Ü’¨§¿à?S’¨Î#QÀ÷ÜìYYMÀûPeý¢ˆ@bኼ+abÀ¤]J ¦ IÀÖ¨›€|Q@Úc‚ã9ñM@ G¾°­¢I@”í¼Ù8·ŒÀL„x…Ôó!À;\JÆÄªo@#nÜò’&ü¿ë¼ˆµ%If@žKr…:É1@bçÛÒª™"À2—âzH @Tá餢Ê-Àg« ¥Ú$ÀïElxà?à?ǯ;A7Œ‹@ÕªDx¹¡‹@óÃAàaÀ2šNwÍ›¤@RQozL·‹@ÿjOl^ŒÀåä-¦’tŒÀ?ŠHÊŠŒÀ~@«ÿáü<@àoÝ—@½?Œ×-_eÀTHKÏj@é|(°þ¿ Õ‹gÝjÀÈà›yRÀÒ·’;¹I@¤,XÏlÀ[ A³q@ §ñI]NCÀk?6SêZÀø2ÏÕ^]TÀHOB÷¯­OÀÑE›¤„j¥¿à?EסöQÀ°¬¿¦RÀš86V¹ö‹@óÃAàaÀØHªžRÀNÉkR@þ'èrR@Ú•Àû›R@­þDfKÀÕ¿ö™&ÀFà}ö«s@í|(°þ¿¡pìÀg@cÎçÑë0@'ôŒ½¬‰"ÀØÈXnÏ!@ÎÙÆxÙV@ˆ|Mè Í@Ü9Ë®g@î›CÓøœ0À÷XŒÚïò+ÀkÓqó¼%Àc¤;&Ùøð?ð?»5‚€­¼@ côèäjŸ@H(‘hà qÀͧ¸µ@äûk5¶˜ @’5ýÍŒ»žÀa¡“Å< À&ÒÝaõ&¡À)×cV J@ržt¿¨@Ú0Ë)¹vÀë°§D¥z@SßÓªÀ.â!¤îS{À0¶£gýcÀ#öÿSòC`@‘·j²™~Àˆ#+e@Ñ,¼A+5TÀ2Z/vÀlÀ¼Ù†aÀ¼Ù†aÀÛ_áí’£´¿ð?Dg/)#bÀ6¸7€)cÀº°Bh@H(‘hà qÀW‡Ž Ê>dÀh£ñ!¾b@;Ú\qÌÍc@@7VOìd@Á©”ŸÀ({ñæ@5"ÀÚü/¢…@SßÓªÀ¿ÛÕ¸Uw@øžÄ“@@F¡èT„2À{š©Mß5@ÈV²¢a¯k@û VÈxk @¢T^yRw@,T4J)OAÀŽ9UŠ«6ÀŽ9UŠ«6ÀU¶^è|Ñ?Ð?I»8œ€@†qy EÕ@ã@ÇÝlVQÀE›Vá–@/ÇÙ\Öƒ@׎–Ùl¡€ÀApë‚À·ª0”„À%"¨ Ø&@e Ï笉@3¿"XÀÞ Í¥m/[@—#¥ãÉ)ᅩëØç@ž\À¯û,âY—EÀßS…D@ÛÐ×â=`À—Œ‚Ñ<þa@zœ¦ÿ"5ÀÕ«Á®«NÀZÞ4T”â4ÀŒB®ÉAFBÀ,/Í©JØ“¿Ð?½äŠã@BÀÐWÞwNDÀïBê£ê~@ã@ÇÝlVQÀf"J–FÀÞ;HnïB@_ò¨ü`E@#wMnnG@ßYHUFº}À ”'ïö¿D3å›écf@›#¥ãÉ)ï¿Ê)¨¯LŸW@dj†¬{2 @ð).«€À»uwK0A@ž`šŸPP@˜B^ÿW•@ó• ˜W@8ê̺i "ÀRãÇ‘  ÀåæŽ_(¦À‰0ËÓÒ?Ð?^§®PsC@ÿñ¹1<6„@Æ*ˆàVQÀ`Þí€>˜@Ôîè^í©‡@M&»ÑúÀ*Ú¶Ãë …À^Å5RG¥ˆÀéƒÛ'#@ÜUöª£Š@ }, ˜YÀ¾²µŠ}¹[@'bú±†ëî¿æÅþPó]À~˃6ùFGÀ¤¤4óVGH@Šìâ:aÀÿ1“Qb@JO³;6ÀôŸÞTUPÀÕ²¬ðL’CÀå›9«K“¿Ð?#NEà-MBÀö±ÎXmEÀ<?€@Æ*ˆàVQÀ}@™?,IÀ}­Í’C@¹)úïðPF@¾½i"£ J@G¸=Mõ}À€K øªâÓ¿÷<áúÍg@'bú±†ëî¿°i2ôxëW@åM…Å@5½ãÀŒ8 äü@’J»Ù ØR@ëø@†©è@c²Õ$áW@ÆÁÆÒ"ÀÒ’§Ü°¯À"Ô›AvIÛ?à?”‘ ¢Ôœ€@Ólnü¾w@18ÞÄÍ]ÀMd‰íQ@åà7餸p@ÅåôÏ€ÀÜÄ‚xÀ²<8ÖÞ,qÀ˜a zB:@Ø”üK]“@½´g×$ð`ÀqY`Åg@Ë„#2âò¿!1ΰtcÀUÏ?o›ÕHÀÅj׌±ÀwÉé[³­fÀx-ºl@¶Û¹Høe<ÀX5­mÙDQÀ|r7¢ô5À¥³0&Ò¤¿à?“9×ò>hIÀ,¾Ê®“(BÀÈöŽw€„@18ÞÄÍ]ÀœH4ªô9Àûü@±n¶I@™nLét`B@Í7rŠD:@@_첌À RBê)ùí¿Ã.þ¼Üh@Ë„#2âò¿©_Íd{e@_3çS¬¢-@y­Ý®¾)Àá8^‚œ=ç¿Äý+Nî4Àgˆº±Ê@­ô¨Èîue@„󸡻0Àh’r¼$ À”Húú  ì?ð?ÎÒ»¤ ’@lÐ8·fD‹@N·HZ~mÀÖëbK¯@[Æpd€—„@pôWÿoO’ÀcV§PƧ‹À„†ÃŒâ„ÀT8æCCH@ƃn²·ö£@›P´³‹öqÀ €†ê„w@;A0K~ÑÀmaz‰^tÀ#5 ÒO$[ÀJºÝN¹@pqm§ÃùwÀ8B+u}@}¹6û^ÃMÀVW‹™bÀyÅùÝëGÀ|ÅùÝëGÀ«epOè´¿ð?èŠáx?ÔYÀ´ß®0zSÀÄS“ì•@N·HZ~mÀ„Nf7vMÀ6‘ž\a2Z@Ìèr”ÈS@‡SŽ`áM@ôîHœÀÿ~hÆÙ·¿­(ªw×Oz@A…@põÏÇwä@þÞ Äܧ\À'qØlM¡@>|ܵ¹~@ì—1Ùiª…Àç¼==‚ÀB&š×Ç´~À¿9;!ê3@ÖG$YK•@üCÔóœ0dÀñG56jh@·ë©_[õ¿cN{OUXfÀ–-ôfPÀªr£¶*2@ÿ ÁìXÔjÀ"Î!mÈ o@)®&a¾W@À×YÄþzUÀ¤òµß²OÀ@»¡8-<À›5[Њ¢¿à?2ƒDCUtJÀ+¢[˜üDFÀÔùGq‡@þÞ Äܧ\À[~B¿BÀ=æë7;÷J@P§$u-³F@éÜÙ{áC@Þ‚&zhŸŒÀ€iÙ,@ÁŸÔª²o@¶ë©_[õ¿Ñ°®*)f@ÉXÀî«+@%.æȈ*À4©É>p@˜Ï -g?@¼—à¼c@±Löf@€²êQÄ÷1ÀoW?+E.À£íèÀ×|ìy·ÉÞ?à?ägG ó‡@_­fÖGs„@ùª§œú\Àô ºµ‹C¢@(Ísn)‚@eÂF{ñ‰‡À}\ ¢ç„À‰;Æ‹¿‚À3ñnˆF1@œŽ\ƾ–@'_Á“neeÀî)Òåh@ ™8Kéõ¿¥a”e6igÀ'—$#¶QÀ võnH[;@LÎXÙèdlÀ*öH,Kão@×”DfAÀk< "¹ WÀ*{ ‡ SÀ®Ž^šrz>ÀŽoÐÁ¡¿à?Ýmäˆ=£JÀŸßÂ#¨GÀ‘ïçΰˆ@ùª§œú\ÀkcÐÜnEÀíçöÅ:K@+Ñ‹'·.H@bøóyE@5 ?ƒÎŒÀPo°ê&î @>,ùÅp@ ™8Kéõ¿gØÉ}gf@€[#Oï*@¿›. GÎ*Àîw²­§?@vúk”cžH@Áø\cV@|ÃÂê?Vf@S¦¥-¥2ÀzI³âv1ÀùÛÁiñÀ8â#¾¤¹Ï?Ð? ŒÑëx@3VE—›Vw@¦ùyN KÀhkAϵD“@Iµl¶"Ûu@3ÚåàyÀ…ð}‰îwÀ›ëÆühvÀB…’@–(æbΆ@;XI½ªVÀf9@ÍdY@‡f~´”Iæ¿þÇ rƇXÀemJy›úBÀÜ'é2@6—Ï ^ÀQ@ÎPc`@Ê*ºxï1Àí"@c†­HÀôërDÀm¦)#s0Àýª.ó¿Ð?¬ünì;¸:ÀzjIÈ9ÀJ˜¾••ÿy@¦ùyN KÀîóé«ìn7ÀNj §e;@8˜‡®/¨9@÷¹p8@F(6a}Àx6:Ë@¢”Þ b@‡f~´”Iæ¿9ɳhi¨V@4hnxq%@ÓjWú.À„%:öÐ@@-Ü@@žcïFÔb@e‰n0Í“V@âæ/”ËZ#À–ƒÎæa$"ÀÂä  À~ýúBXÐ?Ð?÷ùÊ´)ñz@¥FI÷ñ—z@ù„Á” ÍJÀÖ´QcQ”@gNÞªá?z@óÎvÿF·{À|œ95[{Àº$Xç{ÀäXÊìºÔ@"Gø¡‡@•^£@XÀ ãÕàèY@cÜÇk>uæ¿2Ñß´YÀ£ñXê÷ŒDÀâ~/Õ8@§s{×5Ð_ÀÜ2s3—Ù`@ž¾%ò¾Ç2À«9ýSâfJÀ©×|ŸOñCÀC£ã º1ÀS.iâ!¿Ð?;Cý (°:À‹ÒÑ’ÇW:À÷½€Éú]{@ù„Á” ÍJÀ(’ãÁ‹:ÀõžRgt;@F8§û|;@áÔï´¿¿:@‹€Xˆ4}À º‰'–¬ @ƒÉÍSc@cÜÇk>uæ¿åŽØËÜëV@HdäânL@ê"ætaÀ”hóñP@ï³d½E@áè :JŒ@ êY¬ÓV@zUl$À>¥²¦÷ ÀX5Bè *ÀÃ[ñóP×Ð?Ð?ä­o+}@Eêº×‹A~@ä×EçåJÀYµ¿‚j•@é,ÃËv@Ë–þ~À<ɦüû;ÀŠMðÓ=€À l% Q‡ @fºòS;ˆ@X'ófYÀ-oVpZ@Mˆ€ÔJeæ¿I@ ŒíZÀÖ¦b7FÀæ|?@<[´Õ`À ƒ—\ýSa@é>¶_Ƨ3Àì+¯ùç5LÀÜi>¾Å®@ÀÚ/þýá3À„ÑpÌg—Ž¿Ð?ùäʇ:ÀdKïyÇ–;À;Ë¢]«Ì|@ä×EçåJÀ$•¼Åİ<À~÷Éò5c;@Ø(${<@Iâ>?ž=@w§Ã/‹j}À‘ܾõ[@™# +µ¦d@Oˆ€ÔJe濘úGÔæ1W@ ÑUx5b@Šõyé%±ÀÊHªhÕ%@™©#º7AJ@Ý@vÖ@#-m_åW@Ôhj@çá$ÀI1eMpÀê\Y*Æ[Àð5cZñ?ð?Ò”õêÐaŸ@tlÈ1/¡@i$˜qiÀ_ŒQ%H¶@y;3âÜÑ¢@q6B À±‹uSΡÀB v‰#€£Àðì9¸Ö@@±¡3k©@Û>š€nÛzÀê¦|aêùz@âÑ$ÇÀ· ¢3|ÀáÕ(úgÀ„Dú+vc@L›TvŠÏÀfÞ|ºÇÑ@(Y™9ÐŽTÀ ÕS6-nÀÎãÛÚwTÀÎãÛÚwTÀGµýôUᬿð?è"ñ ÿ:ZÀñ<…ëº\ÀÍ‘]Lž@i$˜qiÀÒ*dðu_Àë(þºå-[@àÞeÄ]@ùæ<ù¢L`@×ä»k•£ÀᓘS…8@§Ò” †@äÑ$ÇÀEÁˆÈzw@Ògd7@b<]c<À%éÙè`V?@­Ÿ´o@«GÃ÷…C*@LÇÊzZw@*ó‹µEÀ¾÷õêÀN0À¾÷õêÀN0À2k`»àñ?ð?ÿn‚ fç @ZÕ] }£@fCwá{!hÀW-ÛÖÁ·@øÍ=gÞw¦@¥ìcÙ}•¡ÀeEóÔÂE¤Àñ"ÿC_§À@¾fy~˜ ÀOÙð.ß_ª@Ô«Á_|ÀÜ':ñƒ{@ £WMxÀƒé×ë„}À&I{ÔiÀw8H9õ–g@G\’YöÔ‚ÀëÅXtðQ‚@^âY5¾{UÀlÊK pÀºî„¤GîUÀ’óÌÝÔ «¿ð?bëR!yÆYÀÍÖoú]·]À[H2ÏÝŸ@fCwá{!hÀR‚snB!aÀ65åÄíÏZ@熵ié^@I½Ç‡­Ña@vbÍßÀLú‚a>@X¥ªf‡@ £WMxÀÚ6HF×Åw@¿ó=)2Q6@Érõ\b<À“E¹’þtB@xƒ]% r@ 9ŒBÂ×+@\be¡w@D°ë:ö“FÀ¥×SJJø0ÀÆ‘1ÁÛ?à?:ñ\9€@•*Ȧ³Ìv@EAö£VÀ—Ý䨇åœ@øM—z%p@N”8¤h€À®¥3ÀUTêìË?Ð?‰±Í»`£q@+­»FF3j@\¼Ø3FÀ>ê!>Ž@>éK—uc@."†àqÀ1O®0ŽjÀ$ÚÿÔ ¹cÀpøïÚ¬½@‹¹‘˜‰Ìƒ@ª:‡m[TÀ¹˜XÄZW@™ ¾Ä Ü¿vÓÁ<TÀÎŽðuàá=À•ÿëf·ùô?•ì¡1¥ZÀ¤ÍB33]@T7t±-À ½t€#;BÀÍùÌéb'À^Ûæªd7Ž¿Ð?™›+Å$3ÀH>‡?¿o,ÀM 'Ó›Ÿt@\¼Ø3FÀ°CQUÆ%Àcãtp"g3@ÄÄh¼SÒ,@4>¡×ýg%@»$ótÜ6|Àš#íy.ÿ@ÿ{Ó‘éÅY@ž ¾Ä Ü¿!Ÿ—i –U@&HÛ®@Jpû18!ÀòõUq– Ü?ö/Bðo ÀÀ×h›Òc @Hê.tyU@PÂXÔš»#À{¢nBš ÀvRß¹Çì?ð?~ðšÒ'“@Ï£<9Ž@Ä•V_qeÀ<÷èn&°@;ÀDÉ•‡@ ã›òÝu“À²žÒh±‰ŽÀɦàõ‡Àvy7,0@5Óƒ[ n¤@ÊÛz¢ñyuÀh¹œ £Èw@,åK¨^ý¿;-þeuÀç‰ o2H`Àt¼5ñ°2@DÍ(Q|Àº1Ó-<õ}@ÝÇîfNÀÚ¿ï:œcÀ*t4Uà>VÀÌã’¢¼™¬¿ð?ÏÑ[SÀš@ŸÁøMÀ#|`J–Á•@Ä•V_qeÀKæ»w(„GÀI¤f^RgS@(¯_BÞrN@ „ÔøãG@ƒ"Ó˜aœÀ¨1@h6@–lûð|@+åK¨^ý¿4Ej+Ïu@D¤ÑØ4@ªµí~AÀºØÂ49ò@ãy«9G3@¬¹î,fi*@`êòÅ®u@Ó}ÆlDÀ˜|Æ#Ó:ÀY½Øoè§Ý?à?ÏA<¼(È„@©d~Y7@Fí,¦¹TÀj¡@ÜŒÒO†|@îKŸ§¦*…ÀâkÓQñˆÀÔu Ê }ÀðŦÍé@ž¨“:ß•@¶ðÉÎ]¨fÀÞrÇ Vü!@ò:ÀÄw}rºNC@µˆwZý?@r&Ì•B€:@“°z›ŽŒÀµÛ–Š*B*@¢ÔQU{n@vm#·ÓÔí¿OR ¦V f@ òã¹›ö#@ÊCò-Æ1ÀSiŽñþ@‚Ïb6µ:@¬)T …@`H÷}æe@’°ru!$5Àˆ÷SÅãÜ1À ÕÍ Þ?à?T‰w×…†@<Éu¢°ƒ@»‘D„ ìSÀïì˜à?¢@dpEm£6@¶ÁÎ'ç‡À=a8B7„Àk¤B¢°”ÀÀ­‘JaMø?rcB¸eÓ•@|Üß<çgÀêGïÌwµh@PVãchúí¿eœ¡AÏgÀdÆ·v‚9SÀŸ7Ø@o:@?;×9oÀ²—o@îg¬@ÀÖmÈ‹”˜VÀèÿX剥RÀÍan’‘F™¿à?¨ü#ö´BÀòbp›ÞY@Àe«º¸/ˆ@»‘D„ ìSÀ9 ÉÙÄ–<ÀÒBÄlKC@ýj‘5³@@|¶áù2=@©Yý½ŒÀvâ㌖.@XÉW!up@PVãchúí¿P2€ôGf@¹šåý»#@! ÿá2À,ÀY‡›@1Œ"IF@H§Ü’¹@8r®] f@ÊÓGä5Àg©¸4À¤÷/Á|ï?ð?q¬EwIb˜@›÷ùzû{–@ïD/…cÀ#)ÀÏF³@{"/»”@Û•ëªú˜ÀEïç}—À „V =•À@ŸáfÓ’ÀXÅ£aÖ—¦@qÉæì6yÀ‰¶ðȪ3y@õ‹Ë«XÄý¿º «Ç-xÀKý­ ÖdÀ ¦@)R@«ö)y€ÀêîŽZñ;€@<ù9›ÿtQÀoºÞO›5hÀ“óP+!#dÀ6ïù§¿ð?ÃüDì"TRÀRú蘘æPÀªzØ{™@ïD/…cÀ7µÐõ+OÀ¶˜õ"­ÆR@ª£w6PQ@¥e¦ï×íO@OȪ5×ïœÀnÂó훸A@.Lô«Ì³@ø‹Ë«XÄý¿ÝrÀˆv@–#‰{”2@S\Æñ¼^BÀZ¡2t^n3@tP« Ô_@h4'Á` .@ZO_w\v@Þ‹Á‰5®FÀñažsúPEÀ $-©8ð?ð?môÎÖ^š@íØ×E­¢™@€UpÜú bÀýçtñ§ ´@¯Ãë˜@{3³ö›Àš_|±–XšÀMê‡všœ™Àxx §fJ*Àùо KâˆNQ@w÷^Û;$À;0¡5"oD@( ƒ­ú‚@ÒrA‰(ý¿' o’”Êv@Ià.k÷0@ÌÖµM°BÀ7=š_‘¥8@œ[±\d@œÂ™4w/@ý̾ښv@ïäÕ®GÀZʰ›¡äCÀ1àÐi„¶Ð?Ð?Ö¹¦µ||@ìÀ.}@ÂH‰9Eõ@ÀføÎMß•@¥„&%å}@¶ŠW¹`}À5—sKV~Àt¢}×nÔ~À¨7‡Ê†ÀþÂ#!fDˆ@ä“9è\ÀÌb7K°@Fõo£·WbÀ´«>qÇ)a@h_$óf3ÀÓΈÅ°KÀÞ4æY@ÀíÁÇþ„¿Ð?ÒR4ħ)1Àœ‹]ì”1ÀlïêdhD|@ÂH‰9Eõ@ÀbƒdÏ2À Xq³1@:Ñ#¢¦!2@vÎ~7ù’2@…ÈnÃ8[}Àò Bu'@ܶƒ–,Hd@Øìœ=ÇÜ¿á*á½W@R ã¨@x;Ÿ'#À¢KzIg:@̪û*ÀH@`ã˜Ђ@$wÖ’ÛV@#„Ö‘Ô_(Àœ Bú À9gå8Ñ?Ð?4è×Oï¼~@zsà}•€@Ì€ZŠ?À”(Bo@–@µ•Tå@/´xŸ·ÐÀ w"H*À5œ¨…‚ÀÊ+…ƒ&j À‚wãÍ+‰@»¼&˜WŠ]À;->ÅZ@J»ý%uœÚ¿Úx7;Ì[Àš@ôÄEJÀ¯ü@DeÝB@u€ZcÀxJ7Öl¦a@·$ø=óÿ3À¶pÃoMÀÌå—–®4ÀpÄ~81‚¿Ð?!É„31X0À™NÑ õ¢1À~"’›Á}@Ì€ZŠ?À¡‹ÉÞ3Àb˜åÕê0@œ;u1A2@éž/Y²3@¸g­Ó”}À‹dÊðÍÐ*@º‹‘ž’že@J»ý%uœÚ¿€y˜…WW@âø´¶£9 @±Eœbä`#À{:Æü"@µƒM@–“žl‚[@~=<†¤W@žê>7rI)ÀŸ™Ô6Á Àâ ó2n½ñ?ð?ªµ¸Û% @-fÄ»gÑ¢@A <Ôò\ÀQeâàn·@ì¸6@a¥@8ʹ5¡ÀLôß—…£ÀOWLSú6¦À`ß…e FÀšðÆ…ª@â$±¥ÀT¬Ó€@O{@+mPdŸø¿xQßýš}ÀN¥ØËIlÀqÚDÿèf@øE „h„ÀÝcÒ»%‚@äár¤úæTÀÑØ<oÀ×ú¯pþP ¿ð?+@k³NÀ-1=ÿ³pQÀCQ±dPŸ@A <Ôò\À‰vˆÐSÀÜ­sÝRæO@Á°x R@jP‹Yœ–T@2L‡EÑÀ¼\F _ˆN@ø§,‹ý†@.mPdŸø¿½í˜Vð¡w@•Ô‚ü{*@ó/'ÝÁCÀ`{d÷LE@Tù^B‹0q@¾7šû®F2@~ZäÄ dw@mf¢K?JÀU˜»ŒÜý·?ð?P¼¸ÿSï @X6Ó¢L°?q àó2A@ÚZê cP@ÀÐŽ«Ä|T?zbâ›úë À8cMG‡J°¿ÒÓô^zT¿ær¼ºzs@ÿv”ÎÑ%À¿iMºa4=À¿‹/N5§º?ð?ÎH£gRÑ @k[q²?*^R¢ù3R@²µ¾H 3A@Û’i÷¿ÃV?¿5¶™Í À  a²¿ ÒaÏÀV¿‡[€û%À¿UMfØÍxs@“âkO}8@À¨8îIÓ›?Ð?5Ü·Á’ðò?òLüæ‘ú?eªÂ%@AÓùbÈõ¿H.…ö¶G¿ŸòwK%Á¿KÔ®ÃÀ\ÖÀÕ À&†ã潓S@Kg¯0½0¤¿¬H¥’!Àü=¦¿§~&@|ô?Ð?ÐFãÉó?Áìõæ‹RŸ?¿Ø5£A6@»¸Ø?Â%@™dÙ8ÊH?ÿj:TºÆó¿Íebu‹MŸ¿ÐÑŸØÆH¿*Û( ­Åê?‘çuŸ¯hù?ñ £g:@Ž´¯Rñ0¤¿ÏJk9õ‘S@¬SÝáGÇ!À ô›O$À‡+ôl_²Ÿ?Ð?/rMÏŸú?ñyÈNîþ©?ém‡,ß*@¿mʃ]ó:@è bY?6ìûì™ú¿A`êù©¿zÛ@ª]Y¿Eµ5“–eÕ¿ È6ÀÓ”ë3À»ß<Ä­S@â“æÏèM¨¿wèQT,}#ÀWþ‡0£3@Ic|Ç_Ÿ?Ð?<ö§|wú?~G·¨HØ©?!q LË:@€»ŽYß*@Ò{+ÕÒ“.?ÀðqáôMÀ¡§øaÒàs@3µ®%rпÜuþÍÓ’HÀ©ÕZvY@ÕE³\s~ã?Ĥí%J@µ(è8ýª\@ÞvWΣ?Ud .ò#ÀÏS|Ãwã¿aó€sG£¿Û÷ö'} À8ú„è†5Àœ7n> GÀ¾K—«d@øà6ÿº³~ ÍÞ=ÀÈ÷Îk$Çk!Àš'ƒB1á¿o`ÞÜÙ— ¿¤CŒ»C"@ YE:¤“7@°hÀü€fS@`Òóhÿ®zÖd@fõL(:Às‡¦sJÀ„çS˜çÒ¹?à?>?ÖºY)@S{€º_Tì? ›¢/›±N@À&Oº!À`@ž 6a«ý¯?Ò…–ÏÆ )Àp*¢ Iì¿ë·vñ¯¿i СDÀ8˜KÄ97ÀkÎ(JK>KÀÑ@„1d@C„\оçÿ4¢ÈCM@À¹‘Þk®?@åW@J¶?à?Vîæ o%@Ö»¾ 24è?º@_Fd¦\@âÐtpê±N@S˜µýT«?ƒÑ]êÞf%ÀÃVσõ*è¿ÿ~J«¿ö)€0%@tå,‘z <@,HÂ×°V@&¾âïñçÿÂ%ÊK0d@f˜OáÖ;À‡þ¡¦*EÀ¨ ¦E®á»?à?bUakÿ/@6þä-#ô?~Y©¯×Q@úëlcc@ðX’£Ýº?bi{ù/Àz„ ½ô¿¦± Ðî º¿î,êp oÀÞ&Ôaî8Àôßü ºŠOÀo6WU‚Md@Xn0§!Ä¿ZqfíвAÀQ¦»k P1@§\·?à?¹³[à *@Í`èá àð?ÅKuUE`@Þ ŽQ@ÂÅ|N~Þµ?ƒR"ö*ÀIQ:ŽÙð¿ G½‘TÕµ¿·Gz^#¿'@$ß$A@[dzÊýY@ã¸z+Û!Ä¿hq‹ËHLd@w…(Šû¥=À²iâ8ÀÛ^Äß!ö­?Ð?e.`8#@ ê\|ì?`[ïC@-xJ*@V@ï%jñ!¹´?“Ç‹”ý"Àn¯»ì¿"ž˜¸¯´¿^¦ð€[CÀÈï"B†0*À‚ ŸÊ§ùAÀûÿgÆ4jT@Z€9K‘³¿%¬g„p 3À*ˆÚvÜ­¨?Ð?sä×'!Z@¾$t1Q#ç?8D^R@õÖÓGïC@:ëÏn±?Íh«äKÀ`QiÏç¿8W­ ±¿È&¨ÏÄ+@4Ùèä3@ýèã¦OM@À)ο}‘³¿†ÓBÞhT@ÐK €/ÀñšÆ3¶?ð?Cz¶Ñ8 @®BÝF;²?º?á¢ÊB@ú}P@8KÇ\¯¹X?ÚÐW¸$5 À7ƒ°)µþ±¿Èq 8¶X¿°©J‡0B@{Œ#uë@Á3,9E¯:À;ô;‚Us@ó>ûægà¿¿ø¨JØÓ:À/¹Ê7^G@!(-ö~2¾?ð?c Ö@æ‘]~¸?göÿû¶U@¢¸3ùB@(õÛmÑ`?DS‰ÓÀPà ¥îz¸¿KqìTÏ`¿vUó?üD * ?å…ÎÓPÏ&@ Y€¿FÊ4@ý)©(~K?ÛMV 󿨮A¾Þ' ¿² *yyK¿ŠV}/Iàñ?¨ám€õ–⿊j!÷‘$À4òLOnS@ª9»bB¤¿rco‘À 0n~%´&@ 0n~%´&@ó=çEN ?Ð?¿o>Ì‘Ú÷?¨¨êålH¤?rدõC:@o1G¹‹Ï&@Ûê‘ ?Q?ÄmáÖ÷¿ b,÷÷D¤¿*òF0@éF7.@#,@¾UÎGÁ`?i_ùI5ÿ¿#Å­„²)°¿)(úß½`¿ê@-ª~ÿ¿Œ¸—@ @+ ­z="@Ïã58á9¨¿ðl ‚„S@›[õÔ'b%À!ã˜õÌÏ2Àß÷ªÅ%ÀĘՠÆÙÀ?ð?3ò¾Î&"@t[~tlÖ?XvÑnQ@ÔÁ¢ZÒ2`@~Mè¦"ä‹?'oHÛ"ÀWFö}gÖ¿»¢·‘}Ý‹¿¬¶wÎ…oÿ?‡¹YQ;T2À(œÖÉQÀù®[³ s@Và”FÌ¿ï/°Ox«DÀâ!ˆÂÿW@:¬UE@ÌmL×ÁÂ?ð?“y=æ©$@ýq`Æœ÷Ø?Sñ•Èb@ÇÛn^;Q@v,÷•?Àôæ¦á $À £ªñØ¿‡?$‹ª¿,Q ˜µÓÀðy² @l5@åpzÒïN@!,@•\FÌ¿œ.iäs@Š*‹bGÀÛSYÏãXÀmƒrÔFÀÜoW%ÎÂ?ð?**u/Ü'@ØQšgé˜á?U3vH¨AT@J#6êc@q™áàíô™?EAcv Õ'Àç7”Ὲ1éWË홿  ”~Ò?"M<9À299ï±®UÀvL7!_ºs@a… ¤aп½1iRÈ/GÀªÃ÷þÊÇY@"6Ƙ՟D@DãœÚÄ?ð?R£Y'c)@´øÐEB¹â?_™a€´ìd@W¦%–ÜAT@ÍýÃÇ@ž›?ùª§â,\)Àþç·´â¿ÉqU©–›¿*‹-4W=ÀÜðNùÂÔ=@þ(|ØU@^6ÿŠпÿ5ù)¤·s@]«æ«¨HÀX†jKÑs\ÀßÑîÕ ÃFÀyñGŽÇÄ?ð?ì“gÄ>í.@„w Áê?ÚÞ ÌW@êÂa‡g@%k %§?—Ž"”ã.ÀE;ë8¸¸ê¿/ŒÌ§¿èˆµ©åú¿«ïÍHEa?Àø×§¬YÀè}áÚlÔs@+.9%í¦Ñ¿§Ç…ÛNÁIÀÁ‡[7àX@Óâi’æC@BiUìdCÅ?ð?aþ‰çø§/@4!Sçbë?´ÐA–kh@oP¨QÞÌW@¹º*Áۧ?r¸ÂØž/ÀëÛ‹˜Zë¿«Û^©§¿ÀeqÿBÌ¿GKòLoC@NMO¯“@\@¯L^¹§Ñ¿‹ÍÊÑs@r¬/ePYJÀ_…ÁïC]ÀÑÑšŒiGÀ×­,ãƦ?Ð?ɱ’ph°@Sä¦}ÉÓ?}Þ@ÖÀHÀ%„¡¬:Óª?Ð?±]Š@6‰P 5ä?°Ò_ÇU+B@ÆÊ¿jÌR@:©ÞÙ„½ª?è`<e}À $5v,ä¿ã $h)²ª¿^J@ìèÀ~²Kƒ~&ÀmóŽë!CÀøº-‚%T@zèL"Ù³¿J¤xºPå0ÀÄ[¿¡!@Â[¿¡!@7µ¨ß!©?Ð?S7ð¯ž@Mµ<;¹ïâ?þ‡¥£žQ@î h±„+B@½‚Å1©?m –!ˆ’ÀÛ8™K®çâ¿ꯗ`©¿ˆw e4ù?´<°Ò}1@|ü*Ì;ÓG@ÙmbRÙ³¿EŒ¸”#T@=±È}¥/Àô³hbèq)Àñ³hbèq)ÀJ~tœâ¼?à?rð8†q«2@<º®ge ü?ü?½RЦUªê¿JCyv=”¿>_´à¹>¿È(jë;Ð@Þsã÷Á @Y®:¶Gv*Àg»» 1S@ÑÔò¬•ž¿éÄÅÀÀ,Ð?œ4@É´M |Ø ?Ð?qþ»àÍÿõ?·¸D"IJ ?  US·9@êÜbDâ…"@Ï rpYI? í6lüõ¿äR€3° ¿¦”ôŠUI¿¢·÷ú·ŠÀ½x3«i¿>®"×À­"¤e•ž¿9˜Å~:-S@£`åº2$À3ºž<2ÀûàÍÅ1¸?ð?°“χÕ7@K­§?¯¿Á?nã:ƒG@ ¿”T@ˆÏ7Kdp?î™Ã`N4À±“¶%m¼Á¿‰x3ãHap¿XŸÏÆL‡#@\{£@â0t/ÚPÀÍH¥Is@ãÕi°yÿî$ÕÅ´(=Àå ½ŸçF@È|E1« T@»\N Â?ð?ð7Ö¯p¯@>oy÷ý}Ê?œÒ ¾É?^@bœ°3PG@¸êØHxwx?åW²Ÿ,ªÀÄ{†ø yÊ¿ªJÊyúrx¿À9  …9À4GÆ™M@ ¼i”ŽÀ{Ê0³âyÿÿËgŠ—Es@³ÒÁšÀEÀ-ïÔqEÀHчùúÂRÀç¥wHý›?Ð?øcÔÏ€¶ú?Ëóô•¤­?Jb¥T¸-@Îõ\{©Î9@ ñ)Cìq`?m+r¼°ú¿i£ìc±­¿‰ƒ€a_n`¿öëϰ׳@з):0‡ñ¿ +aÄ‘4ÀQg =bS@m\.s‚©§¿¼~„ó À9úÈìu3@9úÈìu3@Š”÷9lE£?Ð?þ&ûÉ­e@C¥°Äëi´?46ˆ¶Ã¡A@“bL -@Ÿ¢û¿¦f?ZÙµaÀ·Ùe´¿ÔÙ­Ü¡f¿è—:7ÍÀ¸­x·Q” @vɈn…Ï@¦Ö Œ¿©§¿”ÓC^S@AÏrÙ‹V'À]f®pïK3À]f®pïK3ÀÉöKÒ¿?ð?xR*âM "@ K6_$Å×?s‚?‰xQ@³§¦zŠÂ_@€’ãÄšS?ž;üwÊ"ÀKøÎ¦1¿×¿)FúÃK¿>$Y"£@œ»9òr(À†¡”§C_XÀÑ]Êa@{s@/'Éqj³Ë¿Â–ðl¹^CÀˆæ {îAX@¾Ï'`òÝR@Ì éMç€Ä?ð?qÆÉÌ?'@Kª¸ß£Þ?Ø^ ,cd@õ]iã¥Q@@X ¬·0”?´÷Poû9'À¹¬_°4œÞ¿þ#Fª+”¿jØòTþš4À ®õ»cØ5@»%åÚ{fG@:œAø±³Ë¿ú ÏçEws@!ÖTJÒôHÀ jÂñÛ‚YÀ|6—ŸŽ×SÀvç­—€ØÁ?ð? â¿ ”Ç'@ÆÙÅkâ?ì¼QçT@ŸSDîý:c@VÙ¥ªˆœ?¥*NjÆÀ'ÀdöQ¾Íe⿹ÃêÜœ¿ˆ=ù… ¸@Ã]ÎEnX3À8ªÐÖ¶E\À5|‹_–”s@fH9GijÏ¿Ò þ^ÖEÀº¸%»Z@µgš¨BR@öݺ¤Ñ¿Å?ð?=‡v^ý,@}Tø%tæ? Dsûfg@ÅžJQçT@Áïä’+d¡?2iú#õ,ÀÎ&¹mæ¿Ã€BÄ1_¡¿\Bæbˆ2À n$C}‚>@i-…¾¨ùQ@† 9eºjÏ¿»‘ÀK§s@EüüX»›JÀúòùæ#]Àâö®ÑíeTÀصé‡Î̳?à?Jÿz¹@D‡*¶Û?{ /–ŠH@ßVf÷V@å^Tcþ˜?]½ “¯À<µH+­Û¿Í¨ƒQö˜¿øºè¹N:ó?­I5¾¸)Àû†"PÀײa{K®c@©ÍaüSMÁ¿ù,}‚åZ8À·Èob3I@šd ø£A@2#?·?à?<¸·qÛ!@”vý+à? †i׋¬Z@†AÕŠH@66 ?~V.½Õ!À ~Xøà¿@5>;¿<ȪIÌ• Àe¼˜æ3@Yy°-GH@Å-©€MÁ¿/î~Tqªc@–"ÆÞK<ÀýÔ4!YóMÀKÈqÊ$÷DÀ¡«8,Æ¥?Ð?kzœB‚@µÑÄ„kQÔ?!ÜêP}<@yÌ~·K@Î5a5,)•?Jו<{À+º…èJÔ¿¥êOì!•¿‰–—Äæ¦¿toÃ?TÀI¾&õ.BÀ£s nÈS@4õ„„²¿³æUÌì*À,éºÝ5@cé˜üÉ1@}Âc/EH¨?Ð?íÛêbÃ@’3V1|ªÖ?U—¿«8N@äóâyš}<@#â²t+›—?hé»À©þ/S¢Ö¿ °Ì«’—¿®1ÓfíŠ ÀfãÚñ¸Þ(@ü?M Ú›>@¨‰a賄²¿ÆRƒ×®ÄS@0¯ß¤Û.ÀˆßÔV³;À…X'N‹5Àü¢ÎºÄ·?à?/ë5Ÿ!h(@ÈW¬ý•!í?Ò˜9-å`P@'3@p¤_@³Ñá“b±?yb5{s^(À|J´'í¿$,°®[±¿P-›džø¿§w¥B2ÀÕɺ€HTÀE’¶Kãc@Îï([9ÿ@EtAÅá{R@QW-ÌŒ9ÿ£Uxëkßc@.tFÝâÇ?À€†É‡"FÀ€†É‡"FÀ‰/e2™ÈÉ?ð?r’OQ#>@~*|ýx@Ûh{±L­b@çÏH"¸Mr@â»R`ÐË?›ÚúL>À<âÎ &pÀö¶:]ÄË¿è6Ç…~5À“À³hDÀ´ÍM…ofÀg/)³>þs@Œ2°g_FÓ¿Í3Íî„PÀ •ðA@ôêòeO@>•¡·{ßÊ?ð?¿WÀç;l?@•¡W?lX@ßc$ds@ÎAë|­b@¥3îÿÌ?]ç¢Ò©^?À'9kP4OÀ#ßhóÌ¿(CÄkß 'À÷sÙ&õèQ@½w #­e@‰Š,‘FÓ¿8ïœûµús@¸ù"Ý—ÊPÀÝ ‘ŃüIÀ¾lßLó¼VÀJ¥¯ïÑ»?à?3+ˆCþd2@¢ßØ“ƒEü?¦Â}ý6%U@"[Æïe@1‹Ù‚Þ¹Å?žaãzq\2À1#‹ƒ_8ü¿{É}Můſ8=·ºÀÇ ¼Ñ¤5À¼Ñ˜2g¤XÀ÷2(Þd@jÛ_Ô¿ߤØB]|AÀáâ]N >@ )#â0¼?à?chKš¥2@AöBßШü?m» µJe@ºo¾–m%U@5Œ„6.Æ?¤àÍzïœ2À½xç¦~›ü¿ô¤ÈˆñûÅ¿n#Xm¯]À«·ÊWéD@ÈPÖ2ÚâX@J³û(‚¿ÔðÚ›d@.MP§¶AÀ#}Òƒ¶ZGÀ:Å2W%±²?ð?(<>, @ü\¿ªö¶?'–ø"­B@ ¯'ÁSP@~>(u#hc?•/Gw' À0‚cÆò¶¿@wøkÙdc¿s’š"lÃ0@ŸßMǨò3@£¶Q%Ä®SÀ¶,Pë" s@ÈV¤~¼¿ßÚin=@6À ‚/HŸ³Z@ùE= |‘Â?ð?SE"õÿ@”˜8ËbÑÆ?*a;º/^@a®Æ1S­B@ÓÀ¼¡Hs?ÔЉ¥aûÀ‚ÃñÀ„ÍÆ¿eZš ]Es¿¿þo¤ÿDÀa÷$°Dñ¿Š‰˜ìäÑDÀ/X 6Y~¼¿Mø¼_s@1VC•mFÀvFì XÀˆ—ºÿi¶?ð?NY¶M{@A—)ú÷¯Ã?…n¨æÚG@Ps–ª©T@o„Ñœ0ås?œL.×mwÀTu¦¡ ¬Ã¿%¼¥®;ás¿-k»C¬.@ £èž=#%@4 ŸÆÃ?ð?h€û³21!@-艬_Ñ?Yuza@Ÿ§Ò@$ÛG@a,u¤Ž?¹EeÇ-!Àgöü7\Ñ¿ íJ&‹¿(¹1WÄDÀƒQé/WB@Îú¿á@1Àss>Žgw¿6,b^ s@¡Ê‹½¦GÀöùdSÐúEÀ6™Ñ]*ºXÀ ‹x[,ª?à?å<ï ëó @ ­‰§"À?0²T ”=@Œ¯»°I@ž‚˜§Qs?¢æ´í ÀúåæïÀ¿ò–k33Ms¿D['ïF@žéPMû¡í?¡b¤KÀ“¦3²½=c@uAOK´§¶¿LðÿÁUw/ÀC^XiZ¤C@Åq‡AI@\…7ÐHþ´?à?øbï_= @“ÁúÈ‘äÉ?i˜Â®…T@½Ë2´Y”=@ê?¡ôk?ß`·Ì@›Àº¡¼U™ÞÉ¿{ ïEù~¿šÛ|ß13ÀÖwÊß§@¬ÓhÊò @ur€Êî§¶¿Ôei®8c@7Oh <9À®!“ÄCÀP+½·iIÀg›É¼_÷½?ð?‚Õk‡Õ"@H ÿè&zÙ?]1¹kîQ@`nNÉ8n_@ÿqà é‘?ü "À¹<ÞksÙ¿ßT–Nä‘¿ÅäVNüO'@tùVA¯¹À4çáyØ^ÀFá«cpVs@"”„Ž¡©Ê¿ [•~åBÀœÔ >¯X@œÔ >¯X@a‚«9Æ?ð?‘5-ã*@æ”/{Çæâ?AWàÕíùf@äðšîQ@£¹/ÒE“š?‡¦zÇýÛ*À®`(Éáâ¿'5ý‚@Œš¿ÆW‹7BÀª±CãÀ6@Ž“ýÔ?@\J·fæ©Ê¿.«úÉUQs@!rä¢ÙJÀ$d0«ZÀ$d0«ZÀq¤×â æ ?Ð?!“¯ íÌ@ÇÁQ@æ{Ã?e¦‰©Ö\5@®ÖÊóB@­ö’Úæ?ld²2ÎÅÀBP0þvÿˆ«ŸÝ¿—€1†Å@¬­c Û À0e<Ž-`AÀre„ÈsoS@ éç*äO®¿8E”ýA†$À‹TáMŠa:@Kÿ}¬/¾7@V5Œéwx§?Ð?8>ù;€ˆ@§î3ÅË?1Æü1 J@^jÒ ]5@kkÈø(†?ÅL ùƒÀÙ–ãû« Ë¿›¹J‘W"†¿ÌÚ¢tj!À2Ÿ[Ûþ@;±Ã D,@Ïko2P®¿Y¬¿J^jS@+h"Ì,Àròô%Î=ÀµD@)"Ó:À·8ß!oÕÂ?ð?5ÈMù½¦.@EæKoþì?ÂøŠgY@ZB=‘f@¥ÇZQm«?äÙ'myœ.À Ïâ¸ô쿞·[âc«¿Œ ú D@–*÷ó4À(@K˜s`cÀŠ@ÊÓˆs@uÂÿ[³Ð¿Àÿø-þFÀΪŠu”ƒY@S3clöV@ñ‘±lúÈ?ð?(·/C!4@„ëlš ó?¢Ký9¡~m@¥L”1ÑY@À‘÷&²?2&ê„4ÀFŸ€9ó¿œdE‡úü±¿¶±K›®@Àr*yáêCD@ºÐÞ†UT@:©: †³Ð¿uw\уs@5+íÒà.NÀ›,´Æìœ^À&(¢;[Àpº¶ÉÄ?ð?Êt%ah3@¨–›”Âõ?R‚÷ ]@ÿ´Ÿãa’j@"¯'8Û¶?eýÜ.a3À‡ÎR€òõ¿+ ‘½Ò¶¿Ñ“6Aµ‚@¯687sõ9À×<’bmeÀ›àž¢s@[õŒžÙÑ¿x>óÅ$ƒIÀ^5¡\E*V@^5¡\E*V@š"K£Ê?ð?)ÿÐH8@?iˆª”Zú?/‡×@”p@_¸B!]@G ¥}™¼?u¯lÎ?8ÀëêÄÎPú¿Füæºá޼¿$–+Œ´@À_Å÷ÎZI@FÑ bÐZ@ÛD•&ÌÙÑ¿@ïò¹s@Qð˜©CçOÀaq¸K\Àaq¸K\À‘yrOæ?Ð?˜¨JÅ8@t¼>•õÝ?ýûFŠÀ½@@é#(úCúN@Ï")‡¢?qò­Ìí.À² BòhéÝ¿mêaå¡¢¿ JŠÅÇ?ÆÆU*,À”•F£R‡GÀÑïFEâ¼S@ó=Ãy²¿Yîq±,À½~uQ›0@«—™Y5@™³¾3/J«?Ð?Wý½lâ @)îùG@÷á?hXMÄ€ŒR@´"ZÄë½@@—Ëų8¦?…­À`/f„óïá¿ÜÍX¬/¦¿üü^ÛÀ+o1³Æ.@ØÚÌyh@@{2ÆÑ¾y²¿eÞr<$¸S@å9°Õ±Ô0Às žZ?˜6À¹Ÿ¦½ã =ÀB¸èW¯Á¸?à?çPÔQïØ-@¥­Ë–éô?ÒˆpÞÜS@¾uŸæa@7PÙ„ðM½?ÇbSsËË-À¿$…éaàô¿—ßm× A½¿(P{½ÅAö¿E•žÝئ1À‹ŒñI¡®YÀ£¹ç±×c@´ÛËn¿Uf çp¶>À„bPöª<2@ÓnU@„D@Ø—¼?à?äMþ=1@ŒƒK)ø?ÐNrIæ©d@ rt#S@]€;!³íÀ?¤UöEg61ÀQaÿ§ø¿åRŒ??æÀ¿¦´b°“Ó-ÀñŽí+EB@ÌL€ŒS@¼0b@n¿]ä)´Óc@c¯åÞºAÀ¤,rv‚:À–!r@ÅÒMÀzƒ¢w¦Åª?Ð?&†Û8/"@åawtñµì?Ÿð2N#—E@ÒV2…T@fE6ÄDª¶?còå£&"À}Uõìe¨ì¿O"´d“Ÿ¶¿ˆÍ¶¤–ú¿¾ÀËŠ_#ÀB%²ãKÀÿÞµ óS@Sò8‘䱿Š!è$ ³0À«ù¡êª3@Œ µè­?Ð?o©Çš½R$@{ÐJŸ3 ð? àcÆ_íV@²ª› [—E@ø‹¬ ³T¹? 'I$ÀGñ¡ð¿tl¹Ì¿H¹¿É¤ÕôÀU>ÂUT5@kƒXÀ ´F@X¹ºäޱ¿¡m34µîS@X\Ho¦2À× Wïœ>Àˆ‡¬ÐLø ?à?TÙaû?ÕLª?y a~g‚2@ȆBs½Ý@@HJë”X?Üý„‚8‹û¿çm`lª¿ »pÚX¿»¼¦xYß&@íö@1p*@øI°ÛwJÀ«uߨéb@üŠÝÙ°±©¿ áctå $À%¹§ •âM@©²÷)jD´?à?fJ­w@Zi².¿?VQU‚˜Q@çÄ:I—‚2@wöT]m?X?-btÀûÂeˆ½¿¿%ÿçyœWm¿Þý0AZp<ÀœN»ŽñÙë¿èv;J®;ÀïÕÝ1󱩿Sab#äb@qA8Yðñ7Àlu:IaKÀÃ\©»¨”?Ð?êd•Á¼ó? Ãë¥?¯î3à'@Ì_îŒ5@´B¸uYX?1]η󿞉Sg祿 ûú¼2TX¿‰îB,@ÇJ¾›Ÿç@o§è¿àª=À±3»S@kUG¡¿<#Dä‡À$/¶ãÙH'@íº£\=@’ÖŸy¥?Ð?úÞü}…@ž3d³ƒË¶?¾L©³RD@!¾pà'@É54Ri?cDÀ¤õµ–ƶ¿£`ôƒ‡Li¿_¯C“s¬+ÀFó¸Ï"—ö?noú¯YÀæ%`H¡¿Œ™±ÜÉûR@<õŒ} ~)ÀJ»9€&ÀjfÇ <Àïàbý¸`¨?à?Ìf-T:9 @„ʼŽ"¬Á?•÷ép}È=@ž‘þUÜI@BDhÃñv?^QO€2 ÀÖé̱ħÁ¿\kôìv¿7u«ß2#@œ=qŒ  @=†ý{²PÀ^OÛc@©C¤Ø‹?µ¿éH(-À•ÉîÑC@gãŒ0>OL@ðÆY° ±¶?à?En£B>Y@º{¤|ŒtÐ?8ç,¨YÌV@a”ÐWÊÈ=@ý¬;º9]…?^àO×úRÀgÝ{pпùìÙWòW…¿ùu˜Ú±ø:ÀÆG5Ú5@…BKŽ÷ À>âµÂ?µ¿?©€PÂc@…|gA;À™Çžg-8DÀ¶A¾ŠâLÀS„øDž"œ?Ð?ŠÆ*ßö=@FáÖ>€»?~vdÀ»2@-Šie?@àKUt?–UÜ8À ²]3]x»¿<ƒ·ýµ´t¿Šfïæ ñ@`}b5{©¿Fnðº$›BÀ¿q®Â?2S@;²Q 4©¿Z4Ú­ß ÀXþ´¿8@SW;@¹ÉöˆNì§?Ð?†õôA@mìç.dÇ? àˆÉI@ÖùwŒê2@HöjŽ¡?4Åã’ÿÀØDû…ƒ]Ç¿kY”_Ÿœ¿Š`±¹U*ÀŽ”No&@øH´E÷@eè!X4©¿üC.›,S@":¨ª°,ÀÛüÆx±:À˜ü¿¨=À¦ô»ŽàíŸ?Ð?äÍ.Äêá@#ç+ÄÄ?¯7@¢¼¤5@4 ‚ŒÓB@µÑ„‚?p>* lÚÀ¨Ž?ˆ§½Ä¿“¹iÙ‚¿-vzÉ @[pÐÏþèþ¿ßVN¹DÀÌÐ;vóJS@c”ð‘•Ĭ¿eõÈ?#Àïq þHª:@ïq þHª:@®8¶·ù*©?Ð?»Š•ÉÞÔ@ÒK8€×_Ð?QÌM@˜òÅ„ô¤5@Áºž=ÇyŒ?KZÛõÎÀñ Uú³ZпƦŠ~×pŒ¿TÝÚ5Ä)À$×gƒ»K@¨&êWì¢$@ ~¿ÙßĬ¿Ÿ¼™ÉDS@@š)LxU.ÀÇêËmÕr>ÀÇêËmÕr>ÀPÏSOYá±?à?<·V`ª@&B(qÌÞ?ûÁr®uI@ñ³®v9SV@ªa—c“wž?«HË”jŸÀ“o3w%†Þ¿¯2ò3õlž¿„¯Šñ@쎼üËÀ¸uUPˆVÀœM´‘dc@ñÜa½¿¿ñãV‹Ñª5À´'ÅëÐI@´'ÅëÐI@jÿ<\mº?à?@g>c«&@yDݦc˜æ?ìé¶V‘D`@)Ë kÃuI@‡æ*Z¾…¦?¸“Óû1£&À~£Wăæ¿^J)÷ä}¦¿àìÚD9ÀRĺ›Cˆ4@Sóa{k@@Á[ ³½¿¿d:ë]c@ñ†lùÚ@Àd¸š ð@OÀd¸š ð@OÀÁ2È¥г?à?S¤«]#@øIò–þå?ûÇe``”M@mk¦ó©4Z@Yf«û¨?§ÙÜœU#ÀûÕ(ö忺ÏöDò¨¿€óZêÃ@[²L÷ˆ $À˜ZiåXÀA25-w}c@L¸ÌøñÀ¿ðGÂ>#8À†€.òtF@>«3ÔÊòH@ä/XÕ²»?à?>³î¾+@ Mw Áî?dãµÍÎ'b@cò¼À¬”M@/½Í·¾w±?/%¨^ +À k³B×µî¿P¯— q±¿S}ífØ8Àbi!V°¼9@,EKOê‹F@˳³×#òÀ¿¿0Œ„wc@ôê ›Ý@À¤~ê ÞLÀ[F‚› PÀ(>˜óĵ?à?1[•Z¬(@þ˜rfï?×Vý âQ@g±_Ôz^@;ÍöûËø³?Á|(À¡8,ûî¿`˜þvð³¿$¦Ç–›@ÄÜu’†ó)ÀS¼Îù(¸ZÀšè./c—c@°Á–‚9{Á¿SOL.ë¨:À—IôÖÓ×@@DïéÀH@=߃3ü¼?à? \iÊ?0@W3Ÿd¬ªô?m2fÞ°.d@¾û Q@;Û«šº?°*Þ 0ÀðÜ2 ¢ô¿è&–º¿Fr¥8ÀšŠ‘ºE?@AºÉϲL@·ä¥f{Á¿¬D'Ô¡‘c@a+éw4¾AÀ‘¼`Ý GÀ±† žétPÀ#IÞ„c¾§?Ð?ÄØÌ)Õ¤@++ê‚å?X•þìcC@s e”Q@wD¸ ¶5¯?0rª—ÀºñNZxå¿wcš»­'¯¿@·aƒè¿£ð €!ÀCn×àOÀazAµãÌS@‰S5нX°¿Kà]{Þ/ÀC\¨æA:6@bX õRš¯?Ð?¿™áÄz$&@'o²ò?W/·Ôß«X@ѪuWïE@œ˜¾AhW½?É{YÜ&ÀFu÷^ýñ¿pÝ\VI½¿ßB½#¤ (ÀcøÊ>e°5@RGQà"ŠD@ëóv¿çX°¿Üš2ÀŸÇS@C»öŽ3À+;(ÇnRAÀ‘pÁÌωŽ?Ð?3fÕ<“¼ë?.ö¤Á—J?æ²V¡"@o±Aœ§ª1@tÉëîN?—~7×¶ë¿[r‰D¿}|“†èN¿iíó8@¦[ €ñl @wc~'ÿ"@ÀàÄ9$ÇR@£i°ÕG–¿—h.¨8êÀÑ1Ÿ‹ï>@Sømpñ¥?Ð?–àûhð@üQ%yµ?€Sã|:D@ɤçÏ"@+VA¢ÏŠÄ1À®\çÃ/Qô?ö}`J®&Àí ˆJ/¹ž¿Ä€EÇÚ×R@Šo ÜÑH+Àjµ’'ÀÅ"–v]Á<À†Eú¢>›¶?ð?Ž…AþMu@(1~ cÓ?ÆQib©M@îuž™NZ@? b`‹?(L%@nÀÊW|#í]Ó¿õ.ÜY‹¿Ù›ç939@Æuþê<,@QŸgÓcÀ`/½’ör@ÛúT‹<}ÿI_ïíÈ:Àº£¶&üS@ 3——ÈŒ\@Ý ”Ù]È?ð?˜§Öò\›-@+öoçä?a[øÎÝ´i@ùå¥ÿ®©M@4‘åÍ„?›2]ƒ“-À}:2åáä¿t™Kú|¿³AIÿ2‡QÀí«¯þ‰*@eO¨'¥ 5ÀD»ØÝn}ÿïwïr@[Ôƒ¸ÜLÀqB}¨¤¨TÀ¢Ìi^4ƒ]ÀºhÑiÞSª?à?i çש]@X=­–ÎÉÍ?Æ Áõ#&B@¸†™¥O@t2K(ˆ?ÑÉ5XÀVjFöÀÍ¿-r)Ð!ˆ¿j€&@ì't`ä@®cs½¼UÀ`u¨8«c@О† _·¿ß¿Y/Àe–TúH@ÆQ#ÏÀK@¤4Þý˜¹?à?SÜSCöÜ!@IdB§ùÜ?øÖ$™Ï\@‡«_ÒR&B@¨FÅÇ—?)Ll¨×!À°=.RuðÜ¿›ËÁx—¿<Ú¬RAÀD)Ã9 &@Öv¥±šñ?lsDùV_·¿áÐ;ƒc@Ö•=µÉx>ÀÝa·v€AKÀôúY ÇHNÀÔփ粮?à?Ñò©Òý@¯÷?)<Ö?²¶G—ÀE@8BgºØR@x8ö¾œ”?@ú7lõÀ%Ç…ãÓ4Ö¿_ŽœN•”¿ƒ“xÁ¯#@î³ûrýï¿ ©iôä±WÀ:º@ã'c@ƒ@¯\ãÔº¿„±„Î¥2Àa˜‚œmðJ@a˜‚œmðJ@ÙZ>ւ׺?à?ÊÃVi%@äñÐBwØã?Yö$[š`@(1(rÏÀE@S’Ϋe¢?Çð˜b%ÀñÚ4¦ëÑã¿LÁ∠_¢¿>´•ÕQ'AÀå/aÅäj/@š¿Ša*@V5“¤(Õº¿‰n•Åéc@:’³ª@Àán£.7OÀán£.7OÀ¤üÕôvð°?à? Á夈¹@uè5wê1à?¶vµC¦I@×_lIÅ;V@fbÿ¡?¨Š¡_®ÀAÊ$‰,à¿äërj ¡¿ãõËçw‘ @ÑFëB ÀZõG,³YÀÒÔ0Ñ?c@èüÌ䫽¿ibÁ|`4ÀÉËL»…J@ÉËL»…J@=žŒ2¼?à?„UL~)@ '³Ñàê?Á"’¸Ôäa@”3=…¦I@·ÎZ:åT¬?}È·‰ u)ÀÇ“&Ç?Öê¿3>¾šJ¬¿ºRxK€AÀ§Œa,•´4@Lø?ƒÅ9@«Ûj«½¿Üi[¿8c@†AùšZå@ÀWSVš¦ßOÀWSVš¦ßOÀžôš´âÚ¢?Ð?P‚úoéZ@+w­O ×? µsÙ=@S!$OµþI@¨øŒBŽ›?öÂc¦Œ?Ó¦À1À–›¸Ql=ÀoVØÊžX@À0& :ÊÄ?ð?óhã? 8@®S@y)@J†ÁE.a@ˆžÉËl$n@ï.쀹Å?ê~î8À_YÁ"Àý;㽯ſòÈÍßÄ"@á’ãÂæ4ÀJ¡(JoÛmÀ"zÿ“Œrs@M᜿•Dпo@óEIÀv¸„Q@ˆ „™cX@)aÒ5¨Î?ð?S­d;¼A@ÿ‹ŠíÖ@îþ›¯ëu@ "r.a@+µû‡ØÐ?ÛÊù•‚´AÀ«Êx³ÌÀ#!’ËñýÏ¿ø¤=½àPÀXoªLeªO@ÆN½*X@Ö›ÓÀ¿Dп¿ 'Õäks@&£SÁÇ RÀRƒ‡ô5xWÀ¨ó@”Ã`À쓹󜾦?Ð?*ƒà.@]âkÞÓ=æ?¸ëv„™C@?œp²ôWQ@’`X;İ?ˆç\ŠsÀò’4š3æ¿vï•…¼°¿ ©òc1õ?nén×Ò³ÀŠT—ÑPÀI„_§ŒS@ gް¿n: j©Ì+À¦TþÍ"@ÍéýD€7@¹ÿK"õ¯?Ð?°äT%¼$@W9rCï?c›ew%X@%z®4™C@îñàG[‘·?°Ñwö²$À_4˜¿!5ï¿9FâU…†·¿óѤLÝ0ÀžHþü0Ó2@6#Ð×~°>@È´s·°¿²™¥N†S@Bµþ§ü…3ÀDû:G+À½M„Ì0AÀ(Âc.¸¸?à?’°yÃvè1@´l#³ð'þ?å?¿)5.V@Ch‡œ"Òc@$dø‰ðcÉ?Ö¡´¹ß1Àvb£9þ¿¡nËŒWÉ¿À ÒDÁÛ?^ƒÆ¬*¶-À¤îm1aÀ?(j”W§c@Æ{æ ѽ¿eÿ,6‰a>ÀN^µÁÊ—F@GÆõ¢À?à?«wxÀy8@]ã%ÑÝM@Q#Ðý„j@²?:on.V@ioÑ?².¤Oµ8Àß°€põCÀíBÉÜÑ¿¿\µÌå@Àn[ÂÁþE@Ø eR@ü^tãVѽ¿tBB[¡c@",pŒpDÀ\››`c QÀÆiɤ-‹?Ð?ÊÅ5”ë?7>Ï'&E ?uÊô5ÊB!@ïƒÕ:ð·2@mÜýn2S?É63îë¿x|æÅqA ¿Ùƒÿ.S¿OËF̹æ!@•-ÅÙ˜#@QP kˆ5CÀl{3…¥R@¯¼½fY’¿ÁÖ–l©ÀѸ%íÂC;@Tª„›¶˜§?Ð? é¿[ô@[$t.ÆC¼?Ë©TJG@¿ïŠÇöB!@®äbø¸¬p?|…†ïÀªOE¢V=¼¿–1í¨p¿6¯üÓõ5ÀEµÿ¶àë¿%‚tïC¤4ÀÝ‘¶–Y’¿}ú“­ŽR@m’žvz+ÀdêF:+Ã9À”qÔkÅ4‘?Ð?e8ÆÓÄõó?øM§/Ïëª?‚Ç)ëú&@¯ÍI¿Š6@M0q«'b?Œ<­ðó¿í䮬ð䪿¨ @‹ #b¿Á¤Ë @VúpÓb\@üIîEÀÊH|S¼R@œ²¹š¿cš$ÄI$ÀHבý¢'@°ãD]—:@eûO/ͨ?Ð?¨ö³=‡È @@ß\N(iÃ?Xq×ÃØI@‰2ã>?ú&@Iq^Ñ(.z?Q- /Á ÀtÇ®`4dÿ^A~²z'z¿Jæ`Ë5À8÷Ó*éuñ?˜"îlø¤-À"«Ì÷¹š¿ìî ’´R@j› Ü-ÀÒ2öA~'À-ù4ŠÔm:ÀdŠÔ•nÛ´?ð?±B¤S˜@, G 9Õ?NçÖVë9M@!çà‡Ì[@~gFqR?Ö«XzÀ´ºoÁÿ2Õ¿¸w¤ÌM¿NéÍ6ø?@¼ÍÖ×@'4@ƒÓ !vçfÀ¸`çàÓr@óù&A›mÁ¿øÈ©®‰8ÀÀí- ©%T@fŸ_GçY@‰J×>âÊ?ð?.¢ •%81@5¤p|ê?™u×ÏÑl@°-Í6:M@F bT´^¤?R¿,›?31À¿mâËçtê¿ñéèX¤¿â×$ä©UÀqtÍE)@(èØ¸öAÀ‘5KAÈmÁ¿€êîòêËr@´‚ägÿ˜NÀúl¤0’UÀ±°eõ»[ÀŒ27øŠ¸?ð?¿út–u"@6gMÙà#à?Çö6”IR@»)sZÁ`@üZ’…9œ?ÛüñÄo"ÀñÿzzÊà¿#ÁG 0œ¿ªý*©WS<@ufR‡[+'@@ÆKiÑhÀ¬H̯ër@šaØ«7Å¿Îiö?Ì=ÀPlÇ‹i3Y@PlÇ‹i3Y@%Þà?Ë?ð?]+ ߀4@ÈBP kíñ?=¢‰Õíp@÷u×xR@ƒ~O'¢Y¯?¾ ¢hz4ÀUÃütÄçñ¿W&xÀO¯¿Øù‚–ö‘UÀÒb‚t8Æ5@±ÄIl¦î(À3%J¡â7Å¿?‘ãr@±Ðú PÀóBÝûÌ[ÀóBÝûÌ[À÷òSC¬?à?ËãFt@Ù†ÐÛ×?îæÌ»²E@nÉ´ßS@Ë%½L¡—?gÖ“« Àà}èrÓÒ׿‚ l™—¿i/cµ&A)@2• Zßfý?›q^ÇZÀi~ÞËc@oÅ'‡ò¸¿3#ê+ŠÊ0ÀÍ˃4K@´k7¬{H@v§o >~¼?à?# ¥†ûI(@%ÖŠÊ!è?©„JÁa@)ÔÀQ²E@ᨥÖÔ§?j!岎A(À¬ ¢`Éè¿i  t’̧¿¹zñ£ƒEÀ)O>b^/@Vý07(@ŸeÛí1ޏ¿jðg¿ûb@ýæTúë@À\"]WŒ¬OÀ!ÒÓ±LÀç^”²°?à?l6ˆ.ÀË@e&Úµ6á?Ä*"¦•«I@´µÎÑ^IV@Ðz_\>£?5 ÷ïÀÀà»<00á¿–Âr7£¿æ üË á%@À7”¸†nü¿füdýÃÈ\ÀPJû³>c@‹BÝX0=»¿ñw÷ß3À÷n€cJ@àf§–ó¿G@õ-7À½?à?O5͸©Ÿ,@|ìÂÿï?Õp÷žc@-^î׫I@x–e×ßâ±?»€/Ñ”,À!¸>¢óï¿ãáVÚܱ¿_eYÑNEÀ°µ‡ÆÉ4@Š‡Ù¸÷ÀQ,”=œÞ࿾éxjH¿§¿¤ÔZ\Z @&Y¹âÄÀ)tù»ÆxPÀý ClZNS@D±¸­¿«º‡pì'À(BðJ.K1@4ž¢ò<6@Àòº61'°?Ð?Åø=üp’#@g9N`+ë?ÖÁ_‹VÂW@ùç¢DA@º7z^Zd³?ä’,͉#À\1£™ë¿á¸*¿Ê[³¿’ Å G–5À7Æí¹õ/@Ï"§kÏ4@Ãy`Ûý¸­¿û+míFS@Dvˆ±·|3À‘´ÿÔâ7Àâ•ÃHíµ>À²•P Cµ?à?A•À~Lh-@Æûk®÷?_´¾ ·S@ƒ„¤ÓÝ/a@pÕÄïÈ#Â? ßBÁvZ-À‹™ÁÐ ÷¿«c<@¿ˆ§#7a§@f“´±™ï$Àd—Ź®ŒaÀÎÆ.h hc@ܪó‰ü¼¿ (“c¼f:ÀÒ·Þ|3@EÌŽz¬sE@å@ÍÀ?à?´ìîP*¸6@ãòVû×@×iž_* j@‘¸Ü ÷S@eÓëTÌ?¯òœz­6À•®M–ÏÀŒåž<%úË¿\­sþ{²EÀõ‡óC@¶–žŽ‰J@¥:áÓü¼¿¬¾‘Ôac@h¤„!paDÀâéØ_”ú;ÀÔëæyOÀ[gÊ̶§?Ð?Í®ùè{Ñ!@ý×a³ï?mRãOdUF@Cµ½n˜S@.ñ»Eû,»?®g±¢È!ÀÇÐþ=ï¿Á!Yt{»¿ „T)‘†ô?`1—ì6À9ö ÑQ§RÀØ¿Ew‚S@ÿ$ûÏÛ‡ª¿d§¦ƒÛî,Àxˆ3¹¦4@b"šÔu±?Ð?[à߆ @*@΋€Ôfìö?ãŠ'“w\@ö\‹úUF@ºíÂE Ä?“@]3*Àûø Ááö¿Úl!©®úÿÈLìOÚ5Àlÿ~>6@Ò¶ÀD@@ªúP ˆª¿‚•õˆç{S@ÄÁ(q€K5À©Ä£!@ÀE„/ÝÑÛ§?ð?dEÈåý @3­Õ¨×¿Á?òØ)\¶3@@C¸_(T@í1¿€®Xw?dNKÚFö À Ÿ~h»Á¿Ñ]aÙRw¿œ³”ÚME@uä Ö€¹F@h#“±;fÀº¯Æqƒr@Ÿ¤‡ñÿ«¿2¥ïOÀ™+Àd¸ú~QWU@4ªFœe:É?ð?ò™îH©,@>(ÆÿTÇâ?müÅ4Þ0j@p¦Ï1à3@@J¸/WB³˜?:âN&‡†,ÀDW ¤Ââ¿—Õ¢­˜¿@à°D=÷YÀ/²-7;ÀXÄÄ“XÀnv¶Ó9¬¿¸èQŠ7{r@ݰ¸+MÀ×j¡…úsTÀyxôEz?Ð?- |ØÑó?ë^ÜS8q­?ádâЉ&@“ ÍÇo­7@P3#iIÞe?»:¬]Ìó¿@Q’ri­¿xš­š=Øe¿S‹ÑC$@Ñc{0Ô½!@³ê¦QÖHÀ‚ÖØP|šR@ô1]¼D–¿ª­¬†"À>s=™Í'@ÖÄuúåÓ4@¾Ðؽnª?Ð?%Í=Oìä@ØíÍ8±É?/ò‹ M@ ÅÔÂ&@¬jNô£‚?”@àÀe´•îÀÉ¿‹öÌž‚¿Tå^\˜è9À•ë»Ûì?Ëi‹H2ÀÅÓžõD–¿E"kð‘R@Þ*›ÁE¶.Àlàä3÷'À^DÈ Lø4Àg ä#!“?Ð?„™×l­“û?3¬‹Ùù·?eÁg},@°«2jWü;@‹¹—B]s?M»›E‹û¿?©6£î·¿?‰H-¨Ws¿ñh”4§µ"@.¨ ¢e@äËRÒïIÀ$M G±R@Üù÷ŽÐ;ž¿Ý÷‚ñ%XÀ^¸­M4@^¸­M4@Ñ4Þ‰L¦«?Ð?pú‹‡jð@šï+ñyµÐ?M‡›…P@ ±—h},@\,mŒ?‡¯VêÀ_&b°Ð¿ÜõÊHyø‹¿—ÕU@ã9ÀªQBÖ¬G@~ó®í;)ÀŸ¥Ÿ<ž¿Jþ¾î©R@ÕCuO$0À[*@!5À[*@!5ÀNb™IÄǶ?ð?HuT7~"@ý„^Áxsá?±c[ô¼¸Q@þ•§ÐOz`@×àûìw ?W…Ø=Øw"ÀÑ›é¢má¿ì=)Õjr ¿³3òã33A@ë…— c1@ÎB~€…ÙkÀÚáÊÆJÉr@Õ„x?AË¿­¤ä³Š½:Àì8×vjY@ðÖæQ•ÄS@—FºJ#áÌ?ð?·-!>;t7@º%ñ|'"ö?ª}S`»q@%7~¶ê¸Q@³¶êîã´?â'ìˆcl7À sÂÓÀö¿ë?ô Ü´¿Æ—#‘çYÀ¼è‘Y5@d) ž@ ;Àz mÆqË¿\°ÛgqÀr@S Û²†ñPÀWÆ+^#T\ÀÑ}>IVÀ niMwš?Ð?†¥„_#@k’öDÖÉ?Û Å|áz5@¹U@7šMC@mV® Ñ ‹?0¾ ³CÀ1]GnÉ¿§¬"ì‹¿è`@§ã Ø—@h€­3¤ÏMÀ Å-~áR@ÓOCký¥¿6´õå9À1ïj–Yu;@;tä‚‹83@œ½Æ#U®?Ð?Ì+þ ã{@Õ*­n#Ý?yÐ-ã…S@xœ7ó{5@}`ÒeÑãž?È2ÝÜqÀ[µHã~Ý¿Ôб3Øž¿f˜2ìëõ9À¨SàG½&@3ø)¤äî¿Ýž— ¤ý¥¿ÆKØR@HÕÆ”ñÂ1À.ø3 !@ÀAY[â§”6ÀÃ=þ‚î/®?à?QßÁ,Ø@“±ÎQâ?átãp$‡I@:+U —zV@¯À„¤=Á¥?íxÍûËÀñ1›IáI⿎+;¤¸¥¿F ˜fv+@hŠ¡HÄðí?EŸ°Ñ_À%ýA}Gùb@¸|ó˜l¸¿Ç»—ªå1À¥°‡¢ø¨J@rÈ+Øz©B@”b¨µö`¿?à?ÁŒÄ 0@ŽHÔd ó?LmÜåqe@áà[f‡I@[\¸ªŸ¶?SÅm0À2ÉAIÝó¿²€ÒŸ–¶¿f3Ÿ»·JÀ}4SIJÈ4@M +<‡e#@.4Qß«¸¿©¡þR˜ðb@^Mz꽘BÀÁÚÁø‡PÀÿ¨ÂŠ#GÀ‰;•Ìíø ?Ð?D$ ±&_@þ«©¼³Ù?4Ù_ûÀß=@Ü‹hìJ@¨,Òþ ¡?„ƒéVÀ£øø¨Ù¿p:û‚¡¿q L=o†@t³…– xó¿ˆ'jÿïPÀö—³NÑS@–Jzøª¿ fâ¯:$À+ä8·†B7@ÌžUL2@Tdâ3S°?Ð?=à ›ý£"@HeÏ$»ºè? .a%€W@`Xà=@UhŽàOg°?„¾›œ"À;°6°è¿eE:uU`°¿Áµ^Nb2:À.» kóN*@µ÷©ëŠ^%@¬§àé;ª¿ãÚèdd S@!ñs3À¯¸ýj{>À¬‰Rµ7Àª®³¦ÞÂ?ð?âœõü7@J‚𿈷@¹wƒCa@¨h1ˆUìm@÷:¸ÙŠ,Ê?ç„×ì8ñ7ÀmƃÔ{¯À6ÿ)¦ Ê¿¦§úC3@øô/‰Ë%À6+ZèsýqÀe±É*s@ù¦K“Ê¿äÌ¿Ú œFÀB°ÚxæQ@B°ÚxæQ@­ªMr÷Ð?ð?*G[a“E@P˵6îß@G*’±y@"6 °Ca@“´‚‹×?>D–“‰EÀíàÙcrÑÀöV¶Öπ׿§Ë³ø`aZÀä6!XP@{™èôˆŠP@0C®é^“Ê¿ñ‰Ê»"s@¢µøMRTÀ¿®›JXÀ¿®›JXÀ´ÿ¿8@ÉÄ?ð?>¸Ó]U=@¹Z9<@üÑ­¿c@œ»ÎTq@m235ºÓ?ëGø‚>G=À¾if§À¬êÒµ°Ó¿œYsCÄR-@©ƒY¸10ÀbÉesÀÐÌ=Ds@CŒä…ä™É¿²¬Ì7P IÀÉËÛè SC@NRÀË,éP@gÝ~í±Ñ?ð?á©Ç;ßH@D†ÿwe@µÿzW|@Z)Ïà¿c@)ÃFuý¹à?#ßšÝÓHÀß¼+¦[ÀNòîï±à¿d7¬1œZÀ4·•àP,S@ <ú1kV@vr &šÉ¿Šh×(¬½?ó6Ö+¶!ÀÁŸð¿s@BôÄ/½¿tñôq m@líÛ™»Àõ‡ ],TÀrö“U?^S@÷E@%䦿=ÅïÆ†+À§îÌlÿL0@“L²ÜE²?Ð?‰¥÷蘎,@éz®ˆéëù?Ÿ›ËЈ‚^@i®>×eF@S“1~‡Ç?Ùj:(€,ÀÈÎÞù¿Je”Y˜{Ç¿!O\ã:ÀÙ♀×p6@jÂÓîHQ<@5,`䦿„Q~dDWS@¬àØ 6À.ô±øX}9Àü¶ƒß”¤?ð?†:O½Þ @ÕÿîýèÂ?ÙKœ;-¼=@‹O9Îÿ‰U@Àki1¥{?{ î6®× ÀBåYÕã¿cwõO¦{¿Œù­ÌgÎH@()ÉkˆÑI@ v4ÐÑ5iÀ û6obr@­é$Wòª¢¿zŽ4òy¤'À5ãäç‰H@+1(¤ÖÊ?ð?ƫꗴá0@*}¢G®è?ýi“1vm@¼¶·z¼=@üÚøøB ¢??Ý\Ý0À,û£SL§è¿ðu§ÒV¢¿#:jE›^À¦õÎ[ ÀkÛÕ%^[À¾r­Š"«¢¿A& ЃYr@y€ÊÐNÀŸ)$méÕGÀ!·oÁÑ­‹?Ð?^ÏKCRqó?Ÿ±ƒa¯?”ùeæ$@²¡›ƒ 9@*öý·mði?<ûëíƒkó¿@¦Pœå¸¯¿,¿®èi¿¤%< w'@|™[¶šÄ$@j:¢¦ KÀ³2c5yR@È›îst‘¿w}v~óÀñR궪ö'@ôR궪ö'@~HÑØ ¬?Ð? *„¾­µ@W STÐ?¹£Lƒ6P@ê™u]Ææ$@²¡l KŠ?œ+mÿʯÀN’´6пQÑØ7ÆCŠ¿Î  >À}|¬ò 'ä?ܦ o¹5Àþˆm¡t‘¿–ÌéöoR@-:I-0ÀF ~X©l(ÀI ~X©l(À‚%e07l±?ð?Ÿ~¸FÚY@B:…)§õØ?|\ 5ÞuK@ôІÅÃ2]@ @øúÆ–?ve¢ŽðPÀò\ñ„íØ¿Bí™ÎŽ¿–¿àAUÀûE@iŒ@@MÎ* mêlÀÊ‹6r@mzÙ°A7¹¿1ž0‹54À¶z¾ DtT@¯gGÄM`G@Oáom@BÍ?ð?¢ ¤Xzú6@ÙÔÎL&øô?”½CÐq@‘?­%vK@û>ƒÊ"³?׆àfýò6Àmú/öPñô¿™ƒý޳¿²9ªÇ12^ÀRq¥ú˜¶&@þ&Ú PÀÏ·Ì‚7¹¿* ‘ÁÆr@ޤöPÀNlP|åUÀé[˜DIÀVŒŽÔ •?Ð?É8£Üo@Po8E?ÈÂ?T4C²úG1@lQ\M2ÿ@@ò¦I"ƒ?Å6ÛTiÀa5Ð.˜Á¿3È¢‚ƒ¿IØÍýs[$@§kûD…!@ÈV}›mÕNÀƒ-áªy§R@}|¨T—' ¿Ô58>†ÀOù©“Ÿ9@dO%¼Æ&@#Õ•Âì|®?Ð?>W§»@h¿Òä%;Û?WÝn†>‰S@Ï”?Q'H1@ã+±½›?ˆ"ŒI‰±Àƒ6´€1Û¿üڔݳ›¿RŒ‰RjR>À¼_'ZÅ@nFõ Á$À² Á' ¿FÏòR@Rü–ÙÂ1À²¥ð-×<ÀèH“€Ó¢)À×(ºÅ°¨?à?5gÔ[Z@Ð ,È cÛ?Éoù–wE@qÉËQ™ºS@uáyNŸ?G«×Àõ>®¢XÛ¿ÉãVd Ÿ¿‹“•2@-ª2wܺ@4[Y úe`Àå¿b@_ÙkUE1³¿ßƒñ†ì,À’ˆ2©¸žÍb@ÕÞ—Á.iCÀs'xÕDÏPÀ‰¥&ï:å:À³.(‘ À?ð?/DSnÌ\3@šp<*â&û?¶yÎU¤]@ûË^V4$@ñ¦Oóı?Ð?Ö%«°âÀ'@‘_d‘qò?Iâ½Z¸[@òH»D.A@ÚÚì 9¤¼?7 7ãǵ'À6ú!òhò¿^½>Õ–¼¿ÆZcn\@?Àüª,ñ"0@ÚS³rB)@â4»*'§¿QdPÿR@¯ö|Ò!5ÀBßA®8ÀD¹#²Ü4,À‹‡G|Ó³?à?t(€\¥C-@¼ïºGùù?žê8²S@r,B˜a@¬=1ä‡Å?f4î;5-ÀMí©œ ù¿îª]¼I}Å¿ŽgLÐìÉ#@Ð)†óÀ*õ ådÀ¼é+5û c@<ȾÙÖíµ¿u Ú<·7Ào¿¬¨‰“3@o¿¬¨‰“3@9€ÀkÂ?à?{¸~Â)3;@—ꥪT@XÑön@ÿÎñÅk²S@M‚øÔ?M[—Ä%;ÀûÉçE-IÀVŒÆÿ5ùÓ¿ÏJ¤Ýq™OÀV¶g©OFC@nü‹è-UB@ŽÄyv `š c@JÔþè•FÀŒ‡Œâ<ÀŒ‡Œâ<À'7+UE¾µ?à?­DÃÝû®1@\‰ôöç¶@:{zÅ_V@hÏPÌÖ`c@e˜Ø˜Ï?I‚ÝÌâ¥1À¹8î‡N®ÀkÍ?ù–ˆÏ¿rǦ2@¨éôD À²¹~ªeÀrȧüª:c@—¨Ž¥ô²¿u¸±þÖ&:À‡ö@¡ä2@Jb$Ã?à?Ÿh"åÕ ?@ªÝIÄYW @GzFkRp@ÿ;ð?ÿ_V@y‡Öñº»Û?Bô¹]Ýú>ÀSYÏIAH À 8$=v­Û¿A¬lÿOÀ§ Ùã–F@ÜÇã7H"H@IÙ|€Öô²¿!†í›q3c@¢€þö­îFÀ”×…Õñ’=À…¸!!V¡?ð?å.'ES¶È3ÀTÂóð¿gá»ï©¿ÖÅX™aÀlç|¬žVÀ_ß|´^À¾WÙ!ÈÏ‘¿Ipµgt8r@ï»o!5PÀb¬nK_ˆ?Ð?ðÝÎ^Èò?Ò—úˆìÔ°?Z1r€½r#@Ë}ÐÌ…¨:@¿Ûµ*n?ÔDÐUÂò¿$³„ϰ¿íxs!n¿òºÏrÃõ*@·y~õ§Â'@= ·¤´ùMÀ¡\¨|XR@ pó–ÙÆˆ¿–»*4Hñ ÀWÂéŸE(@½Æ:覡­?Ð?]ÓÜ,Ú@ߨ2„zÔ?¼Ÿ&Æ ÿQ@õÕÛ·ïr#@zvZ¦ùY’?ÆI: ÕÒÀ•´µïsÔ¿ÐÞ@¹)Ї«‘CÀä×íá裿'‹%)4eb@†°öküÁAÀô‰ šËHFÀs¦Î{ÜQ£?à?… y©D@~)˜Ô?’¡Ál²@@,º:3£Q@Ðn䟼–?ƒ6ת=À¦²9ƒ Կ㮀y –¿n£S(¡7@á`âRÑ,@-ì½â`ÀS§±,:†b@LV µª¿e=xr`]&À&3Ã[×ÒI@ó;/k² À?à?͇U‰ÆX.@þ[óÝ­ð?G>ÿqne@A[ÔÝ—²@@ã˶™U²?"žÓjM.À+ò ^Ÿ§ð¿Ä1~¼N²¿ Ú‚ÌÂhQÀí&à!y $@Õj|™ò;ÀxRµª¿X ‘Œ&|b@ï-,b[ŽBÀhæ‰QVMÀ>}ÈÑï–?Ð?ãQ]@÷Èö!2Í?þñcÃQ˜4@š! GD@µxáZØÁ‘?°¥¸öÀ}ƒR@Bÿ•Л7 ¿4¬,W¯À–ûö^+ñ;@pwÙœ¨°?Ð?oÿ“q!@Û‡gÅe7å?zG¿ÇUW@Dª×ð†˜4@iÌçdÝΩ?̯לj!À"¹äß.å¿ÊKwæ~Ä©¿Ú)ZŒAÀrdúãÝ>@ÉÆTÜ`¸ À JK°Å7 ¿ £«ù†“R@ËsÚUç^3À6‡Ù¯@ÀÒrÌ]•–º?ð?½³ˆ–‡À.@«ãv¬ô?BLx,9ÇX@?2¼v‡Bg@QV¼¼Ê»?TX V³.ÀÞ, '£ô¿¶—Qо»¿}ÛÈô'³C@$´¾ú))@Xç~ßrÀ¹…‰-µr@¶âÿÐEY¿Ü‰Î£?Àæ]&ÛÒ,[@ªËP¨£æù@”a^kˆk@áGªç˜AM@m®†w/É?-·˜ðCØ6À­ëœ+òÀs%G£þ#É¿'Õµ!äQÀ¼î餧>:@ Ã5­Qa@#ü@pásüZZð¿!§ÄÂhôtÀ¿C´¹{år@µLªñ‚ÿ.J~``DÀv<ØéQ@d͇åÈÒ?ð?„^­ ·J@§Ä¦ V@ìyñÛ·Õ}@¾Ô1’a@ÕõlÍoá?…î*JÀÐeÛúËKÀÃx2£fá¿ýËøp'bÀdeR’$P@ÙôÁ.A@S‰Œ $ƒÃ¿ÂØ•TªÜr@œeµJ‰ëUÀšé“fYÀ›Ûáà¢?Ð?,Ô8Ó.@Ø“…V7ê?ðNs¯C@„:¡àï)Q@¶Åžd£Œ·?ïL!# À}—êè)꿪 ¢(É€·¿ÚJÈ2@¨41D"û¿`YG^VÀŸˆ6VþR@4^¥¡O¢¿ $ƒ·¢l&Àî•4&PÑ#@XÝÏ5³?Ð?ë b42¶-@xÃ0µ°ú?/àkû†#`@£ùu27C@°¬¦}àùÇ?ïâú=§-ÀMªäCF£ú¿?ô»FÏíÇ¿qÓ´‹«TBÀ޲T3@”㌎,@†©.~¢¿MÃ6öR@3yàÌÖÎ6À›ôæ‰P-À›býñƤ?Ð?8—¹ž!@½õèÆ]ñ?:èá¶DF@RKºlaS@$š1ÄÁ?¬m‚•!ÀÃ9Êã±Tñ¿!4¦ÐÁ¿ìŽsÆ¿Å@.íÀXÒ£ÀÚö9ì"WÀ{¾ò¶S@þ¨È~ß¿ç‹[^ÍÐ(Àhþß¿ݳ?Ð?”J§DLÛ0@1ÝB|*@†ÇÚÁna@ñðw“ïDF@p·í_Ð?5N(|{Ò0À"U2z”Àghs]Wп®³©rè–BÀÈHaƹ°6@’Ò™*Ûû3@öÖ+‘¿€‰ænS@¿ž¦Îw·7À¸÷ÙvÌÎÂ?ð?p0E˜3ï'@à bËb´á?ÂñIþAPT@¨q›ª*³c@û(Z1š?ð„´?›è'Àãæ¯á¿¸g€"*š¿ÉF™YQr@Š›ÝÇÍ¿sÌE6ˆEÀ'irþ‹Ä?ð?´Ñkð‡)@IU³F¼ââ?àûƒ:e@ d¬qvPT@ÙœN¨ð›?×ò¦rç€)À‡ø|ˆÝ⿜×Áeõ蛿³LÂÝÇÍ¿ˆ“¸nÊNr@`ŒÃXõFÀX&iS¾â£?Ð?tváEå\ @­Ók3É?8syVÙ€7@CcúçÆtF@‘޹¨ø …?nYWÆS À+}øÚ—+É¿œ«½@š…¿è³&[Ò©¿EøC…àô ÀGž4•ªÀð ¸hR@¿4E˜°¿×`Rá&ÀÏÏzË%5@ÃÿUñ¥?Ð?0¡ÛÆy4@dc£¦èÐË?A UÓÓÇH@*öX7@ÒÕY(߇?åb (q/À¦¯ì¸DÈË¿ø™«Á%؇¿PþO"ƒ[Ú?ô@Å‘ ø?_ ¼e{¨ @)Nâ;°¿ó¤eR@è`ÎÃ=)ÀuOE¨™#ÀˆDEù´?à?˜ê¡ ¥Ð!@”9R2—á?e|O­·òJ@ƒÊÙ nY@ÅÔ(Åx^¡?¾¿ûîzÊ!À?yÏ‘á¿âmßvX¡¿X |ó×Ô¿¦Ñ`ú+Ñ,À¬¤?Iâ4À‡ÁÊm€b@{ð@RûòÀ¿¦¥ë@8À^Z rE{R@ï’)Ù·?à?©êkÎC$@î'.[8ä?LyÃÞ¥é\@9à8BýòJ@Ï›„ ²Á£?‚<«<$À‡qÏÔKûã¿ñ¯ nܺ£¿Í%®ÞE÷?ÓoÏ3@®Žá0œa)@}FÅ'óÀ¿GÄzÖ|b@ÈM¿i’;À³Ç®)¤AÀŽ1 ݦ?Ð?©j2¡4h@/ÿ„»Ç"Ø?ëˆïµ§>@VCÓE¢L@ä2]g6›?€Áu‘ `ÀÏ œ_”Ø¿Y Ã,›¿,Eí™ý²Õ¿ABåLx%Ày‹÷…T¨/À÷¿Vö‚˜R@e»%•t±¿,2u½F§)ÀÄÛúL»G@UVÍD Æ©?Ð?o³G<2@„•L2Ü?'ž]‹ÃµP@‡»T¨>@L<ÁÀnÊŸ?é^Àµ©øÀ„…õŒ'Ü¿›3_P¾Ÿ¿tlÚ@-î?”ï1jqÈ@ôéf»Ò"@¯éâ7Ât±¿œËVän”R@7!)¶xó-À›fÌS7ÀFhèÍ(-Ç?ð?*+›áª9@ö«8–ÀM@ƒP|ÞPa@ôòèê³p@ëàÅnXÙÄ?¶Gu9ÀKº¨ÍúFÀàüpJ¯ÐÄ¿®­M—Ào¿Z€:‡LÀ‚K¯mTUÀᛇ±r@‡äv1zÑ¿Juab³KÀØQêC_Uj@A–ÑX¸Ë?ð?¿¥+™D‚>@g$GéÖ@ŸN3x3(s@8ž@2 Qa@H‚6òÈ?þÈL3˜u>ÀãµUv¼yÀÿ´n³çÈ¿v¤.6[ä@{:“;@=¹Æ†ÎH@ÿB—^zÑ¿_Iö|¬r@;î{ì¹0PÀra5av¦ZÀiÄG K¸?à?v ’".@ÿ®ËÚ­¸õ?CéçcqS@©zÈÜÞa@°~à‡ÃP¿?fÝí .À7¨àUó®õ¿ÿ€·ú¼B¿¿¬ÔXJÏü¿žÖß™¼AÀ8q£±òJÀû9ZðÉb@?—P¤EæÀ¿Kÿà‰‰<À<¤ðKLZ@€j+œò¯½?à?c­EðVk2@œy{L Žú?I¹­p§Íe@#ÓN•qS@ÒÜšðT$Ã?hiÅc2ÀΖ'‚ú¿)b-Âÿ@kÙÏ,ý@7Ýz€,ÿ1@Ö€#½Ã¢>@ºGqæÀ¿§ƒÛNÅb@ðÐs°unAÀ Òa+eKÀß¾÷î‘k¹?à?êºq4 ­1@ΗÃ@Óü?cüT#n¶U@†ÿ8}Ôc@nm Ç?Ãö¢é-¥1À6&ƒÝ†ü¿S1¥>ǿБé)&RÀrÊÓZ+EÀ™¦µãWPÀ8:]ãb@¨&ý˜0¿¿ÀüZ*>À5¸5\3¢W@pb­¿?à? Ç#± 6@ÿ$çóÏ@¹P³±§h@z,Š3¦¶U@}ì)½@ËÌ?Óa™š)ÿ5À¸Þ¬5qÇÀ•ƒ±Ö~½Ì¿P LУþ?VMT‰‡6@äžéú&B@ü+ß…é0¿¿tÝQ8Þb@ÐQÌ@³BÀ†^ùÔVIÀu…Z"ØŽÊ?ð?p¤žÝ¬›D@ Õi$¸•@ì™Ö !h@£ÜÒ:êu@9gƒ„Âà? ÞêH‘DÀî¾WYŒÀêP:*ºà¿0-98Š‹Àä~la…XÀ`´GFcÀeê+íRýr@=bÊWÙÊ¿Ë &‹OÀ£¼Zb@½!Hì×Ð?ð?ÿÍ}ÿ¹&J@£wVgs•@Î΋ò·{@Aæ¡#L!h@”…M„´Då?Õ÷¨“ŠJÀæ(`‰À~ _Xû9å¿Ê<‚Û¤@¸72éeK@—qÕŒCçT@ñÙÆÙÊ¿J«&X ør@ÎXvÿSÀŒ"Õm@TÀ!xµXó´«?Ð?irªÑ¯á'@ŒA.ì÷?ßx¾Y²J@È™àÙ!X@ÃS²öÇ?¯þ¥¡Õ'À\ÛÏç˜ß÷¿é!RÈêÇ¿¸º"âéúÀn~Uºè;À(ÂŽÞýDFÀ"²‘>ÞS@£ˆ-=y¤¿4phØKŒ0ÀÏ ξñ4@H‡~9ܱ?Ð?XÃ9þ‘Í.@ÛËY{Ûþ?¼2ºâ_@R:/­ž²J@Æ8vëªèÎ?Äb§®]½.ÀÞ6¶ àÊþ¿n? ZhØÎ¿Yƒs©¶Ù?"Ýÿð6M0@Zà}Ìj‘7@*÷» ry¤¿F«¼_¤S@}™<{S5À-×P£‹Æ'À¾@Rýݬ?Ð?ÿÎÛ{†+@oå¹x€þ?1ÓÒskM@)Mb{Z@Y÷çmæÐ?¨uôŸŽw+ÀXõ\Fîoþ¿lÂ'»CÝпL¦)¹ÍÀ+y8é”6?ÀšŒö4‰TIÀ' 3S@ËÝY©x—¿Â†‹«´W1À»¼:‡ã²?Ð?K›Nõü2@†0óÿÒ÷@|éiñ@a@qî|¿kM@‘HZeš Ö?×­°b7û1À¶žëéþìÀ…Õ?‹šÖ¿{»œÏÑ­¿»4•üF3@ƒ€¢ƒ$:@cêÍCÊx—¿nú1M.S@ÿ½Ž«Á¯6À Ÿ:vÌÁ?ð?$¥ý0ÀÔŽí.µ/MÀÅ´BgBr@ê½V;пð—V-,½FÀfš¶<†Yb@¾Bõi™øT@ýCoø“È?ð?È©:žº4@è ÁÛPô?!Ú5S›Ãm@¯÷°ãbZ@üòÝ4é³?);ã'|³4À¹+îÞIô¿HÓÚZ⳿ÜýÙh„0À>‚€í+@–êWd­@É:?,;пÔxÏ*>r@zœø’ª LÀ^pö}QÀ5Ù[‡´DÀ¯"‚°=]5ÀæÁ2Çx(EÀìÿ{É»R@ö¥t>Ìþ©¿cÜnBÏÄ-ÀÌó\I6;B@ !æôÕ4@ê•o²&±?Ð?6›AÆ^*@¡½ë`ËŒ÷?ýðQþ‘)\@Õaê±G@ô'ÍPÅ?¢æ¢‰Q*Àù†7)ù€÷¿hÁ¾xýÄ¿’ˆÃG@À†ŒÌ˶+@CU*Ïê/@®C]ÿ©¿Gä¸ ¶R@[vŸYp4À§Œ‚˜²4À3•@û&ÀZóÆóˆº?à?Ýïn£6@¤}q@æƒ×‹ýY@Í»UWD"g@ŒT¨W@Ö?Fý¼2—6ÀFhmDºeÀ3Œs!®4Ö¿ $îĬõ?Ï$Y©µHÀDLdXÀ œæÖ‰Õb@B'fd] ´¿rúÕéÊC?À¾Pù¡BÎD@¼Pù¡BÎD@a) Þ'Â?à?ý{×áý>@ÈY<¥º@[-rƒùno@rÕlóÎýY@œ'GºvÞ?9³\—£í>À‡(÷è©ÀfÚX¨ÂfÞ¿E”÷µ„N$ÀŒÑ0(8l@@ñƒPFÿB@TÒz(‘ ´¿ÞÐo!Ðb@A‰$8bEÀ­ã«¬ ™7Àªã«¬ ™7ÀØj»S¬«?Ð?¹G.*@Ts¾íœü?¤ã L@J¯‰ÁahY@;=c~]Ï?ßVË´ *ÀIí0€sü¿ŒÖöЇLÏ¿À„—µD¹?ñÎ|$<À)àù« KÀÙÛ|áãïR@•Lˆ8âÆ—¿¿Ÿ}Áe0À^h[ðMÆ4@áùÍö+³?Ð?£8Ù¾¡2@Ì]K#Õ@7XFSva@±ztû_ L@%h ½Õ?a\ØÔØ 2Àò8piÊÀÎ`ν±Õ¿Í}ó»ŒÀèPÉ3)3@ ƒöhÀŽ4@KI=Ç—¿UVP¸êR@¬^j¶ñµ6À÷FnM:(ÀqeyûÏÀ?ð?¹(¿ª.%@0ÆR.©ß?ÁµhxŠS@_‡]p¯a@ØåëÝݸ–?CÆÈà(%À\Qo†.þÞ¿Å+¨²–¿FýDÞb]6@Lˆ%t`š8@A°ú¹ã@Àø¥1eÙq@•ñ¶…)˿͎ÆÒÀBÀmÁQÒAb@o±:ì•Å?ð?Jk¢–*3+@;ZìΆëã?ÍXå÷LŸf@²S-ìOŠS@ºí@3Z-?%Ïž»++Àà ¡'æã¿©e.å`%¿PjÀëhBÀ~zIšØ@ÝB#ÎN¹BÀé½lØË)Ë¿ñáã‹Õq@ÚÊ ŒŠHÀ'Æ’š‹PÀ‘"øÑLÚ±?à?»±¦ï{@üR¿±%Ö?Ëc>‡F@P†0´CT@Ž}Å¢¤Í’?ð÷$‹s À•´1˜<Ö¿š¤ÚÇ’¿…Z¬š<&@O®«œ‡@>è*¶r÷:À˜«q1ïa@$[¹ÏG½¿Ýß«$¿4ÀC¤¤ ØD@Zïð =R@œ/›¡Dm·?à?åf§ç!@*€}8lÝ?ëØ~}xZ@µViN‡F@ ʳ’®˜?©=¢!Àu9xÝ¿Ùj¢‹ø¦˜¿â˜Úi%2ÀGÕ›EÈ@fÓ‹sb)À¤8TH½¿ èæ‰4ëa@°F‹@:ÀÍÙ€óo3À“¾¸ôAÀY2h:Ùæ¢?Ð??Ié¤.½@‘oæ¬ÑùÎ?LJ¾…OÁ9@ÊRä˜Ø G@± î9';Ž?Ë;„K²À£Ö1ïο>›þƒÈ0Ž¿Þn…ÃÞ@¦*=šâ•ï¿e­{jþŸ2À`Êvµ R@¢7*kÛ䮿b×6ŒJ%ÀlûjE 8B@lûjE 8B@U»ëòFJ©?Ð?‰ Ø|=@‘«äs¿ºÔ?éï2‰$ªN@O£’Á9@£ Î&;”?™‡¨36À@.£³Ô¿—¢<64”¿¤#Y Ê!À¶wÌx’ @¦·r’/ À<¬Q0+宿”=¿2R@ò ‰Õz,À…¯ ¸rz1À…¯ ¸rz1ÀÚ‡ê­õ£?Ð?< /Xs@–Á´YGÕ?¶èw:=@»+7T J@9xí„ò¯—?õ̼:À¼SøÙO?Õ¿|U»ÿ¦—¿Glb›C@Ž—ê¬OÀÔå¹Nß7Àñ‡CÐØR@ƒ³Ö¯¿#’ Yv˜&À~ú”¯ïeG@a¦åÝÖ2B@E·J0,«?Ð?»”Ý–5@L–ˆ‹úÜ?xJó$œQ@¼¨ÕïÊ:=@í5ÿ!! ?F›4 `þÀm™ïÜ¿Ëʦ  ¿îœ6 DÅ!À"óÍÈÓ@4ãŒiרà¿à¡MÑÖ¯¿VÊÆ’R@ü@ÒœÀ.À½ŠÞœ7Àv­$õ1À€(RØ¥?Ð?ŽÐ[ºZÐ@¨°D×`ÅÜ?~±:;1z@@nÐ+ß©CM@á+•N$¢?u}1ÉöÆÀç~u/‰¹Ü¿>ÈñÖ¢¿!w²Ðh@º\¶­ûøÀ=>êµV:=ÀcÖºO4R@èTx,Òí¯¿EÜ­~Áì'ÀF¿ßº÷I@Kü86i-B@£5m1­?Ð?·ã׆Ύ@ Q3t*æã?´½‡šT@èKÜÆ[z@@ƒ1žX©?Z»7ÑÀ =U¦ùÝã¿n‚¶L©¿¾Ð¢ðô!À‡»Ä˜r@è"¡E@õÆ$×,“Sb.R@h—5‰0Àʦ¼ÄßY:À'ÛP£r2À‡N|Yi¦?Ð?ÿÌ"zS@Xv&Ÿ,ã?}©6ÔbxB@c&¥¡4ZP@;d_x:«?)x*/WõÀ{í–$ã¿ô È·b.«¿vjS¶wL@˜s6jCã&Àé$çXAÀ{þÆ—KR@Šyäöö®¿pãA˹G)À—*mE«ïI@i7™°Ä'B@Ä8B‘(ÿ®?Ð?kj/@vñ"@à~êuæê?²»ÀÛ¹V@ÌA2…’xB@T ½ë‹³?Š´»ò é"Àª!ñ‹…Úê¿‹ïëÓ³¿æ¯™;‰Y"ÀÒÒFgôÔ"@ª‡¢<6 @ØF÷®¿Xm¢°ER@£.ïa¸1ÀºÚóÂ;ÀixåÝnñ2ÀÝQEr0§?Ð?UðÏÛçº@•J§ë:é?÷o`ØD@¯ò¹0R@Æ)òèÍ´?YË8¡à«Àzâˆø.é¿ýstM´¿­œìì@ZÁèÏV·-À·m<#DÀÓ+˜™cR@0÷g¹ç¸¬¿r|—}´©*À¯›wA,PG@‡•@ˆé!B@ Í<ø:x°?Ð?ÒÁˆÕ”‹&@DDmDíñ?(\´]`“Y@î÷ñ÷˜D@YÍ/„M‚¼?/oŸAç€&Àk;ÓÆäñ¿Cð×Ìt¼¿:›¼@ö"À ¸?'@×Så )§@¶éã1¹¬¿N -†Ž]R@©ð¸î2ÀˆY(¾Ò9Àb"2s3ÀŸh]I¨?Ð?{7Þå„"@ôxÃp5hð?Ï:GÜF@ö &­S$T@©€J-£½?QÑAÔz"Àdq§¬`ð¿Z„‚/½¿³_ðF@|¦Ö<2ÀF°å”üFÀ³+Óý|R@§ýÄêIõ¨¿ì â,Àñ5£Ã×B@ñ5£Ã×B@,o#Ý“s±?Ð?+ð)¸‘Ÿ*@x¹STL—÷?–d€« \@MÊA‚ÜF@×ZšqçÄ?¹ËpÜ@’*ÀÓÙšº‹÷¿¥â:ŒüÜÄ¿”RÀf¡Ì#ÀNú+@¾‹ÇÊv$@Ë N\Šõ¨¿Kû‹vR@fP?º*4À¼ O€÷3À¼ O€÷3À¡÷ö;8d©?Ð?¶Á\gz%@»i@õ?)£Ò¬îCI@Ä()Å7V@ÑyÒάÁÄ?éÍ..o%À Qÿ7õ¿Ò “Ô¶Ä¿Z²›˜±² @bË-œ_’5À{>ë­aåIÀ9íï•R@ðºÃ¯Fh£¿ñR9„-Àš¹Þ¼ìª4@dâB%B@AGæC²q²?Ð?’{ЍÄ7/@¥T_°þ?ôs¦7Lã_@h·ké/DI@%’[:E+Î?;êÿ3u'/À[V þ¿P¸û ‚ο™q÷ÅÞ$À¤®§P3„0@ƒ©1.žn)@‚(Ìxh£¿ÍÔDR@uB*i–n5ÀfAãËók'À7ÙfRu~4ÀÅrèw!‚º?à?CrŒö‡Æ8@ó…)4é @Ô‰ %ÀÐ[@½åjTPkh@$›·þ:Ý?e!¬ñ)¹8À³w¨1¯Ú ÀN3`9+Ý¿`…€ÿ´B@ø´…UÞHÀ Ê´ Þ\ÀÎu?८b@"§Ú§¿IæWA¤ý>À^ÙR@÷ÿ6«rÃ?à?ù?Þ)‹/B@›¾¼êÏÀ@²à‰q®q@–€D÷Ñ[@èßW­ªtå?ƒ¿mU»%BÀ¬Z¬–'¶À"›0iå¿“2Ÿë.6À$ÛŸa]6C@°…FÕU9>@GÙø‘§¿ÙÃÐG©b@òͺFÀac8H2EÀ³ b?²¯?à?6PÓQHý@b7ÊéŸOÍ?Ä—•ú C@™àAÙP@©m+e}…?ÚóóŠÐ÷ÀS æ`›GÍ¿öXq;„w…¿^ÄKáwº0@þ«áÅ)?2@GhDÒQú8ÀaºÂŸa@Ûœ’t(«¹¿À%z,-t1À;ìþq˜MW@!ódaQ¶?à?^Œ–|(@¶Ó&¥Ô?þÒ’³Þ€W@^®ªÃ+ C@2(éΖEŽ?{C±­Í À톮}`ŸÔ¿›þN=Ž¿vA`;Ààï()û?JÑHÇ;À\­´»j«¹¿ÔØUT›a@©À6ÒÔ’8À"Oè©31EÀ©NÇÜÞ°?à?t¬}í¤@ûP3äÁìÔ?*‚SðE@+¹PçƒXS@)¨íJÄ‘?KtÏ]VÀ&MPæÔ¿¼‰oÒ¾‘¿ ¤X¦ƒ®0@ƒú‡¶¥9&@ÿ/'+wAÀJ¹þ]µa@à¥øW"®»¿æl¢U«2Àôו´±D@ƒò’(ëGW@ÂÏÀ>y$¸?à?ʳ’„¡£!@Ìîª9ôÝ?×Ï1 Åb[@þÉ'ŒðE@ò/içn™?’x¼¸2ž!Àùƒ«áÿêÝ¿åg™¿ˆî£)I*;À1÷ª>£@ƒ »Deí5ÀÝåÍÐi®»¿Pq/Ðn°a@2åë‚¿µ:À¢-ö›¢Z3ÀWótïöÅEÀ†b^ƒÁæ¡?Ð?È­GFa@ýÞÍ7EÍ?1#k—9@›ü F@Œq„ˆŒ?!©üîü ÀKî%ü:Í¿i×ù¼~Œ¿s¶äT… @QC (@%zOÀçŠ6ÀüÀåCËQ@D /Ö7­¿ók¿è#Àû—AìÝB@1 ÂøAG@ÇK1Cü©?Ð?ª:Ë¥Ì@Õ~KÝA@Õ?¨TmÜ:œO@ècNQ9@Z¨f·”?Éΰ%-ÅÀ‰gdUù8Õ¿G†÷oL°”¿mÚVnÐ$+ÀÌ(ß<±h@¢6Êã5 À ¦•"8­¿µ¬\ÝÅQ@Ohnã,À2•Õe1À¯\-7e]6À2ý°HÚð¢?Ð?ã(bv@Öý­ÇœÔ?{OBNÏl<@ß3eòH@ã4-˜T–?ÿš”s¢ÀqXÏ’Ô¿Ãû+L–¿¶ôæƒ> @%á:[tÅ÷¿ƒÃ¶†ü¸;À¿A{áQ@›Sª ®¿z’ά*%ÀBBåÁ;G@BBåÁ;G@ÒQר«?Ð?¢¡­ž@²(—e‘Ý?ç”1­çR@QŸm³m<@ijÙk ?¹íB£”À™Ù>†Ý¿ñЃó§e ¿dù‹IQ+À tÉòÿ¬@TÞ²ÿDÀnK ø ®¿´wÖ«ÛQ@•k®G/ÀYvˆÌ’÷6ÀYvˆÌ’÷6ÀyÔ4ýÃ?ð?nJA[ž5@^m&%-û?ON I`@a©ÿ´Ýl@e]É®ÚÁ?Ʋ±z•5ÀÞUÕšû!û¿í•×˜Ö Á¿Æóh™»¯?@l¶¡ÅkÕ3ÀÖk`Àp&¬Â øq@ØeÀ¥–<ο"çÜRsFÀó9qƒkÉi@õ€)G5g@–k:PºÍ?ð?Ηõ@@ò¢‡õ[7@"Fì·t@_¤F`@Õ$CÛiÉ?+”Z@ÀK\˜A/ÀÿÐòåj_É¿ûài•b±KÀÜ"66>@ÎjªÌ$À÷ül¸ä<ο&Ovçñq@yCW§^°PÀÙÀQ3ZÀÍ©`–”WÀ%ßV*à Å?ð?3)lj›9@L[y|'@Jõî£òa@@ òHeo@ÈNáÈšÉ?2/uü9Àô‹[}#Àùç¡DrÉ¿àyTú£>@ ®Â¯yË@À)Ykk3cÀÏùÅûr@)„ªöZÍ¿èFX¬PÂGÀ#È_•íÁi@»Ío‰.g@-|cË Ï?ð?îóþ¶?C@¥_ú88 @éNÿ7w@çúù3òa@§x»8=?Ó?ˆ1_{17CÀoø«>t, À£§ë·6Ó¿¦|N2áFLÀý v6 *C@€tyXÅ?èÙÁçA[Í¿·Jäžr@úõ;§ØQÀ½Ëd åZÀxÀ¶Z‰4XÀBL}ºì¶?à?s9÷¨.@:~êÐ÷?phdT@™ ¬ya@ýQá0i×Â?´)èp .ÀêÄjÔªÅ÷¿>l÷‚οò¤›I«U-@P B^š7À§(çcôUÀUm›T&b@* VF»¿¹V‰5÷9Àsn£È‡'W@sn£È‡'W@¥Tc 4ÆÀ?à? €5ú—Ø6@ ° õ@â›Óæj@(Ê/ 8T@Éx§ü˜Ì? 03ˆÍÍ6ÀÃ`Ü™k À¨}£6z‹Ì¿jùåû =À •‡è|…7@PE·Ô3Ø@3 Þ{œF»¿mKLâb@;)L‚DCÀ)™7ˆ×HÀ)™7ˆ×HÀ9 l0Ç?ð?ûð½P“A@^l¿(xö@–r"½2f@›=?^s@h½&Ž FÛ?XBƒ™ŒŠAÀÂ÷¤çÀÑns8Û¿FIæˆÄ;@j.)ÂVNÀa+tK?ÃhÀ‡ìZ!>r@ é\]LÄÇ¿çîRžtJÀ{G¦üa@x0üC g@Ú½ŽS¤¾Ñ?ð?º¯åìéJ@‡Q%Ü@´@¼àj#Ç}@uqt >2f@úè¦õ<áä?ý/PÖ¤ÛJÀ6E,n¨ÀÛÛ“äÒÖ俎f ™NÀš‹µ/L@æG.ÚZ4@Ôñd»‰ÄÇ¿B‰mÃ7r@¢¨b‘…Ó‚6F@T[þmö@@ á8JFVUÀ)’ì¬|q@ÍykÝ»üÉ¿]äÞ®bAÀ€Äqó¸‹T@¡5N0§®i@ÞÝÍÝh×È?ð?¨3ZÜU52@œÐbï? èÙ½œXl@E—1JU@ˆÈ²9lª?íÈŠ¶/2À÷Ô€Z~ûî¿êè¾^dª¿ jŸÅRÀîçÕ•FL$@rµþCæõNÀáÈ/÷þüÉ¿ƒžùD5wq@§Ùêe]#KÀ›Û@«çDCÀ–!XÀ[zE\ìÀ?ð?ƒ×uÏún,@?c¡Y(Äë?T¦PX@§¢Ûì3&e@‹P~&X«?eŸÖ8e,À›Ü ¡ºë¿(Ž÷ «¿=O­ãÔF@1‚mó/Ø3@O 4&ÚYZÀãwÓ’q@Ó©ùsË¿³D[Èë”BÀæ/ûõa@_ÿh‹¨i@½óO¥ªÊ?ð?Ku«th6@¨N XÕáõ?h§ùivLp@ÂVNPX@áÑ~Ì^^µ?¸9Ä`6ÀÀʲíRÚõ¿¹ú“ Wµ¿~.¶•½)RÀûÈÆ σ0@Ì~Û8|jIÀÆP}Œ@t˿𼙌q@——l7ðDMÀâç†tOQÀDKMv¦ºXÀ{osàñÁ?ð?š@$Øk'1@ æ»t‘ó?ŒÅ'tH‘[@ó Ä|ög@0çz%ú-µ?ÍØ ó 1ÀÇV}`ó¿ó~&Šü%µ¿œaŸPâÑE@UÙmʼn@t…¾w_À\ÞŠ«§q@µb7ö8TÌ¿Œ»Ô´ÌCÀïrçïg@ÏFÀ'¢i@oñŽ!wÌ?ð?0·JƒB;@®$=Jþ?Onq Á˜r@l3~¢‘[@¤ßÑÔÀ?¼]3o:8;À-ÏdžÏ>þ¿bG\u¿ÍÀ¿ùyÆî~WRÀ–²Ë¯¨j7@‚jn[DÀ½Pæ‚TÌ¿¼+»^¡q@©áBµMqOÀ Ë¦QØVÀ@âœË!bYÀyÿû’ù²?à?ug´©Ü€$@ÓMiÌ`Àé?G”Ø=O@FŠáVûZ@¡Fä+°?Þ/n rx$ÀZN­Îµé¿­<A%°¿X²IíÐr5@L„pÏÀ¯Ÿ«ÅSWRÀî„Å—¥½a@eÛ¯$ t¼¿˜Æ;E 5À¬–Ô”z›Y@¬–Ô”z›Y@CïÆJž]¾?à? DþÓ—i0@\žû ô?,1ïtue@ôñ+ ŽO@ýÍÉùÆã¹?nÛb0À°9‚Ë•”ô¿Rï¹R&Ù¹¿‰¾ÇVÞžBÀ[RŒöÞ.@ÖÛ¼Ò¤}-ÀNó¾œit¼¿mZ o ·a@~õš°qÔ@ÀXH >¬ JÀXH >¬ JÀù¢ùÄÄ?ð?ÿž‹åL8@#>Y¦‘%@õнÊea@>š*Ç/6n@1ÅËò´2È? )Áü&B8Àˆ=WÏüÀKÎZø(È¿AQä»ôD@âç‘lϨ5ÀLR2˜eÀcó­1ûÓq@¬Ùj¦Ë¿8«91ßMFÀþ?ž¥†”i@þ?ž¥†”i@¢i#UÐ?ð?n‡ï°}•C@$Q’Þ4£ @ìj  åºw@U怩÷ea@#rpab€Ó?=<üÔŒCÀV;n”ü– ÀÍÃwÓ¿v²Þž»SÀ°¦©qC@zâ*L}B3À%±Q}N¦Ë¿\vÏ3Íq@$"7 öQÀ¤—fYaºZÀ¤—fYaºZÀP€{¼Å?ð? f£6•<@F½^E}Š@åý fdc@‚¦¦—AÔp@¿ÉÎÆÑ?A´¦—‡<À`9cÜÀ{ίUl¾Ñ¿!]*²VD@žWˆ×AÀÕ+ëd¶·gÀÅü´êq@Q(öÙË·É¿z-¡­Ì—GÀlôÆ`*ÿf@[ù‡Ki@eˆ”Ñ\Ñ?ð?%Ä·£-G@ÖdxG@bÉ=¶n“z@OÕkw3dc@–Ç<ÈÔÜ?zEèµ"GÀX AÚ>Àÿ’hæ/ÇܿȢ‘‹~SÀE¨¾G@œÏs:¬"À6ºA¸É¿ìFz½ããq@!ì  ÖSÀF¦´ëo­XÀicsé_k[À–÷¶#TÆ?ð?)iâç²±@@an×­I @´Öx¸#ƒe@ãÈ—áë©r@åL¸bß°Ù?Ìã¬wc©@À¼è¼; À8ö§n¤Ù¿à›“¼´—C@œ6‡ •UHÀ¨Í°%}jÀD . Úr@7à+I«rÆ¿Æ2ã3`èHÀŽÌUˆ¦Ýa@Û UÉ…i@YEÉöÒ?ð?¶GB0;K@sÑýB ã@<„G}y}@À{>D[ƒe@ÖöM ôä?õý¢-KÀÙº£4'×Àíc9éä¿'/²o¬TÀ€-lŸsXL@€yÛå5Ñ?%fl?årÆ¿´†@-ûq@X½XLTÀž`uÚ¯SÀLŠ^Ê\Àiž×X[/§?Ð?Åx‘×5a#@™à>&‚Óò?™z0æÄG@~wޏàœT@ÖÚIÂ?ém!W#À-*7p·Éò¿8þˆrW@¿ÄSž´¶"@v€lÿú.ÀGüŒQMÀ½ÈiwR@³V_G›¡¿/\÷«õ?*À‡]4­Ìd4@ætØÿ}I@+^&5³?Ð?×UÉÆÇ/@ÂîÂqfßþ?|¨d=m`@65¶CWÄG@ rÜ©ýÍ?¬>·/À¿¼:¿WÏþ¿†Å’îÍ¿¤ÙåýÁÎ4À¬Ò•² 0@øø/ê+@Ð ½L›¡¿r,Cì"R@ô?鿀5À32+Æ'À¼þµ7Ç×<À‚¼ ræBÈ?ð?zí Gš^F@4¶,Uø@ÈåªÆÓ'j@ ÌíÄð­v@·?4·`¯é?Ï#—”RFÀÙZ©rëÀQ!\E’¡é¿ (êš²A@ï>ݵÆRÀ !ÕkpÀDàe”1r@8!ևᵿ<ý¿BóžKÀB¯}îui@òª§]+ûÓ?ð?:ƒ5ÀÅnR@QÏo¾dÀ#@ìtÀöù%‚@G´O(j@Ço’¾+*õ?^ 5HÝdRÀâkËÆµ#ÀÝxTËõ¿iT]¤UÀìçc²ü=S@VÖœZw2@K'TÀᵿt|gîØ+r@k…à¿ç¼VÀ¦„ès“]ÀìûÙîÏö»?ð?´~åoêÝ!@úzïŠÍŠÚ?É]9ÍßQ@·^¥†÷^@I.K¼·“?›NÝÏùØ!À…hßvƒÚ¿I.CM“±“¿xö ¸K@k3Oœœ¿M@6f4­æ>TÀÍÊià0q@øž.¸gÆ¿¬Œ ´Å >À!\Z°…i@Atv¬½Ç?ð?í÷ñX.@Îÿûbê‰æ?®Ià fi@û9:¨ûßQ@\ý ?u6H£O.Àå}¯ƒæ¿›: g"¹ ¿©¬¨e!lVÀuß´_s@iD¬&¤§VÀv)îñgÆ¿Høã.h+q@ñ„ m ~IÀT0Ù»f\WÀÉ4A¶Ôð½?ð?JžÅ‰@&@1¢a&·ëâ?Æi^(•T@C––šÄÓa@ ïòd’7 ?TШúf &À„€*Øåâ¿ñóø-Š2 ¿}o%:‰µK@}ätþ¬¯F@3U0>YÀOçAnEq@>­ÜÕ,8È¿Y³Š;ÿ'@ÀuIPefT@Ó[¤¾¤i@ï2Ó3>†É?ð?”\ð—[Ó2@ÑqmÞ±"ð? Dë…©Xm@j–³ƒ]•T@ò[Nzਫ?ùì*„Í2ÀÒˆÕ!°ð¿Ý öOK «¿O¡fjôVÀ¶·°AzÓ%@Ê»NOæSÀŽ1_k8È¿½²y?q@ -ÝNî‰KÀc÷$TÑ.CÀ<5.©…úWÀ]bËàî¯?à? ¥ë¹ñ@ ïy‡ŠmÚ?}Q½™b‚G@mÐøÀ× ±bhÒ¿^ßåì²*”¿^ŒG?²\+@v™kѲu@ÅŸ§:jAÀ´±ú¡ZoQ@ë2lœùuª¿=š®ô³}"À=N}èF@CÚ¬tI@–´,9&­?Ð?äÄ!¤ãó@æq,U%ß?J5tES@Tº$<©:@ú‹ðZ¡?™;èŒRéÀ> ß¿Ûcôº„S¡¿ )èÐï6À>ôÓx0@V ÿ’--À4ß=ï=vª¿ô²×™hQ@…¯YDÀ/À¹t_ç¸6À>Hø9?9ÀãÒ íµû±?à?A|nàt#@w•ÄŠÈwè?Ü­=¥m N@xÑñU.Z@Aí®Å®?”seâl#À(ÛÞ »mè¿üuq{¸®¿îB*F·;@_G`/pý?Ü…´å¢ TÀârÏ Å„a@¦¯Hûr™º¿­ÓI<µ°3À™•´ÁìmY@™•´ÁìmY@é.ý¾?à?r¥ã—YÅ0@f µ?,õ?Å; V™e@Åf6» N@”›ŽÑ…º?¼¾y¶u¾0À*¯I ‚õ¿wýéìzº¿æq¾vMGÀèöeLål/@Ôø} ¸8Àγ©·™º¿óÌh:Á}a@«Â(¢õ@À=Õ„$ýåIÀ=Õ„$ýåIÀGÈùOÃ?ð?aH€7@ NaÊiG@2²¤,Ô`@2«+Óü%m@ ‰G±øÆ?ù´\7ÀJ‚žE7@ÀåDÞF‰îÆ¿|rzŽŽJ@¬†±5ô#ÀÃcòÁfÀ@… ™‡šq@oΔ4yÝÉ¿]CÒvéDÀäܘ{gi@äܘ{gi@SÙulÐ?ð?íh*8ÊòC@ÜBÉlB& @ DâÂ'Bx@²¥ªXÔ`@Ì’%¬lÜÓ?[¼ï`øéCÀÿ`[Ð ÀS¸¤ÓÓ¿”TteÅWÀ¼T׃¬C@±™ŸkCÀíÁ¡ý»ÝÉ¿a–kø^“q@9ÖXÝRÀæJêÓZÀæJêÓZÀ,È^ Ä?ð?5?Φ«&;@‚i7b@æm-Âb@A©yÏ>p@¾í¡c×Ð?I ¦®à;Àc~R$XÀ)À8tÏп7ZÊêNùI@Ú~W7Àˆf½`ÞniÀ¿Re6¨°q@|T3þÈ¿âÆ;(FÀ½½×f@qÆ`i@Fô²ãÇ\Ñ?ð?ü4üj«ŠG@€§}Š@˜á­ {@—,™Ü]Âb@âÇò~4Ý?¡ГGÀB¬»;ÁÀŒíö^»&Ý¿\Ÿ0Œ†XXÀÀùëQëG@Éá¨/¤<ÀÐë\<È¿—ç[‚©q@'ÌÞ2SÀ¸* “ƒXÀç¯.DÜ<[ÀŸ€n6yÅ?ð?ÌVÆ¿º?@°™›rà @sÃ3Ðd@%«Er@6bO¹ KØ?Ͻä ùª?À>p2¤µ À-m€‰ø>Ø¿K$B=DI@çër–sBÀÄ9 bš*lÀQªÓ/Çq@ð°-Y¢Å¿b*‹RmGÀz,^Äܾa@A­ÏªÍYi@N07OÒ?ð?S]AlÕ•K@·.­¢##@YêVS^"~@Åå%ñEÐd@ÏãÏõÆå?W@˜1ˆKÀµ“íJ#ÀR *¥Få¿K”ÑYÀDD.tuL@æÜÙ¢sZ3À|Ux£ØÅ¿­¸?´:Àq@ ëÎ.UYTÀÇzà¿sŒSÀ°Ae¤7í[ÀCÚp«Æ?ð?£DߟhlB@‚DT³eÕ@@$Æø²þf@ò†`i"ês@- ß‘8Cá?ÛšêÖbBÀD$m"ÌÀê«8A:á¿9ly΢mH@>P`ÞIÀc—RÚ›ônÀ£X2‚'Þq@®ÎøÖ”€À¿4Ÿž¹HÀ÷b€ BT@²;àRi@× MEÓ?ð?öw˜ËP@ÆÝbY@À‘àÝC®€@¨–—Xîþf@eÆJ‰î?Y*qtPÀt—~Ï3À—Æè‘ü…KÔYÀœ¹cð¥P@¢}‘É$ÀѦs¿€À¿”ƃٚ×q@§½º*‡UÀKÆD<çFÀ3øU ¡\À˜2GJ-Ç?ð?\ GN³EE@á>5Áð@»;ÙöúNi@?`iv-ëu@5ÊÌ4è?9èíæG:EÀЍ°r•¤À¥˜˜ '迟–uG@(4Åñú£OÀ¼s»£¨æpÀ™‰Ë™õq@ºµ8€ôˆ´¿ýÊ‘ÛÔ JÀ4"1ªKi@8"=Ô?ð?áEòzÞ•R@ôÊ€_Ó#@†¡&ðýd‚@ä ùO 9wâgZ@öòtL&4A@•M_`Ò‘?’;öfàŠÀFó¼9 ²×¿ÓŸ.CÍ‘¿ús¾ƒ­JÀQã(ÎÔJ@2~ØSgæJÀA¼ôŒ«´¿ü¢À>—õ`@ ;µTé9À¤1X;ðDÀ u:Lø¬?à?–’…Æç@;€¶XJÒ?‘oÔåÒC@éÕ¸ö6Q@â€R†8E?¯Œö >áÀË3¢ ¤Ò¿ÂþÂòr;¿®1†“•@@¼e,¸™I<@TªÖù4ÄLÀÀé‹“a@C2N²d¶¿åG'¶õ-À™Xš8ä@D@­£­¿ÉV@ÇÐ!1º?à?Z¨xõñ}#@¦ÕÞ_Ûà?êùŽXb^@®ñÄÓC@Ùk!þ'?Á{¦¢Úw#À•º¹WÖ࿯ުá¿*ét1×JÀë÷£"×(@Äü«­9HÀ7záëd¶¿ ¶bî+ a@ˆN",áé;À¿C½^m3À8ì” {{EÀMúi®?à?… !ï‰@e༇Â8Ù?nºó‘ ¨F@k"šË ¬S@GïÛð—è˜?ð…dÀ MÓâ0Ù¿*¼¯ ùߘ¿ªpºÆ<‰@@†3–P5@°þ6FÔPÀÌvclã#a@¨¿Gº·¿¾ôž+0À-«—Ç%µQ@„·0%UÄV@¿9’^õù»?à?X§äd÷Æ'@ݽ@.d{ç?'t]^Wa@°E¨F@¦È.Á0§?Œ$¯»¼¾'À3Mþ¬Csç¿·‘žº(§¿ž€KÀ¨û[XÕ!@z{ûAEÀHX8‹@º·¿/ϵa@È>Vpô=ÀÎ8ß“#AÀ/’¤Õ+ FÀÈå2 ‘°?à?<Âê“Ü@\›á°…Gá?-;ffÓ´I@R¨œ…—QV@£<Ü“rY£?f‹»ÞÐÀÿÂ’÷@á¿Î•mR£¿ôÅOFo@@:6›'éÊ,@mÈn¿¤RSÀºÄšsy8a@©4YЏ¿Áõ„tÛ<1ÀËÙ} n¿V@ËÙ} n¿V@´i’Cǽ?à?ÁÇè²,@—&M¸…ð?TÚ•{¨c@)Á~ƵI@| /‚Oþ±?CÃmÞ¨,À1d\4m 𿟻? |÷±¿, {6rKÀ»Ö™ ì˜(@_ë8ÔCÀ/¼’˜Š¸¿<ž½OP1a@±ØI‡Œ@À$† Ù`™FÀ$† Ù`™FÀÆB±ïc±?à?˜¦ü‹¹w"@5üC·Mç?e¶ý ·úL@ŸSö²¡(Y@½-î)f­?Áf÷p"À¶ê°pC翣ŠZ­¿ŸåøF@@‘lÎÖ#@K€N­‚ÝUÀâ} [Ma@¹1Æ(±¸¿l=ȳËe2ÀvÖi/Æ@Y@žÚx÷KºV@Aù$™¿?à?X\b‰=(1@¼u´¿¥õ?Ï÷ç·T$f@Rx‘ÞûL@Öf bP»?Ÿ"-!1À‘ú!õÕœõ¿DèCyÚD»¿£Õ^m%åKÀ}³Á¼â/@±ÔLÖô™@ÀЇh±¸¿óç¢öEa@ƒ‹ïX AÀ‘pQ¿IÀPåOQ/,GÀ»ç7MÂ?ð?»g9&ˆé5@@‚"ô¤ùþ?Uœ…œ=`@¶`b…2l@ôzt®äÅ?ÈŠ_Õß5ÀþKïëþ¿ž0ˆfýÚÅ¿Û69cP@$ðM÷kq÷?Í"3h1uhÀZŒÿ†bq@ÁØé&È¿FV­26”CÀdÂÑ:i@AÞaNï´f@'0WÚ·Ð?ð?vºN¯”WD@ѱ›rÁ @ûC'gÍx@_ƒ¹÷Å=`@Yf˜‘SÔ? iàÏ“NDÀ'û}é·´ ÀYsˆ°JÔ¿_-ô(r\ÀÒRÃEÛC@’¿SgLÀ”ù dÈ¿ÉÕÉ[q@%.¿ð+)RÀˆ| ôleZÀH#¢Û®ÁWÀúóâZÃ?ð?%n_Ì9@èÐéÊbS@ùîç§òb@S|@õ¿po@²,C)—Ð?R7À9ÀyS)›ÎIÀv¨PøÏ¿,ñ†a2’O@ ))‡ÿ(Àâë¸kÀ¤wgWxq@»º¦%]Æ¿$n¢h[ÈDÀ$ñ^X¯f@$ñ^X¯f@g¸í†¥Ñ?ð?׬˛ïG@ÞI‹ðÁÛ@´©‘î¤{@¡.5j!b@MÝI·Ý?«û TäGÀð@FÆÞÒÀ–ÉÀËH©Ý¿]ù¾%]À¡q·% H@vh÷dJÁGÀw>DäX]Æ¿ÜÛü$­pq@ ÞÝÜíCSÀ0ú¾ùYXÀ0ú¾ùYXÀ“èk6œ Ä?ð?²~ÅÑV)>@Éζ‚ ^ @Q:¥+-d@ú°S“Krq@φ¿êî ×?¾VY>ÀÊqÂðP À1š+z׿¤¤îoæN@€t¥$¹_9À†:˜hbÌmÀ9…{åŽq@bœNËمÿå iƒFÀ*æÍÈL a@ÉÞQK‡©f@&˜û¨¨•Ò?ð?µ¿ï±àøK@µôÿt@Ì0«~@|Îad@|-+Ÿ›`å?ûzÂùêKÀäm]ÁîgÀü¥eÀûUå¿P0Þ]À¼Äj+†L@ ÊpBHCCÀös4 †Ã¿W ëgÛ†q@‡=M«dTÀq±:\iSÀ$ä&8-õXÀ»Ü!Å?ð?O:Pü„A@o1´ÞOì@rôëó6f@bQ\iÄGs@Y…áæÕXà?ÇX ´ä{AÀž~~‡ãÀË6)ZPà¿%T­x‚N@à? 2µLCÀ?›iwRFpÀ†âg¯j¤q@¬^Vsì—¾¿Ÿ­ýBGÀ‰ÖѨŠT@Xìý{£f@Uz2PˆÓ?ð?9ßE1>P@•£þVIa@sÁÓ¡3ñ€@á?ØMY6f@\A3ÓOî?"³©BÃ5PÀRK=QÀørÔ@î¿§á7}ô¾^ÀñF5/Ÿ¥P@s6µÝ=À²5Øq;˜¾¿ÃÇN¦¬q@C»/²‹UÀºæTGì»FÀƒ?Ði“YÀ"þÆ?ð??$Àéog0Äù?t¶ÔÆ?Àpô&¬â¢¿D…¤"ÁP@ßânM*ÀVøÒ·70ÀŒÏ+ùLº?ð?\òAmzÊ#@¼7Ð7Pá?óÁ_,(S@»º½Ý:±`@6“`nJž? áâ<Ä#À컎Já¿%c«vv@ž¿j}¾ƒ~KS@QŠ-®™âP@·I‹\ž*`À§Î(ëÛp@âj!5†Ä¿®¢.0³;Àþª$fT@ž`y˜a@ÿ¿~A:ØÊ?ð?j ðÞC54@8@ Dn­ñ?r‘„°&to@uú@FYS@$WÙ#rí®?ñ/ϧä.4ÀÈLÂRÛ§ñ¿ ǵ£±ã®¿¡l÷ø_À¯¡ý†ÊN(@FKç’çu\Àrˆ j†Ä¿й…@Ôp@\ cCLÀÌÍÎiÈCÀô”\¡PÀµÊÌw]:¼?ð?Nðm3(@“ïUXuè?‡`ËôÁU@l¼iÎc@µ¹8Ú ¨?Ë·£!þ*(À©vÇ è¿ r‘/¨¿è¿qåAS@«hð„ÙÔJ@Ë)vÁ=•bÀ(Ð{ãîp@';¯/ÌÅ¿`\0Þ=À‹ò¤j7•a@‹ò¤j7•a@ˆ¡ËÁIœÌ?ð? +8±ñ‰8@;w3¯tø?];å(ãq@Ç}Xù,ÂU@~sà~_¸?Ëþï«d8ÀKwv)lø¿Õ ¦W¸¿î™4Òq_Àšƒ¯…÷Y2@R$qކíYÀéSq÷gÌÅ¿fc.L­çp@­ÊH’!@ºWÙHæ?ÇuKx³V@Ì¿ˆ<á;@5TÉ(C¬?QèuüŠ!ÀT<k¤?æ¿õÃo7¬¿ŸõPH3@Àw‰Ü¢ @ˆR¼ò­5ÀÓF߯¿¦¿H4Ž4žQ@¥|¬)01Àk‚Ã9³˜9Àät¢Ûãê1À˜ø ±?à?ʱFê<Ï$@o›Êׄí?«Ò ;EO@ÏË7 5Z[@$J*Íï´?(ßtÆ$À÷wñÀwí¿Mã çƒæ´¿$ýå«~ÒB@7‚&P>Y@é¤ N¬ZÀ9 .,a@Y=w$¶¿ü¬OM2ÀñríŠY@BP .ŠQ@^•"“Á?à?Ky´ÎÃ4@T2Tà tý?x[^µL\i@Ì¦ŠøQEO@ÞDsMäÄ?`Sˆô˜º4ÀŒ!ØVgý¿^ÖèÛÄ¿ÛݽðÛƒPÀ£ŒÊþ3@Ù!W½BÀÿ`WB°$¶¿¬tRv:$a@G µº+?BÀžÒ36;JÀ­nñ¥\BÀ”Å´± Â?ð?¤ß°Efƒ8@žïËGâY@S¶Þ¢²qa@Ç:€n@Øò]åRÎ?€?ܸÕw8Àj”Ê.ÁPÀZ é~οß/4•zR@ð×8ÔV迲泹lÀ‰P¯ Aq@ìÖÚ°äšÄ¿²±_Õ^c@"fƒèíp@’ÚHMðÕ?IÂBé<À´ª0èÿ ÀÞ¡riåÕ¿{š¬ìJ?R@zB&,Àˆ.‡ÃèboÀ8 PkVq@7)o’?Ô{&Ž(ÀÖЩjè\׿+дà?’¿€ •ýoöU@K¿d¬ W@| ƒñŠ_ÀŸ¬a¯µ”p@ÓQs¾¹Á¿Ûô}jx7ÀâQàîúS@PѱzÀÉ?ð?zÌ•*1@äÉF3¼˜ê?Þ—Ñí†l@¸¤ñÝkO@C’‹š¤?í@ï@¬%1À|¿â‘ê¿ZC¦”¤¿üÙ‘|aÀ²í^&‹ã@|ô8ÅaÀÙÄÎåÁ¿6©øØýp@!½µ«JÀ‹¿›QtBÀÏVCx‰˜?Ð?·S^’Ý·@ñYØ—™À?3´¹QÒ)2@½ª^P6A@@‰;ŸÏ_q}?©ÍªWæ±À4rìqM”À¿jŽ}ýg}¿\Íçn]ü5@œ%^ƒ·‘3@£³I,çAÀ§ìp©Ö§P@^Uƒ0N ¢¿–| #‰ÀΊ–˜ ÷3@Њ–˜ ÷3@ƒÿ/¬{«?Ð?”ª`Òjù@Cj AÉ™Ò?+gü“GP@¯Ù7*2@2Ésïê~?Œ›ð„»òÀ<¨ˆœÛ“Ò¿s| ©y¿ˆÒðÞâ¥AÀLíg™G @ï]Ó#èM@À³ñ‘H~ ¢¿Ûá"ú© P@O¼µdƒ—,À¾2îê"À¾2îê"ÀoOf!énš?Ð?¡ÄE%zê@ù[`É"Ç?aʲüÐ4@+š8§ ’B@3yxf&F‡?|š@ÕlâÀˆ-MnÇ¿\0`àø=‡¿VoÐ&~õ5@ÿF¨·ñ0@ÔÑ8jJDÀ¹Oã2»P@Á3½ñØ£¿{5*X™¢ÀX÷1TžuA@ù¬]©"ô3@gÒŒƒ;­?Ð?âL ¸$Z@J¹Hû§ŒÙ?c/îð¶rR@ƒ„r2Ñ4@ïaã¿™?Œ:DÀ¯ÒÏ.GØ£¿YÜ£³P@"À´¡Œ.À?†tB%÷0À“âòK˜c#Àêÿ"Xœ?Ð?µÞ޼#¾ @4Õs{Ï?·…’­“¬7@%åËNŽE@“88Ìô‘?vÝh³ À1ñÕa_„Ï¿Z8øèí‘¿Æ·Íàvá5@qsNc,a)@¨ZÁ„C¹FÀ@÷Ï+ÏÎP@ÓkÑš¤¿£ØúZÅÀåðMƒnF@êGŶtð3@2)tDÃþ®?Ð?±ƒÛðY@VÅŒ;#Dá?_óÜÇT@ÃZÎЬ7@)º=¥£?ÐúíKNÀÆïÅsƒ=á¿”Å<}£¿t¸EíÌBÀ•²Åáh@îTŸêÁ;ÀèR›¤¿¯ôÑõÆP@Þ°ˆE0ÀÀ\_M,Z6ÀW‹ÆD`Þ#À/1z Ež?Ð?BD­v› @5´à0£;Õ?3Á­ï½:@èÍËè½G@·FRÂ>›?o…så´™À3õ%NÓ2Õ¿Ä þ›¿¬§`Gè¿5@ja¿ñ“"@ðúp4IÀU3žÍ°âP@è.C &Ȥ¿=mã3¯ñÀ”Ð~ñ¼çH@ߦ˜'—ì3@S°ãÛjc°?Ð?ãæ‹™R"@S/'Öšç?¹Ï_OEW@Èaº4¾:@¾±Ý­_­?ôÀÑØû!ÀÏÇö÷æ¿MP}S­¿o†ü,iBÀyí³ÕD @^y¯õn9À9h6¶[Ȥ¿A\‡0ªÚP@pþ`¶I1À]çkÿ-r9Àæ…‰ÿW[$ÀÄ•ççúÀ?ð?5«/`Á3@ø•ï®~*ü?C7ÓÅs^@ÑUÇS›j@Ä7Ç#Ä?Ü:Î+–¸3ÀQöÀöü¿æÛçð4 Ä¿þdfinU@¤¥|žF¨7@~¬O¸íºkÀ¿Ù£•Ýöp@ Û k<Ä¿_o½ýAÀÞc ë¬âh@€é¡UŠèS@÷Ô±IÑ?ð?à †d7E@Õí$ľ?@m‡¿‰ˆîy@wW·LÁ^@ÝÓ» GÕ?ÂÝôô-EÀó c—I2Àî?7¯†Õ¿0ÅŠÎaÃbÀÎ4ªõøD@Ýl°]/.WÀ=LLŸ<Ŀ외ëÍîp@ SRÀI¤n^8ZÀ×é¾~“ÚDÀÒÄöym¡?Ð?{•¹òBI@who—râ?ÇÇÃ@@òw@š ªM@\r 9­?!ßåVA>À Š'­ai⿲à,;+­¿—ýb R5@ýİ5‹@1®O]NNÀwïeÙ[ Q@›"Ö4Т¿°—ñSX4"ÀœvSVØ`F@â…Ÿ…Nä3@Uþ]$C2²?Ð?J9¯.ÏÐ(@ ²“ÑA¨ó?¾ÿ¡ÆóÃ\@À¼¥QòÃ@@ÙÅßi$¿?t(äÅ(ÀþˆN÷žó¿I,°±¿¿f?ÉÜ*CÀdR¸,(@N[Ô"F5À;“ÉÀТ¿¢× nQ@1Çs«a3ÀZ  ®8ÀPí(\%À]2cGî¢?Ð?Í!áˆ@@—ØRâç?†¤ \¡B@‡A¡±uP@Äû«î´?ôÜø2À[HÒ£oÖç¿>Q•@ä´¿æUJ5@PÛA¥û翸RÛRwPÀ¶ C}2 Q@›yýÿY ¿´å’&Z#Àò·˜bçcA@„deÞãß3@ðì–}.³?Ð?ÄÜšÓ•×,@’nPGù? '”4ÌÆ_@ck$Œ¡B@“Àg\S'Æ?• ºÓ;É,ÀsÝ_}:ù¿6ƒq]MÆ¿hh¡  CÀàˆ,@&ÄBªñå2À”Ñû5*Z ¿4øÅ-™Q@ŽhŽìu4À€¸¾*$3ÀL®'Ù0à%ÀòšKŒ£?Ð?à¼:]Ú¯@âéËÉØšî?éá–»œD@ÝpT0R@+¸ÊL½?žãÓ«hŸÀmœgÙöŠî¿Ëy¥²õ½¿d^¶)Cª4@Î~Ô%Àè 4ÎQÀ{Žúh5Q@5· U™¿ Áƒ¬…$ÀŠ‹$_JÛ3@Š‹$_JÛ3@â@wƒ ´?Ð?~Ö#šª0@®»Ác@þÃ+|a@øßôÎðœD@ç2Þ^Ï?æây³k¡0ÀSìt À¹´KN<Ï¿½•)7#DÀ‚z~•0@ÓïÓôß0ÀëäLU™¿/×ð^.Q@Íèq5Àâ*'vÆf&Àâ*'vÆf&ÀN¯HÕW¤?Ð?ͽ'I(P"@ïêÓN6ló?ÝiL}®¶F@ʯ“ŸT@•òMz™Ä?;½WF"Àd†Íaó¿ÿÔ9pŽÄ¿Ð¹c^Á>4@/n¡d,ÀMûŠŸ+SÀ#ÏeKQ@ –ÎôÙ@Ž¿=¬º8·%À‡¬ÖÔÖ3@äuPSú´?Ð?G‘‹§'3@2ÃÁ$ÄP@ËÜñ,c@w»)#é¶F@\>á‹Õ?#ÿ[c3À+ËßàEÀ"jøU€Õ¿Äß\ʵDÀfóÝxä 3@Wvç–5Þ-Àµ}(AŽ¿\Òÿ\ÐDQ@Ò¬D^°6Àñ{pÞð&À ©ã÷ëô´?ð?FÙ6xju@¬ÅÆðvÖ?Ûj’ QÊM@Íg§.¢[@l@})©»‘?Pvü¼%mÀÆÍËßipÖ¿‚,C1‚¶‘¿Ñ> T¿ŸX@Α̵ݧY@Uá´JGaÀBD+cp@s¦ØÉºr¾¿Á‚ú}u5À¨<ÛádÊ?ð?µÃ4ë¿í1@Æ.«.Nì??AŽƒ¡m@–i0÷ÊM@¬ÿåW¦?IheŠè1À:´·àÜEì¿´”8gQ¦¿Ûæ:”‚cÀp² ­@ðÍ‘Ž¸cÀƒùPh s¾¿Bü¯ê\p@×UøýüKÀÚ‡϶?ð?ܲ,ªÓ¬!@Y± `„Øß?^Zj¶DQ@Ÿ+rLË_@KÍnQ°œ?†öϧ!À²Fˆ>Îß¿Z5[ì§œ¿ôÂá¨X@˜­É#œ2V@k)oä>˜cÀ*pŒÙÛup@³'–F¶À¿>,´tu7ÀU>H2™ÓS@K<|šÌ?ð?”›åiqÊ5@ •Y³l¡ó?,;¾±×p@¼#çãDQ@ü«åÈ:¯±?*÷¡iÃ5ÀYçèV›ó¿- :(†©±¿.ÀÓ6µcÀøƒ’_c*@ƒ\ƒVbÀWNì¼q¶À¿½*½\np@¨Ãê4íåLÀè¿w¸èÓBÀÐ œ\Õ¬˜?Ð?3FJÃÄ«@‘êÏŸüÆ? âÑGíÕ3@Bµ$¸‹%B@))¿£–†?8‹Á¤À 1#Æ¿Û{*8 Ž†¿µM3ªå£8@ 0lÅCÃ2@ðºÂEôEÀÈøHlňP@"›¶þà¡¿xs-M~À Uœ÷[VA@2î´>@<é†Üž[XÀË39Tì›`@Á•KÏö²¿)Dáõ+ÀHYû·¬FV@w–ìŠ|•¿?à?½‘Ê!ÞA/@X¸®~øñ?T¿ü°[e@Ù5'HšF@žèö9ç©´?Òy[É5/ÀÇÏ•Œññ¿5¹×¤ê¡´¿ Æ´€Þ=TÀŽõšX°)@ÕUµöOÀqNá&ž²¿²ì["Ê“`@Šz”[b@Àtüu[’:FÀxl4sœ?Ð?…Eçß.…@[KfÓKÔ?K€×fb’9@d_+æÉ+G@;Ã/I#š?Ñ.rxÀ([CÔ¿Æ¢È`š¿çØ\èÃt8@w¡ÝÂfî'@Ìr•’ÎJÀÙÉŒU¯P@Ý­ž±Î¢¿ÛBigĪÀ=k]:à»H@‘ÍÙh¬°?Ð?Wþrh{"@·~3Íç?,ÖÔý­ÚW@…þn¤’9@9jÿÿð¦®?Œr«ï±s"À£?¨HDÃ翳a5Q&š®¿kGz>”DÀ’Yó €^ @ÈV¯µ=ÀMƒ.â΢¿íúã §P@v¨Úãa1À*ÊK9ÀC`^\ž?Ð?ï¥þá½@ô3z\åÚ?NP©?À<@äÝk oôI@•³O†ˆL£?lZ¢ƒµÀd£ YÙÚ¿XGÕéC£¿ ^†‡I8@ý"+`â5!@6¹jMMÀþ zˆÃP@ê¿;²œQ¢¿„§mëÏÀ$T :·H@¯È5ÐD±?Ð?—ëÉ÷=²%@$R"½Ì"ï?ºã÷ЃZ@‡]íå‰À<@Ú_paW¶?7¾¿)¨%ÀÎzË“äï¿#½ùßfM¶¿8?IVú÷DÀ«^ %$@FÉWÜ¥†;À vÿËQ¢¿*tiǽºP@ñy(wÙd2Àç‡ç7{ç9ÀkVI Y$ ?Ð?ýàn@º@ÅÞ)Ù˜á?˜‹L‚@@_Ú“8íL@(¥IÅ?¬?˜(…2@À2*|b‚á¿Ü0nùõ«¿&aœe8@³ôZY@¼³a–vØOÀlð=×P@ÁYö¡¿b²6­þ Àß.Ë«:F@¤(½a_v²?Ð?ÇŸiBÔL)@Cõ7#ô?ôÒ.³@X]@K­uÌ«@@Æ÷IÀ?McþÖ@)À:þKû¬ô¿Ç¹}-aÿ¿¿?Ë!hEÀÉl•-(@”-0bEj9À"3ñ!¡¿ºw:ÈçÎP@`§ÔãÂm3À ©ß7À¼µÿ®±?à?‹šUä)@Í*ÄB»Ãö?TWz‰ áQ@8úe `@" $Ä?‘JB×)ÀÖ]ƒc¸ö¿¼ý¼ŽúÿâÐ]ÇG@~Œ-Ær@Id8aÀGIª&Xë`@̦Ì_o­¿õk$A2ÀßQªFQ@ƒ ׯ^Ã?à?xÐ2îR=@½ç ˜…È @àħ—,p@M‹µ³;áQ@ HfŽ«Ö?‹wËëPD=À,ú9¬» À!¡?2B Ö¿›MƒjÇæUÀÆ€e z<@^úXöBaGÀºkrÍ«o­¿Öºw™ã`@²m›|DÀíÉù2CÀ–²ˆo Â?ð?1Í;>@?Ïò2% @ÃuR|Ìc@¿ i‚¹q@Œ^¹Âx3Ü?ª©`>À»’ / À ”½‡Ó$Ü¿ —a…pW@ô‘_ÂIýÀ\©7ä@ŠrÀÅ4:Hq@ã o±Ž¶¿ç6”†ÆÃAÀ3·ÌkK¬UÀ–̃Ç~@Ò%Ÿ9]QÀxæU_hÀ(­A$ðj@mñýÛÛᲿð?×÷L[®_Àr”}’߯_ÀÀ×VÒá›@+óÔá ŽoÀ“¨`Ñvß_Àøªl P`@\¶4«\`@]ÚšˆTi`@…\°¦<«À@,¯evù?Jê„3†@EÑÇtõ]À*Iý¿Øt@?9ÂxÅø:@±-œ…H€@KÂ+ÝMD#@Úü@h‚Ú1×@‡[ØÀ é5@+=VÚ„@G„ ŸŒßd@ ]!‡'S3À¸2Œ®à£DÀ=¹ê5QçÐ?Ð?I§IZ T}@\ƒ-Òê¦~@Òc§Ó§ŽAÀl榋•@Å…9€@H*é§J~À Uçh§ÀÕ"”¸?Š€À ¨ô@é¿DígAßY‰@Ð"_%S[À.uV¨½X@aLoãÚ¿8nu3µ¢XÀÌ(fËû¬ÀßX)ˆ°ã1À5)rkFÀ†e˜D¿£_@Ãu±½iÄ1Àøèw“òâIÀÓ´ ŽS@˜h’~Ž„¿Ð?ªXÍEï1Àq¶‰¾2Àã»[@ÔÖ|@Òc§Ó§ŽAÀÿ¤¸ÊK–3À´C—FX…2@¦£‹ªõZ3@ñmÕ2:4@ÞåDË}ÀõÄÇ(@ÓÚaÆxôf@`LoãÚ¿ˆU‚µÑ U@¯•wÒÔ @"Î?@l’èçkˆ@^„ÉÍËj,@³Êx´Ï @À¼ÊÝ6òT@f]E(&À}aï+7Ài+2¤™á?à?Ô~mHûEŽ@[ÅFç(@‚ zµ|_DÀq{MP¦@&ãXÓ„@‘@6уiOÀ‰Œ“–¶ÀLS^¹ÇבÀ GÖ’Ì2Àkä¸Ú¶™@¼&:ºê0nÀ¹REëP^h@%N™º9¾Ý¿»Wƒ,iÀ·¼â<3ÀAó½;pFÀª‹ˈ\À¶I1Ø p@H} !±÷AÀfÉ‘zέZÀf1¦Ò¶c@P[ÞÛ†‡¿à?Ô£L×p5À¥oÓŸçl6ÀgWT÷,g@‚ zµ|_DÀ[<Û|ïð7À‚ÓôÚœ¹5@$°e†17@«ôiØÂ8@šBdÙRãÀËjs-®ÙB@O1îrýiw@%N™º9¾Ý¿ó„f Ge@CÁ“^Ô+@þþv5>ö@ï‘Î G{*@ÔibºÙ>A@ŽÏ,"@`ÉÑ\‚e@RçFÕ9À?l§»žOGÀÍ%Ð+áVñ?ð?’z)J,BŸ@]³¬ê ¡@ƒLêPx4ÀÒiKœ„¶@|\œ¢@ønM£³0 À×-Œ ª¡À•©·JG£Àq1¹ã0RÀ&R?_ª@ÐVê½€À±cnç x@@á÷³®òÀ¿ 7zºyÀ>áZðGÀ±aç”Ð[À¿™ŸifqÀ@@M€E€@d¤Ù˜¹*RÀ^7ŒÍ~kÀ~‘åfãq@Nƒ£¼v¿ð?Ì@E‰”O%À\ š A'Àü¥>Dºž@ƒLêPx4ÀáÝxÙ_)Ày1g&@wše¸¶(@iL I*@!€žÀé®k~¢Y@}G<ßö݇@Dá÷³®òÀ¿K*;Žnu@Üçf‹^@îa«Gè)@M“¾c@@.~WpT@ß!üÌŒ’5@Î Btvu@ ÷°‡ LÀäT—Ë&UÀ  Ù#/ñ?ð?ûîÎÂÀ$ @öâ ‡•¢@´¨ŒƒUE@o¨i£·@Ï HÏä¤@¼¨ÔÝ=À À~±¢Àø&9€Û¤ÀûÚÁp^ˆ[ÀèW(pRxª@‚ݽ@ˆ‚À„33@Wäx@£»íºæ?ÀüKzÀ¨¤÷ëôLÀ?ƒÝó¼_ÀÛ#£E§tÀˆh™ÅH€€@èà€]RÀaÄ#1õUlÀ7 –° l@”„ aÌÚˆ?ð?$µz~Ûo6@³a÷èZ 9@÷r ýµž@´¨ŒƒUE@ËA…õï;@£%öG7À;­Éaú9À[ y ý<ÀV²áåß%žÀn•ÎX``@†Á6äKPˆ@£»íºæ?m °ch—u@ªZ‰ywÙÀ À8Ë*@¹93–·C@@@£øŸV@åÎõÌ9@;2).u@ùÄÀÙ26OÀ‹wî –PÀ#qŒŠÊÑ?Ð?jßì"®€@Âôök ƒ@íÏ}pŸþ:@΀Œ—@”l“ª½…@–uCŠVÀ%ÌáÒP˃À¡t´‰*™†ÀNõ­ª¨BÀp£E ÜŠ@N›„åé—cÀë/(m(Y@G¤± ÅÙ? 린ÁßZÀ¨„Y¬&1À.{äŒBÀ*fèS XÀËó’ Ž¼`@3¼ÀJ 2À 3<3MÀéœ',(@@ŠH¹2Ñ~?Ð?7Tü4°,@ç~ÞM`0@Žïzu@íÏ}pŸþ:@‚ù¯2²2@°ûiÙÑ-ÀC’`¤1À]$Íþôn3Àê¢D»P~ÀRPV;D@F­YäÀh@H¤± ÅÙ?[Qûû¥ÁU@*à 5eÀö(qIÅ @x”½þ•;'@cîüv ñ8@Ò'ÀÃ@J 7ösCU@ `Cáª61Àü°¾¨#À-±Ðçùò?ð?¥;{y[=¡@+ ‰‡%¤@–¯Ë¾ðe@KDY‹O¸@†*O¶.‹§@@deUÌó¡À{Ug®»ú¤À+V„¨ÀÖõžÇgÀ6 æB«@@ÇÃÎæ(…ÀÙ æêly@2åN3s5@6[kšÃw{À¬”MÏ—þSÀSNÙapdÀ°%]ÄQ}{ÀàE$Ö­ù€@½¿¡ÊZÂRÀœd̆nÀaG V¿¨?ð?[HÝⲑW@|×¥‹[@j£öÞ" @–¯Ë¾ðe@§4 `@2¬±1‹XÀÔºÏ÷‘®\À(îé’TÂ`Àžò‚g[‚žÀ…r“.Ìh@µãÿZ@ü„ÝG@@˜Þöˆ‰Yu@2´Â\¶ßRÀ5)vm†ß?à?‘”sоžˆ@7S·é†@6Xü„QdÀçì%á£@R,qÆQ…@Q¬¸“<‰Àðz{‡À ì—…Ú…À³\×˨êI@#!KÞ‚—@mµ+=Üó`À$_‰0‘f@uÕ¨¯ý¿\§ï®eÀ»´°@@n:ˆcÅ!@‚f@ó³ä(ÀÀiŽçòm@¯¾ôu(@ÀË µí”±UÀ­ÔG4ŸM@ ͤ\85©¿à?¤¨¬+«»SÀÖ$•Ý\RÀ++ Š@6Xü„QdÀJúN^lQÀ-B§ðÆ9T@ŸºÆx7ÒR@ -ƒ ƒQ@n/´i;~Àð0öúŸ-À<§h?Ømt@sÕ¨¯ý¿¾ç2;.d@2‘áq\N1@B )9N#À_J«â®—ð?çrÒûÇ%À0CœI=@ÊÅ)@ŸÀ2»IEA@K3¿a@@¨æ=ªÔ?@Í`gñ‚}À˜‡Tv¥rÀÇt Säd@³ÞÜAg`é¿Ûô#•œNT@È^ IË;@±*ïW#À¦¹ê£§ýú?ønùŒ>ú¿6úþà2Ãü?ïÄ ‡èLT@6˜B\³ÀP)Ð ñ°!ÀP)Ð ñ°!ÀïBÁ8û'à?à?,>Ã&Š@‚÷#ïK‰@ºË£›ï[À^õ"nè£@"Âñçxˆ@ÁC ÷‚ÝŠÀR|¿eý‰À/,Ç–$‰ÀѰzf`8@—¼}£ª"˜@HÄGfÀƒD/ý~g@s‡Qãi¾ô¿Å¿Å’Í›fÀ ãFM0¾õ?—®^cà Àò†.SÂLKÀú Þ½ØÛm@9}^l‹@À^ÖVà WÀTå?‡TZ@6áÿuN@z:1Ó­ø ¿à?[Dˆã¿KÀëEÂÈÓ©JÀv¯^íYÙŠ@ºË£›ï[À¢«¹eËIÀ^ÛQL@¤ÿàdK@vv†Z€J@›X(deŒÀÀ ’’@üèﱨYu@u‡Qãi¾ô¿Ù~pd@P&S²Ø¯'@ðcM“QÀú»ÁHr@ÄEŒ:ª @A¼T÷@ª&oí´]d@BÕùNm1ÀD:ш™7?Àwà Ö1À@Ï­ ¤[ð?ð?Mèø¬÷š@°R™pŸš@üN`‹h?eÀåÖùç%W´@ó÷¥íTHš@|×” ¾›À]ß$Gc›ÀG7‰´ª ›ÀE,&ÇL.3@‰-c€v¨@ ¹22ÊxÀ¹²†¸;Cw@Ær“‘„‹ÿ¿äuú~wÀ ¹ÖœŽ´À’>Ì3G1AÀ~5‡R/cÀx™šCËC~@1Âügº¼PÀoŒXð¾gÀœ3vCîq@÷éCÍ5U^@ _ Î׉©¿ð?¼¨¬% %UÀ´š# ÚßTÀ/l¬\JK›@üN`‹h?eÀß$R›TÀ½c×’“ÀU@~” gyU@åíi$3U@i·®‘ÓšÀ¨ ÷æokA@>!¹ÁÍ…@Ér“‘„‹ÿ¿eŽ˜(w’t@±L½ÖÒö1@–•¦17'ÀÒõšŠä1@Ìoý¥)T4@orSÀÅ)@‡Þ̵ ot@$`[í±DÀ0ûžéè;TÀGßpA]üAÀ½ÞV¨0à?à?ðœgÓ‹@ž[UÚ Œ@îo¯€ó¦LÀ°:Isɤ@=7%$EŒ@„ ǹ©ŒÀÑ=¬FäŒÀäÄêñIÀÉìÎ/¥ÃÀ¡°4uù̘@ï·cÈu…kÀ¦’ìJg@ØB«úZçä¿— ¥ØÆ–gÀìlF0ÀoëÈêN:ÀÃÏ3;]çXÀæ˜VÐ`®n@Q§à+Üí@À·"v‚(xXÀ%ªsqc@ÿ;¹è“N@ó[¥Ce‘¿à?z‹xH4Æ<À±Íö½ú=Àx Ë‹@îo¯€ó¦LÀÚŠÝA9<=Àxc>¤=@@‹¶Êà=@‹5Þ®Ñ>@ØÒŸy®À¹cº…¹K=@Ä‚å…@v@ØB«úZçä¿¶ýK ¶d@P—ô@@ÚšBÀz³=œ&@`ñy+K0@‰5Ð7Ï@  ÎOô€d@¢º¿ËÐ6À`æa+»ªFÀ€ëçU/"2Àª?¹«¨Åà?à?¬$m¸Œ@Z{•jô’@‹Zd½Ä¨<ÀÌ  j?¥@PG¬núsŽ@~/5ý Àl+n‚ŽÀMtX%’jÀÆOq«j?6ÀEéB &™@ÊB³jäPnÀ¶ð×t™Àg@;‚l)]Ó¿?$™¯hÀ¤ãhU˜O$À¤wbVqAÀ5DPéÐ^À¤f³É‹o@šøÈAÀc{B'8YÀÆmUÕ$Dc@>I""nÓN@Ùjn)ÿ¿€¿à?CHËÔ-À(‰–íë-ÀOM cüXŒ@‹Zd½Ä¨<À€ëg€˜Ï.ÀÛÆ … ú-@!Ž7Þ.@/×½É/@!ÜÓ@˜ÇÀð9¯6ãD@#*V:ܱv@<‚l)]ӿлZËËÚd@o%Ñ„Ô@P”ƒÐнÀ½ÚdC‡Š,@bâh˜6@ƒSŒ]ù #@æV?v“d@»…˜¢9ÀBSØ-ÚFÀ›B4­$H2À#H«üð?ð?;4 9¨@o…Æô£6Ÿ@B†´‡,ÿ?Ù›÷0<¸µ@"–ûl @kð±I¤žÀ,ñe÷ À;y$ý–ø À‘]Så­SÀµÝýèÀ©@Y[–€À[ɼ9x@}ø]CÄ?šÚßK; xÀŒ`–‰=ÀKÜ÷ØèUÀX‚íg·vrÀâÉ«6‹@“Ç,yOQÀï)½çýiÀ^€V! {q@¥(tž_@9ºŸO3I?ð?W_³¬Íï?5B·vv¼ð?0xÚù¦õœ@B†´‡,ÿ?2ž`rLñ?Ëueœýmð¿`dµJñ¿é %R3ò¿#å*sæÀ¤ „p[@ˆ*PX«!‡@}ø]CÄ?²}oÆu@JžÇ¿}òÕ¿œ‹«1zu À‚W#(¼gA@ÜÖÔFCK@¹>´úM6@Îy³û˜¦t@äy‹LÀéˆ ¼TÀ$þ\ PnBÀÇÀáy3á?à?I}§¸¢Ž@¢éñu|@–7Ì’žœ?@mwqZç4¦@]#}à_¾‘@ ^[2´À¸LgÀÝ%"±\’Àî>`ÞŒ¦LÀCe×™õß™@ô¦Š‡œ rÀXìCI‰Bh@}uòd­Þ?aIÅûg*iÀÖ!Ø•0?3À»æÙ 2gJÀˆ`š1@¡Å³G¡@–7Ì’žœ?@©¸o ò2@©Û(øñì0ÀÑ4Np72ÀqKòó#›3À-•<P ŽÀŸ­=/(Q@ç©zéÙw@}uòd­Þ?rÇ‹ø(e@ŒÀÞâh ÀrÁQç–6ÀÌjF·4@&DHì@@*à—~±)@?ÄNËcºd@„ T‹?Àߨù0B@ÀÛ—äAÊ”2À€‘yLàkñ?ð?ÇåD8¨Ÿ@ÍTÀɳv6žÀ^S ¢”Âd@Y<`+Oü‡@0e„Ô6Üü?´Ò)1 Pu@p[N`(+ÀP%ÄÜM!À/ÊBÔ4H@)ÿÁy«.R@5Û—46=@íðÒ‘ÝÎt@´8Ü!%RQÀ¹6@³»BÀŒ¹6@³»BÀ-»ÜP¥á?à?Ìð0×\@ ‚ hôp’@OŽ²Ç¡X@MžF9§@Cx*óÉ”@É´:gfýÀÂö>O&“À‡÷ì¶••À/ŒCÙóñWÀLêç)ƒ£š@Ý<é0–uÀÉfX êÇh@Þ/Þ›¤‰õ?WnNdIjÀ‰<õЗ=Àè¤D_ɺQÀíb >BlÀ¬‡" åsp@„ øàAÀC;Ÿs\Àf4çé)ÖO@ïµÐê|›?à?œÁÑ dI@z9‘9ŸL@ST¸(@OŽ²Ç¡X@jB|8!P@ÛTY^JÀú?Hˆy¸MÀjN½Ø¿PÀi™m­/hŽÀ~ý|ˆX@ÏÓófx@à/Þ›¤‰õ?Å´/˜ze@šÇl–‡$Àã*{øÇ À ÊÔ¡ÿâ;@Ïè-D@¢w¨ºGn0@|Z„˜ äd@êHL}ëBÀÏè©3ã2À¹‰ÜìÎ?Ð?â¿zþ]w@Õ\=kÎût@üº/L˜sRÀ“ |Ol’@öýU7Ü×r@Ž–OT´æwÀh¶|X’vuÀ[Ò]FsÀm¦±*Ñ6@îéoº- ‡@‰‚º ›eQÀEÅ_'V@ÂPÏâÜé¿ÉïáªìËTÀDcܧ¿|@5íŒu«N!@½ã’(õ0(À6&ïäw=\@+`»oÑ.ÀjغÁ„DÀéYI@*pE=—¿Ð?¯3NµšAÀ5ûäž?À¨ý°$y@üº/L˜sRÀ7 â¢cd<Àã2¢ò³B@JÔ?•~+@@—¹ • =@–nÕ!_}À„³&?vqÀÕʆÂÐc@ÀPÏâÜé¿¿ú¯ ÍS@QØïº½2@÷Ï­ U¯"ÀDkͱTð?@B wŸÈ;@{*¸¯¶n9@ ΈpÀ̆@ô"W±ŠÔÀ{ˆÞ@1þ€¼×âS@« ¸kÀçRz?Z!Àfï].ÀȽ\¯ï?ð? PSjÈј@(£% ,—@喇М‰hÀ%_.BŒ8³@ì‡}=¢•@#w¬q™Àk툢IÁ—À<!îš-–À×£‚5f=C@˺«‚€¤§@À EpvÀòå¶»wvv@œjãÎvÀKÙÿf¬uÀÀÂü3f–2@`3È­ Ñé?ý êéL`ÀB†•Zôû|@Ñ¢¿1ŽOÀf5™ÈÿÉeÀñF›A1¿i@ñF›A1¿i@ Œ¬lC®¿ð?‰7)‡¿ÊWÀÇ-p6VÀ¡·þ„tß™@喇М‰hÀöâLA÷¼TÀ’£µdX@j²e¡ˆÅV@ïZÉBU@5ËÃmðoÀ$‡ÿ6@Xa¦.š´„@œjãÎvÀ&X÷1l t@ÿÈ€Ñ[¤4@ÛSYtÙ[@ÀT—õLÿx+@¶W”r¾|-Àï÷K<&@7*Ò'úòs@ <K3BÀã êÞNÀã êÞNÀa­Òû´ à?à?þšòù˜‰@N˜â_cˆ@aUjUÔRÀ°s?¦0££@ã„Í;g<‡@Uœä&FŠÀ—Ê]^‰ÀBÞ"šÙ‡Àÿqf6!@­êlŃô—@³‰¦àú iÀ·ã·–»°f@{oÛž–‘é¿‘ÆÍw­!fÀ —is‡à@¨^`1G ÀƬ Q®UÀ4ìãN!_m@úǵ=ì?ÀrÆ=otVÀâØ·®`@7;™ßVóY@Ðl6tþ•¿à?±x\£AÀA6ÞßÎ@Àɇ PŠ@aUjUÔRÀ7¡ùyÇ@À²Ù¯_°B@³†¸?A@Yq‰o@@ËZivÀÜóÝ8Ió5@Ñï»$u@{oÛž–‘é¿$,Ž˜-d@oa6³<@Ê‘uµL/ÀÐ÷¹p‚#@¬h‹|<ó¿Þ›ÐY Ð@uÔ RŸd@º3<ËÃ4ÀjçØCÀÞrƒ7¡ß>Àƒ,]”<Ð?Ð?dìáÁuiz@ˆ¯íÕ˜±y@°!‚…™6ÀÏýò%ô”@ÛÃoÙ»þx@âЕ0%{ÀíwÏ8hzÀFMd°yÀ¬nCpÆÀo€!Gˆ@9 (âµ[Àlþ{\ìV@#{u¹/Ï¿À4÷+išVÀðËŒoG,ó?™–ýë½ À’±‡Wa=KÀOæíÄ]@‘ÎíÐá$0ÀÀü3N$GÀ%Bf^%¯R@Ã(„g(J@»×ŠP9{¿Ð?· ȬP&ÀñŸÓTµ%Àò„xFÎz@°!‚…™6ÀÌ<E6%ÀÔËÖIï&@x¬Ùþ O&@ö_RP´%@ãcwA ”}ÀqGž±¶0@÷–fΊ“e@#{u¹/Ï¿½aS{ÔOT@ gÇÕ@ŠRHýó¼À±ÊËØ/š@´µxL@@Ÿž­Î@ÖÀÎT@ ëžúëg'ÀÀ¢¢à×;6À§°ã ” /À8L:žRpð?ð?Àˆ”€‘C›@ËJÖfR›@2jfü‡[AÀùßë´@4?æWíš@ÍŠ¿ ;œÀ'D¡â¸â›Àå[U}¶›À9ã=ëŒIÀnç¢*Zœ¨@¾,°þ²n~ÀSÚç7M)w@D¥üi+<Ó¿˜Ú©wÀÀëý­úÀ^ìÄ{gIÀÅ£é}pÀ²`üT-~@ƒ„óÌ€SPÀ»ömÃÙgÀ󹨤Õr@¡ºj/M^j@\ÊP]Dt„¿ð?¨"1çÅN1À;UÕ½Q31À²ÌtM»Y›@2jfü‡[AÀ‚‘§ 1ÀX—%áÐ1@Ê›B£Î³1@¬ÒÚ6º—1@¡*Àê­À;ñ`&ù½V@îTϨð†@F¥üi+<Ó¿ýñž-st@ò/›mG @8„ÐAí<À‚ÉkÓ‚>@S"ÅÐÕà3@z›‡ƒqÑ3@)Ô#Y&t@÷ýÈž JÀx vXjVÀBÞ¤ ¯aOÀQFJHø¤Ð?Ð?(—’ž'|@>«ß‚L™|@¼þRÛ@o“º—-ö”@’£úrÅ }@ÞDóµ}À³å~”ày}Àåï3Jäð}ÀCº} þ4Àb‰N,ôˆ@?ûÇ¡!œ`ÀÔ¡=«{gW@7³£‚º?Á „w–WÀp©.4®*Àt÷»ˆð1À»[6D­uSÀ¶‚"*G˜^@3êžtä0À±û†Lñ”HÀm˜4˜Q@íÐÂì”J@ä/&¡ \?Ð?BÊ×£1@67°h(c@˜ƒÀÒ®ó{@¼þRÛ@ìñˆ–Á@⃩ÿºÀR7qÙÏÀ“<4‚#|ÀïâÊpYÍ}ÀÀ˜#@=@ ëkŠÓlf@7³£‚º?Ie µ±—T@^ÀûÜ—Oä¿Ûæ‚a˜À/ôé÷÷_"@¦ÌïÅ‹½@+¼0ó@ewv/é8T@÷< ìÛî,À3“e†V4ÀúÁVó £/ÀËP~ŒÚÐ?Ð?zmà¬í}@ìnDrc6~@Ñe²E—4@´Ê“ÄÏm•@qÀÉ b@&ñ~ÀtØ9hÕ/À ]ô2€ÀKõ¼ÿ›=À´q^ÜŽN‰@¶:uŸ bÀ`2žЦW@wRh´ÆÒ?¤k ÙXÀxf&YŒÝÀj'Í9s5ÀãÿàφVÀ´H,>³_@¿šs °0ÀÜëÈóUIÀ@lV%ÌJ@@lV%ÌJ@‡?¤=*x?Ð?¾©Neôö$@E/]ºßÆ%@úLCXOœ|@Ñe²E—4@ Ùž&@Q™ló ¤%À¶hòð«z&Àõ08œY'À^šò}À݉;ÛA@^6×f@wRh´ÆÒ?Gêhen½T@hKhˆ¢ŸÀ£r•ÅÀÐ}¥©$ª%@@·!£™X#@“z$E4@úû|ãKT@B“j Ó/Àp2›ïÇä/Àp2›ïÇä/Àó±qŸñ?ð?7¯eÍž@ºë}™ñŸ@q9D‘ûa@´Úéèµ@hçîNù @ Q῟À™Q×pƒ À¬ýE}ªŒ¡Àtö‘âQcÀ/J¿dr«©@à`\ÑF~ƒÀLëÛ+çw@ ×y§¤ÿ?”Ë xÀèÛœD¸>=À? 8"ÝYÀmy'ì²yÀäêI;{u@‘nbrîÝPÀéU‹ÛjÀ?%A‘Èß^@”Ïk@œÐ’ûÉ¥?ð?»M¢ƒR@iÜ×GX¬S@ûü QT@q9D‘ûa@¡LàQèT@ά?–»#SÀ´RJ#WTÀžU¿ÓUÀËKé¯óžÀïG}*Ve@i}H2«?‡@ ×y§¤ÿ?§æ×ùpät@÷é> hÀŸ¡.X¿ ª@”NV¨çû„À_ ìLi(x@4»mw¡š@FÇ(.B+yÀèÇÛŸCÀ—Ê M^ÀÂ%ÆMø|Àµk¨wç@î[@î˜ QÀé±°‚²éjÀ5-«…¼;k@­;Nª ®?ð?Ùž2þZ@Y†âä\]@ñ‰ïG}ž@‡ÍØñäìi@S‰ŠêÛð_@¹wŠ„˜ô[ÀŒýÅkíh^Àjbh6Š`Àró$­OžÀŠÖ¨wûh@&\æ†n¦‡@4»mw¡š@HÃËÆ u@®+ËȘü5ÀÒIြ>À¦Ú¢J¦ÇL@Ñ2“¾O×J@Ó†ËË@@y±´«Õst@E†Ö(]òRÀ3!5PÀ‡.õ.´Wî?ð?}·ÖL1–@c( >“@ >ü舱pÀn#»ͱ@¹N="¯@æéž#¨–Àì^ÁÀcuÿ _‘ÀŸÔ»ïŸ÷S@‹ Ïð›¦@f¹#2ÊÒqÀÿA«}u@&™óþYösÀx©+wísF@kPâOØLI@~3"Ÿ¤QÀŠÿqôq{@ Š ÛjMÀ%U >kcÀKáÚÞJåo@ŒZÓZ†Wµ¿ð?D@zUL_À$nA¼&#[ÀŒ‹yǸ9˜@ >ü舱pÀ™Ïª¿“‡WÀÔS઼ó_@IÄ?¢L´[@\ÅmX@ÍdºþwBÀ¬f³L: ÀüNîU9ƒ@%™´ldÀ†vòè‘\@¬b•p@†Ië?3`±¿ð?tr¶ôYÀö]ËVñVÀ ÉÄX˜@G“ï°wkÀ¥¦ÔH GTÀÕ^Úv•†Z@ÝR$ÄrW@ñ ߸ÿ¸T@ÈZÖÚIÀ@\v/ý%@ì £]¨ƒ@[fŽ ›ÀMÐŽs@šn0Cÿ6@€Bï ñqJÀ™åÚh%@ÒÜÇ&ÃR@ŽØ”!êP@Š7¸…²UÀèµúx?@mú똨„@ËîæÈý¿"8CÈÿ¬s@îPJL]Ñ1@ S›ŒIÀü% 'Y/@?‚f BÀü~j{K(@¬ÉšùŒs@Ï´ŽXçBÀ6Š#f= NÀ¶„x§QSÀaUþþuß?à?×ËLÔPˆ@²ÍR^†@¬Ä¯DËNÀ½—ðø¢@iç+[”„@칈Ó2çˆÀã"AVé†Àù ^}@…À´›Ùuì?z»ÅWy—@”:3<0IiÀ!^Lv´$f@,…û®I6ä¿¡øÚG:eÀhZÓÙ\­+@ úüf®øÜ?pUÖ¯XÀ¦gmè…l@i2HHx>À+]+©?UÀ•$ÐzQ`@•$ÐzQ`@æ¯;}”’¿à?ý ´ß<ÀŽ3×¹‹:À¡Ï\Qzb‰@¬Ä¯DËNÀŒýV­ªp8À-¤?S%“=@s…Š)£5;@t¯Ž9@U'1É5fÀäe¶:@Ñ;¥} ‚t@.…û®I6ä¿9½¨ËòÌc@Ð.·Pö@_€†Ú8ÀŸ®*Ê£ð$@Jkþ¸k(À*–qLº§@°8!6õœc@Ðb?#b5À:æHáŸzCÀ:æHáŸzCÀ[pJŒØÏ?Ð? Þ5Zy@È:‘w@¹>sœwí0À,`ñá…a“@Æï®#v@« ~‰iºyÀ kY+xÀü€w´vÀèÌ,¨”æÀ€:^/ȇ@lHénâ[À{çNä]V@UÝ,úÅ¿Ù8|ÁĬUÀpsÿ’ú@È{¹ÈÀ%‘1¿>pMÀ`Åjç\@¶f<Ñ.À¬ç´êåEÀ’²¿ª4FR@‡¬™brP@ð )íc©t¿Ð?àóeäžo À*lè,_áÀW¨óåÁÞy@¹>sœwí0À39"eÀ‚$çÛÛ @•úÉP«@2‹VÀ@~ê¸Xž{}Àqè?¡™2@ ®× íd@XÝ,úÅ¿rÀ&çíS@Švðèû?½#Ù°»_(Àñ¶+‚@YAV Àâµ|Ùœ@<Éáhs­S@?Öž©‡ï'Àú¦;f=Ò5À{IϨ£3À_P7™aÐ?Ð?S³'ˆÊåy@bÅ$Ÿ¥Úx@¨†êý…" Àd¹rÔΓ@ù!¶hDÚw@|xÛs˜zÀiÉ »…yÀ ±æ—u~xÀ‡E9s€,ÀM ¢Ÿ˜ˆ@A ‡(øŠ^ÀÙ¼#Dl˜V@($ažÜ„¿þ:ã'¤"VÀˆt$ÎÀ @(Žêš*g Àr•k©‚QÀô~»ÏºJ]@y¼xšN*/À/I®Â|‘FÀaâÇÛjkR@Wå3,à“P@M®á£Õ‰O¿Ð?#¬0ªœú¿AŠÝ&Šù¿X:ô bhz@¨†êý…" ÀÕ?³‚ø¿å»«ðÙSû?첆ùô9ú?ášuÜk+ù?ŒH Ü(–}À×–ŽÁ8m8@ôF†ˆÐVe@/$ažÜ„¿JX˜óéT@ °¨AúÎÔ?ì{/K(ÀjÐ0¬S2 @^¿ÔÇ…së¿&æØ@ÅÌF’{¾S@Ó¥¬l*À†œÃCØÿ5Ày¦É ©Ì3ÀýG#cXQà?à?‚J›ì»¾Š@@Ò̘0<Š@T¨E?15@mÞ7À=¤@¸Åv"¼‰@¶]6Ù‘€‹ÀHÃeTúŠÀ,V-.¦vŠÀà­Wš%FÀ?¿±•m˜@(á|4i¡pÀO˜h®@Ôf@ÃâììaÔ?碠!õ›fÀði 1êÙ@˜;¹±Ýê8ÀEšxÎddÀi#ý°m@ë±@¢‚?Àãò…BWÀK˜ø æµ`@K˜ø æµ`@cõø z?à?· Ÿ%@JR@fš$@­¢{YÆÿŠ@T¨E?15@ ()Œ5$@7å?Ö˜%Àu㧨k/%ÀtœÈ$ÀãxζÀÅÉ×KäŠN@4óʽ¿u@ÂâììaÔ?=eÄñ3d@Ý%‹^w;ÀUF²`ø8Àðã¥üŒL3@ä ©A@Z9gnñƒ'@JÖþ*Ðc@_^i¾E=À"=µÎõCÀ"=µÎõCÀWó= 2…à?à?Ö†•³~¡‹@AZóÀ“·‹@'¸ü©f I@ef¢¦°¤@\&+tºÍ‹@Í ü^tŒÀo+ÿ‹ŒÀ· ~R졌ÀïØ”[wlNÀ°" $Ę@Ú?ArÀæ¾Pg@•L Uwµå?èÓâRÂgÀÿkޤãï¿Z´Xgp¾@Àt™ôd_gÀ½ñÄÂn@Ýp¸sÚ?Àý(ùWÀMÖp.)4Z@éÒÚcØ`@x†;E 3Ž?à?ûLõa9@óg?p,9@h5u]¥‹@'¸ü©f I@8ÆŽ@9@s}/Fè×9Àª » ì9ÀÙˆÝ|G:À«<9N¤ÛÀK®Ã«zR@\-.:›%v@’L Uwµå?ÞÙk¡QWd@„¶#‰j6À,Á'u³R8À¢‹ªB‘6@›jðSW@¿ Ø_*¤*@h…>©Gâc@ö÷˜À9@À¾D+ÆÛL?À讑DÀ`¯:éõ¹Ð?Ð?)1z¢aŽ|@«ü%Í¢N}@— ¾4ýC@Üö/>Ù&•@ÁGŽRò~@ ÓPQås}Àœ¶Ð°/:~À•w(±À\â¥ÜÐŒCÀ‹tî;‰@ÜY¤š0qcÀRË|€ƒOW@ÍC£f÷à?/§Î™WÀPôhnˆÀW’óAI5À(xv»9sZÀ/ÐLËø„^@!m³2ß0ÀŸÿT~µHÀÅ8&z0>@ïµDûP@©tË$£Ñ‡?Ð?Ÿ`ƒ­@4@tö—_É4@.u šY|@— ¾4ýC@Ú 7÷T5@€v³Jtã4À.’ p5À.]šj6ÀZ Ò~À¬b•×E@º ©´ƒŠf@ÍC£f÷à?‚‡¡jÑ|T@ ³ôÚÀ@šìšÎ(ÀIDÞ*@hÊLr˜@L¸Clã@°7j^õS@êa©½Áx1À¹Î¼"À8H–³H4Àjñ E«ïà?à?ÇË<±…@äÔÕM@&¨g¼”²[@Ö¥ÿo ¥@êÆ·²J@Ám•†’ŽÀåH9¥æÀjÉuü÷ÓÀ6a g÷XÀ€X{Îx™@ôÈÅ\åtÀGã'¾Žg@{Ï{ln÷?A{!ÆÞhÀÐW#p\"$Àhç~²†dIÀìÿ W¡mÀ¯'¸ƒòn@ïÉ—DD@À6ò–ЛwYÀÌ>X.qa@ôë§EU ?à?ÛõÚ4)dL@ÒµNe'ÓM@£AÃò@&¨g¼”²[@Ö×ýn­TO@qfxTMÀ($S{˜ÏNÀ"Óî.PÀšK6¿Á8ŽÀ^Âwf]Y@߸1R¢ív@Ï{ln÷?‡Ì­H•£d@Òÿ7^M'ÀÂsbü9À@ xýîŸ=@‘¦Bø ,@tQ =¡0@.ÃbM”d@u F:ôôBÀá‰ß·¨rDÀ3óNìÈÍ?Ð?ã`º Bu@ë6Òœªq@ÎçžÞNÀCj]z5‘@$Ý ›˜m@çÍI=~uÀ4LžßrÀÄ/Á)nÀ”2o LY1@ÊøÜ1†@}§{Và;RÀ¤¡lÈôU@†?¶TcHã¿ õ@U-SÀ3 ÷¯h-@€ÜµÙ€r0@nµ¹ÖÚã6ÀÖŠ¹åذZ@k»v6,À¸Ñj/cBÀHÐÿ2>YQ@M³Àä‚“¿Ð? ˜è’´;À_]Ë«þ47ÀN³â„Q[w@ÎçžÞNÀ ‚… dp3À|;S0Ú;<@º€O¦7@ð‡NÏ3@æO ¢(}À€hvJ@ÂÖ?Ì4½™?§b@‡?¶TcHã¿Wü6•’S@ÏĪ@ãæ˜Ì 2À:˜d´•˜ÿ?ª ™ËË<4ÀGÔ<>ìi@B»”S@¡Ê÷ÄàÀé«P¨º4Ài+Q×$î?ð?Ív@{i»•@ù<ÈW³Ž’@ ü»8NhÀÀ˜èˆ ’±@Þ½kl±@E!È+–À_Ñûî’À¨ÂÚ,&*ÀȰûŸÇF@…)ÍÁu¦@AjqRœtÀ²ã™Ô”5u@£,zØ[nÿ¿Ý),+±sÀ˜¶¡e÷òJ@^ jÖÛH@S©Ï+J:`À2ºGxû{@ä¬S+fqLÀ—‡VòbÀxuG!ºö[@k©ÌT4zq@ÛÜ‹„5¯¿ð?ŠMDqU“VÀì‰r‚GSÀJ‡8ò±—@ ü»8NhÀɼù(vPÀJ°fZW@Ð5"µ&ªS@CÁÊP@—$‡ 0À¸éí3@’Fakƒ@£,zØ[nÿ¿ò"l™3s@)¦dƒ44@i§…’@”QÀ¥{Iè&)@-ÃÃ/!QÀØë42%@ÖX»}€s@JÄ|w¸5AÀgÀãU#¹@À°\+lçTÀKøsž€Þ?à?Fˆjg†@F7n‘ƒƒ@jœ×`WRÀËÅ­zò¡@ÅG7É(ÿ€@‘î2+ªà†À¾d¸‡-íƒÀHÏšU%[ÀøLy1ˆ$@S¬tœ¼–@zÃoì gÀ¹{l–ie@Iª7»ç¿Ûå‹÷cÀ»–(_€I8@qsÃ&Ã0@‡~)UÀLެ]k@\µÂ Ç<Àli*£þ…SÀå…Ø§X@ZÍãî›a@JãH’L—¿à?›\eÉd/AÀu¯Î7Çï=À+vA=}ˆ@jœ×`WRÀ«¾uE.:À þ_afŒA@³ X·Ë‘>@½7švL :@=•gE‚=ÀóÅOò°°3@üÅg¨y|s@Iª7»ç¿ßR!K{Qc@ ]Ùö€d@ B;æ15AÀ¯ ÔK‰!@Ò Æc<ÀòbH9 )@ëëEf+c@ Ÿå‹3ÀÅ+Z ¤‚=À±úd,EÀ|n€¢ÞÎ?Ð?Ƨ $‘w@ÏÙÜJoŠt@Á$¡yZ8À~†_U’@¯[¥ÚLBr@ôñËSŸwÀ…'SøŽÿtÀö†”ÉiªrÀ2 I×÷ö¿Š¼©Ç½‡@«öô¶"…YÀAV`úžU@½-lŠõßο¨çjm`TÀ:‘FÞÅi%@+ùŽG:@ÆçÉ AJÀÁúðÄ¢·[@»Xõ i-ÀŽQ#óVDÀ 3ÁRðO@Ýf¾Q@FœL(r‘~¿Ð?¾u:¤c'À²ššx$À"‰?e¦x@Á$¡yZ8Àp)<[2"À_¸]>³Š'@å/9í$@^±|Aš"@ÿjâëN}Àæò7O‘è-@„ååTåc@À-lŠõßο1o@DpS@yC)›þ@ Ⱦ¹ï0ÀŠ G0tÉ@ÕÊ•ð×ß&À?yÁP@¥ECÀ:S@ž§–Eñ%À•C¾Ð 3À3¾Øïç@5ÀDY·*>ß?à?ò¢ê_-؇@ÆÂ'ýš¤…@¥*]ÓÂ77À-N3¸‘º¢@‡hyÒ¥ƒ@®ÿ±zgˆÀñ»TP­&†ÀUüùÛ „ÀD‹ÔÈÀ¨0ÀŠÕ.±ìO—@îX4%ilÀ¿Ëž˜¾Õe@P—l×öÊ¿44¼üÌdÀ¬XsEQ2@Mr`Ö1Ú?O,‚‘Ђ_À«OÌ?9l@ƒ´jíhq=Àþ<ê2Œ»TÀVr•$˜áa@Vr•$˜áa@ïó ]Mª|¿à?’ªèØ+&ÀùȬ@Ò$ÀËVDh[üˆ@¥*]ÓÂ77ÀòÖ"-D"Ào±&@la÷Ę$@€êvZô±"@+eÀŠü‘üQD@Ñ÷^sæLt@P—l×öÊ¿ôh“Õc@¼™?Cá@[DF Å@À¡órÒU,@Iô%×Í»1ÀuŒUÒU"@ø˜e•Jc@™êKi8À&ÈpÄ¢mEÀ&ÈpÄ¢mEÀ™‚Â&EŸÏ?Ð?2y:ßx@Ð}‘yÓv@¼Ydúfêø?†R ]ó"“@z˄۱*u@ÄK†9yÀϱNxdwÀ¶•“;аuÀŠ€ÙYz /À¸H=Už‡@žÅì¼1¦^À9´{vÞ V@C”¥ëM¨?NÐûÉ@œßZƒRŽ£@¹iÃÖ†@ºÑÆàŠÀ÷X¨×‰¹ˆÀß}Ã2_o‡ÀY±µº&GÀJÒ]²Øí—@ÿ>ƒu¦pÀ=ëQGf@×’Bh¡‡Ú?vŽ!Lå¯eÀ<7WÓ&@6‹Ž4+0ÀšÀ©$T":VÀù¼}‡þX`@M'¨]þ)b@ÜÖƒ/Ë‚?à?“Æíu-@ȘÞf,@Eó™øŠ@h‹p¬ŒP>@îXhDŽ*@”h¢T.À,ýò›¿,À^j¶?+À^&_‡ Ày–É•ÝO@q«M8Íu@Ö’Bh¡‡Ú?ÝMYëˆÒc@bñƒªØ© ÀfÚMgîÄ@À˜AJ¾-4@Ú©?|BM!À4´S®(@fÛànÏkc@—ฑ=À|\FO­™CÀPJX2ÇEÀêÝ 53à?à?;ÎÙCŠ@¨·®]u‰@U`Œ2ß3M@e¾¢õÂü£@±Ðyn8­ˆ@)|# óüŠÀ—ÁåÇ(ŠÀÐP º [‰À²‰¯xOÀÂEž@˜@Hý]rÀ)ý ‚f@\t¦˜­,è?jÛ:`&fÀðúÈÅjS@ìâ ’Š8ÀÊ:Ü=e*hÀ£!js*9m@ÖÍðP‘m>À£ 5²VÀ{ò ð¡Y@¡ˆÝ–Ob@Ûœ+E|Ù‘?à?Ó!ùOÑÊ<@„ô>)wè;@,Ì;¿°»Š@U`Œ2ß3M@mÁÞ} ;@à¿õǺ•=ÀÙõ l%­<ÀíTu‰´Ë;Àþc)SÆÀö@íFtS@;’ þðzu@]t¦˜­,è?µ©H oõc@íUt„S€Àšƒµ…Lò@À“µU¯l7@ü¢ÅaîþÀ½d‡ç+@èm]íB}c@Ÿ¢t„!@Àr˜ƒ-¼>Àv‘‚ ôEÀžK ÐHfÐ?Ð?f›™=a%{@WQëÁ¨ëz@‘£á*4ÚE@½)ÌYn”@d–‚k²z@ ì0+ï{À"Ѥų{ÀŸMdÞx{ÀªÐ¹CÀЗü`안@G«+fdcÀ¥w—%ÿ½V@¢4´¸†ãá?¥Fì¬D VÀàæ°&²Øû?êEáÜ{0À*“Ô¡'[ÀwºYÌÍŸ]@}ú‰À.ÀE•›CdGÀ4¸‰—އ=@¶¹tR@á€MçkŠ?Ð?÷ɘKË5@bHéSôœ5@æ pê”l{@‘£á*4ÚE@ôbî—ÿn5@a uMm6Àò³kU=6Àx¼üR6Àæ­×ñ}ÀN&€ÙcHF@© ž½hÜe@¢4´¸†ãá?¤ß²µ}T@P£Ä3FÀ"Šé?1ÀÝy®YÖ*@TúváÒä¿nÉ^Ó«!@k/fEOS@<}6…1À¬{ñÈ4´!À•Ú-ûA!6Àp $šBšð?ð?´Ï_çœ@M4ƒ†6}œ@óúÄ"xVm@—²ñ)ã´@ Hp§'ëœ@ŸÉ­ôìœÀs«Œ•\À× ž(äÍÀNaDèhÀÜÞÿû»í¨@‚n…BVÏ„À–÷ä›ûv@ßáêiê @ç\‰˜wÀ€;ÞÝü¿uÒ®¹TÀÖê70þ=~ÀF£K³×~@¬FW¥õOÀ]¨»RhÀ‹˜t‹Çšr@dRm^ñޱ?ð?ʺ™*¿›]@È™ ^@ño3Í,œ@óúÄ"xVm@ùBâý^@gì²=äƒ^À2.Œþ¦ù^ÀÃ^G20q_Àúã–µY#žÀžŸH·Û¯i@SWŒO<†@ßáêiê @ÆoŽÂ>t@“zý+~8À Ã’t[¯QÀ1?c“-lN@¨GZÍžµ @~0+û”¯@@'áh§û¡s@êƒ_©ÏóRÀÈEIò±NVÀ²–Ái?í?ð?CMgrŽ”@JÇÄ =@s§¦XójÀ¬.u餰@£8Χ‚KŠ@Á×ÔÒg”ÀÞüš—d…Àû_´Ž‰ÀŠÀ ¥V?`ãM@8z3! Í¥@mJsC¡rÀSÄöâGŠt@sÇódÀŸ!¦Œºd@˜Õƒ£@꿤ç@ÎbÀð{JÎì@@ž¾ @@?Æ:—RÀÈQŽœJj@tßÂÚ3;Àôêû•9óQÀª Ì{+cK@ †_-ûa@VîÕ®áÉ›¿à?Në3tyCÀ\g°ð@ÀcëmÞ†@ߺ•ÏÁSUÀ EO‰:À?ÿܬ×ÔC@òßö‚^@@žÆeŽÖ;@ÈI‡:bÀúÛ×MÝ',@k iL‚r@˜Õƒ£@ê¿—WúÎÜb@*/é7·›!@òÛ9ÊEÀ¯—\bÀ@Ó2¶`FÀ¢F_2ˆ@½ ¥¿b@û:XYÝ1À(Þ!âDn0À²UªÖ‰DÀ¯iT~ÁñÝ?à?ð™Ë~N…@?'eâ‡ð@ÅÃxJOÀL%ƒyîZ¡@fÿç5~@5Ã=ú·…ÀbEXI‚Àß¾½EË~ÀÀÝÑMt@Žin+Q–@ j-ðRgÀ)tåèKìd@kHóã¿qeÄòL/cÀ_¦˜Œa?@.I‹DTW8@/òzRFeWÀýˆR¯ÿj@è{A¬Š…;ÀâÁùUô~RÀWÄŸ’ $X@Ѱ–R>a@–›`¼ºþ“¿à?ô·Å•—<À þ]ér8ÀïÎEI«?‡@ÅÃxJOÀÁ6Á‘›D4ÀÔßí›$=@Ä24Ÿ‰8@ËîS°ò¨4@‡ü™r8'À =Àó87@Œc9M¸èr@kHóã¿[UGå¡ùb@ûêÕ€…@–øKÕÚ}EÀ"Q¤¶R#@kþsŸ7CÀîiÙ@ýŸ•a÷Íb@˜plÖ 4À³ù7þ<Àû'÷ÔµDÀ[®åûLÎ?Ð?Íʲê÷ùu@+÷¦„âr@8Ç83À~ûE'⹑@'¹Vh:p@¾«ÝËlvÀ#«;1EsÀ5W7P3pÀH·7¼– Àß&Ó n–†@EmXN0¿YÀJ/Ð…UU@ã§LhÆ¿Ž-uó@“SÀÀÔ­ ¶,@¢^²ÐÅ_ @κRZLÀóHöÈóZ@w+õNíÖ+À€ý7¢CÀ þµ;VEO@xâÖËh_Q@æÎ¾5x¿Ð?Ù)û6U±!ÀEœ‹pOhÀ±ë^¼¸¬w@8Ç83ÀZïE:!ÀÒ§1Ç "@9ºÓ0@3³ý©@âr–q9}À, ?E¾±0@)¶>Nc@ ã§LhÆ¿wõ cOS@—‘è)ÿÿ?Uf„J5À^* Ž@êÓ剛0À,b±}g@øe;e·ÜR@𫺨šr&À³²Š8Ë2ÀT8arÌá4ÀÛívh¤©Þ?à?ú+뀭†@œ¬Eæƒ@ ‹®Á¾y*À†ƒö-¢@69–f+v@8é\g›*‡À:ž0þ T„À=dújÖÀôyÖà‹3Àbl›åÞ–@2¸quú8lÀæ'íúºSe@x^æbli¶¿²‘N©4úcÀÊOõB¼Ô9@ÿúµ @Ü:“Û»`ÀõÞ{Lk@!q®‡í'<À5ðfqÍ£SÀ6Ç´È:a@6Ç´È:a@Â+ãù rp¿à?G›¾lÞÀ 6ìñxÒÀí‰bîñ%ˆ@ ‹®Á¾y*ÀrœÃ&ÀU¬—g@xø ÛJ@»£#µ@°]ð%CPÀ ?¨ùâE@¨Ç¿u²s@x^æbli¶¿v5Іã5c@f0ƒÓ õ?çPT1EÀŠÐŽ4.@T\ô÷“\<À-Ÿ\Ôú"@à;òëëb@ðêÐâìÕ8À¡vž–½ EÀ¡vž–½ EÀÔðéÊÏ?Ð?0kÄwfiw@¾.ýt@ƒ]_üÄ@°K×€’@‘mDvòÐr@³ôÑËñwÀ$]¨ƒYwuÀ]HÖ‘>sÀØ&öp‡º0ÀG3.(‡@.è@ÍÀÀ^ÀPó‰z‰U@b²kOâ¸?§`«‰>dTÀ¼ùÕäº&@€ÛdrÞÁ?¨.Zˆ_SÀÃ&2©³¦[@Jͪixx,ÀTRE=DÀè:ÈÁ£Q@è:ÈÁ£Q@éŸ8Maá_?Ð?e*—‚@åI’@©5tµ«x@ƒ]_üÄ@È€Ecå@ÇaÏ)w À`}¾µ\ŽÀ¯ª%H3SÀý/̓åk}À<Èð"ôU;@& …tcd@c²kOâ¸?Ù8ÔjUS@qžû«Så¿0Âêi}35ÀbYÑHó!@! báSä'Àáž'§§@ÜàêœûR@zì„ ÇJ+À`ÀLU¬95À`ÀLU¬95À…J@r|gß?à?ΧÕõ-ˆ@=’ÝiK(†@eú†—kC@#¿Pç¢@­ƒÔëM„@Ÿ iˆÀé5CP¦°†ÀLxßÊ„ÀH’Á7?HÀ¨ÆE׿t—@(EuÁy«pÀ×!«°Àe@r¯œÅß?Aéü3sÑdÀªªn;·e3@ˆ—GYfÀ«³ÄÿfÀ'à-žàl@|oÙþ}È<ÀZÔ$<¨ÛTÀX®_’¹ÿ_@¾™QQõÆa@jƒ{Ç`ˆ?à?âmž„J¢2@¤›'Z1@Iidèd>‰@eú†—kC@‘GäŒK/@=b`ö3À·¢%o|1ÀÇ—Z 0ÀxºÄ퓌À]´öd®†P@}Íf¶Òvt@v¯œÅß?R¨†+òuc@þIe¶@ÀÇÍ'FREÀQàX>Ê5@_ci'Ó3À .Yo(@ÞÏ c@ÛæÒ=Àüo%áÜACÀû_› eEÀRmÇÈï?ð?®Zlz|û˜@«B3Ègi—@z%j¨‰`@·îº|ŒQ³@Ð(þhšð•@5¼Uoæ™À‡¬(Á›˜Àœ(ý¼<–À°²ËID¬_ÀCÈÐç@^é”ÿýÀåù±òøu@Ž/w_™6ú?ï;ÌäAuÀ8 žc‰¤?@D³êÇ]@À~Žù]éxÀ˜èÏz‰c|@¡Õ!'òMÀ[î›eÀë+Òi@:{ŒqÊêq@Ö‚—â ¤?ð?¦/Šy^ P@-Kö'N@È eÞ™@z%j¨‰`@-%% 0L@Ôy³tPÀŸ}˜Â³×NÀÅ ¶MçLÀ·‹sfŒ²À&Ì£ï…c@YÊÏ‹´Ö„@Ž/w_™6ú?lY¹©†—s@µêH‘O„+À¾/rˆ UÀõUED²6PÀi‚ €L2NÀ¸t[¤‘UÀ;zñ‰Üð?ð?Ž•GÒ™@;w–ÓöÁ˜@J•œ•g@•ç޺ɾ³@íxBðݼ—@ 9A¦ ƒšÀ0Ü‚l™ÀLy!dç_˜ÀýjˆØcÀ¬óedc¨@‘ßÂe%XƒÀx˜2v@ÙLêÂÑ›@07¢µuÀ˜óú7@.HÞDHÀRå:‘“Ð{ÀŸ‘©Å|@7ÿƒ™ÍfMÀçï%XÐ'fÀ_ƒ å\@’æf3r@ªÛ€ï¬?ð?ìÃðQÛ'W@K¿x§3V@<ùéÊŒš@J•œ•g@CÆÅƒIU@í©:UåÆWÀ+Úq=$ÌVÀUJ¡·ÛUÀ£RDÞÀ×)4Wªf@s‚Òï4…@ÙLêÂÑ›@[¾ù„5ºs@Ç™XÌ‘3ÀŽTÂ8ëUÀ…›P.8ŸK@Ö¾­Âõ9À?±¯ÕäQ>@Ÿ[7Û-s@ü{ÔMQÀŽV")¡dAÀ.ìjsɽUÀjYYZ0Hà?à?so0u£²Š@ÌŽ¡3Š@AÚ&<Û^@*kI{/¤@ì9íÚû¶‰@kjß´Zt‹Àp•#A¿ñŠÀÓ‰R!‘qŠÀ¶½_}© XÀ4í²­ui˜@ªÑ±ËºtÀµÇomf@pNèótø?r=ø3¶,fÀáš„æ‘@ºÄ‚IPG@Àe‰RÜLÐnÀ‰ÐÃ{6*m@³}¹ µ=À€¸FÛÕVÀyÎA4b@ NïÆ½¢?à?jDþ¬©N@‰¼TÎN@T‹úG‹@AÚ&<Û^@’¬¼š¥ˆM@ü£B8)ˆOÀ ï_%(òNÀ¶qú¬ð^NÀJ† ``ŽÀg¶¦HUôY@ŒïŽGk‘u@qNèótø?"†+Þ Þc@Ó,j:‘)À­›‡XÀ÷ oü @3b[—fw@™eBôDcƒÀ?tu*\~À¬°I,\ÅwÀzÎ3?$y9@%J35ìn•@Z¬»IcÀ\«4è.d@;ýÄo¼íë¿"Q—˜˜½aÀ£IòèPE@콈Æ8€G@Uc&IPÀÖ6Òÿ’Ki@胭€¼9ÀÖ%@>zƒPÀ53šÄnú]@O¼U  ¿à?‹¨CÓ ^EÀôÿøïº@ÀD‚½ûøÀ…@¹>­›‡XÀ•‹SÏ2:ÀÆCÜ©´E@©ž±þ@@üG×{èœ:@Ò_·´TùŒÀê+ÞÆgW"@ëäü ã‘q@>ýÄo¼íë¿ÀÛ(+\nb@忳BCÁ#@‡½ãŠO/JÀ/Pð}0â@+ Ú¸tŠMÀF¯<õS@´ü N?Yb@ÎmY),T0À¿ì`ÂÊBÀƒHD ÛÝ?à?§.l€Äªƒ@ìKCf@Ñd1'…RÀÊ«‹°uq @~6?~¿y@DOJ¶éþƒÀâ ¹îšìÀÖ Â~ý{yÀª~SDqÓ,@¥/Ï p¬•@ߤ´¯rHeÀÎ+ÉREd@“áÞí.¡å¿³êöbÀò`I;BD@Q;nÑÕ¦C@0€ô{!ÔTÀ8Á"ð·˜i@±’/Ͳ :À„—`#ÕQÀ/^rÖJ@÷)Y Ü0^@÷?°{˜¿à?¹<×ü @Àá¿ÊbŒ:À¥šÞ^†@Ñd1'…RÀàñ.z15À-US"è@@t­$þ:@Áͺ 'Œ5@?qúÀ[£ ‚øÜ1@Þ†­‡öq@”áÞí.¡å¿ ;-¨i‰b@´®ŸKa@u-dÖÝIÀÓ[26 @…œ`‚¼JÀ²áRÚ™Ä@O(‘K¤fb@¥ø“õ”v2Àr”bUã&0ÀçÀ¿+BÀ%`Å¢hÝ?à?’‹¢)®F„@R„Ëì‚€@z ¨?£¶IÀ¥UhÊ @]#86äz@Ûk1k_¢„ÀƒMš —Í€À|ˆjóÑ]{ÀÐ(æwy@Á¼®k%ì•@~¤UÁ™gÀÄú/Ãtd@Ð?´³k£Ý¿ ké·sbÀ•K–EC@ûÂ5¢Ž?@΋ւYÀkDâÝèi@h/~½¨X:ÀüŒh6&ˆQÀßúZñ·¦W@E°âZ£h^@ —©²×Í¿à?âR‰^L7À¿ɬõø2Àm³¯Oèv†@z ¨?£¶IÀìÝÍ×Sæ.ÀY ºµ7@ A.ÈÁN3@Þr/@ûŒ–,°ÀF=]ý:@òn¶©Zr@Ò?´³k£Ý¿Ñ¬Ï:¥b@1Ð@Þý@ÍJvJH¢IÀºƒ7ì%@껎Í@HÀ@. ð@_@&Ë5ajtb@HP“@n§4À+Ó7€<Àœ¾®5®RBÀÏ¿‹ê±Àí?ð?ù- þé”@ʼnRøa‘@££í‡LÀF®íúã%±@²Ç1û.åŒ@9 îþM•ÀTÛnµ‘À|¦“YoÀD-ÕϹ2Àú2£.¦@¥¯æ¼¤÷yÀ¶í˜†¥t@q)E—ÓßÝ¿ÆùEhìÑrÀ×ìjàQ@ZN«göÂG@à…ãi½VnÀ7ûfÏ9z@¢÷L¦JÀ›Ÿ1D™bÀ -UŽÀ¡n@ -UŽÀ¡n@ؓź¡’¿ð?¼\lŸ\¤9À|ZƒÖ÷O5ÀktAêâ–@££í‡LÀEYº¶1À€ùø:@CiBàµ5@0[ym 2@ÇFVަ%Às-,)åHR@| §u¼‚@l)E—Óßݿڵ³ÚÁr@I"W9ª@ÔH­EüYÀ'èÜ>:@¤“§¨ŸUÀ*ð;Ô 1@(¶…Û—‚r@aœfiçFÀÌéè“yRÀÌéè“yRÀp»¯q¡î?ð?!áä4ý”•@ «ÁaQ’@zkªS\õÀ”3Ó´øƒ±@ŒZ?^N@T›Nñ#–À¼›­d®’À–Ä‘µÀ–'vÝ-!FÀ8î`r¦@ûtŽb|Àø#Mjž×t@êÛ¬¬Ìœ?Úv£–3sÀt±P˜D‰P@›†¯Ô?@%™ùﬨqÀô¡~Ûz@™_§j‡óJÀÃÄÅmZbÀ·NÞý$q@AÁó\/Ün@U48 ¹b¿ð?‰ä߇œ Àû:ÛVTHÀ4ÛM¼Z—@zkªS\õÀaŽ6µ)œÀ_Ó]í·, @©ÈŠ#Ã@ C7f@â+¨ =ÀíŽ>¥¥OW@‹»)•ƒ@êÛ¬¬Ìœ?”¼ïTßr@€21ä8æ?gËã?wYÀ¯e–'Á½?@˜½ÎÐTSÀÀKs¡3@ qlV3‘r@ñævVA7IÀr6D²TÀ¬°wp RÀ?Œ«,úuÎ?Ð?á8IfõGv@û¬ŸWRs@Ó\ú%'%@H- ·ä‘@n¹ÑZÁp@pkÜ,¿vÀ$ãßf¹¹sÀ²¢VqÀÕ/#8Â1ÀQéí ¹†@ dÍnïÚ^À‚¹¶€ U@Uº7ýìÁ?¼ý:.˜SÀ0r7 Ž/.@, £Ø @:–&×:TÀ–ÞeKäZ@Å_0§G@+À;z±•.CÀÏùÊ–+FQ@C[mèO@q:•G?k?Ð?¯&Q!÷­@Ä=¶åÎ@æçlʸÞw@Ó\ú%'%@±W”™ @Ãú$CÀµ!‰lÀ¦‡ 7m7Àk’î%Y}À±žƒ•<@Šê§\}c@Uº7ýìÁ?\ô‡•µýR@þVÉxw´ñ¿%KÁ+9‰9À.%m·Ã"@ݰŸøî91Àîýt @³C R@Ô%pº—+ÀãIÍìiÝ4ÀM…»EÇ2Àw+TiÉÒî?ð?3(\‡1—@c·f”@þj_eögW@ßy 0H²@WƤ’@fCÆ™z…—ÀïÍ&›Ù”ÀVäˆõf{’ÀCgO’ÎÆXÀq> §@3Qªœ°€ÀGRtÌ?u@1%N!ò?æZÊÿsÀxжlK@ƒñÓ[Á?ìÉ÷-yàvÀâU4%={@ ðñ{ŒKÀ 8UvÄcÀâƒû§ßTo@âƒû§ßTo@ƒüwõÆ?ð?p×+~F@­µ•[Ø—C@2 ­è@žå¾yÐr@2µ€žŽ’QÀJºér¿AÀ’ñFa×;SÀ꘎B‡òß?à?“œ!voi‰@Äv‘M ˆ@„MºÑ`!`@Av)¿¬ƒ£@pËy’Òç†@¢ÄBKéŠÀ}ùh'ˆÀû "|‡À±š(t§ôWÀëü™9Ôë—@ЂܥtÀ›R¢Æåe@çÙIþJ²ø?-Œ— vIeÀç¢uU0@½õÓ)8À›’ïòYoÀêhGHVl@蟧`m<Àè0=®Ž£UÀjȾBK `@F$™pâ£?à?“î ‹5’O@~…fMùM@Q§ÇoŠ@„MºÑ`!`@±.AbuL@Ä0|˜3PÀ ^ãaÂNÀÑè€ý3MÀ ²vÒÀüÀ„’C4,Z@ cñ)ít@åÙIþJ²ø?‹÷œ5c@CrÄáŠ*Àñ…ãõJÀ±ÚíèÈá?@*©*£Ù¼5À‰ttCº0@?eê·¥áb@³i9èBÀ̾ƒ7ßbCÀÏÐñ÷:Ü?à?ßT‹a,‚@Ý_Ö;Õˆ{@|ÀÅ?:8UÀ³†p˜.Ÿ@( JïÙÛt@´¸,;o‚À½Eôöî{À¤ F”(uÀ‹<¶×ÿk5@îG*p•@˜4³Z?bcÀ,BÞ­`©c@52º'pç¿óüÓJOaÀê³ß…RÀö÷Ä´J¦h@SãÙŽ½©8À¿í›ROÀ!¹“WÎÜV@ÎxWÅÄœ¿à?ù;·Ûp“BÀ÷yé¦ú$<À])ÃÊ‘…@|ÀÅ?:8UÀŠÚ³×#R5À¥ zÅ×B@±6ùÁŒ<@§ÌÐL‘ 5@ÃHr²äŒÀ®±÷A_Ô)@ w\q@42º'pç¿Çsågb@çÑ€\!@¸¯w$÷NÀio8@”›"QÀœ³î@/v·¾Zb@¤Wšßƒð0Àï*¹C‘;ÀȽn¦–ŽÜ?à?2SR¶/º‚@‰(î|@ÿXÓ¬¿OÀ„Î2§gÕŸ@!5¥*—Xv@$¢µŠƒÀm`9˜Ñ^}À[A«¨œ¯vÀú7µ_„%@2V‘þO•@ì°a•ššeÀ [?jÕc@×’ÂoY„á¿úëÆ9jaÀr†µ{G@–+M¬G@ c‡& ôVÀÚÆiÀïh@!©æ¼uô8À"ü¥Àü"PÀ!F,;OJ@C½ÆSW@“ À-CI•¿à?€”`'Å<ÀµÖþh§5Àé ºgžX…@ÿXÓ¬¿OÀ~ÙZJɹ0Àÿ eñu<@1ú%€¼û5@‰€Ú²ëú0@f X"ë¿¿`f¦Œ¥@g¹ß> ÞwÀ¢. ¶t@½#“÷œ8æ¿ú/ £ÁqÀ9ÇÂ>[lV@jÙÇ×7S@ ¹>:„kÀMfÉ [;y@UÉ1%ì>IÀ3Wà` `À&@‹ß.g@&@‹ß.g@ ÉáÚœo›¿ð?ðNm{õsBÀÛ~/.Ý=À½»ìš~¸•@Ùø%´TÀ ÏNzê6Àc9ÀB@]þÏŒ=@ ¼4/þH7@SØüÆÿœÀvÇ,ÇF1N@éܤòCÐ@¾#“÷œ8æ¿Ví€)Tr@€ ,eÆ @[VY¤]À$ž÷ø¬6@bãÛÕ\Àjbî|X¿.@CF ­€r@º©i–"EÀæÂíøfLÀæÂíøfLÀž.¼žv9Ý?à?_×ÐTjêƒ@ñÍ…¨´€@Í(³ùB›2À‘È®˜ @`–ÙyÄy@sšÿpA„À/.TB³J€ÀOÕq5zÀ¸š>¥L(Àbñ=wË•@Ä+Ÿé¼.jÀÃÐ_I1d@y1\÷tÂÀ¿=_ÂB£bÀTx,2ÿEE@ {CÇmÍ>@N+;üQ`Àت *‰i@BˆD€ ‰9ÀXФ!QÀ]c±›H^@¹i¦\qYW@$¥6dñ;x¿à?®&ï|.¿ À¸jÝqðÀ½8«ƒ#†@Í(³ùB›2À,œ ãàªÀ…Êë[!@§œ6Õ(f@9ò½Ž @3¨ÃuiÀµv¹¸¼C@qY~­«/r@{1\÷tÂÀ¿Äƒy›°ob@7Åqà®ý?’«Ð M’MÀ&^ÔâÛ+@ôy¢1~JÀcBÁ=¿¬!@»eà¸",b@n „ÙP7ÀÛ'7r¤+BÀ6ÌU\ãC<À—¹fÏí?ð?Zaba”@Ézñ¤á@Ûæ“ûµ#@ö`·¥^ó°@øw轂»‹@BðDqŒì”Àû2”¼Ð/‘À®@·í;ŒÀ4sˆqHÀ¡Ô>€ ¦@n’ýÞ^‹|ÀÄC(at@]­‘Ÿ.Ê?DÞ½jRxrÀ8nCƒT@ÁxêôG@¥oêõˆrÀ«•Ç_:Ùy@6 —»ÒIÀÔ¼šò¦aÀ~²¶¼Ìp@±ÆÿY…g@nŒJ¤”k?ð?å•€ì@_Bér @/ü^š–@Ûæ“ûµ#@·ü?µ/@ ñû–?À:¿oú À¸Ž´ŸÀ9-C]+ÀU6מäšX@¬ÌAÖ‚@\­‘Ÿ.Ê?J±CÀŒr@dtºM ñ¿@½éuÀ>ªÛž—+z@´³4ÅëJÀn™°5v0bÀ-e(E•ìp@¥8DZg@Ë Ü:D“?ð?—·$[Ú:@¬ÞÙNO‰6@A¿>N—@ÏÒš6M@ïRæé2@†E£&^;À™ä®5ë÷6À‘7ºF3À‰šì5ÖGÀ™:üj¤µ]@WšÞ¶­ê‚@´‘Vd°›æ?jÓ–4g©r@¦‡èV8Àôz…gÕ¹]Àª;ƒ¹‰C@ØX…ÈWVÀraÅŠ6@ùÉè¤Hr@á@0DÛKÀòˆÅÄR…TÀìòz§ºLÀ÷[gCÞ?à?€?t-eê…@WëÌŠ<Í‚@«¸{cS"K@ ½o±t°¡@aâ‡ÆW!€@k¾ÿi\†À= G /ƒÀÀ&:Cu€ÀËwªJkIÀ°Ûoðo•–@˜Ddù÷µpÀY>†ÏÄd@€ ÓPØíã?Œ©‰ê:cÀþ÷a Y=A@lgª¨q@`²·ôœgÀ>«R]K€j@ ªû‰d:ÀèsXSZ¾RÀŒÍ_"<±^@4õfÅ.ßW@);r÷~‘?à?ÜÂHŽ=99@¼c ÁÁ£5@TºÍª‡@«¸{cS"K@ö‡9…¢2@ÿ†3x¼9ÀùñW6ÀÕôº8ñ2ÀÆ#o¿ iÀJÙ{×À‡Q@:«Fs@‚ ÓPØíã?‘ÑÜ–Çb@tÐÔPÀ÷ÏèÕçõMÀkC6âd6@ÚƒCªDÀ€! ’)@N—Æ£’Wb@ì³Âç8>ÀD1„žBÀK÷xóõ<Àü½,uŸÞ?à?½¨ª¥†@–G{WNÞƒ@éæýµ'T@Ú"Àú¢@Bʂغn@3ç!‡ÀÜ¥AâK„À/fkßÎÀpi{?PÀÁåHnÝ–@T÷u^øqÀa‹ØÎ–ød@9×g¨+í?Äè‡y`ŸcÀ´¬0+^?@1tùê'Ì¿\BDÜEjÀúW®¢\×j@˜´ÛZ†¬:À»aÀ-ÉPSÀqç² X@qç² X@E椆¼Œ™?à?½âRëÖB@­æîÓè†@@¾ÆÌ^»Eˆ@éæýµ'T@^ò€h=@ŸÊÒnú=CÀå~Náâ@À7Vã$[ =ÀKJÂ…7À7 å†UT@í䌠s@:×g¨+í?÷”·æb@þ» ç¬i ÀæC>>}NNÀêk*»9@ó@ÍõBÀÇf¶iFÈ+@å9™àüfb@, ½ðS@À­²Å‹;1=À­²Å‹;1=ÀÕ‘òüî?ð?$ïh—@48_3N•@î}%ŽÝ°j@ÃÇ@¬>x²@P]#0Ý’@EOb%îð—Àæ|›í&~•À·ãѾxK“ÀÃOãpiôcÀ•ªGÒ'§@hŠb=äAƒÀæÍbS¦-u@« 4µ+†@ZÅ0v¬tÀP§í@ L@I™Œ–30ÀÎ9@l}À¯rlYÏ0{@ â1(×óJÀbz’ëçcÀèìñ ޳[@H¯Ó\=h@pŸûUçÚ°?ð?s%‰fjhY@u{Šü<ÏV@ý]p–í˜@î}%ŽÝ°j@&ÆÉåzT@ÿ€¥ËôüYÀ±©¹—–TWÀ¼žlgÌñTÀZæÎ–ºÀs*nEg@H>è‘Wøƒ@­ 4µ+†@›”¼Øs@ª?ÇÔ5À锇!êÄ^Àºu¤JM@ó÷EÌw”QÀžox'FŽ>@¦Æ•Öêvr@{6è[‚”QÀfg˜}PÐ@Àï´ÊÛŒlMÀf…ÛuœZß?à?®Y«‡è3ˆ@­Ùq§=†@3ÝöÊÇ`@gýíõQà¢@©‘Op„@ÁÂG@âɈÀ³hvâxdžÀÕVÉÂî„À Øap%ÖWÀ8ó!™¡t—@ßÂo½’tÀ¤§"¾öce@|Ö¦ùÉø?t@<sdÀHy¨Qjr8@dW£‰0ÀJ›øÿmÙoÀïy§£Œk@K‹u:;À[ýçƒTÀ/†_mX@Jc<ªŠý¤?à?3Ä×,P@ç&£çä¹M@F¿¤µ¢‰@3ÝöÊÇ`@Ÿ±àQK@ŸÆ\wÑPÀ(ŸîrNÀq•ÇþIúKÀFZNfëÀ£ ¾XZ@Tü#õNt@~Ö¦ùÉø?üía¿(c@+OÅ&3k+Àþ¶ú‹˜ZOÀ~e>”àE@@!²Â¡ªk@À:¼ ›Ç·0@é©Åc‡b@ð÷a–ÞBÀ(døÌú§=Àʃ;0{¿Û?à?ºÐ²M¹P@ìÂM{ey@³éu—RÀÊbxñò2ž@"t!QŸr@J½ü¹uŠÀ ۲ȹyÀd¾)iÝrÀ^ŠFŸ´1@'_þÜÀ”@Ô€VÚd¾cÀD£¬”@c@οŠm´oã¿"ªÍÑqv`Àv4a¼dK@'™{{ëM@TfÐf¦TÀE.h2 h@àyh%I¨7ÀB‰àbL¸MÀœl0ó¡I@7F‡O ‘™¿à?çïƒû@À«TÌÒ*z7ÀB–¾ÌO„@³éu—RÀ‰¼dN71Àï—ÒJ[7@@€`8sÈ7@kÎ϶p1@£ «ö±ÑŒÀTb ×^0@÷ÍÛ+wŽp@οŠm´oã¿FÈAö½Òa@t{^w @@ÑŽÑ&éPÀÇŒéá©j@ºe–½=.SÀº q?Ø’@Ÿ‰Ó²a@¾[#€1À“_v/ÀÁzsÖì?ð?“ƒ÷ב@o³±T¯Š@/Ct>^ÀZÀ‘ÍTòÓ®@›13õôƒ@43®’À(À¾ ‹À€nsz­:„À¨î¦ø©­-@ÑðpBø¤@j¿ÎzêuÀ»ížjs@®»Å?·½ë¿—ž¾×!ÇpÀ 3΄›Z@Ûª=¦V8Z@ð U+ôøhÀJ†Ú+Ox@2‰Y_¿ïGÀ€e†±4Ÿ^À•¨+EÎY@˜¨+EÎY@iQ$ì1¢¿ð?á5ó,=GÀA©ôÈt`AÀJ* †¤”@/Ct>^ÀZÀ;L›ü9Àu=HeG@þ²‘ˆïA@Ö_sbŒX:@ÍMGÏÞœÀVqBŒH@êGeLDí€@°»Å?·½ë¿{(Ljìq@öà¯+ª%@˜«ka›Ð`Àÿ`rW3@´Ø³féaÀÖ2"ÄË´+@çJsÒ>¿q@ÖÖ,dÖ‚CÀ¬Ü¨•nC?À¯Ü¨•nC?ÀèÂÝScÌ?Ð?œþ¦Ü«er@\ê–Æl@ÿ8@÷/À¤˜Žµ|y@°(8Øie@N}ºFªrÀà óœ/{lÀ[õögBºeÀà!¨z’æú¿£á1¶^2…@)G¹`Ã!XÀpÀIsÝ•S@•Eae‚_¿¿Þkݯ*QÀu!™ïŸ9@÷ÎÖ…N€6@„^àelMÀpX“q0—X@À2…î6(À‚_8 ?À«)]C¼F@½U³ºû9@[-óªKa@›Eae‚_¿¿iîÍóR@´ßH±ù?BÝAOOÃ@ÀcW³R<@e\͸@À¶Ì4Ûªü@ÿËÿqÌQ@,†“’%À~Î°Ž•+À*Ù¢îY†À ¯Eaþ¶Ü?à?›#ÿú‚@ÔµAè2Ž}@ø²Œz#ÀoøX× @Kñ5òów@˜…PÂEƒÀ²ÇËw ~ÀUšªB·_wÀ´ø6îìS-ÀÝi?1n•@ȹk¶©djÀƒ@Y®XÂc@äU¸/m:¥¿Š7¿ä£oaÀVC(H@€7R¶ÂB@<Œ#k aÀ+i-Oáh@§½´‰À}8ÀÇîbAPÀœl|Ÿo]@‹`àT*J@<`îȹti¿à?I Äí—@À°àÓ•Þ À4IüÜm…@ø²Œz#Àeî}ìÀv“Ýõ`…@ ëy¶I @Êú°Zê?@©ð›ÀßÎOE@4áÚÏ—§q@ãU¸/m:¥¿C:U?Ÿ b@ìÌcrAî?Y[vOºÁPÀR^íwe-@),ðcï8OÀg"‰ß96"@rç½ÖÙa@´Þæõ¯7ÀVA9$,áAÀF;‚2É/ÀêÕHaá í?ð?º§m•“@ÍBŒ{&@,ø?Ôb:@"WæWRi°@ËðEƈ@X»ybkè“ÀQU…Ž]ªÀlôž2þ.‰ÀÔ…1É‚JÀè±¢?$¬¥@0{T˜³|ÀS¸ðs@qglh[ÓÖ?š;¥ÇqÀÚ7à@ |•d´z@ ÿ‡Õ“„À£#÷2¸€ÀQÿ‡Ñv,{Àƒô{ÁuCÀP€mVFì•@ŒÞüoÀ©!ÙFd@))äDÙÚ?¦ÓK¥E"bÀÀê'F@e{±Al6@‚ÜïçåÌeÀV»¥|i@ý- ®ù 9À7:>´AQÀz LØ–`@,­óŠJ@cõBòîaˆ?à?ljN>Ú«0@ËŒÍe+@rVÒ»Èc†@iÂy”lB@’º¯Q¿&@Ìòù£Ïö0Àæ…â¯9’+À³7k¡¿g&Àþ OÛ7À$Y sò¸N@Ã}]r@*)äDÙÚ?ËHcLXb@õþý AÀp³)îºãPÀˆA'/‚E4@)°NÃÖMKÀ׿>úå&@×cÅê„ôa@N£ÿ­O<ÀýVŸ!1DÀ™EL±M'0À'ÒÚc€¹í?ð?­Î;Vâ”@ì(ÍjY‘@77 7Ÿ^@ÄŠ¾©±@~ð‘œSÓŒ@m~p©F•Àv—»C¬‘ÀïÊ Ôù\ÀpGUöYÀÕ¦6¥.¦@ˆ—-¡»€À¸$Y\Ot@îJm^Ÿmõ?n±˜œrÀ„–R¦›ÎT@FP%°a›=@-e`OxÀ¶0gÎÌy@Û‡¢Ú:OIÀÄWSUÈaÀtÇn@“[Ûñ¼Z@$>Vt¤?ð?§ýf˜ÃL@O2ì5]HG@c¬ÊGð–@77 7Ÿ^@ªU°mƒWC@¼ltù˜ŒLÀwþý‚‹·GÀÖIò3à³CÀLIÈÅBYÀ³b)”‹óa@R¦ͳµ‚@îJm^Ÿmõ?#Ç‚Õdur@ä&JGÿ(À}îË>haÀYºj,nEG@\}ƒ¸ ŸYÀbcØGë_9@I§ÊÛr@2º3Õ­`NÀq¥ÙÛ©QRÀ‚¯Oü–H@À2º> Uî?ð?X+zO”•@J%Ôv®U’@ ™¿:t™e@G&˜ä¤~±@]ëõiä'@§]ñc¿–À nKª²’À¿…ÚåÅÀ8¯Úà c`Àb¸Ls¦@?¼šylöÀ¬¶7ïê€t@¡Þü—€*þ?FKgÀßrÀŒ/•TP[S@¸Þ Kf‹,@ÆZÜ–ãåzÀ[ø^5Ôz@Ͱ_ Ô“IÀshÃ#ÌRbÀ®—N’g@]õ>5ðZ@JÆÏÛró«?ð?ž9ŠT@£YóbÿP@4ïól눗@ ™¿:t™e@ø^–³áL@yÙ„fTÀ¥©O¯DUQÀj w,tMÀsf$ÆxÀëvä*ªd@Y…Mä ƒ@£Þü—€*þ?ób¹c“r@?<Ä®·”1ÀÂc2,ý:aÀ´ÒàÖòjJ@ZC†o"XÀ´±öñ;@òhz¹¨r@ª‚EÀ]PÀ†Í~;¹LÀ—¾ÚœØi@ÀDmKº“lî?ð?ŸÇQZN–@HÅ*Xd“@ ´žl@ôy!“?à±@ùžÚªËÛ@b%Þ{Æ–À|ãÈÌ“ÀÖ¼¸–6‘ÀÕFÅC-ôcÀØOÈ¢Gº¦@gh¿8ƒÀ$k «¾³t@ëtŸ%BÂ@,IÅBsÀÒ’ÓIÌQ@ÀÈïº9Œò¿Î®Wi5‘}À ³aH*uz@ªËñ¹×IÀ®pdÈìábÀÏßm*$[@Ïßm*$[@çJ;Úâý±?ð?X8j„+TZ@!3öŸãV@¢ÁÏ.˜@ ´žl@ŒF<‡æS@ô²:÷áZÀ£¾må^WÀÁ†ÏHHQTÀiMï´·ªÀWéÕšg@ûµzâ€bƒ@ìtŸ%BÂ@O\U²r@æ©GÅ;Ñ6Àpæ |aÀà°¸£·M@ÿQH¾iÚVÀàm$>@tCÎò r@\Š•È“QÀåƒU‹@ÀåƒU‹@ÀP2TIÈî?ð?»ºÕ¿—@<|Í·†”@ƒozÚ¾aq@Oß-JŠD²@.iÿ>D’@71¥”—Àðäü”ÀCiÈ4³¬’ÀŽIMKA°gÀí*‹ž§@T nÓ€„ÀöÄ|Óçt@ÇNâÀ'À@—9¨sÀÔv># P@Ìí¶l °0ÀûCÿ )€À|ZTUÔÌz@‘Î2áJÀEæÕë¥ucÀbL… OY[@œ3¹¤¶?ð?œâ `@Ÿô¶Ó_]@èe‡ø à˜@ƒozÚ¾aq@gžîþ#Z@ЦB¤gß`À1YäÈË^À–í»Ðy¹ZÀN¬ÿ’<ÛÀ>÷Úò{j@/£7Öp¶ƒ@ÇNâÀ'À@âænAFÒr@èöPØ÷6<ÀB6*ëuÌaÀ>1ÿ@t•P@g=Ý~ÉUÀâ+ˆÁ9±@@@$i1Á0r@uy_ØÒRÀ<6Ì^¬@ÀR‹w¼$HÛ?à? l‹ÿ‚€@¥ãfrw@B`X·PÀ¨RëÊWB@EãP빦p@b™ë—г€À:Ë(Œ¹wÀe`G-ñØpÀ:üx˜,@)Eçp”@e|\uòdÀ´– DƒÜb@a íeÃß¿=¯65¬À_À*¨†b|vN@ Rh¤Ë¬VÀ}ä¹8Èsg@‰Í¦ض6Àç´g}6LÀ^—áÛ¨w–¿à?f<ÉùI;Àx›^;a3ÀS÷ú¥ƒ@B`X·PÀŽb¹´¢†+Ào‚¥Eœ;@JÖ⬛3@ýNç¥Ù+@b=i2ÀŒÀ°l5&3@^öZyÞp@a íeÃß¿K£z2‰a@“>/@P.@ºú»RÀ_öÀu= @îœbY'MUÀFªòEû@\ #…sda@0U¥ 2ÀŒ;žœX—Ë?Ð?d»O£q@¤Šfõ£h@Xµcòd 6ÀÂ/`ÔÝ@¬ò|F>Øa@|Z­9qÀ÷÷®qóhÀ"hšp|bÀ|ÿ{@(:ÿ¥„@LUm›C8VÀsýK¦S@ÉoážêKÅ¿T7ê-PÀ,á5¢=@0ã$É‚I=@Š;;ÖäJÀ–Ŧ¶w¶W@7XiAû&À®!Z=À%ÈAëR9@?qÔìIc~¿Ð?"SyùÕ"À[¡^-HÀwŠÂZ|ùs@Xµcòd 6Àh å_öÁÀø‹ée#@AÍr±Ÿ@ÑÃzW@ègÍ|ÀzáxCÿ}+@I0Cún`@ÉoážêKÅ¿èÇ/ ¡¡Q@¾]V`!¼@ïJ¥ «BÀBöÞÉÚ@ùiz½äDÀÚßÖã¯ø @•6lkpQ@>G¤ø#À­ÛœÇÀÿÆUiŸçË?Ð?ÓÉjóVŠq@¦@,·çëi@¤;2Ž'Àë‰/V­}Ž@Q™T'c@,FßQ4ÆqÀéiªÒ_DjÀÁù5s³hcÀ0]˜TLÀ§ìKwÝ„@]‡WcXÀp'²Rò-S@î9.è@賿;Adþ{PÀû‚~Fй<@ ș芣9@”ùjtK8Í`À²J=fó¼K@-}á^øE@—<†xÚaÀD£](¹Ah@Dõ†ƒ7ÀÊÚ§«ÛNÀA>¦[sà\@úåH=R9¿à?ÉmèW¿2ÀøMj±îâ,ÀHSU¢#A&Àâó§üþ Àpø S±×Z@ Š0r¯|@CÒµ„'ß? n·Ôôîq@~ë$ƒFÀFÑe¼bÀuoØ!!B@”JÀð`Àš‰¶è4@±´¢ïN–q@œTo„’ JÀFÞž·SÀ]ͪ>OßÌ?Ð?qø ~Gs@ãŠ0wàZn@"$|ÞQ6@¼Ëè÷6<@ƒ¼=)”åg@û‚ˆWË–sÀ‚èóŸ¼×nÀ8[®ÃßGhÀÀäü&4Àµ ^Ž…@·>”ÿ )_Àƒ7¼Â ±S@% Ø/ßÍ?H‹ìdêvQÀ±£[_;9@@œM`#-@ŒÂ6×ñ†VÀûU“ 5ÕX@â±¶> (À®´­1a@À¡ÀêÊDP@8>vW$‚}?Ð?V—åøÙš#@îF¾ïÞ@¸ªç™‰´u@"$|ÞQ6@Ø|'çL@ZgŽ&~ë#À° ö]À€ÐƒÃÛ°À¼›×ê)}Àª³=<ס?@®ÞÕ Ôa@% Ø/ßÍ?xY{a5 R@{è‡LŒìÀ#) ÚBÀmS¿®J÷$@¼Î9 @ÀÖs²Oj5@ßõŒ/­£Q@‹Ÿ1±I,ÀWBáÒ’à3Àêh³M4Í?Ð?”ë?Wàés@f¥¤çäp@Ê¡å$fñ@@Wé`Ïc•@´º†7Ìi@=u¯ó AtÀÅ_ MpÀ‘[ %=jÀÖÚZYj:Àî1›c\Í…@ÛNÀ¤Á`Àùù;A2ßS@byY› Ö?OdzÏQÀ ×.$5@8@ŒÍˆ¸«%@…Š‚•øXÀY*"Y@36ƒ³5K(À˜"Òâ—à@ÀD5s•~M@3Þ@;µw†?Ð?9L:†Š.@ëÖ¹s‰”(@¥†­«*?v@Ê¡å$fñ@@©DÊbÈ#@Qì7/Àyœ")ÀÒNMÌû$À»li…«J}ÀM]Æ SB@F å1*b@byY› Ö?Ëb×E&R@˜»—DLz ÀD òCÀ²#{´Hñ'@Û¸<,j‰>À96輦@S›t±Q@C§¸.À˦ȃ2ÀPšÒ—ŠÝ?à?‘´Q§²“„@ä€èÌ6ð€@u.@ÔW@â‘ñ @bÇ»Pãâ{@?HÚ‹ó„ÀÌÎþ?ÀànœÈd|À³ñFtº|PÀm-›Ñ–@½=å0!õqÀü:ûPšd@Õ8Á¢ãî?ÔSž=Ý*bÀ2HiÄ.æF@ðî <ÒP,@Ü)“òu}kÀú`ÍRqi@|rF¤Œ8Àt÷ÏûdQÀV¤Üf—W@´,÷Fž?à?î—0)H E@Ï.N5ÔQA@¤6p•Õ†@u.@ÔW@Z±Ph˜ƒ<@±íîºIlEÀˆ†L4¢AÀ°vEIj=À-jpãpÀmß:âóT@\Š›4Î~r@×8Á¢ãî?Ïêí‹/Cb@Ų´4ܧ"À¼¢˜]k=SÀµœº¦;@‡Y@ޱ%MÀ–=0”½,@Þ¾ñ«¿a@,µ°d@ÀÞZžhF<ÀT«µ7âÝ?à?VTг9E…@±ðüˆê@J”s`]@?îa(O¡@ÿÛƒ.~@âPµ§£®…À_]SC‚ÀÞOHÄ~À¦ª‹ ÇëSÀ”nj †R–@Ü$©¥;/sÀ½äÏ2B?d@œntpnÞó?À<æˆbÀže7QçqE@äz=•e@UÉ`RnÀò¹ï¸Âi@^vn:WÍ8ÀÈNÄ¡ëQÀöbpâÈšJ@ÚdÒУ?à? ¿[—t!K@ƒ_S/ÚF@“\ x‡@J”s`]@ÅP®S¢?C@©Â>†é§KÀi)7pKGÀN‹Q'ŸCÀùùîúû›À]Z²“³W@멯XÝÑr@œntpnÞó?âR¥ab@vCé3¸'ÀÑÎÓù„SÀÊHXkT>@=´W?õKÀ:~Ôe£.@*a3ZÎa@Þs³AÀ•û¡’ÞH0ÀÝîë<<;Þ?à?ÙÆÝØºþ…@oî÷‚@žûó"ða@ä<ÃÔÞ¯¡@$­x CZ€@ׯ½2®r†ÀN[?c [ƒÀ×Ú£w°€Àže¶÷ƒWÀ£Ô Åƒ˜–@ÃÒçI)ptÀP‚Ù(qd@š`Oir™ø?_òÊ¿ébÀ„¶C âC@à#&{ªð¿·^PöapÀ7À»I`j@ͦþfÀ¬ÿ»ê?š™™™™™é?rê!¶qú @8=-¼¯@ÁPú ‘¤@gºMn|V´@Àÿx”„¨½@wtÏ_B ¢À>®ܰÀõ!uUƒ¿Àt…x.$`@&üxp‚*ÀÚ"ôNÌ]À½ ÒÙ˜ê?š™™™™™é? ÿ+³_¡@34Ò\­<°@~€ÇÂÏ´@ÅH&œÕ‘¤@ ËGèdY¾@wì~ÊØu¢À²1rðŸ@±À§*‡¿¢ÀÀ¿ ]î*À°rFgÀ`@ÕHû£5f^À6l–=ø?ÍÌÌÌÌÌì?NÃí `¨@ÒEÅš»xÏ@ê…ICôº@ú§ÑVXIÔ@EwC™(Qô@P›â¤À¯‰C¸wÊÀW½ß-ñÀSÜ¥¢E°ƒ@‘±|@"v}†Wù“ÀÃVEœ¿E@¨¶ ³PÀ¹Ó¢C\]0ÀÖ3bE@¥«-Ìr‚PÀ’:õ×–â)@{Cd"tê?ÍÌÌÌÌÌì?zžG` ¹š@È [@Á@ÔÂìUÙ_Ç@ê…ICôº@HU¿Fæ@ªéÏTy–ÀO̰ƒQ½ÀíFÓ£y»âÀ§Ær=˜ÀÔí?iâdÀ“گߠ@¨¶ ³PÀ?YkÖ`_@ñKî‘'¦!À)î JÜGÀØÎmþ^^@ïØÛ2KÀ+DäP(5õ?ÍÌÌÌÌÌô?DQ«@|[âº@ˆV²ŒÚȰ@ûè#­£›À@I¥t1¡lÈ@-Ž#Áot­ÀbmãUW¥»À+ίòÉÀ@\‰•}‡h@hX¡÷[ùÀßÝ ·¦fÀõž?£õ?ÍÌÌÌÌÌô?öNC?T¬@ž®¯Ù–º@Ñ|þ:øÀ@a»oãɰ@‹dßÎôÈ@À÷k¡©®ÀAÖs6{?¼ÀÒ*¸A\ƒÊÀö²2¤ùÀŠðM‡kh@"+ÌæÏgÀ"Òð€+@ÍÌÌÌÌÌü?¢²·±[¸@OõDËdß@ó1h†¿Ë@¶Ýó-ä@ûtŠ7:A¼žbŸï€´À:ÀwalÚÀk/“¢­Áòòð±¡ü“@¢K @òæŒ@L†ÄeE¤ÀçP$FÄT@•xÖTW^À4@ÃÙ~‚>À”zò¹T@V&•C_ÀE©|æ:9@pöÇ1•Ðú?ÍÌÌÌÌÌü?æÏo «@¹{+›kÑ@ ÿ=£x×@ó1h†¿Ë@0¨ä(sö@da¯úÎÁ¦Àdü‚ÎSÍÀ)½fµåòÀül˜Kr;¨À½©\±³HuÀÒ9¯eñ°@¡xÖTW^À˜#Oº]m@Ìò‚ ¥0ÀqôžØ,ªVÀ‚´™l¬kl@=KË&ŠYÀmrcal-2.4.1/test/data/test-optimizer-callback-ref-x-0.npy000066400000000000000000000151701456301662300231530ustar00rootroot00000000000000“NUMPYv{'descr': '‚ë½Ò3@XŸ¦WƒP@x)ÍùA0@Ð:B [DP@P üн)@˜&4Wl`@`È·±Õ2@PSOZP@ ÜJ:U@¹8K@ñO@ÀÑŽù @x锵Ér@Ø´ËXXq\@€¼;òRb@¨ÄùÕÑçH@X³áŸjQ@P½ vL[5@à0­ßäP@èS²¶Ò2@ ÈöZP@à®i³ñ-@°€™%¿ão@ÎÙžJa@𓚠¬R:@»<2’p@ÐÛõ\pC@PÔãÝ´O@àÈ>œ /@üð¨ÚŒ^@&¬èhK@°°*ýõx]@dín§Ð?PFÍëÄ•l@@ mïœ(À@…¨Ñ¢äK@úJvòèÀ@f“Ò AK@µX@I"À`,ôqÃZ@œÍ%‹8ÀÐOW£ÂÃq@ ì#nêC@ð£5åìP@ ôüR“ø@ø_ˆ`P@@,Xά @pœj~ÀÅ^@¬ýãÀÿã?€$fxÅ~m@Bè¹õV'À µ4ØUB\@@WÞZ[&Àá~YFK@`@-¶uÄ!Àû+ö&gJ@à›¸ ¡'À°PµÒ¿¦i@zü–ðÀMÀɨX#i@hÛ ™oáQÀXùíøza@¸Ý€Ñ @°’¼èQ†p@`@„Œi¸¿pØUæ—Xo@@?¢Ñh)À0åO¤ìÛm@à$ö8V\8ÀPËkll@ ƒu1üAÀð˜Ïq±&k@Ð1Â`†HÀ€MZ#wj@àvyó NÀpG^QK Y@°Ú¦Ò´BÀóvgš5H@Àß<´ì4À0=)êkxW@Ëœº±¸GÀ áz«*q@§ Á--À@hÃm±/P@`Y3GÀ 8EZ3“n@VŠÒæ¹CÀPê+Jâì\@@è´s·9ÀàÅOZØ][@°š#´[·?À 1¤ÅZ@Ð뱆VÑBÀ`'ÅšÚÂX@Øâ¼S]œEÀpAz ªg@˜â~ÞøsXÀÀã°®¼V@ø»5KKÀ`æ·ò“ÛE@“‹[}>À`¤jçp@I¾¸'9FÀ ç/òJÅ_@ÐØ§S!<À Za‹gÑm@HÁ¢@ˆQÀ •Û¢Ö\@ ÉuTÇÇCÀ°[&N9gJ@PÕ¡£sã6ÀÐRåaXâX@ðoÏ¢IÀ`•®AS~W@à‰ÔfzLÀ`ª…kí?f@ˆ‘ f*_À€Pþ-E@àÕ"®oö@Àà”¬c5D@Ä­»ÀôUBÀ¸åº¿ë `@Ðû‘e·BÀàs¿•üo@¸GôV«UÀ`u>´ôùL@pÛf(@x8ÀÈP"[@€q·š]KÀ@1p’*fY@(«Ðj NÀR îMÉG@ä¦[ŠŒS@À 8[RnPF@P8œ ÛÁAÀࢡ|ðD@ôæðÔCÀpìd´Ó¾c@xr)ðòndÀ°ÿOÚ+œb@ÝCK½eÀ,[5 \`@˜Ù³4¾JÀ`n‚%ã|N@0c¹%UY=À`“rQl@`©µ$`Àà)A9“cZ@Ô+%3wQÀp(ÐtmpX@|‚5ÔRÀPoω]±f@¬|B;0dÀp¹íp…e@¸æè¨reÀÐéÕŽ­›C@eרÜFÀ *"µP8B@€²÷8HÀiëÀìû`@Ð)è§]diÀ]EôO‘@Ä4ezRb@bÂŽ¡YÆp@¨¾¿Sw>I@5ö˜ŒJp@Ü äòP@¸K»YÕ›@Ü,Èlc@>÷š£²Ž@vkm_òÁv@VQç± Ü}@dJþkj@„^ÿúé}@ÆïFµVm@’-.ãÂO|@Wš"ã2Hp@¤]ûæ”{@µIàšßq@fnt2âæj@ úp°‘xc@î6´,Œl@@l/NÉ]@IÌ Ðo@XÍÔõÍE@¼¾6«\Ún@HZŽX.ŸL@.U€Fð@¨ n›³q@|KÙ<›@påÁŸ u@î}xg @Œ@Œ‘JŽŠWx@˜ ±Rtk@Ü8©ÞÖ©[@ÈHÑÇ ¼Š@ 5üš–â~@@d j@‰¤ì¢å a@°P[ì+`y@)5ºû£r@UœÚ¡o@SÙo-7@ÀVË#Ž@(,d¼?|b@ª*<‡3m@`ŽWR[I@üyKCgMŒ@,Wîååp@l¯ox‹@Ôò¥J…gs@Æò§ü®z@–_Þ¶f@ r€¾èi@t÷X§! Z@ìJÑ  3y@¢~¬ÅÔKm@Òcëh„ˆ@®RšÓ2@€@¦Ç7Æðáw@;/÷N£×q@Úæ¡©o@°ùÉ&aïP@άró£|Œ@€¯y¨%©^@((`Е{@p*ÿpl6V@B<&¶Š@ òÝ—ól@ܺC8èi@`Q{ÍQ@Ðè[HŠ ‰@¨6ñË*u@öötVbˆ@8•z?}sx@¼ ûg³g@JXJ¸.±[@¼ÆöJèw@P=Je`ðn@ô}Ì¡kf@éÐdna@:¼ã ‚Ï{@€×ó[8W5@(ì׿•âj@ jéKm8@ ge‘þy@x…(=@"S@úc0 %i@ˆÕýL3ÚI@r˜i~a]h@8¹Ã.OP@ÞÍrYšw@¨Ò•çv”c@Ä©bÁ!év@Äŵ¥Ïêf@¬~TD7v@È(­Cn2j@R«bgãe@´«íßc]@JZ˜fƒùd@!ždBL`@¤ØHcÀ.j@?‡mÇ@îOÆõJi@Pöàþp’2@U碞rˆ@ ¸ÿ©#-`@$6gsOw@ˆ»•óV@Òš~Ùv@ø%ö;¤]@KÒ À|à§‘<†r@‘<íj5@jUé[àÊq@Ÿù·žÍG@JІma@p¶•M®B@ ü Ês€@xËUd ]i@Æ"º¯o@’%iì_@°½€jQ~~@8ˆqÀf@s@ð,]æa]@ÿ°oV@@¥% ÏK\@‡ÑÕ߬Y@ÏYÊô‚@@0·œužb@’Wça^Ðn@øÆŸ¢ƒB@À)sz(}@ðGÊ!ÌÃR@´ r5…k@ȱœØ×B@,„Á.»æ‰@xZ–w/c@ð“²# Vx@°°.­PS@jJ·ßÈv@Ø©6ÀS@ÞöMWF;…@HVö¹(d@N…EÒµc@\f&ED@nÐ%Y¯8b@à),Jg3E@3ˆÝ6±@€!š¡WoW@I°5qco@@Û®zs7@î(ÿ$‚²@ )BôW@ Íõ¹l@Ð-™ zã7@h•Ý$F^z@p… ž!H@êÝïmDºˆ@P§×<"¹X@$j†´w@0­¸ìéDI@Dó° Še@ð¨TÿÙä9@¶÷ÈÌt@°;a¥ðÔJ@.tRÓvb@pÑÌ<@ÿ$8ƒlå@ —äeHB@~ù}âW€@@кÉà2@YÖN@n@ ܰ&"@Š8Â…l@à}e4•"@,:Q#xØj@€Üÿ«ø"@þçØö-i@@(P‰ì#@Z ñD5„g@ nÜã%@²ê¿lçe@ º¿h&@H<àJd@`/^‡#(@º$†²E»r@ ÆêÍ9@äªó£>@ä5ª•&ÀùM:§NW€@@šLÂ^l'À#’~üán@€’µÎÀNvŽ”3m@@U-·ÊÀ†°¹€ôX‹@@ƽÍÏ6ÀÂ¥‰@€) • ¹4ÀiúC‚òw@CxùY£"À: Á‘OF†@ÀˆäHÝ0Àµ '㣄@€@¿UÀ¢+À:r|¤c@€Ðä ª1À{Ï¡U¢@0\¥‹´0EÀ&*í§±@ðQ‰cFWUÀ®už¬ˆ@€MI04lUÀvÜ1±@@0¯½å`UÀ–@šžŸê{@Vò«*9EÀ2¡F0'Š@`+Œ/NùTÀ¶ Žhciˆ@ 4´ÒzTÀlƒÑÑr¸†@ ì(TÀÐXÊöe@43Ecy3ÀpÖà‡¶Zƒ@ðMâ›”RÀºÂ=T- ’@@Rqny²bÀ‡p2‹‘@¡ìN+½bÀ¾0ô߀@ÑÑÝRÀNÍ-[n@8fFéŒÅBÀ¿ÕŠ„|@°˜›•·RÀH‡¶Š@à¸b©bÀˆZµìˆ@€G‰‹ubÀ Ì;úF)‡@¨‘=@BbÀ¶Ó l…@xeƒj…õaÀ$ŽQ4»ƒ@àÇŽƒªaÀ*%}‚@H§Tz[Àþ]4tå{@€” ÒD@[À›Ú¬¢X€€@à8ÏTJ[À˜ ó¸C@øíõëöN[À6ψå.}@k'¼ÎG[Àê·ÝL‹@øH.Û¬kÀ5UY}‰@8‚ ûgkÀb–ÖÚ5«‡@¸ç)ÒÚÓjÀ&¾k¡Uç…@0Õ@jÀ.(ää|$„@Ü^ëFjÀ *Bìör@(î_ôñQÀ­¿>Kí‘@„Ó%iÿqÀ„sœÈ…ë@ÄîÑkrÀ°‹ê°Ø@ûÏá8bÀ¼ø±™ßm@€xNÒRÀ¦ãnòÂõ{@æ¦I³bÀRE̘Š@<Ò0UöqÀ^ÄÈ0@9ˆ@dˆk4}æqÀö7Âcfv@Ôú!xÉÄaÀB‹ºÊ°’t@}Ž•y™aÀ‡1¡cœx“@hY:IŸvÀ•ÜΡgr@ ™òþ¨VÀ]zB Zq@\w«Ék½VÀŲ¹¡Sp@È÷j ï¹VÀè[´»ò n@¤üXN²VÀª¿9® ©Œ@•L!ÁªvÀ<™ €·j@8‹û”VÀ¬õþÍ2Ôh@ؽU?‰‰VÀvÞîzWïf@8{&µrVÀ½ÆÜe@½µQÈBVÀ²¨S P”@HŸ@rý|{Àj¶¸¼ë’@ð#8ÆŸŠ{ÀÖu"—´Õq@ àØ*Œ…[À4Þ?İǀ@° ¼˜3ŠkÀÎbúÞÄzo@Ôk组[Àt^qm@ŒšIŒ[À€çÑt!ok@ ¤ÛÛr[Àò%ZJvy@È@€ô`kÀ¸„$ìÊ‹‡@|pCëêW{À¢C!]§…@¨\ã@Þ&{ÀÐ)²¦\@èï`ÕT@HO‡2Ãhy@zp/Ô«u@¨.dP{šv@*nòò–u@(ü±{Ÿ·c@ìP•%f@à“‹jºP@ï)¢±V@à(¢‹If[@°@o¦Š5g@ÐYõIe@¤ ùÌw@ â\ç\@®£à‡+Zx@ÀÙå,P.@Îéñê?çX@¬#SÁ;@KXD@ÐØå…w@o¼óäød@@†‹»¥d@0™š…U@hû|Ö¶Q@HÆíËF@𛧃ëS]@` §\žV@À=Tx%G@ ÝÌx!G@Мˆá¢P@tÙÈgåÀW@àjaKèC@Œ÷x§‚KX@€„¿z&@<ÌÚ%ZÎH@@ÒÝ6 @Àø*Àœqi@@?uÙz@ࢡ`Ú]@è•ö.À2g@˜¨”þóN@ØÁÍ£[d@¸Ø#+çO@ðoœ UlQ@xT kQ@@Ð B¹?¨\@€fRÇßP@pE%mµgF@ô¶`ÛFA@ þQÐO@Hl÷Cž±Q@ÐŽÝbR@ÐóM"b@€<|=þª1@ º$ð>Šb@€z¢ü3À¨ Ýç"êR@"ÍÊÆi@0¬™AMC@°S[N÷f@Üž¡ D@Xà º d@ïªn¶D@ÐBψÝq@hOœÕcU@ðð å>l@¨¶Û‘öU@ðm7šÃE@°D²Bn¥6@`7ÌÃmv^@TûÁºwW@» 0pï@@@~‡ÖG@²f€J)@`ºšCÅnX@€1s4Ö6À@õ DÚÌH@€š×ˆži@ÀÝLŠÝ±0@HPW#Äf@ÐŒùŒ¶1@ àˆ>*âs@0÷ÙQB@ð-—Ü`@@‰»ϲ3@ ôƒ,7£k@€eY1¤D@@å4×¹?e@ ¥ù¯g;E@@ãXí˜M@V6`§C6@€òÆP5Ë?@À‰ OKv6@äiÔžñ@àĉ ù G@@ võP9À  é©ê¡7@þ›¼Xzi@@m·+‘ÀaLòM›v@‚­‡òw"ÀP-z²l³S@z§ñ ÌÀÈ·üÔa¹`@ßH¿1¥ À@§P–?k@‰Ï1ijÀp`IÝT@ª ¼:ÂÀ úÜ `³\@’SîÞ³À€êgÈN@§‘iœÀDû@½«@ƒâôü?À@˜Æ¹ºEKÀ jìÊXÀãWßii@‡p†X+;À˜\^¹t}V@€—>‚!+ÀÀ~­Í•S@À”õÆAÝ*Àh²)ÉK`@`0ó•$;Àà-FSzðj@ Åé:5KÀÐÊ<ŽD@€itÜC+À SE¨† <@`py¯Ñy+ÀÀ×íg!ž<@@ð2´;À¸EÂXä?à"‘Í=<À\JfÑ<À`ëO.ä<Àg é€Y£@{ÊK)ÈŸš@RiË!Œˆ @ŽÃ„=â•@À(­÷ôª@¹©E©(”@ÑÛ·ü¨¨@Ü 9Ÿ@pŸq>hq¸@ûC¡|Í?¡@‰1§‘b¿Ôüþ¶$>z?FŒp¨Ó¿b¨Äæc­?MäæjNÇl?OË”“Ú‹? Hþv®©¿Mš½HÙ¦?°¶˜½;m¿‰2Îìu?јµ?°YÅþb?w'8ئl?.rVE‚?—¹N¬Ö¦¿.rVE¢?mrcal-2.4.1/test/data/test-optimizer-callback-ref-x-1.npy000066400000000000000000000150301456301662300231470ustar00rootroot00000000000000“NUMPYv{'descr': '‚ë½Ò3@XŸ¦WƒP@x)ÍùA0@Ð:B [DP@P üн)@˜&4Wl`@`È·±Õ2@PSOZP@ ÜJ:U@¹8K@ñO@ÀÑŽù @x锵Ér@Ø´ËXXq\@€¼;òRb@¨ÄùÕÑçH@X³áŸjQ@P½ vL[5@à0­ßäP@èS²¶Ò2@ ÈöZP@à®i³ñ-@°€™%¿ão@ÎÙžJa@𓚠¬R:@»<2’p@ÐÛõ\pC@PÔãÝ´O@àÈ>œ /@üð¨ÚŒ^@&¬èhK@°°*ýõx]@dín§Ð?PFÍëÄ•l@@ mïœ(À@…¨Ñ¢äK@úJvòèÀ@f“Ò AK@µX@I"À`,ôqÃZ@œÍ%‹8ÀÐOW£ÂÃq@ ì#nêC@ð£5åìP@ ôüR“ø@ø_ˆ`P@@,Xά @pœj~ÀÅ^@¬ýãÀÿã?€$fxÅ~m@Bè¹õV'À µ4ØUB\@@WÞZ[&Àá~YFK@`@-¶uÄ!Àû+ö&gJ@à›¸ ¡'À°PµÒ¿¦i@zü–ðÀMÀɨX#i@hÛ ™oáQÀXùíøza@¸Ý€Ñ @°’¼èQ†p@`@„Œi¸¿pØUæ—Xo@@?¢Ñh)À0åO¤ìÛm@à$ö8V\8ÀPËkll@ ƒu1üAÀð˜Ïq±&k@Ð1Â`†HÀ€MZ#wj@àvyó NÀpG^QK Y@°Ú¦Ò´BÀóvgš5H@Àß<´ì4À0=)êkxW@Ëœº±¸GÀ áz«*q@§ Á--À@hÃm±/P@`Y3GÀ 8EZ3“n@VŠÒæ¹CÀPê+Jâì\@@è´s·9ÀàÅOZØ][@°š#´[·?À 1¤ÅZ@Ð뱆VÑBÀ`'ÅšÚÂX@Øâ¼S]œEÀpAz ªg@˜â~ÞøsXÀÀã°®¼V@ø»5KKÀ`æ·ò“ÛE@“‹[}>À`¤jçp@I¾¸'9FÀ ç/òJÅ_@ÐØ§S!<À Za‹gÑm@HÁ¢@ˆQÀ •Û¢Ö\@ ÉuTÇÇCÀ°[&N9gJ@PÕ¡£sã6ÀÐRåaXâX@ðoÏ¢IÀ`•®AS~W@à‰ÔfzLÀ`ª…kí?f@ˆ‘ f*_À€Pþ-E@àÕ"®oö@Àà”¬c5D@Ä­»ÀôUBÀ¸åº¿ë `@Ðû‘e·BÀàs¿•üo@¸GôV«UÀ`u>´ôùL@pÛf(@x8ÀÈP"[@€q·š]KÀ@1p’*fY@(«Ðj NÀR îMÉG@ä¦[ŠŒS@À 8[RnPF@P8œ ÛÁAÀࢡ|ðD@ôæðÔCÀpìd´Ó¾c@xr)ðòndÀ°ÿOÚ+œb@ÝCK½eÀ,[5 \`@˜Ù³4¾JÀ`n‚%ã|N@0c¹%UY=À`“rQl@`©µ$`Àà)A9“cZ@Ô+%3wQÀp(ÐtmpX@|‚5ÔRÀPoω]±f@¬|B;0dÀp¹íp…e@¸æè¨reÀÐéÕŽ­›C@eרÜFÀ *"µP8B@€²÷8HÀiëÀìû`@Ð)è§]diÀ]EôO‘@Ä4ezRb@bÂŽ¡YÆp@¨¾¿Sw>I@5ö˜ŒJp@Ü äòP@¸K»YÕ›@Ü,Èlc@>÷š£²Ž@vkm_òÁv@VQç± Ü}@dJþkj@„^ÿúé}@ÆïFµVm@’-.ãÂO|@Wš"ã2Hp@¤]ûæ”{@µIàšßq@fnt2âæj@ úp°‘xc@î6´,Œl@@l/NÉ]@IÌ Ðo@XÍÔõÍE@¼¾6«\Ún@HZŽX.ŸL@.U€Fð@¨ n›³q@|KÙ<›@påÁŸ u@î}xg @Œ@Œ‘JŽŠWx@˜ ±Rtk@Ü8©ÞÖ©[@ÈHÑÇ ¼Š@ 5üš–â~@@d j@‰¤ì¢å a@°P[ì+`y@)5ºû£r@UœÚ¡o@SÙo-7@ÀVË#Ž@(,d¼?|b@ª*<‡3m@`ŽWR[I@üyKCgMŒ@,Wîååp@l¯ox‹@Ôò¥J…gs@Æò§ü®z@–_Þ¶f@ r€¾èi@t÷X§! Z@ìJÑ  3y@¢~¬ÅÔKm@Òcëh„ˆ@®RšÓ2@€@¦Ç7Æðáw@;/÷N£×q@Úæ¡©o@°ùÉ&aïP@άró£|Œ@€¯y¨%©^@((`Е{@p*ÿpl6V@B<&¶Š@ òÝ—ól@ܺC8èi@`Q{ÍQ@Ðè[HŠ ‰@¨6ñË*u@öötVbˆ@8•z?}sx@¼ ûg³g@JXJ¸.±[@¼ÆöJèw@P=Je`ðn@ô}Ì¡kf@éÐdna@:¼ã ‚Ï{@€×ó[8W5@(ì׿•âj@ jéKm8@ ge‘þy@x…(=@"S@úc0 %i@ˆÕýL3ÚI@r˜i~a]h@8¹Ã.OP@ÞÍrYšw@¨Ò•çv”c@Ä©bÁ!év@Äŵ¥Ïêf@¬~TD7v@È(­Cn2j@R«bgãe@´«íßc]@JZ˜fƒùd@!ždBL`@¤ØHcÀ.j@?‡mÇ@îOÆõJi@Pöàþp’2@U碞rˆ@ ¸ÿ©#-`@$6gsOw@ˆ»•óV@Òš~Ùv@ø%ö;¤]@KÒ À|à§‘<†r@‘<íj5@jUé[àÊq@Ÿù·žÍG@JІma@p¶•M®B@ ü Ês€@xËUd ]i@Æ"º¯o@’%iì_@°½€jQ~~@8ˆqÀf@s@ð,]æa]@ÿ°oV@@¥% ÏK\@‡ÑÕ߬Y@ÏYÊô‚@@0·œužb@’Wça^Ðn@øÆŸ¢ƒB@À)sz(}@ðGÊ!ÌÃR@´ r5…k@ȱœØ×B@,„Á.»æ‰@xZ–w/c@ð“²# Vx@°°.­PS@jJ·ßÈv@Ø©6ÀS@ÞöMWF;…@HVö¹(d@N…EÒµc@\f&ED@nÐ%Y¯8b@à),Jg3E@3ˆÝ6±@€!š¡WoW@I°5qco@@Û®zs7@î(ÿ$‚²@ )BôW@ Íõ¹l@Ð-™ zã7@h•Ý$F^z@p… ž!H@êÝïmDºˆ@P§×<"¹X@$j†´w@0­¸ìéDI@Dó° Še@ð¨TÿÙä9@¶÷ÈÌt@°;a¥ðÔJ@.tRÓvb@pÑÌ<@ÿ$8ƒlå@ —äeHB@~ù}âW€@@кÉà2@YÖN@n@ ܰ&"@Š8Â…l@à}e4•"@,:Q#xØj@€Üÿ«ø"@þçØö-i@@(P‰ì#@Z ñD5„g@ nÜã%@²ê¿lçe@ º¿h&@H<àJd@`/^‡#(@º$†²E»r@ ÆêÍ9@äªó£>@ä5ª•&ÀùM:§NW€@@šLÂ^l'À#’~üán@€’µÎÀNvŽ”3m@@U-·ÊÀ†°¹€ôX‹@@ƽÍÏ6ÀÂ¥‰@€) • ¹4ÀiúC‚òw@CxùY£"À: Á‘OF†@ÀˆäHÝ0Àµ '㣄@€@¿UÀ¢+À:r|¤c@€Ðä ª1À{Ï¡U¢@0\¥‹´0EÀ&*í§±@ðQ‰cFWUÀ®už¬ˆ@€MI04lUÀvÜ1±@@0¯½å`UÀ–@šžŸê{@Vò«*9EÀ2¡F0'Š@`+Œ/NùTÀ¶ Žhciˆ@ 4´ÒzTÀlƒÑÑr¸†@ ì(TÀÐXÊöe@43Ecy3ÀpÖà‡¶Zƒ@ðMâ›”RÀºÂ=T- ’@@Rqny²bÀ‡p2‹‘@¡ìN+½bÀ¾0ô߀@ÑÑÝRÀNÍ-[n@8fFéŒÅBÀ¿ÕŠ„|@°˜›•·RÀH‡¶Š@à¸b©bÀˆZµìˆ@€G‰‹ubÀ Ì;úF)‡@¨‘=@BbÀ¶Ó l…@xeƒj…õaÀ$ŽQ4»ƒ@àÇŽƒªaÀ*%}‚@H§Tz[Àþ]4tå{@€” ÒD@[À›Ú¬¢X€€@à8ÏTJ[À˜ ó¸C@øíõëöN[À6ψå.}@k'¼ÎG[Àê·ÝL‹@øH.Û¬kÀ5UY}‰@8‚ ûgkÀb–ÖÚ5«‡@¸ç)ÒÚÓjÀ&¾k¡Uç…@0Õ@jÀ.(ää|$„@Ü^ëFjÀ *Bìör@(î_ôñQÀ­¿>Kí‘@„Ó%iÿqÀ„sœÈ…ë@ÄîÑkrÀ°‹ê°Ø@ûÏá8bÀ¼ø±™ßm@€xNÒRÀ¦ãnòÂõ{@æ¦I³bÀRE̘Š@<Ò0UöqÀ^ÄÈ0@9ˆ@dˆk4}æqÀö7Âcfv@Ôú!xÉÄaÀB‹ºÊ°’t@}Ž•y™aÀ‡1¡cœx“@hY:IŸvÀ•ÜΡgr@ ™òþ¨VÀ]zB Zq@\w«Ék½VÀŲ¹¡Sp@È÷j ï¹VÀè[´»ò n@¤üXN²VÀª¿9® ©Œ@•L!ÁªvÀ<™ €·j@8‹û”VÀ¬õþÍ2Ôh@ؽU?‰‰VÀvÞîzWïf@8{&µrVÀ½ÆÜe@½µQÈBVÀ²¨S P”@HŸ@rý|{Àj¶¸¼ë’@ð#8ÆŸŠ{ÀÖu"—´Õq@ àØ*Œ…[À4Þ?İǀ@° ¼˜3ŠkÀÎbúÞÄzo@Ôk组[Àt^qm@ŒšIŒ[À€çÑt!ok@ ¤ÛÛr[Àò%ZJvy@È@€ô`kÀ¸„$ìÊ‹‡@|pCëêW{À¢C!]§…@¨\ã@Þ&{ÀÐ)²¦\@èï`ÕT@HO‡2Ãhy@zp/Ô«u@¨.dP{šv@*nòò–u@(ü±{Ÿ·c@ìP•%f@à“‹jºP@ï)¢±V@à(¢‹If[@°@o¦Š5g@ÐYõIe@¤ ùÌw@ â\ç\@®£à‡+Zx@ÀÙå,P.@Îéñê?çX@¬#SÁ;@KXD@ÐØå…w@o¼óäød@@†‹»¥d@0™š…U@hû|Ö¶Q@HÆíËF@𛧃ëS]@` §\žV@À=Tx%G@ ÝÌx!G@Мˆá¢P@tÙÈgåÀW@àjaKèC@Œ÷x§‚KX@€„¿z&@<ÌÚ%ZÎH@@ÒÝ6 @Àø*Àœqi@@?uÙz@ࢡ`Ú]@è•ö.À2g@˜¨”þóN@ØÁÍ£[d@¸Ø#+çO@ðoœ UlQ@xT kQ@@Ð B¹?¨\@€fRÇßP@pE%mµgF@ô¶`ÛFA@ þQÐO@Hl÷Cž±Q@ÐŽÝbR@ÐóM"b@€<|=þª1@ º$ð>Šb@€z¢ü3À¨ Ýç"êR@"ÍÊÆi@0¬™AMC@°S[N÷f@Üž¡ D@Xà º d@ïªn¶D@ÐBψÝq@hOœÕcU@ðð å>l@¨¶Û‘öU@ðm7šÃE@°D²Bn¥6@`7ÌÃmv^@TûÁºwW@» 0pï@@@~‡ÖG@²f€J)@`ºšCÅnX@€1s4Ö6À@õ DÚÌH@€š×ˆži@ÀÝLŠÝ±0@HPW#Äf@ÐŒùŒ¶1@ àˆ>*âs@0÷ÙQB@ð-—Ü`@@‰»ϲ3@ ôƒ,7£k@€eY1¤D@@å4×¹?e@ ¥ù¯g;E@@ãXí˜M@V6`§C6@€òÆP5Ë?@À‰ OKv6@äiÔžñ@àĉ ù G@@ võP9À  é©ê¡7@þ›¼Xzi@@m·+‘ÀaLòM›v@‚­‡òw"ÀP-z²l³S@z§ñ ÌÀÈ·üÔa¹`@ßH¿1¥ À@§P–?k@‰Ï1ijÀp`IÝT@ª ¼:ÂÀ úÜ `³\@’SîÞ³À€êgÈN@§‘iœÀDû@½«@ƒâôü?À@˜Æ¹ºEKÀ jìÊXÀãWßii@‡p†X+;À˜\^¹t}V@€—>‚!+ÀÀ~­Í•S@À”õÆAÝ*Àh²)ÉK`@`0ó•$;Àà-FSzðj@ Åé:5KÀÐÊ<ŽD@€itÜC+À SE¨† <@`py¯Ñy+ÀÀ×íg!ž<@@ð2´;À¸EÂXä?à"‘Í=<À\JfÑ<À`ëO.ä<Àg é€Y£@{ÊK)ÈŸš@RiË!Œˆ @ŽÃ„=â•@À(­÷ôª@¹©E©(”@ÑÛ·ü¨¨@Ü 9Ÿ@pŸq>hq¸@ûC¡|Í?¡@/ug°s²¨¿,³<õ5ƒ‘¿²ÄPí¹6©¿.rVE’¿mrcal-2.4.1/test/data/test-optimizer-callback-ref-x-2.npy000066400000000000000000000147701456301662300231620ustar00rootroot00000000000000“NUMPYv{'descr': '‚ë½Ò3@XŸ¦WƒP@x)ÍùA0@Ð:B [DP@P üн)@˜&4Wl`@`È·±Õ2@PSOZP@ ÜJ:U@¹8K@ñO@ÀÑŽù @x锵Ér@Ø´ËXXq\@€¼;òRb@¨ÄùÕÑçH@X³áŸjQ@P½ vL[5@à0­ßäP@èS²¶Ò2@ ÈöZP@à®i³ñ-@°€™%¿ão@ÎÙžJa@𓚠¬R:@»<2’p@ÐÛõ\pC@PÔãÝ´O@àÈ>œ /@üð¨ÚŒ^@&¬èhK@°°*ýõx]@dín§Ð?PFÍëÄ•l@@ mïœ(À@…¨Ñ¢äK@úJvòèÀ@f“Ò AK@µX@I"À`,ôqÃZ@œÍ%‹8ÀÐOW£ÂÃq@ ì#nêC@ð£5åìP@ ôüR“ø@ø_ˆ`P@@,Xά @pœj~ÀÅ^@¬ýãÀÿã?€$fxÅ~m@Bè¹õV'À µ4ØUB\@@WÞZ[&Àá~YFK@`@-¶uÄ!Àû+ö&gJ@à›¸ ¡'À°PµÒ¿¦i@zü–ðÀMÀɨX#i@hÛ ™oáQÀXùíøza@¸Ý€Ñ @°’¼èQ†p@`@„Œi¸¿pØUæ—Xo@@?¢Ñh)À0åO¤ìÛm@à$ö8V\8ÀPËkll@ ƒu1üAÀð˜Ïq±&k@Ð1Â`†HÀ€MZ#wj@àvyó NÀpG^QK Y@°Ú¦Ò´BÀóvgš5H@Àß<´ì4À0=)êkxW@Ëœº±¸GÀ áz«*q@§ Á--À@hÃm±/P@`Y3GÀ 8EZ3“n@VŠÒæ¹CÀPê+Jâì\@@è´s·9ÀàÅOZØ][@°š#´[·?À 1¤ÅZ@Ð뱆VÑBÀ`'ÅšÚÂX@Øâ¼S]œEÀpAz ªg@˜â~ÞøsXÀÀã°®¼V@ø»5KKÀ`æ·ò“ÛE@“‹[}>À`¤jçp@I¾¸'9FÀ ç/òJÅ_@ÐØ§S!<À Za‹gÑm@HÁ¢@ˆQÀ •Û¢Ö\@ ÉuTÇÇCÀ°[&N9gJ@PÕ¡£sã6ÀÐRåaXâX@ðoÏ¢IÀ`•®AS~W@à‰ÔfzLÀ`ª…kí?f@ˆ‘ f*_À€Pþ-E@àÕ"®oö@Àà”¬c5D@Ä­»ÀôUBÀ¸åº¿ë `@Ðû‘e·BÀàs¿•üo@¸GôV«UÀ`u>´ôùL@pÛf(@x8ÀÈP"[@€q·š]KÀ@1p’*fY@(«Ðj NÀR îMÉG@ä¦[ŠŒS@À 8[RnPF@P8œ ÛÁAÀࢡ|ðD@ôæðÔCÀpìd´Ó¾c@xr)ðòndÀ°ÿOÚ+œb@ÝCK½eÀ,[5 \`@˜Ù³4¾JÀ`n‚%ã|N@0c¹%UY=À`“rQl@`©µ$`Àà)A9“cZ@Ô+%3wQÀp(ÐtmpX@|‚5ÔRÀPoω]±f@¬|B;0dÀp¹íp…e@¸æè¨reÀÐéÕŽ­›C@eרÜFÀ *"µP8B@€²÷8HÀiëÀìû`@Ð)è§]diÀ]EôO‘@Ä4ezRb@bÂŽ¡YÆp@¨¾¿Sw>I@5ö˜ŒJp@Ü äòP@¸K»YÕ›@Ü,Èlc@>÷š£²Ž@vkm_òÁv@VQç± Ü}@dJþkj@„^ÿúé}@ÆïFµVm@’-.ãÂO|@Wš"ã2Hp@¤]ûæ”{@µIàšßq@fnt2âæj@ úp°‘xc@î6´,Œl@@l/NÉ]@IÌ Ðo@XÍÔõÍE@¼¾6«\Ún@HZŽX.ŸL@.U€Fð@¨ n›³q@|KÙ<›@påÁŸ u@î}xg @Œ@Œ‘JŽŠWx@˜ ±Rtk@Ü8©ÞÖ©[@ÈHÑÇ ¼Š@ 5üš–â~@@d j@‰¤ì¢å a@°P[ì+`y@)5ºû£r@UœÚ¡o@SÙo-7@ÀVË#Ž@(,d¼?|b@ª*<‡3m@`ŽWR[I@üyKCgMŒ@,Wîååp@l¯ox‹@Ôò¥J…gs@Æò§ü®z@–_Þ¶f@ r€¾èi@t÷X§! Z@ìJÑ  3y@¢~¬ÅÔKm@Òcëh„ˆ@®RšÓ2@€@¦Ç7Æðáw@;/÷N£×q@Úæ¡©o@°ùÉ&aïP@άró£|Œ@€¯y¨%©^@((`Е{@p*ÿpl6V@B<&¶Š@ òÝ—ól@ܺC8èi@`Q{ÍQ@Ðè[HŠ ‰@¨6ñË*u@öötVbˆ@8•z?}sx@¼ ûg³g@JXJ¸.±[@¼ÆöJèw@P=Je`ðn@ô}Ì¡kf@éÐdna@:¼ã ‚Ï{@€×ó[8W5@(ì׿•âj@ jéKm8@ ge‘þy@x…(=@"S@úc0 %i@ˆÕýL3ÚI@r˜i~a]h@8¹Ã.OP@ÞÍrYšw@¨Ò•çv”c@Ä©bÁ!év@Äŵ¥Ïêf@¬~TD7v@È(­Cn2j@R«bgãe@´«íßc]@JZ˜fƒùd@!ždBL`@¤ØHcÀ.j@?‡mÇ@îOÆõJi@Pöàþp’2@U碞rˆ@ ¸ÿ©#-`@$6gsOw@ˆ»•óV@Òš~Ùv@ø%ö;¤]@KÒ À|à§‘<†r@‘<íj5@jUé[àÊq@Ÿù·žÍG@JІma@p¶•M®B@ ü Ês€@xËUd ]i@Æ"º¯o@’%iì_@°½€jQ~~@8ˆqÀf@s@ð,]æa]@ÿ°oV@@¥% ÏK\@‡ÑÕ߬Y@ÏYÊô‚@@0·œužb@’Wça^Ðn@øÆŸ¢ƒB@À)sz(}@ðGÊ!ÌÃR@´ r5…k@ȱœØ×B@,„Á.»æ‰@xZ–w/c@ð“²# Vx@°°.­PS@jJ·ßÈv@Ø©6ÀS@ÞöMWF;…@HVö¹(d@N…EÒµc@\f&ED@nÐ%Y¯8b@à),Jg3E@3ˆÝ6±@€!š¡WoW@I°5qco@@Û®zs7@î(ÿ$‚²@ )BôW@ Íõ¹l@Ð-™ zã7@h•Ý$F^z@p… ž!H@êÝïmDºˆ@P§×<"¹X@$j†´w@0­¸ìéDI@Dó° Še@ð¨TÿÙä9@¶÷ÈÌt@°;a¥ðÔJ@.tRÓvb@pÑÌ<@ÿ$8ƒlå@ —äeHB@~ù}âW€@@кÉà2@YÖN@n@ ܰ&"@Š8Â…l@à}e4•"@,:Q#xØj@€Üÿ«ø"@þçØö-i@@(P‰ì#@Z ñD5„g@ nÜã%@²ê¿lçe@ º¿h&@H<àJd@`/^‡#(@º$†²E»r@ ÆêÍ9@äªó£>@ä5ª•&ÀùM:§NW€@@šLÂ^l'À#’~üán@€’µÎÀNvŽ”3m@@U-·ÊÀ†°¹€ôX‹@@ƽÍÏ6ÀÂ¥‰@€) • ¹4ÀiúC‚òw@CxùY£"À: Á‘OF†@ÀˆäHÝ0Àµ '㣄@€@¿UÀ¢+À:r|¤c@€Ðä ª1À{Ï¡U¢@0\¥‹´0EÀ&*í§±@ðQ‰cFWUÀ®už¬ˆ@€MI04lUÀvÜ1±@@0¯½å`UÀ–@šžŸê{@Vò«*9EÀ2¡F0'Š@`+Œ/NùTÀ¶ Žhciˆ@ 4´ÒzTÀlƒÑÑr¸†@ ì(TÀÐXÊöe@43Ecy3ÀpÖà‡¶Zƒ@ðMâ›”RÀºÂ=T- ’@@Rqny²bÀ‡p2‹‘@¡ìN+½bÀ¾0ô߀@ÑÑÝRÀNÍ-[n@8fFéŒÅBÀ¿ÕŠ„|@°˜›•·RÀH‡¶Š@à¸b©bÀˆZµìˆ@€G‰‹ubÀ Ì;úF)‡@¨‘=@BbÀ¶Ó l…@xeƒj…õaÀ$ŽQ4»ƒ@àÇŽƒªaÀ*%}‚@H§Tz[Àþ]4tå{@€” ÒD@[À›Ú¬¢X€€@à8ÏTJ[À˜ ó¸C@øíõëöN[À6ψå.}@k'¼ÎG[Àê·ÝL‹@øH.Û¬kÀ5UY}‰@8‚ ûgkÀb–ÖÚ5«‡@¸ç)ÒÚÓjÀ&¾k¡Uç…@0Õ@jÀ.(ää|$„@Ü^ëFjÀ *Bìör@(î_ôñQÀ­¿>Kí‘@„Ó%iÿqÀ„sœÈ…ë@ÄîÑkrÀ°‹ê°Ø@ûÏá8bÀ¼ø±™ßm@€xNÒRÀ¦ãnòÂõ{@æ¦I³bÀRE̘Š@<Ò0UöqÀ^ÄÈ0@9ˆ@dˆk4}æqÀö7Âcfv@Ôú!xÉÄaÀB‹ºÊ°’t@}Ž•y™aÀ‡1¡cœx“@hY:IŸvÀ•ÜΡgr@ ™òþ¨VÀ]zB Zq@\w«Ék½VÀŲ¹¡Sp@È÷j ï¹VÀè[´»ò n@¤üXN²VÀª¿9® ©Œ@•L!ÁªvÀ<™ €·j@8‹û”VÀ¬õþÍ2Ôh@ؽU?‰‰VÀvÞîzWïf@8{&µrVÀ½ÆÜe@½µQÈBVÀ²¨S P”@HŸ@rý|{Àj¶¸¼ë’@ð#8ÆŸŠ{ÀÖu"—´Õq@ àØ*Œ…[À4Þ?İǀ@° ¼˜3ŠkÀÎbúÞÄzo@Ôk组[Àt^qm@ŒšIŒ[À€çÑt!ok@ ¤ÛÛr[Àò%ZJvy@È@€ô`kÀ¸„$ìÊ‹‡@|pCëêW{À¢C!]§…@¨\ã@Þ&{ÀÐ)²¦\@èï`ÕT@HO‡2Ãhy@zp/Ô«u@¨.dP{šv@*nòò–u@(ü±{Ÿ·c@ìP•%f@à“‹jºP@ï)¢±V@à(¢‹If[@°@o¦Š5g@ÐYõIe@¤ ùÌw@ â\ç\@®£à‡+Zx@ÀÙå,P.@Îéñê?çX@¬#SÁ;@KXD@ÐØå…w@o¼óäød@@†‹»¥d@0™š…U@hû|Ö¶Q@HÆíËF@𛧃ëS]@` §\žV@À=Tx%G@ ÝÌx!G@Мˆá¢P@tÙÈgåÀW@àjaKèC@Œ÷x§‚KX@€„¿z&@<ÌÚ%ZÎH@@ÒÝ6 @Àø*Àœqi@@?uÙz@ࢡ`Ú]@è•ö.À2g@˜¨”þóN@ØÁÍ£[d@¸Ø#+çO@ðoœ UlQ@xT kQ@@Ð B¹?¨\@€fRÇßP@pE%mµgF@ô¶`ÛFA@ þQÐO@Hl÷Cž±Q@ÐŽÝbR@ÐóM"b@€<|=þª1@ º$ð>Šb@€z¢ü3À¨ Ýç"êR@"ÍÊÆi@0¬™AMC@°S[N÷f@Üž¡ D@Xà º d@ïªn¶D@ÐBψÝq@hOœÕcU@ðð å>l@¨¶Û‘öU@ðm7šÃE@°D²Bn¥6@`7ÌÃmv^@TûÁºwW@» 0pï@@@~‡ÖG@²f€J)@`ºšCÅnX@€1s4Ö6À@õ DÚÌH@€š×ˆži@ÀÝLŠÝ±0@HPW#Äf@ÐŒùŒ¶1@ àˆ>*âs@0÷ÙQB@ð-—Ü`@@‰»ϲ3@ ôƒ,7£k@€eY1¤D@@å4×¹?e@ ¥ù¯g;E@@ãXí˜M@V6`§C6@€òÆP5Ë?@À‰ OKv6@äiÔžñ@àĉ ù G@@ võP9À  é©ê¡7@þ›¼Xzi@@m·+‘ÀaLòM›v@‚­‡òw"ÀP-z²l³S@z§ñ ÌÀÈ·üÔa¹`@ßH¿1¥ À@§P–?k@‰Ï1ijÀp`IÝT@ª ¼:ÂÀ úÜ `³\@’SîÞ³À€êgÈN@§‘iœÀDû@½«@ƒâôü?À@˜Æ¹ºEKÀ jìÊXÀãWßii@‡p†X+;À˜\^¹t}V@€—>‚!+ÀÀ~­Í•S@À”õÆAÝ*Àh²)ÉK`@`0ó•$;Àà-FSzðj@ Åé:5KÀÐÊ<ŽD@€itÜC+À SE¨† <@`py¯Ñy+ÀÀ×íg!ž<@@ð2´;À¸EÂXä?à"‘Í=<À\JfÑ<À`ëO.ä<Àg é€Y£@{ÊK)ÈŸš@RiË!Œˆ @ŽÃ„=â•@À(­÷ôª@¹©E©(”@ÑÛ·ü¨¨@Ü 9Ÿ@pŸq>hq¸@ûC¡|Í?¡@mrcal-2.4.1/test/data/test-optimizer-callback-ref-x-3.npy000066400000000000000000000152301456301662300231530ustar00rootroot00000000000000“NUMPYv{'descr': '‚ë½Ò3@XŸ¦WƒP@x)ÍùA0@Ð:B [DP@P üн)@˜&4Wl`@`È·±Õ2@PSOZP@ ÜJ:U@¹8K@ñO@ÀÑŽù @x锵Ér@Ø´ËXXq\@€¼;òRb@¨ÄùÕÑçH@X³áŸjQ@P½ vL[5@à0­ßäP@èS²¶Ò2@ ÈöZP@à®i³ñ-@°€™%¿ão@ÎÙžJa@𓚠¬R:@»<2’p@ÐÛõ\pC@PÔãÝ´O@àÈ>œ /@üð¨ÚŒ^@&¬èhK@°°*ýõx]@dín§Ð?PFÍëÄ•l@@ mïœ(À@…¨Ñ¢äK@úJvòèÀ@f“Ò AK@µX@I"À`,ôqÃZ@œÍ%‹8ÀÐOW£ÂÃq@ ì#nêC@ð£5åìP@ ôüR“ø@ø_ˆ`P@@,Xά @pœj~ÀÅ^@¬ýãÀÿã?€$fxÅ~m@Bè¹õV'À µ4ØUB\@@WÞZ[&Àá~YFK@`@-¶uÄ!Àû+ö&gJ@à›¸ ¡'À°PµÒ¿¦i@zü–ðÀMÀɨX#i@hÛ ™oáQÀXùíøza@¸Ý€Ñ @°’¼èQ†p@`@„Œi¸¿pØUæ—Xo@@?¢Ñh)À0åO¤ìÛm@à$ö8V\8ÀPËkll@ ƒu1üAÀð˜Ïq±&k@Ð1Â`†HÀ€MZ#wj@àvyó NÀpG^QK Y@°Ú¦Ò´BÀóvgš5H@Àß<´ì4À0=)êkxW@Ëœº±¸GÀ áz«*q@§ Á--À@hÃm±/P@`Y3GÀ 8EZ3“n@VŠÒæ¹CÀPê+Jâì\@@è´s·9ÀàÅOZØ][@°š#´[·?À 1¤ÅZ@Ð뱆VÑBÀ`'ÅšÚÂX@Øâ¼S]œEÀpAz ªg@˜â~ÞøsXÀÀã°®¼V@ø»5KKÀ`æ·ò“ÛE@“‹[}>À`¤jçp@I¾¸'9FÀ ç/òJÅ_@ÐØ§S!<À Za‹gÑm@HÁ¢@ˆQÀ •Û¢Ö\@ ÉuTÇÇCÀ°[&N9gJ@PÕ¡£sã6ÀÐRåaXâX@ðoÏ¢IÀ`•®AS~W@à‰ÔfzLÀ`ª…kí?f@ˆ‘ f*_À€Pþ-E@àÕ"®oö@Àà”¬c5D@Ä­»ÀôUBÀ¸åº¿ë `@Ðû‘e·BÀàs¿•üo@¸GôV«UÀ`u>´ôùL@pÛf(@x8ÀÈP"[@€q·š]KÀ@1p’*fY@(«Ðj NÀR îMÉG@ä¦[ŠŒS@À 8[RnPF@P8œ ÛÁAÀࢡ|ðD@ôæðÔCÀpìd´Ó¾c@xr)ðòndÀ°ÿOÚ+œb@ÝCK½eÀ,[5 \`@˜Ù³4¾JÀ`n‚%ã|N@0c¹%UY=À`“rQl@`©µ$`Àà)A9“cZ@Ô+%3wQÀp(ÐtmpX@|‚5ÔRÀPoω]±f@¬|B;0dÀp¹íp…e@¸æè¨reÀÐéÕŽ­›C@eרÜFÀ *"µP8B@€²÷8HÀiëÀìû`@Ð)è§]diÀ]EôO‘@Ä4ezRb@bÂŽ¡YÆp@¨¾¿Sw>I@5ö˜ŒJp@Ü äòP@¸K»YÕ›@Ü,Èlc@>÷š£²Ž@vkm_òÁv@VQç± Ü}@dJþkj@„^ÿúé}@ÆïFµVm@’-.ãÂO|@Wš"ã2Hp@¤]ûæ”{@µIàšßq@fnt2âæj@ úp°‘xc@î6´,Œl@@l/NÉ]@IÌ Ðo@XÍÔõÍE@¼¾6«\Ún@HZŽX.ŸL@.U€Fð@¨ n›³q@|KÙ<›@påÁŸ u@î}xg @Œ@Œ‘JŽŠWx@˜ ±Rtk@Ü8©ÞÖ©[@ÈHÑÇ ¼Š@ 5üš–â~@@d j@‰¤ì¢å a@°P[ì+`y@)5ºû£r@UœÚ¡o@SÙo-7@ÀVË#Ž@(,d¼?|b@ª*<‡3m@`ŽWR[I@üyKCgMŒ@,Wîååp@l¯ox‹@Ôò¥J…gs@Æò§ü®z@–_Þ¶f@ r€¾èi@t÷X§! Z@ìJÑ  3y@¢~¬ÅÔKm@Òcëh„ˆ@®RšÓ2@€@¦Ç7Æðáw@;/÷N£×q@Úæ¡©o@°ùÉ&aïP@άró£|Œ@€¯y¨%©^@((`Е{@p*ÿpl6V@B<&¶Š@ òÝ—ól@ܺC8èi@`Q{ÍQ@Ðè[HŠ ‰@¨6ñË*u@öötVbˆ@8•z?}sx@¼ ûg³g@JXJ¸.±[@¼ÆöJèw@P=Je`ðn@ô}Ì¡kf@éÐdna@:¼ã ‚Ï{@€×ó[8W5@(ì׿•âj@ jéKm8@ ge‘þy@x…(=@"S@úc0 %i@ˆÕýL3ÚI@r˜i~a]h@8¹Ã.OP@ÞÍrYšw@¨Ò•çv”c@Ä©bÁ!év@Äŵ¥Ïêf@¬~TD7v@È(­Cn2j@R«bgãe@´«íßc]@JZ˜fƒùd@!ždBL`@¤ØHcÀ.j@?‡mÇ@îOÆõJi@Pöàþp’2@U碞rˆ@ ¸ÿ©#-`@$6gsOw@ˆ»•óV@Òš~Ùv@ø%ö;¤]@KÒ À|à§‘<†r@‘<íj5@jUé[àÊq@Ÿù·žÍG@JІma@p¶•M®B@ ü Ês€@xËUd ]i@Æ"º¯o@’%iì_@°½€jQ~~@8ˆqÀf@s@ð,]æa]@ÿ°oV@@¥% ÏK\@‡ÑÕ߬Y@ÏYÊô‚@@0·œužb@’Wça^Ðn@øÆŸ¢ƒB@À)sz(}@ðGÊ!ÌÃR@´ r5…k@ȱœØ×B@,„Á.»æ‰@xZ–w/c@ð“²# Vx@°°.­PS@jJ·ßÈv@Ø©6ÀS@ÞöMWF;…@HVö¹(d@N…EÒµc@\f&ED@nÐ%Y¯8b@à),Jg3E@3ˆÝ6±@€!š¡WoW@I°5qco@@Û®zs7@î(ÿ$‚²@ )BôW@ Íõ¹l@Ð-™ zã7@h•Ý$F^z@p… ž!H@êÝïmDºˆ@P§×<"¹X@$j†´w@0­¸ìéDI@Dó° Še@ð¨TÿÙä9@¶÷ÈÌt@°;a¥ðÔJ@.tRÓvb@pÑÌ<@ÿ$8ƒlå@ —äeHB@~ù}âW€@@кÉà2@YÖN@n@ ܰ&"@Š8Â…l@à}e4•"@,:Q#xØj@€Üÿ«ø"@þçØö-i@@(P‰ì#@Z ñD5„g@ nÜã%@²ê¿lçe@ º¿h&@H<àJd@`/^‡#(@º$†²E»r@ ÆêÍ9@äªó£>@ä5ª•&ÀùM:§NW€@@šLÂ^l'À#’~üán@€’µÎÀNvŽ”3m@@U-·ÊÀ†°¹€ôX‹@@ƽÍÏ6ÀÂ¥‰@€) • ¹4ÀiúC‚òw@CxùY£"À: Á‘OF†@ÀˆäHÝ0Àµ '㣄@€@¿UÀ¢+À:r|¤c@€Ðä ª1À{Ï¡U¢@0\¥‹´0EÀ&*í§±@ðQ‰cFWUÀ®už¬ˆ@€MI04lUÀvÜ1±@@0¯½å`UÀ–@šžŸê{@Vò«*9EÀ2¡F0'Š@`+Œ/NùTÀ¶ Žhciˆ@ 4´ÒzTÀlƒÑÑr¸†@ ì(TÀÐXÊöe@43Ecy3ÀpÖà‡¶Zƒ@ðMâ›”RÀºÂ=T- ’@@Rqny²bÀ‡p2‹‘@¡ìN+½bÀ¾0ô߀@ÑÑÝRÀNÍ-[n@8fFéŒÅBÀ¿ÕŠ„|@°˜›•·RÀH‡¶Š@à¸b©bÀˆZµìˆ@€G‰‹ubÀ Ì;úF)‡@¨‘=@BbÀ¶Ó l…@xeƒj…õaÀ$ŽQ4»ƒ@àÇŽƒªaÀ*%}‚@H§Tz[Àþ]4tå{@€” ÒD@[À›Ú¬¢X€€@à8ÏTJ[À˜ ó¸C@øíõëöN[À6ψå.}@k'¼ÎG[Àê·ÝL‹@øH.Û¬kÀ5UY}‰@8‚ ûgkÀb–ÖÚ5«‡@¸ç)ÒÚÓjÀ&¾k¡Uç…@0Õ@jÀ.(ää|$„@Ü^ëFjÀ *Bìör@(î_ôñQÀ­¿>Kí‘@„Ó%iÿqÀ„sœÈ…ë@ÄîÑkrÀ°‹ê°Ø@ûÏá8bÀ¼ø±™ßm@€xNÒRÀ¦ãnòÂõ{@æ¦I³bÀRE̘Š@<Ò0UöqÀ^ÄÈ0@9ˆ@dˆk4}æqÀö7Âcfv@Ôú!xÉÄaÀB‹ºÊ°’t@}Ž•y™aÀ‡1¡cœx“@hY:IŸvÀ•ÜΡgr@ ™òþ¨VÀ]zB Zq@\w«Ék½VÀŲ¹¡Sp@È÷j ï¹VÀè[´»ò n@¤üXN²VÀª¿9® ©Œ@•L!ÁªvÀ<™ €·j@8‹û”VÀ¬õþÍ2Ôh@ؽU?‰‰VÀvÞîzWïf@8{&µrVÀ½ÆÜe@½µQÈBVÀ²¨S P”@HŸ@rý|{Àj¶¸¼ë’@ð#8ÆŸŠ{ÀÖu"—´Õq@ àØ*Œ…[À4Þ?İǀ@° ¼˜3ŠkÀÎbúÞÄzo@Ôk组[Àt^qm@ŒšIŒ[À€çÑt!ok@ ¤ÛÛr[Àò%ZJvy@È@€ô`kÀ¸„$ìÊ‹‡@|pCëêW{À¢C!]§…@¨\ã@Þ&{ÀÐ)²¦\@èï`ÕT@HO‡2Ãhy@zp/Ô«u@¨.dP{šv@*nòò–u@(ü±{Ÿ·c@ìP•%f@à“‹jºP@ï)¢±V@à(¢‹If[@°@o¦Š5g@ÐYõIe@¤ ùÌw@ â\ç\@®£à‡+Zx@ÀÙå,P.@Îéñê?çX@¬#SÁ;@KXD@ÐØå…w@o¼óäød@@†‹»¥d@0™š…U@hû|Ö¶Q@HÆíËF@𛧃ëS]@` §\žV@À=Tx%G@ ÝÌx!G@Мˆá¢P@tÙÈgåÀW@àjaKèC@Œ÷x§‚KX@€„¿z&@<ÌÚ%ZÎH@@ÒÝ6 @Àø*Àœqi@@?uÙz@ࢡ`Ú]@è•ö.À2g@˜¨”þóN@ØÁÍ£[d@¸Ø#+çO@ðoœ UlQ@xT kQ@@Ð B¹?¨\@€fRÇßP@pE%mµgF@ô¶`ÛFA@ þQÐO@Hl÷Cž±Q@ÐŽÝbR@ÐóM"b@€<|=þª1@ º$ð>Šb@€z¢ü3À¨ Ýç"êR@"ÍÊÆi@0¬™AMC@°S[N÷f@Üž¡ D@Xà º d@ïªn¶D@ÐBψÝq@hOœÕcU@ðð å>l@¨¶Û‘öU@ðm7šÃE@°D²Bn¥6@`7ÌÃmv^@TûÁºwW@» 0pï@@@~‡ÖG@²f€J)@`ºšCÅnX@€1s4Ö6À@õ DÚÌH@€š×ˆži@ÀÝLŠÝ±0@HPW#Äf@ÐŒùŒ¶1@ àˆ>*âs@0÷ÙQB@ð-—Ü`@@‰»ϲ3@ ôƒ,7£k@€eY1¤D@@å4×¹?e@ ¥ù¯g;E@@ãXí˜M@V6`§C6@€òÆP5Ë?@À‰ OKv6@äiÔžñ@àĉ ù G@@ võP9À  é©ê¡7@þ›¼Xzi@@m·+‘ÀaLòM›v@‚­‡òw"ÀP-z²l³S@z§ñ ÌÀÈ·üÔa¹`@ßH¿1¥ À@§P–?k@‰Ï1ijÀp`IÝT@ª ¼:ÂÀ úÜ `³\@’SîÞ³À€êgÈN@§‘iœÀDû@½«@ƒâôü?À@˜Æ¹ºEKÀ jìÊXÀãWßii@‡p†X+;À˜\^¹t}V@€—>‚!+ÀÀ~­Í•S@À”õÆAÝ*Àh²)ÉK`@`0ó•$;Àà-FSzðj@ Åé:5KÀÐÊ<ŽD@€itÜC+À SE¨† <@`py¯Ñy+ÀÀ×íg!ž<@@ð2´;À¸EÂXä?à"‘Í=<À\JfÑ<À`ëO.ä<Àg é€Y£@{ÊK)ÈŸš@RiË!Œˆ @ŽÃ„=â•@À(­÷ôª@¹©E©(”@ÑÛ·ü¨¨@Ü 9Ÿ@pŸq>hq¸@ûC¡|Í?¡@‰1§‘b¿Ôüþ¶$>z?FŒp¨Ó¿b¨Äæc­?MäæjNÇl?OË”“Ú‹? Hþv®©¿Mš½HÙ¦?°¶˜½;m¿‰2Îìu?јµ?°YÅþb?w'8ئl?.rVE‚?—¹N¬Ö¦¿.rVE¢?/ug°s²¨¿,³<õ5ƒ‘¿²ÄPí¹6©¿.rVE’¿mrcal-2.4.1/test/data/test-optimizer-callback-ref-x-4.npy000066400000000000000000000147701456301662300231640ustar00rootroot00000000000000“NUMPYv{'descr': '‚ë½Ò3@XŸ¦WƒP@x)ÍùA0@Ð:B [DP@P üн)@˜&4Wl`@`È·±Õ2@PSOZP@ ÜJ:U@¹8K@ñO@ÀÑŽù @x锵Ér@Ø´ËXXq\@€¼;òRb@¨ÄùÕÑçH@X³áŸjQ@P½ vL[5@à0­ßäP@èS²¶Ò2@ ÈöZP@à®i³ñ-@°€™%¿ão@ÎÙžJa@𓚠¬R:@»<2’p@ÐÛõ\pC@PÔãÝ´O@àÈ>œ /@üð¨ÚŒ^@&¬èhK@°°*ýõx]@dín§Ð?PFÍëÄ•l@@ mïœ(À@…¨Ñ¢äK@úJvòèÀ@f“Ò AK@µX@I"À`,ôqÃZ@œÍ%‹8ÀÐOW£ÂÃq@ ì#nêC@ð£5åìP@ ôüR“ø@ø_ˆ`P@@,Xά @pœj~ÀÅ^@¬ýãÀÿã?€$fxÅ~m@Bè¹õV'À µ4ØUB\@@WÞZ[&Àá~YFK@`@-¶uÄ!Àû+ö&gJ@à›¸ ¡'À°PµÒ¿¦i@zü–ðÀMÀɨX#i@hÛ ™oáQÀXùíøza@¸Ý€Ñ @°’¼èQ†p@`@„Œi¸¿pØUæ—Xo@@?¢Ñh)À0åO¤ìÛm@à$ö8V\8ÀPËkll@ ƒu1üAÀð˜Ïq±&k@Ð1Â`†HÀ€MZ#wj@àvyó NÀpG^QK Y@°Ú¦Ò´BÀóvgš5H@Àß<´ì4À0=)êkxW@Ëœº±¸GÀ áz«*q@§ Á--À@hÃm±/P@`Y3GÀ 8EZ3“n@VŠÒæ¹CÀPê+Jâì\@@è´s·9ÀàÅOZØ][@°š#´[·?À 1¤ÅZ@Ð뱆VÑBÀ`'ÅšÚÂX@Øâ¼S]œEÀpAz ªg@˜â~ÞøsXÀÀã°®¼V@ø»5KKÀ`æ·ò“ÛE@“‹[}>À`¤jçp@I¾¸'9FÀ ç/òJÅ_@ÐØ§S!<À Za‹gÑm@HÁ¢@ˆQÀ •Û¢Ö\@ ÉuTÇÇCÀ°[&N9gJ@PÕ¡£sã6ÀÐRåaXâX@ðoÏ¢IÀ`•®AS~W@à‰ÔfzLÀ`ª…kí?f@ˆ‘ f*_À€Pþ-E@àÕ"®oö@Àà”¬c5D@Ä­»ÀôUBÀ¸åº¿ë `@Ðû‘e·BÀàs¿•üo@¸GôV«UÀ`u>´ôùL@pÛf(@x8ÀÈP"[@€q·š]KÀ@1p’*fY@(«Ðj NÀR îMÉG@ä¦[ŠŒS@À 8[RnPF@P8œ ÛÁAÀࢡ|ðD@ôæðÔCÀpìd´Ó¾c@xr)ðòndÀ°ÿOÚ+œb@ÝCK½eÀ,[5 \`@˜Ù³4¾JÀ`n‚%ã|N@0c¹%UY=À`“rQl@`©µ$`Àà)A9“cZ@Ô+%3wQÀp(ÐtmpX@|‚5ÔRÀPoω]±f@¬|B;0dÀp¹íp…e@¸æè¨reÀÐéÕŽ­›C@eרÜFÀ *"µP8B@€²÷8HÀiëÀìû`@Ð)è§]diÀ]EôO‘@Ä4ezRb@bÂŽ¡YÆp@¨¾¿Sw>I@5ö˜ŒJp@Ü äòP@¸K»YÕ›@Ü,Èlc@>÷š£²Ž@vkm_òÁv@VQç± Ü}@dJþkj@„^ÿúé}@ÆïFµVm@’-.ãÂO|@Wš"ã2Hp@¤]ûæ”{@µIàšßq@fnt2âæj@ úp°‘xc@î6´,Œl@@l/NÉ]@IÌ Ðo@XÍÔõÍE@¼¾6«\Ún@HZŽX.ŸL@.U€Fð@¨ n›³q@|KÙ<›@påÁŸ u@î}xg @Œ@Œ‘JŽŠWx@˜ ±Rtk@Ü8©ÞÖ©[@ÈHÑÇ ¼Š@ 5üš–â~@@d j@‰¤ì¢å a@°P[ì+`y@)5ºû£r@UœÚ¡o@SÙo-7@ÀVË#Ž@(,d¼?|b@ª*<‡3m@`ŽWR[I@üyKCgMŒ@,Wîååp@l¯ox‹@Ôò¥J…gs@Æò§ü®z@–_Þ¶f@ r€¾èi@t÷X§! Z@ìJÑ  3y@¢~¬ÅÔKm@Òcëh„ˆ@®RšÓ2@€@¦Ç7Æðáw@;/÷N£×q@Úæ¡©o@°ùÉ&aïP@άró£|Œ@€¯y¨%©^@((`Е{@p*ÿpl6V@B<&¶Š@ òÝ—ól@ܺC8èi@`Q{ÍQ@Ðè[HŠ ‰@¨6ñË*u@öötVbˆ@8•z?}sx@¼ ûg³g@JXJ¸.±[@¼ÆöJèw@P=Je`ðn@ô}Ì¡kf@éÐdna@:¼ã ‚Ï{@€×ó[8W5@(ì׿•âj@ jéKm8@ ge‘þy@x…(=@"S@úc0 %i@ˆÕýL3ÚI@r˜i~a]h@8¹Ã.OP@ÞÍrYšw@¨Ò•çv”c@Ä©bÁ!év@Äŵ¥Ïêf@¬~TD7v@È(­Cn2j@R«bgãe@´«íßc]@JZ˜fƒùd@!ždBL`@¤ØHcÀ.j@?‡mÇ@îOÆõJi@Pöàþp’2@U碞rˆ@ ¸ÿ©#-`@$6gsOw@ˆ»•óV@Òš~Ùv@ø%ö;¤]@KÒ À|à§‘<†r@‘<íj5@jUé[àÊq@Ÿù·žÍG@JІma@p¶•M®B@ ü Ês€@xËUd ]i@Æ"º¯o@’%iì_@°½€jQ~~@8ˆqÀf@s@ð,]æa]@ÿ°oV@@¥% ÏK\@‡ÑÕ߬Y@ÏYÊô‚@@0·œužb@’Wça^Ðn@øÆŸ¢ƒB@À)sz(}@ðGÊ!ÌÃR@´ r5…k@ȱœØ×B@,„Á.»æ‰@xZ–w/c@ð“²# Vx@°°.­PS@jJ·ßÈv@Ø©6ÀS@ÞöMWF;…@HVö¹(d@N…EÒµc@\f&ED@nÐ%Y¯8b@à),Jg3E@3ˆÝ6±@€!š¡WoW@I°5qco@@Û®zs7@î(ÿ$‚²@ )BôW@ Íõ¹l@Ð-™ zã7@h•Ý$F^z@p… ž!H@êÝïmDºˆ@P§×<"¹X@$j†´w@0­¸ìéDI@Dó° Še@ð¨TÿÙä9@¶÷ÈÌt@°;a¥ðÔJ@.tRÓvb@pÑÌ<@ÿ$8ƒlå@ —äeHB@~ù}âW€@@кÉà2@YÖN@n@ ܰ&"@Š8Â…l@à}e4•"@,:Q#xØj@€Üÿ«ø"@þçØö-i@@(P‰ì#@Z ñD5„g@ nÜã%@²ê¿lçe@ º¿h&@H<àJd@`/^‡#(@º$†²E»r@ ÆêÍ9@äªó£>@ä5ª•&ÀùM:§NW€@@šLÂ^l'À#’~üán@€’µÎÀNvŽ”3m@@U-·ÊÀ†°¹€ôX‹@@ƽÍÏ6ÀÂ¥‰@€) • ¹4ÀiúC‚òw@CxùY£"À: Á‘OF†@ÀˆäHÝ0Àµ '㣄@€@¿UÀ¢+À:r|¤c@€Ðä ª1À{Ï¡U¢@0\¥‹´0EÀ&*í§±@ðQ‰cFWUÀ®už¬ˆ@€MI04lUÀvÜ1±@@0¯½å`UÀ–@šžŸê{@Vò«*9EÀ2¡F0'Š@`+Œ/NùTÀ¶ Žhciˆ@ 4´ÒzTÀlƒÑÑr¸†@ ì(TÀÐXÊöe@43Ecy3ÀpÖà‡¶Zƒ@ðMâ›”RÀºÂ=T- ’@@Rqny²bÀ‡p2‹‘@¡ìN+½bÀ¾0ô߀@ÑÑÝRÀNÍ-[n@8fFéŒÅBÀ¿ÕŠ„|@°˜›•·RÀH‡¶Š@à¸b©bÀˆZµìˆ@€G‰‹ubÀ Ì;úF)‡@¨‘=@BbÀ¶Ó l…@xeƒj…õaÀ$ŽQ4»ƒ@àÇŽƒªaÀ*%}‚@H§Tz[Àþ]4tå{@€” ÒD@[À›Ú¬¢X€€@à8ÏTJ[À˜ ó¸C@øíõëöN[À6ψå.}@k'¼ÎG[Àê·ÝL‹@øH.Û¬kÀ5UY}‰@8‚ ûgkÀb–ÖÚ5«‡@¸ç)ÒÚÓjÀ&¾k¡Uç…@0Õ@jÀ.(ää|$„@Ü^ëFjÀ *Bìör@(î_ôñQÀ­¿>Kí‘@„Ó%iÿqÀ„sœÈ…ë@ÄîÑkrÀ°‹ê°Ø@ûÏá8bÀ¼ø±™ßm@€xNÒRÀ¦ãnòÂõ{@æ¦I³bÀRE̘Š@<Ò0UöqÀ^ÄÈ0@9ˆ@dˆk4}æqÀö7Âcfv@Ôú!xÉÄaÀB‹ºÊ°’t@}Ž•y™aÀ‡1¡cœx“@hY:IŸvÀ•ÜΡgr@ ™òþ¨VÀ]zB Zq@\w«Ék½VÀŲ¹¡Sp@È÷j ï¹VÀè[´»ò n@¤üXN²VÀª¿9® ©Œ@•L!ÁªvÀ<™ €·j@8‹û”VÀ¬õþÍ2Ôh@ؽU?‰‰VÀvÞîzWïf@8{&µrVÀ½ÆÜe@½µQÈBVÀ²¨S P”@HŸ@rý|{Àj¶¸¼ë’@ð#8ÆŸŠ{ÀÖu"—´Õq@ àØ*Œ…[À4Þ?İǀ@° ¼˜3ŠkÀÎbúÞÄzo@Ôk组[Àt^qm@ŒšIŒ[À€çÑt!ok@ ¤ÛÛr[Àò%ZJvy@È@€ô`kÀ¸„$ìÊ‹‡@|pCëêW{À¢C!]§…@¨\ã@Þ&{ÀÐ)²¦\@èï`ÕT@HO‡2Ãhy@zp/Ô«u@¨.dP{šv@*nòò–u@(ü±{Ÿ·c@ìP•%f@à“‹jºP@ï)¢±V@à(¢‹If[@°@o¦Š5g@ÐYõIe@¤ ùÌw@ â\ç\@®£à‡+Zx@ÀÙå,P.@Îéñê?çX@¬#SÁ;@KXD@ÐØå…w@o¼óäød@@†‹»¥d@0™š…U@hû|Ö¶Q@HÆíËF@𛧃ëS]@` §\žV@À=Tx%G@ ÝÌx!G@Мˆá¢P@tÙÈgåÀW@àjaKèC@Œ÷x§‚KX@€„¿z&@<ÌÚ%ZÎH@@ÒÝ6 @Àø*Àœqi@@?uÙz@ࢡ`Ú]@è•ö.À2g@˜¨”þóN@ØÁÍ£[d@¸Ø#+çO@ðoœ UlQ@xT kQ@@Ð B¹?¨\@€fRÇßP@pE%mµgF@ô¶`ÛFA@ þQÐO@Hl÷Cž±Q@ÐŽÝbR@ÐóM"b@€<|=þª1@ º$ð>Šb@€z¢ü3À¨ Ýç"êR@"ÍÊÆi@0¬™AMC@°S[N÷f@Üž¡ D@Xà º d@ïªn¶D@ÐBψÝq@hOœÕcU@ðð å>l@¨¶Û‘öU@ðm7šÃE@°D²Bn¥6@`7ÌÃmv^@TûÁºwW@» 0pï@@@~‡ÖG@²f€J)@`ºšCÅnX@€1s4Ö6À@õ DÚÌH@€š×ˆži@ÀÝLŠÝ±0@HPW#Äf@ÐŒùŒ¶1@ àˆ>*âs@0÷ÙQB@ð-—Ü`@@‰»ϲ3@ ôƒ,7£k@€eY1¤D@@å4×¹?e@ ¥ù¯g;E@@ãXí˜M@V6`§C6@€òÆP5Ë?@À‰ OKv6@äiÔžñ@àĉ ù G@@ võP9À  é©ê¡7@þ›¼Xzi@@m·+‘ÀaLòM›v@‚­‡òw"ÀP-z²l³S@z§ñ ÌÀÈ·üÔa¹`@ßH¿1¥ À@§P–?k@‰Ï1ijÀp`IÝT@ª ¼:ÂÀ úÜ `³\@’SîÞ³À€êgÈN@§‘iœÀDû@½«@ƒâôü?À@˜Æ¹ºEKÀ jìÊXÀãWßii@‡p†X+;À˜\^¹t}V@€—>‚!+ÀÀ~­Í•S@À”õÆAÝ*Àh²)ÉK`@`0ó•$;Àà-FSzðj@ Åé:5KÀÐÊ<ŽD@€itÜC+À SE¨† <@`py¯Ñy+ÀÀ×íg!ž<@@ð2´;À¸EÂXä?à"‘Í=<À\JfÑ<À`ëO.ä<Àg é€Y£@{ÊK)ÈŸš@RiË!Œˆ @ŽÃ„=â•@À(­÷ôª@¹©E©(”@ÑÛ·ü¨¨@Ü 9Ÿ@pŸq>hq¸@ûC¡|Í?¡@mrcal-2.4.1/test/data/test-optimizer-callback-ref-x-5.npy000066400000000000000000000147701456301662300231650ustar00rootroot00000000000000“NUMPYv{'descr': '‚ë½Ò3@XŸ¦WƒP@x)ÍùA0@Ð:B [DP@P üн)@˜&4Wl`@`È·±Õ2@PSOZP@ ÜJ:U@¹8K@ñO@ÀÑŽù @x锵Ér@Ø´ËXXq\@€¼;òRb@¨ÄùÕÑçH@X³áŸjQ@P½ vL[5@à0­ßäP@èS²¶Ò2@ ÈöZP@à®i³ñ-@°€™%¿ão@ÎÙžJa@𓚠¬R:@»<2’p@ÐÛõ\pC@PÔãÝ´O@àÈ>œ /@üð¨ÚŒ^@&¬èhK@°°*ýõx]@dín§Ð?PFÍëÄ•l@@ mïœ(À@…¨Ñ¢äK@úJvòèÀ@f“Ò AK@µX@I"À`,ôqÃZ@œÍ%‹8ÀÐOW£ÂÃq@ ì#nêC@ð£5åìP@ ôüR“ø@ø_ˆ`P@@,Xά @pœj~ÀÅ^@¬ýãÀÿã?€$fxÅ~m@Bè¹õV'À µ4ØUB\@@WÞZ[&Àá~YFK@`@-¶uÄ!Àû+ö&gJ@à›¸ ¡'À°PµÒ¿¦i@zü–ðÀMÀɨX#i@hÛ ™oáQÀXùíøza@¸Ý€Ñ @°’¼èQ†p@`@„Œi¸¿pØUæ—Xo@@?¢Ñh)À0åO¤ìÛm@à$ö8V\8ÀPËkll@ ƒu1üAÀð˜Ïq±&k@Ð1Â`†HÀ€MZ#wj@àvyó NÀpG^QK Y@°Ú¦Ò´BÀóvgš5H@Àß<´ì4À0=)êkxW@Ëœº±¸GÀ áz«*q@§ Á--À@hÃm±/P@`Y3GÀ 8EZ3“n@VŠÒæ¹CÀPê+Jâì\@@è´s·9ÀàÅOZØ][@°š#´[·?À 1¤ÅZ@Ð뱆VÑBÀ`'ÅšÚÂX@Øâ¼S]œEÀpAz ªg@˜â~ÞøsXÀÀã°®¼V@ø»5KKÀ`æ·ò“ÛE@“‹[}>À`¤jçp@I¾¸'9FÀ ç/òJÅ_@ÐØ§S!<À Za‹gÑm@HÁ¢@ˆQÀ •Û¢Ö\@ ÉuTÇÇCÀ°[&N9gJ@PÕ¡£sã6ÀÐRåaXâX@ðoÏ¢IÀ`•®AS~W@à‰ÔfzLÀ`ª…kí?f@ˆ‘ f*_À€Pþ-E@àÕ"®oö@Àà”¬c5D@Ä­»ÀôUBÀ¸åº¿ë `@Ðû‘e·BÀàs¿•üo@¸GôV«UÀ`u>´ôùL@pÛf(@x8ÀÈP"[@€q·š]KÀ@1p’*fY@(«Ðj NÀR îMÉG@ä¦[ŠŒS@À 8[RnPF@P8œ ÛÁAÀࢡ|ðD@ôæðÔCÀpìd´Ó¾c@xr)ðòndÀ°ÿOÚ+œb@ÝCK½eÀ,[5 \`@˜Ù³4¾JÀ`n‚%ã|N@0c¹%UY=À`“rQl@`©µ$`Àà)A9“cZ@Ô+%3wQÀp(ÐtmpX@|‚5ÔRÀPoω]±f@¬|B;0dÀp¹íp…e@¸æè¨reÀÐéÕŽ­›C@eרÜFÀ *"µP8B@€²÷8HÀiëÀìû`@Ð)è§]diÀ]EôO‘@Ä4ezRb@bÂŽ¡YÆp@¨¾¿Sw>I@5ö˜ŒJp@Ü äòP@¸K»YÕ›@Ü,Èlc@>÷š£²Ž@vkm_òÁv@VQç± Ü}@dJþkj@„^ÿúé}@ÆïFµVm@’-.ãÂO|@Wš"ã2Hp@¤]ûæ”{@µIàšßq@fnt2âæj@ úp°‘xc@î6´,Œl@@l/NÉ]@IÌ Ðo@XÍÔõÍE@¼¾6«\Ún@HZŽX.ŸL@.U€Fð@¨ n›³q@|KÙ<›@påÁŸ u@î}xg @Œ@Œ‘JŽŠWx@˜ ±Rtk@Ü8©ÞÖ©[@ÈHÑÇ ¼Š@ 5üš–â~@@d j@‰¤ì¢å a@°P[ì+`y@)5ºû£r@UœÚ¡o@SÙo-7@ÀVË#Ž@(,d¼?|b@ª*<‡3m@`ŽWR[I@üyKCgMŒ@,Wîååp@l¯ox‹@Ôò¥J…gs@Æò§ü®z@–_Þ¶f@ r€¾èi@t÷X§! Z@ìJÑ  3y@¢~¬ÅÔKm@Òcëh„ˆ@®RšÓ2@€@¦Ç7Æðáw@;/÷N£×q@Úæ¡©o@°ùÉ&aïP@άró£|Œ@€¯y¨%©^@((`Е{@p*ÿpl6V@B<&¶Š@ òÝ—ól@ܺC8èi@`Q{ÍQ@Ðè[HŠ ‰@¨6ñË*u@öötVbˆ@8•z?}sx@¼ ûg³g@JXJ¸.±[@¼ÆöJèw@P=Je`ðn@ô}Ì¡kf@éÐdna@:¼ã ‚Ï{@€×ó[8W5@(ì׿•âj@ jéKm8@ ge‘þy@x…(=@"S@úc0 %i@ˆÕýL3ÚI@r˜i~a]h@8¹Ã.OP@ÞÍrYšw@¨Ò•çv”c@Ä©bÁ!év@Äŵ¥Ïêf@¬~TD7v@È(­Cn2j@R«bgãe@´«íßc]@JZ˜fƒùd@!ždBL`@¤ØHcÀ.j@?‡mÇ@îOÆõJi@Pöàþp’2@U碞rˆ@ ¸ÿ©#-`@$6gsOw@ˆ»•óV@Òš~Ùv@ø%ö;¤]@KÒ À|à§‘<†r@‘<íj5@jUé[àÊq@Ÿù·žÍG@JІma@p¶•M®B@ ü Ês€@xËUd ]i@Æ"º¯o@’%iì_@°½€jQ~~@8ˆqÀf@s@ð,]æa]@ÿ°oV@@¥% ÏK\@‡ÑÕ߬Y@ÏYÊô‚@@0·œužb@’Wça^Ðn@øÆŸ¢ƒB@À)sz(}@ðGÊ!ÌÃR@´ r5…k@ȱœØ×B@,„Á.»æ‰@xZ–w/c@ð“²# Vx@°°.­PS@jJ·ßÈv@Ø©6ÀS@ÞöMWF;…@HVö¹(d@N…EÒµc@\f&ED@nÐ%Y¯8b@à),Jg3E@3ˆÝ6±@€!š¡WoW@I°5qco@@Û®zs7@î(ÿ$‚²@ )BôW@ Íõ¹l@Ð-™ zã7@h•Ý$F^z@p… ž!H@êÝïmDºˆ@P§×<"¹X@$j†´w@0­¸ìéDI@Dó° Še@ð¨TÿÙä9@¶÷ÈÌt@°;a¥ðÔJ@.tRÓvb@pÑÌ<@ÿ$8ƒlå@ —äeHB@~ù}âW€@@кÉà2@YÖN@n@ ܰ&"@Š8Â…l@à}e4•"@,:Q#xØj@€Üÿ«ø"@þçØö-i@@(P‰ì#@Z ñD5„g@ nÜã%@²ê¿lçe@ º¿h&@H<àJd@`/^‡#(@º$†²E»r@ ÆêÍ9@äªó£>@ä5ª•&ÀùM:§NW€@@šLÂ^l'À#’~üán@€’µÎÀNvŽ”3m@@U-·ÊÀ†°¹€ôX‹@@ƽÍÏ6ÀÂ¥‰@€) • ¹4ÀiúC‚òw@CxùY£"À: Á‘OF†@ÀˆäHÝ0Àµ '㣄@€@¿UÀ¢+À:r|¤c@€Ðä ª1À{Ï¡U¢@0\¥‹´0EÀ&*í§±@ðQ‰cFWUÀ®už¬ˆ@€MI04lUÀvÜ1±@@0¯½å`UÀ–@šžŸê{@Vò«*9EÀ2¡F0'Š@`+Œ/NùTÀ¶ Žhciˆ@ 4´ÒzTÀlƒÑÑr¸†@ ì(TÀÐXÊöe@43Ecy3ÀpÖà‡¶Zƒ@ðMâ›”RÀºÂ=T- ’@@Rqny²bÀ‡p2‹‘@¡ìN+½bÀ¾0ô߀@ÑÑÝRÀNÍ-[n@8fFéŒÅBÀ¿ÕŠ„|@°˜›•·RÀH‡¶Š@à¸b©bÀˆZµìˆ@€G‰‹ubÀ Ì;úF)‡@¨‘=@BbÀ¶Ó l…@xeƒj…õaÀ$ŽQ4»ƒ@àÇŽƒªaÀ*%}‚@H§Tz[Àþ]4tå{@€” ÒD@[À›Ú¬¢X€€@à8ÏTJ[À˜ ó¸C@øíõëöN[À6ψå.}@k'¼ÎG[Àê·ÝL‹@øH.Û¬kÀ5UY}‰@8‚ ûgkÀb–ÖÚ5«‡@¸ç)ÒÚÓjÀ&¾k¡Uç…@0Õ@jÀ.(ää|$„@Ü^ëFjÀ *Bìör@(î_ôñQÀ­¿>Kí‘@„Ó%iÿqÀ„sœÈ…ë@ÄîÑkrÀ°‹ê°Ø@ûÏá8bÀ¼ø±™ßm@€xNÒRÀ¦ãnòÂõ{@æ¦I³bÀRE̘Š@<Ò0UöqÀ^ÄÈ0@9ˆ@dˆk4}æqÀö7Âcfv@Ôú!xÉÄaÀB‹ºÊ°’t@}Ž•y™aÀ‡1¡cœx“@hY:IŸvÀ•ÜΡgr@ ™òþ¨VÀ]zB Zq@\w«Ék½VÀŲ¹¡Sp@È÷j ï¹VÀè[´»ò n@¤üXN²VÀª¿9® ©Œ@•L!ÁªvÀ<™ €·j@8‹û”VÀ¬õþÍ2Ôh@ؽU?‰‰VÀvÞîzWïf@8{&µrVÀ½ÆÜe@½µQÈBVÀ²¨S P”@HŸ@rý|{Àj¶¸¼ë’@ð#8ÆŸŠ{ÀÖu"—´Õq@ àØ*Œ…[À4Þ?İǀ@° ¼˜3ŠkÀÎbúÞÄzo@Ôk组[Àt^qm@ŒšIŒ[À€çÑt!ok@ ¤ÛÛr[Àò%ZJvy@È@€ô`kÀ¸„$ìÊ‹‡@|pCëêW{À¢C!]§…@¨\ã@Þ&{ÀÐ)²¦\@èï`ÕT@HO‡2Ãhy@zp/Ô«u@¨.dP{šv@*nòò–u@(ü±{Ÿ·c@ìP•%f@à“‹jºP@ï)¢±V@à(¢‹If[@°@o¦Š5g@ÐYõIe@¤ ùÌw@ â\ç\@®£à‡+Zx@ÀÙå,P.@Îéñê?çX@¬#SÁ;@KXD@ÐØå…w@o¼óäød@@†‹»¥d@0™š…U@hû|Ö¶Q@HÆíËF@𛧃ëS]@` §\žV@À=Tx%G@ ÝÌx!G@Мˆá¢P@tÙÈgåÀW@àjaKèC@Œ÷x§‚KX@€„¿z&@<ÌÚ%ZÎH@@ÒÝ6 @Àø*Àœqi@@?uÙz@ࢡ`Ú]@è•ö.À2g@˜¨”þóN@ØÁÍ£[d@¸Ø#+çO@ðoœ UlQ@xT kQ@@Ð B¹?¨\@€fRÇßP@pE%mµgF@ô¶`ÛFA@ þQÐO@Hl÷Cž±Q@ÐŽÝbR@ÐóM"b@€<|=þª1@ º$ð>Šb@€z¢ü3À¨ Ýç"êR@"ÍÊÆi@0¬™AMC@°S[N÷f@Üž¡ D@Xà º d@ïªn¶D@ÐBψÝq@hOœÕcU@ðð å>l@¨¶Û‘öU@ðm7šÃE@°D²Bn¥6@`7ÌÃmv^@TûÁºwW@» 0pï@@@~‡ÖG@²f€J)@`ºšCÅnX@€1s4Ö6À@õ DÚÌH@€š×ˆži@ÀÝLŠÝ±0@HPW#Äf@ÐŒùŒ¶1@ àˆ>*âs@0÷ÙQB@ð-—Ü`@@‰»ϲ3@ ôƒ,7£k@€eY1¤D@@å4×¹?e@ ¥ù¯g;E@@ãXí˜M@V6`§C6@€òÆP5Ë?@À‰ OKv6@äiÔžñ@àĉ ù G@@ võP9À  é©ê¡7@þ›¼Xzi@@m·+‘ÀaLòM›v@‚­‡òw"ÀP-z²l³S@z§ñ ÌÀÈ·üÔa¹`@ßH¿1¥ À@§P–?k@‰Ï1ijÀp`IÝT@ª ¼:ÂÀ úÜ `³\@’SîÞ³À€êgÈN@§‘iœÀDû@½«@ƒâôü?À@˜Æ¹ºEKÀ jìÊXÀãWßii@‡p†X+;À˜\^¹t}V@€—>‚!+ÀÀ~­Í•S@À”õÆAÝ*Àh²)ÉK`@`0ó•$;Àà-FSzðj@ Åé:5KÀÐÊ<ŽD@€itÜC+À SE¨† <@`py¯Ñy+ÀÀ×íg!ž<@@ð2´;À¸EÂXä?à"‘Í=<À\JfÑ<À`ëO.ä<Àg é€Y£@{ÊK)ÈŸš@RiË!Œˆ @ŽÃ„=â•@À(­÷ôª@¹©E©(”@ÑÛ·ü¨¨@Ü 9Ÿ@pŸq>hq¸@ûC¡|Í?¡@mrcal-2.4.1/test/test-CHOLMOD-factorization.py000077500000000000000000000027031456301662300210740ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Tests the CHOLMOD_factorization python class''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils from scipy.sparse import csr_matrix indptr = np.array([0, 2, 3, 6, 8]) indices = np.array([0, 2, 2, 0, 1, 2, 1, 2]) data = np.array([1, 2, 3, 4, 5, 6, 7, 8], dtype=float) Jsparse = csr_matrix((data, indices, indptr)) Jdense = Jsparse.toarray() Jdense_ref = \ np.array(((1, 0, 2), (0, 0, 3), (4, 5, 6), (0, 7, 8)), dtype=float) testutils.confirm_equal(Jdense, Jdense_ref, relative = True, worstcase = True, eps = 1e-6, msg = "csr_matrix representation works as expected") bt = np.array(((1., 5., 3.), (2., -2., -8))) F = mrcal.CHOLMOD_factorization(Jsparse) xt = F.solve_xt_JtJ_bt(bt) JtJ = nps.matmult(nps.transpose(Jdense), Jdense) xt_ref = nps.transpose(np.linalg.solve(JtJ, nps.transpose(bt))) testutils.confirm_equal(xt, xt_ref, relative = True, worstcase = True, eps = 1e-6, msg = "solve_xt_JtJ_bt produces the correct result") testutils.finish() mrcal-2.4.1/test/test-basic-calibration.py000077500000000000000000000424141456301662300205060ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Basic camera-calibration test I observe, with noise, a number of chessboards from various angles with several cameras. And I make sure that I can more or less compute the camera intrinsics and extrinsics ''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils from test_calibration_helpers import sample_dqref import copy # I want the RNG to be deterministic np.random.seed(0) ############# Set up my world, and compute all the perfect positions, pixel ############# observations of everything models_ref = ( mrcal.cameramodel(f"{testdir}/data/cam0.opencv8.cameramodel"), mrcal.cameramodel(f"{testdir}/data/cam0.opencv8.cameramodel"), mrcal.cameramodel(f"{testdir}/data/cam1.opencv8.cameramodel"), mrcal.cameramodel(f"{testdir}/data/cam1.opencv8.cameramodel") ) imagersizes = nps.cat( *[m.imagersize() for m in models_ref] ) lensmodel = models_ref[0].intrinsics()[0] # I have opencv8 models_ref, but let me truncate to opencv4 models_ref to keep this # simple and fast lensmodel = 'LENSMODEL_OPENCV4' for m in models_ref: m.intrinsics( intrinsics = (lensmodel, m.intrinsics()[1][:8])) Nintrinsics = mrcal.lensmodel_num_params(lensmodel) Ncameras = len(models_ref) Nframes = 50 models_ref[0].extrinsics_rt_fromref(np.zeros((6,), dtype=float)) models_ref[1].extrinsics_rt_fromref(np.array((0.08,0.2,0.02, 1., 0.9,0.1))) models_ref[2].extrinsics_rt_fromref(np.array((0.01,0.07,0.2, 2.1,0.4,0.2))) models_ref[3].extrinsics_rt_fromref(np.array((-0.1,0.08,0.08, 4.4,0.2,0.1))) pixel_uncertainty_stdev = 1.5 object_spacing = 0.1 object_width_n = 10 object_height_n = 9 calobject_warp_ref = np.array((0.002, -0.005)) # shapes (Nframes, Ncameras, Nh, Nw, 2), # (Nframes, 4,3) q_ref,Rt_ref_board_ref = \ mrcal.synthesize_board_observations(models_ref, object_width_n = object_width_n, object_height_n = object_height_n, object_spacing = object_spacing, calobject_warp = calobject_warp_ref, rt_ref_boardcenter = np.array((0., 0., 0., -2, 0, 4.0)), rt_ref_boardcenter__noiseradius = np.array((np.pi/180.*30., np.pi/180.*30., np.pi/180.*20., 2.5, 2.5, 2.0)), Nframes = Nframes) frames_ref = mrcal.rt_from_Rt(Rt_ref_board_ref) ############# I have perfect observations in q_ref. I corrupt them by noise # weight has shape (Nframes, Ncameras, Nh, Nw), weight01 = (np.random.rand(*q_ref.shape[:-1]) + 1.) / 2. # in [0,1] weight0 = 0.2 weight1 = 1.0 weight = weight0 + (weight1-weight0)*weight01 # I want observations of shape (Nframes*Ncameras, Nh, Nw, 3) where each row is # (x,y,weight) observations_ref = nps.clump( nps.glue(q_ref, nps.dummy(weight,-1), axis=-1), n=2) q_noise,observations = sample_dqref(observations_ref, pixel_uncertainty_stdev, make_outliers = True) # Now I make some of the observations bogus, and mark them as input outliers. # The solve should be robust to that, but any code that uses the bogus data # DESPITE it being marked as bogus will generate a test failure # # Let's pretend the center of the chessboard has an apriltag, so all those # observations are bogus. I block out a 5x5 chunk in the center i0 = object_height_n//2 j0 = object_width_n//2 observations[..., i0-2:i0+3,j0-2:j0+3, 2] = -1. # weight<=0: outlier observations[..., i0-2:i0+3,j0-2:j0+3,:2] = -100.0 # all the values are bogus ############# Now I pretend that the noisy observations are all I got, and I run ############# a calibration from those # Dense observations. All the cameras see all the boards indices_frame_camera = np.zeros( (Nframes*Ncameras, 2), dtype=np.int32) indices_frame = indices_frame_camera[:,0].reshape(Nframes,Ncameras) indices_frame.setfield(nps.outer(np.arange(Nframes, dtype=np.int32), np.ones((Ncameras,), dtype=np.int32)), dtype = np.int32) indices_camera = indices_frame_camera[:,1].reshape(Nframes,Ncameras) indices_camera.setfield(nps.outer(np.ones((Nframes,), dtype=np.int32), np.arange(Ncameras, dtype=np.int32)), dtype = np.int32) indices_frame_camintrinsics_camextrinsics = \ nps.glue(indices_frame_camera, indices_frame_camera[:,(1,)]-1, axis=-1) intrinsics_data,extrinsics_rt_fromref,frames_rt_toref = \ mrcal.seed_stereographic(imagersizes = imagersizes, focal_estimate = 1500, indices_frame_camera = indices_frame_camera, observations = observations, object_spacing = object_spacing) # I have a stereographic intrinsics estimate. Mount it into a full distortiony # model, seeded with random numbers intrinsics = np.zeros((Ncameras,Nintrinsics), dtype=float) intrinsics[:,:4] = intrinsics_data intrinsics[:,4:] = np.random.random( (Ncameras, intrinsics.shape[1]-4) ) * 1e-6 optimization_inputs = \ dict( intrinsics = intrinsics, extrinsics_rt_fromref = extrinsics_rt_fromref, frames_rt_toref = frames_rt_toref, points = None, observations_board = observations, indices_frame_camintrinsics_camextrinsics = indices_frame_camintrinsics_camextrinsics, observations_point = None, indices_point_camintrinsics_camextrinsics = None, lensmodel = lensmodel, calobject_warp = None, imagersizes = imagersizes, calibration_object_spacing = object_spacing, verbose = False, do_apply_regularization = True) # Solve this thing incrementally optimization_inputs['do_optimize_intrinsics_core'] = False optimization_inputs['do_optimize_intrinsics_distortions'] = False optimization_inputs['do_optimize_extrinsics'] = True optimization_inputs['do_optimize_frames'] = True optimization_inputs['do_optimize_calobject_warp'] = False mrcal.optimize(**optimization_inputs, do_apply_outlier_rejection = True) optimization_inputs['do_optimize_intrinsics_core'] = True optimization_inputs['do_optimize_intrinsics_distortions'] = False optimization_inputs['do_optimize_extrinsics'] = True optimization_inputs['do_optimize_frames'] = True optimization_inputs['do_optimize_calobject_warp'] = False mrcal.optimize(**optimization_inputs, do_apply_outlier_rejection = True) testutils.confirm_equal( mrcal.num_states(**optimization_inputs), 4*Ncameras + 6*(Ncameras-1) + 6*Nframes, msg="num_states()") testutils.confirm_equal( mrcal.num_states_intrinsics(**optimization_inputs), 4*Ncameras, msg="num_states_intrinsics()") testutils.confirm_equal( mrcal.num_intrinsics_optimization_params(**optimization_inputs), 4, msg="num_intrinsics_optimization_params()") testutils.confirm_equal( mrcal.num_states_extrinsics(**optimization_inputs), 6*(Ncameras-1), msg="num_states_extrinsics()") testutils.confirm_equal( mrcal.num_states_frames(**optimization_inputs), 6*Nframes, msg="num_states_frames()") testutils.confirm_equal( mrcal.num_states_points(**optimization_inputs), 0, msg="num_states_points()") testutils.confirm_equal( mrcal.num_states_calobject_warp(**optimization_inputs), 0, msg="num_states_calobject_warp()") testutils.confirm_equal( mrcal.num_measurements_boards(**optimization_inputs), object_width_n*object_height_n*2*Nframes*Ncameras, msg="num_measurements_boards()") testutils.confirm_equal( mrcal.num_measurements_points(**optimization_inputs), 0, msg="num_measurements_points()") testutils.confirm_equal( mrcal.num_measurements_regularization(**optimization_inputs), Ncameras * 2, msg="num_measurements_regularization()") optimization_inputs['do_optimize_intrinsics_core'] = True optimization_inputs['do_optimize_intrinsics_distortions'] = True optimization_inputs['do_optimize_extrinsics'] = True optimization_inputs['do_optimize_frames'] = True optimization_inputs['do_optimize_calobject_warp'] = True optimization_inputs['calobject_warp'] = np.array((0.001, 0.001)) stats = mrcal.optimize(**optimization_inputs, do_apply_outlier_rejection = True) rmserr = stats['rms_reproj_error__pixels'] testutils.confirm_equal( mrcal.state_index_intrinsics(2, **optimization_inputs), 8*2, msg="state_index_intrinsics()") testutils.confirm_equal( mrcal.state_index_extrinsics(2, **optimization_inputs), 8*Ncameras + 6*2, msg="state_index_extrinsics()") testutils.confirm_equal( mrcal.state_index_frames(2, **optimization_inputs), 8*Ncameras + 6*(Ncameras-1) + 6*2, msg="state_index_frames()") testutils.confirm_equal( mrcal.state_index_calobject_warp(**optimization_inputs), 8*Ncameras + 6*(Ncameras-1) + 6*Nframes, msg="state_index_calobject_warp()") testutils.confirm_equal( mrcal.measurement_index_boards(2, **optimization_inputs), object_width_n*object_height_n*2* 2, msg="measurement_index_boards()") testutils.confirm_equal( mrcal.measurement_index_regularization(**optimization_inputs), object_width_n*object_height_n*2*Nframes*Ncameras, msg="measurement_index_regularization()") ############# Calibration computed. Now I see how well I did models_solved = \ [ mrcal.cameramodel( optimization_inputs = optimization_inputs, icam_intrinsics = i ) for i in range(Ncameras)] # if 0: # for i in range(1,Ncameras): # models_solved[i].write(f'/tmp/tst{i}.cameramodel') testutils.confirm_equal(rmserr, 0, eps = 2.5, msg = "Converged to a low RMS error") testutils.confirm_equal( optimization_inputs['calobject_warp'], calobject_warp_ref, eps = 2e-3, msg = "Recovered the calibration object shape" ) testutils.confirm_equal( np.std( mrcal.residuals_board(optimization_inputs, residuals = stats['x'])), pixel_uncertainty_stdev, eps = pixel_uncertainty_stdev*0.1, msg = "Residual have the expected distribution" ) # Checking the extrinsics. These aren't defined absolutely: each solve is free # to put the observed frames anywhere it likes. The projection-diff code # computes a transformation to address this. Here I simply look at the relative # transformations between cameras, which would cancel out any extra # transformations, AND since camera0 is fixed at the identity transformation, I # can simply look at each extrinsics transformation. for icam in range(1,len(models_ref)): Rt_extrinsics_err = \ mrcal.compose_Rt( models_solved[icam].extrinsics_Rt_fromref(), models_ref [icam].extrinsics_Rt_toref() ) testutils.confirm_equal( nps.mag(Rt_extrinsics_err[3,:]), 0.0, eps = 0.05, msg = f"Recovered extrinsic translation for camera {icam}") testutils.confirm_equal( (np.trace(Rt_extrinsics_err[:3,:]) - 1) / 2., 1.0, eps = np.cos(1. * np.pi/180.0), # 1 deg msg = f"Recovered extrinsic rotation for camera {icam}") Rt_frame_err = \ mrcal.compose_Rt( mrcal.Rt_from_rt(optimization_inputs['frames_rt_toref']), mrcal.invert_Rt(Rt_ref_board_ref) ) testutils.confirm_equal( np.max(nps.mag(Rt_frame_err[..., 3,:])), 0.0, eps = 0.08, msg = "Recovered frame translation") testutils.confirm_equal( np.min( (nps.trace(Rt_frame_err[..., :3,:]) - 1)/2. ), 1.0, eps = np.cos(1. * np.pi/180.0), # 1 deg msg = "Recovered frame rotation") # Checking the intrinsics. Each intrinsics vector encodes an implicit # transformation. I compute and apply this transformation when making my # intrinsics comparisons. I make sure that within some distance of the pixel # center, the projections match up to within some number of pixels Nw = 60 def projection_diff(models_ref, max_dist_from_center): lensmodels = [model.intrinsics()[0] for model in models_ref] intrinsics_data = [model.intrinsics()[1] for model in models_ref] # v shape (...,Ncameras,Nheight,Nwidth,...) # q0 shape (..., Nheight,Nwidth,...) v,q0 = \ mrcal.sample_imager_unproject(Nw,None, *imagersizes[0], lensmodels, intrinsics_data, normalize = True) W,H = imagersizes[0] focus_center = None focus_radius = -1 if focus_center is None: focus_center = ((W-1.)/2., (H-1.)/2.) if focus_radius < 0: focus_radius = min(W,H)/6. implied_Rt10 = \ mrcal.implied_Rt10__from_unprojections(q0, v[0,...], v[1,...], focus_center = focus_center, focus_radius = focus_radius) q1 = mrcal.project( mrcal.transform_point_Rt(implied_Rt10, v[0,...]), lensmodels[1], intrinsics_data[1]) diff = nps.mag(q1 - q0) # zero-out everything too far from the center center = (imagersizes[0] - 1.) / 2. diff[ nps.norm2(q0 - center) > max_dist_from_center*max_dist_from_center ] = 0 # gp.plot(diff, # ascii = True, # using = mrcal.imagergrid_using(imagersizes[0], Nw), # square=1, _with='image', tuplesize=3, hardcopy='/tmp/yes.gp', cbmax=3) return diff for icam in range(len(models_ref)): diff = projection_diff( (models_ref[icam], models_solved[icam]), 800) testutils.confirm_equal(diff, 0, worstcase = True, eps = 6., msg = f"Recovered intrinsics for camera {icam}") # It would be nice to check the outlier detections, but this is iffy. Here I'm # generating 1% outliers (hard-coded in sample_dqref()), but the outlier # rejection is overly aggressive. I'm currently seeing 4.4%: # # np.count_nonzero(observations[...,2]<=0) / observations[...,0].ravel().size # # The outlier rejection scheme just cuts out 3sigma residuals and above, so it's # not great. I'm not entirely sure why it's over-reporting the outliers here, # but I should investigate that at the same time as I overhaul the outlier # rejection scheme (presumably to use one of my flavors of Cook's D factor) # I test make_perfect_observations(). Doing it here is easy; doing it elsewhere # it much more work if True: optimization_inputs_perfect = copy.deepcopy(optimization_inputs) mrcal.make_perfect_observations(optimization_inputs_perfect, observed_pixel_uncertainty=0) x = mrcal.optimizer_callback(**optimization_inputs_perfect, no_jacobian = True, no_factorization = True)[1] Nmeas = mrcal.num_measurements_boards(**optimization_inputs_perfect) if Nmeas > 0: i_meas0 = mrcal.measurement_index_boards(0, **optimization_inputs_perfect) testutils.confirm_equal( x[i_meas0:i_meas0+Nmeas], 0, worstcase = True, eps = 1e-8, msg = f"make_perfect_observations() works for boards") else: testutils.confirm( False, msg = f"Nmeasurements_boards <= 0") testutils.finish() mrcal-2.4.1/test/test-basic-sfm.py000077500000000000000000000173611456301662300170070ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Basic structure-from-motion test I observe, with noise, a number of points from various angles with a single camera, and I make sure that I can accurately compute the locations of the points ''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils ############# Set up my world, and compute all the perfect positions, pixel ############# observations of everything m = mrcal.cameramodel(f"{testdir}/data/cam0.opencv8.cameramodel") imagersize = m.imagersize() lensmodel,intrinsics_data = m.intrinsics() # This many points are not optimized, and we know exactly where they are. We # need this to set the scale of the problem. Otherwise the solve is ambiguous Npoints_fixed = 3 pref_true = np.array((( 10., 20., 100.), ( 25., 30., 90.), ( 5., 10., 94.), (-45., -20., 95.), (-35., 14., 77.), ( 5., -0., 110.), ( 1., 50., 50.))) # The points are all somewhere at +z. So the Camera poses are all ~ identity rt_cam_ref_true = np.array(((-0.1, -0.07, 0.01, 10.0, 4.0, -7.0), (-0.01, 0.05,-0.02, 30.0,-8.0, -8.0), (-0.1, 0.03,-0.03, 10.0,-9.0, 20.0), ( 0.04,-0.04, 0.03, -20.0, 2.0,-11.0), ( 0.01, 0.05,-0.05, -10.0, 3.0, 9.0))) # shape (Ncamposes, Npoints, 3) pcam_true = mrcal.transform_point_rt(nps.mv(rt_cam_ref_true, -2,-3), pref_true) # shape (Ncamposes, Npoints, 2) qcam_true = mrcal.project(pcam_true, lensmodel, intrinsics_data) # Observations are incomplete. Not all points are observed from everywhere indices_point_camintrinsics_camextrinsics = \ np.array(((0, 0, 1), (0, 0, 2), (0, 0, 4), (1, 0, 0), (1, 0, 1), (1, 0, 4), (2, 0, 0), (2, 0, 1), (2, 0, 2), (3, 0, 1), (3, 0, 2), (3, 0, 3), (3, 0, 4), (4, 0, 0), (4, 0, 3), (4, 0, 4), (5, 0, 0), (5, 0, 1), (5, 0, 2), (5, 0, 3), (5, 0, 4), (6, 0, 2), (6, 0, 3), (6, 0, 4)), dtype = np.int32) def make_noisy_inputs(): r'''Construct incomplete, noisy observations to feed to the solver''' # The seed points array is the true array, but corrupted by noise. All the # points are observed at some point #print(repr((np.random.random(points.shape)-0.5)/3)) points_noise = np.array([[-0.16415198, 0.10697666, 0.07137079], [-0.02353459, 0.07269802, 0.05804911], [-0.05218085, -0.09302461, -0.16626839], [ 0.03649283, -0.04345566, -0.1589429 ], [-0.05530528, 0.03942736, -0.02755858], [-0.16252387, 0.07792151, -0.12200266], [-0.02611094, -0.13695699, 0.06799326]]) # The fixed points are perfect points_noise[-Npoints_fixed:, :] = 0 pref_noisy = pref_true * (1. + points_noise) Ncamposes,Npoints = pcam_true.shape[:2] ipoints = indices_point_camintrinsics_camextrinsics[:,0] icamposes = indices_point_camintrinsics_camextrinsics[:,2] qcam_indexed = nps.clump(qcam_true, n=2)[icamposes*Npoints+ipoints,:] #print(repr(np.random.randn(*qcam_indexed.shape) * 1.0)) qcam_noise = np.array([[-0.40162837, -0.60884836], [-0.65186956, -2.23240529], [ 0.40217293, -0.40160168], [ 2.05376895, -1.47389235], [-0.01090807, 0.35468639], [-0.37916168, -1.06052742], [-0.08546853, -2.69946391], [ 0.76133345, -1.38759769], [-1.05998307, -0.27779779], [-2.22203688, 1.47809028], [ 1.68526798, 0.83635394], [ 1.26203342, 2.58905488], [ 1.18282463, -0.41362789], [ 0.41615768, 2.06621809], [ 0.27271605, 1.19721072], [-1.48421641, 3.20841776], [ 1.10563011, 0.38313526], [ 0.25591618, -0.97987565], [-0.2431585 , -1.34797656], [ 1.57805536, -0.26467537], [ 1.23762306, 0.94616712], [ 0.29441229, -0.78921128], [-1.33799634, -1.65173241], [-0.24854348, -0.14145806]]) qcam_indexed_noisy = qcam_indexed + qcam_noise observations = nps.glue(qcam_indexed_noisy, nps.transpose(np.ones((qcam_indexed_noisy.shape[0],))), axis = -1) #print(repr((np.random.random(rt_cam_ref_true.shape)-0.5)/10)) rt_cam_ref_noise = \ np.array([[-0.00781127, -0.04067386, -0.01039731, 0.02057068, -0.0461704 , 0.02112582], [-0.02466267, -0.01445134, -0.01290107, -0.01956848, 0.04604318, 0.0439563 ], [-0.02335697, 0.03171099, -0.00900416, -0.0346394 , -0.0392821 , 0.03892269], [ 0.00229462, -0.01716853, 0.01336239, -0.0228473 , -0.03919978, 0.02671576], [ 0.03782446, -0.016981 , 0.03949906, -0.03256744, 0.02496247, 0.02924358]]) rt_cam_ref_noisy = rt_cam_ref_true * (1.0 + rt_cam_ref_noise) return rt_cam_ref_noisy, pref_noisy, observations ############### Do everything in the ref coord system, with a few fixed-position ############### points to set the scale rt_cam_ref_noisy, pref_noisy, observations = make_noisy_inputs() stats = mrcal.optimize( intrinsics = nps.atleast_dims(intrinsics_data, -2), extrinsics_rt_fromref = rt_cam_ref_noisy, points = pref_noisy, observations_point = observations, indices_point_camintrinsics_camextrinsics = indices_point_camintrinsics_camextrinsics, lensmodel = lensmodel, imagersizes = nps.atleast_dims(imagersize, -2), Npoints_fixed = Npoints_fixed, point_min_range = 1.0, point_max_range = 1000.0, do_optimize_intrinsics_core = False, do_optimize_intrinsics_distortions = False, do_optimize_extrinsics = True, do_optimize_frames = True, do_apply_outlier_rejection = False, do_apply_regularization = True, verbose = False) # Got a solution. How well do they fit? fit_rms = np.sqrt(np.mean(nps.norm2(pref_noisy - pref_true))) testutils.confirm_equal(fit_rms, 0, msg = f"Solved at ref coords with known-position points", eps = 1.0) testutils.finish() mrcal-2.4.1/test/test-broadcasting.py000077500000000000000000000066341456301662300176040ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Broadcasting test for various functions ''' import sys import argparse import re import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils import numpy as np import numpysane as nps def test_ref_calibration_object(): obj = mrcal.ref_calibration_object(10,9,5) testutils.confirm_equal(obj.shape, (9,10,3), msg = "ref_calibration_object() baseline case: shape") testutils.confirm_equal(obj[0,1,0] - obj[0,0,0], 5, msg = "ref_calibration_object() baseline case: dx") testutils.confirm_equal(obj[1,0,1] - obj[0,0,1], 5, msg = "ref_calibration_object() baseline case: dy") obj = mrcal.ref_calibration_object(10,9, (5,6)) testutils.confirm_equal(obj.shape, (9,10,3), msg = "ref_calibration_object() different x,y spacing: shape") testutils.confirm_equal(obj[0,1,0] - obj[0,0,0], 5, msg = "ref_calibration_object() different x,y spacing: dx") testutils.confirm_equal(obj[1,0,1] - obj[0,0,1], 6, msg = "ref_calibration_object() different x,y spacing: dy") obj = mrcal.ref_calibration_object(10,9, np.array(((5,6), (2,3)))) testutils.confirm_equal(obj.shape, (2, 9,10,3), msg = "ref_calibration_object() different x,y spacing, broadcasted: shape") testutils.confirm_equal(obj[0,0,1,0] - obj[0,0,0,0], 5, msg = "ref_calibration_object() different x,y spacing, broadcasted: dx[0]") testutils.confirm_equal(obj[0,1,0,1] - obj[0,0,0,1], 6, msg = "ref_calibration_object() different x,y spacing, broadcasted: dy[0]") testutils.confirm_equal(obj[1,0,1,0] - obj[1,0,0,0], 2, msg = "ref_calibration_object() different x,y spacing, broadcasted: dx[1]") testutils.confirm_equal(obj[1,1,0,1] - obj[1,0,0,1], 3, msg = "ref_calibration_object() different x,y spacing, broadcasted: dy[1]") obj = mrcal.ref_calibration_object(10,9,5, calobject_warp = np.array((3,4))) testutils.confirm_equal(obj.shape, (9,10,3), msg = "ref_calibration_object() one calobject_warp: shape") obj = mrcal.ref_calibration_object(10,9,5, calobject_warp = np.array(((3,4),(2,5)))) testutils.confirm_equal(obj.shape, (2,9,10,3), msg = "ref_calibration_object() multiple calobject_warp: shape") obj = mrcal.ref_calibration_object(10,9, nps.dummy(np.array(((5,6), (2,3))), -2), # shape (2,1,2) calobject_warp = np.array(((3,4),(2,5),(0.1,0.2)))) testutils.confirm_equal(obj.shape, (2,3,9,10,3), msg = "ref_calibration_object() multiple calobject_warp, x,y spacing: shape") test_ref_calibration_object() testutils.finish() mrcal-2.4.1/test/test-cahvor.c000066400000000000000000000156051456301662300162130ustar00rootroot00000000000000// Apparently I need this in MSVC to get constants #define _USE_MATH_DEFINES #include #include #include #include #include #include "../minimath/minimath.h" #include "test-harness.h" /* For everything that is a part of my cost function I need to compute gradients in respect to the parameters. Thus I need to re-implement the CAHVOR projection. I re-worked the math and simplified the implementation. This file is a small test program that makes sure that my simpler implementation produces the same result as the reference function. */ #define bool_t bool // basic linear algebra used by the reference cahvor projection function. Comes // from m-jplv/libmat3/mat3.c double dot3( const double a[3], /* input vector */ const double b[3]) /* input vector */ { double f; /* Check for NULL inputs */ if ((a == NULL) || (b == NULL)) return 0.0; /* Dot the two vectors */ f = a[0] * b[0] + a[1] * b[1] + a[2] * b[2]; /* Return the dot product */ return f; } double *sub3( const double a[3], /* input minuend vector */ const double b[3], /* input subtrahend vector */ double c[3]) /* output difference vector */ { /* Check for NULL inputs */ if ((a == NULL) || (b == NULL) || (c == NULL)) return NULL; /* Subtract the two vectors */ c[0] = a[0] - b[0]; c[1] = a[1] - b[1]; c[2] = a[2] - b[2]; /* Return a pointer to the result */ return c; } double *scale3( double s, /* input scalar */ const double a[3], /* input vector */ double b[3]) /* output vector */ { /* Check for NULL inputs */ if ((a == NULL) || (b == NULL)) return NULL; /* Perform the scalar multiplication */ b[0] = s * a[0]; b[1] = s * a[1]; b[2] = s * a[2]; /* Return a pointer to the result */ return b; } double *add3( const double a[3], /* input addend vector */ const double b[3], /* input addend vector */ double c[3]) /* output sum vector */ { /* Check for NULL inputs */ if ((a == NULL) || (b == NULL) || (c == NULL)) return NULL; /* Add the two vectors */ c[0] = a[0] + b[0]; c[1] = a[1] + b[1]; c[2] = a[2] + b[2]; /* Return a pointer to the result */ return c; } // original implementation from m-jplv/libcmod/cmod_cahvor.c, with the gradient // stuff culled out static void cmod_cahvor_3d_to_2d( const double pos3[3], /* input 3D position */ const double c[3], /* input model center vector C */ const double a[3], /* input model axis vector A */ const double h[3], /* input model horiz. vector H */ const double v[3], /* input model vert. vector V */ const double o[3], /* input model optical axis O */ const double r[3], /* input model radial-distortion terms R */ bool_t approx, /* input flag to use fast approximation */ double *range, /* output range along A (same units as C) */ double pos2[2], /* output 2D image-plane projection */ double par[2][3]) /* output partial-derivative matrix of pos2 to pos3 */ { double alpha, beta, gamma, xh, yh; double omega, omega_2, tau, mu; double p_c[3], pp[3], pp_c[3], wo[3], lambda[3]; double dldp[3][3], dppdp[3][3], m33[3][3], n33[3][3]; double dxhdpp[3], dyhdpp[3], v3[3], u3[3]; double dudt; /* Calculate p' and other necessary quantities */ sub3(pos3, c, p_c); omega = dot3(p_c, o); omega_2 = omega * omega; scale3(omega, o, wo); sub3(p_c, wo, lambda); tau = dot3(lambda, lambda) / omega_2; mu = r[0] + (r[1] * tau) + (r[2] * tau * tau); scale3(mu, lambda, pp); add3(pos3, pp, pp); /* Calculate alpha, beta, gamma, which are (p' - c) */ /* dotted with a, h, v, respectively */ sub3(pp, c, pp_c); alpha = dot3(pp_c, a); beta = dot3(pp_c, h); gamma = dot3(pp_c, v); /* Calculate the projection */ pos2[0] = xh = beta / alpha; pos2[1] = yh = gamma / alpha; *range = alpha; } // my simplified version static void project_cahvor( const double pos3[3], /* input 3D position */ const double c[3], /* input model center vector C */ const double a[3], /* input model axis vector A */ const double h[3], /* input model horiz. vector H */ const double v[3], /* input model vert. vector V */ const double o[3], /* input model optical axis O */ const double r[3], /* input model radial-distortion terms R */ double pos2[2] /* output 2D image-plane projection */ ) /* output partial-derivative matrix of pos2 to pos3 */ { // canonical equivalent: // if canonical, I have // c = 0, 0, 0 // a = 0, 0, 1 // h = fx, 0, cx // v = 0, fy, cy // o = sin(ph)*cos(th), sin(ph)*sin(th), cos(ph) // r = r0, r1, r2 assert(c[0] == 0 && c[1] == 0 && c[2] == 0); assert(a[0] == 0 && a[1] == 0 && a[2] == 1); assert(h[1] == 0); assert(v[0] == 0); double norm2o = norm2_vec(3, o); assert( norm2o > 1 - 1e-6 && norm2o < 1 + 1e-6 ); double norm2p = norm2_vec(3, pos3); double omega = dot_vec(3, pos3, o); double tau = norm2p / (omega*omega) - 1.0; double mu = r[0] + tau*(r[1] + r[2] * tau); double px = pos3[0] * (mu + 1.0) - mu*omega*o[0]; double py = pos3[1] * (mu + 1.0) - mu*omega*o[1]; double pz = pos3[2] * (mu + 1.0) - mu*omega*o[2]; double fx = h[0]; double fy = v[1]; double cx = h[2]; double cy = v[2]; pos2[0] = fx*px/pz + cx; pos2[1] = fy*py/pz + cy; } int main(int argc, char* argv[]) { double c[] = { 0, 0, 0 }; double a[] = { 0, 0, 1 }; double h[] = { 11, 0, 23 }; double v[] = { 0, 13, 7 }; double o[] = {0.1,0.2,0.9 }; double r[] = { 7, 8, 2 }; double o_len = sqrt(norm2_vec(3, o)); for(int i=0; i<3; i++) o[i] /= o_len; double p[] = {12, 13, 99}; double range; double projection_orig[2]; cmod_cahvor_3d_to_2d( p, c,a,h,v,o,r, false, &range, projection_orig, NULL ); double projection_new[2]; project_cahvor( p, c,a,h,v,o,r, projection_new ); // out2: new implementation, with scaled up 3d vector. The scaling should // have NO effect double projection_new_scaled3d[2]; for(int i=0;i<3;i++) p[i] *= 10.0; project_cahvor( p, c,a,h,v,o,r, projection_new_scaled3d ); confirm_eq_double(projection_new[0], projection_orig[0], 1e-6); confirm_eq_double(projection_new[1], projection_orig[1], 1e-6); confirm_eq_double(projection_new_scaled3d[0], projection_orig[0], 1e-6); confirm_eq_double(projection_new_scaled3d[1], projection_orig[1], 1e-6); TEST_FOOTER(); } mrcal-2.4.1/test/test-cameramodel.py000077500000000000000000000110651456301662300174070ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Tests for cameramodel reading/writing''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils import tempfile import atexit import shutil workdir = tempfile.mkdtemp() def cleanup(): global workdir try: shutil.rmtree(workdir) workdir = None except: pass atexit.register(cleanup) # I do this: # load file # compare with hardcoded # save # load again # compare with hardcoded # # modify with setter # call getter and compare m = mrcal.cameramodel(f"{testdir}/data/cam0.opencv8.cameramodel") testutils.confirm_equal( m.extrinsics_rt_fromref(), [ 2e-2, -3e-1, -1e-2, 1., 2, -3., ] ) testutils.confirm_equal( m.intrinsics()[0], 'LENSMODEL_OPENCV8' ) testutils.confirm_equal( m.intrinsics()[1], [ 1761.181055, 1761.250444, 1965.706996, 1087.518797, -0.01266096516, 0.03590794372, -0.0002547045941, 0.0005275929652, 0.01968883397, 0.01482863541, -0.0562239888, 0.0500223357,] ) m.write(f'{workdir}/out.cameramodel') m.write(f'{workdir}/out.cahvor') m1 = mrcal.cameramodel(f'{workdir}/out.cameramodel') testutils.confirm_equal( m1.extrinsics_rt_fromref(), [ 2e-2, -3e-1, -1e-2, 1., 2, -3., ] ) testutils.confirm_equal( m1.intrinsics()[0], 'LENSMODEL_OPENCV8' ) testutils.confirm_equal( m1.intrinsics()[1], [ 1761.181055, 1761.250444, 1965.706996, 1087.518797, -0.01266096516, 0.03590794372, -0.0002547045941, 0.0005275929652, 0.01968883397, 0.01482863541, -0.0562239888, 0.0500223357,] ) m2 = mrcal.cameramodel(f'{workdir}/out.cahvor') testutils.confirm_equal( m2.extrinsics_rt_fromref(), [ 2e-2, -3e-1, -1e-2, 1., 2, -3., ] ) testutils.confirm_equal( m2.intrinsics()[0], 'LENSMODEL_OPENCV8' ) testutils.confirm_equal( m2.intrinsics()[1], [ 1761.181055, 1761.250444, 1965.706996, 1087.518797, -0.01266096516, 0.03590794372, -0.0002547045941, 0.0005275929652, 0.01968883397, 0.01482863541, -0.0562239888, 0.0500223357,] ) rt_0r = np.array([ 4e-1, -1e-2, 1e-3, -2., 3, -5., ]) Rt_r0 = mrcal.invert_Rt( mrcal.Rt_from_rt( rt_0r )) m.extrinsics_Rt_toref( Rt_r0 ) testutils.confirm_equal( m.extrinsics_rt_fromref(), rt_0r ) # Let's make sure I can read and write empty and non-empty valid-intrinsics # regions m = mrcal.cameramodel(f"{testdir}/data/cam0.opencv8.cameramodel") testutils.confirm_equal( m.valid_intrinsics_region(), None, msg = "read 'valid_intrinsics_region is None' properly") r_open = np.array(((0, 0), (0, 10), (10,10), (10, 0))) r_closed = np.array(((0, 0), (0, 10), (10,10), (10, 0), (0, 0))) r_empty = np.zeros((0,2)) m.valid_intrinsics_region(r_open) testutils.confirm_equal( m.valid_intrinsics_region(), r_closed, msg="was able to set an open valid_intrinsics_region and to see it be closed") m.write(f'{workdir}/out.cameramodel') m1 = mrcal.cameramodel(f'{workdir}/out.cameramodel') testutils.confirm_equal( m1.valid_intrinsics_region(), r_closed, msg="read 'valid_intrinsics_region' properly") m.valid_intrinsics_region(r_empty) testutils.confirm_equal( m.valid_intrinsics_region(), r_empty, msg="was able to set an empty valid_intrinsics_region") m.write(f'{workdir}/out.cameramodel') m1 = mrcal.cameramodel(f'{workdir}/out.cameramodel') testutils.confirm_equal( m1.valid_intrinsics_region(), r_empty, msg="read empty valid_intrinsics_region properly") # Make sure we can read model data with extra spacing string = r''' { 'lens_model': 'LENSMODEL_OPENCV8', # intrinsics are fx,fy,cx,cy,distortion0,distortion1,.... 'intrinsics': [ 1761.181055, 1761.250444, 1965.706996, 1087.518797, -0.01266096516, 0.03590794372, -0.0002547045941, 0.0005275929652, 0.01968883397, 0.01482863541, -0.0562239888, 0.0500223357,], # extrinsics are rt_fromref 'extrinsics': [ 2e-2, -3e-1, -1e-2, 1., 2, -3., ], 'imagersize': [ 4000, 2200 ] } ''' import io with io.StringIO(string) as f: m = mrcal.cameramodel(f) testutils.confirm_equal( m.intrinsics()[1], [ 1761.181055, 1761.250444, 1965.706996, 1087.518797, -0.01266096516, 0.03590794372, -0.0002547045941, 0.0005275929652, 0.01968883397, 0.01482863541, -0.0562239888, 0.0500223357,], msg="extra spaces don't confuse the parser") testutils.finish() mrcal-2.4.1/test/test-compute-chessboard-corners-parsing.py000077500000000000000000000274341456301662300240460ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Tests the parsing of corners.vnl data ''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils import io corners_all_or_none_noweight = r'''# filename x y frame100-cam1.jpg 0 0 frame100-cam1.jpg 1 0 frame100-cam1.jpg 0 1 frame100-cam1.jpg 1 1 frame100-cam1.jpg 0 2 frame100-cam1.jpg 1 2 frame100-cam2.jpg 10 10 frame100-cam2.jpg 11 10 frame100-cam2.jpg 10 11 frame100-cam2.jpg 11 11 frame100-cam2.jpg 10 12 frame100-cam2.jpg 11 12 frame101-cam1.jpg 20 20 frame101-cam1.jpg 21 20 frame101-cam1.jpg 20 21 frame101-cam1.jpg 21 21 frame101-cam1.jpg 20 22 frame101-cam1.jpg 21 22 frame101-cam2.jpg 30 30 frame101-cam2.jpg 31 30 frame101-cam2.jpg 30 31 frame101-cam2.jpg 31 31 frame101-cam2.jpg 30 32 frame101-cam2.jpg 31 32 frame102-cam1.jpg - - frame102-cam2.jpg 40 40 frame102-cam2.jpg 41 40 frame102-cam2.jpg 40 41 frame102-cam2.jpg 41 41 frame102-cam2.jpg 40 42 frame102-cam2.jpg 41 42 ''' observations_ref = np.empty((5,3,2,3), dtype=float) observations_ref_x = observations_ref[:,:,:,0] observations_ref_y = nps.transpose(observations_ref[:,:,:,1]) observations_ref_x[:] = np.arange(2) observations_ref_y[:] = np.arange(3) observations_ref_w = nps.clump(observations_ref[:,:,:,2], n=3) observations_ref_w[:] = 1.0 # default weight observations_ref_frame = nps.mv(observations_ref[..., :2], 0, -1) observations_ref_frame += np.arange(5)*10 indices_frame_camera_ref = np.array(((0,0), (0,1), (1,0), (1,1), (2,1), ), dtype=np.int32) paths_ref = ("frame100-cam1.jpg", "frame100-cam2.jpg", "frame101-cam1.jpg", "frame101-cam2.jpg", "frame102-cam2.jpg") try: observations, indices_frame_camera, paths = \ mrcal.compute_chessboard_corners(W = 2, H = 3, globs_per_camera = ('frame*-cam1.jpg','frame*-cam2.jpg'), corners_cache_vnl = io.StringIO(corners_all_or_none_noweight)) except Exception as e: observations = f"Error: {e}" indices_frame_camera = f"Error: {e}" testutils.confirm_equal( observations, observations_ref, msg = "observations: all-or-none-no-weight") testutils.confirm_equal( indices_frame_camera, indices_frame_camera_ref, msg = "indices_frame_camera: all-or-none-no-weight") testutils.confirm_equal( paths, paths_ref, msg = "paths: all-or-none-no-weight") ############################################################### corners_all_or_none = r'''# filename x y weight frame100-cam1.jpg 0 0 0.01 frame100-cam1.jpg 1 0 0.02 frame100-cam1.jpg 0 1 0.03 frame100-cam1.jpg 1 1 0.04 frame100-cam1.jpg 0 2 0.05 frame100-cam1.jpg 1 2 0.06 frame100-cam2.jpg 10 10 0.07 frame100-cam2.jpg 11 10 0.08 frame100-cam2.jpg 10 11 0.09 frame100-cam2.jpg 11 11 0.10 frame100-cam2.jpg 10 12 0.11 frame100-cam2.jpg 11 12 0.12 frame101-cam1.jpg 20 20 0.13 frame101-cam1.jpg 21 20 0.14 frame101-cam1.jpg 20 21 0.15 frame101-cam1.jpg 21 21 0.16 frame101-cam1.jpg 20 22 0.17 frame101-cam1.jpg 21 22 0.18 frame101-cam2.jpg 30 30 0.19 frame101-cam2.jpg 31 30 0.20 frame101-cam2.jpg 30 31 0.21 frame101-cam2.jpg 31 31 0.22 frame101-cam2.jpg 30 32 0.23 frame101-cam2.jpg 31 32 0.24 frame102-cam1.jpg - - - frame102-cam2.jpg 40 40 0.25 frame102-cam2.jpg 41 40 0.26 frame102-cam2.jpg 40 41 -2 frame102-cam2.jpg 41 41 0.28 frame102-cam2.jpg 40 42 - frame102-cam2.jpg 41 42 0.30 ''' observations_ref = np.empty((5,3,2,3), dtype=float) observations_ref_x = observations_ref[:,:,:,0] observations_ref_y = nps.transpose(observations_ref[:,:,:,1]) observations_ref_x[:] = np.arange(2) observations_ref_y[:] = np.arange(3) observations_ref_w = nps.clump(observations_ref[:,:,:,2], n=3) observations_ref_w[:] = (np.arange(30) + 1) / 100 observations_ref[4,1,0,2] = -1. observations_ref[4,2,0,2] = -1. observations_ref_frame = nps.mv(observations_ref[..., :2], 0, -1) observations_ref_frame += np.arange(5)*10 indices_frame_camera_ref = np.array(((0,0), (0,1), (1,0), (1,1), (2,1), ), dtype=np.int32) paths_ref = ("frame100-cam1.jpg", "frame100-cam2.jpg", "frame101-cam1.jpg", "frame101-cam2.jpg", "frame102-cam2.jpg") try: observations, indices_frame_camera, paths = \ mrcal.compute_chessboard_corners(W = 2, H = 3, globs_per_camera = ('frame*-cam1.jpg','frame*-cam2.jpg'), corners_cache_vnl = io.StringIO(corners_all_or_none), weight_column_kind = 'weight') except Exception as e: observations = f"Error: {e}" indices_frame_camera = f"Error: {e}" testutils.confirm_equal( observations, observations_ref, msg = "observations: all-or-none") testutils.confirm_equal( indices_frame_camera, indices_frame_camera_ref, msg = "indices_frame_camera: all-or-none") testutils.confirm_equal( paths, paths_ref, msg = "paths: all-or-none") ############################################################### corners_all_or_none_level = r'''# filename x y level frame100-cam1.jpg 0 0 0 frame100-cam1.jpg 1 0 1 frame100-cam1.jpg 0 1 2 frame100-cam1.jpg 1 1 3 frame100-cam1.jpg 0 2 4 frame100-cam1.jpg 1 2 5 frame100-cam2.jpg 10 10 0 frame100-cam2.jpg 11 10 1 frame100-cam2.jpg 10 11 2 frame100-cam2.jpg 11 11 3 frame100-cam2.jpg 10 12 4 frame100-cam2.jpg 11 12 5 frame101-cam1.jpg 20 20 0 frame101-cam1.jpg 21 20 1 frame101-cam1.jpg 20 21 2 frame101-cam1.jpg 21 21 3 frame101-cam1.jpg 20 22 4 frame101-cam1.jpg 21 22 5 frame101-cam2.jpg 30 30 0 frame101-cam2.jpg 31 30 1 frame101-cam2.jpg 30 31 2 frame101-cam2.jpg 31 31 3 frame101-cam2.jpg 30 32 4 frame101-cam2.jpg 31 32 5 frame102-cam1.jpg - - - frame102-cam2.jpg 40 40 0 frame102-cam2.jpg 41 40 1 frame102-cam2.jpg 40 41 -2 frame102-cam2.jpg 41 41 3 frame102-cam2.jpg 40 42 - frame102-cam2.jpg 41 42 5 ''' observations_ref = np.empty((5,3,2,3), dtype=float) observations_ref_x = observations_ref[:,:,:,0] observations_ref_y = nps.transpose(observations_ref[:,:,:,1]) observations_ref_x[:] = np.arange(2) observations_ref_y[:] = np.arange(3) observations_ref_w = nps.clump(observations_ref[:,:,:,2], n=-2) observations_ref_w[:] = np.power(2., -np.arange(6)) observations_ref[4,1,0,2] = -1. observations_ref[4,2,0,2] = -1. observations_ref_frame = nps.mv(observations_ref[..., :2], 0, -1) observations_ref_frame += np.arange(5)*10 indices_frame_camera_ref = np.array(((0,0), (0,1), (1,0), (1,1), (2,1), ), dtype=np.int32) paths_ref = ("frame100-cam1.jpg", "frame100-cam2.jpg", "frame101-cam1.jpg", "frame101-cam2.jpg", "frame102-cam2.jpg") try: observations, indices_frame_camera, paths = \ mrcal.compute_chessboard_corners(W = 2, H = 3, globs_per_camera = ('frame*-cam1.jpg','frame*-cam2.jpg'), corners_cache_vnl = io.StringIO(corners_all_or_none_level), weight_column_kind = 'level') except Exception as e: observations = f"Error: {e}" indices_frame_camera = f"Error: {e}" testutils.confirm_equal( observations, observations_ref, msg = "observations: all-or-none-level") testutils.confirm_equal( indices_frame_camera, indices_frame_camera_ref, msg = "indices_frame_camera: all-or-none-level") testutils.confirm_equal( paths, paths_ref, msg = "paths: all-or-none-level") ############################################################### corners_complicated = r'''# filename x y weight frame100-cam1.jpg 0 0 0.01 frame100-cam1.jpg 1 0 0.02 frame100-cam1.jpg 0 1 0.03 frame100-cam1.jpg 1 1 0.04 frame100-cam1.jpg 0 2 0.05 frame100-cam1.jpg 1 2 0.06 frame100-cam2.jpg 10 10 0.07 frame100-cam2.jpg 11 10 0.08 frame100-cam2.jpg 10 11 0.09 frame100-cam2.jpg 11 11 0.10 # comments and whitespace shouldn't break stuff frame100-cam2.jpg 10 12 0.11 frame100-cam2.jpg 11 12 0.12 frame101-cam1.jpg 20 20 0.13 frame101-cam1.jpg 21 20 0.14 # missing weight should default to 1.0 frame101-cam1.jpg 20 21 # weight of 0 means "ignore point" frame101-cam1.jpg 21 21 0 frame101-cam1.jpg 20 22 0.17 frame101-cam1.jpg 21 22 0.18 frame101-cam2.jpg 30 30 0.19 frame101-cam2.jpg 31 30 0.20 frame101-cam2.jpg 30 31 0.21 frame101-cam2.jpg 31 31 0.22 frame101-cam2.jpg 30 32 0.23 frame101-cam2.jpg 31 32 0.24 frame102-cam1.jpg - - - frame102-cam2.jpg 40 40 0.25 frame102-cam2.jpg 41 40 0.26 frame102-cam2.jpg - - -2 frame102-cam2.jpg 41 41 0.28 frame102-cam2.jpg - - - frame102-cam2.jpg 41 42 0.30 ''' observations_ref = np.empty((5,3,2,3), dtype=float) observations_ref_x = observations_ref[:,:,:,0] observations_ref_y = nps.transpose(observations_ref[:,:,:,1]) observations_ref_x[:] = np.arange(2) observations_ref_y[:] = np.arange(3) observations_ref_frame = nps.mv(observations_ref[..., :2], 0, -1) observations_ref_frame += np.arange(5)*10 observations_ref_w = nps.clump(observations_ref[:,:,:,2], n=3) observations_ref_w[:] = (np.arange(30) + 1) / 100 observations_ref[4,1,0,:] = -1. observations_ref[4,2,0,:] = -1. observations_ref[2,1,0,2] = 1.0 # missing weight in the datafile: use default observations_ref[2,1,1,2] = -1.0 indices_frame_camera_ref = np.array(((0,0), (0,1), (1,0), (1,1), (2,1), ), dtype=np.int32) paths_ref = ("frame100-cam1.jpg", "frame100-cam2.jpg", "frame101-cam1.jpg", "frame101-cam2.jpg", "frame102-cam2.jpg") try: observations, indices_frame_camera, paths = \ mrcal.compute_chessboard_corners(W = 2, H = 3, globs_per_camera = ('frame*-cam1.jpg','frame*-cam2.jpg'), corners_cache_vnl = io.StringIO(corners_complicated), weight_column_kind = 'weight') except Exception as e: observations = f"Error: {e}" indices_frame_camera = f"Error: {e}" testutils.confirm_equal( observations, observations_ref, msg = "observations: complicated") testutils.confirm_equal( indices_frame_camera, indices_frame_camera_ref, msg = "indices_frame_camera: complicated") testutils.confirm_equal( paths, paths_ref, msg = "paths: complicated") testutils.finish() mrcal-2.4.1/test/test-convert-lensmodel.py000077500000000000000000000114401456301662300205730ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Test of the mrcal-convert-lensmodel tool ''' import sys import numpy as np import numpysane as nps import os import subprocess import re import io testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils import tempfile import atexit import shutil workdir = tempfile.mkdtemp() def cleanup(): global workdir try: shutil.rmtree(workdir) workdir = None except: pass atexit.register(cleanup) def check(filename_from, model_from, lensmodel_to, args, *, must_warn_of_aphysical_translation, what, distance = 3): process = \ subprocess.Popen( (f"{testdir}/../mrcal-convert-lensmodel", *args, "--outdir", workdir, lensmodel_to), encoding = 'ascii', stdin = subprocess.PIPE, stdout = subprocess.PIPE, stderr = subprocess.PIPE) with open(filename_from, "r") as f: text_from = f.read() stdout,stderr = process.communicate(input = text_from) if process.returncode != 0: testutils.confirm( False, msg = f"{what}: convert failed: {stderr}" ) else: testutils.confirm( True, msg = f"{what}: convert succeeded" ) have_warn_of_aphysical_translation = \ re.search("WARNING: fitted camera moved by.*aphysically high", stderr) if must_warn_of_aphysical_translation: testutils.confirm( have_warn_of_aphysical_translation, msg = "Expected a warning about an aphysical translation") else: testutils.confirm( not have_warn_of_aphysical_translation, msg = "Expected no warning about an aphysical translation") with io.StringIO(stdout) as f: model_converted = mrcal.cameramodel(f) difflen, diff, q0, implied_Rt10 = \ mrcal.projection_diff( (model_converted, model_from), use_uncertainties = False, distance = distance) icenter = np.array(difflen.shape) // 2 ithird = np.array(difflen.shape) // 3 testutils.confirm_equal( 0, difflen[icenter[0],icenter[1]], eps = 2.0, msg = f"{what}: low-enough diff at the center") testutils.confirm_equal( 0, difflen[ithird[0],ithird[1]], eps = 3.0, msg = f"{what}: low-enough diff at 1/3 from top-left") filename_from = f"{testdir}/data/cam0.splined.cameramodel" model_from = mrcal.cameramodel(filename_from) check( filename_from, model_from, "LENSMODEL_CAHVOR", ("--radius", "1000", "--intrinsics-only", "--sampled", # need multiple attempts to hit the accuracy targets below "--num-trials", "8",), must_warn_of_aphysical_translation = False, what = 'CAHVOR, sampled, intrinsics-only',) check( filename_from, model_from, "LENSMODEL_CAHVOR", ("--radius", "1000", "--sampled", "--distance", "3", # need multiple attempts to hit the accuracy targets below "--num-trials", "8",), must_warn_of_aphysical_translation = True, what = 'CAHVOR, sampled at 3m',) check( filename_from, model_from, "LENSMODEL_CAHVOR", ("--radius", "1000", "--sampled", "--distance", "3000", # need multiple attempts to hit the accuracy targets below "--num-trials", "8",), must_warn_of_aphysical_translation = True, what = 'CAHVOR, sampled at 3000m',) check( filename_from, model_from, "LENSMODEL_CAHVOR", ("--radius", "1000", "--sampled", "--distance", "3000,3", # need multiple attempts to hit the accuracy targets below "--num-trials", "8",), must_warn_of_aphysical_translation = False, what = 'CAHVOR, sampled at 3000m,3m',) # Need a model with optimization_inputs to do non-sampled fits if not os.path.isdir(f"{testdir}/../../mrcal-doc-external"): testutils.print_blue(f"../mrcal-doc-external isn't on this disk. Skipping non-sampled tests") else: filename_from = f"{testdir}/../../mrcal-doc-external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/splined.cameramodel" model_from = mrcal.cameramodel(filename_from) check( filename_from, model_from, "LENSMODEL_OPENCV8", ("--radius", "-1000"), must_warn_of_aphysical_translation = False, what = 'non-sampled fit to opencv8',) testutils.finish() mrcal-2.4.1/test/test-extrinsics-moved-since-calibration.py000077500000000000000000000045021456301662300240230ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Checks mrcal._extrinsics_moved_since_calibration() ''' import sys import argparse import re import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils import numpy as np import numpysane as nps from test_calibration_helpers import calibration_baseline ############# Set up my world, and compute all the perfect positions, pixel ############# observations of everything object_spacing = 0.1 object_width_n = 10 object_height_n = 9 calobject_warp_true = np.array((0.002, -0.005)) model = 'opencv4' Ncameras = 4 Nframes = 10 fixedframes = False extrinsics_rt_fromref_true = \ np.array(((0, 0, 0, 0, 0, 0), (0.08, 0.2, 0.02, 1., 0.9, 0.1), (0.01, 0.07, 0.2, 2.1, 0.4, 0.2), (-0.1, 0.08, 0.08, 3.4, 0.2, 0.1), )) optimization_inputs_baseline, \ models_true, models_baseline, \ indices_frame_camintrinsics_camextrinsics, \ lensmodel, Nintrinsics, imagersizes, \ intrinsics_true, extrinsics_true_mounted, frames_true, \ observations_true, \ Nframes = \ calibration_baseline(model, Ncameras, Nframes, None, object_width_n, object_height_n, object_spacing, extrinsics_rt_fromref_true, calobject_warp_true, fixedframes, testdir) for i in range(len(models_baseline)): testutils.confirm(not models_baseline[i]._extrinsics_moved_since_calibration(), msg = f"Camera {i} unmoved") extrinsics_rt_fromref = extrinsics_rt_fromref_true.copy() extrinsics_rt_fromref[:,-1] += 1e-3 for i in range(len(models_baseline)): models_baseline[i].extrinsics_rt_fromref(extrinsics_rt_fromref[i]) for i in range(len(models_baseline)): testutils.confirm(models_baseline[i]._extrinsics_moved_since_calibration(), msg = f"Camera {i} moved") testutils.finish() mrcal-2.4.1/test/test-gradients.py000077500000000000000000000237531456301662300171250ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Tests gradients reported by the C code Here I make sure that the gradients reported by the projection function do describe the gradient of the values reported by that function. This test does NOT make sure that the values are RIGHT, just that the values are consistent with the gradients. test-projections.py looks at the values only, so together these two tests validate the projection functionality ''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils import subprocess from io import StringIO import re tests = ( # mostly all "LENSMODEL_PINHOLE extrinsics frames intrinsic-core intrinsic-distortions calobject-warp", "LENSMODEL_PINHOLE extrinsics frames intrinsic-distortions", "LENSMODEL_PINHOLE extrinsics frames intrinsic-core", "LENSMODEL_PINHOLE extrinsics frames", "LENSMODEL_STEREOGRAPHIC extrinsics frames intrinsic-core intrinsic-distortions calobject-warp", "LENSMODEL_STEREOGRAPHIC extrinsics intrinsic-distortions", "LENSMODEL_STEREOGRAPHIC extrinsics frames intrinsic-core", "LENSMODEL_STEREOGRAPHIC frames", "LENSMODEL_CAHVOR extrinsics frames intrinsic-core intrinsic-distortions calobject-warp", "LENSMODEL_CAHVOR extrinsics frames intrinsic-distortions", "LENSMODEL_CAHVOR extrinsics frames intrinsic-core", "LENSMODEL_CAHVOR extrinsics frames", "LENSMODEL_OPENCV4 extrinsics frames intrinsic-core intrinsic-distortions calobject-warp", "LENSMODEL_OPENCV4 extrinsics frames intrinsic-distortions", "LENSMODEL_OPENCV4 extrinsics frames intrinsic-core", "LENSMODEL_OPENCV4 extrinsics frames", # partials; cahvor "LENSMODEL_CAHVOR frames intrinsic-core intrinsic-distortions", "LENSMODEL_CAHVOR frames intrinsic-distortions", "LENSMODEL_CAHVOR frames intrinsic-core", "LENSMODEL_CAHVOR frames", "LENSMODEL_CAHVOR extrinsics intrinsic-core intrinsic-distortions", "LENSMODEL_CAHVOR extrinsics intrinsic-distortions", "LENSMODEL_CAHVOR extrinsics intrinsic-core", "LENSMODEL_CAHVOR extrinsics", "LENSMODEL_CAHVOR intrinsic-core intrinsic-distortions", "LENSMODEL_CAHVOR intrinsic-distortions", "LENSMODEL_CAHVOR intrinsic-core", # partials; opencv4 "LENSMODEL_OPENCV4 frames intrinsic-core intrinsic-distortions", "LENSMODEL_OPENCV4 frames intrinsic-distortions", "LENSMODEL_OPENCV4 frames intrinsic-core", "LENSMODEL_OPENCV4 frames", "LENSMODEL_OPENCV4 extrinsics intrinsic-core intrinsic-distortions", "LENSMODEL_OPENCV4 extrinsics intrinsic-distortions", "LENSMODEL_OPENCV4 extrinsics intrinsic-core", "LENSMODEL_OPENCV4 extrinsics", "LENSMODEL_OPENCV4 intrinsic-core intrinsic-distortions", "LENSMODEL_OPENCV4 intrinsic-distortions", "LENSMODEL_OPENCV4 intrinsic-core", # splined "LENSMODEL_SPLINED_STEREOGRAPHIC_3 extrinsics intrinsic-distortions", "LENSMODEL_SPLINED_STEREOGRAPHIC_3 frames extrinsics intrinsic-distortions calobject-warp", "LENSMODEL_SPLINED_STEREOGRAPHIC_2 extrinsics intrinsic-distortions", "LENSMODEL_SPLINED_STEREOGRAPHIC_2 frames extrinsics intrinsic-distortions calobject-warp", ) def get_variable_map(s): r'''Generates a perl snippet to classify a variable The output classes are 0 intrinsics-core 1 intrinsics-distortions 2 extrinsics 3 frames 4 discrete points 5 calobject_warp''' m = re.search("^## Intrinsics: (\d+) variables per camera \((\d+) for the core, (\d+) for the rest; (\d+) total\). Starts at variable (-?\d+)", s, re.M) NintrinsicsPerCamera = int(m.group(1)) NintrinsicsCorePerCamera = int(m.group(2)) NintrinsicsDistortionsPerCamera = int(m.group(3)) Nvar_intrinsics = int(m.group(4)) ivar0_intrinsics = int(m.group(5)) m = re.search("^## Extrinsics: \d+ variables per camera for all cameras except camera 0 \((\d+) total\). Starts at variable (-?\d+)", s, re.M) Nvar_extrinsics = int(m.group(1)) ivar0_extrinsics = int(m.group(2)) m = re.search("^## Frames: \d+ variables per frame \((\d+) total\). Starts at variable (-?\d+)", s, re.M) Nvar_frames = int(m.group(1)) ivar0_frames = int(m.group(2)) m = re.search("^## Discrete points: \d+ variables per point \((\d+) total\). Starts at variable (-?\d+)", s, re.M) Nvar_points = int(m.group(1)) ivar0_points = int(m.group(2)) m = re.search("^## calobject_warp: (\d+) variables. Starts at variable (-?\d+)", s, re.M) Nvar_calobject_warp = int(m.group(1)) ivar0_calobject_warp = int(m.group(2)) intrinsics_any = f"ivar >= {ivar0_intrinsics} && ivar < {ivar0_intrinsics} +{Nvar_intrinsics}" extrinsics = f"ivar >= {ivar0_extrinsics} && ivar < {ivar0_extrinsics} +{Nvar_extrinsics}" frames = f"ivar >= {ivar0_frames} && ivar < {ivar0_frames} +{Nvar_frames}" points = f"ivar >= {ivar0_points} && ivar < {ivar0_points} +{Nvar_points}" calobject_warp = f"ivar >= {ivar0_calobject_warp} && ivar < {ivar0_calobject_warp}+{Nvar_calobject_warp}" if NintrinsicsCorePerCamera == 0: intrinsics_classify = 1 else: intrinsics_classify = f"(ivar - {ivar0_intrinsics}) % {NintrinsicsPerCamera} < {NintrinsicsCorePerCamera} ? 0 : 1" err = 'die("Could not classify variable ivar. Giving up")' return f"({calobject_warp}) ? 5 : (({points}) ? 4 : (({frames})? 3 : (({extrinsics}) ? 2 : (({intrinsics_any}) ? ({intrinsics_classify}) : {err}))))" def vartype_name(i): d = { 0: "intrinsics-core", 1: "intrinsics-distortions", 2: "extrinsics", 3: "frames", 4: "discrete points", 5: "calobject_warp" } return d[i] def get_measurement_map(s): r'''Generates a perl snippet to classify a measurement The output classes are 0 boards 1 points 2 regularization''' m = re.search("^## Measurement calobjects: (\d+) measurements. Starts at measurement (\d+)", s, re.M) Nmeas_boards = m.group(1) imeas0_boards = m.group(2) m = re.search("^## Measurement points: (\d+) measurements. Starts at measurement (\d+)", s, re.M) Nmeas_points = m.group(1) imeas0_points = m.group(2) m = re.search("^## Measurement regularization: (\d+) measurements. Starts at measurement (\d+)", s, re.M) Nmeas_regularization = m.group(1) imeas0_regularization = m.group(2) boards = f"imeasurement >= {imeas0_boards} && imeas < {imeas0_boards} + {Nmeas_boards}" points = f"imeasurement >= {imeas0_points} && imeas < {imeas0_points} + {Nmeas_points}" regularization = f"imeasurement >= {imeas0_regularization} && imeas < {imeas0_regularization} + {Nmeas_regularization}" err = 'die("Could not classify measurement imeasurement. Giving up")' return f"({regularization}) ? 2 : (({points}) ? 1 : (({boards})? 0 : {err}))" def meastype_name(i): d = { 0: "boards", 1: "points", 2: "regularization" } return d[i] for test in tests: try: full = \ subprocess.check_output( [f"{testdir}/../test-gradients"] + test.split(), shell = False, encoding = 'ascii') except Exception as e: testutils.confirm(False, msg=f"failed to check gradients for '{test}'") continue varmap = get_variable_map(full) measmap = get_measurement_map(full) cut = subprocess.check_output( ("vnl-filter", "gradient_reported || gradient_observed", "--perl", # I compute error_relative myself because I # want to add an extra eps. This smoothes # out reported relative gradient errors for # tiny gradients. If they're tiny I could # accidentally trigger an error otherwise "-p", "error_relative=error/((abs(gradient_reported)+abs(gradient_observed))/2. + 1e-3)", "-p", f"type={varmap},meastype={measmap}"), input=full, encoding='ascii') with StringIO(cut) as f: err_class = np.loadtxt(f) # I now have all the relative errors and all the variable, measurement # classifications. I check each class for mismatches separately. Each class # allows a small number of outliers. The reason I check each class # separately is because different classses have very different point. # Looking at everything together could result in ALL of one class being # considered an outlier, and the test would pass i_thisvar_all = [err_class[:,1] == vartype for vartype in range(6)] i_thismeas_all = [err_class[:,2] == meastype for meastype in range(3)] for vartype in range(6): for meastype in range(3): i = i_thisvar_all[vartype] * i_thismeas_all[meastype] err = err_class[ i, 0 ] if len(err) <= 0: continue err_relative_99percentile = testutils.percentile_compat(err, 99, interpolation='higher') testutils.confirm(err_relative_99percentile < 1e-3, f"99%-percentile relative error={err_relative_99percentile} for vars {vartype_name(vartype)}, meas {meastype_name(meastype)} in {test}") testutils.finish() mrcal-2.4.1/test/test-graft-models.py000077500000000000000000000075571456301662300175350ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Test of the mrcal-graft-models tool The basic usage of the tool is simple, but it also supports a non-trivial mode where it applies an implied transformation. I make sure to test that here ''' import sys import numpy as np import numpysane as nps import os import subprocess testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils import tempfile import atexit import shutil workdir = tempfile.mkdtemp() def cleanup(): global workdir try: shutil.rmtree(workdir) workdir = None except: pass atexit.register(cleanup) rt_0r = np.array((1., 2., 3., 4., 5., 6.)) rt_1r = np.array((0.8, -0.01, -0.2, 2., -4., 2.)) imagersize = np.array((2000, 1000), dtype=int) cxy_center = (imagersize-1.)/2. pitch_y = 100. cxy_pitched = cxy_center + np.array((0., pitch_y)) # very long lenses. I want rotation to look very much like panning fxycxy0 = nps.glue( np.array(( 50000., 50000.)), cxy_pitched, axis=-1) fxycxy1 = nps.glue( np.array(( 50000., 50000.)), cxy_center, axis=-1) model0 = mrcal.cameramodel( intrinsics = ('LENSMODEL_PINHOLE', fxycxy0), imagersize = imagersize, extrinsics_rt_fromref = rt_0r ) model1 = mrcal.cameramodel( intrinsics = ('LENSMODEL_PINHOLE', fxycxy1), imagersize = imagersize, extrinsics_rt_fromref = rt_1r ) filename0 = f"{workdir}/model0.cameramodel" filename1 = f"{workdir}/model1.cameramodel" model0.write(filename0) model1.write(filename1) # Basic test. Combine intrinsics and extrinsics without fitting any extra # transform out = subprocess.check_output( (f"{testdir}/../mrcal-graft-models", filename0, filename1), encoding = 'ascii', stderr = subprocess.DEVNULL) filename01 = f"{workdir}/model01.cameramodel" with open(filename01, "w") as f: print(out, file=f) model01 = mrcal.cameramodel(filename01) testutils.confirm_equal(model01.intrinsics()[1], model0.intrinsics()[1], msg = f"Basic grafted intrinsics match", eps = 1.0e-6) testutils.confirm_equal(model01.extrinsics_rt_fromref(), model1.extrinsics_rt_fromref(), msg = f"Basic grafted extrinsics match", eps = 1.0e-6) # More complicated test. I want to compensate for the different intrinsics with # modified extrinsics such that the old-intrinsics and new-intrinsics project # world points to the same place out = subprocess.check_output( (f"{testdir}/../mrcal-graft-models", '--radius', '-1', filename0, filename1), encoding = 'ascii', stderr = subprocess.DEVNULL) filename01_compensated = f"{workdir}/model01_compensated.cameramodel" with open(filename01_compensated, "w") as f: print(out, file=f) model01_compensated = mrcal.cameramodel(filename01_compensated) p1 = np.array((11., 17., 10000.)) pref = mrcal.transform_point_rt( model1.extrinsics_rt_toref(), p1) q = mrcal.project( mrcal.transform_point_rt( model1.extrinsics_rt_fromref(), pref ), *model1.intrinsics()) q_compensated = \ mrcal.project( mrcal.transform_point_rt( model01_compensated.extrinsics_rt_fromref(), pref), *model01_compensated.intrinsics()) testutils.confirm_equal(q_compensated, q, msg = f"Compensated projection ended up in the same place", eps = 0.1) testutils.finish() mrcal-2.4.1/test/test-harness.h000066400000000000000000000075031456301662300163770ustar00rootroot00000000000000#pragma once // Apparently I need this in MSVC to get constants #define _USE_MATH_DEFINES #include #include #include #define GREEN "\x1b[32m" #define RED "\x1b[31m" #define COLOR_RESET "\x1b[0m" // global variable for the results tracking int Ntests = 0; int NtestsFailed = 0; __attribute__((unused)) static void _confirm(bool x, const char* what_x, int where) { Ntests++; if(x) printf(GREEN "OK: %s is true" COLOR_RESET"\n", what_x); else { printf(RED "FAIL on line %d: %s is false" COLOR_RESET"\n", where, what_x); NtestsFailed++; } } #define confirm(x) _confirm(x, #x, __LINE__) __attribute__((unused)) static void _confirm_eq_int(int x, int xref, const char* what_x, const char* what_xref, int where) { Ntests++; if(x == xref) printf(GREEN "OK: %s == %s, as it should" COLOR_RESET"\n", what_x, what_xref); else { printf(RED "FAIL on line %d: %s != %s: %d != %d" COLOR_RESET"\n", where, what_x, what_xref, x, xref); NtestsFailed++; } } #define confirm_eq_int(x,xref) _confirm_eq_int(x, xref, #x, #xref, __LINE__) __attribute__((unused)) static void _confirm_eq_int_max_array(const int* x, const int* xref, int N, const char* what_x, const char* what_xref, int where) { Ntests++; for(int i=0; i worst_err) worst_err = err; } Ntests++; if(worst_err < eps) printf(GREEN "OK: %s ~ %s, as it should" COLOR_RESET"\n", what_x, what_xref); else { printf(RED "FAIL on line %d: %s !~ %s" COLOR_RESET"\n", where, what_x, what_xref); NtestsFailed++; } } #define confirm_eq_double_max_array(x,xref, N, eps) \ _confirm_eq_double_max_array(x, xref, N, #x, #xref, eps, __LINE__) #define TEST_FOOTER() \ if(NtestsFailed == 0) \ { \ printf(GREEN "%s: all %d tests passed" COLOR_RESET "\n", argv[0], Ntests); \ return 0; \ } \ else \ { \ printf(RED "%s: %d/%d tests failed" COLOR_RESET "\n", argv[0], NtestsFailed, Ntests); \ return 1; \ } mrcal-2.4.1/test/test-lensmodel-string-manipulation.c000066400000000000000000000210701456301662300227060ustar00rootroot00000000000000#include #include #include #include "../mrcal.h" #include "test-harness.h" static bool modelHasCore_fxfycxcy( const mrcal_lensmodel_t* lensmodel ) { mrcal_lensmodel_metadata_t meta = mrcal_lensmodel_metadata(lensmodel); return meta.has_core; } #define COMPARE_CONFIG_ELEMENT(name, type, pybuildvaluecode, PRIcode,SCNcode, bitfield, cookie) \ if(config_a->name != config_b->name) return false; static bool LENSMODEL_CAHVORE__compare_config( const mrcal_LENSMODEL_CAHVORE__config_t* config_a, const mrcal_LENSMODEL_CAHVORE__config_t* config_b) { MRCAL_LENSMODEL_CAHVORE_CONFIG_LIST(COMPARE_CONFIG_ELEMENT, ); return true; } static bool LENSMODEL_SPLINED_STEREOGRAPHIC__compare_config( const mrcal_LENSMODEL_SPLINED_STEREOGRAPHIC__config_t* config_a, const mrcal_LENSMODEL_SPLINED_STEREOGRAPHIC__config_t* config_b) { MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC_CONFIG_LIST(COMPARE_CONFIG_ELEMENT, ); return true; } static bool eq_lensmodel(const mrcal_lensmodel_t* a, const mrcal_lensmodel_t* b) { if(a->type != b->type) return false; #define COMPARE_CONFIG_RETURN_FALSE_IF_NEQ(s,n) \ if( a->type == MRCAL_##s ) \ { \ const mrcal_##s##__config_t* config_a = &a->s##__config; \ const mrcal_##s##__config_t* config_b = &b->s##__config; \ \ if(!s##__compare_config(config_a, config_b)) \ return false; \ } MRCAL_LENSMODEL_WITHCONFIG_STATIC_NPARAMS_LIST( COMPARE_CONFIG_RETURN_FALSE_IF_NEQ ); MRCAL_LENSMODEL_WITHCONFIG_DYNAMIC_NPARAMS_LIST( COMPARE_CONFIG_RETURN_FALSE_IF_NEQ ); return true; } static void _confirm_lensmodel(bool result, mrcal_lensmodel_t* x, mrcal_lensmodel_t xref, const char* what_x, const char* what_xref, int where) { Ntests++; if(eq_lensmodel(x, &xref)) printf(GREEN "OK: equal %s and %s" COLOR_RESET"\n", what_x, what_xref); else { printf(RED "FAIL on line %d: NOT equal %s and %s" COLOR_RESET"\n", where, what_x, what_xref); NtestsFailed++; } } #define confirm_lensmodel(x,xref) _confirm_lensmodel(x, &lensmodel, xref, #x, #xref, __LINE__) static void _confirm_lensmodel_name(const char* x, const char* xref, int where) { Ntests++; if(0 == strcmp(x,xref)) printf(GREEN "OK: equal %s and %s" COLOR_RESET"\n", x, xref); else { printf(RED "FAIL on line %d: NOT equal %s and %s" COLOR_RESET"\n", where, x, xref); NtestsFailed++; } } #define confirm_lensmodel_name(x,xref) _confirm_lensmodel_name(x, xref, __LINE__) int main(int argc, char* argv[]) { mrcal_lensmodel_t ref; mrcal_lensmodel_t lensmodel; confirm_lensmodel( mrcal_lensmodel_from_name(&lensmodel, "LENSMODEL_CAHVOR"), (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_CAHVOR} ); confirm_lensmodel( mrcal_lensmodel_from_name(&lensmodel, "LENSMODEL_ABCD"), (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_INVALID_TYPE} ); confirm_lensmodel( mrcal_lensmodel_from_name(&lensmodel, "LENSMODEL_SPLINED_STEREOGRAPHIC"), (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_INVALID_MISSINGCONFIG} ); confirm_lensmodel( mrcal_lensmodel_from_name(&lensmodel, "LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=30_Ny=20_fov_x_deg=200_"), (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_INVALID_BADCONFIG} ); confirm_lensmodel( mrcal_lensmodel_from_name(&lensmodel, "LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=30_Ny=20"), (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_INVALID_BADCONFIG} ); confirm_lensmodel( mrcal_lensmodel_from_name(&lensmodel, "LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=30_Ny=20__"), (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_INVALID_BADCONFIG} ); confirm_lensmodel( mrcal_lensmodel_from_name(&lensmodel, "LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=30_Ny=20_fov_x_deg=200 "), (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_INVALID_BADCONFIG} ); confirm_lensmodel( mrcal_lensmodel_from_name(&lensmodel, "LENSMODEL_SPLINED_STEREOGRAPHIC__order=3_Nx=30_Ny=20_fov_x_deg=200"), (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_INVALID_BADCONFIG} ); confirm_lensmodel( mrcal_lensmodel_from_name(&lensmodel, "LENSMODEL_SPLINED_STEREOGRAPHICorder=3_Nx=30_Ny=20_fov_x_deg=200"), (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_INVALID_TYPE} ); ref = (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_CAHVORE, .LENSMODEL_CAHVORE__config = { .linearity = 0.13 }}; confirm_lensmodel( mrcal_lensmodel_from_name(&lensmodel, "LENSMODEL_CAHVORE_linearity=0.13"), ref ); ref = (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC, .LENSMODEL_SPLINED_STEREOGRAPHIC__config = { .order = 3, .Nx = 30, .Ny = 20, .fov_x_deg = 200 }}; confirm_lensmodel( mrcal_lensmodel_from_name(&lensmodel, "LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=30_Ny=20_fov_x_deg=200"), ref ); confirm_lensmodel_name( mrcal_lensmodel_name_unconfigured(&(mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_CAHVOR}), "LENSMODEL_CAHVOR" ); confirm_lensmodel_name( mrcal_lensmodel_name_unconfigured(&(mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_CAHVORE}), "LENSMODEL_CAHVORE_linearity=..." ); char buf[1024]; char buf_small[2]; confirm(mrcal_lensmodel_name(buf, sizeof(buf), &(mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_CAHVOR})); confirm_lensmodel_name( buf, "LENSMODEL_CAHVOR" ); confirm(mrcal_lensmodel_name(buf, sizeof(buf), &(mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_CAHVORE, .LENSMODEL_CAHVORE__config = {.linearity = 0.12}})); confirm_lensmodel_name( buf, "LENSMODEL_CAHVORE_linearity=0.12" ); confirm(!mrcal_lensmodel_name(buf_small, sizeof(buf_small), &(mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_CAHVOR})); confirm(!mrcal_lensmodel_name(buf_small, sizeof(buf_small), &(mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_CAHVORE, .LENSMODEL_CAHVORE__config = {.linearity = 0.12}})); confirm_lensmodel_name( mrcal_lensmodel_name_unconfigured(&(mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC}), "LENSMODEL_SPLINED_STEREOGRAPHIC_order=..._Nx=..._Ny=..._fov_x_deg=..." ); confirm(mrcal_lensmodel_name(buf, sizeof(buf), &(mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC})); confirm_lensmodel_name( buf, "LENSMODEL_SPLINED_STEREOGRAPHIC_order=0_Nx=0_Ny=0_fov_x_deg=0" ); ref = (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC, .LENSMODEL_SPLINED_STEREOGRAPHIC__config = { .order = 3, .Nx = 30, .Ny = 20, .fov_x_deg = 200 }}; confirm(mrcal_lensmodel_name(buf, sizeof(buf), &ref)); confirm_lensmodel_name( buf, "LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=30_Ny=20_fov_x_deg=200" ); confirm( modelHasCore_fxfycxcy(&(mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_CAHVOR})); confirm( modelHasCore_fxfycxcy(&(mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_OPENCV8})); confirm( modelHasCore_fxfycxcy(&(mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC})); confirm_eq_int(mrcal_lensmodel_num_params(&(mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_CAHVOR}), 9); confirm_eq_int(mrcal_lensmodel_num_params(&(mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_OPENCV8}), 12); confirm_eq_int(mrcal_lensmodel_num_params(&(mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC, .LENSMODEL_SPLINED_STEREOGRAPHIC__config = { .order = 3, .Nx = 30, .Ny = 20, .fov_x_deg = 200 }}), 4 + 30*20*2); TEST_FOOTER(); } mrcal-2.4.1/test/test-linearizations.py000077500000000000000000000307471456301662300202010ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Linearization test Make sure the linearization assumptions used in the uncertainty computations hold. The expressions are derived in the docstring for mrcal.projection_uncertainty() ''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import copy import testutils from test_calibration_helpers import sample_dqref # I want the RNG to be deterministic np.random.seed(0) ############# Set up my world, and compute all the perfect positions, pixel ############# observations of everything models_ref = ( mrcal.cameramodel(f"{testdir}/data/cam0.opencv8.cameramodel"), mrcal.cameramodel(f"{testdir}/data/cam0.opencv8.cameramodel"), mrcal.cameramodel(f"{testdir}/data/cam1.opencv8.cameramodel"), mrcal.cameramodel(f"{testdir}/data/cam1.opencv8.cameramodel") ) imagersizes = nps.cat( *[m.imagersize() for m in models_ref] ) lensmodel = models_ref[0].intrinsics()[0] # I have opencv8 models_ref, but let me truncate to opencv4 models_ref to keep this # simple and fast lensmodel = 'LENSMODEL_OPENCV4' for m in models_ref: m.intrinsics( intrinsics = (lensmodel, m.intrinsics()[1][:8])) Nintrinsics = mrcal.lensmodel_num_params(lensmodel) Ncameras = len(models_ref) Ncameras_extrinsics = Ncameras - 1 Nframes = 50 models_ref[0].extrinsics_rt_fromref(np.zeros((6,), dtype=float)) models_ref[1].extrinsics_rt_fromref(np.array((0.08,0.2,0.02, 1., 0.9,0.1))) models_ref[2].extrinsics_rt_fromref(np.array((0.01,0.07,0.2, 2.1,0.4,0.2))) models_ref[3].extrinsics_rt_fromref(np.array((-0.1,0.08,0.08, 4.4,0.2,0.1))) pixel_uncertainty_stdev = 1.5 object_spacing = 0.1 object_width_n = 10 object_height_n = 9 calobject_warp_ref = np.array((0.002, -0.005)) # shapes (Nframes, Ncameras, Nh, Nw, 2), # (Nframes, 4,3) q_ref,Rt_ref_board_ref = \ mrcal.synthesize_board_observations(models_ref, object_width_n = object_width_n, object_height_n = object_height_n, object_spacing = object_spacing, calobject_warp = calobject_warp_ref, rt_ref_boardcenter = np.array((0., 0., 0., -2, 0, 4.0)), rt_ref_boardcenter__noiseradius = np.array((np.pi/180.*30., np.pi/180.*30., np.pi/180.*20., 2.5, 2.5, 2.0)), Nframes = Nframes) ############# I have perfect observations in q_ref. I corrupt them by noise # weight has shape (Nframes, Ncameras, Nh, Nw), weight01 = (np.random.rand(*q_ref.shape[:-1]) + 1.) / 2. # in [0,1] weight0 = 0.2 weight1 = 1.0 weight = weight0 + (weight1-weight0)*weight01 # I want observations of shape (Nframes*Ncameras, Nh, Nw, 3) where each row is # (x,y,weight) observations_ref = nps.clump( nps.glue(q_ref, nps.dummy(weight,-1), axis=-1), n=2) # These are perfect intrinsics_ref = nps.cat( *[m.intrinsics()[1] for m in models_ref] ) extrinsics_ref = nps.cat( *[m.extrinsics_rt_fromref() for m in models_ref[1:]] ) if extrinsics_ref.size == 0: extrinsics_ref = np.zeros((0,6), dtype=float) frames_ref = mrcal.rt_from_Rt(Rt_ref_board_ref) # Dense observations. All the cameras see all the boards indices_frame_camera = np.zeros( (Nframes*Ncameras, 2), dtype=np.int32) indices_frame = indices_frame_camera[:,0].reshape(Nframes,Ncameras) indices_frame.setfield(nps.outer(np.arange(Nframes, dtype=np.int32), np.ones((Ncameras,), dtype=np.int32)), dtype = np.int32) indices_camera = indices_frame_camera[:,1].reshape(Nframes,Ncameras) indices_camera.setfield(nps.outer(np.ones((Nframes,), dtype=np.int32), np.arange(Ncameras, dtype=np.int32)), dtype = np.int32) indices_frame_camintrinsics_camextrinsics = \ nps.glue(indices_frame_camera, indices_frame_camera[:,(1,)] - 1, axis=-1) # Add a bit of noise to make my baseline not perfect _,observations_baseline = sample_dqref(observations_ref, pixel_uncertainty_stdev) baseline = \ dict(intrinsics = intrinsics_ref, extrinsics_rt_fromref = extrinsics_ref, frames_rt_toref = frames_ref, points = None, observations_board = observations_baseline, indices_frame_camintrinsics_camextrinsics = indices_frame_camintrinsics_camextrinsics, observations_point = None, indices_point_camintrinsics_camextrinsics = None, lensmodel = lensmodel, do_optimize_calobject_warp = True, calobject_warp = calobject_warp_ref, do_optimize_intrinsics_core = True, do_optimize_intrinsics_distortions = True, do_optimize_extrinsics = True, imagersizes = imagersizes, calibration_object_spacing = object_spacing, do_apply_regularization = True) mrcal.optimize(**baseline, do_apply_outlier_rejection = False) # Done setting up. I'll be looking at tiny motions off the baseline Nframes = len(frames_ref) Ncameras = len(intrinsics_ref) lensmodel = baseline['lensmodel'] Nintrinsics = mrcal.lensmodel_num_params(lensmodel) Nmeasurements_boards = mrcal.num_measurements_boards(**baseline) Nmeasurements_regularization = mrcal.num_measurements_regularization(**baseline) b0,x0,J0 = mrcal.optimizer_callback(no_factorization = True, **baseline)[:3] J0 = J0.toarray() ########################################################################### # First a very basic gradient check. Looking at an arbitrary camera's # intrinsics. The test-gradients tool does this much more thoroughly optimization_inputs = copy.deepcopy(baseline) db_packed = np.random.randn(len(b0)) * 1e-9 mrcal.ingest_packed_state(b0 + db_packed, **optimization_inputs) x1 = mrcal.optimizer_callback(no_factorization = True, no_jacobian = True, **optimization_inputs)[1] dx_observed = x1 - x0 dx_predicted = nps.inner(J0, db_packed) testutils.confirm_equal( dx_predicted, dx_observed, eps = 1e-1, worstcase = True, relative = True, msg = "Trivial, sanity-checking gradient check") if 0: import gnuplotlib as gp gp.plot( nps.cat(dx_predicted, dx_observed,), _with='lines', legend=np.arange(2), _set = mrcal.plotoptions_measurement_boundaries(**optimization_inputs), wait=1) ########################################################################### # We're supposed to be at the optimum. E = norm2(x) ~ norm2(x0 + J db) = # norm2(x0) + 2 dbt Jt x0 + norm2(J db). At the optimum Jt x0 = 0 -> E = # norm2(x0) + norm2(J db). dE = norm2(J db) = norm2(dx_predicted) x_predicted = x0 + dx_predicted dE = nps.norm2(x1) - nps.norm2(x0) dE_predicted = nps.norm2(dx_predicted) testutils.confirm_equal( dE_predicted, dE, eps = 1e-3, relative = True, msg = "diff(E) predicted") # At the optimum dE/db = 0 -> xtJ = 0 xtJ0 = nps.inner(nps.transpose(J0),x0) mrcal.pack_state(xtJ0, **optimization_inputs) testutils.confirm_equal( xtJ0, 0, eps = 1.5e-2, worstcase = True, msg = "dE/db = 0 at the optimum: original") ########################################################################### # I perturb my input observation vector qref by dqref. noise_for_gradients = 1e-3 dqref,observations_perturbed = sample_dqref(baseline['observations_board'], noise_for_gradients) optimization_inputs = copy.deepcopy(baseline) optimization_inputs['observations_board'] = observations_perturbed mrcal.optimize(**optimization_inputs, do_apply_outlier_rejection=False) b1,x1,J1 = mrcal.optimizer_callback(no_factorization = True, **optimization_inputs)[:3] J1 = J1.toarray() dx_observed = x1-x0 db_observed = b1-b0 w = observations_perturbed[...,2] w[w < 0] = 0 # outliers have weight=0 w = np.ravel(nps.mv(nps.cat(w,w),0,-1)) # each weight controls x,y xtJ1 = nps.inner(nps.transpose(J1),x1) mrcal.pack_state(xtJ0, **optimization_inputs) testutils.confirm_equal( xtJ1, 0, eps = 1e-2, worstcase = True, msg = "dE/db = 0 at the optimum: perturbed") # I added noise reoptimized, did dx do the expected thing? # I should have # x(b+db, qref+dqref) = x + J db + dx/dqref dqref # -> x1-x0 ~ J db + dx/dqref dqref # x[measurements] = (q - qref) * weight # -> dx/dqref = -diag(weight) dx_predicted = nps.inner(J0,db_observed) dx_predicted[:Nmeasurements_boards] -= w * dqref.ravel() # plot_dx = gp.gnuplotlib( title = "dx predicted,observed", # _set = f'arrow nohead from {Nmeasurements_boards},graph 0 to {Nmeasurements_boards},graph 1') # plot_dx.plot( (nps.cat(dx_observed,dx_predicted), # dict(legend = np.array(('observed','predicted')), # _with = 'lines')), # (dx_observed-dx_predicted, # dict(legend = "err", # _with = "lines lw 2", # y2=1))) testutils.confirm_equal( dx_predicted, dx_observed, eps = 1e-6, worstcase = True, msg = "dx follows the prediction") # The effect on the # parameters should be db = M dqref. Where M = inv(JtJ) Jobservationst W M = np.linalg.solve( nps.matmult(nps.transpose(J0),J0), nps.transpose(J0[:Nmeasurements_boards, :]) ) * w db_predicted = nps.matmult( dqref.ravel(), nps.transpose(M)).ravel() istate0_frames = mrcal.state_index_frames (0, **baseline) istate0_calobject_warp = mrcal.state_index_calobject_warp(**baseline) istate0_extrinsics = mrcal.state_index_extrinsics(0, **baseline) if istate0_extrinsics is None: istate0_extrinsics = istate0_frames slice_intrinsics = slice(0, istate0_extrinsics) slice_extrinsics = slice(istate0_extrinsics, istate0_frames) slice_frames = slice(istate0_frames, istate0_calobject_warp) # These thresholds look terrible. And they are. But I'm pretty sure this is # working properly. Look at the plots: if 0: import gnuplotlib as gp plot_db = gp.gnuplotlib( title = "db predicted,observed", _set = mrcal.plotoptions_state_boundaries(**optimization_inputs)) plot_db.plot( (nps.cat(db_observed,db_predicted), dict(legend = np.array(('observed','predicted')), _with = 'linespoints')), (db_observed-db_predicted, dict(legend = "err", _with = "lines lw 2", y2=1))) plot_db.wait() testutils.confirm_equal( db_predicted[slice_intrinsics], db_observed [slice_intrinsics], percentile = 80, eps = 0.2, msg = f"Predicted db from dqref: intrinsics") testutils.confirm_equal( db_predicted[slice_extrinsics], db_observed [slice_extrinsics], relative = True, percentile = 80, eps = 0.2, msg = f"Predicted db from dqref: extrinsics") testutils.confirm_equal( db_predicted[slice_frames], db_observed [slice_frames], percentile = 80, eps = 0.2, msg = f"Predicted db from dqref: frames") testutils.finish() mrcal-2.4.1/test/test-match-feature.py000077500000000000000000000106071456301662300176640ustar00rootroot00000000000000#!/usr/bin/env python3 import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils import cv2 image = mrcal.load_image(f'{testdir}/data/figueroa-overpass-looking-S.0.downsampled.jpg', bits_per_pixel = 8, channels = 1) # some made-up homography with scaling, rotating, skewing and translating H01 = np.array((( 0.7, 0.3, 1.), ( -0.4, 0.95, 2.), ( 3e-5, 4e-6, 1.),), dtype=np.float32) H10 = np.linalg.inv(H01) # The feature I'm going to test with. This is the corner of one of the towers q0 = np.array((294,159), dtype=np.float32) # The transformed image. The matcher should end-up reversing this # transformation, since it will be given the homography. # # shape (H,W,2) image1 = \ mrcal.transform_image( image, mrcal.apply_homography( H01, nps.glue(*[ nps.dummy(arr, -1) for arr in \ np.meshgrid( np.arange(500), np.arange(600))], axis=-1).astype(np.float32) )) # I have the source images and the "right" homography and the "right" matching # pixels coords. Run the matcher, and compare templatesize = (30,20) search_radius = 50 H10_shifted = H10.copy() H10_shifted[0,2] += 10.2 H10_shifted[1,2] -= 20.4 q1_matched, diagnostics = \ mrcal.match_feature( image, image1, q0, H10 = H10_shifted, search_radius1 = 50, template_size1 = templatesize, method = cv2.TM_CCOEFF_NORMED) testutils.confirm_equal( q1_matched, mrcal.apply_homography(H10, q0), worstcase = True, eps = 0.1, msg=f'match_feature(method=TM_CCOEFF_NORMED) reports the correct pixel coordinate') q1_matched, diagnostics = \ mrcal.match_feature( image, image1, q0, H10 = H10_shifted, search_radius1 = 50, template_size1 = templatesize, method = cv2.TM_SQDIFF_NORMED) testutils.confirm_equal( q1_matched, mrcal.apply_homography(H10, q0), worstcase = True, eps = 0.1, msg=f'match_feature(method=TM_SQDIFF_NORMED) reports the correct pixel coordinate') q1_matched, diagnostics = \ mrcal.match_feature( image, image1, q0, H10 = H10_shifted, search_radius1 = 1000, template_size1 = templatesize, method = cv2.TM_CCOEFF_NORMED) testutils.confirm_equal( q1_matched, mrcal.apply_homography(H10, q0), worstcase = True, eps = 0.1, msg=f'out-of-bounds search_radius works ok') templatesize_hw = np.array((templatesize[-1],templatesize[-2])) testutils.confirm_equal( diagnostics['matchoutput_image'].shape, image1.shape - templatesize_hw + 1, msg = 'out-of-bounds search radius looks at the whole image') q1_matched, diagnostics = \ mrcal.match_feature( image*0, image1, q0, H10 = H10_shifted, search_radius1 = 50, template_size1 = templatesize, method = cv2.TM_CCOEFF_NORMED) testutils.confirm_equal( q1_matched, None, msg = 'failing correlation returns None') try: mrcal.match_feature( image*0, image1, q0, H10 = H10_shifted, search_radius1 = 50, template_size1 = (5000, 5000), method = cv2.TM_CCOEFF_NORMED) except: testutils.confirm(True, msg='Too-big template size throws an exception') else: testutils.confirm(False, msg='Too-big template size throws an exception') testutils.finish() mrcal-2.4.1/test/test-optimizer-callback.py000077500000000000000000000211531456301662300207110ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Tests the mrcal optimization callback function This is a regression test. It simply checks that the stored values are what's output. If anything changes, this test barfs. Any changes in the internals of the C code will trigger a failure here. If we see a failure without significant changes though, that's a bug that should be tracked down. To accept the current code as "right", set store_current_output_as_reference to True, and run this script. That updates the golden reference data so that subsequent runs of the test pass ''' # Set this to True to store the current values as the "true" values. Leave as # False to run the test. Leave as False in the repo store_current_output_as_reference = False import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils from functools import reduce def linspace_shaped(*shape): product = reduce( lambda x,y: x*y, shape) return np.linspace(0,1,product).reshape(*shape) # I read the synthetic-data observations. These have 3 frames with 2 cameras # each. I want to make things uneven, so I make the first two frames have only 1 # camera each observations, indices_frame_camera, paths = \ mrcal.compute_chessboard_corners(10, 10, globs_per_camera = ('frame*-cam0.xxx','frame*-cam1.xxx'), corners_cache_vnl = f"{testdir}/data/synthetic-board-observations.vnl") indices_frame_camintrinsics_camextrinsics = np.zeros((len(indices_frame_camera), 3), dtype=indices_frame_camera.dtype) indices_frame_camintrinsics_camextrinsics[:, :2] = indices_frame_camera indices_frame_camintrinsics_camextrinsics[:, 2] = indices_frame_camintrinsics_camextrinsics[:, 1]-1 i = (1,2,4,5) observations = observations [i, ...] indices_frame_camintrinsics_camextrinsics = indices_frame_camintrinsics_camextrinsics[i, ...] paths = [paths[_] for _ in i] # reference models models = [ mrcal.cameramodel(m) for m in ( f"{testdir}/data/cam0.opencv8.cameramodel", f"{testdir}/data/cam1.opencv8.cameramodel",) ] lensmodel = models[0].intrinsics()[0] intrinsics_data = nps.cat(models[0].intrinsics()[1], models[1].intrinsics()[1]) extrinsics_rt_fromref = mrcal.compose_rt( models[1].extrinsics_rt_fromref(), models[0].extrinsics_rt_toref() ) imagersizes = nps.cat(models[0].imagersize(), models[1].imagersize()) # I now have the "right" camera parameters. I don't have the frames or points, # but it's fine to just make them up. This is a regression test. frames_rt_toref = linspace_shaped(3,6) frames_rt_toref[:,5] += 5 # push them back indices_point_camintrinsics_camextrinsics = \ np.array(((0,1,-1), (1,0,-1), (1,1, 0), (2,0,-1), (2,1, 0)), dtype = np.int32) points = 10. + 2.*linspace_shaped(3,3) observations_point_xy = 1000. + 500. * linspace_shaped(5,2) observations_point_weights = np.array((0.9, 0.8, 0.9, 1.3, 1.8)) observations_point = \ nps.glue(observations_point_xy, nps.transpose(observations_point_weights), axis = -1) all_test_kwargs = ( dict(do_optimize_intrinsics_core = False, do_optimize_intrinsics_distortions= True, do_optimize_extrinsics = False, do_optimize_frames = False, do_optimize_calobject_warp = False, do_apply_regularization = True), dict(do_optimize_intrinsics_core = True, do_optimize_intrinsics_distortions= False, do_optimize_extrinsics = False, do_optimize_frames = False, do_optimize_calobject_warp = False, do_apply_regularization = True), dict(do_optimize_intrinsics_core = False, do_optimize_intrinsics_distortions= False, do_optimize_extrinsics = False, do_optimize_frames = True, do_optimize_calobject_warp = False, do_apply_regularization = True), dict(do_optimize_intrinsics_core = True, do_optimize_intrinsics_distortions= True, do_optimize_extrinsics = False, do_optimize_frames = True, do_optimize_calobject_warp = False, do_apply_regularization = True), dict(do_optimize_intrinsics_core = True, do_optimize_intrinsics_distortions= True, do_optimize_extrinsics = True, do_optimize_frames = True, do_optimize_calobject_warp = True, do_apply_regularization = False), dict(do_optimize_intrinsics_core = True, do_optimize_intrinsics_distortions= True, do_optimize_extrinsics = True, do_optimize_frames = True, do_optimize_calobject_warp = True, do_apply_regularization = False, outlier_indices = np.array((1,2), dtype=np.int32))) itest = 0 for kwargs in all_test_kwargs: observations_copy = observations.copy() if 'outlier_indices' in kwargs: # mark the requested outliers, and delete the old way of specifying # these for i in kwargs['outlier_indices']: nps.clump(observations_copy, n=3)[i,2] = -1. del kwargs['outlier_indices'] optimization_inputs = \ dict( intrinsics = intrinsics_data, extrinsics_rt_fromref = nps.atleast_dims(extrinsics_rt_fromref, -2), frames_rt_toref = frames_rt_toref, points = points, observations_board = observations_copy, indices_frame_camintrinsics_camextrinsics = indices_frame_camintrinsics_camextrinsics, observations_point = observations_point, indices_point_camintrinsics_camextrinsics = indices_point_camintrinsics_camextrinsics, lensmodel = lensmodel, calobject_warp = np.array((1e-3, 2e-3)), imagersizes = imagersizes, calibration_object_spacing = 0.1, point_min_range = 1.0, point_max_range = 1000.0, verbose = False, **kwargs ) x,J = mrcal.optimizer_callback( **optimization_inputs )[1:3] J = J.toarray() # let's make sure that pack and unpack work correctly J2 = J.copy() mrcal.pack_state( J2, **optimization_inputs) mrcal.unpack_state( J2, **optimization_inputs) testutils.confirm_equal( J2, J, msg="unpack(pack(J)) = J") J2 = J.copy() mrcal.unpack_state( J2, **optimization_inputs) mrcal.pack_state( J2, **optimization_inputs) testutils.confirm_equal( J2, J, msg="pack(unpack(J)) = J") # I compare full-state J so that I can change SCALE_... without breaking the # test mrcal.pack_state(J, **optimization_inputs) if store_current_output_as_reference: np.save(f"{testdir}/data/test-optimizer-callback-ref-x-{itest}.npy", x) np.save(f"{testdir}/data/test-optimizer-callback-ref-J-{itest}.npy", J) else: x_ref = np.load(f"{testdir}/data/test-optimizer-callback-ref-x-{itest}.npy") J_ref = np.load(f"{testdir}/data/test-optimizer-callback-ref-J-{itest}.npy") testutils.confirm_equal(x, x_ref, msg = f"comparing x for case {itest}") testutils.confirm_equal(J, J_ref, msg = f"comparing J for case {itest}") itest += 1 testutils.finish() mrcal-2.4.1/test/test-parser-cameramodel.c000066400000000000000000000223401456301662300204660ustar00rootroot00000000000000#include #include #include #include "../mrcal.h" #include "test-harness.h" #define CAMERAMODEL_T(Nintrinsics) \ struct \ { \ mrcal_cameramodel_t cameramodel; \ double intrinsics[Nintrinsics]; \ } #define Nintrinsics_CAHVORE (4+5+3) typedef CAMERAMODEL_T(Nintrinsics_CAHVORE) cameramodel_cahvore_t; #define check(string, ref, len) do { \ mrcal_cameramodel_t* m = mrcal_read_cameramodel_string(string, len);\ confirm(m != NULL); \ if(m != NULL) \ { \ confirm_eq_int(m-> lensmodel.type, \ (ref)->lensmodel.type); \ confirm_eq_double_max_array(m-> intrinsics, \ (ref)->intrinsics, \ Nintrinsics_CAHVORE, \ 1e-6); \ confirm_eq_double_max_array(m-> rt_cam_ref, \ (ref)->rt_cam_ref, \ 6, \ 1e-6); \ confirm_eq_int_max_array((int*)m-> imagersize, \ (int*)(ref)->imagersize, \ 2); \ mrcal_free_cameramodel(&m); \ } \ } while(0) #define check_fail(string,len) do{ \ mrcal_cameramodel_t* m = mrcal_read_cameramodel_string(string,len); \ confirm(m == NULL); \ if(m != NULL) \ mrcal_free_cameramodel(&m); \ } while(0) int main(int argc, char* argv[]) { mrcal_cameramodel_t cameramodel; cameramodel_cahvore_t cameramodel_ref = (cameramodel_cahvore_t) { .cameramodel = {.lensmodel = {.type = MRCAL_LENSMODEL_CAHVORE, .LENSMODEL_CAHVORE__config.linearity = 0.34}, .imagersize = {110,400}, .rt_cam_ref = {0,1,2,33,44e4,-55.3e-3}, }, .intrinsics = {4, 3, 4, 5, 0, 1, 3, 5, 4, 10, 11, 12} }; // baseline check("{\n" " 'lensmodel': \"LENSMODEL_CAHVORE_linearity=0.34\",\n" " 'extrinsics': [ 0., 1, 2, 33, 44e4, -55.3E-3, ],\n" " 'intrinsics': [ 4, 3, 4, 5, 0, 1, 3, 5, 4, 10, 11, 12 ],\n" " 'imagersize': [110, 400],\n" "}\n", (mrcal_cameramodel_t*)&cameramodel_ref, 0); // different spacing, different quote, paren check("{\n" " 'lensmodel' : b'LENSMODEL_CAHVORE_linearity=0.34',\n" " b'extrinsics' :[ 0., 1, 2, 33, 44e4, -55.3E-3, ],\n" " \"intrinsics\": (4, 3, 4, 5, 0, 1, 3, 5, 4, 10, 11, 12 ), 'imagersize': [110, 400],\n" "\n" "}\n", (mrcal_cameramodel_t*)&cameramodel_ref, 0); // comments, weird spacing check(" # f {\n" "#{ 'lensmodel': 'rrr'\n" "{'lensmodel': #\"LENSMODEL_CAHVOR\",\n" "\"LENSMODEL_CAHVORE_linearity=0.34\",\n" " 'extrinsics': [ 0., 1, 2, 33, # 44e4, -55.3E-3,\n" "44e4, -55.3E-3\n" "#,\n" ",\n" "#]\n" "],'intrinsics': [ 4, 3, 4,\n5, 0, \n\n 1, 3, 5, 4, 10, 11, 12 ],\n" " 'imagersize': [110, 400]\n" "# }\n" "} \n" " # }\n", (mrcal_cameramodel_t*)&cameramodel_ref, 0); // extra keys check("{\n" " 'lensmodel': \"LENSMODEL_CAHVORE_linearity=0.34\", 'f': 5,\n" " 'extrinsics': [ 0., 1, 2, 33, 44e4, -55.3E-3, ], 'xxx':\n" " # fff\n" " b'rr','qq': b'asdf;lkj&*()DSFEWR]]{}}}',\n" "'vvvv': [ 1,2, [4,5],[3,[4,3,[]],444], ]," " 'intrinsics': [ 4, 3, 4, 5, 0, 1, 3, 5, 4, 10, 11, 12 ],\n" " 'imagersize': [110, 400],\n" "}\n", (mrcal_cameramodel_t*)&cameramodel_ref, 0); // trailing garbage check_fail("{\n" " 'lensmodel': \"LENSMODEL_CAHVORE_linearity=0.34\",\n" " 'extrinsics': [ 0., 1, 2, 33, 44e4, -55.3E-3, ],\n" " 'intrinsics': [ 4, 3, 4, 5, 0, 1, 3, 5, 4, 10, 11, 12 ],\n" " 'imagersize': [110, 400],\n" "} f\n", 0); // double-defined key check_fail("{\n" " 'lensmodel': \"LENSMODEL_CAHVORE_linearity=0.34\",\n" " 'lensmodel': \"LENSMODEL_CAHVORE_linearity=0.34\",\n" " 'extrinsics': [ 0., 1, 2, 33, 44e4, -55.3E-3, ],\n" " 'intrinsics': [ 4, 3, 4, 5, 0, 1, 3, 5, 4, 10, 11, 12 ],\n" " 'imagersize': [110, 400],\n" "}\n", 0); check_fail("{\n" " 'lensmodel': \"LENSMODEL_CAHVORE_linearity=0.34\",\n" " 'extrinsics': [ 0., 1, 2, 33, 44e4, -55.3E-3, ],\n" " 'extrinsics': [ 0., 1, 2, 33, 44e4, -55.3E-3, ],\n" " 'intrinsics': [ 4, 3, 4, 5, 0, 1, 3, 5, 4, 10, 11, 12 ],\n" " 'imagersize': [110, 400],\n" "}\n", 0); check_fail("{\n" " 'lensmodel': \"LENSMODEL_CAHVORE_linearity=0.34\",\n" " 'extrinsics': [ 0., 1, 2, 33, 44e4, -55.3E-3, ],\n" " 'intrinsics': [ 4, 3, 4, 5, 0, 1, 3, 5, 4, 10, 11, 12 ],\n" " 'intrinsics': [ 4, 3, 4, 5, 0, 1, 3, 5, 4, 10, 11, 12 ],\n" " 'imagersize': [110, 400],\n" "}\n", 0); check_fail("{\n" " 'lensmodel': \"LENSMODEL_CAHVORE_linearity=0.34\",\n" " 'extrinsics': [ 0., 1, 2, 33, 44e4, -55.3E-3, ],\n" " 'intrinsics': [ 4, 3, 4, 5, 0, 1, 3, 5, 4, 10, 11, 12 ],\n" " 'imagersize': [110, 400],\n" " 'imagersize': [110, 400],\n" "}\n", 0); // missing key check_fail("{\n" " 'extrinsics': [ 0., 1, 2, 33, 44e4, -55.3E-3, ],\n" " 'intrinsics': [ 4, 3, 4, 5, 0, 1, 3, 5, 4, 10, 11, 12 ],\n" " 'imagersize': [110, 400],\n" "}\n", 0); check_fail("{\n" " 'lensmodel': \"LENSMODEL_CAHVORE_linearity=0.34\",\n" " 'intrinsics': [ 4, 3, 4, 5, 0, 1, 3, 5, 4, 10, 11, 12 ],\n" " 'imagersize': [110, 400],\n" "}\n", 0); check_fail("{\n" " 'lensmodel': \"LENSMODEL_CAHVORE_linearity=0.34\",\n" " 'extrinsics': [ 0., 1, 2, 33, 44e4, -55.3E-3, ],\n" " 'imagersize': [110, 400],\n" "}\n", 0); check_fail("{\n" " 'lensmodel': \"LENSMODEL_CAHVORE_linearity=0.34\",\n" " 'extrinsics': [ 0., 1, 2, 33, 44e4, -55.3E-3, ],\n" " 'intrinsics': [ 4, 3, 4, 5, 0, 1, 3, 5, 4, 10, 11, 12 ],\n" "}\n", 0); // Wrong number of intrinsics check_fail("{\n" " 'lensmodel': \"LENSMODEL_CAHVORE_linearity=0.34\",\n" " 'extrinsics': [ 0., 1, 2, 33, 44e4, -55.3E-3, ],\n" " 'intrinsics': [ 4, 3, 4, 5, 0, 1, 3, 5, 4, 10, 11, ],\n" " 'imagersize': [110, 400],\n" "}\n", 0); check_fail("{\n" " 'lensmodel': \"LENSMODEL_CAHVORE_linearity=0.34\",\n" " 'extrinsics': [ 0., 1, 2, 33, 44e4, -55.3E-3, ],\n" " 'intrinsics': [ 4, 3, 4, 5, 0, 1, 3, 5, 4, 10, 11, 99,88],\n" " 'imagersize': [110, 400],\n" "}\n", 0); // Roundtrip write/read bool write_cameramodel_succeeded = mrcal_write_cameramodel_file("/tmp/test-parser-cameramodel.cameramodel", (mrcal_cameramodel_t*)&cameramodel_ref); confirm(write_cameramodel_succeeded); if(write_cameramodel_succeeded) { FILE* fp = fopen("/tmp/test-parser-cameramodel.cameramodel", "r"); char buf[1024]; int Nbytes_read = fread(buf, 1, sizeof(buf), fp); fclose(fp); confirm(Nbytes_read > 0); confirm(Nbytes_read < (int)sizeof(buf)); if(Nbytes_read > 0 && Nbytes_read < (int)sizeof(buf)) { // Added byte to make sure we're not 0-terminated. Which the parser // must deal with buf[Nbytes_read] = '5'; check(buf, (mrcal_cameramodel_t*)&cameramodel_ref, Nbytes_read); } } TEST_FOOTER(); } mrcal-2.4.1/test/test-poseutils-lib.py000077500000000000000000001324311456301662300177320ustar00rootroot00000000000000#!/usr/bin/env python3 import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import mrcal._poseutils_npsp as _poseutils import cv2 from testutils import * from test_calibration_helpers import grad def R_from_r(r): r'''Rotation matrix from a Rodrigues vector Simple reference implementation from wikipedia: https://en.wikipedia.org/wiki/Rodrigues%27_rotation_formula ''' th_sq = nps.norm2(r) Kth = np.array((( 0, -r[2], r[1]), ( r[2], 0, -r[0]), (-r[1], r[0], 0))) if th_sq > 1e-20: # normal path th = np.sqrt(th_sq) s = np.sin(th) c = np.cos(th) K = Kth / th return np.eye(3) + s*K + (1. - c)*nps.matmult(K,K) # small th. Can't divide by it. But I can look at the limit. # # s*K = Kth * sin(th)/th -> Kth # # (1-c)*nps.matmult(K,K) = (1-c) Kth^2/th^2 -> Kth^2 s / 2th -> Kth^2/2 return np.eye(3) + Kth + nps.matmult(Kth,Kth) / 2. def r_from_R(R): r'''Rodrigues vector from a Rotation matrix Simple reference implementation from wikipedia: https://en.wikipedia.org/wiki/Rotation_matrix#Conversion_from_and_to_axis%E2%80%93angle I assume the input is a valid rotation matrix ''' axis = np.array((R[2,1] - R[1,2], R[0,2] - R[2,0], R[1,0] - R[0,1] )) if nps.norm2(axis) > 1e-20: # normal path costh = (np.trace(R) - 1.)/2. th = np.arccos(costh) return axis / nps.mag(axis) * th # small mag(axis). Can't divide by it. But I can look at the limit. # # axis / (2 sinth)*th = axis/2 *th/sinth ~ axis/2 return axis/2. def Rt_from_rt(rt): r'''Simple reference implementation''' return nps.glue(R_from_r(rt[:3]), rt[3:], axis=-2) def rt_from_Rt(Rt): r'''Simple reference implementation''' return nps.glue(r_from_R(Rt[:3,:]), Rt[3,:], axis=-1) def invert_rt(rt): r'''Simple reference implementation b = Ra + t -> a = R'b - R't ''' r = rt[:3] t = rt[3:] R = R_from_r(r) tinv = -nps.matmult(t, R) return nps.glue( -r, tinv.ravel(), axis=-1) def invert_Rt(Rt): r'''Simple reference implementation b = Ra + t -> a = R'b - R't ''' R = Rt[:3,:] tinv = -nps.matmult(Rt[3,:], R) return nps.glue( nps.transpose(R), tinv.ravel(), axis=-2) def invert_R(R): r'''Simple reference implementation ''' return nps.transpose(R) def compose_Rt(Rt0, Rt1): r'''Simple reference implementation b = R0 (R1 x + t1) + t0 = = R0 R1 x + R0 t1 + t0 ''' R0 = Rt0[:3,:] t0 = Rt0[ 3,:] R1 = Rt1[:3,:] t1 = Rt1[ 3,:] R2 = nps.matmult(R0,R1) t2 = nps.matmult(t1, nps.transpose(R0)) + t0 return nps.glue( R2, t2.ravel(), axis=-2) def normalize_r(r): r'''If abs(rot) > 180deg -> flip direction, abs(rot) <- 180-abs(rot)''' norm2 = nps.norm2(r) if norm2 < np.pi*np.pi: return r mag = np.sqrt(norm2) r_unit = r / mag mag = mag % (np.pi*2.) if mag < np.pi: # same direction, but fewer full rotations return r_unit*mag return -r_unit * (np.pi*2. - mag) def normalize_rt(rt): return nps.glue(normalize_r(rt[:3]), rt[3:], axis=-1) def compose_r(r0, r1): r'''Simple reference implementation''' return r_from_R(nps.matmult( R_from_r(r0), R_from_r(r1))) def compose_rt(rt0, rt1): r'''Simple reference implementation''' return rt_from_Rt(compose_Rt( Rt_from_rt(rt0), Rt_from_rt(rt1))) # Big array. I'm going to slice this thing for my working arrays to produce # interesting non-contiguous input, output base = np.zeros((7,11,13,5), dtype=float) base[1,1,0:3,1] = np.array((1., 2., 0.1)) r0_ref = base[1,1,0:3,1] base[1,1,3:6,1] = np.array((3., 5., -2.4)) t0_ref = base[1,1,3:6,1] base[1,1,6:9,1] = np.array((-.3, -.2, 1.1)) r1_ref = base[1,1,6:9,1] base[1,1,9:12,1] = np.array((-8., .5, -.4)) t1_ref = base[1,1,9:12,1] base[1,2,0:3,1] = np.array((-10., -108., 3.)) x = base[1,2,0:3,1] base[1,:3,:3,2] = R_from_r(r0_ref) R0_ref = base[1,:3,:3,2] base[1,3:7,:3,2]= nps.glue(R0_ref, t0_ref, axis=-2) Rt0_ref = base[1,3:7,:3,2] base[1,2,3:9,1]= nps.glue(r0_ref, t0_ref, axis=-1) rt0_ref = base[1,2,3:9,1] base[1,7:10,:3,2] = R_from_r(r1_ref) R1_ref = base[1,7:10,:3,2] base[2,:4,:3,2]= nps.glue(R1_ref, t1_ref, axis=-2) Rt1_ref = base[2,:4,:3,2] base[1,3,:6,1]= nps.glue(r1_ref, t1_ref, axis=-1) rt1_ref = base[1,3,:6,1] # the implementation has a separate path for tiny R, so I test it separately base[1,5,0:3,1] = np.array((-2.e-18, 3.e-19, -5.e-18)) r0_ref_tiny = base[1,5,0:3,1] base[5,:3,:3,2] = R_from_r(r0_ref_tiny) R0_ref_tiny = base[5,:3,:3,2] out333 = base[:3, :3, :3, 3] out343 = base[:3,3:7, :3, 3] out43 = base[2, 4:8, :3, 2] out33 = base[2, 8:11, :3, 2] out33a = base[3, :3, :3, 2] out33b = base[3, 3:6, :3, 2] out33c = base[3, 6:9, :3, 2] out33d = base[4, :3, :3, 2] out36 = base[6, :3, :6, 2] out3 = base[1, 3, 6:9, 1] out6 = base[1, 4, :6, 1] out66 = base[5,3:9, 3:9, 2] out66a = base[6,3:9, 3:9, 2] confirm_equal( mrcal.identity_R(out=out33), np.eye(3), msg='identity_R') confirm_equal( mrcal.identity_Rt(out=out43), nps.glue(np.eye(3), np.zeros((3,),), axis=-2), msg='identity_Rt') confirm_equal( mrcal.identity_r(out=out3), np.zeros((3,)), msg='identity_r') confirm_equal( mrcal.identity_rt(out=out6), np.zeros((6,)), msg='identity_rt') ################# rotate_point_R y = \ mrcal.rotate_point_R(R0_ref, x, out = out3) confirm_equal( y, nps.matmult(x, nps.transpose(R0_ref)), msg='rotate_point_R result') y, J_R, J_x = \ mrcal.rotate_point_R(R0_ref, x, get_gradients=True, out = (out3,out333,out33)) J_R_ref = grad(lambda R: nps.matmult(x, nps.transpose(R)), R0_ref) J_x_ref = R0_ref confirm_equal( y, nps.matmult(x, nps.transpose(R0_ref)), msg='rotate_point_R result') confirm_equal( J_R, J_R_ref, msg='rotate_point_R J_R') confirm_equal( J_x, J_x_ref, msg='rotate_point_R J_x') # In-place R0_ref_copy = np.array(R0_ref) x_copy = np.array(x) y = \ mrcal.rotate_point_R(R0_ref_copy, x_copy, out = x_copy) confirm_equal( y, nps.matmult(x, nps.transpose(R0_ref)), msg='rotate_point_R result written in-place into x') # inverted y = \ mrcal.rotate_point_R(R0_ref, x, out = out3, inverted=True) confirm_equal( y, nps.matmult(x, R0_ref), msg='rotate_point_R(inverted) result') y, J_R, J_x = \ mrcal.rotate_point_R(R0_ref, x, get_gradients=True, out = (out3,out333,out33), inverted = True) J_R_ref = grad(lambda R: nps.matmult(x, R), R0_ref) J_x_ref = nps.transpose(R0_ref) confirm_equal( y, nps.matmult(x, R0_ref), msg='rotate_point_R(inverted) result') confirm_equal( J_R, J_R_ref, msg='rotate_point_R(inverted) J_R') confirm_equal( J_x, J_x_ref, msg='rotate_point_R(inverted) J_x') # inverted in-place R0_ref_copy = np.array(R0_ref) x_copy = np.array(x) y = \ mrcal.rotate_point_R(R0_ref_copy, x_copy, out = x_copy, inverted = True) confirm_equal( y, nps.matmult(x, R0_ref), msg='rotate_point_R result written in-place into x') ################# rotate_point_r y = mrcal.rotate_point_r(r0_ref, x, out = out3) confirm_equal( y, nps.matmult(x, nps.transpose(R_from_r(r0_ref))), msg='rotate_point_r result') y, J_r, J_x = mrcal.rotate_point_r(r0_ref, x, get_gradients=True, out = (out3, out33, out33a)) J_r_ref = grad(lambda r: nps.matmult(x, nps.transpose(R_from_r(r))), r0_ref) J_x_ref = grad(lambda x: nps.matmult(x, nps.transpose(R_from_r(r0_ref))), x) confirm_equal( y, nps.matmult(x, nps.transpose(R_from_r(r0_ref))), msg='rotate_point_r result') confirm_equal( J_r, J_r_ref, msg='rotate_point_r J_r') confirm_equal( J_x, J_x_ref, msg='rotate_point_r J_x') r0_ref_copy = np.array(r0_ref) x_copy = np.array(x) y = mrcal.rotate_point_r(r0_ref_copy, x_copy, out = x_copy) confirm_equal( y, nps.matmult(x, nps.transpose(R_from_r(r0_ref))), msg='rotate_point_r result written in-place into x') r0_ref_copy = np.array(r0_ref) x_copy = np.array(x) out33_copy = np.array(out33) out33a_copy = np.array(out33a) y, J_r, J_x = mrcal.rotate_point_r(r0_ref_copy, x_copy, get_gradients=True, out = (x_copy, out33, out33a)) confirm_equal( y, nps.matmult(x, nps.transpose(R_from_r(r0_ref))), msg='rotate_point_r (with gradients) result written in-place into x') confirm_equal( J_r, J_r_ref, msg='rotate_point_r (with gradients) result written in-place into x: J_r') confirm_equal( J_x, J_x_ref, msg='rotate_point_r (with gradients) result written in-place into x: J_x') # inverted y = mrcal.rotate_point_r(r0_ref, x, out = out3, inverted=True) confirm_equal( y, nps.matmult(x, R_from_r(r0_ref)), msg='rotate_point_r(inverted) result') y, J_r, J_x = mrcal.rotate_point_r(r0_ref, x, get_gradients=True, out = (out3, out33, out33a), inverted = True) J_r_ref = grad(lambda r: nps.matmult(x, R_from_r(r)), r0_ref) J_x_ref = grad(lambda x: nps.matmult(x, R_from_r(r0_ref)), x) confirm_equal( y, nps.matmult(x, R_from_r(r0_ref)), msg='rotate_point_r(inverted) result') confirm_equal( J_r, J_r_ref, msg='rotate_point_r(inverted) J_r') confirm_equal( J_x, J_x_ref, msg='rotate_point_r(inverted) J_x') # inverted, in-place r0_ref_copy = np.array(r0_ref) x_copy = np.array(x) y = mrcal.rotate_point_r(r0_ref_copy, x_copy, inverted = True, out = x_copy) confirm_equal( y, nps.matmult(x, R_from_r(r0_ref)), msg='rotate_point_r(inverted) result written in-place into x') r0_ref_copy = np.array(r0_ref) x_copy = np.array(x) out33_copy = np.array(out33) out33a_copy = np.array(out33a) y, J_r, J_x = mrcal.rotate_point_r(r0_ref_copy, x_copy, get_gradients=True, inverted = True, out = (x_copy, out33, out33a)) confirm_equal( y, nps.matmult(x, R_from_r(r0_ref)), msg='rotate_point_r(inverted, with-gradients) result written in-place into x') confirm_equal( J_r, J_r_ref, msg='rotate_point_r(inverted, with-gradients result written in-place into x) J_r') confirm_equal( J_x, J_x_ref, msg='rotate_point_r(inverted, with-gradients result written in-place into x) J_x') ################# transform_point_Rt y = mrcal.transform_point_Rt(Rt0_ref, x, out = out3) confirm_equal( y, nps.matmult(x, nps.transpose(R0_ref))+t0_ref, msg='transform_point_Rt result') y, J_Rt, J_x = mrcal.transform_point_Rt(Rt0_ref, x, get_gradients=True, out = (out3, out343, out33)) J_Rt_ref = grad(lambda Rt: nps.matmult(x, nps.transpose(Rt[:3,:])) + Rt[3,:], Rt0_ref) J_x_ref = R0_ref confirm_equal( y, nps.matmult(x, nps.transpose(R0_ref))+t0_ref, msg='transform_point_Rt result') confirm_equal( J_Rt, J_Rt_ref, msg='transform_point_Rt J_Rt') confirm_equal( J_x, J_x_ref, msg='transform_point_Rt J_x') # In-place. I can imagine wanting to write the result in-place into t. But not # into any of R Rt0_ref_copy = np.array(Rt0_ref) x_copy = np.array(x) y = mrcal.transform_point_Rt(Rt0_ref_copy, x_copy, out = Rt0_ref_copy[3,:]) confirm_equal( y, nps.matmult(x, nps.transpose(R0_ref))+t0_ref, msg='transform_point_Rt result written in-place into t') Rt0_ref_copy = np.array(Rt0_ref) x_copy = np.array(x) y = mrcal.transform_point_Rt(Rt0_ref_copy, x_copy, out = x_copy) confirm_equal( y, nps.matmult(x, nps.transpose(R0_ref))+t0_ref, msg='transform_point_Rt result written in-place into x') Rt0_ref_copy = np.array(Rt0_ref) x_copy = np.array(x) y, J_Rt, J_x = mrcal.transform_point_Rt(Rt0_ref_copy, x_copy, out = (Rt0_ref_copy[3,:], out343, out33), get_gradients = True) confirm_equal( y, nps.matmult(x, nps.transpose(R0_ref))+t0_ref, msg='transform_point_Rt (with gradients) result written in-place into t') confirm_equal( J_Rt, J_Rt_ref, msg='transform_point_Rt (with gradients) result written in-place into t: J_Rt') confirm_equal( J_x, J_x_ref, msg='transform_point_Rt (with gradients) result written in-place into t: J_x') Rt0_ref_copy = np.array(Rt0_ref) x_copy = np.array(x) y, J_Rt, J_x = mrcal.transform_point_Rt(Rt0_ref_copy, x_copy, out = (x_copy, out343, out33), get_gradients = True) confirm_equal( y, nps.matmult(x, nps.transpose(R0_ref))+t0_ref, msg='transform_point_Rt (with gradients) result written in-place into x') confirm_equal( J_Rt, J_Rt_ref, msg='transform_point_Rt (with gradients) result written in-place into x: J_Rt') confirm_equal( J_x, J_x_ref, msg='transform_point_Rt (with gradients) result written in-place into x: J_x') # inverted y = mrcal.transform_point_Rt(Rt0_ref, x, out = out3, inverted = True) confirm_equal( y, nps.matmult(x, R0_ref) - nps.matmult(t0_ref, R0_ref), msg='transform_point_Rt(inverted) result') y, J_Rt, J_x = mrcal.transform_point_Rt(Rt0_ref, x, get_gradients=True, out = (out3, out343, out33), inverted = True) J_Rt_ref = grad(lambda Rt: nps.matmult(x, Rt[:3,:]) - nps.matmult(Rt[3,:], Rt[:3,:]), Rt0_ref) J_x_ref = nps.transpose(R0_ref) confirm_equal( y, nps.matmult(x, R0_ref)-nps.matmult(t0_ref, R0_ref), msg='transform_point_Rt(inverted) result') confirm_equal( J_Rt, J_Rt_ref, msg='transform_point_Rt(inverted) J_Rt') confirm_equal( J_x, J_x_ref, msg='transform_point_Rt(inverted) J_x') # inverted in-place. I can imagine wanting to write the result in-place into t. But not # into any of R Rt0_ref_copy = np.array(Rt0_ref) x_copy = np.array(x) y = mrcal.transform_point_Rt(Rt0_ref_copy, x_copy, out = Rt0_ref_copy[3,:], inverted = True) confirm_equal( y, nps.matmult(x, R0_ref)-nps.matmult(t0_ref, R0_ref), msg='transform_point_Rt(inverted) result written in-place into t') Rt0_ref_copy = np.array(Rt0_ref) x_copy = np.array(x) y = mrcal.transform_point_Rt(Rt0_ref_copy, x_copy, out = x_copy, inverted = True) confirm_equal( y, nps.matmult(x, R0_ref)-nps.matmult(t0_ref, R0_ref), msg='transform_point_Rt(inverted) result written in-place into x') Rt0_ref_copy = np.array(Rt0_ref) x_copy = np.array(x) y, J_Rt, J_x = mrcal.transform_point_Rt(Rt0_ref_copy, x_copy, out = (Rt0_ref_copy[3,:], out343, out33), get_gradients = True, inverted = True) confirm_equal( y, nps.matmult(x, R0_ref)-nps.matmult(t0_ref, R0_ref), msg='transform_point_Rt(inverted) (with gradients) result written in-place into t') confirm_equal( J_Rt, J_Rt_ref, msg='transform_point_Rt(inverted) (with gradients) result written in-place into t: J_Rt') confirm_equal( J_x, J_x_ref, msg='transform_point_Rt(inverted) (with gradients) result written in-place into t: J_x') Rt0_ref_copy = np.array(Rt0_ref) x_copy = np.array(x) y, J_Rt, J_x = mrcal.transform_point_Rt(Rt0_ref_copy, x_copy, out = (x_copy, out343, out33), get_gradients = True, inverted = True) confirm_equal( y, nps.matmult(x, R0_ref)-nps.matmult(t0_ref, R0_ref), msg='transform_point_Rt(inverted) (with gradients) result written in-place into x') confirm_equal( J_Rt, J_Rt_ref, msg='transform_point_Rt(inverted) (with gradients) result written in-place into x: J_Rt') confirm_equal( J_x, J_x_ref, msg='transform_point_Rt(inverted) (with gradients) result written in-place into x: J_x') ################# transform_point_rt y = mrcal.transform_point_rt(rt0_ref, x, out = out3) confirm_equal( y, nps.matmult(x, nps.transpose(R0_ref))+t0_ref, msg='transform_point_rt result') y, J_rt, J_x = mrcal.transform_point_rt(rt0_ref, x, get_gradients=True, out = (out3,out36,out33a)) J_rt_ref = grad(lambda rt: nps.matmult(x, nps.transpose(R_from_r(rt[:3])))+rt[3:], rt0_ref) J_x_ref = grad(lambda x: nps.matmult(x, nps.transpose(R0_ref))+t0_ref, x) confirm_equal( y, nps.matmult(x, nps.transpose(R0_ref))+t0_ref, msg='transform_point_rt result') confirm_equal( J_rt, J_rt_ref, msg='transform_point_rt J_rt') confirm_equal( J_x, J_x_ref, msg='transform_point_rt J_x') # In-place. I can imagine wanting to write the result in-place into t. But not # into any of r or J rt0_ref_copy = np.array(rt0_ref) x_copy = np.array(x) y = mrcal.transform_point_rt(rt0_ref_copy, x_copy, out = rt0_ref_copy[3:]) confirm_equal( y, nps.matmult(x, nps.transpose(R0_ref))+t0_ref, msg='transform_point_rt result written in-place into t') rt0_ref_copy = np.array(rt0_ref) x_copy = np.array(x) y = mrcal.transform_point_rt(rt0_ref_copy, x_copy, out = x_copy) confirm_equal( y, nps.matmult(x, nps.transpose(R0_ref))+t0_ref, msg='transform_point_rt result written in-place into x') rt0_ref_copy = np.array(rt0_ref) x_copy = np.array(x) out36_copy = np.array(out36) out33a_copy = np.array(out33a) y, J_rt, J_x = mrcal.transform_point_rt(rt0_ref_copy, x_copy, get_gradients=True, out = (rt0_ref_copy[3:],out36_copy,out33a_copy)) confirm_equal( y, nps.matmult(x, nps.transpose(R0_ref))+t0_ref, msg='transform_point_rt (with gradients) result written in-place into t') confirm_equal( J_rt, J_rt_ref, msg='transform_point_rt (with gradients) result written in-place into t: J_rt') confirm_equal( J_x, J_x_ref, msg='transform_point_rt (with gradients) result written in-place into t: J_x') rt0_ref_copy = np.array(rt0_ref) x_copy = np.array(x) out36_copy = np.array(out36) out33a_copy = np.array(out33a) y, J_rt, J_x = mrcal.transform_point_rt(rt0_ref_copy, x_copy, get_gradients=True, out = (x_copy, out36_copy,out33a_copy)) confirm_equal( y, nps.matmult(x, nps.transpose(R0_ref))+t0_ref, msg='transform_point_rt (with gradients) result written in-place into x') confirm_equal( J_rt, J_rt_ref, msg='transform_point_rt (with gradients) result written in-place into x: J_rt') confirm_equal( J_x, J_x_ref, msg='transform_point_rt (with gradients) result written in-place into x: J_x') # Inverted y = mrcal.transform_point_rt(rt0_ref, x, out = out3, inverted=True) confirm_equal( y, nps.matmult(x-t0_ref, R0_ref), msg='transform_point_rt(inverted) result') y, J_rt, J_x = mrcal.transform_point_rt(rt0_ref, x, get_gradients=True, out = (out3,out36,out33a), inverted = True) J_rt_ref = grad(lambda rt: nps.matmult(x-rt[3:], R_from_r(rt[:3])), rt0_ref) J_x_ref = grad(lambda x: nps.matmult(x-t0_ref, R0_ref), x) confirm_equal( y, nps.matmult(x-t0_ref, R0_ref), msg='transform_point_rt(inverted) result') confirm_equal( J_rt, J_rt_ref, msg='transform_point_rt(inverted) J_rt') confirm_equal( J_x, J_x_ref, msg='transform_point_rt(inverted) J_x') # Inverted in-place. I can imagine wanting to write the result in-place into t. # But not into any of r or J rt0_ref_copy = np.array(rt0_ref) x_copy = np.array(x) y = mrcal.transform_point_rt(rt0_ref_copy, x_copy, inverted=True, out = rt0_ref_copy[3:]) confirm_equal( y, nps.matmult(x-t0_ref, R0_ref), msg='transform_point_rt(inverted) result written in-place into t') rt0_ref_copy = np.array(rt0_ref) x_copy = np.array(x) y = mrcal.transform_point_rt(rt0_ref_copy, x_copy, inverted=True, out = x_copy) confirm_equal( y, nps.matmult(x-t0_ref, R0_ref), msg='transform_point_rt(inverted) result written in-place into x') rt0_ref_copy = np.array(rt0_ref) x_copy = np.array(x) out36_copy = np.array(out36) out33a_copy = np.array(out33a) y, J_rt, J_x = mrcal.transform_point_rt(rt0_ref_copy, x_copy, get_gradients=True, inverted=True, out = (rt0_ref_copy[3:],out36_copy,out33a_copy)) confirm_equal( y, nps.matmult(x-t0_ref, R0_ref), msg='transform_point_rt(inverted, with gradients) result written in-place into t') confirm_equal( J_rt, J_rt_ref, msg='transform_point_rt(inverted, with gradients) result written in-place into t: J_rt') confirm_equal( J_x, J_x_ref, msg='transform_point_rt(inverted, with gradients) result written in-place into t: J_x') rt0_ref_copy = np.array(rt0_ref) x_copy = np.array(x) out36_copy = np.array(out36) out33a_copy = np.array(out33a) y, J_rt, J_x = mrcal.transform_point_rt(rt0_ref_copy, x_copy, get_gradients=True, inverted=True, out = (x_copy,out36_copy,out33a_copy)) confirm_equal( y, nps.matmult(x-t0_ref, R0_ref), msg='transform_point_rt(inverted, with gradients) result written in-place into x') confirm_equal( J_rt, J_rt_ref, msg='transform_point_rt(inverted, with gradients) result written in-place into x: J_rt') confirm_equal( J_x, J_x_ref, msg='transform_point_rt(inverted, with gradients) result written in-place into x: J_x') ################# r_from_R r = mrcal.r_from_R(R0_ref, out = out3) confirm_equal( r, r0_ref, msg='r_from_R result') r, J_R = mrcal.r_from_R(R0_ref, get_gradients=True, out = (out3,out333)) J_R_ref = grad(r_from_R, R0_ref) confirm_equal( r, r0_ref, msg='r_from_R result') confirm_equal( J_R, J_R_ref, msg='r_from_R J_R') # Do it again, actually calling opencv. This is both a test, and shows how to # migrate old code r, J_R = mrcal.r_from_R(R0_ref, get_gradients=True, out = (out3,out333)) rref,J_R_ref = cv2.Rodrigues(R0_ref) confirm_equal( r, rref, msg='r_from_R result, comparing with cv2.Rodrigues') # I'm not comparing with opencv's gradient report or dr/dR. It doesn't match. I # know my gradient is correct because I numerically checked it above. Maybe # opencv is doing something different because of the constraints placed on R. # Figuring this out would be good # J_R_ref = nps.transpose(J_R_ref) # fix opencv's weirdness. Now shape=(3,9) # J_R_ref = J_R_ref.reshape(3,3,3) # confirm_equal( J_R, # J_R_ref, # msg='r_from_R J_R, comparing with cv2.Rodrigues') # I've seen this show up in the wild. r_from_R() was producing [nan nan nan] R_fuzzed_I = \ np.array([[ 0.9999999999999999 , -0.000000000000000010408340855861, 0. ], [-0.000000000000000010408340855861, 0.9999999999999999 , 0.000000000000000013877787807814], [ 0. , 0.000000000000000013877787807814, 0.9999999999999999 ]]) confirm_equal( mrcal.r_from_R(R_fuzzed_I), np.zeros((3,)), msg = 'r_from_R() can handle numerical fuzz') ################# R_from_r R = mrcal.R_from_r(r0_ref, out = out33) confirm_equal( R, R0_ref, msg='R_from_r result') R, J_r = mrcal.R_from_r(r0_ref, get_gradients=True, out = (out33,out333)) J_r_ref = grad(R_from_r, r0_ref) confirm_equal( R, R0_ref, msg='R_from_r result') confirm_equal( J_r, J_r_ref, msg='R_from_r J_r') # the implementation has a separate path for tiny R, so I test it separately R = mrcal.R_from_r(r0_ref_tiny, out = out33) confirm_equal( R, R0_ref_tiny, msg='R_from_r result for tiny r0') R, J_r = mrcal.R_from_r(r0_ref_tiny, get_gradients=True, out = (out33,out333)) J_r_ref = grad(R_from_r, r0_ref_tiny) confirm_equal( R, R0_ref_tiny, msg='R_from_r result for tiny r0') confirm_equal( J_r, J_r_ref, msg='R_from_r J_r for tiny r0') # Do it again, actually calling opencv. This is both a test, and shows how to # migrate old code R, J_r = mrcal.R_from_r(r0_ref, get_gradients=True, out = (out33,out333)) Rref,J_r_ref = cv2.Rodrigues(r0_ref) J_r_ref = nps.transpose(J_r_ref) # fix opencv's weirdness. Now shape=(9,3) J_r_ref = J_r_ref.reshape(3,3,3) confirm_equal( R, Rref, msg='R_from_r result, comparing with cv2.Rodrigues') confirm_equal( J_r, J_r_ref, msg='R_from_r J_r, comparing with cv2.Rodrigues') rt = mrcal.rt_from_Rt(Rt0_ref, out = out6) confirm_equal( rt, rt0_ref, msg='rt_from_Rt result') rt, J_R = mrcal.rt_from_Rt(Rt0_ref, get_gradients = True, out = (out6,out333)) J_R_ref = grad(r_from_R, Rt0_ref[:3,:]) confirm_equal( rt, rt0_ref, msg='rt_from_Rt result') confirm_equal( J_R, J_R_ref, msg='rt_from_Rt grad result') Rt = mrcal.Rt_from_rt(rt0_ref, out=out43) confirm_equal( Rt, Rt0_ref, msg='Rt_from_rt result') Rt, J_r = mrcal.Rt_from_rt(rt0_ref, get_gradients = True, out = (out43,out333)) J_r_ref = grad(R_from_r, rt0_ref[:3]) confirm_equal( Rt, Rt0_ref, msg='Rt_from_rt result') confirm_equal( J_r, J_r_ref, msg='Rt_from_rt grad result') Rt = mrcal.invert_Rt(Rt0_ref, out=out43) confirm_equal( Rt, invert_Rt(Rt0_ref), msg='invert_Rt result') # in-place Rt0_ref_copy = np.array(Rt0_ref) Rt = mrcal.invert_Rt(Rt0_ref_copy, out=Rt0_ref_copy) confirm_equal( Rt, invert_Rt(Rt0_ref), msg='invert_Rt result written in-place') R = mrcal.invert_R(R0_ref, out=out33) confirm_equal( R, invert_R(R0_ref), msg='invert_R result') # in-place R0_ref_copy = np.array(R0_ref) R = mrcal.invert_R(R0_ref_copy, out=R0_ref_copy) confirm_equal( R, invert_R(R0_ref), msg='invert_R result written in-place') rt = mrcal.invert_rt(rt0_ref, out=out6) confirm_equal( rt, invert_rt(rt0_ref), msg='invert_rt result') # in-place rt0_ref_copy = np.array(rt0_ref) rt = mrcal.invert_rt(rt0_ref_copy, out=rt0_ref_copy) confirm_equal( rt, invert_rt(rt0_ref), msg='invert_rt result written in-place') rt,drt_drt = mrcal.invert_rt(rt0_ref, get_gradients = True, out=(out6,out66)) drt_drt_ref = grad(invert_rt, rt0_ref) confirm_equal( rt, invert_rt(rt0_ref), msg='invert_rt with grad result') confirm_equal( drt_drt, drt_drt_ref, msg='invert_rt drt/drt result') # in-place rt0_ref_copy = np.array(rt0_ref) drt_drt_copy = np.array(drt_drt) rt,drt_drt = mrcal.invert_rt(rt0_ref_copy, out=(rt0_ref_copy,drt_drt_copy), get_gradients=True) confirm_equal( rt, invert_rt(rt0_ref), msg='invert_rt with grad result written in-place') confirm_equal( drt_drt, drt_drt_ref, msg='invert_rt with grad drt/drt result written in-place') Rt2 = mrcal.compose_Rt(Rt0_ref, Rt1_ref, out=out43) confirm_equal( Rt2, compose_Rt(Rt0_ref, Rt1_ref), msg='compose_Rt result') # in-place Rt0_ref_copy = np.array(Rt0_ref) Rt1_ref_copy = np.array(Rt1_ref) Rt2 = mrcal.compose_Rt(Rt0_ref_copy, Rt1_ref_copy, out=Rt0_ref_copy) confirm_equal( Rt2, compose_Rt(Rt0_ref, Rt1_ref), msg='compose_Rt result written in-place to Rt0') Rt0_ref_copy = np.array(Rt0_ref) Rt1_ref_copy = np.array(Rt1_ref) Rt2 = mrcal.compose_Rt(Rt0_ref_copy, Rt1_ref_copy, out=Rt1_ref_copy) confirm_equal( Rt2, compose_Rt(Rt0_ref, Rt1_ref), msg='compose_Rt result written in-place to Rt1') rt2 = mrcal.compose_rt(rt0_ref, rt1_ref, out = out6) confirm_equal( rt2, compose_rt(rt0_ref, rt1_ref), msg='compose_rt result') # in-place rt0_ref_copy = np.array(rt0_ref) rt1_ref_copy = np.array(rt1_ref) rt2 = mrcal.compose_rt(rt0_ref_copy, rt1_ref_copy, out=rt0_ref_copy) confirm_equal( rt2, compose_rt(rt0_ref, rt1_ref), msg='compose_rt result written in-place to rt0') rt0_ref_copy = np.array(rt0_ref) rt1_ref_copy = np.array(rt1_ref) rt2 = mrcal.compose_rt(rt0_ref_copy, rt1_ref_copy, out=rt1_ref_copy) confirm_equal( rt2, compose_rt(rt0_ref, rt1_ref), msg='compose_rt result written in-place to rt1') rt2 = _poseutils._compose_rt(rt0_ref, rt1_ref, out=out6) confirm_equal( rt2, compose_rt(rt0_ref, rt1_ref), msg='compose_rt result; calling _compose_rt() directly') # in-place rt0_ref_copy = np.array(rt0_ref) rt1_ref_copy = np.array(rt1_ref) rt2 = _poseutils._compose_rt(rt0_ref_copy, rt1_ref_copy, out=rt0_ref_copy) confirm_equal( rt2, compose_rt(rt0_ref, rt1_ref), msg='compose_rt (calling _compose_rt() directly) written in-place to rt0') rt0_ref_copy = np.array(rt0_ref) rt1_ref_copy = np.array(rt1_ref) rt2 = _poseutils._compose_rt(rt0_ref_copy, rt1_ref_copy, out=rt1_ref_copy) confirm_equal( rt2, compose_rt(rt0_ref, rt1_ref), msg='compose_rt (calling _compose_rt() directly) written in-place to rt1') rt2,drt2_drt0,drt2_drt1 = \ mrcal.compose_rt(rt0_ref, rt1_ref, get_gradients=True, out = (out6, out66, out66a)) drt2_drt0_ref = grad(lambda rt0: compose_rt( rt0, rt1_ref), rt0_ref) drt2_drt1_ref = grad(lambda rt1: compose_rt( rt0_ref, rt1), rt1_ref) confirm_equal( rt2, compose_rt(rt0_ref, rt1_ref), msg='compose_rt result') confirm_equal( drt2_drt0, drt2_drt0_ref, msg='compose_rt drt2_drt0') confirm_equal( drt2_drt1, drt2_drt1_ref, msg='compose_rt drt2_drt1') # in-place rt0_ref_copy = np.array(rt0_ref) rt1_ref_copy = np.array(rt1_ref) drt2_drt0_copy = np.array(drt2_drt0) drt2_drt1_copy = np.array(drt2_drt1) rt2,drt2_drt0,drt2_drt1 = \ mrcal.compose_rt(rt0_ref_copy, rt1_ref_copy, get_gradients=True, out=(rt0_ref_copy,drt2_drt0_copy,drt2_drt1_copy)) confirm_equal( rt2, compose_rt(rt0_ref, rt1_ref), msg='compose_rt (with gradients) result written in-place to rt0') confirm_equal( drt2_drt0, drt2_drt0_ref, msg='compose_rt (with gradients) result written in-place to rt0: drt2_drt0') confirm_equal( drt2_drt1, drt2_drt1_ref, msg='compose_rt (with gradients) result written in-place to rt0: drt2_drt1') rt0_ref_copy = np.array(rt0_ref) rt1_ref_copy = np.array(rt1_ref) rt2,drt2_drt0,drt2_drt1 = \ mrcal.compose_rt(rt0_ref_copy, rt1_ref_copy, get_gradients=True, out=(rt1_ref_copy,drt2_drt0_copy,drt2_drt1_copy)) confirm_equal( rt2, compose_rt(rt0_ref, rt1_ref), msg='compose_rt (with gradients) result written in-place to rt1') confirm_equal( drt2_drt0, drt2_drt0_ref, msg='compose_rt (with gradients) result written in-place to rt1: drt2_drt0') confirm_equal( drt2_drt1, drt2_drt1_ref, msg='compose_rt (with gradients) result written in-place to rt1: drt2_drt1') Rt2 = mrcal.compose_Rt(Rt0_ref, Rt1_ref,Rt0_ref, out=out43) confirm_equal( Rt2, compose_Rt(compose_Rt(Rt0_ref, Rt1_ref), Rt0_ref), msg='compose_Rt with 3 inputs') rt2 = mrcal.compose_rt(rt0_ref, rt1_ref,rt0_ref, out=out6) # Needed here. The two rotations are semantically equivalent, but numerically # different rt2 = normalize_rt(rt2) confirm_equal( rt2, compose_rt(compose_rt(rt0_ref, rt1_ref), rt0_ref), msg='compose_rt with 3 inputs') ################# compose_r() # # I check big, almost-0 and 0 arrays in both positions, and all the gradients. r0big = base[:3,0,0,0] r0nearzero = base[:3,1,0,0] r0zero = base[:3,2,0,0] r1big = base[:3,3,0,0] r1nearzero = base[:3,4,0,0] r1zero = base[:3,5,0,0] r01 = base[:3,6,0,0] dr01_dr0 = base[3:6,:3,0,0] dr01_dr1 = base[3:6,3:6,0,0] r0big[:] = np.array(( 1.0, 3.0, 1.1)) * 1e-1 r1big[:] = np.array((-2.0, -1.2, 0.3)) * 1e-1 r0nearzero[:] = np.array(( 1.7, -2.0, -5.1 )) * 1e-12 r1nearzero[:] = np.array((-1.2, 5.2, 0.03)) * 1e-12 r0zero[:] *= 0. r1zero[:] *= 0. confirm_equal( mrcal.compose_r(r0big, r1big), compose_r (r0big, r1big), msg='compose_r basic operation') mrcal.compose_r(r0big, r1big, out=r01) confirm_equal( r01, compose_r (r0big, r1big), msg='compose_r in-place output') r01_notinplace, dr01_dr0_notinplace, dr01_dr1_notinplace = \ mrcal.compose_r(r0big, r1big, get_gradients=True) dr01_dr0_ref = grad(lambda r0: compose_r( r0, r1big), r0big, step=1e-5) dr01_dr1_ref = grad(lambda r1: compose_r( r0big, r1), r1big, step=1e-5) confirm_equal( r01_notinplace, compose_r (r0big, r1big), msg='compose_r gradients: r01') confirm_equal( dr01_dr0_notinplace, dr01_dr0_ref, msg='compose_r gradients: dr01_dr0') confirm_equal( dr01_dr1_notinplace, dr01_dr1_ref, msg='compose_r gradients: dr01_dr1') mrcal.compose_r(r0big, r1big, get_gradients=True, out = (r01, dr01_dr0, dr01_dr1)) confirm_equal( r01, compose_r (r0big, r1big), msg='compose_r in-place gradients: r01') confirm_equal( dr01_dr0, dr01_dr0_ref, msg='compose_r in-place gradients: dr01_dr0') confirm_equal( dr01_dr1, dr01_dr1_ref, msg='compose_r in-place gradients: dr01_dr1') mrcal.compose_r(r0big, r1nearzero, get_gradients=True, out = (r01, dr01_dr0, dr01_dr1)) dr01_dr0_ref = grad(lambda r0: compose_r( r0, r1nearzero), r0big, step=1e-5) dr01_dr1_ref = grad(lambda r1: compose_r( r0big, r1), r1nearzero, step=1e-5) confirm_equal( r01, compose_r (r0big, r1nearzero), msg='compose_r in-place r1nearzero gradients: r01') confirm_equal( dr01_dr0, dr01_dr0_ref, msg='compose_r in-place r1nearzero gradients: dr01_dr0') confirm_equal( dr01_dr1, dr01_dr1_ref, msg='compose_r in-place r1nearzero gradients: dr01_dr1') mrcal.compose_r(r0big, r1zero, get_gradients=True, out = (r01, dr01_dr0, dr01_dr1)) dr01_dr0_ref = grad(lambda r0: compose_r( r0, r1zero), r0big, step=1e-5) dr01_dr1_ref = grad(lambda r1: compose_r( r0big, r1), r1zero, step=1e-5) confirm_equal( r01, compose_r (r0big, r1zero), msg='compose_r in-place r1zero gradients: r01') confirm_equal( dr01_dr0, dr01_dr0_ref, msg='compose_r in-place r1zero gradients: dr01_dr0') confirm_equal( dr01_dr1, dr01_dr1_ref, msg='compose_r in-place r1zero gradients: dr01_dr1') mrcal.compose_r(r0nearzero, r1big, get_gradients=True, out = (r01, dr01_dr0, dr01_dr1)) dr01_dr0_ref = grad(lambda r0: compose_r( r0, r1big), r0nearzero, step=1e-5) dr01_dr1_ref = grad(lambda r1: compose_r( r0nearzero, r1), r1big, step=1e-5) confirm_equal( r01, compose_r (r0nearzero, r1big), msg='compose_r in-place r1nearzero gradients: r01') confirm_equal( dr01_dr0, dr01_dr0_ref, msg='compose_r in-place r1nearzero gradients: dr01_dr0') confirm_equal( dr01_dr1, dr01_dr1_ref, msg='compose_r in-place r1nearzero gradients: dr01_dr1') mrcal.compose_r(r0zero, r1big, get_gradients=True, out = (r01, dr01_dr0, dr01_dr1)) dr01_dr0_ref = grad(lambda r0: compose_r( r0, r1big), r0zero, step=1e-5) dr01_dr1_ref = grad(lambda r1: compose_r( r0zero, r1), r1big, step=1e-5) confirm_equal( r01, compose_r (r0zero, r1big), msg='compose_r in-place r1zero gradients: r01') confirm_equal( dr01_dr0, dr01_dr0_ref, msg='compose_r in-place r1zero gradients: dr01_dr0') confirm_equal( dr01_dr1, dr01_dr1_ref, msg='compose_r in-place r1zero gradients: dr01_dr1') mrcal.compose_r(r0nearzero, r1nearzero, get_gradients=True, out = (r01, dr01_dr0, dr01_dr1)) dr01_dr0_ref = grad(lambda r0: compose_r( r0, r1nearzero), r0nearzero, step=1e-5) dr01_dr1_ref = grad(lambda r1: compose_r( r0nearzero, r1), r1nearzero, step=1e-5) confirm_equal( r01, compose_r (r0nearzero, r1nearzero), msg='compose_r in-place r0nearzero,r1nearzero gradients: r01') confirm_equal( dr01_dr0, dr01_dr0_ref, msg='compose_r in-place r0nearzero,r1nearzero gradients: dr01_dr0') confirm_equal( dr01_dr1, dr01_dr1_ref, msg='compose_r in-place r0nearzero,r1nearzero gradients: dr01_dr1') mrcal.compose_r(r0nearzero, r1zero, get_gradients=True, out = (r01, dr01_dr0, dr01_dr1)) dr01_dr0_ref = grad(lambda r0: compose_r( r0, r1zero), r0nearzero, step=1e-5) dr01_dr1_ref = grad(lambda r1: compose_r( r0nearzero, r1), r1zero, step=1e-5) confirm_equal( r01, compose_r (r0nearzero, r1zero), msg='compose_r in-place r0nearzero,r1zero gradients: r01') confirm_equal( dr01_dr0, dr01_dr0_ref, msg='compose_r in-place r0nearzero,r1zero gradients: dr01_dr0') confirm_equal( dr01_dr1, dr01_dr1_ref, msg='compose_r in-place r0nearzero,r1zero gradients: dr01_dr1') mrcal.compose_r(r0zero, r1nearzero, get_gradients=True, out = (r01, dr01_dr0, dr01_dr1)) dr01_dr0_ref = grad(lambda r0: compose_r( r0, r1nearzero), r0zero, step=1e-5) dr01_dr1_ref = grad(lambda r1: compose_r( r0zero, r1), r1nearzero, step=1e-5) confirm_equal( r01, compose_r (r0zero, r1nearzero), msg='compose_r in-place r0zero,r1nearzero gradients: r01') confirm_equal( dr01_dr0, dr01_dr0_ref, msg='compose_r in-place r0zero,r1nearzero gradients: dr01_dr0') confirm_equal( dr01_dr1, dr01_dr1_ref, msg='compose_r in-place r0zero,r1nearzero gradients: dr01_dr1') mrcal.compose_r(r0zero, r1zero, get_gradients=True, out = (r01, dr01_dr0, dr01_dr1)) dr01_dr0_ref = grad(lambda r0: compose_r( r0, r1zero), r0zero, step=1e-5) dr01_dr1_ref = grad(lambda r1: compose_r( r0zero, r1), r1zero, step=1e-5) confirm_equal( r01, compose_r (r0zero, r1zero), msg='compose_r in-place r0zero,r1zero gradients: r01') confirm_equal( dr01_dr0, dr01_dr0_ref, msg='compose_r in-place r0zero,r1zero gradients: dr01_dr0') confirm_equal( dr01_dr1, dr01_dr1_ref, msg='compose_r in-place r0zero,r1zero gradients: dr01_dr1') # Finally, let's look at rotation composition when the result is 0 mrcal.compose_r(r0big, -r0big, get_gradients=True, out = (r01, dr01_dr0, dr01_dr1)) dr01_dr0_ref = grad(lambda r0: compose_r( r0, -r0big), r0big, step=1e-5) dr01_dr1_ref = grad(lambda r1: compose_r( r0big, r1), -r0big, step=1e-5) confirm_equal( r01, compose_r (r0big, -r0big), msg='compose_r in-place r0big,-r0big gradients: r01') confirm_equal( dr01_dr0, dr01_dr0_ref, msg='compose_r in-place r0big,-r0big gradients: dr01_dr0') confirm_equal( dr01_dr1, dr01_dr1_ref, msg='compose_r in-place r0big,-r0big gradients: dr01_dr1') mrcal.compose_r(r0nearzero, -r0nearzero, get_gradients=True, out = (r01, dr01_dr0, dr01_dr1)) dr01_dr0_ref = grad(lambda r0: compose_r( r0, -r0nearzero), r0nearzero, step=1e-5) dr01_dr1_ref = grad(lambda r1: compose_r( r0nearzero, r1), -r0nearzero, step=1e-5) confirm_equal( r01, compose_r (r0nearzero, -r0nearzero), msg='compose_r in-place r0nearzero,-r0nearzero gradients: r01') confirm_equal( dr01_dr0, dr01_dr0_ref, msg='compose_r in-place r0nearzero,-r0nearzero gradients: dr01_dr0') confirm_equal( dr01_dr1, dr01_dr1_ref, msg='compose_r in-place r0nearzero,-r0nearzero gradients: dr01_dr1') mrcal.compose_r(r0zero, -r0zero, get_gradients=True, out = (r01, dr01_dr0, dr01_dr1)) dr01_dr0_ref = grad(lambda r0: compose_r( r0, -r0zero), r0zero, step=1e-5) dr01_dr1_ref = grad(lambda r1: compose_r( r0zero, r1), -r0zero, step=1e-5) confirm_equal( r01, compose_r (r0zero, -r0zero), msg='compose_r in-place r0zero,-r0zero gradients: r01') confirm_equal( dr01_dr0, dr01_dr0_ref, msg='compose_r in-place r0zero,-r0zero gradients: dr01_dr0') confirm_equal( dr01_dr1, dr01_dr1_ref, msg='compose_r in-place r0zero,-r0zero gradients: dr01_dr1') ################# compose_r_tinyr0_gradientr0() # These are a subset of the compose_r() tests just above r1big = base[:3,3,0,0] r1nearzero = base[:3,4,0,0] r0zero = base[:3,2,0,0] r1zero = base[:3,5,0,0] r01 = base[:3,6,0,0] dr01_dr0 = base[3:6,:3,0,0] r1big [:] = np.array((-2.0, -1.2, 0.3)) * 1e-1 r1nearzero [:] = np.array((-1.2, 5.2, 0.03)) * 1e-12 r0zero [:] *= 0. r1zero [:] *= 0. mrcal.compose_r_tinyr0_gradientr0(r1big, out = dr01_dr0) dr01_dr0_ref = grad(lambda r0: compose_r( r0, r1big), r0zero, step=1e-5) confirm_equal( dr01_dr0, dr01_dr0_ref, msg='compose_r_tinyr0_gradientr0 in-place r1zero gradients: dr01_dr0') mrcal.compose_r_tinyr0_gradientr0(r1nearzero, out = dr01_dr0) dr01_dr0_ref = grad(lambda r0: compose_r( r0, r1nearzero), r0zero, step=1e-5) confirm_equal( dr01_dr0, dr01_dr0_ref, msg='compose_r_tinyr0_gradientr0 in-place r1nearzero gradients: dr01_dr0') mrcal.compose_r_tinyr0_gradientr0(r1zero, out = dr01_dr0) dr01_dr0_ref = grad(lambda r0: compose_r( r0, r1zero), r0zero, step=1e-5) confirm_equal( dr01_dr0, dr01_dr0_ref, msg='compose_r_tinyr0_gradientr0 in-place r1zero gradients: dr01_dr0') mrcal.compose_r_tinyr0_gradientr0(-r0zero, out = dr01_dr0) dr01_dr0_ref = grad(lambda r0: compose_r( r0, -r0zero), r0zero, step=1e-5) confirm_equal( dr01_dr0, dr01_dr0_ref, msg='compose_r_tinyr0_gradientr0 in-place r0zero,-r0zero gradients: dr01_dr0') finish() mrcal-2.4.1/test/test-poseutils.py000077500000000000000000000173301456301662300171660ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Tests various pose transformations''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils p = np.array([[1.79294696, 3.84665205, 8.88059626], [1.94285588, 5.5994178, 9.08980913], [1.16926135, 7.11203249, 6.49111756], [4.97016243, 3.36377894, 9.91309303], [7.0578383, 6.96290783, 2.74822211], [2.09286004, 8.32613405, 4.29534757], [5.390182, 6.97763688, 8.75498418], [6.54142328, 3.77331963, 3.29282044], [5.84571708, 4.87274621, 4.32639624], [7.00320821, 0.70546965, 5.67190652]]) Rt = np.array([[ 0.37796712, -0.5149426 , 0.7693991 ], [ 0.52322138, 0.80441527, 0.28134581], [-0.76379333, 0.29622659, 0.5734715 ], [ 0.9447233, 6.8439095, 9.6958398 ]]) R = Rt[:3, :] t = Rt[ 3, :] noise = np.array([[0.00035356, 0.00043613, 0.00006606], [0.00043968, 0.00043783, 0.00060678], [0.00063803, 0.00024423, 0.00010871], [0.00004966, 0.00053377, 0.00018905], [0.00007708, 0.00023529, 0.0002229 ], [0.00090558, 0.00072379, 0.00004062], [0.00072059, 0.00074467, 0.00044128], [0.00024228, 0.00058201, 0.00041458], [0.00018121, 0.00078172, 0.00016128], [0.00019021, 0.00001371, 0.00096808]]) Tp = nps.matmult( p, nps.transpose(R) ) + t Rt_fit = \ mrcal.align_procrustes_points_Rt01(Tp + noise, p) R_fit = Rt_fit[:3, :] t_fit = Rt_fit[ 3, :] testutils.confirm_equal( R_fit, R, eps=1e-2, msg='Procrustes fit R' ) testutils.confirm_equal( t_fit, t, eps=1e-2, msg='Procrustes fit t' ) R_fit_vectors = \ mrcal.align_procrustes_vectors_R01(nps.matmult( p, nps.transpose(R) ) + noise, p) testutils.confirm_equal( R_fit_vectors, R, eps=1e-2, msg='Procrustes fit R (vectors)' ) testutils.confirm_equal( mrcal.invert_Rt(mrcal.Rt_from_rt(mrcal.invert_rt(mrcal.rt_from_Rt(Rt)))), Rt, msg = 'Rt/rt and invert') testutils.confirm_equal( mrcal.compose_Rt( Rt, mrcal.invert_Rt(Rt)), nps.glue(np.eye(3), np.zeros((3,)), axis=-2), msg = 'compose_Rt') testutils.confirm_equal( mrcal.compose_rt( mrcal.rt_from_Rt(Rt), mrcal.invert_rt(mrcal.rt_from_Rt(Rt))), np.zeros((6,)), msg = 'compose_rt') testutils.confirm_equal( mrcal.compose_r( mrcal.r_from_R(R), -mrcal.r_from_R(R)), np.zeros((3,)), msg = 'compose_r') testutils.confirm_equal( mrcal.identity_Rt(), nps.glue(np.eye(3), np.zeros((3,)), axis=-2), msg = 'identity_Rt') testutils.confirm_equal( mrcal.identity_rt(), np.zeros((6,)), msg = 'identity_rt') testutils.confirm_equal( mrcal.transform_point_Rt( Rt, p ), Tp, msg = 'transform_point_Rt') testutils.confirm_equal( mrcal.transform_point_rt( mrcal.rt_from_Rt(Rt), p ), Tp, msg = 'transform_point_rt') testutils.confirm_equal( mrcal.transform_point_Rt( mrcal.invert_Rt(Rt), Tp ), p, msg = 'transform_point_Rt inverse') testutils.confirm_equal( mrcal.transform_point_rt( mrcal.invert_rt(mrcal.rt_from_Rt(Rt)), Tp ), p, msg = 'transform_point_rt inverse') ######### quaternion business testutils.confirm_equal( mrcal.R_from_quat( mrcal.quat_from_R(R) ), R, msg = 'R <-> quaternion transforms are inverses of one another') # shape (2,3,3) RR = nps.cat( R, nps.matmult(R,R) ) # shape (2,4,3) RtRt = nps.cat( Rt, mrcal.compose_Rt(Rt,Rt) ) testutils.confirm_equal( mrcal.R_from_quat( mrcal.quat_from_R(RR) ), RR, msg = 'R <-> quaternion transforms are inverses of one another. Broadcasted') # I'm concerned about quat_from_R() broadcasting properly. I check testutils.confirm_equal( mrcal.quat_from_R(RR.reshape(2,1,3,3)).shape, (2,1,4), msg = 'quat_from_R() shape') testutils.confirm_equal( mrcal.quat_from_R(RR.reshape(2,3,3)).shape, (2,4), msg = 'quat_from_R() shape') testutils.confirm_equal( mrcal.quat_from_R(R).shape, (4,), msg = 'quat_from_R() shape') # in-place output R2 = np.zeros(R. shape, dtype=float) RR2 = np.zeros(RR.shape, dtype=float) r2 = np.zeros(R. shape[:-2] + (3,), dtype=float) rr2 = np.zeros(RR.shape[:-2] + (3,), dtype=float) q2 = np.zeros(R. shape[:-2] + (4,), dtype=float) qq2 = np.zeros(RR.shape[:-2] + (4,), dtype=float) q = mrcal.quat_from_R(R) qq = mrcal.quat_from_R(RR) mrcal.quat_from_R(R, out=q2) testutils.confirm_equal( q2, q, msg = 'quat_from_R() in-place') mrcal.quat_from_R(RR, out=qq2) testutils.confirm_equal( qq2, qq, msg = 'quat_from_R() in-place') mrcal.R_from_quat(q, out=R2) testutils.confirm_equal( R2, mrcal.R_from_quat(q), msg = 'R_from_quat() in-place') mrcal.R_from_quat(qq, out=RR2) testutils.confirm_equal( RR2, mrcal.R_from_quat(qq), msg = 'R_from_quat() in-place') Rt2 = np.zeros(Rt. shape, dtype=float) RtRt2 = np.zeros(RtRt.shape, dtype=float) rt2 = np.zeros(Rt. shape[:-2] + (6,), dtype=float) rtrt2 = np.zeros(RtRt.shape[:-2] + (6,), dtype=float) qt2 = np.zeros(Rt. shape[:-2] + (7,), dtype=float) qtqt2 = np.zeros(RtRt.shape[:-2] + (7,), dtype=float) qt = mrcal.qt_from_Rt(Rt) qtqt = mrcal.qt_from_Rt(RtRt) mrcal.qt_from_Rt(Rt, out=qt2) testutils.confirm_equal( qt2, qt, msg = 'qt_from_Rt() in-place') mrcal.qt_from_Rt(RtRt, out=qtqt2) testutils.confirm_equal( qtqt2, qtqt, msg = 'qt_from_Rt() in-place') mrcal.Rt_from_qt(qt, out=Rt2) testutils.confirm_equal( Rt2, mrcal.Rt_from_qt(qt), msg = 'Rt_from_qt() in-place') mrcal.Rt_from_qt(qtqt, out=RtRt2) testutils.confirm_equal( RtRt2, mrcal.Rt_from_qt(qtqt), msg = 'Rt_from_qt() in-place') ####### small-angle R_from_r() for th in (1e-12, 1e-11, 1e-10, 1e-9, 1e-8, 1e-7, 1e-6): c,s = np.cos(th), np.sin(th) rtiny = np.array((0, th, 0)) Rtiny = np.array((( c, 0, s), ( 0, 1, 0), (-s, 0, c))) testutils.confirm_equal( mrcal.R_from_r(rtiny), Rtiny, worstcase = True, eps = 1e-13, msg = f'R_from_r() for tiny rotations: th = {th}') testutils.confirm_equal( mrcal.r_from_R(Rtiny), rtiny, worstcase = True, eps = 1e-13, msg = f'r_from_R() for tiny rotations: th = {th}') ###### skew_symmetric() a = np.array((1.,5.,7.)) b = np.array((3.,-.1,-10.)) A = mrcal.skew_symmetric(a) testutils.confirm_equal( nps.inner(A,b), np.cross(a,b), eps = 1e-13, msg = f'skew_symmetric()') testutils.finish() mrcal-2.4.1/test/test-projection--special-cases.py000077500000000000000000000252571456301662300221110ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Tests special-case projection functions Simple things like project_lonlat(), project_stereographic(), etc. I do 3 things: Here I make sure the projection functions return the correct values. This is a regression test, so the "right" values were recorded at some point, and any deviation is flagged. I make sure that project(unproject(x)) == x I run a gradient check. I do these for the simple project_...() function AND the generic project() function. ''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils from test_calibration_helpers import grad if len(sys.argv) != 2: raise Exception("Need one argument on the commandline: the projection type. Currently I support 'pinhole','latlon','lonlat','stereographic'") if sys.argv[1] == 'pinhole' or \ sys.argv[1] == 'latlon' or \ sys.argv[1] == 'lonlat': # pixels/rad fx,fy = 3000., 2000. # pixel where latlon = (0,0) projects to. May be negative cx,cy = (-10000., 4000.) # a few points, some wide, some not. Some behind the camera p = np.array(((1.0, 2.0, 10.0), (-1.1, 0.3, -1.0), (-0.9, -1.5, -1.0))) if sys.argv[1] == 'pinhole': unproject_is_normalized = False else: unproject_is_normalized = True if sys.argv[1] == 'pinhole': # pinhole projects ahead only p[:,2] = abs(p[:,2]) if sys.argv[1] == 'pinhole': lensmodel = 'LENSMODEL_PINHOLE' func_project = mrcal.project_pinhole func_unproject = mrcal.unproject_pinhole name = 'pinhole' q_projected_ref = np.array([[ -9700., 4400.], [ -13300., 4600.], [ -12700., 1000.]]) elif sys.argv[1] == 'lonlat': lensmodel = 'LENSMODEL_LONLAT' func_project = mrcal.project_lonlat func_unproject = mrcal.unproject_lonlat name = 'lonlat' q_projected_ref = np.array([[ -9700.99404253, 4392.88198287], [-16925.83416075, 4398.25498944], [-17226.33265541, 2320.61601685]]) elif sys.argv[1] == 'latlon': lensmodel = 'LENSMODEL_LATLON' func_project = mrcal.project_latlon func_unproject = mrcal.unproject_latlon name = 'latlon' q_projected_ref = np.array([[ -9706.7632608 , 4394.7911197 ], [-12434.4909092 , 9700.27171822], [-11389.09468198, -317.59786068]]) elif sys.argv[1] == 'stereographic': lensmodel = 'LENSMODEL_STEREOGRAPHIC' func_project = mrcal.project_stereographic func_unproject = mrcal.unproject_stereographic name = 'stereographic' fx,fy,cx,cy = 1512., 1112, 500., 333. # a few points, some wide, some not. Some behind the camera p = np.array(((1.0, 2.0, 10.0), (-1.1, 0.3, -1.0), (-0.9, -1.5, -1.0))) q_projected_ref = np.array([[ 649.35582325, 552.6874014 ], [-5939.33490417, 1624.58376866], [-2181.52681292, -2953.8803086 ]]) unproject_is_normalized = False else: raise Exception("Unknown projection type. Currently I support 'lonlat','stereographic'") intrinsics = (lensmodel, np.array((fx,fy,cx,cy))) q_projected = func_project(p, intrinsics[1]) testutils.confirm_equal(q_projected, q_projected_ref, msg = f"project_{name}()", worstcase = True, relative = True) testutils.confirm_equal(mrcal.project(p, *intrinsics), q_projected, msg = f"project({name}) returns the same as project_{name}()", worstcase = True, relative = True) v_unprojected = func_unproject(q_projected, intrinsics[1]) if unproject_is_normalized: testutils.confirm_equal( nps.mag(v_unprojected), 1., msg = f"unproject_{name}() returns normalized vectors", worstcase = True, relative = True) testutils.confirm_equal( v_unprojected, p / nps.dummy(nps.mag(p), axis=-1), msg = f"unproject_{name}()", worstcase = True, relative = True) else: cos = nps.inner(v_unprojected, p) / (nps.mag(p)*nps.mag(v_unprojected)) cos = np.clip(cos, -1, 1) testutils.confirm_equal( np.arccos(cos), np.zeros((p.shape[0],), dtype=float), msg = f"unproject_{name}()", worstcase = True) # Not normalized by default. Make sure that if I ask for it to be # normalized, that it is testutils.confirm_equal( nps.mag( mrcal.unproject(q_projected, *intrinsics, normalize = True) ), 1., msg = f"unproject({name},normalize = True) returns normalized vectors", worstcase = True, relative = True) testutils.confirm_equal( nps.mag( mrcal.unproject(q_projected, *intrinsics, normalize = True, get_gradients = True)[0] ), 1., msg = f"unproject({name},normalize = True, get_gradients=True) returns normalized vectors", worstcase = True, relative = True) testutils.confirm_equal( mrcal.unproject(q_projected, *intrinsics), v_unprojected, msg = f"unproject({name}) returns the same as unproject_{name}()", worstcase = True, relative = True) testutils.confirm_equal( mrcal.project(mrcal.unproject(q_projected, *intrinsics),*intrinsics), q_projected, msg = f"project(unproject()) is an identity", worstcase = True, relative = True) testutils.confirm_equal( func_project(func_unproject(q_projected,intrinsics[1]),intrinsics[1]), q_projected, msg = f"project_{name}(unproject_{name}()) is an identity", worstcase = True, relative = True) # Now gradients for project() ipt = 1 _,dq_dp_reported = func_project(p[ipt], intrinsics[1], get_gradients=True) dq_dp_observed = grad(lambda p: func_project(p, intrinsics[1]), p[ipt]) testutils.confirm_equal(dq_dp_reported, dq_dp_observed, msg = f"project_{name}() dq/dp", worstcase = True, relative = True) _,dq_dp_reported,dq_di_reported = mrcal.project(p[ipt], *intrinsics, get_gradients=True) dq_dp_observed = grad(lambda p: mrcal.project(p, *intrinsics), p[ipt]) dq_di_observed = grad(lambda intrinsics_data: mrcal.project(p[ipt], intrinsics[0],intrinsics_data), intrinsics[1]) testutils.confirm_equal(dq_dp_reported, dq_dp_observed, msg = f"project({name}) dq/dp", worstcase = True, relative = True) testutils.confirm_equal(dq_di_reported, dq_di_observed, msg = f"project({name}) dq/di", worstcase = True, relative = True, eps = 1e-5) # Now gradients for unproject() ipt = 1 _,dv_dq_reported = func_unproject(q_projected[ipt], intrinsics[1], get_gradients=True) dv_dq_observed = grad(lambda q: func_unproject(q, intrinsics[1]), q_projected[ipt]) testutils.confirm_equal(dv_dq_reported, dv_dq_observed, msg = f"unproject_{name}() dv/dq", worstcase = True, relative = True, eps = 2e-6) for normalize in (False, True): v_unprojected,dv_dq_reported,dv_di_reported = \ mrcal.unproject(q_projected[ipt], *intrinsics, get_gradients = True, normalize = normalize) dv_dq_observed = grad(lambda q: mrcal.unproject(q, *intrinsics, normalize=normalize), q_projected[ipt]) dv_di_observed = grad(lambda intrinsics_data: mrcal.unproject(q_projected[ipt], intrinsics[0],intrinsics_data, normalize=normalize), intrinsics[1]) testutils.confirm_equal(dv_dq_reported, dv_dq_observed, msg = f"unproject({name}, normalize={normalize}) dv/dq", worstcase = True, relative = True, eps = 1e-5) testutils.confirm_equal(dv_di_reported, dv_di_observed, msg = f"unproject({name}, normalize={normalize}) dv/di", worstcase = True, relative = True, eps = 1e-5) v_unprojected_inplace = v_unprojected.copy() *0 dv_dq_reported_inplace = dv_dq_reported.copy()*0 dv_di_reported_inplace = dv_di_reported.copy()*0 mrcal.unproject(q_projected[ipt], *intrinsics, get_gradients=True, normalize=normalize, out = [v_unprojected_inplace,dv_dq_reported_inplace,dv_di_reported_inplace]) testutils.confirm_equal(v_unprojected_inplace, v_unprojected, msg = f"unproject({name}, normalize={normalize}) works in-place: v_unprojected", worstcase = True, relative = True) testutils.confirm_equal(dv_dq_reported_inplace, dv_dq_reported, msg = f"unproject({name}, normalize={normalize}) works in-place: dv_dq", worstcase = True, relative = True) testutils.confirm_equal(dv_di_reported_inplace, dv_di_reported, msg = f"unproject({name}, normalize={normalize}) works in-place: dv_di", worstcase = True, relative = True) testutils.finish() mrcal-2.4.1/test/test-projection-diff.py000077500000000000000000000125711456301662300202230ustar00rootroot00000000000000#!/usr/bin/env python3 r'''diff test Make sure the projection-diff function produces correct results ''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils model_opencv8 = mrcal.cameramodel(f"{testdir}/data/cam0.opencv8.cameramodel") model_splined = mrcal.cameramodel(f"{testdir}/data/cam0.splined.cameramodel") gridn_width = 50 ########## Compare the model to itself. I should get 0 diff and identity transform difflen, diff, q0, implied_Rt10 = \ mrcal.projection_diff( (model_splined,model_splined), gridn_width = gridn_width, distance = None, use_uncertainties = False ) testutils.confirm_equal( difflen.shape[1], gridn_width, msg = "Expected number of columns" ) testutils.confirm_equal( difflen.shape[0], int(round( model_splined.imagersize()[1] / model_splined.imagersize()[0] * gridn_width)), msg = "Expected number of rows" ) icenter = np.array(difflen.shape) // 2 testutils.confirm_equal( difflen*0, difflen, eps = 0.08, worstcase = True, relative = False, msg = "diff(model,model) at infinity should be 0") testutils.confirm_equal( 0, np.arccos((np.trace(implied_Rt10[:3,:]) - 1) / 2.) * 180./np.pi, eps = 0.01, msg = "diff(model,model) at infinity should produce a rotation of 0 deg") testutils.confirm_equal( 0, nps.mag(implied_Rt10[3,:]), eps = 0.01, msg = "diff(model,model) at infinity should produce a translation of 0 m") difflen, diff, q0, implied_Rt10 = \ mrcal.projection_diff( (model_splined,model_splined), gridn_width = 50, distance = 3., use_uncertainties = False ) testutils.confirm_equal( difflen*0, difflen, eps = 0.08, worstcase = True, relative = False, msg = "diff(model,model) at 3m should be 0") testutils.confirm_equal( 0, np.arccos((np.trace(implied_Rt10[:3,:]) - 1) / 2.) * 180./np.pi, eps = 0.01, msg = "diff(model,model) at 3m should produce a rotation of 0 deg") testutils.confirm_equal( 0, nps.mag(implied_Rt10[3,:]), eps = 0.01, msg = "diff(model,model) at 3m should produce a translation of 0 m") ########## Check outlier handling when computing diffs without uncertainties. ########## The model may only fit in one regions. Using data outside of that ########## region poisons the solve unless we treat those measurements as ########## outliers. This is controlled by the f_scale parameter in ########## implied_Rt10__from_unprojections(). difflen, diff, q0, implied_Rt10 = \ mrcal.projection_diff( (model_opencv8,model_splined), gridn_width = gridn_width, distance = 5, use_uncertainties = False, focus_radius = 800) testutils.confirm_equal( 0, difflen[icenter[0],icenter[1]], eps = 0.1, msg = "Low-enough diff with high focus_radius") difflen, diff, q0, implied_Rt10 = \ mrcal.projection_diff( (model_opencv8,model_splined), gridn_width = gridn_width, distance = 5, use_uncertainties = False, focus_radius = 366) testutils.confirm_equal( 0, difflen[icenter[0],icenter[1]], eps = 0.1, msg = "Low-enough diff with low focus_radius") ########## Check that the solver is willing to move the origin around freely to ########## compute a very tight fit. I'm seeing that the 'trf' solver doesn't ########## like doing that and that it finds a highly suboptimal implied ########## transformation # I generate a model with a focal length shifted anisotropically. This sounds # weird, but is representative of the variation I see in real-life solves model_opencv8_shiftedz = mrcal.cameramodel(model_opencv8) lensmodel,intrinsics = model_opencv8_shiftedz.intrinsics() intrinsics[0] *= 1.0001 intrinsics[1] *= 1.0002 model_opencv8_shiftedz.intrinsics(intrinsics = (lensmodel,intrinsics)) difflen, diff, q0, implied_Rt10 = \ mrcal.projection_diff( (model_opencv8,model_opencv8_shiftedz), gridn_width = gridn_width, distance = 50000, use_uncertainties = False, focus_radius = 1500) testutils.confirm_equal( 0, difflen[icenter[0],icenter[1]], eps = 5e-3, msg = "implied_Rt10 solver moves translation sufficiently. Looking at difflen at center") testutils.confirm_equal( 0, np.mean(difflen), eps = .12, msg = "implied_Rt10 solver moves translation sufficiently. Looking at mean(difflen)") testutils.finish() mrcal-2.4.1/test/test-projection-uncertainty.py000077500000000000000000001661311456301662300216620ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Uncertainty-quantification test I run a number of synthetic-data camera calibrations, applying some noise to the observed inputs each time. I then look at the distribution of projected world points, and compare that distribution with theoretical predictions. This test checks two different types of calibrations: --fixed cam0: we place camera0 at the reference coordinate system. So camera0 may not move, and has no associated extrinsics vector. The other cameras and the frames move. When evaluating at projection uncertainty I pick a point referenced off the frames. As the frames move around, so does the point I'm projecting. But together, the motion of the frames and the extrinsics and the intrinsics should map it to the same pixel in the end. --fixed frames: the reference coordinate system is attached to the frames, which may not move. All cameras may move around and all cameras have an associated extrinsics vector. When evaluating at projection uncertainty I also pick a point referenced off the frames, but here any point in the reference coord system will do. As the cameras move around, so does the point I'm projecting. But together, the motion of the extrinsics and the intrinsics should map it to the same pixel in the end. Exactly one of these two arguments is required. The lens model we're using must appear: either "--model opencv4" or "--model opencv8" or "--model splined" ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--fixed', type=str, choices=('cam0','frames'), required=True, help='''Are we putting the origin at camera0, or are all the frames at a fixed (and non-optimizeable) pose? One or the other is required.''') parser.add_argument('--model', type=str, choices=('opencv4','opencv8','splined'), required = True, help='''Which lens model we're using. Must be one of ('opencv4','opencv8','splined')''') parser.add_argument('--Nframes', type=int, default=50, help='''How many chessboard poses to simulate. These are dense observations: every camera sees every corner of every chessboard pose''') parser.add_argument('--Nsamples', type=int, default=100, help='''How many random samples to evaluate''') parser.add_argument('--Ncameras', type = int, default = 4, help='''How many cameras to simulate. By default we use 4. The values of those 4 are hard-coded, so --Ncameras must be <= 4''') parser.add_argument('--distances', type=str, default='5,inf', help='''Comma-separated list of distance where we test the uncertainty predictions. Numbers and "inf" understood. The first value on this list is used for visualization in --show-distribution''') parser.add_argument('--do-sample', action='store_true', help='''By default we don't run the time-intensive samples of the calibration solves. This runs a very limited set of tests, and exits. To perform the full set of tests, pass --do-sample''') parser.add_argument('--show-distribution', action='store_true', help='''If given, we produce plots showing the distribution of samples''') parser.add_argument('--write-models', action='store_true', help='''If given, we write the resulting models to disk for further analysis''') parser.add_argument('--make-documentation-plots', type=str, help='''If given, we produce plots for the documentation. Takes one argument: a string describing this test. This will be used in the filenames of the resulting plots. To make interactive plots, pass ""''') parser.add_argument('--terminal-pdf', type=str, help='''The gnuplotlib terminal for --make-documentation-plots .PDFs. Omit this unless you know what you're doing''') parser.add_argument('--terminal-svg', type=str, help='''The gnuplotlib terminal for --make-documentation-plots .SVGs. Omit this unless you know what you're doing''') parser.add_argument('--terminal-png', type=str, help='''The gnuplotlib terminal for --make-documentation-plots .PNGs. Omit this unless you know what you're doing''') parser.add_argument('--explore', action='store_true', help='''If given, we drop into a REPL at the end''') parser.add_argument('--extra-observation-at', type=float, help='''Adds one extra observation at the given distance''') parser.add_argument('--range-to-boards', type=float, default=4.0, help='''Nominal range to the simulated chessboards''') parser.add_argument('--reproject-perturbed', choices=('mean-frames', 'mean-frames-using-meanq', 'mean-frames-using-meanq-penalize-big-shifts', 'fit-boards-ref', 'diff', 'optimize-cross-reprojection-error'), default = 'mean-frames', help='''Which reproject-after-perturbation method to use. This is for experiments. Some of these methods will be probably wrong.''') args = parser.parse_args() args.distances = args.distances.split(',') for i in range(len(args.distances)): if args.distances[i] == 'inf': args.distances[i] = None else: if re.match("[0-9deDE.-]+", args.distances[i]): s = float(args.distances[i]) else: print('--distances is a comma-separated list of numbers or "inf"', file=sys.stderr) sys.exit(1) args.distances[i] = s return args args = parse_args() if args.Ncameras <= 0 or args.Ncameras > 4: print(f"Ncameras must be in [0,4], but got {args.Ncameras}. Giving up", file=sys.stderr) sys.exit(1) if args.fixed == 'frames' and re.match('mean-frames-using-meanq', args.reproject_perturbed): print("--fixed frames currently not implemented together with --reproject-perturbed mean-frames-using-meanq.", file = sys.stderr) sys.exit(1) testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils import copy import numpy as np import numpysane as nps from test_calibration_helpers import calibration_baseline,calibration_sample fixedframes = (args.fixed == 'frames') import tempfile import atexit import shutil workdir = tempfile.mkdtemp() def cleanup(): global workdir try: shutil.rmtree(workdir) workdir = None except: pass atexit.register(cleanup) terminal = dict(pdf = args.terminal_pdf, svg = args.terminal_svg, png = args.terminal_png, gp = 'gp') pointscale = dict(pdf = 1, svg = 1, png = 1, gp = 1) pointscale[""] = 1. def shorter_terminal(t): # Adjust the terminal string to be less tall. Makes the multiplots look # better: less wasted space m = re.match("(.*)( size.*?,)([0-9.]+)(.*?)$", t) if m is None: return t return m.group(1) + m.group(2) + str(float(m.group(3))*0.8) + m.group(4) if args.make_documentation_plots: print(f"Will write documentation plots to {args.make_documentation_plots}-xxxx.pdf and .svg") if terminal['svg'] is None: terminal['svg'] = 'svg size 800,600 noenhanced solid dynamic font ",14"' if terminal['pdf'] is None: terminal['pdf'] = 'pdf size 8in,6in noenhanced solid color font ",12"' if terminal['png'] is None: terminal['png'] = 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' extraset = dict() for k in pointscale.keys(): extraset[k] = f'pointsize {pointscale[k]}' # I want the RNG to be deterministic np.random.seed(0) ############# Set up my world, and compute all the perfect positions, pixel ############# observations of everything pixel_uncertainty_stdev = 1.5 object_spacing = 0.1 object_width_n = 10 object_height_n = 9 calobject_warp_true = np.array((0.002, -0.005)) extrinsics_rt_fromref_true = \ np.array(((0, 0, 0, 0, 0, 0), (0.08, 0.2, 0.02, 1., 0.9, 0.1), (0.01, 0.07, 0.2, 2.1, 0.4, 0.2), (-0.1, 0.08, 0.08, 3.4, 0.2, 0.1), )) optimization_inputs_baseline, \ models_true, models_baseline, \ indices_frame_camintrinsics_camextrinsics, \ lensmodel, Nintrinsics, imagersizes, \ intrinsics_true, extrinsics_true_mounted, frames_true, \ observations_true, \ args.Nframes = \ calibration_baseline(args.model, args.Ncameras, args.Nframes, args.extra_observation_at, object_width_n, object_height_n, object_spacing, extrinsics_rt_fromref_true, calobject_warp_true, fixedframes, testdir, range_to_boards = args.range_to_boards) # I evaluate the projection uncertainty of this vector. In each camera. I'd like # it to be center-ish, but not AT the center. So I look at 1/3 (w,h). I want # this to represent a point in a globally-consistent coordinate system. Here I # have fixed frames, so using the reference coordinate system gives me that # consistency. Note that I look at q0 for each camera separately, so I'm going # to evaluate a different world point for each camera q0_baseline = imagersizes[0]/3. if args.make_documentation_plots is not None: import gnuplotlib as gp if args.make_documentation_plots: for extension in ('pdf','svg','png','gp'): processoptions_output = dict(wait = False, terminal = terminal[extension], _set = extraset[extension], hardcopy = f'{args.make_documentation_plots}--simulated-geometry.{extension}') gp.add_plot_option(processoptions_output, 'set', 'xyplane relative 0') mrcal.show_geometry(models_baseline, show_calobjects = True, unset='key', **processoptions_output) else: processoptions_output = dict(wait = True) gp.add_plot_option(processoptions_output, 'set', 'xyplane relative 0') mrcal.show_geometry(models_baseline, show_calobjects = True, unset='key', **processoptions_output) def observed_points(icam): obs_cam = observations_true[indices_frame_camintrinsics_camextrinsics[:,1]==icam, ..., :2].ravel() return obs_cam.reshape(len(obs_cam)//2,2) if args.make_documentation_plots: for extension in ('pdf','svg','png','gp'): obs_cam = [ ( (observed_points(icam),), (q0_baseline, dict(_with = f'points pt 3 lw 2 lc "red" ps {2*pointscale[extension]}'))) \ for icam in range(args.Ncameras) ] processoptions_output = dict(wait = False, terminal = shorter_terminal(terminal[extension]), _set = extraset[extension], hardcopy = f'{args.make_documentation_plots}--simulated-observations.{extension}') gp.plot( *obs_cam, tuplesize=-2, _with='dots', square=1, _xrange=(0, models_true[0].imagersize()[0]-1), _yrange=(models_true[0].imagersize()[1]-1, 0), multiplot = 'layout 2,2', **processoptions_output) else: obs_cam = [ ( (observed_points(icam),), (q0_baseline, dict(_with = f'points pt 3 lw 2 lc "red" ps {2*pointscale[""]}'))) \ for icam in range(args.Ncameras) ] processoptions_output = dict(wait = True) gp.plot( *obs_cam, tuplesize=-2, _with='dots', square=1, _xrange=(0, models_true[0].imagersize()[0]-1), _yrange=(models_true[0].imagersize()[1]-1, 0), multiplot = 'layout 2,2', **processoptions_output) # These are at the optimum intrinsics_baseline = nps.cat( *[m.intrinsics()[1] for m in models_baseline] ) extrinsics_baseline_mounted = nps.cat( *[m.extrinsics_rt_fromref() for m in models_baseline] ) frames_baseline = optimization_inputs_baseline['frames_rt_toref'] calobject_warp_baseline = optimization_inputs_baseline['calobject_warp'] if args.write_models: for i in range(args.Ncameras): models_true [i].write(f"/tmp/models-true-camera{i}.cameramodel") models_baseline[i].write(f"/tmp/models-baseline-camera{i}.cameramodel") sys.exit() def reproject_perturbed__mean_frames(q, distance, # shape (Ncameras, Nintrinsics) baseline_intrinsics, # shape (Ncameras, 6) baseline_rt_cam_ref, # shape (Nframes, 6) baseline_rt_ref_frame, # shape (2) baseline_calobject_warp, # dict baseline_optimization_inputs, # shape (..., Ncameras, Nintrinsics) query_intrinsics, # shape (..., Ncameras, 6) query_rt_cam_ref, # shape (..., Nframes, 6) query_rt_ref_frame, # shape (..., 2) query_calobject_warp, # list of dicts of length ... query_optimization_inputs): r'''Reproject by computing the mean in the space of frames This is what the uncertainty computation does (as of 2020/10/26). The implied rotation here is aphysical (it is a mean of multiple rotation matrices) ''' # shape (Ncameras, 3) p_cam_baseline = mrcal.unproject(q, lensmodel, baseline_intrinsics, normalize = True) * distance # shape (Ncameras, 3) p_ref_baseline = \ mrcal.transform_point_rt( mrcal.invert_rt(baseline_rt_cam_ref), p_cam_baseline ) if fixedframes: p_ref_query = p_ref_baseline else: # shape (Nframes, Ncameras, 3) # The point in the coord system of all the frames p_frames = mrcal.transform_point_rt( \ nps.dummy(mrcal.invert_rt(baseline_rt_ref_frame),-2), p_ref_baseline) # shape (..., Nframes, Ncameras, 3) p_ref_query_allframes = \ mrcal.transform_point_rt( nps.dummy(query_rt_ref_frame, -2), p_frames ) if args.reproject_perturbed == 'mean-frames': # "Normal" path: I take the mean of all the frame-coord-system # representations of my point if not fixedframes: # shape (..., Ncameras, 3) p_ref_query = np.mean( p_ref_query_allframes, axis = -3) # shape (..., Ncameras, 3) p_cam_query = \ mrcal.transform_point_rt(query_rt_cam_ref, p_ref_query) # shape (..., Ncameras, 2) return mrcal.project(p_cam_query, lensmodel, query_intrinsics) else: # Experimental path: I take the mean of the projections, not the points # in the reference frame # guaranteed that not fixedframes: I asserted this above # shape (..., Nframes, Ncameras, 3) p_cam_query_allframes = \ mrcal.transform_point_rt(nps.dummy(query_rt_cam_ref, -3), p_ref_query_allframes) # shape (..., Nframes, Ncameras, 2) q_reprojected = mrcal.project(p_cam_query_allframes, lensmodel, nps.dummy(query_intrinsics,-3)) if args.reproject_perturbed != 'mean-frames-using-meanq-penalize-big-shifts': return np.mean(q_reprojected, axis=-3) else: # Experiment. Weighted mean to de-emphasize points with huge shifts w = 1./nps.mag(q_reprojected - q) w = nps.mv(nps.cat(w,w),0,-1) return \ np.sum(q_reprojected*w, axis=-3) / \ np.sum(w, axis=-3) def reproject_perturbed__fit_boards_ref(q, distance, # shape (Ncameras, Nintrinsics) baseline_intrinsics, # shape (Ncameras, 6) baseline_rt_cam_ref, # shape (Nframes, 6) baseline_rt_ref_frame, # shape (2) baseline_calobject_warp, # dict baseline_optimization_inputs, # shape (..., Ncameras, Nintrinsics) query_intrinsics, # shape (..., Ncameras, 6) query_rt_cam_ref, # shape (..., Nframes, 6) query_rt_ref_frame, # shape (..., 2) query_calobject_warp, # list of dicts of length ... query_optimization_inputs): r'''Reproject by explicitly computing a procrustes fit to align the reference coordinate systems of the two solves. We match up the two sets of chessboard points ''' calobject_height,calobject_width = baseline_optimization_inputs['observations_board'].shape[1:3] # shape (Nsamples, Nh, Nw, 3) if query_calobject_warp.ndim > 1: calibration_object_query = \ nps.cat(*[ mrcal.ref_calibration_object(calobject_width, calobject_height, baseline_optimization_inputs['calibration_object_spacing'], calobject_warp=calobject_warp) \ for calobject_warp in query_calobject_warp] ) else: calibration_object_query = \ mrcal.ref_calibration_object(calobject_width, calobject_height, baseline_optimization_inputs['calibration_object_spacing'], calobject_warp=query_calobject_warp) # shape (Nsamples, Nframes, Nh, Nw, 3) pcorners_ref_query = \ mrcal.transform_point_rt( nps.dummy(query_rt_ref_frame, -2, -2), nps.dummy(calibration_object_query, -4)) # shape (Nh, Nw, 3) calibration_object_baseline = \ mrcal.ref_calibration_object(calobject_width, calobject_height, baseline_optimization_inputs['calibration_object_spacing'], calobject_warp=baseline_calobject_warp) # frames_ref.shape is (Nframes, 6) # shape (Nframes, Nh, Nw, 3) pcorners_ref_baseline = \ mrcal.transform_point_rt( nps.dummy(baseline_rt_ref_frame, -2, -2), calibration_object_baseline) # shape (Nsamples,4,3) Rt_refq_refb = \ mrcal.align_procrustes_points_Rt01( \ # shape (Nsamples,N,3) nps.mv(nps.clump(nps.mv(pcorners_ref_query, -1,0),n=-3),0,-1), # shape (N,3) nps.clump(pcorners_ref_baseline, n=3)) # shape (Ncameras, 3) p_cam_baseline = mrcal.unproject(q, lensmodel, baseline_intrinsics, normalize = True) * distance # shape (Ncameras, 3). In the ref coord system p_ref_baseline = \ mrcal.transform_point_rt( mrcal.invert_rt(baseline_rt_cam_ref), p_cam_baseline ) # shape (Nsamples,Ncameras,3) p_ref_query = \ mrcal.transform_point_Rt(nps.mv(Rt_refq_refb,-3,-4), p_ref_baseline) # shape (..., Ncameras, 3) p_cam_query = \ mrcal.transform_point_rt(query_rt_cam_ref, p_ref_query) # shape (..., Ncameras, 2) q1 = mrcal.project(p_cam_query, lensmodel, query_intrinsics) if q1.shape[-3] == 1: q1 = q1[0,:,:] return q1 # The others broadcast implicitly, while THIS main function really cannot handle # outer dimensions, and needs an explicit broadcasting loop @nps.broadcast_define(((2,), (), ('Ncameras', 'Nintrinsics'), ('Ncameras', 6), ('Nframes', 6), (2,), (), ('Ncameras', 'Nintrinsics'), ('Ncameras', 6), ('Nframes', 6), (2,), ()), ('Ncameras',2)) def reproject_perturbed__diff(q, distance, # shape (Ncameras, Nintrinsics) baseline_intrinsics, # shape (Ncameras, 6) baseline_rt_cam_ref, # shape (Nframes, 6) baseline_rt_ref_frame, # shape (2) baseline_calobject_warp, # dict baseline_optimization_inputs, # shape (Ncameras, Nintrinsics) query_intrinsics, # shape (Ncameras, 6) query_rt_cam_ref, # shape (Nframes, 6) query_rt_ref_frame, # shape (2) query_calobject_warp, # dict query_optimization_inputs): r'''Reproject by using the "diff" method to compute a rotation ''' # shape (Ncameras, 3) p_cam_baseline = mrcal.unproject(q, lensmodel, baseline_intrinsics, normalize = True) * distance p_cam_query = np.zeros((args.Ncameras, 3), dtype=float) for icam in range (args.Ncameras): # This method only cares about the intrinsics model_baseline = \ mrcal.cameramodel( intrinsics = (lensmodel, baseline_intrinsics[icam]), imagersize = imagersizes[0] ) model_query = \ mrcal.cameramodel( intrinsics = (lensmodel, query_intrinsics[icam]), imagersize = imagersizes[0] ) implied_Rt10_query = \ mrcal.projection_diff( (model_baseline, model_query), distance = distance, use_uncertainties = False, focus_center = None, focus_radius = 1000.)[3] mrcal.transform_point_Rt( implied_Rt10_query, p_cam_baseline[icam], out = p_cam_query[icam] ) # shape (Ncameras, 2) return \ mrcal.project( p_cam_query, lensmodel, query_intrinsics) def reproject_perturbed__optimize_cross_reprojection_error(q, distance, # shape (Ncameras, Nintrinsics) baseline_intrinsics, # shape (Ncameras, 6) baseline_rt_cam_ref, # shape (Nframes, 6) baseline_rt_ref_frame, # shape (2) baseline_calobject_warp, # dict baseline_optimization_inputs, # shape (..., Ncameras, Nintrinsics) query_intrinsics, # shape (..., Ncameras, 6) query_rt_cam_ref, # shape (..., Nframes, 6) query_rt_ref_frame, # shape (..., 2) query_calobject_warp, # list of dicts of length ... query_optimization_inputs): r'''Reproject by explicitly computing a ref-refperturbed transformation I have a baseline solve (parameter vector b) and a perturbed solve (parameter vector bperturbed) obtained from perturbing the observations qref and re-optimizing. I also have an arbitrary baseline query pixel q and distance d from which I compute the perturbed reprojection qperturbed. I need to eventually compute Var(qperturbed). I linearize everything to get delta_qperturbed ~ dqperturbed/dbperturbed dbperturbed/dqref delta_qref. Let L = dqperturbed/dbperturbed M = dbperturbed/dqref so delta_qperturbed = L M delta_qref Then Var(qperturbed) = L M Var(qref) Mt Lt. I have M from the usual uncertainty propagation logic, so I just need L = dqperturbed/dbperturbed In my usual least squares solve each chessboard point produces two elements of the measurements x: x_point = qref - project(intrinsics, T_cam_ref T_ref_frame p) Here I optimize the reprojection error looking at the PERTURBED chessboard,frames,points and the UNPERTURBED camera intrinsics, extrinsics. This requires computing a ref transformation to take into account the shifting reference frame that results when re-optimizing: x_cross_point = qref - project(intrinsics, T_cam_ref T_ref_refperturbed T_refperturbed_frameperturbed p_perturbed) And I reoptimize norm2(x_cross_point) by varying T_ref_refperturbed. This is parametrized as rt_ref_refperturbed. Let J_cross = dx_cross_point/drt_ref_refperturbed. I assume everything is locally linear, as defined by J_cross, and I take a single Newton step. I minimize E = norm2(x_cross_point0 + dx_cross_point) I set the derivative to 0: 0 = dE/drt_ref_refperturbed ~ (x_cross_point0 + dx_cross_point)t J_cross -> J_cross_t x_cross_point0 = -J_cross_t dx_cross_point Furthermore, dx_cross_point = J_cross drt_ref_refperturbed, so J_cross_t x_cross_point0 = -J_cross_t J_cross drt_ref_refperturbed and drt_ref_refperturbed = -inv(J_cross_t J_cross) J_cross_t x_cross_point0 Everything I'm looking at implies small deviations, so I use T_ref_refperturbed=identity (rt_ref_refperturbed = 0) as the operating point, and rt_ref_refperturbed = -inv(J_cross_t J_cross) J_cross_t x_cross_point0 This is good, but implies that J_cross needs to be computed directly by propagating gradients from the projection and the transform composition. We can do better. Since everything I'm looking at is near the original solution to the main optimization problem, I can look at EVERYTHING in the linear space defined by the optimal measurements x and their gradient J. The x_cross_point expression can be simplified: x_cross_point = x_cross_point0 + J_intrinsics dintrinsics + J_extrinsics drt_cam_ref + J_frame drt_ref_frame + J_calobject_warp dcalobject_warp In the expression above we use the unperturbed intrinsics and extrinsics, so dintrinsics = 0 and drt_cam_ref = 0. The shift in the calibration object warp comes directly from the shift in parameters: dcalobject_warp = M[calobject_warp] delta_qref. That leaves drt_ref_frame. This represents a shift from the optimized rt_ref_frame to rt_ref_frameperturbed = compose_rt(rt_ref_refperturbed, rt_refperturbed_frameperturbed). For x_cross_point0, I have rt_ref_refperturbed = 0, so there I have drt_ref_frame = M[frame] delta_qref. And for the gradient I have: J_cross = dx_cross_point/drt_ref_refperturbed = J_frame drt_ref_frame/drt_ref_refperturbed which I can obtain from the transform composition functions. Now that I have rt_ref_refperturbed, I can use it to compute qperturbed. This can accept arbitrary q, not just those in the solve, so I actually need to compute projections, rather than looking at a linearized space defined by J I have pcam = unproject(intrinsics, q) pcam_perturbed = T_camperturbed_refperturbed T_refperturbed_ref T_ref_cam pcam qperturbed = project(intrinsics_perturbed, pcam_perturbed) dqperturbed/dbperturbed[intrinsics] comes directly from this project() dqperturbed/dbperturbed[extrinsics] = dqperturbed/dpcam_perturbed (dpcam_perturbed/dextrinsics + dpcam_perturbed/drt_ref_refperturbed drt_ref_refperturbed/dextrinsics) So I need gradients of rt_ref_refperturbed in respect to p_perturbed ''' if fixedframes: raise Exception("reproject_perturbed__optimize_cross_reprojection_error(fixedframes = True) is not yet implemented") def compose_rt3_withgrad_drt1(rt0, rt1, rt2): rt01,drt01_drt0,drt01_drt1 = \ mrcal.compose_rt(rt0, rt1, get_gradients = True) rt012,drt012_drt01,drt012_drt2 = \ mrcal.compose_rt(rt01, rt2, get_gradients = True) drt012_drt1 = nps.matmult(drt012_drt01, drt01_drt1) return rt012,drt012_drt1 def transform_point_rt3_withgrad_drt1(rt0, rt1, rt2, p): rt012,drt012_drt1 = compose_rt3_withgrad_drt1(rt0,rt1,rt2) pp, dpp_drt012, dpp_dp = mrcal.transform_point_rt(rt012, p, get_gradients = True) dpp_drt1 = nps.matmult(dpp_drt012, drt012_drt1) return pp, dpp_drt1 def transform_point_identity_gradient(p): r'''Computes dprot/drt where prot = transform(rt,p) and rt = identity prot = rotate(p) + t, so clearly dprot/dt = I Now let's look at the rotation mrcal_transform_point_rt_full() from rotate_point_r_core() defines prot = rotate(rt, p) at rt=identity: const val_withgrad_t cross[3] = { (rg[1]*x_ing[2] - rg[2]*x_ing[1]), (rg[2]*x_ing[0] - rg[0]*x_ing[2]), (rg[0]*x_ing[1] - rg[1]*x_ing[0]) }; const val_withgrad_t inner = rg[0]*x_ing[0] + rg[1]*x_ing[1] + rg[2]*x_ing[2]; // Small rotation. I don't want to divide by 0, so I take the limit // lim(th->0, xrot) = // = x + cross(r, x) + r rt x lim(th->0, (1 - cos(th)) / (th*th)) // = x + cross(r, x) + r rt x lim(th->0, sin(th) / (2*th)) // = x + cross(r, x) + r rt x/2 for(int i=0; i<3; i++) x_outg[i] = x_ing[i] + cross[i] + rg[i]*inner / 2.; So dprot/dr = dcross/dr + d(r*inner / 2)/dr = [ 0 p2 -p1] = [-p2 0 p0] + (inner I + outer(r,p))/2 [ p1 -p0 0] At r=identity I have r = 0, so [ 0 p2 -p1] dprot/dr = [-p2 0 p0] [ p1 -p0 0] This is the usual skew-symmetric matrix that appears in the matrix form of the cross product ''' # strange-looking implementation to make broadcasting work dprot_drt = np.zeros(p.shape[:-1] + (3,6), dtype=float) dprot_drt[...,0,1] = p[...,2] dprot_drt[...,0,2] = -p[...,1] dprot_drt[...,1,0] = -p[...,2] dprot_drt[...,1,2] = p[...,0] dprot_drt[...,2,0] = p[...,1] dprot_drt[...,2,1] = -p[...,0] dprot_drt[...,0,0+3] = 1. dprot_drt[...,1,1+3] = 1. dprot_drt[...,2,2+3] = 1. _,dprot_drt_reference,_ = \ mrcal.transform_point_rt(mrcal.identity_rt(), p, get_gradients=True) if nps.norm2((dprot_drt-dprot_drt_reference).ravel()) > 1e-10: raise Exception("transform_point_identity_gradient() is computing the wrong thing. This is a bug") return dprot_drt observations_board = \ baseline_optimization_inputs.get('observations_board') indices_frame_camintrinsics_camextrinsics = \ baseline_optimization_inputs['indices_frame_camintrinsics_camextrinsics'] object_width_n = observations_board.shape[-2] object_height_n = observations_board.shape[-3] object_spacing = baseline_optimization_inputs['calibration_object_spacing'] # shape (Nh,Nw,3) calibration_object_baseline = \ mrcal.ref_calibration_object(object_width_n, object_height_n, object_spacing, calobject_warp = baseline_calobject_warp) # need to define the broadcasted function myself @nps.broadcast_define( ((2,),) ) def ref_calibration_object(calobject_warp): return \ mrcal.ref_calibration_object(object_width_n, object_height_n, object_spacing, calobject_warp = calobject_warp) calibration_object_query = \ ref_calibration_object(query_calobject_warp) weight = observations_board[...,2] # shape (Nobservations, 6) rt_ref_frame_all = \ baseline_rt_ref_frame[ ..., indices_frame_camintrinsics_camextrinsics[:,0], :] # shape (..., Nobservations, 6) rt_refperturbed_frameperturbed_all = \ query_rt_ref_frame[ ..., indices_frame_camintrinsics_camextrinsics[:,0], :] # shape (Nobservations, Nintrinsics) intrinsics_all = \ baseline_intrinsics[ indices_frame_camintrinsics_camextrinsics[:,1], :] if nps.norm2(baseline_rt_cam_ref[0]) > 1e-12: raise Exception("I'm assuming a vanilla calibration problem reference at cam0") # shape (Nobservations, 6) rt_cam_ref_all = \ baseline_rt_cam_ref[ indices_frame_camintrinsics_camextrinsics[:,2]+1, :] # I look at the un-perturbed data first, to double-check that I'm doing the # right thing. This is purely a self-checking step. I don't need to do it if 1: if 1: # shape (Nobservations,Nh,Nw,3), pref = mrcal.transform_point_rt(nps.dummy(rt_ref_frame_all, -2,-2), calibration_object_baseline) pcam = mrcal.transform_point_rt(nps.dummy(rt_cam_ref_all, -2,-2), pref) else: # More complex form, using custom function. # shape (..., Nobservations,Nh,Nw,3), pcam, _ = \ transform_point_rt3_withgrad_drt1(nps.dummy(rt_cam_ref_all, -2,-2), mrcal.identity_rt(), p_ref) # shape (..., Nobservations,Nh,Nw,2) qq = \ mrcal.project(pcam, baseline_optimization_inputs['lensmodel'], nps.dummy(intrinsics_all, -2,-2)) x = (qq - observations_board[...,:2])*nps.dummy(weight,-1) x[...,weight<=0,:] = 0 # outliers x = x.ravel() if len(x) != mrcal.num_measurements_boards(**baseline_optimization_inputs): raise Exception("Unexpected len(x). This is a bug") x_baseline = mrcal.optimizer_callback(**baseline_optimization_inputs)[1] if nps.norm2(x - x_baseline[:len(x)]) > 1e-12: raise Exception("Unexpected x. This is a bug") E_baseline = nps.norm2(x) # Alright. I'm mimicking the optimization function well-enough. Let's look # at the crossed quantities if 1: # shape (..., Nobservations,Nh,Nw,3), pref = mrcal.transform_point_rt( nps.dummy(rt_refperturbed_frameperturbed_all, -2,-2), nps.mv(calibration_object_query,-4,-5)) dpref_drt_ref_refperturbed = transform_point_identity_gradient(pref) # shape (..., Nobservations,Nh,Nw,3), # (..., Nobservations,Nh,Nw,3,6) pcam, _, dpcam_dpref = \ mrcal.transform_point_rt(nps.dummy(rt_cam_ref_all, -2,-2), pref, get_gradients = True) dpcam_drt_ref_refperturbed = nps.matmult(dpcam_dpref, dpref_drt_ref_refperturbed) else: # More complex form, using custom function. # shape (..., Nobservations,Nh,Nw,3), # (..., Nobservations,Nh,Nw,3,6) pcam, dpcam_drt_ref_refperturbed = \ transform_point_rt3_withgrad_drt1(nps.dummy(rt_cam_ref_all, -2,-2), mrcal.identity_rt(), nps.dummy(rt_refperturbed_frameperturbed_all, -2,-2), nps.mv(calibration_object_query,-4,-5)) # shape (..., Nobservations,Nh,Nw,2) # (..., Nobservations,Nh,Nw,2,3) qq,dq_dpcam,_ = \ mrcal.project(pcam, baseline_optimization_inputs['lensmodel'], nps.dummy(intrinsics_all, -2,-2), get_gradients = True) x = (qq - observations_board[...,:2])*nps.dummy(weight,-1) x[...,weight<=0,:] = 0 # outliers # shape (..., Nobservations*Nh*Nw*2) x = nps.clump(x, n=-4) E_perturbed = nps.norm2(x) dx_dpcam = dq_dpcam*nps.dummy(weight,-1,-1) dx_dpcam[...,weight<=0,:,:] = 0 # outliers dx_drt_ref_refperturbed = nps.matmult(dx_dpcam, dpcam_drt_ref_refperturbed) # shape (...,Nobservations,Nh,Nw,2,6) -> # (...,Nobservations*Nh*Nw*2,6) -> dx_drt_ref_refperturbed = \ nps.mv(nps.clump(nps.mv(dx_drt_ref_refperturbed, -1, -5), n = -4), -2, -1) J = dx_drt_ref_refperturbed # need to define the broadcasted function myself @nps.broadcast_define((('N',6),('N',)), (6,)) def lstsq(J,x): # -inv(JtJ)Jt x0 return np.linalg.lstsq(J, x, rcond = None)[0] rt_ref_refperturbed = -lstsq(J, x) # I have a 1-step solve. Let's look at the error to confirm that it's # smaller if 1: # shape (..., Nobservations,Nh,Nw,3) pcam = \ mrcal.transform_point_rt( mrcal.compose_rt(nps.dummy(rt_cam_ref_all, -2,-2), nps.mv(rt_ref_refperturbed, -2,-5), nps.dummy(rt_refperturbed_frameperturbed_all, -2,-2)), nps.mv(calibration_object_query,-4,-5)) # shape (..., Nobservations,Nh,Nw,2) qq = \ mrcal.project(pcam, baseline_optimization_inputs['lensmodel'], nps.dummy(intrinsics_all, -2,-2), get_gradients = False) x = (qq - observations_board[...,:2])*nps.dummy(weight,-1) x[...,weight<=0,:] = 0 # outliers # shape (..., Nobservations*Nh*Nw*2) x = nps.clump(x, n=-4) E_perturbed_solvedref = nps.norm2(x) print(f"RMS error baseline = {np.sqrt(E_baseline / (x.shape[-1]/2))} pixels") print(f"RMS error perturbed = {np.sqrt(E_perturbed / (x.shape[-1]/2))} pixels") print(f"RMS error perturbed_solvedref = {np.sqrt(E_perturbed_solvedref / (x.shape[-1]/2))} pixels") # shape (Ncameras, 3) p_cam_baseline = mrcal.unproject(q, lensmodel, baseline_intrinsics, normalize = True) * distance # shape (Ncameras, 3) p_ref_baseline = \ mrcal.transform_point_rt( mrcal.invert_rt(baseline_rt_cam_ref), p_cam_baseline ) # shape (...,Ncameras, 3) p_ref_query = \ mrcal.transform_point_rt( nps.dummy(rt_ref_refperturbed, -2), p_ref_baseline, inverted = True ) # shape (..., Ncameras, 3) p_cam_query = \ mrcal.transform_point_rt(query_rt_cam_ref, p_ref_query) # shape (..., Ncameras, 2) # # If ... was (), the current code sets it to (1,). So I force the right # shape return mrcal.project(p_cam_query, lensmodel, query_intrinsics). \ reshape( *query_intrinsics.shape[:-1], 2) # Which implementation we're using. Use the method that matches the uncertainty # computation. Thus the sampled ellipsoids should match the ellipsoids reported # by the uncertianty method if re.match('mean-frames', args.reproject_perturbed): reproject_perturbed = reproject_perturbed__mean_frames elif args.reproject_perturbed == 'fit-boards-ref': reproject_perturbed = reproject_perturbed__fit_boards_ref elif args.reproject_perturbed == 'diff': reproject_perturbed = reproject_perturbed__diff elif args.reproject_perturbed == 'optimize-cross-reprojection-error': reproject_perturbed = reproject_perturbed__optimize_cross_reprojection_error else: raise Exception("getting here is a bug") q0_true = dict() for distance in args.distances: # shape (Ncameras, 2) q0_true[distance] = \ reproject_perturbed(q0_baseline, 1e5 if distance is None else distance, intrinsics_baseline, extrinsics_baseline_mounted, frames_baseline, calobject_warp_baseline, optimization_inputs_baseline, intrinsics_true, extrinsics_true_mounted, frames_true, calobject_warp_true, # optimization_inputs_sampled not available here: # the "true" values aren't the result of an # optimization None) # I check the bias for cameras 0,1. Cameras 2,3 have q0 outside of the # chessboard region, or right on its edge, so regularization DOES affect # projections there: it's the only contributor to the projection behavior in # that area for icam in range(args.Ncameras): if icam == 2 or icam == 3: continue testutils.confirm_equal(q0_true[distance][icam], q0_baseline, eps = 0.1, worstcase = True, msg = f"Regularization bias small-enough for camera {icam} at distance={'infinity' if distance is None else distance}") for icam in (0,3): # I move the extrinsics of a model, write it to disk, and make sure the same # uncertainties come back if icam >= args.Ncameras: break model_moved = mrcal.cameramodel(models_baseline[icam]) model_moved.extrinsics_rt_fromref([1., 2., 3., 4., 5., 6.]) model_moved.write(f'{workdir}/out.cameramodel') model_read = mrcal.cameramodel(f'{workdir}/out.cameramodel') icam_intrinsics_read = model_read.icam_intrinsics() icam_extrinsics_read = mrcal.corresponding_icam_extrinsics(icam_intrinsics_read, **model_read.optimization_inputs()) testutils.confirm_equal(icam if fixedframes else icam-1, icam_extrinsics_read, msg = f"corresponding icam_extrinsics reported correctly for camera {icam}") p_cam_baseline = mrcal.unproject( q0_baseline, *models_baseline[icam].intrinsics(), normalize = True) Var_dq_ref = \ mrcal.projection_uncertainty( p_cam_baseline * 1.0, model = models_baseline[icam], observed_pixel_uncertainty = pixel_uncertainty_stdev) Var_dq_moved_written_read = \ mrcal.projection_uncertainty( p_cam_baseline * 1.0, model = model_read, observed_pixel_uncertainty = pixel_uncertainty_stdev ) testutils.confirm_equal(Var_dq_moved_written_read, Var_dq_ref, eps = 0.001, worstcase = True, relative = True, msg = f"var(dq) with full rt matches for camera {icam} after moving, writing to disk, reading from disk") Var_dq_inf_ref = \ mrcal.projection_uncertainty( p_cam_baseline * 1.0, model = models_baseline[icam], atinfinity = True, observed_pixel_uncertainty = pixel_uncertainty_stdev ) Var_dq_inf_moved_written_read = \ mrcal.projection_uncertainty( p_cam_baseline * 1.0, model = model_read, atinfinity = True, observed_pixel_uncertainty = pixel_uncertainty_stdev ) testutils.confirm_equal(Var_dq_inf_moved_written_read, Var_dq_inf_ref, eps = 0.001, worstcase = True, relative = True, msg = f"var(dq) with rotation-only matches for camera {icam} after moving, writing to disk, reading from disk") # the at-infinity uncertainty should be invariant to point scalings (the # real scaling used is infinity). The not-at-infinity uncertainty is NOT # invariant, so I don't check that Var_dq_inf_far_ref = \ mrcal.projection_uncertainty( p_cam_baseline * 100.0, model = models_baseline[icam], atinfinity = True, observed_pixel_uncertainty = pixel_uncertainty_stdev ) testutils.confirm_equal(Var_dq_inf_far_ref, Var_dq_inf_ref, eps = 0.001, worstcase = True, relative = True, msg = f"var(dq) (infinity) is invariant to point scale for camera {icam}") if not args.do_sample: testutils.finish() sys.exit() ( intrinsics_sampled, \ extrinsics_sampled_mounted, \ frames_sampled, \ points_sampled, \ calobject_warp_sampled, \ optimization_inputs_sampled ) = \ calibration_sample( args.Nsamples, optimization_inputs_baseline, pixel_uncertainty_stdev, fixedframes) def check_uncertainties_at(q0_baseline, idistance): distance = args.distances[idistance] # distance of "None" means I'll simulate a large distance, but compare # against a special-case distance of "infinity" if distance is None: distance = 1e5 atinfinity = True distancestr = "infinity" else: atinfinity = False distancestr = str(distance) # shape (Ncameras,3) p_cam_baseline = mrcal.unproject(q0_baseline, lensmodel, intrinsics_baseline, normalize = True) * distance # shape (Nsamples, Ncameras, 2) q_sampled = \ reproject_perturbed(q0_baseline, distance, intrinsics_baseline, extrinsics_baseline_mounted, frames_baseline, calobject_warp_baseline, optimization_inputs_baseline, intrinsics_sampled, extrinsics_sampled_mounted, frames_sampled, calobject_warp_sampled, optimization_inputs_sampled) # shape (Ncameras, 2) q_sampled_mean = np.mean(q_sampled, axis=-3) # shape (Ncameras, 2,2) Var_dq_observed = np.mean( nps.outer(q_sampled-q_sampled_mean, q_sampled-q_sampled_mean), axis=-4 ) # shape (Ncameras) worst_direction_stdev_observed = mrcal.worst_direction_stdev(Var_dq_observed) # shape (Ncameras, 2,2) Var_dq = \ nps.cat(*[ mrcal.projection_uncertainty( \ p_cam_baseline[icam], atinfinity = atinfinity, model = models_baseline[icam], observed_pixel_uncertainty = pixel_uncertainty_stdev) \ for icam in range(args.Ncameras) ]) # shape (Ncameras) worst_direction_stdev_predicted = mrcal.worst_direction_stdev(Var_dq) # q_sampled should be evenly distributed around q0_baseline. I can make eps # as tight as I want by increasing Nsamples testutils.confirm_equal( nps.mag(q_sampled_mean - q0_baseline), 0, eps = 0.3, worstcase = True, msg = f"Sampled projections cluster around the sample point at distance = {distancestr}") # I accept 20% error. This is plenty good-enough. And I can get tighter matches # if I grab more samples testutils.confirm_equal(worst_direction_stdev_observed, worst_direction_stdev_predicted, eps = 0.2, worstcase = True, relative = True, msg = f"Predicted worst-case projections match sampled observations at distance = {distancestr}") # I now compare the variances. The cross terms have lots of apparent error, # but it's more meaningful to compare the eigenvectors and eigenvalues, so I # just do that for icam in range(args.Ncameras): testutils.confirm_covariances_equal(Var_dq[icam], Var_dq_observed[icam], what = f"camera {icam} at distance = {distancestr}", # high error tolerances; Nsamples is too low for better eps_eigenvalues = 0.35, eps_eigenvectors_deg = 15) return q_sampled,Var_dq q_sampled,Var_dq = check_uncertainties_at(q0_baseline, 0) for idistance in range(1,len(args.distances)): check_uncertainties_at(q0_baseline, idistance) if not (args.explore or \ args.show_distribution or \ args.make_documentation_plots is not None): testutils.finish() sys.exit() import gnuplotlib as gp def make_plot(icam, report_center_points = True, **kwargs): q_sampled_mean = np.mean(q_sampled[:,icam,:],axis=-2) def make_tuple(*args): return args data_tuples = \ make_tuple(*mrcal.utils._plot_args_points_and_covariance_ellipse(q_sampled[:,icam,:], "Observed uncertainty"), mrcal.utils._plot_arg_covariance_ellipse(q_sampled_mean, Var_dq[icam], "Predicted uncertainty"),) if report_center_points: data_tuples += \ ( (q0_baseline, dict(tuplesize = -2, _with = 'points pt 3 ps 3', legend = 'Baseline center point')), (q0_true[args.distances[0]][icam], dict(tuplesize = -2, _with = 'points pt 3 ps 3', legend = 'True center point')), (q_sampled_mean, dict(tuplesize = -2, _with = 'points pt 3 ps 3', legend = 'Sampled mean'))) plot_options = \ dict(square=1, _xrange=(q0_baseline[0]-2,q0_baseline[0]+2), _yrange=(q0_baseline[1]-2,q0_baseline[1]+2), title=f'Uncertainty reprojection distribution for camera {icam}', **kwargs) gp.add_plot_option(plot_options, 'set', ('xtics 1', 'ytics 1')) return data_tuples, plot_options if args.show_distribution: plot_distribution = [None] * args.Ncameras for icam in range(args.Ncameras): data_tuples, plot_options = make_plot(icam) if args.extra_observation_at is not None: plot_options['title'] += f': boards at {args.range_to_boards}m, extra one at {args.extra_observation_at}m' plot_distribution[icam] = gp.gnuplotlib(**plot_options) plot_distribution[icam].plot(*data_tuples) if args.make_documentation_plots is not None: data_tuples_plot_options = \ [ make_plot(icam, report_center_points=False) \ for icam in range(args.Ncameras) ] plot_options = data_tuples_plot_options[0][1] del plot_options['title'] gp.add_plot_option(plot_options, 'unset', 'key') data_tuples = [ data_tuples_plot_options[icam][0] for icam in range(args.Ncameras) ] if args.make_documentation_plots: for extension in ('pdf','svg','png','gp'): processoptions_output = dict(wait = False, terminal = terminal[extension], _set = extraset[extension], hardcopy = f'{args.make_documentation_plots}--distribution-onepoint.{extension}') gp.plot( *data_tuples, **plot_options, multiplot = f'layout 2,2', **processoptions_output) else: processoptions_output = dict(wait = True) gp.plot( *data_tuples, **plot_options, multiplot = f'layout 2,2', **processoptions_output) data_tuples_plot_options = \ [ mrcal.show_projection_uncertainty( models_baseline[icam], observed_pixel_uncertainty = pixel_uncertainty_stdev, observations = 'dots', distance = args.distances[0], contour_increment = -0.4, contour_labels_styles = '', return_plot_args = True) \ for icam in range(args.Ncameras) ] plot_options = data_tuples_plot_options[0][1] del plot_options['title'] gp.add_plot_option(plot_options, 'unset', 'key') gp.add_plot_option(plot_options, 'set', ('xtics 1000', 'ytics 1000')) if args.make_documentation_plots: for extension in ('pdf','svg','png','gp'): if extension == 'png': continue data_tuples = [ data_tuples_plot_options[icam][0] + \ [(q0_baseline[0], q0_baseline[1], 0, \ dict(tuplesize = 3, _with =f'points pt 3 lw 2 lc "red" ps {2*pointscale[extension]} nocontour'))] \ for icam in range(args.Ncameras) ] # look through all the plots # look through all the data tuples in each plot # look at the last data tuple # if it's dict(_with = 'dots ...'): ignore it def is_datatuple_withdots(t): d = t[-1] if type(d) is not dict: return False if '_with' not in d: return False w = d['_with'] if type(w) is not str: return False return re.match('dots',w) is not None def subplots_noobservations(p): return \ [ t for t in p if not is_datatuple_withdots(t) ] data_tuples_no_observations = \ [ subplots_noobservations(p) for p in data_tuples ] for obs_yesno, dt in (('observations', data_tuples), ('noobservations', data_tuples_no_observations)): processoptions_output = dict(wait = False, terminal = shorter_terminal(terminal[extension]), _set = extraset[extension], hardcopy = f'{args.make_documentation_plots}--uncertainty-wholeimage-{obs_yesno}.{extension}') if '_set' in processoptions_output: gp.add_plot_option(plot_options, 'set', processoptions_output['_set']) del processoptions_output['_set'] gp.plot( *dt, **plot_options, multiplot = f'layout 2,2', **processoptions_output) else: data_tuples = [ data_tuples_plot_options[icam][0] + \ [(q0_baseline[0], q0_baseline[1], 0, \ dict(tuplesize = 3, _with =f'points pt 3 lw 2 lc "red" ps {2*pointscale[""]} nocontour'))] \ for icam in range(args.Ncameras) ] processoptions_output = dict(wait = True) if '_set' in processoptions_output: gp.add_plot_option(plot_options, 'set', processoptions_output['_set']) del processoptions_output['_set'] gp.plot( *data_tuples, **plot_options, multiplot = f'layout 2,2', **processoptions_output) if args.explore: import IPython IPython.embed() mrcal-2.4.1/test/test-projections.py000077500000000000000000000600301456301662300174710ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Tests for project() and unproject() Here I make sure the projection functions return the correct values. A part of this is a regression test: the "right" project() results were recorded at some point, and any deviation is flagged. This also test gradients, normalization and in-place output. I want to check all combinations of add others here: latlon, lonlat, stereographic. Broadcasted and not. Test the project() and unproject() paths - project/unproject - get_gradients: yes/no - model simple: yes/no - broadcasted: yes/no - unproject normalize: yes/no - explicit "out" in args check() covers all of these for ONE model ''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils from test_calibration_helpers import grad import re def check(intrinsics, p_ref, q_ref): ########## project q_projected = mrcal.project(p_ref, *intrinsics) testutils.confirm_equal(q_projected, q_ref, msg = f"Projecting {intrinsics[0]}", eps = 1e-2) q_projected *= 0 mrcal.project(p_ref, *intrinsics, out = q_projected) testutils.confirm_equal(q_projected, q_ref, msg = f"Projecting {intrinsics[0]} in-place", eps = 1e-2) meta = mrcal.lensmodel_metadata_and_config(intrinsics[0]) if meta['has_gradients']: @nps.broadcast_define( ((3,),('N',)) ) def grad_broadcasted(p_ref, i_ref): return grad(lambda pi: mrcal.project(pi[:3], intrinsics[0], pi[3:]), nps.glue(p_ref,i_ref, axis=-1)) dq_dpi_ref = grad_broadcasted(p_ref,intrinsics[1]) q_projected,dq_dp,dq_di = mrcal.project(p_ref, *intrinsics, get_gradients=True) testutils.confirm_equal(q_projected, q_ref, msg = f"Projecting {intrinsics[0]} with grad", eps = 1e-2) testutils.confirm_equal(dq_dp, dq_dpi_ref[...,:3], msg = f"dq_dp {intrinsics[0]}", eps = 1e-2) testutils.confirm_equal(dq_di, dq_dpi_ref[...,3:], msg = f"dq_di {intrinsics[0]}", eps = 1e-2) out=[q_projected,dq_dp,dq_di] out[0] *= 0 out[1] *= 0 out[2] *= 0 mrcal.project(p_ref, *intrinsics, get_gradients=True, out=out) testutils.confirm_equal(q_projected, q_ref, msg = f"Projecting {intrinsics[0]} with grad in-place", eps = 1e-2) testutils.confirm_equal(dq_dp, dq_dpi_ref[...,:3], msg = f"dq_dp in-place", eps = 1e-2) testutils.confirm_equal(dq_di, dq_dpi_ref[...,3:], msg = f"dq_di in-place", eps = 1e-2) if meta['noncentral']: if re.match('LENSMODEL_CAHVORE',intrinsics[0]): # CAHVORE. I set E=0, and the projection becomes central. Then # unproject() is well-defined and I can run the tests intrinsics[1][-3:] = 0 q_projected = mrcal.project(p_ref, *intrinsics) else: # Some other kind of noncentral model. I don't bother with # unproject() return ########## unproject if 1: ##### Un-normalized v_unprojected = mrcal.unproject(q_projected, *intrinsics, normalize = False) cos = nps.inner(v_unprojected, p_ref) / nps.mag(p_ref) cos = np.clip(cos, -1, 1) testutils.confirm_equal( np.arccos(cos), np.zeros((p_ref.shape[0],), dtype=float), msg = f"Unprojecting {intrinsics[0]}", eps = 1e-6) if 1: ##### Normalized v_unprojected_nograd = mrcal.unproject(q_projected, *intrinsics, normalize = True) testutils.confirm_equal( nps.norm2(v_unprojected_nograd), 1, msg = f"Unprojected v are normalized", eps = 1e-6) cos = nps.inner(v_unprojected_nograd, p_ref) / nps.mag(p_ref) cos = np.clip(cos, -1, 1) testutils.confirm_equal( np.arccos(cos), np.zeros((p_ref.shape[0],), dtype=float), msg = f"Unprojecting {intrinsics[0]} (normalized)", eps = 1e-6) if not meta['has_gradients']: # no in-place output for the no-gradients unproject() path return v_unprojected *= 0 mrcal.unproject(q_projected, *intrinsics, normalize = True, out = v_unprojected) testutils.confirm_equal( nps.norm2(v_unprojected), 1, msg = f"Unprojected in-place v are normalized", eps = 1e-6) cos = nps.inner(v_unprojected, p_ref) / nps.mag(p_ref) cos = np.clip(cos, -1, 1) testutils.confirm_equal( np.arccos(cos), np.zeros((p_ref.shape[0],), dtype=float), msg = f"Unprojecting in-place {intrinsics[0]}", eps = 1e-6) ### unproject gradients v_unprojected,dv_dq,dv_di = mrcal.unproject(q_projected, *intrinsics, get_gradients=True) # I'd like to turn this on, but unproject() doesn't behave the way it # should, so this test always fails currently # # testutils.confirm_equal( v_unprojected, # v_unprojected_nograd, # msg = f"Unproject() should return the same thing whether get_gradients or not", # eps = 1e-6) if re.match('^LENSMODEL_CAHVORE',intrinsics[0]): dv_dqi_ref = None else: # Two different gradient computations, to match the two different ways the # internal computation is performed if intrinsics[0] == 'LENSMODEL_PINHOLE' or \ intrinsics[0] == 'LENSMODEL_STEREOGRAPHIC' or \ intrinsics[0] == 'LENSMODEL_LATLON' or \ intrinsics[0] == 'LENSMODEL_LONLAT': @nps.broadcast_define( ((2,),('N',)) ) def grad_broadcasted(q_ref, i_ref): return grad(lambda qi: mrcal.unproject(qi[:2], intrinsics[0], qi[2:]), nps.glue(q_ref,i_ref, axis=-1)) dv_dqi_ref = grad_broadcasted(q_projected,intrinsics[1]) else: @nps.broadcast_define( ((2,),('N',)) ) def grad_broadcasted(q_ref, i_ref): return grad(lambda qi: \ mrcal.unproject_stereographic( \ mrcal.project_stereographic( mrcal.unproject(qi[:2], intrinsics[0], qi[2:]))), nps.glue(q_ref,i_ref, axis=-1)) dv_dqi_ref = grad_broadcasted(q_projected,intrinsics[1]) testutils.confirm_equal(mrcal.project(v_unprojected, *intrinsics), q_projected, msg = f"Unprojecting {intrinsics[0]} with grad", eps = 1e-2) testutils.confirm_equal(dv_dq, dv_dqi_ref[...,:2], msg = f"dv_dq: {intrinsics[0]}", worstcase = True, relative = True, eps = 0.01) testutils.confirm_equal(dv_di, dv_dqi_ref[...,2:], msg = f"dv_di {intrinsics[0]}", worstcase = True, relative = True, eps = 0.01) # Normalized unprojected gradients v_unprojected,dv_dq,dv_di = mrcal.unproject(q_projected, *intrinsics, normalize = True, get_gradients = True) testutils.confirm_equal( nps.norm2(v_unprojected), 1, msg = f"Unprojected v (with gradients) are normalized", eps = 1e-6) cos = nps.inner(v_unprojected, p_ref) / nps.mag(p_ref) cos = np.clip(cos, -1, 1) testutils.confirm_equal( np.arccos(cos), np.zeros((p_ref.shape[0],), dtype=float), msg = f"Unprojecting (normalized, with gradients) {intrinsics[0]}", eps = 1e-6) if re.match('^LENSMODEL_CAHVORE',intrinsics[0]): dvnormalized_dqi_ref = None else: @nps.broadcast_define( ((2,),('N',)) ) def grad_normalized_broadcasted(q_ref, i_ref): return grad(lambda qi: \ mrcal.unproject(qi[:2], intrinsics[0], qi[2:], normalize=True), nps.glue(q_ref,i_ref, axis=-1)) dvnormalized_dqi_ref = grad_normalized_broadcasted(q_projected,intrinsics[1]) testutils.confirm_equal(dv_dq, dvnormalized_dqi_ref[...,:2], msg = f"dv_dq (normalized v): {intrinsics[0]}", worstcase = True, relative = True, eps = 0.01) testutils.confirm_equal(dv_di, dvnormalized_dqi_ref[...,2:], msg = f"dv_di (normalized v): {intrinsics[0]}", worstcase = True, relative = True, eps = 0.01) # unproject() with gradients, in-place if 1: # Normalized output out=[v_unprojected,dv_dq,dv_di] out[0] *= 0 out[1] *= 0 out[2] *= 0 mrcal.unproject(q_projected, *intrinsics, normalize = True, get_gradients = True, out = out) testutils.confirm_equal( nps.norm2(v_unprojected), 1, msg = f"Unprojected v (with gradients, in-place) are normalized", eps = 1e-6) cos = nps.inner(v_unprojected, p_ref) / nps.mag(p_ref) cos = np.clip(cos, -1, 1) testutils.confirm_equal( np.arccos(cos), np.zeros((p_ref.shape[0],), dtype=float), msg = f"Unprojecting (normalized, with gradients, in-place) {intrinsics[0]}", eps = 1e-6) if dvnormalized_dqi_ref is not None: testutils.confirm_equal(dv_dq, dvnormalized_dqi_ref[...,:2], msg = f"dv_dq (normalized v, in-place): {intrinsics[0]}", worstcase = True, relative = True, eps = 0.01) testutils.confirm_equal(dv_di, dvnormalized_dqi_ref[...,2:], msg = f"dv_di (normalized v, in-place): {intrinsics[0]}", worstcase = True, relative = True, eps = 0.01) if 1: # un-normalized output out=[v_unprojected,dv_dq,dv_di] out[0] *= 0 out[1] *= 0 out[2] *= 0 mrcal.unproject(q_projected, *intrinsics, normalize = False, get_gradients = True, out = out) cos = nps.inner(v_unprojected, p_ref) / nps.mag(p_ref) cos = np.clip(cos, -1, 1) testutils.confirm_equal( np.arccos(cos), np.zeros((p_ref.shape[0],), dtype=float), msg = f"Unprojecting (non-normalized, with gradients, in-place) {intrinsics[0]}", eps = 1e-6) if dv_dqi_ref is not None: testutils.confirm_equal(dv_dq, dv_dqi_ref[...,:2], msg = f"dv_dq (unnormalized v, in-place): {intrinsics[0]}", worstcase = True, relative = True, eps = 0.01) testutils.confirm_equal(dv_di, dv_dqi_ref[...,2:], msg = f"dv_di (unnormalized v, in-place): {intrinsics[0]}", worstcase = True, relative = True, eps = 0.01) # a few points, some wide, some not. None behind the camera p = np.array(((1.0, 2.0, 10.0), (-1.1, 0.3, 1.0), (-0.9, -1.5, 1.0))) check( ('LENSMODEL_PINHOLE', np.array(((1512., 1112, 500., 333.), (1512., 1112, 500., 433.), (1512., 1112, 500., 533.)))), p, np.array([[ 651.2, 555.4], [-1163.2, 766.6], [ -860.8, -1135. ]])) check( ('LENSMODEL_STEREOGRAPHIC', np.array(((1512., 1112, 500., 333.), (1502., 1112, 500., 433.), (1522., 1112, 500., 533.)))), p, np.array([[ 649.35582325, 552.6874014], [-813.05440267, 698.1222302], [-408.67354332, -573.48815174]])) check( ('LENSMODEL_LATLON', np.array(((1512., 1112, 500., 333.), (1502., 1112, 500., 433.), (1522., 1112, 500., 533.)))), p, np.array([[ 647.79131656, 552.50386255], [-718.86844854, 757.09995546], [-204.73403533, -559.86662025]])) check( ('LENSMODEL_LONLAT', np.array(((1512., 1112, 500., 333.), (1502., 1112, 500., 433.), (1522., 1112, 500., 533.)))), p, np.array([[ 650.69900257, 551.44238248], [-751.13786254, 654.42977413], [-615.34458492, -400.73749463]])) check( ('LENSMODEL_OPENCV4', np.array((1512., 1112, 500., 333., -0.012, 0.035, -0.001, 0.002))), p, np.array([[ 651.27371 , 555.23042 ], [-1223.38516 , 678.01468 ], [-1246.7310448, -1822.799928 ]])) check( ('LENSMODEL_OPENCV5', np.array((1512., 1112, 500., 333., -0.012, 0.035, -0.001, 0.002, 0.019))), p, np.array([[ 651.2740691 , 555.2309482 ], [-1292.8121176 , 691.9401448 ], [-1987.550162 , -2730.85863427]])) check( ('LENSMODEL_OPENCV8', np.array((1512., 1112, 500., 333., -0.012, 0.035, -0.001, 0.002, 0.019, 0.014, -0.056, 0.050))), p, np.array([[ 651.1885442 , 555.10514968], [-1234.45480366, 680.23499814], [ -770.03274263, -1238.4871943 ]])) check( ('LENSMODEL_CAHVOR', np.array((4842.918, 4842.771, 1970.528, 1085.302, -0.001, 0.002, -0.637, -0.002, 0.016))), p, np.array([[ 2143.17840406, 1442.93419919], [ -92.63813066, 1653.09646897], [ -249.83199315, -2606.46477164]])) # E ~ 0: almost central check( ('LENSMODEL_CAHVORE_linearity=0.00', np.array((4842.918, 4842.771, 1970.528, 1085.302, -0.001, 0.002, -0.637, -0.002, 0.016, 1e-8, 2e-8, 3e-8))), p, np.array(([2140.340769278752759, 1437.371480086463635], [496.634661939782575, 1493.316705796434917], [970.117888562484495, -568.301135889864668]))) # E != 0: noncentral check( ('LENSMODEL_CAHVORE_linearity=0.00', np.array((4842.918, 4842.771, 1970.528, 1085.302, -0.001, 0.002, -0.637, -0.002, 0.016, 1e-2, 2e-2, 3e-2))), p, np.array(([2140.342263050081783, 1437.374408380910836], [491.682975341940221, 1494.659342555658441], [962.730552352575160, -580.643118338666000]))) # E != 0: noncentral. AND linearity > 0 check( ('LENSMODEL_CAHVORE_linearity=0.40', np.array((4842.918, 4842.771, 1970.528, 1085.302, -0.001, 0.002, -0.637, -0.002, 0.016, 1e-2, 2e-2, 3e-2))), p, np.array(([2140.788976358770469, 1438.250116781426641], [426.278593220184689, 1512.393568241352796], [882.926242407330619, -713.971745152981612]))) # Note that some of the projected points are behind the camera (z<0), which is # possible with these models. Also note that some of the projected points are # off the imager (x<0). This is aphysical, but it just means that the model was # made up; which it was. The math still works normally, and this is just fine as # a test check( ('LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=11_Ny=8_fov_x_deg=200', np.array([ 1500.0, 1800.0, 1499.5,999.5, 2.017284705,1.242204557,2.053514381,1.214368063,2.0379067,1.212609628, 2.033278227,1.183689487,2.040018023,1.188554431,2.069146825,1.196304649, 2.085708658,1.186478238,2.065787617,1.163377825,2.086372192,1.138856716, 2.131609155,1.125678279,2.128812604,1.120525061,2.00841491,1.21864154, 2.024522768,1.239588759,2.034947935,1.19814079,2.065474055,1.19897294, 2.044562395,1.200557321,2.087714092,1.160440038,2.086478691,1.151822407, 2.112862582,1.147567288,2.101575718,1.146312256,2.10056469,1.157015327, 2.113488262,1.111679758,2.019837901,1.244168216,2.025847768,1.215633807, 2.041980956,1.205751212,2.075077056,1.199787561,2.070877831,1.203261678, 2.067244278,1.184705736,2.082225077,1.185558149,2.091519961,1.17501817, 2.120258866,1.137775228,2.120020747,1.152409316,2.121870228,1.113069319, 2.043650555,1.247757041,2.019661062,1.230723629,2.067917203,1.209753396, 2.035034141,1.219514335,2.045350268,1.178474255,2.046346049,1.169372592, 2.097839998,1.194836758,2.112724938,1.172186377,2.110996386,1.154899043, 2.128456883,1.133228404,2.122513384,1.131717886,2.044279196,1.233288366, 2.023197297,1.230118703,2.06707694,1.199998862,2.044147271,1.191607451, 2.058590053,1.1677808,2.081593501,1.182074581,2.08663053,1.159156329, 2.084329086,1.157727374,2.073666528,1.151261965,2.114290905,1.144710519, 2.138600912,1.119405248,2.016299528,1.206147494,2.029434175,1.211507857, 2.057936091,1.19801196,2.035691392,1.174035359,2.084718618,1.203604729, 2.085910021,1.158385222,2.080800068,1.150199852,2.087991586,1.162019581, 2.094754507,1.151061493,2.115144642,1.154299799,2.107014195,1.127608146, 2.005632475,1.238607328,2.02033157,1.202101384,2.061021703,1.214868271, 2.043015135,1.211903685,2.05291186,1.188092787,2.09486724,1.179277314, 2.078230124,1.186273023,2.077743945,1.148028845,2.081634186,1.131207467, 2.112936851,1.126412871,2.113220553,1.114991063,2.017901873,1.244588667, 2.051238803,1.201855728,2.043256406,1.216674722,2.035286046,1.178380907, 2.08028318,1.178783085,2.051214271,1.173560417,2.059298121,1.182414688, 2.094607679,1.177960959,2.086998287,1.147371259,2.12029442,1.138197348, 2.138994213, 1.114846113,],)), # some points behind the camera! np.array([[-0.8479983, -0.52999894, -0.34690877], [-0.93984618, 0.34159794, -0.16119387], [-0.97738792, 0.21145412, 5.49068928]]), np.array([[ 965.9173441 , 524.31894367], [1246.58668369, 4621.35427783], [4329.41598149, 3183.75121559]])) check( ('LENSMODEL_SPLINED_STEREOGRAPHIC_order=2_Nx=11_Ny=8_fov_x_deg=200', np.array([ 1500.0, 1800.0, 1499.5,999.5, 2.017284705,1.242204557,2.053514381,1.214368063,2.0379067,1.212609628, 2.033278227,1.183689487,2.040018023,1.188554431,2.069146825,1.196304649, 2.085708658,1.186478238,2.065787617,1.163377825,2.086372192,1.138856716, 2.131609155,1.125678279,2.128812604,1.120525061,2.00841491,1.21864154, 2.024522768,1.239588759,2.034947935,1.19814079,2.065474055,1.19897294, 2.044562395,1.200557321,2.087714092,1.160440038,2.086478691,1.151822407, 2.112862582,1.147567288,2.101575718,1.146312256,2.10056469,1.157015327, 2.113488262,1.111679758,2.019837901,1.244168216,2.025847768,1.215633807, 2.041980956,1.205751212,2.075077056,1.199787561,2.070877831,1.203261678, 2.067244278,1.184705736,2.082225077,1.185558149,2.091519961,1.17501817, 2.120258866,1.137775228,2.120020747,1.152409316,2.121870228,1.113069319, 2.043650555,1.247757041,2.019661062,1.230723629,2.067917203,1.209753396, 2.035034141,1.219514335,2.045350268,1.178474255,2.046346049,1.169372592, 2.097839998,1.194836758,2.112724938,1.172186377,2.110996386,1.154899043, 2.128456883,1.133228404,2.122513384,1.131717886,2.044279196,1.233288366, 2.023197297,1.230118703,2.06707694,1.199998862,2.044147271,1.191607451, 2.058590053,1.1677808,2.081593501,1.182074581,2.08663053,1.159156329, 2.084329086,1.157727374,2.073666528,1.151261965,2.114290905,1.144710519, 2.138600912,1.119405248,2.016299528,1.206147494,2.029434175,1.211507857, 2.057936091,1.19801196,2.035691392,1.174035359,2.084718618,1.203604729, 2.085910021,1.158385222,2.080800068,1.150199852,2.087991586,1.162019581, 2.094754507,1.151061493,2.115144642,1.154299799,2.107014195,1.127608146, 2.005632475,1.238607328,2.02033157,1.202101384,2.061021703,1.214868271, 2.043015135,1.211903685,2.05291186,1.188092787,2.09486724,1.179277314, 2.078230124,1.186273023,2.077743945,1.148028845,2.081634186,1.131207467, 2.112936851,1.126412871,2.113220553,1.114991063,2.017901873,1.244588667, 2.051238803,1.201855728,2.043256406,1.216674722,2.035286046,1.178380907, 2.08028318,1.178783085,2.051214271,1.173560417,2.059298121,1.182414688, 2.094607679,1.177960959,2.086998287,1.147371259,2.12029442,1.138197348, 2.138994213, 1.114846113,],)), # some points behind the camera! np.array([[-0.8479983, -0.52999894, -0.34690877], [-0.93984618, 0.34159794, -0.16119387], [-0.97738792, 0.21145412, 5.49068928]]), np.array([[ 958.48347896, 529.99410342], [1229.87308989, 4625.05434521], [4327.8166836 , 3183.44237796]])) testutils.finish() mrcal-2.4.1/test/test-py-gradients.py000077500000000000000000000175631456301662300175550ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Tests gradients reported by the python code This is conceptually similar to test-gradients.py, but here I validate the python code path ''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils intrinsics = \ ( ('LENSMODEL_PINHOLE', np.array((1512., 1112, 500., 333.))), ('LENSMODEL_STEREOGRAPHIC', np.array((1512., 1112, 500., 333.))), ('LENSMODEL_OPENCV4', np.array((1512., 1112, 500., 333., -0.012, 0.035, -0.001, 0.002))), ('LENSMODEL_CAHVOR', np.array((4842.918,4842.771,1970.528,1085.302, -0.001, 0.002, -0.637, -0.002, 0.016))), ('LENSMODEL_SPLINED_STEREOGRAPHIC_order=3_Nx=11_Ny=8_fov_x_deg=200', np.array([ 1900, 1800, 1499.5,999.5, 2.017284705,1.242204557,2.053514381,1.214368063,2.0379067,1.212609628, 2.033278227,1.183689487,2.040018023,1.188554431,2.069146825,1.196304649, 2.085708658,1.186478238,2.065787617,1.163377825,2.086372192,1.138856716, 2.131609155,1.125678279,2.128812604,1.120525061,2.00841491,1.21864154, 2.024522768,1.239588759,2.034947935,1.19814079,2.065474055,1.19897294, 2.044562395,1.200557321,2.087714092,1.160440038,2.086478691,1.151822407, 2.112862582,1.147567288,2.101575718,1.146312256,2.10056469,1.157015327, 2.113488262,1.111679758,2.019837901,1.244168216,2.025847768,1.215633807, 2.041980956,1.205751212,2.075077056,1.199787561,2.070877831,1.203261678, 2.067244278,1.184705736,2.082225077,1.185558149,2.091519961,1.17501817, 2.120258866,1.137775228,2.120020747,1.152409316,2.121870228,1.113069319, 2.043650555,1.247757041,2.019661062,1.230723629,2.067917203,1.209753396, 2.035034141,1.219514335,2.045350268,1.178474255,2.046346049,1.169372592, 2.097839998,1.194836758,2.112724938,1.172186377,2.110996386,1.154899043, 2.128456883,1.133228404,2.122513384,1.131717886,2.044279196,1.233288366, 2.023197297,1.230118703,2.06707694,1.199998862,2.044147271,1.191607451, 2.058590053,1.1677808,2.081593501,1.182074581,2.08663053,1.159156329, 2.084329086,1.157727374,2.073666528,1.151261965,2.114290905,1.144710519, 2.138600912,1.119405248,2.016299528,1.206147494,2.029434175,1.211507857, 2.057936091,1.19801196,2.035691392,1.174035359,2.084718618,1.203604729, 2.085910021,1.158385222,2.080800068,1.150199852,2.087991586,1.162019581, 2.094754507,1.151061493,2.115144642,1.154299799,2.107014195,1.127608146, 2.005632475,1.238607328,2.02033157,1.202101384,2.061021703,1.214868271, 2.043015135,1.211903685,2.05291186,1.188092787,2.09486724,1.179277314, 2.078230124,1.186273023,2.077743945,1.148028845,2.081634186,1.131207467, 2.112936851,1.126412871,2.113220553,1.114991063,2.017901873,1.244588667, 2.051238803,1.201855728,2.043256406,1.216674722,2.035286046,1.178380907, 2.08028318,1.178783085,2.051214271,1.173560417,2.059298121,1.182414688, 2.094607679,1.177960959,2.086998287,1.147371259,2.12029442,1.138197348, 2.138994213, 1.114846113,])), ('LENSMODEL_SPLINED_STEREOGRAPHIC_order=2_Nx=11_Ny=8_fov_x_deg=200', np.array([ 1900, 1800, 1499.5,999.5, 2.017284705,1.242204557,2.053514381,1.214368063,2.0379067,1.212609628, 2.033278227,1.183689487,2.040018023,1.188554431,2.069146825,1.196304649, 2.085708658,1.186478238,2.065787617,1.163377825,2.086372192,1.138856716, 2.131609155,1.125678279,2.128812604,1.120525061,2.00841491,1.21864154, 2.024522768,1.239588759,2.034947935,1.19814079,2.065474055,1.19897294, 2.044562395,1.200557321,2.087714092,1.160440038,2.086478691,1.151822407, 2.112862582,1.147567288,2.101575718,1.146312256,2.10056469,1.157015327, 2.113488262,1.111679758,2.019837901,1.244168216,2.025847768,1.215633807, 2.041980956,1.205751212,2.075077056,1.199787561,2.070877831,1.203261678, 2.067244278,1.184705736,2.082225077,1.185558149,2.091519961,1.17501817, 2.120258866,1.137775228,2.120020747,1.152409316,2.121870228,1.113069319, 2.043650555,1.247757041,2.019661062,1.230723629,2.067917203,1.209753396, 2.035034141,1.219514335,2.045350268,1.178474255,2.046346049,1.169372592, 2.097839998,1.194836758,2.112724938,1.172186377,2.110996386,1.154899043, 2.128456883,1.133228404,2.122513384,1.131717886,2.044279196,1.233288366, 2.023197297,1.230118703,2.06707694,1.199998862,2.044147271,1.191607451, 2.058590053,1.1677808,2.081593501,1.182074581,2.08663053,1.159156329, 2.084329086,1.157727374,2.073666528,1.151261965,2.114290905,1.144710519, 2.138600912,1.119405248,2.016299528,1.206147494,2.029434175,1.211507857, 2.057936091,1.19801196,2.035691392,1.174035359,2.084718618,1.203604729, 2.085910021,1.158385222,2.080800068,1.150199852,2.087991586,1.162019581, 2.094754507,1.151061493,2.115144642,1.154299799,2.107014195,1.127608146, 2.005632475,1.238607328,2.02033157,1.202101384,2.061021703,1.214868271, 2.043015135,1.211903685,2.05291186,1.188092787,2.09486724,1.179277314, 2.078230124,1.186273023,2.077743945,1.148028845,2.081634186,1.131207467, 2.112936851,1.126412871,2.113220553,1.114991063,2.017901873,1.244588667, 2.051238803,1.201855728,2.043256406,1.216674722,2.035286046,1.178380907, 2.08028318,1.178783085,2.051214271,1.173560417,2.059298121,1.182414688, 2.094607679,1.177960959,2.086998287,1.147371259,2.12029442,1.138197348, 2.138994213, 1.114846113,]))) # a few points, some wide, some not. None behind the camera p = np.array(((1.0, 2.0, 10.0), (-1.1, 0.3, 1.0), (-0.9, -1.5, 1.0))) delta = 1e-6 for i in intrinsics: q,dq_dp,dq_di = mrcal.project(p, *i, get_gradients=True) Nintrinsics = mrcal.lensmodel_num_params(i[0]) testutils.confirm_equal(dq_di.shape[-1], Nintrinsics, msg=f"{i[0]}: Nintrinsics match for {i[0]}") if Nintrinsics != dq_di.shape[-1]: continue for ivar in range(dq_dp.shape[-1]): # center differences p1 = p.copy() p1[..., ivar] = p[..., ivar] - delta/2 q1 = mrcal.project(p1, *i, get_gradients=False) p1[..., ivar] += delta q2 = mrcal.project(p1, *i, get_gradients=False) dq_dp_observed = (q2 - q1) / delta dq_dp_reported = dq_dp[..., ivar] testutils.confirm_equal(dq_dp_reported, dq_dp_observed, eps=1e-5, msg=f"{i[0]}: dq_dp matches for var {ivar}") for ivar in range(dq_di.shape[-1]): # center differences i1 = i[1].copy() i1[..., ivar] = i[1][..., ivar] - delta/2 q1 = mrcal.project(p, i[0], i1, get_gradients=False) i1[..., ivar] += delta q2 = mrcal.project(p, i[0], i1, get_gradients=False) dq_di_observed = (q2 - q1) / delta dq_di_reported = dq_di[..., ivar] testutils.confirm_equal(dq_di_reported, dq_di_observed, eps=1e-5, msg=f"{i[0]}: dq_di matches for var {ivar}") testutils.finish() mrcal-2.4.1/test/test-pylib-projections.py000077500000000000000000000074161456301662300206170ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Tests projections, unprojections, distortions, etc''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils m = mrcal.cameramodel(f"{testdir}/data/cam0.opencv8.cameramodel") W,H = m.imagersize() intrinsics_core = m.intrinsics()[1][:4] testutils.confirm_equal( mrcal.scale_focal__best_pinhole_fit(m, None), 1.0, msg = 'scale_focal__best_pinhole_fit') def fit_check(scale_focal, intrinsics, v, W = W, H = H, scale_imagersize_pinhole = 1.0, eps = 1e-2): r'''Makes sure projected vectors fit into the imager perfectly I'm given a number of points in the camera coords. These much project such that - All projected points lie INSIDE the imager - At least one point lies exactly on the imager boundary ''' intrinsics = intrinsics.copy() intrinsics[:2] *= scale_focal intrinsics *= scale_imagersize_pinhole q = mrcal.project(v, 'LENSMODEL_PINHOLE', intrinsics) if any( q[:,0] < -eps ) or \ any( q[:,0] > W-1+eps ) or \ any( q[:,1] < -eps ) or \ any( q[:,1] > H-1+eps ): return ": Some points lie out of bounds" on_left_edge = np.abs(q[:,0] ) < eps on_right_edge = np.abs(q[:,0] - (W-1)) < eps on_top_edge = np.abs(q[:,1] ) < eps on_bottom_edge = np.abs(q[:,1] - (H-1)) < eps if not ( \ any(on_left_edge) or \ any(on_top_edge) or \ any(on_right_edge) or \ any(on_bottom_edge) ): return ": No points lie on the edge" # all good return '' err_msg = \ fit_check( mrcal.scale_focal__best_pinhole_fit(m, 'corners'), intrinsics_core, mrcal.unproject( np.array((( 0 , 0), (W-1, 0), ( 0, H-1), (W-1, H-1)), dtype=float), *m.intrinsics()),) testutils.confirm( err_msg == '', msg = 'scale_focal__best_pinhole_fit' + err_msg) err_msg = \ fit_check( mrcal.scale_focal__best_pinhole_fit(m, 'centers-horizontal'), intrinsics_core, mrcal.unproject( np.array((( 0, (H-1.)/2.), (W-1, (H-1.)/2.)), dtype=float), *m.intrinsics()),) testutils.confirm( err_msg == '', msg = 'scale_focal__best_pinhole_fit' + err_msg) err_msg = \ fit_check( mrcal.scale_focal__best_pinhole_fit(m, 'centers-vertical'), intrinsics_core, mrcal.unproject( np.array((((W-1.)/2., 0.), ((W-1.)/2., H-1.)), dtype=float), *m.intrinsics()),) testutils.confirm( err_msg == '', msg = 'scale_focal__best_pinhole_fit' + err_msg) err_msg = \ fit_check( mrcal.scale_focal__best_pinhole_fit(m, np.array((((W-1.)/2., 0.), ((W-1.)/2., H-1.)), dtype=float)), intrinsics_core, mrcal.unproject( np.array((((W-1.)/2., 0.), ((W-1.)/2., H-1.)), dtype=float), *m.intrinsics()),) testutils.confirm( err_msg == '', msg = 'scale_focal__best_pinhole_fit' + err_msg) testutils.finish() mrcal-2.4.1/test/test-pywrap-functions.py000077500000000000000000000026361456301662300204720ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Tests the python-wrapped C API ''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils model_splined = mrcal.cameramodel(f"{testdir}/data/cam0.splined.cameramodel") ux,uy = mrcal.knots_for_splined_models(model_splined.intrinsics()[0]) testutils.confirm_equal(ux, np.array([-1.33234678,-1.15470054,-0.9770543,-0.79940807,-0.62176183,-0.44411559,-0.26646936,-0.08882312,0.08882312,0.26646936,0.44411559,0.62176183,0.79940807,0.9770543,1.15470054,1.33234678]), msg=f"knots_for_splined_models ux") testutils.confirm_equal(uy, np.array([-0.88823118,-0.71058495,-0.53293871,-0.35529247,-0.17764624,0.,0.17764624,0.35529247,0.53293871,0.71058495,0.88823118]), msg=f"knots_for_splined_models uy") meta = mrcal.lensmodel_metadata_and_config(model_splined.intrinsics()[0]) meta_ref = {'has_core': 1, 'has_gradients': 1, 'noncentral': 0, 'can_project_behind_camera': 1, 'order': 3, 'Nx': 16, 'Ny': 11, 'fov_x_deg': 120} testutils.confirm_equal(meta, meta_ref, msg="lensmodel_metadata_and_config() keys") testutils.finish() mrcal-2.4.1/test/test-rectification-maps.py000077500000000000000000000062371456301662300207240ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Tests mrcal_rectification_maps() and mrcal.rectification_maps() ''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils # I want to generate a stereo pair. I tweak the intrinsics a bit model0 = mrcal.cameramodel(f"{testdir}/data/cam0.opencv8.cameramodel") model1 = mrcal.cameramodel(model0) intrinsics_data = model1.intrinsics()[1] intrinsics_data[ :2] *= np.array((1.01, -0.98)) intrinsics_data[2:4] += np.array((50, 80.)) model1.intrinsics( intrinsics = (model1.intrinsics()[0], intrinsics_data) ) # Left-right stereo, with sizeable rotation and position fuzz. # I especially make sure there's a forward/back shift rt01 = np.array((0.1, 0.2, 0.05, 3.0, 0.2, 1.0)) model1.extrinsics_rt_toref( mrcal.compose_rt(model0.extrinsics_rt_toref(), rt01)) for rectification in ('LENSMODEL_LATLON', 'LENSMODEL_PINHOLE'): for zoom in (0.6, 1., 10.): def apply_zoom(model, zoom): intrinsics_data_zoomed = np.array(model.intrinsics()[1]) intrinsics_data_zoomed[:2] *= zoom return (model.intrinsics()[0], intrinsics_data_zoomed) model0_zoom = mrcal.cameramodel(model0) model1_zoom = mrcal.cameramodel(model1) for m in (model0_zoom, model1_zoom): m.intrinsics( intrinsics = apply_zoom(m,zoom) ) # I use the canonical rectified-system function here to make sure that this # test checks only the rectification_maps function az_fov_deg = 90 el_fov_deg = 50 models_rectified = \ mrcal.stereo._rectified_system_python( (model0_zoom, model1_zoom), az_fov_deg = az_fov_deg/zoom, el_fov_deg = el_fov_deg/zoom, pixels_per_deg_az = -1./8., pixels_per_deg_el = -1./4., rectification_model = rectification) rectification_maps_ref = \ mrcal.stereo._rectification_maps_python((model0,model1), models_rectified) rectification_maps_ref = np.array(rectification_maps_ref) rectification_maps = \ mrcal.rectification_maps((model0,model1), models_rectified) # some pinhole maps have crazy behavior on the edges (WAAAAAAY out of # view), and I ignore it rectification_maps [rectification_maps > 1e6] = 0 rectification_maps_ref[rectification_maps_ref > 1e6] = 0 testutils.confirm_equal(rectification_maps, rectification_maps_ref, msg=f'Pixel error with ({rectification}). Zoom = {zoom}', worstcase = True, eps = 1e-6) testutils.finish() mrcal-2.4.1/test/test-save-load-image.py000077500000000000000000000032741456301662300200740ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Test of the save_image() and load_image() functions ''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils import tempfile import atexit import shutil workdir = tempfile.mkdtemp() def cleanup(): global workdir try: shutil.rmtree(workdir) workdir = None except: pass atexit.register(cleanup) W,H = 133,211 im8 = np.arange(W*H, dtype=np.uint8).reshape(H,W) im8 *= im8 im16 = np.arange(W*H, dtype=np.uint16).reshape(H,W) im16 *= im16 im24 = np.arange(W*H*3, dtype=np.uint8).reshape(H,W,3) im24 *= im24 filename = f"{workdir}/tst.png" for im,what in ( (im8, "8bpp grayscale"), (im16, "16bpp grayscale"), (im24, "24bpp bgr")): try: mrcal.save_image(filename, im) except: testutils.confirm(False, msg = f"Error saving {what} image") continue testutils.confirm(True, msg = f"Success saving {what} image") try: im_check = mrcal.load_image(filename) except: testutils.confirm(False, msg = f"Error loading {what} image") continue testutils.confirm(True, msg = f"Success loading {what} image") # print(im.shape) # print(im_check.shape) # print(im.dtype) # print(im_check.dtype) testutils.confirm_equal(im, im_check, worstcase=True, msg = f"load/save match for {what}") testutils.finish() mrcal-2.4.1/test/test-solvepnp.py000077500000000000000000000045741456301662300170130ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Validates estimate_monocular_calobject_poses_Rt_tocam() estimate_monocular_calobject_poses_Rt_tocam() is part of the calibration seeding functions. This uses solvePnP(), which is sensitive to the user-supplied focal-length estimates. Here I load some data that has been a problem in the past, and make sure that estimate_monocular_calobject_poses_Rt_tocam() can handle it ''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils import pickle # Load the data. These are written by the disabled-by-default code at the end of # estimate_monocular_calobject_poses_Rt_tocam() test_cases = ( # ./mrcal-calibrate-cameras \ # --corners-cache newfish-from-mike-email-extreme-fisheys/VuzeXR/calibration1/fishcorners.vnl \ # --lensmodel LENSMODEL_OPENCV8 \ # --focal 500 \ # --object-spacing 0.048 \ # --object-width-n 10 \ # --observed-pixel-uncertainty 2 \ # 'HET_0315_L*.jpg' 'HET_0315_R*.jpg' 'solvepnp-ultrawide-focal-too-long', # ./mrcal-calibrate-cameras \ # --corners-cache doc/out/external/2022-11-05--dtla-overpass--samyang--alpha7/2-f22-infinity/corners.vnl \ # --lensmodel LENSMODEL_OPENCV8 \ # --focal 1900 \ # --object-spacing 0.0588 \ # --object-width-n 14 \ # --observed-pixel-uncertainty 2 \ # '*.JPG' 'solvepnp-wide-focal-too-wide') for t in test_cases: filename = f'{testdir}/data/{t}.pickle' with open(filename,'rb') as f: args = pickle.load(f) testutils.confirm_does_not_raise( \ lambda: mrcal.estimate_monocular_calobject_poses_Rt_tocam(*args), msg = t) testutils.finish() mrcal-2.4.1/test/test-stereo-range.py000077500000000000000000000200271456301662300175270ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Checks the C and Python implementations of stereo_range() This test needs external data, so it isn't included in the enabled-by-default set ''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils import cv2 # This test needs data external to this repository. Can be downloaded like this: if False: import subprocess subprocess.check_output("wget -O /tmp/0.cameramodel https://mrcal.secretsauce.net/external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/0.cameramodel && " + "wget -O /tmp/1.cameramodel https://mrcal.secretsauce.net/external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/1.cameramodel && " "wget -O /tmp/0.jpg https://mrcal.secretsauce.net/external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/0.jpg && " "wget -O /tmp/1.jpg https://mrcal.secretsauce.net/external/2022-11-05--dtla-overpass--samyang--alpha7/stereo/1.jpg", shell = True) model_filenames=("/tmp/0.cameramodel", "/tmp/1.cameramodel") image_filenames=("/tmp/0.jpg", "/tmp/1.jpg") pixels_per_deg_az = -.25 pixels_per_deg_el = -.25 az_fov_deg = dict(LENSMODEL_LATLON = 160, LENSMODEL_PINHOLE = 120) el_fov_deg = 60 az0_deg = 0 el0_deg = 0 models = [mrcal.cameramodel(f) \ for f in model_filenames] images = [mrcal.load_image(f, bits_per_pixel = 8, channels = 1) \ for f in image_filenames] clahe = cv2.createCLAHE() clahe.setClipLimit(8) images = [ clahe.apply(image) for image in images ] # This is a hard-coded property of the OpenCV StereoSGBM implementation disparity_scale = 16 q = np.array(((30, 100), (300, 200), (1000, 400), (500, 300), (80, 500), (400, 350), (900, 350), (1100, 350), (1400, 350), (400, 450), (900, 450), (1100, 450), (1400, 450), (1300, 450))) results_from_disparity_min = dict() for rectification_model in ('LENSMODEL_LATLON', 'LENSMODEL_PINHOLE', ): models_rectified = \ mrcal.rectified_system(models, az_fov_deg = az_fov_deg[rectification_model], el_fov_deg = el_fov_deg, az0_deg = az0_deg, el0_deg = el0_deg, pixels_per_deg_az = pixels_per_deg_az, pixels_per_deg_el = pixels_per_deg_el, rectification_model = rectification_model) for disparity_min in (0,10,): disparity_max = 128 results_from_disparity_min[disparity_min] = dict() # round to nearest multiple of disparity_scale. The OpenCV StereoSGBM # implementation requires this num_disparities = disparity_max - disparity_min num_disparities = disparity_scale*round(num_disparities/disparity_scale) stereo_sgbm = \ cv2.StereoSGBM_create(minDisparity = disparity_min, numDisparities = num_disparities, P1 = 600, P2 = 2400, disp12MaxDiff = 1, uniquenessRatio = 5, speckleWindowSize = 100, speckleRange = 2, mode = cv2.StereoSGBM_MODE_SGBM) rectification_maps = mrcal.rectification_maps(models, models_rectified) images_rectified = [mrcal.transform_image(images[i], rectification_maps[i]) \ for i in range(2)] disparity = stereo_sgbm.compute(*images_rectified) ranges_dense = \ mrcal.stereo_range( disparity, models_rectified, disparity_scale = disparity_scale, disparity_min = disparity_min, disparity_scaled_max = 32767) ranges_dense_python = \ mrcal.stereo._stereo_range_python( disparity, models_rectified, disparity_scale = disparity_scale, disparity_min = disparity_min, disparity_scaled_max = 32767 ) ranges_sparse = \ mrcal.stereo_range( disparity[q[:,1], q[:,0]], models_rectified, qrect0 = q, disparity_scale = disparity_scale, disparity_min = disparity_min) ranges_sparse_python = \ mrcal.stereo._stereo_range_python( disparity[q[:,1], q[:,0]], models_rectified, qrect0 = q, disparity_scale = disparity_scale, disparity_min = disparity_min) results_from_disparity_min[disparity_min]['disparity'] = \ disparity results_from_disparity_min[disparity_min]['ranges_dense'] = \ ranges_dense results_from_disparity_min[disparity_min]['ranges_dense_python'] = \ ranges_dense_python results_from_disparity_min[disparity_min]['ranges_sparse'] = \ ranges_sparse results_from_disparity_min[disparity_min]['ranges_sparse_python'] = \ ranges_sparse_python testutils.confirm_equal( ranges_dense, ranges_dense_python, worstcase = True, eps = 1e-3, msg=f'Dense stereo_range() matches in C and Python: rectification_model={rectification_model} disparity_min={disparity_min}') testutils.confirm_equal( ranges_sparse, ranges_sparse_python, worstcase = True, eps = 1e-3, msg=f'Sparse stereo_range() matches in C and Python: rectification_model={rectification_model} disparity_min={disparity_min}') testutils.confirm_equal( ranges_sparse, ranges_dense[q[:,1], q[:,0]], worstcase = True, eps = 1e-3, msg=f'Sparse and dense stereo_range() match: rectification_model={rectification_model} disparity_min={disparity_min}') if False: range_image_limits = (1,1000) disparity_colored = mrcal.apply_color_map(disparity, a_min = disparity_min*disparity_scale, a_max = disparity_max*disparity_scale) ranges_colored = mrcal.apply_color_map(ranges_dense, a_min = range_image_limits[0], a_max = range_image_limits[1]) mrcal.save_image("/tmp/disparity.png", disparity_colored) mrcal.save_image("/tmp/range.png", ranges_colored) print("Wrote /tmp/disparity.png and /tmp/range.png") testutils.finish() mrcal-2.4.1/test/test-stereo.py000077500000000000000000000415751456301662300164500ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Tests the stereo routines ''' import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import scipy.interpolate import testutils model0 = mrcal.cameramodel(f"{testdir}/data/cam0.opencv8.cameramodel") model1 = mrcal.cameramodel(model0) for lensmodel in ('LENSMODEL_LATLON', 'LENSMODEL_PINHOLE'): # I create geometries to test. First off, a vanilla geometry for left-right stereo rt01 = np.array((0,0,0, 3.0, 0, 0)) model1.extrinsics_rt_toref( mrcal.compose_rt(model0.extrinsics_rt_toref(), rt01)) az_fov_deg = 90 el_fov_deg = 50 models_rectified = \ mrcal.rectified_system( (model0, model1), az_fov_deg = az_fov_deg, el_fov_deg = el_fov_deg, pixels_per_deg_az = -1./8., pixels_per_deg_el = -1./4., rectification_model = lensmodel) az0 = 0. el0 = 0. try: mrcal.stereo._validate_models_rectified(models_rectified) testutils.confirm(True, msg=f'Generated models pass validation ({lensmodel})') except: testutils.confirm(False, msg=f'Generated models pass validation ({lensmodel})') Rt_cam0_rect = mrcal.compose_Rt( model0.extrinsics_Rt_fromref(), models_rectified[0].extrinsics_Rt_toref()) Rt01_rectified = mrcal.compose_Rt( models_rectified[0].extrinsics_Rt_fromref(), models_rectified[1].extrinsics_Rt_toref()) testutils.confirm_equal(models_rectified[0].intrinsics()[0], lensmodel, msg=f'model0 has the right lensmodel ({lensmodel})') testutils.confirm_equal(models_rectified[1].intrinsics()[0], lensmodel, msg=f'model1 has the right lensmodel ({lensmodel})') testutils.confirm_equal(Rt_cam0_rect, mrcal.identity_Rt(), msg=f'vanilla stereo has a vanilla geometry ({lensmodel})') testutils.confirm_equal( Rt01_rectified[3,0], nps.mag(rt01[3:]), msg=f'vanilla stereo: baseline ({lensmodel})') Naz,Nel = models_rectified[0].imagersize() q0 = np.array(((Naz-1.)/2., (Nel-1.)/2.)) v0 = mrcal.unproject(q0, *models_rectified[0].intrinsics(), normalize=True) if lensmodel == 'LENSMODEL_LATLON': v0_rect = mrcal.unproject_latlon(np.array((az0, el0))) # already normalized testutils.confirm_equal( v0_rect, v0, msg=f'vanilla stereo: az0,el0 represent the same point ({lensmodel})') else: v0_rect = mrcal.unproject_pinhole(np.array((np.tan(az0), np.tan(el0)))) v0_rect /= nps.mag(v0_rect) testutils.confirm_equal( v0_rect, v0, msg=f'vanilla stereo: az0,el0 represent the same point ({lensmodel})', eps = 1e-3) dq0x = np.array((1e-1, 0)) dq0y = np.array((0, 1e-1)) v0x = mrcal.unproject(q0+dq0x, *models_rectified[0].intrinsics()) v0y = mrcal.unproject(q0+dq0y, *models_rectified[0].intrinsics()) dthx = np.arccos(nps.inner(v0x,v0)/np.sqrt(nps.norm2(v0x)*nps.norm2(v0))) dthy = np.arccos(nps.inner(v0y,v0)/np.sqrt(nps.norm2(v0y)*nps.norm2(v0))) pixels_per_rad_az_rect = nps.mag(dq0x)/dthx pixels_per_rad_el_rect = nps.mag(dq0y)/dthy q0_cam0 = mrcal.project(mrcal.rotate_point_R(Rt_cam0_rect[:3,:], v0), *model0.intrinsics()) q0x_cam0 = mrcal.project(mrcal.rotate_point_R(Rt_cam0_rect[:3,:], v0x), *model0.intrinsics()) q0y_cam0 = mrcal.project(mrcal.rotate_point_R(Rt_cam0_rect[:3,:], v0y), *model0.intrinsics()) pixels_per_rad_az_cam0 = nps.mag(q0x_cam0 - q0_cam0)/dthx pixels_per_rad_el_cam0 = nps.mag(q0y_cam0 - q0_cam0)/dthy testutils.confirm_equal(pixels_per_rad_az_rect * 8., pixels_per_rad_az_cam0, msg=f'vanilla stereo: az pixel density ({lensmodel})', relative = True, eps = 1e-2) testutils.confirm_equal(pixels_per_rad_el_rect * 4., pixels_per_rad_el_cam0, msg=f'vanilla stereo: el pixel density ({lensmodel})', relative = True, eps = 1e-2) v0 = mrcal.unproject(np.array((0, (Nel-1.)/2.)), *models_rectified[0].intrinsics()) v1 = mrcal.unproject(np.array((Naz-1,(Nel-1.)/2.)), *models_rectified[0].intrinsics()) az_fov_deg_observed = np.arccos(nps.inner(v0,v1)/(nps.mag(v0)*nps.mag(v1))) * 180./np.pi testutils.confirm_equal(az_fov_deg_observed, az_fov_deg, msg=f'vanilla stereo: az_fov ({lensmodel})', eps = 0.5) v0 = mrcal.unproject(np.array(((Naz-1.)/2., 0, )), *models_rectified[0].intrinsics()) v0[0] = 0 # el_fov applies at the stereo center only v1 = mrcal.unproject(np.array(((Naz-1.)/2., Nel-1,)), *models_rectified[0].intrinsics()) v1[0] = 0 el_fov_deg_observed = np.arccos(nps.inner(v0,v1)/(nps.mag(v0)*nps.mag(v1))) * 180./np.pi testutils.confirm_equal(el_fov_deg_observed, el_fov_deg, msg=f'vanilla stereo: el_fov ({lensmodel})', eps = 0.5) ############### Complex geometry # Left-right stereo, with sizeable rotation and position fuzz. # I especially make sure there's a forward/back shift rt01 = np.array((0.1, 0.2, 0.05, 3.0, 0.2, 1.0)) model1.extrinsics_rt_toref( mrcal.compose_rt(model0.extrinsics_rt_toref(), rt01)) el0_deg = 10.0 models_rectified = \ mrcal.rectified_system( (model0, model1), az_fov_deg = az_fov_deg, el_fov_deg = el_fov_deg, el0_deg = el0_deg, pixels_per_deg_az = -1./8., pixels_per_deg_el = -1./4., rectification_model = lensmodel) el0 = el0_deg*np.pi/180. # az0 is the "forward" direction of the two cameras, relative to the # baseline vector baseline = rt01[3:] / nps.mag(rt01[3:]) # "forward" for each of the two cameras, in the cam0 coord system forward0 = np.array((0,0,1.)) forward1 = mrcal.rotate_point_r(rt01[:3], np.array((0,0,1.))) forward01 = forward0 + forward1 az0 = np.arcsin( nps.inner(forward01,baseline) / nps.mag(forward01) ) try: mrcal.stereo._validate_models_rectified(models_rectified) testutils.confirm(True, msg=f'Generated models pass validation ({lensmodel})') except: testutils.confirm(False, msg=f'Generated models pass validation ({lensmodel})') Rt_cam0_rect = mrcal.compose_Rt( model0.extrinsics_Rt_fromref(), models_rectified[0].extrinsics_Rt_toref()) Rt01_rectified = mrcal.compose_Rt( models_rectified[0].extrinsics_Rt_fromref(), models_rectified[1].extrinsics_Rt_toref()) # I visualized the geometry, and confirmed that it is correct. The below array # is the correct-looking geometry # # Rt_cam0_ref = model0.extrinsics_Rt_fromref() # Rt_rect_ref = mrcal.compose_Rt( mrcal.invert_Rt(Rt_cam0_rect), # Rt_cam0_ref ) # rt_rect_ref = mrcal.rt_from_Rt(Rt_rect_ref) # mrcal.show_geometry( [ model0, model1, rt_rect_ref ], # cameranames = ( "camera0", "camera1", "stereo" ), # show_calobjects = False, # wait = True ) # print(repr(Rt_cam0_rect)) testutils.confirm_equal(Rt_cam0_rect, np.array([[ 0.9467916 , -0.08500675, -0.31041828], [ 0.06311944, 0.99480206, -0.07990489], [ 0.3155972 , 0.05605985, 0.94723582], [ 0. , -0. , -0. ]]), msg=f'complex stereo geometry ({lensmodel})') testutils.confirm_equal( Rt01_rectified[3,0], nps.mag(rt01[3:]), msg=f'complex stereo: baseline ({lensmodel})') Naz,Nel = models_rectified[0].imagersize() q0 = np.array(((Naz-1.)/2., (Nel-1.)/2.)) v0 = mrcal.unproject(q0, *models_rectified[0].intrinsics(), normalize=True) if lensmodel == 'LENSMODEL_LATLON': v0_rect = mrcal.unproject_latlon(np.array((az0, el0))) # already normalized testutils.confirm_equal( v0_rect, v0, msg=f'complex stereo: az0,el0 represent the same point ({lensmodel})') else: v0_rect = mrcal.unproject_pinhole(np.array((np.tan(az0), np.tan(el0)))) v0_rect /= nps.mag(v0_rect) testutils.confirm_equal( v0_rect, v0, msg=f'complex stereo: az0,el0 represent the same point ({lensmodel})', eps = 1e-3) dq0x = np.array((1e-1, 0)) dq0y = np.array((0, 1e-1)) v0x = mrcal.unproject(q0+dq0x, *models_rectified[0].intrinsics()) v0y = mrcal.unproject(q0+dq0y, *models_rectified[0].intrinsics()) dthx = np.arccos(nps.inner(v0x,v0)/np.sqrt(nps.norm2(v0x)*nps.norm2(v0))) dthy = np.arccos(nps.inner(v0y,v0)/np.sqrt(nps.norm2(v0y)*nps.norm2(v0))) pixels_per_rad_az_rect = nps.mag(dq0x)/dthx pixels_per_rad_el_rect = nps.mag(dq0y)/dthy q0_cam0 = mrcal.project(mrcal.rotate_point_R(Rt_cam0_rect[:3,:], v0), *model0.intrinsics()) q0x_cam0 = mrcal.project(mrcal.rotate_point_R(Rt_cam0_rect[:3,:], v0x), *model0.intrinsics()) q0y_cam0 = mrcal.project(mrcal.rotate_point_R(Rt_cam0_rect[:3,:], v0y), *model0.intrinsics()) pixels_per_rad_az_cam0 = nps.mag(q0x_cam0 - q0_cam0)/dthx pixels_per_rad_el_cam0 = nps.mag(q0y_cam0 - q0_cam0)/dthy testutils.confirm_equal(pixels_per_rad_az_rect * 8., pixels_per_rad_az_cam0, msg=f'complex stereo: az pixel density ({lensmodel})', relative = True, eps = 1e-2) testutils.confirm_equal(pixels_per_rad_el_rect * 4., pixels_per_rad_el_cam0, msg=f'complex stereo: el pixel density ({lensmodel})', relative = True, eps = 1e-2) v0 = mrcal.unproject(np.array((0, (Nel-1.)/2.)), *models_rectified[0].intrinsics()) v1 = mrcal.unproject(np.array((Naz-1,(Nel-1.)/2.)), *models_rectified[0].intrinsics()) az_fov_deg_observed = np.arccos(nps.inner(v0,v1)/(nps.mag(v0)*nps.mag(v1))) * 180./np.pi testutils.confirm_equal(az_fov_deg_observed, az_fov_deg, msg=f'complex stereo: az_fov ({lensmodel})', eps = 1.) v0 = mrcal.unproject(np.array(((Naz-1.)/2., 0, )), *models_rectified[0].intrinsics()) v0[0] = 0 # el_fov applies at the stereo center only v1 = mrcal.unproject(np.array(((Naz-1.)/2., Nel-1,)), *models_rectified[0].intrinsics()) v1[0] = 0 el_fov_deg_observed = np.arccos(nps.inner(v0,v1)/(nps.mag(v0)*nps.mag(v1))) * 180./np.pi testutils.confirm_equal(el_fov_deg_observed, el_fov_deg, msg=f'complex stereo: el_fov ({lensmodel})', eps = 0.5) # I examine points somewhere in space. I make sure the rectification maps # transform it properly. And I compute what its az,el and disparity would have # been, and I check the geometric functions pcam0 = np.array((( 1., 2., 12.), (-4., 3., 12.))) qcam0 = mrcal.project( pcam0, *model0.intrinsics() ) pcam1 = mrcal.transform_point_rt(mrcal.invert_rt(rt01), pcam0) qcam1 = mrcal.project( pcam1, *model1.intrinsics() ) prect0 = mrcal.transform_point_Rt( mrcal.invert_Rt(Rt_cam0_rect), pcam0) prect1 = prect0 - Rt01_rectified[3,:] qrect0 = mrcal.project(prect0, *models_rectified[0].intrinsics()) qrect1 = mrcal.project(prect1, *models_rectified[1].intrinsics()) Naz,Nel = models_rectified[0].imagersize() row = np.arange(Naz, dtype=float) col = np.arange(Nel, dtype=float) rectification_maps = mrcal.rectification_maps((model0,model1), models_rectified) interp_rectification_map0x = \ scipy.interpolate.RectBivariateSpline(row, col, nps.transpose(rectification_maps[0][...,0])) interp_rectification_map0y = \ scipy.interpolate.RectBivariateSpline(row, col, nps.transpose(rectification_maps[0][...,1])) interp_rectification_map1x = \ scipy.interpolate.RectBivariateSpline(row, col, nps.transpose(rectification_maps[1][...,0])) interp_rectification_map1y = \ scipy.interpolate.RectBivariateSpline(row, col, nps.transpose(rectification_maps[1][...,1])) if lensmodel == 'LENSMODEL_LATLON': qcam0_from_map = \ nps.transpose( nps.cat( interp_rectification_map0x(*nps.transpose(qrect0), grid=False), interp_rectification_map0y(*nps.transpose(qrect0), grid=False) ) ) qcam1_from_map = \ nps.transpose( nps.cat( interp_rectification_map1x(*nps.transpose(qrect1), grid=False), interp_rectification_map1y(*nps.transpose(qrect1), grid=False) ) ) else: qcam0_from_map = \ nps.transpose( nps.cat( interp_rectification_map0x(*nps.transpose(qrect0), grid=False), interp_rectification_map0y(*nps.transpose(qrect0), grid=False) ) ) qcam1_from_map = \ nps.transpose( nps.cat( interp_rectification_map1x(*nps.transpose(qrect1), grid=False), interp_rectification_map1y(*nps.transpose(qrect1), grid=False) ) ) testutils.confirm_equal( qcam0_from_map, qcam0, eps=1e-1, msg=f'rectification map for camera 0 points ({lensmodel})') testutils.confirm_equal( qcam1_from_map, qcam1, eps=1e-1, msg=f'rectification map for camera 1 points ({lensmodel})') # same point, so we should have the same el testutils.confirm_equal( qrect0[:,1], qrect1[:,1], msg=f'elevations of the same observed point match ({lensmodel})') disparity = qrect0[:,0] - qrect1[:,0] r = mrcal.stereo_range( disparity, models_rectified, qrect0 = qrect0, ) testutils.confirm_equal( r, nps.mag(pcam0), msg=f'stereo_range reports the right thing ({lensmodel})') r = mrcal.stereo_range( disparity[0], models_rectified, qrect0 = qrect0[0], ) testutils.confirm_equal( r, nps.mag(pcam0[0]), msg=f'stereo_range (1-element array) reports the right thing ({lensmodel})', eps=2e-6) r = mrcal.stereo_range( float(disparity[0]), models_rectified, qrect0 = qrect0[0], ) testutils.confirm_equal( r, float(nps.mag(pcam0[0])), msg=f'stereo_range (scalar) reports the right thing ({lensmodel})', eps=2e-6) disparity = qrect0[:,0] - qrect1[:,0] p = mrcal.stereo_unproject( disparity, models_rectified, qrect0 = qrect0, ) testutils.confirm_equal( p, prect0, msg=f'stereo_unproject reports the right thing ({lensmodel})') p = mrcal.stereo_unproject( float(disparity[0]), models_rectified, qrect0 = qrect0[0], ) testutils.confirm_equal( p, prect0[0], msg=f'stereo_unproject (scalar) reports the right thing ({lensmodel})') testutils.finish() mrcal-2.4.1/test/test-surveyed-calibration.py000077500000000000000000001037531456301662300212770ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Surveyed camera-calibration test I observe, with noise, a number of fixed, known-pose chessboards from a single camera. And I make sure that I can more or less compute the camera intrinsics and extrinsics. This is a monocular solve. Since the chessboards aren't allowed to move, multiple cameras in one solves wouldn't be interacting with each other, and there's no reason to have more than one ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--write-model', type=str, help='''If given, we write the resulting model to disk for further analysis. The filename is given in this argument''') parser.add_argument('--range-board', type=float, default = 10, help='''Distance from the camera to the center of each chessboard. If omitted, we default to 10''') parser.add_argument('--range-board-center', type=float, help='''Distance from the camera to the center of the MIDDLE chessboard. If omitted, we use --range-board * 2. Everything at one range causes poor calibrations, and I don't want that to be the default case here''') parser.add_argument('--oversample', type=int, default = 1, help='''How many times we observe the stationary scene. Observing multiple times gives us more samples of the noise, resulting in lower uncertainties''') parser.add_argument('--distance', type=float, help='''distance for uncertainty computations. If omitted, we use infinity''') parser.add_argument('--seed-rng', type=int, default=0, help='''Value to seed the rng with''') parser.add_argument('--do-sample', action='store_true', help='''By default we don't run the time-intensive samples of the calibration solves. This runs a very limited set of tests, and exits. To perform the full set of tests, pass --do-sample''') parser.add_argument('--only-report-uncertainty', action='store_true', help='''If given, I ONLY report the uncertainty in projection and errz''') parser.add_argument('--Nsamples', type=int, default=500, help='''How many random samples to evaluate''') parser.add_argument('--make-documentation-plots', type=str, help='''If given, we produce plots for the documentation. Takes one argument: a string describing this test. This will be used in the filenames of the resulting plots. To make interactive plots, pass ""''') parser.add_argument('--terminal-pdf', type=str, help='''The gnuplotlib terminal for --make-documentation-plots .PDFs. Omit this unless you know what you're doing''') parser.add_argument('--terminal-svg', type=str, help='''The gnuplotlib terminal for --make-documentation-plots .SVGs. Omit this unless you know what you're doing''') parser.add_argument('--terminal-png', type=str, help='''The gnuplotlib terminal for --make-documentation-plots .PNGs. Omit this unless you know what you're doing''') args = parser.parse_args() if args.range_board_center is None: args.range_board_center = args.range_board * 2. return args args = parse_args() import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils from test_calibration_helpers import sample_dqref,calibration_sample import copy # I Reduce FOV to make it clear that you need data from different ranges focal_length_scale_from_true = 10. object_spacing = 0.03 object_width_n = 8 object_height_n = 8 pixel_uncertainty_stdev = 0.5 # I have a 3x3 grid of chessboards NboardgridX,NboardgridY = 3,1 # We try to recover this in the calibration process # shape (6,) rt_cam_ref_true = np.array((-0.04, 0.05, -0.1, 1.2, -0.1, 0.1),) random_radius__r_cam_board_true = 0.1 random_radius__t_cam_board_true = 1.0e-1 ############# Plot setup. Very similar to test-projection-uncertainty.py if args.make_documentation_plots is not None: def shorter_terminal(t): # Adjust the terminal string to be less tall. Reduces wasted space in # some of the plots m = re.match("(.*)( size.*?,)([0-9.]+)(.*?)$", t) if m is None: return t return m.group(1) + m.group(2) + str(float(m.group(3))*0.8) + m.group(4) import gnuplotlib as gp terminal = dict(pdf = args.terminal_pdf, svg = args.terminal_svg, png = args.terminal_png, gp = 'gp') pointscale = dict(pdf = 1, svg = 1, png = 1, gp = 1) pointscale[""] = 1. if args.make_documentation_plots: print(f"Will write documentation plots to {args.make_documentation_plots}-xxxx.pdf and .svg") if terminal['svg'] is None: terminal['svg'] = 'svg size 800,600 noenhanced solid dynamic font ",14"' if terminal['pdf'] is None: terminal['pdf'] = 'pdf size 8in,6in noenhanced solid color font ",12"' if terminal['png'] is None: terminal['png'] = 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' extraset = dict() for k in pointscale.keys(): extraset[k] = f'pointsize {pointscale[k]}' # I want the RNG to be deterministic np.random.seed(args.seed_rng) ############# Set up my world, and compute all the perfect positions, pixel ############# observations of everything model_true = mrcal.cameramodel(f"{testdir}/data/cam0.opencv8.cameramodel") imagersize_true = model_true.imagersize() W,H = imagersize_true # I have opencv8 model_true, but I truncate to opencv4 to keep this simple and # fast lensmodel = 'LENSMODEL_OPENCV4' Nintrinsics = mrcal.lensmodel_num_params(lensmodel) intrinsics_data_true = model_true.intrinsics()[1][:Nintrinsics] intrinsics_data_true[:2] *= focal_length_scale_from_true model_true.intrinsics( (lensmodel, intrinsics_data_true), ) model_true.extrinsics_rt_fromref(rt_cam_ref_true) if False: model_true.write("/tmp/true.cameramodel") print("wrote /tmp/true.cameramodel") # Test point. On the left, centered vertically q_query = np.array((W/4, H/2)) # I want to space out the chessboards across the whole imager. To make this # simpler I define it in terms of the "boardcentered" coordinate system, whose # origin is at the center of the chessboard, not in a corner board_center = \ np.array(( (object_width_n -1)*object_spacing/2., (object_height_n-1)*object_spacing/2., 0 )) rt_boardcentered_board_true = mrcal.identity_rt() rt_boardcentered_board_true[3:] = -board_center # The chessboard centers are arranged in an even grid on the imager # # shape (NboardgridY,NboardgridX,2); each row is (qx,qy): the center of each # chessboard q_center = \ nps.mv( \ nps.cat(*np.meshgrid(np.linspace(0.5, NboardgridX-0.5, NboardgridX, endpoint=True)/NboardgridX * W, np.linspace(0.5, NboardgridY-0.5, NboardgridY, endpoint=True)/NboardgridY * H)), 0, -1) v_center = mrcal.unproject(np.ascontiguousarray(q_center), *model_true.intrinsics(), normalize = True) # shape (NboardgridY,NboardgridX,6) rt_cam_boardcentered_true = np.zeros(v_center.shape[:-1] + (6,), dtype=float) rt_cam_boardcentered_true[...,3:] = v_center*args.range_board if args.range_board_center is not None: rt_cam_boardcentered_true[NboardgridY//2, NboardgridX//2,3:] = \ v_center[NboardgridY//2, NboardgridX//2,:]*args.range_board_center # shape (NboardgridY,NboardgridX,6) rt_cam_board_true = mrcal.compose_rt(rt_cam_boardcentered_true, rt_boardcentered_board_true) rt_cam_board_true[...,:3] += (np.random.rand(*rt_cam_board_true[...,:3].shape)*2. - 1.) * random_radius__r_cam_board_true rt_cam_board_true[...,3:] += (np.random.rand(*rt_cam_board_true[...,3:].shape)*2. - 1.) * random_radius__t_cam_board_true # Nboards = NboardgridX*NboardgridY # shape (Nboards,6) rt_cam_board_true = nps.clump(rt_cam_board_true, n=2) rt_ref_board_true = mrcal.compose_rt( mrcal.invert_rt(rt_cam_ref_true), rt_cam_board_true) # We assume that the chessboard poses rt_ref_board_true, rt_cam_board_true were # measured. Perfectly. This it the ground truth AND we have it available in the # calibration # shape (Nh,Nw,3) cal_object = mrcal.ref_calibration_object(object_width_n, object_height_n, object_spacing) # shape (Nframes,Nh,Nw,3) pcam_calobjects = \ mrcal.transform_point_rt(nps.mv(rt_cam_board_true,-2,-4), cal_object) # shape (N,3) pcam_true = nps.clump(pcam_calobjects, n=3) pref_true = mrcal.transform_point_rt(mrcal.invert_rt(rt_cam_ref_true), pcam_true) # shape (N,2) q_true = mrcal.project(pcam_true, lensmodel, intrinsics_data_true) Npoints = q_true.shape[0] if False: # show the angles off the optical axis import gnuplotlib as gp p = pcam_true / nps.dummy(nps.mag(pcam_true),-1) c = p[...,2] th = np.arccos(c).ravel() * 180./np.pi gp.plot(th, yrange=(45,90)) import IPython IPython.embed() sys.exit() # I have perfect observations in q_true. I corrupt them by noise weight has # shape (N,), weight01 = (np.random.rand(*q_true.shape[:-1]) + 1.) / 2. # in [0,1] weight0 = 0.2 weight1 = 1.0 weight = weight0 + (weight1-weight0)*weight01 # out-of-bounds observations are outliers weight[(q_true[:,0] < 0) + \ (q_true[:,1] < 0) + \ (q_true[:,0] > W-1) + \ (q_true[:,1] > H-1)] = -1. ############# Now I pretend that the noisy observations are all I got, and I run ############# a calibration from those # shape (Noversample, N, 3) observations_point = np.zeros((args.oversample,Npoints,3), dtype=float) # write the same perfect data into each oversampled slice observations_point += nps.glue(q_true, nps.dummy(weight,-1), axis=-1) # shape (Noversample*N, 3) observations_point = nps.clump(observations_point,n=2) # Dense observations. The cameras see all the boards indices_point_camintrinsics_camextrinsics = np.zeros( (args.oversample,Npoints, 3), dtype=np.int32) indices_point_camintrinsics_camextrinsics[...,0] += np.arange(Npoints) indices_point_camintrinsics_camextrinsics = nps.clump(indices_point_camintrinsics_camextrinsics,n=2) if False: # Compute the seed using the seeding algorithm focal_estimate = 2000 * focal_length_scale_from_true cxy = np.array(( (W-1.)/2, (H-1.)/2, ), ) intrinsics_core_estimate = \ ('LENSMODEL_STEREOGRAPHIC', np.array((focal_estimate, focal_estimate, *cxy ))) # I select data just at the center for seeding. Eventually should move this to # the general logic in calibration.py i = nps.norm2( observations_point[:Npoints,:2] - cxy ) < 1000**2. observations_point_center = np.array(observations_point[:Npoints]) observations_point_center[~i,2] = -1. Rt_camera_ref_estimate = \ mrcal.calibration._estimate_camera_pose_from_point_observations( \ indices_point_camintrinsics_camextrinsics[:Npoints,:], observations_point_center, (intrinsics_core_estimate,), pref_true, icam_intrinsics = 0) rt_camera_ref_estimate = mrcal.rt_from_Rt(Rt_camera_ref_estimate) intrinsics_data = np.zeros((1,Nintrinsics), dtype=float) intrinsics_data[:,:4] = intrinsics_core_estimate[1] intrinsics_data[:,4:] = np.random.random( (1, intrinsics_data.shape[1]-4) ) * 1e-6 else: # Use a nearby value to the true seed rt_camera_ref_estimate = nps.atleast_dims(np.array(rt_cam_ref_true), -2) rt_camera_ref_estimate[..., :3] += np.random.randn(3) * 1e-2 # r rt_camera_ref_estimate[..., 3:] += np.random.randn(3) * 0.1 # t intrinsics_data = nps.atleast_dims(np.array(intrinsics_data_true), -2) intrinsics_data += np.random.randn(*intrinsics_data.shape) * 1e-2 if args.make_documentation_plots is not None: def makeplot(**plotoptions): mrcal.show_geometry( (rt_camera_ref_estimate,), points = pref_true, # known. fixed. perfect. show_points = True, title = 'Surveyed calibration: nominal geometry', **plotoptions) if args.make_documentation_plots: for extension in ('pdf','svg','png','gp'): makeplot(wait = False, terminal = shorter_terminal(terminal[extension]), _set = extraset[extension], hardcopy = f'{args.make_documentation_plots}/geometry.{extension}') else: makeplot(wait = True) if args.make_documentation_plots is not None: def makeplot(**plotoptions): gp.plot( observations_point[:,:2], _with = f'points ps {pointscale[extension]}', tuplesize = -2, square=1, _xrange = f'0:{W-1}', _yrange = f'{H-1}:0', title = 'Surveyed calibration: observations', **plotoptions) if args.make_documentation_plots: for extension in ('pdf','svg','png','gp'): makeplot(wait = False, terminal = terminal[extension], _set = extraset[extension], hardcopy = f'{args.make_documentation_plots}/observations.{extension}') else: makeplot(wait = True) optimization_inputs_baseline = \ dict( lensmodel = lensmodel, intrinsics = intrinsics_data, extrinsics_rt_fromref = rt_camera_ref_estimate, frames_rt_toref = None, points = pref_true, # known. fixed. perfect. observations_board = None, indices_frame_camintrinsics_camextrinsics = None, observations_point = observations_point, indices_point_camintrinsics_camextrinsics = indices_point_camintrinsics_camextrinsics, calobject_warp = None, imagersizes = nps.atleast_dims(imagersize_true, -2), point_min_range = 0.01, point_max_range = 100., verbose = False, do_apply_outlier_rejection = False, do_apply_regularization = True, do_optimize_calobject_warp = False, do_optimize_frames = False) Nstate = mrcal.num_states(**optimization_inputs_baseline) def optimize(optimization_inputs): optimization_inputs['do_optimize_intrinsics_core'] = False optimization_inputs['do_optimize_intrinsics_distortions'] = False optimization_inputs['do_optimize_extrinsics'] = True mrcal.optimize(**optimization_inputs) optimization_inputs['do_optimize_intrinsics_core'] = True optimization_inputs['do_optimize_intrinsics_distortions'] = True optimization_inputs['do_optimize_extrinsics'] = True mrcal.optimize(**optimization_inputs) # Take one solve sample optimization_inputs = copy.deepcopy(optimization_inputs_baseline) _,optimization_inputs['observations_point'] = \ sample_dqref(optimization_inputs['observations_point'], pixel_uncertainty_stdev) optimize(optimization_inputs) # Grab the residuals. residuals_point() reports ONLY the point reprojection # errors: no range normalization (penalty) terms, no board observations, no # regularization. Also, no outliers rmserr_point = np.std(mrcal.residuals_point(optimization_inputs).ravel()) ############# Calibration computed. Now I see how well I did model_solved = \ mrcal.cameramodel( optimization_inputs = optimization_inputs, icam_intrinsics = 0 ) Rt_extrinsics_err = \ mrcal.compose_Rt( model_solved.extrinsics_Rt_fromref(), model_true .extrinsics_Rt_toref() ) v_query_cam = mrcal.unproject(q_query, *model_solved.intrinsics(), normalize = True) if args.distance is not None: p_query_cam = v_query_cam * args.distance else: p_query_cam = v_query_cam * 1e5 # large distance p_query_ref = mrcal.transform_point_Rt(model_solved.extrinsics_Rt_toref(),p_query_cam) def get_variances(): icam = 0 i_state = mrcal.state_index_extrinsics(icam, **optimization_inputs) rt_extrinsics_err, \ drt_extrinsics_err_drtsolved, \ _ = \ mrcal.compose_rt( model_solved.extrinsics_rt_fromref(), model_solved.extrinsics_rt_toref(), get_gradients = True) derrz_db = np.zeros( (1,Nstate), dtype=float) derrz_db[...,i_state:i_state+6] = drt_extrinsics_err_drtsolved[5:,:] Var_errz = mrcal.model_analysis._propagate_calibration_uncertainty( \ 'covariance', dF_db = derrz_db, optimization_inputs = optimization_inputs) Var_errz = Var_errz[0,0] if args.distance is not None: Var_q = \ mrcal.projection_uncertainty( p_query_cam, model_solved, atinfinity = False, what = 'covariance' ) else: Var_q = \ mrcal.projection_uncertainty( v_query_cam, model_solved, atinfinity = True, what = 'covariance' ) return Var_errz,Var_q if args.only_report_uncertainty: Var_errz,Var_q = get_variances() print("# z-bulk z-center stdev(q) stdev(errz)") # using the 'rms-stdev' expression from _propagate_calibration_uncertainty() print(f"{args.range_board} {args.range_board_center} {np.sqrt(nps.trace(Var_q)/2.):.4f} {np.sqrt(Var_errz):.4f}") sys.exit() # verify problem layout testutils.confirm_equal( Nstate, Nintrinsics + 6, msg="num_states()") testutils.confirm_equal( mrcal.num_states_intrinsics(**optimization_inputs), Nintrinsics, msg="num_states_intrinsics()") testutils.confirm_equal( mrcal.num_intrinsics_optimization_params(**optimization_inputs), Nintrinsics, msg="num_intrinsics_optimization_params()") testutils.confirm_equal( mrcal.num_states_extrinsics(**optimization_inputs), 6, msg="num_states_extrinsics()") testutils.confirm_equal( mrcal.num_states_frames(**optimization_inputs), 0, msg="num_states_frames()") testutils.confirm_equal( mrcal.num_states_points(**optimization_inputs), 0, msg="num_states_points()") testutils.confirm_equal( mrcal.num_states_calobject_warp(**optimization_inputs), 0, msg="num_states_calobject_warp()") testutils.confirm_equal( mrcal.num_measurements_boards(**optimization_inputs), 0, msg="num_measurements_boards()") testutils.confirm_equal( mrcal.num_measurements_points(**optimization_inputs), Npoints*args.oversample*3, msg="num_measurements_points()") testutils.confirm_equal( mrcal.num_measurements_regularization(**optimization_inputs), 6, msg="num_measurements_regularization()") testutils.confirm_equal( mrcal.state_index_intrinsics(0, **optimization_inputs), 0, msg="state_index_intrinsics()") testutils.confirm_equal( mrcal.state_index_extrinsics(0, **optimization_inputs), 8, msg="state_index_extrinsics()") testutils.confirm_equal( mrcal.measurement_index_points(2, **optimization_inputs), 3*2, msg="measurement_index_points()") testutils.confirm_equal( mrcal.measurement_index_regularization(**optimization_inputs), 3*args.oversample*Npoints, msg="measurement_index_regularization()") if args.write_model: model_solved.write(args.write_model) print(f"Wrote '{args.write_model}'") testutils.confirm_equal(rmserr_point, 0, eps = 2.5, msg = "Converged to a low RMS error") # I expect the fitted error (rmserr_point) to be a bit lower than # pixel_uncertainty_stdev because this solve is going to overfit: I don't have # enough data to uniquely define this model. And this isn't even a flexible # splined model! testutils.confirm_equal( rmserr_point, pixel_uncertainty_stdev - pixel_uncertainty_stdev*0.12, eps = pixel_uncertainty_stdev*0.12, msg = "Residual have the expected distribution" ) testutils.confirm_equal( nps.mag(Rt_extrinsics_err[3,:]), 0.0, eps = 0.05, msg = "Recovered extrinsic translation") testutils.confirm_equal( (np.trace(Rt_extrinsics_err[:3,:]) - 1) / 2., 1.0, eps = np.cos(1. * np.pi/180.0), # 1 deg msg = "Recovered extrinsic rotation") # Checking the intrinsics. Each intrinsics vector encodes an implicit # transformation. I compute and apply this transformation when making my # intrinsics comparisons. I make sure that within some distance of the pixel # center, the projections match up to within some number of pixels Nw = 60 def projection_diff(models, max_dist_from_center): lensmodels = [model.intrinsics()[0] for model in models] intrinsics_data = [model.intrinsics()[1] for model in models] imagersizes = [model.imagersize() for model in models] # v shape (...,Ncameras,Nheight,Nwidth,...) # q0 shape (..., Nheight,Nwidth,...) v,q0 = \ mrcal.sample_imager_unproject(Nw,None, *imagersizes[0], lensmodels, intrinsics_data, normalize = True) focus_center = None focus_radius = -1 if focus_center is None: focus_center = ((W-1.)/2., (H-1.)/2.) if focus_radius < 0: focus_radius = min(W,H)/6. implied_Rt10 = \ mrcal.implied_Rt10__from_unprojections(q0, v[0,...], v[1,...], focus_center = focus_center, focus_radius = focus_radius) q1 = mrcal.project( mrcal.transform_point_Rt(implied_Rt10, v[0,...]), lensmodels[1], intrinsics_data[1]) diff = nps.mag(q1 - q0) # zero-out everything too far from the center center = (imagersizes[0] - 1.) / 2. diff[ nps.norm2(q0 - center) > max_dist_from_center*max_dist_from_center ] = 0 if False: import gnuplotlib as gp gp.plot(diff, ascii = True, using = mrcal.imagergrid_using(imagersizes[0], Nw), square=1, _with='image', tuplesize=3, hardcopy='/tmp/yes.gp', cbmax=3) return diff diff = projection_diff( (model_true, model_solved), 800) testutils.confirm_equal(diff, 0, worstcase = True, eps = 6., msg = "Recovered intrinsics") # I test make_perfect_observations(). Doing it here is easy; doing it elsewhere # it much more work if True: optimization_inputs_perfect = copy.deepcopy(optimization_inputs) mrcal.make_perfect_observations(optimization_inputs_perfect, observed_pixel_uncertainty=0) x = mrcal.optimizer_callback(**optimization_inputs_perfect, no_jacobian = True, no_factorization = True)[1] Nmeas = mrcal.num_measurements_points(**optimization_inputs_perfect) if Nmeas > 0: i_meas0 = mrcal.measurement_index_points(0, **optimization_inputs_perfect) testutils.confirm_equal( x[i_meas0:i_meas0+Nmeas], 0, worstcase = True, eps = 1e-8, msg = f"make_perfect_observations() works for points") else: testutils.confirm( False, msg = f"Nmeasurements_points <= 0") if not args.do_sample: testutils.finish() sys.exit() #### We're going to computed a bunch of noisy calibrations, and gather #### statistics. I look at: #### - the projection of one point #### - the error in the z coordinate of the camera position #### #### For each one I compute the predicted uncertainty and the empirical one, #### from the samples, and make sure they match ( intrinsics_sampled, \ rt_cam_ref_sampled_mounted, \ frames_sampled, \ points_sampled, \ calobject_warp_sampled, \ optimization_inputs_sampled ) = \ calibration_sample(args.Nsamples, optimization_inputs_baseline, pixel_uncertainty_stdev, fixedframes = True, function_optimize = optimize) Var_errz,Var_q = get_variances() ####### check errz if 1: rt_extrinsics_sampled_err = \ mrcal.compose_rt( rt_cam_ref_sampled_mounted, model_solved.extrinsics_rt_toref()) errz_sampled = rt_extrinsics_sampled_err[:,0,5:] testutils.confirm_equal( np.mean(errz_sampled), 0, eps = 0.01, msg = f"errz distribution has mean=0") testutils.confirm_equal( np.std(errz_sampled), np.sqrt(Var_errz), eps=0.02, relative = True, msg = f"Predicted Var(errz) correct") if args.make_documentation_plots is not None: errz_sampled = rt_extrinsics_sampled_err[...,0,5] binwidth = 0.01 equation_observed = \ mrcal.fitted_gaussian_equation(x = errz_sampled, binwidth = binwidth, legend = f'Observed in simulation') equation_predicted = \ mrcal.fitted_gaussian_equation(mean = np.mean(errz_sampled), sigma = np.sqrt(Var_errz), N = len(errz_sampled), binwidth = binwidth, legend = "Predicted by mrcal") def makeplot(**plotoptions): gp.plot(errz_sampled, histogram = True, binwidth = binwidth, equation_above = (equation_observed, equation_predicted), xlabel = "Error in z (m)", ylabel = "Count", title = "Surveyed calibration: distribution of error-in-z due to calibration-time noise", **plotoptions) if args.make_documentation_plots: for extension in ('pdf','svg','png','gp'): makeplot(wait = False, terminal = terminal[extension], _set = extraset[extension], hardcopy = f'{args.make_documentation_plots}/var-errz.{extension}') else: makeplot(wait = True) ####### check projection of a point if 1: if 1: # Code check. Computing this directly should mimic the # mrcal.projection_uncertainty() result exactly since it should be 100% the # same computation. # # EXCEPT when looking at infinity. The projection_uncertainty() path # uses atinfinity=True, so it ignores translations completely. THIS path # uses a high distance, so the result will be close, but not identical. # I use a sloppier bound in that case p,dp_drt_cam_ref,_ = \ mrcal.transform_point_rt(model_solved.extrinsics_rt_fromref(), p_query_ref, get_gradients = True) q,dq_dp,dq_di = \ mrcal.project( p, model_solved.intrinsics()[0], model_solved.intrinsics()[1], get_gradients = True) dq_drt_cam_ref = nps.matmult(dq_dp, dp_drt_cam_ref) dq_db = np.zeros( (2,Nstate), dtype=float) icam = 0 i_state = mrcal.state_index_extrinsics(icam, **optimization_inputs) dq_db[...,i_state:i_state+6] = dq_drt_cam_ref i_state = mrcal.state_index_intrinsics(icam, **optimization_inputs) dq_db[...,i_state:i_state+Nintrinsics] = dq_di Var_q2 = mrcal.model_analysis._propagate_calibration_uncertainty( \ 'covariance', dF_db = dq_db, optimization_inputs = optimization_inputs) testutils.confirm_equal(Var_q, Var_q2, relative=True, worstcase=True, eps=1e-6 if args.distance is not None else 1e-2, msg="projection_uncertainty() should do the same thing s caling _propagate_calibration_uncertainty() directly") p_query_cam_sampled = \ mrcal.transform_point_rt(rt_cam_ref_sampled_mounted[:,0,:], p_query_ref) q_query_sampled = \ mrcal.project( p_query_cam_sampled, model_solved.intrinsics()[0], intrinsics_sampled[:,0,:] ) q_query_sampled_mean = np.mean(q_query_sampled, axis=0) # shape (2,2) Var_q_observed = np.mean( nps.outer(q_query_sampled-q_query_sampled_mean, q_query_sampled-q_query_sampled_mean), axis=0 ) worst_direction_stdev_observed = mrcal.worst_direction_stdev(Var_q_observed) worst_direction_stdev_predicted = mrcal.worst_direction_stdev(Var_q) testutils.confirm_equal( nps.mag(q_query_sampled_mean - q_query), 0, eps = 5, worstcase = True, msg = "Sampled projections cluster around the sample point") testutils.confirm_equal(worst_direction_stdev_observed, worst_direction_stdev_predicted, eps = 0.1, worstcase = True, relative = True, msg = f"Predicted worst-case projections match sampled observations") # I now compare the variances. The cross terms have lots of apparent error, # but it's more meaningful to compare the eigenvectors and eigenvalues, so I # just do that testutils.confirm_covariances_equal(Var_q, Var_q_observed, what = "Var_q", eps_eigenvalues = 0.05, eps_eigenvectors_deg = 10, check_biggest_eigenvalue_only = True) if args.make_documentation_plots is not None: def makeplot(**plotoptions): gp.plot(*mrcal.utils._plot_args_points_and_covariance_ellipse( \ q_query_sampled, "Observed in simulation"), mrcal.utils._plot_arg_covariance_ellipse( \ np.mean(q_query_sampled, axis=0), Var_q, "Predicted by mrcal"), square = 1, xlabel = "x (pixels)", ylabel = "y (pixels)", title = "Surveyed calibration: distribution of point projections due to calibration-time noise", **plotoptions) if args.make_documentation_plots: for extension in ('pdf','svg','png','gp'): makeplot(wait = False, terminal = shorter_terminal(terminal[extension]), _set = extraset[extension], hardcopy = f'{args.make_documentation_plots}/var-q.{extension}') else: makeplot(wait = True) testutils.finish() mrcal-2.4.1/test/test-triangulation-uncertainty.py000077500000000000000000001421101456301662300223550ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Triangulation uncertainty quantification test We look at the triangulated position computed from a pixel observation in two cameras. Calibration-time noise and triangulation-time noise both affect the accuracy of the triangulated result. This tool samples both of these noise sources to make sure the analytical uncertainty predictions are correct ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--fixed', type=str, choices=('cam0','frames'), default = 'cam0', help='''Are we putting the origin at camera0, or are all the frames at a fixed (and non-optimizeable) pose? One or the other is required.''') parser.add_argument('--model', type=str, choices=('opencv4','opencv8','splined'), default = 'opencv4', help='''Which lens model we're using. Must be one of ('opencv4','opencv8','splined')''') parser.add_argument('--Nframes', type=int, default=50, help='''How many chessboard poses to simulate. These are dense observations: every camera sees every corner of every chessboard pose''') parser.add_argument('--Nsamples', type=int, default=500, help='''How many random samples to evaluate''') parser.add_argument('--Ncameras', type = int, default = 2, help='''How many calibration-time cameras to simulate. We will use 2 of these for triangulation, selected with --cameras''') parser.add_argument('--cameras', type = int, nargs = 2, default = (0,1), help='''Which cameras we're using for the triangulation. These need to be different, and in [0,Ncameras-1]. The vanilla case will have Ncameras=2, so the default value for this argument (0,1) is correct''') parser.add_argument('--do-sample', action='store_true', help='''By default we don't run the time-intensive samples of the calibration solves. This runs a very limited set of tests, and exits. To perform the full set of tests, pass --do-sample''') parser.add_argument('--stabilize-coords', action = 'store_true', help='''Whether we report the triangulation in the camera-0 coordinate system (which is moving due to noise) or in a stabilized coordinate system based on the frame poses''') parser.add_argument('--cull-left-of-center', action = 'store_true', help='''If given, the calibration data in the left half of the imager is thrown out''') parser.add_argument('--q-calibration-stdev', type = float, default = 0.0, help='''The observed_pixel_uncertainty of the chessboard observations at calibration time. Defaults to 0.0. At least one of --q-calibration-stdev and --q-observation-stdev MUST be given as > 0''') parser.add_argument('--q-observation-stdev', type = float, default = 0.0, help='''The observed_pixel_uncertainty of the point observations at triangulation time. Defaults to 0.0. At least one of --q-calibration-stdev and --q-observation-stdev MUST be given as > 0''') parser.add_argument('--q-observation-stdev-correlation', type = float, default = 0.0, help='''By default, the noise in the observation-time pixel observations is assumed independent. This isn't entirely realistic: observations of the same feature in multiple cameras originate from an imager correlation operation, so they will have some amount of correlation. If given, this argument specifies how much correlation. This is a value in [0,1] scaling the stdev. 0 means "independent" (the default). 1.0 means "100%% correlated".''') parser.add_argument('--baseline', type = float, default = 2., help='''The baseline of the camera pair. This is the horizontal distance between each pair of adjacent cameras''') parser.add_argument('--observed-point', type = float, nargs = 3, required = True, help='''The world coordinate of the observed point. Usually this will be ~(small, 0, large). The code will evaluate two points together: the one passed here, and the same one with a negated x coordinate''') parser.add_argument('--cache', type=str, choices=('read','write'), help=f'''A cache file stores the recalibration results; computing these can take a long time. This option allows us to or write the cache instead of sampling. The cache file is hardcoded to a cache file (in /tmp). By default, we do neither: we don't read the cache (we sample instead), and we do not write it to disk when we're done. This option is useful for tests where we reprocess the same scenario repeatedly''') parser.add_argument('--make-documentation-plots', type=str, help='''If given, we produce plots for the documentation. Takes one argument: a string describing this test. This will be used in the filenames and titles of the resulting plots. Leading directories will be used; whitespace and funny characters in the filename are allowed: will be replaced with _. To make interactive plots, pass ""''') parser.add_argument('--ellipse-plot-radius', type=float, help='''By default, the ellipse plot autoscale to show the data and the ellipses nicely. But that means that plots aren't comparable between runs. This option can be passed to select a constant plot width, which allows such comparisons''') parser.add_argument('--terminal-pdf', type=str, help='''The gnuplotlib terminal for --make-documentation-plots .PDFs. Omit this unless you know what you're doing''') parser.add_argument('--terminal-svg', type=str, help='''The gnuplotlib terminal for --make-documentation-plots .SVGs. Omit this unless you know what you're doing''') parser.add_argument('--terminal-png', type=str, help='''The gnuplotlib terminal for --make-documentation-plots .PNGs. Omit this unless you know what you're doing''') parser.add_argument('--explore', action='store_true', help='''If given, we drop into a REPL at the end''') args = parser.parse_args() if args.Ncameras < 2: raise Exception("--Ncameras must be given at least 2 cameras") if args.cameras[0] == args.cameras[1]: raise Exception("--cameras must select two different cameras") if args.cameras[0] < 0 or args.cameras[0] >= args.Ncameras: raise Exception("--cameras must select two different cameras, each in [0,Ncameras-1]") if args.cameras[1] < 0 or args.cameras[1] >= args.Ncameras: raise Exception("--cameras must select two different cameras, each in [0,Ncameras-1]") if args.q_calibration_stdev <= 0.0 and \ args.q_observation_stdev <= 0.0: raise Exception('At least one of --q-calibration-stdev and --q-observation-stdev MUST be given as > 0') return args args = parse_args() terminal = dict(pdf = args.terminal_pdf, svg = args.terminal_svg, png = args.terminal_png, gp = 'gp') pointscale = dict(pdf = 1, svg = 1, png = 1, gp = 1) pointscale[""] = 1. def shorter_terminal(t): # Adjust the terminal string to be less tall. Makes the multiplots look # better: less wasted space m = re.match("(.*)( size.*?,)([0-9.]+)(.*?)$", t) if m is None: return t return m.group(1) + m.group(2) + str(float(m.group(3))*0.8) + m.group(4) if args.make_documentation_plots: d,f = os.path.split(args.make_documentation_plots) args.make_documentation_plots_extratitle = f args.make_documentation_plots_path = os.path.join(d, re.sub(r"[^0-9a-zA-Z_\.\-]", "_", f)) print(f"Will write documentation plots to {args.make_documentation_plots_path}-xxxx.pdf and .png and .svg") if terminal['svg'] is None: terminal['svg'] = 'svg size 800,600 noenhanced solid dynamic font ",14"' if terminal['pdf'] is None: terminal['pdf'] = 'pdf size 8in,6in noenhanced solid color font ",12"' if terminal['png'] is None: terminal['png'] = 'pngcairo size 1024,768 transparent noenhanced crop font ",12"' else: args.make_documentation_plots_extratitle = None extraset = dict() for k in pointscale.keys(): extraset[k] = f'pointsize {pointscale[k]}' testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils import copy import numpy as np import numpysane as nps import pickle from test_calibration_helpers import calibration_baseline,calibration_sample,grad ############# Set up my world, and compute all the perfect positions, pixel ############# observations of everything fixedframes = (args.fixed == 'frames') object_spacing = 0.1 object_width_n = 10 object_height_n = 9 calobject_warp_true = np.array((0.002, -0.005)) # I want the RNG to be deterministic np.random.seed(0) extrinsics_rt_fromref_true = np.zeros((args.Ncameras,6), dtype=float) extrinsics_rt_fromref_true[:,:3] = np.random.randn(args.Ncameras,3) * 0.1 extrinsics_rt_fromref_true[:, 3] = args.baseline * np.arange(args.Ncameras) extrinsics_rt_fromref_true[:,4:] = np.random.randn(args.Ncameras,2) * 0.1 # cam0 is at the identity. This makes my life easy: I can assume that the # optimization_inputs returned by calibration_baseline() use the same ref # coordinate system as these transformations. I explicitly state this by passing # calibration_baseline(allow_nonidentity_cam0_transform=False) later extrinsics_rt_fromref_true[0] *= 0 # shape (Npoints,3) p_triangulated_true0 = np.array((args.observed_point, args.observed_point), dtype=float) # first point has x<0 p_triangulated_true0[0,0] = -np.abs(p_triangulated_true0[0,0]) # second point is the same, but with a negated x: x>0 p_triangulated_true0[1,0] = -p_triangulated_true0[0,0] Npoints = p_triangulated_true0.shape[0] @nps.broadcast_define( (('Nintrinsics',),('Nintrinsics',), (6,),(6,),(6,), ('Nframes',6), ('Nframes',6), ('Npoints',2,2)), ('Npoints',3)) def triangulate_nograd( intrinsics_data0, intrinsics_data1, rt_cam0_ref, rt_cam0_ref_baseline, rt_cam1_ref, rt_ref_frame, rt_ref_frame_baseline, q, lensmodel, stabilize_coords = True): q = nps.atleast_dims(q,-3) rt01 = mrcal.compose_rt(rt_cam0_ref, mrcal.invert_rt(rt_cam1_ref)) # all the v have shape (...,3) vlocal0 = \ mrcal.unproject(q[...,0,:], lensmodel, intrinsics_data0) vlocal1 = \ mrcal.unproject(q[...,1,:], lensmodel, intrinsics_data1) v0 = vlocal0 v1 = \ mrcal.rotate_point_r(rt01[:3], vlocal1) # The triangulated point in the perturbed camera-0 coordinate system. # Calibration-time perturbations move this coordinate system, so to get # a better estimate of the triangulation uncertainty, we try to # transform this to the original camera-0 coordinate system; the # stabilization path below does that. # # shape (..., 3) p_triangulated0 = \ mrcal.triangulate_leecivera_mid2(v0, v1, rt01[3:]) if not stabilize_coords: return p_triangulated0 # Stabilization path. This uses the "true" solution, so I cannot do # this in the field. But I CAN do this in the randomized trials in # the test. And I can use the gradients to propagate the uncertainty # of this computation in the field # # Data flow: # point_cam_perturbed -> point_ref_perturbed -> point_frames # point_frames -> point_ref_baseline -> point_cam_baseline p_cam0_perturbed = p_triangulated0 p_ref_perturbed = mrcal.transform_point_rt(rt_cam0_ref, p_cam0_perturbed, inverted = True) # shape (..., Nframes, 3) p_frames = \ mrcal.transform_point_rt(rt_ref_frame, nps.dummy(p_ref_perturbed,-2), inverted = True) # shape (..., Nframes, 3) p_ref_baseline_all = mrcal.transform_point_rt(rt_ref_frame_baseline, p_frames) # shape (..., 3) p_ref_baseline = np.mean(p_ref_baseline_all, axis=-2) # shape (..., 3) return mrcal.transform_point_rt(rt_cam0_ref_baseline, p_ref_baseline) ################# Sampling cache_id = f"{args.fixed}-{args.model}-{args.Nframes}-{args.Nsamples}-{args.Ncameras}-{args.cameras[0]}-{args.cameras[1]}-{1 if args.stabilize_coords else 0}-{args.q_calibration_stdev}-{args.q_observation_stdev}-{args.q_observation_stdev_correlation}" cache_file = f"/tmp/test-triangulation-uncertainty--{cache_id}.pickle" if args.cache is None or args.cache == 'write': optimization_inputs_baseline, \ models_true, models_baseline, \ indices_frame_camintrinsics_camextrinsics, \ lensmodel, Nintrinsics, imagersizes, \ intrinsics_true, extrinsics_true_mounted, frames_true, \ observations_true, \ args.Nframes = \ calibration_baseline(args.model, args.Ncameras, args.Nframes, None, object_width_n, object_height_n, object_spacing, extrinsics_rt_fromref_true, calobject_warp_true, fixedframes, testdir, cull_left_of_center = args.cull_left_of_center, allow_nonidentity_cam0_transform = False) else: with open(cache_file,"rb") as f: (optimization_inputs_baseline, models_true, models_baseline, indices_frame_camintrinsics_camextrinsics, lensmodel, Nintrinsics, imagersizes, intrinsics_true, extrinsics_true_mounted, frames_true, observations_true, intrinsics_sampled, extrinsics_sampled_mounted, frames_sampled, calobject_warp_sampled) = pickle.load(f) baseline_rt_ref_frame = optimization_inputs_baseline['frames_rt_toref'] icam0,icam1 = args.cameras Rt01_true = mrcal.compose_Rt(mrcal.Rt_from_rt(extrinsics_rt_fromref_true[icam0]), mrcal.invert_Rt(mrcal.Rt_from_rt(extrinsics_rt_fromref_true[icam1]))) Rt10_true = mrcal.invert_Rt(Rt01_true) # shape (Npoints,Ncameras,3) p_triangulated_true_local = nps.xchg( nps.cat( p_triangulated_true0, mrcal.transform_point_Rt(Rt10_true, p_triangulated_true0) ), 0,1) # Pixel coords at the perfect intersection # shape (Npoints,Ncameras,2) q_true = nps.xchg( np.array([ mrcal.project(p_triangulated_true_local[:,i,:], lensmodel, intrinsics_true[args.cameras[i]]) \ for i in range(2)]), 0,1) # Sanity check. Without noise, the triangulation should report the test point exactly p_triangulated0 = \ triangulate_nograd(models_true[icam0].intrinsics()[1], models_true[icam1].intrinsics()[1], models_true[icam0].extrinsics_rt_fromref(), models_true[icam0].extrinsics_rt_fromref(), models_true[icam1].extrinsics_rt_fromref(), frames_true, frames_true, q_true, lensmodel, stabilize_coords = args.stabilize_coords) testutils.confirm_equal(p_triangulated0, p_triangulated_true0, eps = 1e-6, msg = "Noiseless triangulation should be perfect") p_triangulated0 = \ triangulate_nograd(models_baseline[icam0].intrinsics()[1], models_baseline[icam1].intrinsics()[1], models_baseline[icam0].extrinsics_rt_fromref(), models_baseline[icam0].extrinsics_rt_fromref(), models_baseline[icam1].extrinsics_rt_fromref(), baseline_rt_ref_frame, baseline_rt_ref_frame, q_true, lensmodel, stabilize_coords = args.stabilize_coords) testutils.confirm_equal(p_triangulated0, p_triangulated_true0, worstcase = True, relative = True, eps = 1e-2, reldiff_eps = 0.2, msg = "Re-optimized triangulation should be close to the reference. This checks the regularization bias") slices = ( (q_true[0], (models_baseline[icam0],models_baseline[icam1])), (q_true[1], (models_baseline[icam0],models_baseline[icam1])) ) _, \ _, \ dp_triangulated_dbstate, \ istate_i0, \ istate_i1, \ icam_extrinsics0, \ icam_extrinsics1, \ istate_e1, \ istate_e0 = \ mrcal.triangulation._triangulation_uncertainty_internal(slices, optimization_inputs_baseline, 0,0, stabilize_coords = args.stabilize_coords) ########## Gradient check dp_triangulated_di0_empirical = grad(lambda i0: triangulate_nograd(i0, models_baseline[icam1].intrinsics()[1], models_baseline[icam0].extrinsics_rt_fromref(), models_baseline[icam0].extrinsics_rt_fromref(), models_baseline[icam1].extrinsics_rt_fromref(), baseline_rt_ref_frame, baseline_rt_ref_frame, q_true, lensmodel, stabilize_coords=args.stabilize_coords), models_baseline[icam0].intrinsics()[1], step = 1e-5) dp_triangulated_di1_empirical = grad(lambda i1: triangulate_nograd(models_baseline[icam0].intrinsics()[1],i1, models_baseline[icam0].extrinsics_rt_fromref(), models_baseline[icam0].extrinsics_rt_fromref(), models_baseline[icam1].extrinsics_rt_fromref(), baseline_rt_ref_frame, baseline_rt_ref_frame, q_true, lensmodel, stabilize_coords=args.stabilize_coords), models_baseline[icam1].intrinsics()[1]) dp_triangulated_de1_empirical = grad(lambda e1: triangulate_nograd(models_baseline[icam0].intrinsics()[1], models_baseline[icam1].intrinsics()[1], models_baseline[icam0].extrinsics_rt_fromref(), models_baseline[icam0].extrinsics_rt_fromref(), e1, baseline_rt_ref_frame, baseline_rt_ref_frame, q_true, lensmodel, stabilize_coords=args.stabilize_coords), models_baseline[icam1].extrinsics_rt_fromref()) dp_triangulated_de0_empirical = grad(lambda e0: triangulate_nograd(models_baseline[icam0].intrinsics()[1], models_baseline[icam1].intrinsics()[1], e0, models_baseline[icam0].extrinsics_rt_fromref(), models_baseline[icam1].extrinsics_rt_fromref(), baseline_rt_ref_frame, baseline_rt_ref_frame, q_true, lensmodel, stabilize_coords=args.stabilize_coords), models_baseline[icam0].extrinsics_rt_fromref()) dp_triangulated_drtrf_empirical = grad(lambda rtrf: triangulate_nograd(models_baseline[icam0].intrinsics()[1], models_baseline[icam1].intrinsics()[1], models_baseline[icam0].extrinsics_rt_fromref(), models_baseline[icam0].extrinsics_rt_fromref(), models_baseline[icam1].extrinsics_rt_fromref(), rtrf, baseline_rt_ref_frame, q_true, lensmodel, stabilize_coords=args.stabilize_coords), baseline_rt_ref_frame, step = 1e-5) dp_triangulated_dq_empirical = grad(lambda q: triangulate_nograd(models_baseline[icam0].intrinsics()[1], models_baseline[icam1].intrinsics()[1], models_baseline[icam0].extrinsics_rt_fromref(), models_baseline[icam0].extrinsics_rt_fromref(), models_baseline[icam1].extrinsics_rt_fromref(), baseline_rt_ref_frame, baseline_rt_ref_frame, q, lensmodel, stabilize_coords=args.stabilize_coords), q_true, step = 1e-3) testutils.confirm_equal(dp_triangulated_dbstate[...,istate_i0:istate_i0+Nintrinsics], dp_triangulated_di0_empirical, relative = True, worstcase = True, eps = 0.1, msg = "Gradient check: dp_triangulated_dbstate[intrinsics0]") testutils.confirm_equal(dp_triangulated_dbstate[...,istate_i1:istate_i1+Nintrinsics], dp_triangulated_di1_empirical, relative = True, worstcase = True, eps = 0.1, msg = "Gradient check: dp_triangulated_dbstate[intrinsics1]") if istate_e0 is not None: testutils.confirm_equal(dp_triangulated_dbstate[...,istate_e0:istate_e0+6], dp_triangulated_de0_empirical, relative = True, worstcase = True, eps = 5e-3, msg = "Gradient check: dp_triangulated_dbstate[extrinsics0]") if istate_e1 is not None: testutils.confirm_equal(dp_triangulated_dbstate[...,istate_e1:istate_e1+6], dp_triangulated_de1_empirical, relative = True, worstcase = True, eps = 5e-3, msg = "Gradient check: dp_triangulated_dbstate[extrinsics1]") if optimization_inputs_baseline.get('do_optimize_frames'): istate_f0 = mrcal.state_index_frames(0, **optimization_inputs_baseline) Nstate_frames = mrcal.num_states_frames( **optimization_inputs_baseline) testutils.confirm_equal(dp_triangulated_dbstate[...,istate_f0:istate_f0+Nstate_frames], nps.clump(dp_triangulated_drtrf_empirical, n=-2), relative = True, worstcase = True, eps = 0.1, msg = "Gradient check: dp_triangulated_drtrf") # dp_triangulated_dq_empirical has shape (Npoints,3, Npoints,Ncameras,2) # The cross terms (p_triangulated(point=A), q(point=B)) should all be zero dp_triangulated_dq_empirical_cross_only = dp_triangulated_dq_empirical dp_triangulated_dq_empirical = np.zeros((Npoints,3,2,2), dtype=float) dp_triangulated_dq = np.zeros((Npoints,3,2,2), dtype=float) dp_triangulated_dq_flattened = nps.clump(dp_triangulated_dq, n=-2) for ipt in range(Npoints): dp_triangulated_dq_empirical[ipt,...] = dp_triangulated_dq_empirical_cross_only[ipt,:,ipt,:,:] dp_triangulated_dq_empirical_cross_only[ipt,:,ipt,:,:] = 0 p = np.zeros((3,), dtype=float) dp_triangulated_dq_flattened[ipt] = \ mrcal.triangulation._triangulate_grad_simple(*slices[ipt], p) testutils.confirm_equal(dp_triangulated_dq_empirical_cross_only, 0, eps = 1e-6, msg = "Gradient check: dp_triangulated_dq: cross-point terms are 0") testutils.confirm_equal(dp_triangulated_dq, dp_triangulated_dq_empirical, relative = True, worstcase = True, eps = 5e-3, msg = "Gradient check: dp_triangulated_dq") p_alone = \ mrcal.triangulate( q_true, (models_baseline[icam0],models_baseline[icam1]), stabilize_coords = args.stabilize_coords ) p_calnoise, \ Var_p_calibration_alone = \ mrcal.triangulate( q_true, (models_baseline[icam0],models_baseline[icam1]), q_calibration_stdev = args.q_calibration_stdev, stabilize_coords = args.stabilize_coords ) p_obsnoise, \ Var_p_observation_alone = \ mrcal.triangulate( q_true, (models_baseline[icam0],models_baseline[icam1]), q_observation_stdev = args.q_observation_stdev, q_observation_stdev_correlation = args.q_observation_stdev_correlation, stabilize_coords = args.stabilize_coords ) p, \ Var_p_calibration, \ Var_p_observation, \ Var_p_joint = \ mrcal.triangulate( q_true, (models_baseline[icam0],models_baseline[icam1]), q_calibration_stdev = args.q_calibration_stdev, q_observation_stdev = args.q_observation_stdev, q_observation_stdev_correlation = args.q_observation_stdev_correlation, stabilize_coords = args.stabilize_coords) testutils.confirm_equal(p_alone, p_triangulated0, eps = 1e-6, msg = "triangulate(no noise) returns the right point") testutils.confirm_equal(p_alone, p_calnoise, eps = 1e-6, msg = "triangulate(cal noise) returns the right point") testutils.confirm_equal(p_alone, p_obsnoise, eps = 1e-6, msg = "triangulate(obs noise) returns the right point") testutils.confirm_equal(p_alone, p, eps = 1e-6, msg = "triangulate(both noise) returns the right point") testutils.confirm_equal(Var_p_calibration_alone, Var_p_calibration, eps = 1e-6, msg = "triangulate(cal noise) returns a consistent Var_p_calibration") testutils.confirm_equal(Var_p_observation_alone, Var_p_observation, eps = 1e-6, msg = "triangulate(obs noise) returns a consistent Var_p_observation") testutils.confirm_equal(Var_p_joint.shape, Var_p_calibration.shape, msg = "Var_p_joint.shape matches Var_p_calibration.shape") for ipt in range(Npoints): testutils.confirm_equal(Var_p_joint[ipt,:,ipt,:], Var_p_calibration[ipt,:,ipt,:] + Var_p_observation[ipt,:,:], worstcase = True, eps = 1e-9, msg = "Var(joint) should be Var(cal-time-noise) + Var(obs-time-noise)") if not args.do_sample: testutils.finish() sys.exit() try: intrinsics_sampled did_sample = True except: did_sample = False if not did_sample: ( intrinsics_sampled, \ extrinsics_sampled_mounted, \ frames_sampled, \ points_sampled, \ calobject_warp_sampled, \ optimization_inputs_sampled ) = \ calibration_sample( args.Nsamples, optimization_inputs_baseline, args.q_calibration_stdev, fixedframes) if args.cache is not None and args.cache == 'write': with open(cache_file,"wb") as f: pickle.dump((optimization_inputs_baseline, models_true, models_baseline, indices_frame_camintrinsics_camextrinsics, lensmodel, Nintrinsics, imagersizes, intrinsics_true, extrinsics_true_mounted, frames_true, observations_true, intrinsics_sampled, extrinsics_sampled_mounted, frames_sampled, calobject_warp_sampled), f) print(f"Wrote cache to {cache_file}") # Let's actually apply the noise to compute var(distancep) empirically to compare # against the var(distancep) prediction I just computed # shape (Nsamples,Npoints,2,2) var_qt_onepoint = \ mrcal.triangulation._compute_Var_q_triangulation(args.q_observation_stdev, args.q_observation_stdev_correlation) var_qt = np.zeros((Npoints*2*2, Npoints*2*2), dtype=float) for i in range(Npoints): var_qt[4*i:4*(i+1), 4*i:4*(i+1)] = var_qt_onepoint # I want the RNG to be deterministic. If I turn caching on/off I'd be at a # different place in the RNG here. I reset to keep things consistent np.random.seed(0) qt_noise = \ np.random.multivariate_normal( mean = np.zeros((Npoints*2*2,),), cov = var_qt, size = args.Nsamples ).reshape(args.Nsamples,Npoints,2,2) q_sampled = q_true + qt_noise # I have the perfect observation pixel coords. I triangulate them through my # sampled calibration if fixedframes: extrinsics_sampled_cam0 = extrinsics_sampled_mounted[..., icam_extrinsics0,:] extrinsics_sampled_cam1 = extrinsics_sampled_mounted[..., icam_extrinsics1,:] else: # if not fixedframes: extrinsics_sampled_mounted is prepended with the # extrinsics for cam0 (selected with icam_extrinsics==-1) extrinsics_sampled_cam0 = extrinsics_sampled_mounted[..., icam_extrinsics0+1,:] extrinsics_sampled_cam1 = extrinsics_sampled_mounted[..., icam_extrinsics1+1,:] p_triangulated_sampled0 = triangulate_nograd(intrinsics_sampled[...,icam0,:], intrinsics_sampled[...,icam1,:], extrinsics_sampled_cam0, models_baseline[icam0].extrinsics_rt_fromref(), extrinsics_sampled_cam1, frames_sampled, baseline_rt_ref_frame, q_sampled, lensmodel, stabilize_coords = args.stabilize_coords) ranges = nps.mag(p_triangulated0) ranges_true = nps.mag(p_triangulated_true0) ranges_sampled = nps.transpose(nps.mag(p_triangulated_sampled0)) mean_ranges_sampled = ranges_sampled.mean( axis = -1) Var_ranges_sampled = ranges_sampled.var( axis = -1) # r = np.mag(p) # dr_dp = p/r # Var(r) = dr_dp var(p) dr_dpT # = p var(p) pT / norm2(p) Var_ranges_joint = np.zeros((Npoints,), dtype=float) Var_ranges_calibration = np.zeros((Npoints,), dtype=float) Var_ranges_observations = np.zeros((Npoints,), dtype=float) for ipt in range(Npoints): Var_ranges_joint[ipt] = \ nps.matmult(p_triangulated0[ipt], Var_p_joint[ipt,:,ipt,:], nps.transpose(p_triangulated0[ipt]))[0] / nps.norm2(p_triangulated0[ipt]) Var_ranges_calibration[ipt] = \ nps.matmult(p_triangulated0[ipt], Var_p_calibration[ipt,:,ipt,:], nps.transpose(p_triangulated0[ipt]))[0] / nps.norm2(p_triangulated0[ipt]) Var_ranges_observations[ipt] = \ nps.matmult(p_triangulated0[ipt], Var_p_observation[ipt,:,:], nps.transpose(p_triangulated0[ipt]))[0] / nps.norm2(p_triangulated0[ipt]) diff = p_triangulated0[1] - p_triangulated0[0] distance = nps.mag(diff) distance_true = nps.mag(p_triangulated_true0[:,0] - p_triangulated_true0[:,1]) distance_sampled = nps.mag(p_triangulated_sampled0[:,1,:] - p_triangulated_sampled0[:,0,:]) mean_distance_sampled = distance_sampled.mean() Var_distance_sampled = distance_sampled.var() # diff = p1-p0 # dist = np.mag(diff) # ddist_dp01 = [-diff diff] / dist # Var(dist) = ddist_dp01 var(p01) ddist_dp01T # = [-diff diff] var(p01) [-diff diff]T / norm2(diff) Var_distance = nps.matmult(nps.glue( -diff, diff, axis=-1), Var_p_joint.reshape(Npoints*3,Npoints*3), nps.transpose(nps.glue( -diff, diff, axis=-1),))[0] / nps.norm2(diff) # I have the observed and predicted distributions, so I make sure things match. # For some not-yet-understood reason, the distance distribution isn't # normally-distributed: there's a noticeable fat tail. Thus I'm not comparing # those two distributions (Var_distance,Var_distance_sampled) in this test. p_sampled = nps.clump(p_triangulated_sampled0, n=-2) mean_p_sampled = np.mean(p_sampled, axis=-2) Var_p_sampled = nps.matmult( nps.transpose(p_sampled - mean_p_sampled), p_sampled - mean_p_sampled ) / args.Nsamples testutils.confirm_equal(mean_p_sampled, p_triangulated_true0.ravel(), worstcase = True, # High threshold. Need many more samples to be able to # reduce it eps = p_triangulated_true0[0,2]/150., msg = "Triangulated position matches sampled mean") for ipt in range(2): testutils.confirm_covariances_equal(Var_p_joint[ipt,:,ipt,:], Var_p_sampled[ipt*3:(ipt+1)*3,ipt*3:(ipt+1)*3], what = f"triangulated point variance for point {ipt}", # This is a relatively-high threshold. I can tighten # it, but then I'd need to collect more # samples. Non-major axes have more # relative error eps_eigenvalues = (0.11, 0.2, 0.3), eps_eigenvectors_deg = 6) # It would be great to test the distribution of the difference between two # points, but I'm not doing that: it doesn't look very gaussian while the # analytical uncertainty IS gaussian. This needs investigation if not (args.explore or \ args.make_documentation_plots is not None): testutils.finish() sys.exit() if args.make_documentation_plots is not None: import gnuplotlib as gp empirical_distributions_xz = \ [ mrcal.utils._plot_args_points_and_covariance_ellipse(p_triangulated_sampled0[:,ipt,(0,2)], 'Observed') \ for ipt in range(Npoints) ] # Individual covariances Var_p_joint_diagonal = [Var_p_joint[ipt,:,ipt,:][(0,2),:][:,(0,2)] \ for ipt in range(Npoints)] Var_p_calibration_diagonal = [Var_p_calibration[ipt,:,ipt,:][(0,2),:][:,(0,2)] \ for ipt in range(Npoints)] Var_p_observation_diagonal = [Var_p_observation[ipt,:,:][(0,2),:][:,(0,2)] \ for ipt in range(Npoints)] max_sigma_points = np.array([ np.max(np.sqrt(np.linalg.eig(V)[0])) for V in Var_p_joint_diagonal ]) max_sigma = np.max(max_sigma_points) if args.ellipse_plot_radius is not None: ellipse_plot_radius = args.ellipse_plot_radius else: ellipse_plot_radius = max_sigma*3 title_triangulation = 'Triangulation uncertainty' title_covariance = 'Abs(Covariance) of the [p0,p1] vector (m^2)' title_range0 = 'Range to the left triangulated point' title_distance = 'Distance between the two triangulated points' if args.make_documentation_plots_extratitle is not None: title_triangulation += f': {args.make_documentation_plots_extratitle}' title_covariance += f': {args.make_documentation_plots_extratitle}' title_range0 += f': {args.make_documentation_plots_extratitle}' title_distance += f': {args.make_documentation_plots_extratitle}' subplots = [ [p for p in (empirical_distributions_xz[ipt][1], # points; plot first to not obscure the ellipses mrcal.utils._plot_arg_covariance_ellipse(p_triangulated0[ipt][(0,2),], Var_p_joint_diagonal[ipt], "Predicted-joint"), mrcal.utils._plot_arg_covariance_ellipse(p_triangulated0[ipt][(0,2),], Var_p_calibration_diagonal[ipt], "Predicted-calibration-only"), mrcal.utils._plot_arg_covariance_ellipse(p_triangulated0[ipt][(0,2),], Var_p_observation_diagonal[ipt], "Predicted-observations-only"), empirical_distributions_xz[ipt][0], dict( square = True, _xrange = [p_triangulated0[ipt,0] - ellipse_plot_radius, p_triangulated0[ipt,0] + ellipse_plot_radius], _yrange = [p_triangulated0[ipt,2] - ellipse_plot_radius, p_triangulated0[ipt,2] + ellipse_plot_radius], xlabel = 'Triangulated point x (left/right) (m)', ylabel = 'Triangulated point z (forward/back) (m)',) ) # ignore all None plot items. This will throw away any # infinitely-small ellipses if p is not None ] \ for ipt in range(Npoints) ] def makeplots(dohardcopy, processoptions_base): processoptions = copy.deepcopy(processoptions_base) gp.add_plot_option(processoptions, 'set', ('xtics 0.01', 'ytics 0.01')) # The key should use smaller text than the rest of the plot, if possible if 'terminal' in processoptions: m = re.search('font ",([0-9]+)"', processoptions['terminal']) if m is not None: s = int(m.group(1)) gp.add_plot_option(processoptions, 'set', ('xtics 0.01', 'ytics 0.01', f'key font ",{int(s*0.8)}"')) if dohardcopy: processoptions['hardcopy'] = \ f'{args.make_documentation_plots_path}--ellipses.{extension}' processoptions['terminal'] = shorter_terminal(processoptions['terminal']) # Hardcopies do things a little differently, to be nicer for docs gp.plot( *subplots, multiplot = f'layout 1,2', unset = 'grid', **processoptions ) else: # Interactive plotting, so no multiplots. Interactive plots for p in subplots: gp.plot( *p[:-1], **p[-1], **processoptions ) processoptions = copy.deepcopy(processoptions_base) if dohardcopy: processoptions['hardcopy'] = \ f'{args.make_documentation_plots_path}--p0-p1-magnitude-covariance.{extension}' processoptions['title'] = title_covariance gp.plotimage( np.abs(Var_p_joint.reshape(Npoints*3,Npoints*3)), square = True, xlabel = 'Variable index (left point x,y,z; right point x,y,z)', ylabel = 'Variable index (left point x,y,z; right point x,y,z)', **processoptions) processoptions = copy.deepcopy(processoptions_base) binwidth = np.sqrt(Var_ranges_joint[0]) / 4. equation_range0_observed_gaussian = \ mrcal.fitted_gaussian_equation(x = ranges_sampled[0], binwidth = binwidth, legend = "Idealized gaussian fit to data") equation_range0_predicted_joint_gaussian = \ mrcal.fitted_gaussian_equation(mean = ranges[0], sigma = np.sqrt(Var_ranges_joint[0]), N = len(ranges_sampled[0]), binwidth = binwidth, legend = "Predicted-joint") equation_range0_predicted_calibration_gaussian = \ mrcal.fitted_gaussian_equation(mean = ranges[0], sigma = np.sqrt(Var_ranges_calibration[0]), N = len(ranges_sampled[0]), binwidth = binwidth, legend = "Predicted-calibration") equation_range0_predicted_observations_gaussian = \ mrcal.fitted_gaussian_equation(mean = ranges[0], sigma = np.sqrt(Var_ranges_observations[0]), N = len(ranges_sampled[0]), binwidth = binwidth, legend = "Predicted-observations") if dohardcopy: processoptions['hardcopy'] = \ f'{args.make_documentation_plots_path}--range-to-p0.{extension}' processoptions['title'] = title_range0 gp.add_plot_option(processoptions, 'set', 'samples 1000') gp.plot(ranges_sampled[0], histogram = True, binwidth = binwidth, equation_above = (equation_range0_predicted_joint_gaussian, equation_range0_predicted_calibration_gaussian, equation_range0_predicted_observations_gaussian, equation_range0_observed_gaussian), xlabel = "Range to the left triangulated point (m)", ylabel = "Frequency", **processoptions) processoptions = copy.deepcopy(processoptions_base) binwidth = np.sqrt(Var_distance) / 4. equation_distance_observed_gaussian = \ mrcal.fitted_gaussian_equation(x = distance_sampled, binwidth = binwidth, legend = "Idealized gaussian fit to data") equation_distance_predicted_gaussian = \ mrcal.fitted_gaussian_equation(mean = distance, sigma = np.sqrt(Var_distance), N = len(distance_sampled), binwidth = binwidth, legend = "Predicted") if dohardcopy: processoptions['hardcopy'] = \ f'{args.make_documentation_plots_path}--distance-p1-p0.{extension}' processoptions['title'] = title_distance gp.add_plot_option(processoptions, 'set', 'samples 1000') gp.plot(distance_sampled, histogram = True, binwidth = binwidth, equation_above = (equation_distance_predicted_gaussian, equation_distance_observed_gaussian), xlabel = "Distance between triangulated points (m)", ylabel = "Frequency", **processoptions) if args.make_documentation_plots: for extension in ('pdf','svg','png','gp'): makeplots(dohardcopy = True, processoptions_base = dict(wait = False, terminal = terminal[extension], _set = extraset[extension])) else: makeplots(dohardcopy = False, processoptions_base = dict(wait = True)) if args.explore: import gnuplotlib as gp import IPython IPython.embed() mrcal-2.4.1/test/test-triangulation.py000077500000000000000000000247131456301662300200220ustar00rootroot00000000000000#!/usr/bin/env python3 import sys import numpy as np import numpysane as nps import os testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils from test_calibration_helpers import grad import scipy.optimize # I want the RNG to be deterministic np.random.seed(0) ############### World layout # camera0 is the "reference" model0 = mrcal.cameramodel( intrinsics = ('LENSMODEL_PINHOLE', np.array((1000., 1000., 500., 500.))), imagersize = np.array((1000,1000)) ) model1 = mrcal.cameramodel( intrinsics = ('LENSMODEL_PINHOLE', np.array((1100., 1100., 500., 500.))), imagersize = np.array((1000,1000)) ) # All the callback functions can broadcast on p,v @nps.broadcast_define( ((3,), (3,), (3,), (3,)), ()) def callback_l2_geometric(p, v0, v1, t01): if p[2] < 0: return 1e6 distance_p_v0 = nps.mag(p - nps.inner(p, v0)/nps.norm2(v0) * v0) distance_p_v1 = nps.mag(p-t01 - nps.inner(p-t01,v1)/nps.norm2(v1) * v1) return np.abs(distance_p_v0) + np.abs(distance_p_v1) @nps.broadcast_define( ((3,), (3,), (3,), (3,)), ()) def callback_l2_angle(p, v0, v1, t01): costh0 = nps.inner(p, v0) / np.sqrt(nps.norm2(p) * nps.norm2(v0)) costh1 = nps.inner(p-t01,v1) / np.sqrt(nps.norm2(p-t01) * nps.norm2(v1)) th0 = np.arccos(min(costh0, 1.0)) th1 = np.arccos(min(costh1, 1.0)) return th0*th0 + th1*th1 @nps.broadcast_define( ((3,), (3,), (3,), (3,)), ()) def callback_l1_angle(p, v0, v1, t01): costh0 = nps.inner(p, v0) / np.sqrt(nps.norm2(p) * nps.norm2(v0)) costh1 = nps.inner(p-t01,v1) / np.sqrt(nps.norm2(p-t01) * nps.norm2(v1)) th0 = np.arccos(min(costh0, 1.0)) th1 = np.arccos(min(costh1, 1.0)) return np.abs(th0) + np.abs(th1) @nps.broadcast_define( ((3,), (3,), (3,), (3,)), ()) def callback_linf_angle(p, v0, v1, t01): costh0 = nps.inner(p, v0) / np.sqrt(nps.norm2(p) * nps.norm2(v0)) costh1 = nps.inner(p-t01,v1) / np.sqrt(nps.norm2(p-t01) * nps.norm2(v1)) # Simpler function that has the same min return (1-min(costh0, costh1)) * 1e9 # th0 = np.arccos(min(costh0, 1.0)) # th1 = np.arccos(min(costh1, 1.0)) # return max(np.abs(th0), np.abs(th1)) @nps.broadcast_define( ((3,), (3,), (3,), (4,3)), ()) def callback_l2_reprojection(p, v0local, v1local, Rt01): dq0 = \ mrcal.project(p, *model0.intrinsics()) - \ mrcal.project(v0local, *model0.intrinsics()) dq1 = \ mrcal.project(mrcal.transform_point_Rt(mrcal.invert_Rt(Rt01),p), *model1.intrinsics()) - \ mrcal.project(v1local, *model1.intrinsics()) return nps.norm2(dq0) + nps.norm2(dq1) # can broadcast on p def test_geometry( Rt01, p, whatgeometry, out_of_bounds = False, check_gradients = False): R01 = Rt01[:3,:] t01 = Rt01[ 3,:] # p now has shape (Np,3). The leading dims have been flattened p = p.reshape( p.size // 3, 3) Np = len(p) # p has shape (Np,3) # v has shape (Np,2) v0local_noisy, v1local_noisy,v0_noisy,v1_noisy,q0_ref,q1_ref,q0_noisy,q1_noisy = \ [v[...,0,:] for v in \ mrcal.synthetic_data. _noisy_observation_vectors_for_triangulation(p, Rt01, model0.intrinsics(), model1.intrinsics(), 1, sigma = 0.1)] scenarios = \ ( (mrcal.triangulate_geometric, callback_l2_geometric, v0_noisy, v1_noisy, t01), (mrcal.triangulate_leecivera_l1, callback_l1_angle, v0_noisy, v1_noisy, t01), (mrcal.triangulate_leecivera_linf, callback_linf_angle, v0_noisy, v1_noisy, t01), (mrcal.triangulate_leecivera_mid2, None, v0_noisy, v1_noisy, t01), (mrcal.triangulate_leecivera_wmid2,None, v0_noisy, v1_noisy, t01), (mrcal.triangulate_lindstrom, callback_l2_reprojection, v0local_noisy, v1local_noisy, Rt01), ) for scenario in scenarios: f, callback = scenario[:2] args = scenario[2:] result = f(*args, get_gradients = True) p_reported = result[0] what = f"{whatgeometry} {f.__name__}" if out_of_bounds: p_optimized = np.zeros(p_reported.shape) else: # Check all the gradients if check_gradients: grads = result[1:] for ip in range(Np): args_cut = (args[0][ip], args[1][ip], args[2]) for ivar in range(len(args)): grad_empirical = \ grad( lambda x: f( *args_cut[:ivar], x, *args_cut[ivar+1:]), args_cut[ivar], step = 1e-6) testutils.confirm_equal( grads[ivar][ip], grad_empirical, relative = True, worstcase = True, msg = f"{what}: grad(ip={ip}, ivar = {ivar})", eps = 2e-2) if callback is not None: # I run an optimization to directly optimize the quantity each triangulation # routine is supposed to be optimizing, and then I compare p_optimized = \ nps.cat(*[ scipy.optimize.minimize(callback, p_reported[ip], # seed from the "right" value args = (args[0][ip], args[1][ip], args[2]), method = 'Nelder-Mead', # options = dict(disp = True) )['x'] \ for ip in range(Np) ]) # print( f"{what} p reported,optimized:\n{nps.cat(p_reported, p_optimized)}" ) # print( f"{what} p_err: {p_reported - p_optimized}" ) # print( f"{what} optimum reported/optimized:\n{callback(p_reported, *args)/callback(p_optimized, *args)}" ) testutils.confirm_equal( p_reported, p_optimized, relative = True, worstcase = True, msg = what, eps = 1e-3) else: # No callback defined. Compare projected q q0 = mrcal.project(p_reported, *model0.intrinsics()) q1 = mrcal.project(mrcal.transform_point_Rt(mrcal.invert_Rt(Rt01), p_reported), *model1.intrinsics()) testutils.confirm_equal( q0, q0_ref, relative = False, worstcase = True, msg = f'{what} q0', eps = 25.) testutils.confirm_equal( q1, q1_ref, relative = False, worstcase = True, msg = f'{what} q1', eps = 25.) # square camera layout t01 = np.array(( 1., 0.1, -0.2)) R01 = mrcal.R_from_r(np.array((0.001, -0.002, -0.003))) Rt01 = nps.glue(R01, t01, axis=-2) p = np.array((( 300., 20., 2000.), # far away AND center-ish (-310., 18., 2000.), ( 30., 290., 1500.), # far away AND center-ish (-31., 190., 1500.), ( 3000., 200., 2000.), # far away AND off to either side (-3100., 180., 2000.), ( 300., 2900., 1500.), # far away AND off up/down (-310., 1980., 1500.), ( 3000., -200., 20. ), # very close AND off to either side (-3100., 180., 20. ), ( 300., 2900., 15. ), # very close AND off up/down (-310., 1980., 15. ) )) test_geometry(Rt01, p, "square-camera-geometry", check_gradients = True) # Not checking gradients anymore. If the above all pass, the rest will too. # Turning on the checks will slow stuff down and create more console spew. AND # some test may benignly fail because of the too-small or too-large central # difference steps # cameras facing at each other t01 = np.array(( 0, 0, 100.0 )) R01 = mrcal.R_from_r(np.array((0.001, np.pi+0.002, -0.003))) Rt01 = nps.glue(R01, t01, axis=-2) p = np.array((( 3., 2., 20.), # center-ish (-1000., 18., 20.), # off to various sides (1000., 29., 50.), (-31., 1900., 70.), (-11., -2000., 95.), )) test_geometry(Rt01, p, "cameras-facing-each-other", check_gradients = False) p = np.array((( 3., 2., 101.), # center-ish (-11., -2000., -5.), )) test_geometry(Rt01, p, "cameras-facing-each-other out-of-bounds", out_of_bounds = True) # cameras at 90 deg to each other t01 = np.array(( 100.0, 0, 100.0 )) R01 = mrcal.R_from_r(np.array((0.001, -np.pi/2.+0.002, -0.003))) Rt01 = nps.glue(R01, t01, axis=-2) p = np.array((( 30., 5., 40. ), # center-ish ( -2000., 25., 50. ), # way left in one cam, forward in the other ( 80., -10., 2000.), # forward one, right the other ( 75., 5., 4. ), # corner on both )) test_geometry(Rt01, p, "cameras-90deg-to-each-other", check_gradients = False) p = np.array((( 110., 25., 50. ), ( 90., -100., -5.), )) test_geometry(Rt01, p, "cameras-90deg-to-each-other out-of-bounds", out_of_bounds = True ) testutils.finish() mrcal-2.4.1/test/test-uncertainty-broadcasting.py000077500000000000000000000234241456301662300221430ustar00rootroot00000000000000#!/usr/bin/env python3 r'''Triangulation and projection uncertainty broadcasting test The uncertainty routines support broadcasting, which we evaluate here ''' import sys import argparse import re import os def parse_args(): parser = \ argparse.ArgumentParser(description = __doc__, formatter_class=argparse.RawDescriptionHelpFormatter) parser.add_argument('--fixed', type=str, choices=('cam0','frames'), default = 'cam0', help='''Are we putting the origin at camera0, or are all the frames at a fixed (and non-optimizeable) pose? One or the other is required.''') parser.add_argument('--model', type=str, choices=('opencv4','opencv8','splined'), default = 'opencv4', help='''Which lens model we're using. Must be one of ('opencv4','opencv8','splined')''') parser.add_argument('--Nframes', type=int, default=50, help='''How many chessboard poses to simulate. These are dense observations: every camera sees every corner of every chessboard pose''') parser.add_argument('--stabilize-coords', action = 'store_true', help='''Whether we report the triangulation in the camera-0 coordinate system (which is moving due to noise) or in a stabilized coordinate system based on the frame poses''') parser.add_argument('--cull-left-of-center', action = 'store_true', help='''If given, the calibration data in the left half of the imager is thrown out''') parser.add_argument('--q-calibration-stdev', type = float, default = 0.0, help='''The observed pixel uncertainty of the chessboard observations at calibration time. Defaults to 0.0. At least one of --q-calibration-stdev and --q-observation-stdev MUST be given as > 0''') parser.add_argument('--q-observation-stdev', type = float, default = 0.0, help='''The observed pixel uncertainty of the point observations at triangulation time. Defaults to 0.0. At least one of --q-calibration-stdev and --q-observation-stdev MUST be given as > 0''') parser.add_argument('--q-observation-stdev-correlation', type = float, default = 0.0, help='''By default, the noise in the observation-time pixel observations is assumed independent. This isn't entirely realistic: observations of the same feature in multiple cameras originate from an imager correlation operation, so they will have some amount of correlation. If given, this argument specifies how much correlation. This is a value in [0,1] scaling the stdev. 0 means "independent" (the default). 1.0 means "100% correlated".''') parser.add_argument('--baseline', type = float, default = 2., help='''The baseline of the camera pair. This is the horizontal distance between each pair of adjacent cameras''') args = parser.parse_args() if args.q_calibration_stdev <= 0.0 and \ args.q_observation_stdev <= 0.0: raise Exception('At least one of --q-calibration-stdev and --q-observation-stdev MUST be given as > 0') return args args = parse_args() testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils import copy import numpy as np import numpysane as nps from test_calibration_helpers import calibration_baseline Ncameras = 3 Npoints = 5 # shape (Npoints,3) p_triangulated_true0 = np.zeros((Npoints,3), dtype=float) p_triangulated_true0[:,0] = np.arange(Npoints) - 2.77 p_triangulated_true0[:,1] = np.arange(Npoints) / 10. - 0.344 p_triangulated_true0[:,2] = 100. ############# Set up my world, and compute all the perfect positions, pixel ############# observations of everything fixedframes = (args.fixed == 'frames') object_spacing = 0.1 object_width_n = 10 object_height_n = 9 calobject_warp_true = np.array((0.002, -0.005)) # I want the RNG to be deterministic np.random.seed(0) extrinsics_rt_fromref_true = np.zeros((Ncameras,6), dtype=float) extrinsics_rt_fromref_true[:,:3] = np.random.randn(Ncameras,3) * 0.1 extrinsics_rt_fromref_true[:, 3] = args.baseline * np.arange(Ncameras) extrinsics_rt_fromref_true[:,4:] = np.random.randn(Ncameras,2) * 0.1 # cam0 is at the identity. This makes my life easy: I can assume that the # optimization_inputs returned by calibration_baseline() use the same ref # coordinate system as these transformations. I explicitly state this by passing # calibration_baseline(allow_nonidentity_cam0_transform=False) later extrinsics_rt_fromref_true[0] *= 0 optimization_inputs_baseline, \ models_true, models_baseline, \ indices_frame_camintrinsics_camextrinsics, \ lensmodel, Nintrinsics, imagersizes, \ intrinsics_true, extrinsics_true_mounted, frames_true, \ observations_true, \ args.Nframes = \ calibration_baseline(args.model, Ncameras, args.Nframes, None, object_width_n, object_height_n, object_spacing, extrinsics_rt_fromref_true, calobject_warp_true, fixedframes, testdir, cull_left_of_center = args.cull_left_of_center, allow_nonidentity_cam0_transform = False) #################################################################### # I have the calibrated models, and I can compute the triangulations # # I triangulate my 5 points while observed by cameras (2,1) and cameras (1,0) icameras = ( (2,1), (1,0) ) Nmodelpairs = len(icameras) # shape (Nmodelpairs,2) M = [ [models_baseline[i] for i in icameras[0]], [models_baseline[i] for i in icameras[1]] ] # shape (Npoints,Nmodelpairs, 2,2) q = np.zeros((Npoints,Nmodelpairs, 2,2), dtype=float) for ipt in range(Npoints): for imp in range(Nmodelpairs): q[ipt,imp,0,:] = mrcal.project(p_triangulated_true0[ipt], *M[imp][0].intrinsics()) q[ipt,imp,1,:] = mrcal.project(mrcal.transform_point_Rt( mrcal.compose_Rt( M[imp][1].extrinsics_Rt_fromref(), M[imp][0].extrinsics_Rt_toref() ), p_triangulated_true0[ipt]), *M[imp][1].intrinsics()) p, \ Var_p0p1_calibration_big, \ Var_p0p1_observation_big, \ Var_p0p1_joint_big = \ mrcal.triangulate( q, M, q_calibration_stdev = args.q_calibration_stdev, q_observation_stdev = args.q_observation_stdev, q_observation_stdev_correlation = args.q_observation_stdev_correlation, stabilize_coords = args.stabilize_coords ) testutils.confirm_equal(p.shape, (Npoints,Nmodelpairs,3), msg = "point array has the right shape") testutils.confirm_equal(Var_p0p1_calibration_big.shape, (Npoints,Nmodelpairs,3, Npoints,Nmodelpairs,3), msg = "Big covariance (calibration) matrix has the right shape") testutils.confirm_equal(Var_p0p1_observation_big.shape, (Npoints,Nmodelpairs,3,3), msg = "Big covariance (observation) matrix has the right shape") testutils.confirm_equal(Var_p0p1_joint_big.shape, (Npoints,Nmodelpairs,3, Npoints,Nmodelpairs,3), msg = "Big covariance (joint) matrix has the right shape") # Now I check each block in the diagonal individually for ipt in range(Npoints): for imp in range(Nmodelpairs): p, \ _, _, \ Var_p0p1 = \ mrcal.triangulate( q[ipt,imp], M[imp], q_calibration_stdev = args.q_calibration_stdev, q_observation_stdev = args.q_observation_stdev, q_observation_stdev_correlation = args.q_observation_stdev_correlation, stabilize_coords = args.stabilize_coords ) testutils.confirm_equal(Var_p0p1_joint_big[ipt,imp,:,ipt,imp,:], Var_p0p1, msg = f"Covariance (joint) sub-matrix ipt={ipt} imp={imp}") testutils.confirm_equal(Var_p0p1_calibration_big[ipt,imp,:,ipt,imp,:] + Var_p0p1_observation_big[ipt,imp,:,:], Var_p0p1, msg = f"Covariance (cal + obs) sub-matrix ipt={ipt} imp={imp}") testutils.finish() mrcal-2.4.1/test/test-worst_direction_stdev.py000077500000000000000000000032161456301662300215600ustar00rootroot00000000000000#!/usr/bin/env python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 import sys import os import numpy as np import numpysane as nps testdir = os.path.dirname(os.path.realpath(__file__)) # I import the LOCAL mrcal since that's what I'm testing sys.path[:0] = f"{testdir}/..", import mrcal import testutils np.random.seed(0) @nps.broadcast_define( (('N','N',),), () ) def worstdirection_stdev_ref(V): if V.size == 1: return np.sqrt(nps.atleast_dims(V,-1).ravel()[0]) return np.sqrt( np.sort( np.linalg.eigvalsh(V) ) [-1] ) def random_positive_definite(shape): if len(shape) == 0: return np.abs(np.random.random(1)[0]) if len(shape) == 1: if shape[0] != 1: raise Exception("Variance matrices should be square") return np.abs(np.random.random(1)) if shape[-1] != shape[-2]: raise Exception("Variance matrices should be square") N = shape[-1] M = np.random.random(shape) return nps.matmult(nps.transpose(M), M) for shape in ((2,3,5,5), (5,5), (3,2,2), (2,2), (1,1), (1,), ()): V = random_positive_definite(shape) testutils.confirm_equal( mrcal.worst_direction_stdev(V), worstdirection_stdev_ref(V), msg = f"Checking shape {shape}" ) testutils.finish() mrcal-2.4.1/test/test_calibration_helpers.py000066400000000000000000000402431456301662300212260ustar00rootroot00000000000000#!/usr/bin/python3 import sys import numpy as np import numpysane as nps import copy import os import re # I import the LOCAL mrcal since that's what I'm testing testdir = os.path.dirname(os.path.realpath(__file__)) sys.path[:0] = f"{testdir}/..", import mrcal def sample_dqref(observations, pixel_uncertainty_stdev, make_outliers = False): # Outliers have weight < 0. The code will adjust the outlier observations # also. But that shouldn't matter: they're outliers so those observations # should be ignored weight = observations[...,-1] q_noise = np.random.randn(*observations.shape[:-1], 2) * pixel_uncertainty_stdev / nps.mv(nps.cat(weight,weight),0,-1) if make_outliers: if not hasattr(sample_dqref, 'idx_outliers_ref_flat'): NobservedPoints = observations.size // 3 sample_dqref.idx_outliers_ref_flat = \ np.random.choice( NobservedPoints, (NobservedPoints//100,), # 1% outliers replace = False ) nps.clump(q_noise, n=3)[sample_dqref.idx_outliers_ref_flat, :] *= 20 observations_perturbed = observations.copy() observations_perturbed[...,:2] += q_noise return q_noise, observations_perturbed def grad(f, x, step=1e-6): r'''Computes df/dx at x f is a function of one argument. If the input has shape Si and the output has shape So, the returned gradient has shape So+Si. This applies central differences ''' d = np.zeros(x.shape,dtype=float) dflat = d.ravel() def df_dxi(i, d,dflat): dflat[i] = step fplus = f(x+d) fminus = f(x-d) j = (fplus-fminus)/(2.*step) dflat[i] = 0 return j # grad variable is in first dim Jflat = nps.cat(*[df_dxi(i, d,dflat) for i in range(len(dflat))]) # grad variable is in last dim Jflat = nps.mv(Jflat, 0, -1) return Jflat.reshape( Jflat.shape[:-1] + d.shape ) def calibration_baseline(model, Ncameras, Nframes, extra_observation_at, object_width_n, object_height_n, object_spacing, extrinsics_rt_fromref_true, calobject_warp_true, fixedframes, testdir, cull_left_of_center = False, allow_nonidentity_cam0_transform = False, range_to_boards = 4.0): r'''Compute a calibration baseline as a starting point for experiments This is a perfect, noiseless solve. Regularization IS enabled, and the returned model is at the optimization optimum. So the returned models will not sit exactly at the ground-truth. NOTE: if not fixedframes: the ref frame in the returned optimization_inputs_baseline is NOT the ref frame used by the returned extrinsics and frames arrays. The arrays in optimization_inputs_baseline had to be transformed to reference off camera 0. If the extrinsics of camera 0 are the identity, then the two ref coord systems are the same. To avoid accidental bugs, we have a kwarg allow_nonidentity_cam0_transform, which defaults to False. if not allow_nonidentity_cam0_transform and norm(extrinsics_rt_fromref_true[0]) > 0: raise This logic is here purely for safety. A caller that handles non-identity cam0 transforms has to explicitly say that ARGUMENTS - model: string. 'opencv4' or 'opencv8' or 'splined' - ... ''' if re.match('opencv',model): models_true = ( mrcal.cameramodel(f"{testdir}/data/cam0.opencv8.cameramodel"), mrcal.cameramodel(f"{testdir}/data/cam0.opencv8.cameramodel"), mrcal.cameramodel(f"{testdir}/data/cam1.opencv8.cameramodel"), mrcal.cameramodel(f"{testdir}/data/cam1.opencv8.cameramodel") ) if model == 'opencv4': # I have opencv8 models_true, but I truncate to opencv4 models_true for m in models_true: m.intrinsics( intrinsics = ('LENSMODEL_OPENCV4', m.intrinsics()[1][:8])) elif model == 'splined': models_true = ( mrcal.cameramodel(f"{testdir}/data/cam0.splined.cameramodel"), mrcal.cameramodel(f"{testdir}/data/cam0.splined.cameramodel"), mrcal.cameramodel(f"{testdir}/data/cam1.splined.cameramodel"), mrcal.cameramodel(f"{testdir}/data/cam1.splined.cameramodel") ) else: raise Exception("Unknown lens being tested") models_true = models_true[:Ncameras] lensmodel = models_true[0].intrinsics()[0] Nintrinsics = mrcal.lensmodel_num_params(lensmodel) for i in range(Ncameras): models_true[i].extrinsics_rt_fromref(extrinsics_rt_fromref_true[i]) if not allow_nonidentity_cam0_transform and \ nps.norm2(extrinsics_rt_fromref_true[0]) > 0: raise Exception("A non-identity cam0 transform was given, but the caller didn't explicitly say that they support this") imagersizes = nps.cat( *[m.imagersize() for m in models_true] ) # These are perfect intrinsics_true = nps.cat( *[m.intrinsics()[1] for m in models_true] ) extrinsics_true_mounted = nps.cat( *[m.extrinsics_rt_fromref() for m in models_true] ) x_center = -(Ncameras-1)/2. # shapes (Nframes, Ncameras, Nh, Nw, 2), # (Nframes, 4,3) q_true,Rt_ref_board_true = \ mrcal.synthesize_board_observations(models_true, object_width_n = object_width_n, object_height_n = object_height_n, object_spacing = object_spacing, calobject_warp = calobject_warp_true, rt_ref_boardcenter = np.array((0., 0., 0., x_center, 0, range_to_boards)), rt_ref_boardcenter__noiseradius = np.array((np.pi/180.*30., np.pi/180.*30., np.pi/180.*20., 2.5, 2.5, range_to_boards/2.0)), Nframes = Nframes) if extra_observation_at is not None: q_true_extra,Rt_ref_board_true_extra = \ mrcal.synthesize_board_observations(models_true, object_width_n = object_width_n, object_height_n = object_height_n, object_spacing = object_spacing, calobject_warp = calobject_warp_true, rt_ref_boardcenter = np.array((0., 0., 0., x_center, 0, extra_observation_at)), rt_ref_boardcenter__noiseradius = np.array((np.pi/180.*30., np.pi/180.*30., np.pi/180.*20., 2.5, 2.5, extra_observation_at/10.0)), Nframes = Nframes) q_true = nps.glue( q_true, q_true_extra, axis=-5) Rt_ref_board_true = nps.glue( Rt_ref_board_true, Rt_ref_board_true_extra, axis=-3) Nframes += 1 frames_true = mrcal.rt_from_Rt(Rt_ref_board_true) ############# I have perfect observations in q_true. # weight has shape (Nframes, Ncameras, Nh, Nw), weight01 = (np.random.rand(*q_true.shape[:-1]) + 1.) / 2. # in [0,1] weight0 = 0.2 weight1 = 1.0 weight = weight0 + (weight1-weight0)*weight01 if cull_left_of_center: imagersize = models_true[0].imagersize() for m in models_true[1:]: if np.any(m.imagersize() - imagersize): raise Exception("I'm assuming all cameras have the same imager size, but this is false") weight[q_true[...,0] < imagersize[0]/2.] /= 1000. # I want observations of shape (Nframes*Ncameras, Nh, Nw, 3) where each row is # (x,y,weight) observations_true = nps.clump( nps.glue(q_true, nps.dummy(weight,-1), axis=-1), n=2) # Dense observations. All the cameras see all the boards indices_frame_camera = np.zeros( (Nframes*Ncameras, 2), dtype=np.int32) indices_frame = indices_frame_camera[:,0].reshape(Nframes,Ncameras) indices_frame.setfield(nps.outer(np.arange(Nframes, dtype=np.int32), np.ones((Ncameras,), dtype=np.int32)), dtype = np.int32) indices_camera = indices_frame_camera[:,1].reshape(Nframes,Ncameras) indices_camera.setfield(nps.outer(np.ones((Nframes,), dtype=np.int32), np.arange(Ncameras, dtype=np.int32)), dtype = np.int32) indices_frame_camintrinsics_camextrinsics = \ nps.glue(indices_frame_camera, indices_frame_camera[:,(1,)], axis=-1) if not fixedframes: indices_frame_camintrinsics_camextrinsics[:,2] -= 1 ########################################################################### # p = mrcal.show_geometry(models_true, # frames = frames_true, # object_width_n = object_width_n, # object_height_n = object_height_n, # object_spacing = object_spacing) # sys.exit() # I now reoptimize the perfect-observations problem. Without regularization, # this is a no-op: I'm already at the optimum. With regularization, this will # move us a certain amount (that the test will evaluate). Then I look at # noise-induced motions off this optimization optimum optimization_inputs_baseline = \ dict( intrinsics = copy.deepcopy(intrinsics_true), points = None, observations_board = observations_true, indices_frame_camintrinsics_camextrinsics = indices_frame_camintrinsics_camextrinsics, observations_point = None, indices_point_camintrinsics_camextrinsics = None, lensmodel = lensmodel, calobject_warp = copy.deepcopy(calobject_warp_true), imagersizes = imagersizes, calibration_object_spacing = object_spacing, verbose = False, do_optimize_frames = not fixedframes, do_optimize_intrinsics_core = False if model =='splined' else True, do_optimize_intrinsics_distortions = True, do_optimize_extrinsics = True, do_optimize_calobject_warp = True, do_apply_regularization = True, do_apply_outlier_rejection = False) if fixedframes: # Frames are fixed: each camera has an independent pose optimization_inputs_baseline['extrinsics_rt_fromref'] = \ copy.deepcopy(extrinsics_true_mounted) optimization_inputs_baseline['frames_rt_toref'] = copy.deepcopy(frames_true) else: # Frames are NOT fixed: cam0 is fixed as the reference coord system. I # transform each optimization extrinsics vector to be relative to cam0 optimization_inputs_baseline['extrinsics_rt_fromref'] = \ mrcal.compose_rt(extrinsics_true_mounted[1:,:], mrcal.invert_rt(extrinsics_true_mounted[0,:])) optimization_inputs_baseline['frames_rt_toref'] = \ mrcal.compose_rt(extrinsics_true_mounted[0,:], frames_true) mrcal.optimize(**optimization_inputs_baseline) models_baseline = \ [ mrcal.cameramodel( optimization_inputs = optimization_inputs_baseline, icam_intrinsics = i) \ for i in range(Ncameras) ] return \ optimization_inputs_baseline, \ models_true, models_baseline, \ indices_frame_camintrinsics_camextrinsics, \ lensmodel, Nintrinsics, imagersizes, \ intrinsics_true, extrinsics_true_mounted, frames_true, \ observations_true, \ Nframes def calibration_sample(Nsamples, optimization_inputs_baseline, pixel_uncertainty_stdev, fixedframes, function_optimize = None): r'''Sample calibrations subject to random noise on the input observations optimization_inputs_baseline['observations_board'] and optimization_inputs_baseline['observations_point'] are assumed to contain perfect observations ''' def have(k): return k in optimization_inputs_baseline and \ optimization_inputs_baseline[k] is not None intrinsics_sampled = np.zeros((Nsamples,) + optimization_inputs_baseline['intrinsics'] .shape, dtype=float) if have('frames_rt_toref'): frames_sampled = np.zeros((Nsamples,) + optimization_inputs_baseline['frames_rt_toref'].shape, dtype=float) else: frames_sampled = None if have('points'): points_sampled = np.zeros((Nsamples,) + optimization_inputs_baseline['points'].shape, dtype=float) else: points_sampled = None if have('calobject_warp'): calobject_warp_sampled = np.zeros((Nsamples,) + optimization_inputs_baseline['calobject_warp'].shape, dtype=float) else: calobject_warp_sampled = None optimization_inputs_sampled = [None] * Nsamples Ncameras_extrinsics = optimization_inputs_baseline['extrinsics_rt_fromref'].shape[0] if not fixedframes: # the first row is fixed at 0 Ncameras_extrinsics += 1 extrinsics_sampled_mounted = np.zeros((Nsamples,Ncameras_extrinsics,6), dtype=float) for isample in range(Nsamples): if (isample+1) % 20 == 0: print(f"Sampling {isample+1}/{Nsamples}") optimization_inputs_sampled[isample] = copy.deepcopy(optimization_inputs_baseline) optimization_inputs = optimization_inputs_sampled[isample] if have('observations_board'): optimization_inputs['observations_board'] = \ sample_dqref(optimization_inputs['observations_board'], pixel_uncertainty_stdev)[1] if have('observations_point'): optimization_inputs['observations_point'] = \ sample_dqref(optimization_inputs['observations_point'], pixel_uncertainty_stdev)[1] if function_optimize is None: mrcal.optimize(**optimization_inputs) else: function_optimize(optimization_inputs) intrinsics_sampled [isample,...] = optimization_inputs['intrinsics'] if fixedframes: extrinsics_sampled_mounted[isample, ...] = optimization_inputs['extrinsics_rt_fromref'] else: # the remaining row is already 0 extrinsics_sampled_mounted[isample,1:,...] = optimization_inputs['extrinsics_rt_fromref'] if frames_sampled is not None: frames_sampled[isample,...] = optimization_inputs['frames_rt_toref'] if points_sampled is not None: points_sampled[isample,...] = optimization_inputs['points'] if calobject_warp_sampled is not None: calobject_warp_sampled[isample,...] = optimization_inputs['calobject_warp'] return \ ( intrinsics_sampled, extrinsics_sampled_mounted, frames_sampled, points_sampled, calobject_warp_sampled, optimization_inputs_sampled) mrcal-2.4.1/test/testutils.py000066400000000000000000000244711456301662300162230ustar00rootroot00000000000000#!/usr/bin/python3 import sys import numpy as np import numpysane as nps import os import re from inspect import currentframe import mrcal Nchecks = 0 NchecksFailed = 0 # no line breaks. Useful for test reporting. Yes, this sets global state, but # we're running a test harness. This is fine np.set_printoptions(linewidth=1e10, suppress=True) def percentile_compat(*args, **kwargs): r'''Wrapper for np.percentile() to handle their API change In numpy 1.24 the "interpolation" kwarg was renamed to "method". I need to pass the right thing to work with both old and new numpy. This function tries the newer method, and if that fails, uses the old one. The test is only done the first time. It is assumed that this is called with the old 'interpolation' key. ''' if not 'interpolation' in kwargs or \ percentile_compat.which == 'interpolation': return np.percentile(*args, **kwargs) kwargs_no_interpolation = dict(kwargs) del kwargs_no_interpolation['interpolation'] if percentile_compat.which == 'method': return np.percentile(*args, **kwargs_no_interpolation, method = kwargs['interpolation']) # Need to detect try: result = np.percentile(*args, **kwargs_no_interpolation, method = kwargs['interpolation']) percentile_compat.which = 'method' return result except: percentile_compat.which = 'interpolation' return np.percentile(*args, **kwargs) percentile_compat.which = None def test_location(): r'''Reports string describing current location in the test''' filename_this = os.path.split( __file__ )[1] frame = currentframe().f_back.f_back # I keep popping the stack until I leave the testutils file and I'm not in a # function called "check" while frame: if frame.f_back is None or \ (not frame.f_code.co_filename.endswith(filename_this) and frame.f_code.co_name != "check" ): break frame = frame.f_back testfile = os.path.split(frame.f_code.co_filename)[1] try: return "{}:{}".format(testfile, frame.f_lineno) except: return '' def print_red(x): """print the message in red""" sys.stdout.write("\x1b[31m" + test_location() + ": " + x + "\x1b[0m\n") def print_green(x): """Print the message in green""" sys.stdout.write("\x1b[32m" + test_location() + ": " + x + "\x1b[0m\n") def print_blue(x): """Print the message in blue""" sys.stdout.write("\x1b[34m" + test_location() + ": " + x + "\x1b[0m\n") def relative_scale(a,b, eps = 1e-6): return (np.abs(a) + np.abs(b)) / 2 + eps def relative_diff(a,b, eps = 1e-6): return (a - b) / relative_scale(a,b, eps) def confirm_equal(x, xref, *, msg='', eps=1e-6, reldiff_eps = 1e-6, relative=False, worstcase=False, percentile=None): r'''If x is equal to xref, report test success. msg identifies this check. eps sets the RMS equality tolerance. The x,xref arguments can be given as many different types. This function tries to do the right thing. if relative: I look at a relative error: err = (a-b) / ((abs(a)+abs(b))/2 + eps) else: I look at absolute error: err = a-b if worstcase: I look at the worst-case error error = np.max(np.abs(err)) elif percentile is not None: I look at the given point in the error distribution error = percentile_compat(np.abs(err), percentile) else: RMS error error = np.sqrt(nps.norm2(err) / len(err)) ''' global Nchecks global NchecksFailed Nchecks = Nchecks + 1 # strip all trailing whitespace in each line, in case these are strings if isinstance(x, str): x = re.sub('[ \t]+(\n|$)', '\\1', x) if isinstance(xref, str): xref = re.sub('[ \t]+(\n|$)', '\\1', xref) # convert data to numpy if possible try: xref = np.array(xref) except: pass try: x = np.array(x) except: pass try: # flatten array if possible x = x.ravel() xref = xref.ravel() except: pass try: N = x.shape[0] except: N = 1 try: Nref = xref.shape[0] except: Nref = 1 if N != Nref: # Comparing an array to a scalar reference is allowed if Nref == 1: xref = np.ones((N,), dtype=float) * xref Nref = N else: print_red(("FAILED{}: mismatched array sizes: N = {} but Nref = {}. Arrays: \n" + "x = {}\n" + "xref = {}"). format((': ' + msg) if msg else '', N, Nref, x, xref)) NchecksFailed = NchecksFailed + 1 return False if N != 0: try: # I I can subtract, get the error that way if relative: diff = relative_diff(x, xref, eps = reldiff_eps) else: diff = x - xref if worstcase: what = 'worst-case' err = np.max(np.abs(diff)) elif percentile is not None: what = f'{percentile}%-percentile' err = percentile_compat(np.abs(diff), percentile, interpolation='higher') else: what = 'RMS' err = np.sqrt(nps.norm2(diff) / len(diff)) if not np.all(np.isfinite(err)): print_red(f"FAILED{(': ' + msg) if msg else ''}: Some comparison results are NaN or Inf. {what}. error_x_xref =\n{nps.cat(err,x,xref)}") NchecksFailed = NchecksFailed + 1 return False if err > eps: print_red(f"FAILED{(': ' + msg) if msg else ''}: {what} error = {err}. x_xref_err =\n{nps.cat(x,xref,diff)}") NchecksFailed = NchecksFailed + 1 return False except: # Can't subtract. Do == instead if not np.array_equal(x, xref): print_red(f"FAILED{(': ' + msg) if msg else ''}: x_xref =\n{nps.cat(x,xref)}") NchecksFailed = NchecksFailed + 1 return False print_green("OK" + (': ' + msg) if msg else '') return True def confirm(x, msg=''): r'''If x is true, report test success. msg identifies this check''' global Nchecks global NchecksFailed Nchecks = Nchecks + 1 if not x: print_red("FAILED{}".format((': ' + msg) if msg else '')) NchecksFailed = NchecksFailed + 1 return False print_green("OK{}".format((': ' + msg) if msg else '')) return True def confirm_raises(f, msg=''): r'''If f() raises an exception, report test success. msg identifies this check''' global Nchecks global NchecksFailed Nchecks = Nchecks + 1 try: f() print_red("FAILED{}".format((': ' + msg) if msg else '')) NchecksFailed = NchecksFailed + 1 return False except: print_green("OK{}".format((': ' + msg) if msg else '')) return True def confirm_does_not_raise(f, msg=''): r'''If f() raises an exception, report test failure. msg identifies this check''' global Nchecks global NchecksFailed Nchecks = Nchecks + 1 try: f() print_green("OK{}".format((': ' + msg) if msg else '')) return True except: print_red("FAILED{}".format((': ' + msg) if msg else '')) NchecksFailed = NchecksFailed + 1 return False def confirm_covariances_equal(var, var_ref, *, what, # scalar float to use for all the eigenvalues, of # a list of length 3, to use in order from largest # to smallest. None to skip that axis eps_eigenvalues, eps_eigenvectors_deg, check_biggest_eigenvalue_only = False): # First, the thing is symmetric, right? confirm_equal(nps.transpose(var), var, worstcase = True, msg = f"Var(dq) is symmetric for {what}") l_predicted,v_predicted = mrcal.sorted_eig(var) l_observed,v_observed = mrcal.sorted_eig(var_ref) eccentricity_predicted = l_predicted[-1] / l_predicted[-2] for i in range(var.shape[-1]): # check all the eigenvalues, in order from largest to smallest if isinstance(eps_eigenvalues, float): eps = eps_eigenvalues else: eps = eps_eigenvalues[i] if eps is None: continue confirm_equal(l_observed[-1-i], l_predicted[-1-i], eps = eps, worstcase = True, relative = True, msg = f"Var(dq) worst[{i}] eigenvalue match for {what}") if check_biggest_eigenvalue_only: break # I only check the eigenvector directions if the ellipse is sufficiently # non-circular. A circular ellipse has poorly-defined eigenvector directions if eccentricity_predicted > 2.: # I look at the direction of the largest ellipse axis only v0_predicted = v_predicted[:,-1] v0_observed = v_observed [:,-1] confirm_equal(np.arcsin(nps.mag(np.cross(v0_observed,v0_predicted))) * 180./np.pi, 0, eps = eps_eigenvectors_deg, worstcase = True, msg = f"Var(dq) eigenvectors match for {what}") # I don't bother checking v1. I already made sure the matrix is # symmetric. Thus the eigenvectors are orthogonal, so any angle offset # in v0 will be exactly the same in v1 def finish(): r'''Finalize the executed tests. Prints the test summary. Exits successfully iff all the tests passed. ''' if not Nchecks and not NchecksFailed: print_red("No tests defined") sys.exit(0) if NchecksFailed: print_red("Some tests failed: {} out of {}".format(NchecksFailed, Nchecks)) sys.exit(1) print_green("All tests passed: {} total".format(Nchecks)) sys.exit(0) mrcal-2.4.1/triangulation-genpywrap.py000066400000000000000000000175431456301662300201000ustar00rootroot00000000000000#!/usr/bin/python3 # Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. # Government sponsorship acknowledged. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 r'''Python-wrap the triangulation routines ''' import sys import os import numpy as np import numpysane as nps import numpysane_pywrap as npsp docstring_module = '''Internal triangulation routines This is the written-in-C Python extension module that underlies the triangulation routines. The user-facing functions are available in mrcal.triangulation module in mrcal/triangulation.py All functions are exported into the mrcal module. So you can call these via mrcal._triangulation_npsp.fff() or mrcal.fff(). The latter is preferred. ''' m = npsp.module( name = "_triangulation_npsp", docstring = docstring_module, header = r''' #include "mrcal.h" ''') # All the triangulation routines except Lindstrom have an identical structure. # Lindstrom is slightly different: it takes LOCAL v1 instead of a cam0-coords v1 NAME = "_triangulate_{WHAT}" DOCS = r"""Internal {LONGNAME} triangulation routine This is the internals for mrcal.triangulate_{WHAT}(get_gradients = False). As a user, please call THAT function, and see the docs for that function. The differences: - This is just the no-gradients function. The internal function that returns gradients is _triangulate_{WHAT}_withgrad A higher-level function mrcal.triangulate() is also available for higher-level analysis. """ DOCS_WITHGRAD = r"""Internal {LONGNAME} triangulation routine (with gradients) This is the internals for mrcal.triangulate_{WHAT}(get_gradients = True). As a user, please call THAT function, and see the docs for that function. The differences: - This is just the gradients-returning function. The internal function that skips those is _triangulate_{WHAT} A higher-level function mrcal.triangulate() is also available for higher-level analysis. """ BODY_SLICE = r''' const mrcal_point3_t* v0 = (const mrcal_point3_t*)data_slice__v0; const mrcal_point3_t* v1 = (const mrcal_point3_t*)data_slice__v1; const mrcal_point3_t* t01 = (const mrcal_point3_t*)data_slice__t01; *(mrcal_point3_t*)data_slice__output = mrcal_triangulate_{WHAT}(NULL, NULL, NULL, v0, v1, t01); return true; ''' BODY_SLICE_WITHGRAD = r''' const mrcal_point3_t* v0 = (const mrcal_point3_t*)data_slice__v0; const mrcal_point3_t* v1 = (const mrcal_point3_t*)data_slice__v1; const mrcal_point3_t* t01 = (const mrcal_point3_t*)data_slice__t01; mrcal_point3_t* dm_dv0 = (mrcal_point3_t*)data_slice__output1; mrcal_point3_t* dm_dv1 = (mrcal_point3_t*)data_slice__output2; mrcal_point3_t* dm_dt01 = (mrcal_point3_t*)data_slice__output3; *(mrcal_point3_t*)data_slice__output0 = mrcal_triangulate_{WHAT}( dm_dv0, dm_dv1, dm_dt01, v0, v1, t01); return true; ''' common_kwargs = dict( args_input = ('v0', 'v1', 't01'), prototype_input = ((3,), (3,), (3,)), prototype_output = (3,), Ccode_validate = r''' return CHECK_CONTIGUOUS_AND_SETERROR_ALL();''' ) common_kwargs_withgrad = dict( args_input = ('v0', 'v1', 't01'), prototype_input = ((3,), (3,), (3,)), prototype_output = ((3,), (3,3), (3,3), (3,3)), Ccode_validate = r''' return CHECK_CONTIGUOUS_AND_SETERROR_ALL();''') for WHAT,LONGNAME in (('geometric', 'geometric'), ('leecivera_l1', 'Lee-Civera L1'), ('leecivera_linf', 'Lee-Civera L-infinity'), ('leecivera_mid2', 'Lee-Civera Mid2'), ('leecivera_wmid2', 'Lee-Civera wMid2')): m.function( NAME.format(WHAT = WHAT), DOCS.format(WHAT = WHAT, LONGNAME = LONGNAME), Ccode_slice_eval = { (np.float64,np.float64,np.float64, np.float64): BODY_SLICE.format(WHAT = WHAT) }, **common_kwargs ) m.function( NAME.format( WHAT = WHAT) + "_withgrad", DOCS_WITHGRAD.format(WHAT = WHAT, LONGNAME = LONGNAME), Ccode_slice_eval = { (np.float64,np.float64,np.float64, np.float64,np.float64,np.float64,np.float64): BODY_SLICE_WITHGRAD.format(WHAT = WHAT) }, **common_kwargs_withgrad ) # Lindstrom's triangulation. Takes a local v1, so the arguments are a bit # different m.function( "_triangulate_lindstrom", f"""Internal lindstrom's triangulation routine This is the internals for mrcal.triangulate_lindstrom(). As a user, please call THAT function, and see the docs for that function. The differences: - This is just the no-gradients function. The internal function that returns gradients is _triangulate_lindstrom_withgrad """, args_input = ('v0_local', 'v1_local', 'Rt01'), prototype_input = ((3,), (3,), (4,3),), prototype_output = ((3,) ), Ccode_validate = r''' return CHECK_CONTIGUOUS_AND_SETERROR_ALL();''', Ccode_slice_eval = { (np.float64,np.float64,np.float64, np.float64): r''' const mrcal_point3_t* v0 = (const mrcal_point3_t*)data_slice__v0_local; const mrcal_point3_t* v1 = (const mrcal_point3_t*)data_slice__v1_local; const mrcal_point3_t* Rt01= (const mrcal_point3_t*)data_slice__Rt01; *(mrcal_point3_t*)data_slice__output = mrcal_triangulate_lindstrom(NULL,NULL,NULL, v0, v1, Rt01); return true; '''}, ) m.function( "_triangulate_lindstrom_withgrad", f"""Internal lindstrom's triangulation routine This is the internals for mrcal.triangulate_lindstrom(). As a user, please call THAT function, and see the docs for that function. The differences: - This is just the gradient-returning function. The internal function that skips those is _triangulate_lindstrom """, args_input = ('v0_local', 'v1_local', 'Rt01'), prototype_input = ((3,), (3,), (4,3),), prototype_output = ((3,), (3,3), (3,3), (3,4,3) ), Ccode_validate = r''' return CHECK_CONTIGUOUS_AND_SETERROR_ALL();''', Ccode_slice_eval = { (np.float64,np.float64,np.float64, np.float64,np.float64,np.float64,np.float64): r''' const mrcal_point3_t* v0 = (const mrcal_point3_t*)data_slice__v0_local; const mrcal_point3_t* v1 = (const mrcal_point3_t*)data_slice__v1_local; const mrcal_point3_t* Rt01= (const mrcal_point3_t*)data_slice__Rt01; mrcal_point3_t* dm_dv0 = (mrcal_point3_t*)data_slice__output1; mrcal_point3_t* dm_dv1 = (mrcal_point3_t*)data_slice__output2; mrcal_point3_t* dm_dRt01= (mrcal_point3_t*)data_slice__output3; *(mrcal_point3_t*)data_slice__output0 = mrcal_triangulate_lindstrom(dm_dv0, dm_dv1, dm_dRt01, v0, v1, Rt01); return true; ''' }, ) m.write() mrcal-2.4.1/triangulation.cc000066400000000000000000000612621456301662300160200ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #include "autodiff.hh" extern "C" { #include "triangulation.h" } template static bool triangulate_assume_intersect( // output vec_withgrad_t& m, // inputs. camera-0 coordinates const vec_withgrad_t& v0, const vec_withgrad_t& v1, const vec_withgrad_t& t01) { // I take two 3D rays that are assumed to intersect, and return the // intersection point. Results are undefined if these rays actually // don't intersect // Each pixel observation represents a ray in 3D: // // k0 v0 = t01 + k1 v1 // // t01 = [v0 -v1] k // // This is over-determined: k has 2DOF, but I have 3 equations. I know that // the vectors intersect, so I can use 2 axes only, which makes the problem // uniquely determined. Let's pick the 2 axes to use. The "forward" // direction (z) is dominant, so let's use that. For the second axis, let's // use whichever is best numerically: biggest abs(det), so that I divide by // something as far away from 0 as possible. I have // double fabs_det_xz = fabs(-v0.v[0].x*v1.v[2].x + v0.v[2].x*v1.v[0].x); double fabs_det_yz = fabs(-v0.v[1].x*v1.v[2].x + v0.v[2].x*v1.v[1].x); // If using xz, I have: // // k = 1/(-v0[0]*v1[2] + v0[2]*v1[0]) * [-v1[2] v1[0] ] t01 // [-v0[2] v0[0] ] // [0] -> [1] if using yz val_withgrad_t k0; if(fabs_det_xz > fabs_det_yz) { // xz if(fabs_det_xz <= 1e-10) return false; val_withgrad_t det = v1.v[0]*v0.v[2] - v0.v[0]*v1.v[2]; k0 = (t01.v[2]*v1.v[0] - t01.v[0]*v1.v[2]) / det; if(k0.x <= 0.0) return false; bool k1_negative = (t01.v[2].x*v0.v[0].x > t01.v[0].x*v0.v[2].x) ^ (det.x > 0); if(k1_negative) return false; #if 0 val_withgrad_t k1 = (t01.v[2]*v0.v[0] - t01.v[0]*v0.v[2]) / det; vec_withgrad_t m2 = v1*k1 + t01; m2 -= m; double d2 = m2.v[0].x*m2.v[0].x + m2.v[1].x*m2.v[1].x + m2.v[2].x*m2.v[2].x; fprintf(stderr, "diff: %f\n", d2); #endif } else { // yz if(fabs_det_yz <= 1e-10) return false; val_withgrad_t det = v1.v[1]*v0.v[2] - v0.v[1]*v1.v[2]; k0 = (t01.v[2]*v1.v[1] - t01.v[1]*v1.v[2]) / det; if(k0.x <= 0.0) return false; bool k1_negative = (t01.v[2].x*v0.v[1].x > t01.v[1].x*v0.v[2].x) ^ (det.x > 0); if(k1_negative) return false; #if 0 val_withgrad_t k1 = (t01.v[2]*v0.v[1] - t01.v[1]*v0.v[2]) / det; vec_withgrad_t m2 = v1*k1 + t01; m2 -= m; double d2 = m2.v[1].x*m2.v[1].x + m2.v[1].x*m2.v[1].x + m2.v[2].x*m2.v[2].x; fprintf(stderr, "diff: %f\n", d2); #endif } m = v0 * k0; return true; } // Basic closest-approach-in-3D routine extern "C" mrcal_point3_t mrcal_triangulate_geometric(// outputs // These all may be NULL mrcal_point3_t* _dm_dv0, mrcal_point3_t* _dm_dv1, mrcal_point3_t* _dm_dt01, // inputs // not-necessarily normalized vectors in the camera-0 // coord system const mrcal_point3_t* _v0, const mrcal_point3_t* _v1, const mrcal_point3_t* _t01) { // This is the basic 3D-geometry routine. I find the point in 3D that // minimizes the distance to each of the observation rays. This is simple, // but not as accurate as we'd like. All the other methods have lower // biases. See the Lee-Civera papers for details: // // Paper that compares all methods implemented here: // "Triangulation: Why Optimize?", Seong Hun Lee and Javier Civera. // https://arxiv.org/abs/1907.11917 // // Earlier paper that doesn't have mid2 or wmid2: // "Closed-Form Optimal Two-View Triangulation Based on Angular Errors", // Seong Hun Lee and Javier Civera. ICCV 2019. // // Each pixel observation represents a ray in 3D. The best // estimate of the 3d position of the point being observed // is the point nearest to both these rays // // Let's say I have a ray from the origin to v0, and another ray from t01 // to v1 (v0 and v1 aren't necessarily normal). Let the nearest points on // each ray be k0 and k1 along each ray respectively: E = norm2(t01 + k1*v1 // - k0*v0): // // dE/dk0 = 0 = inner(t01 + k1*v1 - k0*v0, -v0) // dE/dk1 = 0 = inner(t01 + k1*v1 - k0*v0, v1) // // -> t01.v0 + k1 v0.v1 = k0 v0.v0 // -t01.v1 + k0 v0.v1 = k1 v1.v1 // // -> [ v0.v0 -v0.v1] [k0] = [ t01.v0] // [ -v0.v1 v1.v1] [k1] = [-t01.v1] // // -> [k0] = 1/(v0.v0 v1.v1 -(v0.v1)**2) [ v1.v1 v0.v1][ t01.v0] // [k1] [ v0.v1 v0.v0][-t01.v1] // // I return the midpoint: // // x = (k0 v0 + t01 + k1 v1)/2 vec_withgrad_t<9,3> v0 (_v0 ->xyz, 0); vec_withgrad_t<9,3> v1 (_v1 ->xyz, 3); vec_withgrad_t<9,3> t01(_t01->xyz, 6); val_withgrad_t<9> dot_v0v0 = v0.norm2(); val_withgrad_t<9> dot_v1v1 = v1.norm2(); val_withgrad_t<9> dot_v0v1 = v0.dot(v1); val_withgrad_t<9> dot_v0t = v0.dot(t01); val_withgrad_t<9> dot_v1t = v1.dot(t01); val_withgrad_t<9> denom = dot_v0v0*dot_v1v1 - dot_v0v1*dot_v0v1; if(-1e-10 <= denom.x && denom.x <= 1e-10) return (mrcal_point3_t){0}; val_withgrad_t<9> denom_recip = val_withgrad_t<9>(1.)/denom; val_withgrad_t<9> k0 = denom_recip * (dot_v1v1*dot_v0t - dot_v0v1*dot_v1t); if(k0.x <= 0.0) return (mrcal_point3_t){0}; val_withgrad_t<9> k1 = denom_recip * (dot_v0v1*dot_v0t - dot_v0v0*dot_v1t); if(k1.x <= 0.0) return (mrcal_point3_t){0}; vec_withgrad_t<9,3> m = (v0*k0 + v1*k1 + t01) * 0.5; mrcal_point3_t _m; m.extract_value(_m.xyz); if(_dm_dv0 != NULL) m.extract_grad (_dm_dv0->xyz, 0,3, 0, 3*sizeof(double), sizeof(double), 3); if(_dm_dv1 != NULL) m.extract_grad (_dm_dv1->xyz, 3,3, 0, 3*sizeof(double), sizeof(double), 3); if(_dm_dt01 != NULL) m.extract_grad (_dm_dt01->xyz, 6,3, 0, 3*sizeof(double), sizeof(double), 3); #if 0 MSG("intersecting..."); MSG("v0 = (%.20f,%.20f,%.20f)", v0[0].x,v0[1].x,v0[2].x); MSG("t01 = (%.20f,%.20f,%.20f)", t01[0].x,t01[1].x,t01[2].x); MSG("v1 = (%.20f,%.20f,%.20f)", v1[0].x,v1[1].x,v1[2].x); MSG("intersection = (%.20f,%.20f,%.20f) dist %f", m.v[0].x,m.v[1].x,m.v[2].x, sqrt( m.dot(m).x)); #endif return _m; } // Minimize L2 pinhole reprojection error. Described in "Triangulation Made // Easy", Peter Lindstrom, IEEE Conference on Computer Vision and Pattern // Recognition, 2010. extern "C" mrcal_point3_t mrcal_triangulate_lindstrom(// outputs // These all may be NULL mrcal_point3_t* _dm_dv0, mrcal_point3_t* _dm_dv1, mrcal_point3_t* _dm_dRt01, // inputs // not-necessarily normalized vectors in the LOCAL // coordinate system. This is different from the other // triangulation routines const mrcal_point3_t* _v0_local, const mrcal_point3_t* _v1_local, const mrcal_point3_t* _Rt01) { // This is an implementation of the algorithm described in "Triangulation // Made Easy", Peter Lindstrom, IEEE Conference on Computer Vision and // Pattern Recognition, 2010. A copy of this paper is available in this repo // in docs/TriangulationLindstrom.pdf. The implementation here is the niter2 // routine in Listing 3. There's a higher-level implemented-in-python test // in analyses/triangulation.py // // A simpler, but less-accurate way of doing is lives in // triangulate_direct() // I'm looking at wikipedia for the Essential matrix definition: // // https://en.wikipedia.org/wiki/Essential_matrix // // and at Lindstrom's paper. Note that THEY HAVE DIFFERENT DEFINITIONS OF E // // I stick to Lindstrom's convention here. He has (section 2, equation 3) // // E = cross(t) R // transpose(x0) E x1 = 0 // // What are R and t? // // x0' cross(t) R x1 = 0 // x0' cross(t) R (R10 x0 + t10) = 0 // // So Lindstrom has R = R01 -> // // x0' cross(t) R01 (R10 x0 + t10) = 0 // x0' cross(t) (x0 + R01 t10) = 0 // x0' cross(t) R01 t10 = 0 // // This holds if Lindstrom has R01 t10 = +- t // // Note that if x1 = R10 x0 + t10 then x0 = R01 x1 - R01 t10 // // So I let t = t01 // // Thus he's multiplying cross(t01) and R01: // // E = cross(t01) R01 // = cross(t01) R10' // cross(t01) = np.array(((0, -t01[2], t01[1]), // ( t01[2], 0, -t01[0]), // (-t01[1], t01[0], 0))); vec_withgrad_t<18,3> v0 (_v0_local->xyz, 0); vec_withgrad_t<18,3> v1 (_v1_local->xyz, 3); vec_withgrad_t<18,9> R01(_Rt01 ->xyz, 6); vec_withgrad_t<18,3> t01(_Rt01[3] .xyz, 15); val_withgrad_t<18> E[9] = { R01[6]*t01[1] - R01[3]*t01[2], R01[7]*t01[1] - R01[4]*t01[2], R01[8]*t01[1] - R01[5]*t01[2], R01[0]*t01[2] - R01[6]*t01[0], R01[1]*t01[2] - R01[7]*t01[0], R01[2]*t01[2] - R01[8]*t01[0], R01[3]*t01[0] - R01[0]*t01[1], R01[4]*t01[0] - R01[1]*t01[1], R01[5]*t01[0] - R01[2]*t01[1] }; // Paper says to rescale x0,x1 such that their last element is 1.0. // I don't even store it val_withgrad_t<18> x0[2] = { v0[0]/v0[2], v0[1]/v0[2] }; val_withgrad_t<18> x1[2] = { v1[0]/v1[2], v1[1]/v1[2] }; // for debugging #if 0 { fprintf(stderr, "E:\n"); for(int i=0; i<3; i++) fprintf(stderr, "%f %f %f\n", E[0 + 3*i].x, E[1 + 3*i].x, E[2 + 3*i].x); double Ex1[3] = { E[0].x*x1[0].x + E[1].x*x1[1].x + E[2].x, E[3].x*x1[0].x + E[4].x*x1[1].x + E[5].x, E[6].x*x1[0].x + E[7].x*x1[1].x + E[8].x }; double x0Ex1 = Ex1[0]*x0[0].x + Ex1[1]*x0[1].x + Ex1[2]; fprintf(stderr, "conj before: %f\n", x0Ex1); } #endif // Now I implement the algorithm. x0 here is x in the paper; x1 here // is x' in the paper // Step 1. n = nps.matmult(x1, nps.transpose(E))[:2] val_withgrad_t<18> n[2]; n[0] = E[0]*x1[0] + E[1]*x1[1] + E[2]; n[1] = E[3]*x1[0] + E[4]*x1[1] + E[5]; // Step 2. nn = nps.matmult(x0, E)[:2] val_withgrad_t<18> nn[2]; nn[0] = E[0]*x0[0] + E[3]*x0[1] + E[6]; nn[1] = E[1]*x0[0] + E[4]*x0[1] + E[7]; // Step 3. a = nps.matmult( n, E[:2,:2], nps.transpose(nn) ).ravel() val_withgrad_t<18> a = n[0]*E[0]*nn[0] + n[0]*E[1]*nn[1] + n[1]*E[3]*nn[0] + n[1]*E[4]*nn[1]; // Step 4. b = 0.5*( nps.inner(n,n) + nps.inner(nn,nn) ) val_withgrad_t<18> b = (n [0]*n [0] + n [1]*n [1] + nn[0]*nn[0] + nn[1]*nn[1]) * 0.5; // Step 5. c = nps.matmult(x0, E, nps.transpose(x1)).ravel() val_withgrad_t<18> n_2 = E[6]*x1[0] + E[7]*x1[1] + E[8]; val_withgrad_t<18> c = n[0]*x0[0] + n[1]*x0[1] + n_2; // Step 6. d = np.sqrt( b*b - a*c ) val_withgrad_t<18> d = (b*b - a*c).sqrt(); // Step 7. l = c / (b+d) val_withgrad_t<18> l = c / (b + d); // Step 8. dx = l*n val_withgrad_t<18> dx[2] = { l * n[0], l * n[1] }; // Step 9. dxx = l*nn val_withgrad_t<18> dxx[2] = { l * nn[0], l * nn[1] }; // Step 10. n -= nps.matmult(dxx, nps.transpose(E[:2,:2])) n[0] = n[0] - E[0]*dxx[0] - E[1]*dxx[1] ; n[1] = n[1] - E[3]*dxx[0] - E[4]*dxx[1] ; // Step 11. nn -= nps.matmult(dx, E[:2,:2]) nn[0] = nn[0] - E[0]*dx[0] - E[3]*dx[1] ; nn[1] = nn[1] - E[1]*dx[0] - E[4]*dx[1] ; // Step 12. l *= 2*d/( nps.inner(n,n) + nps.inner(nn,nn) ) val_withgrad_t<18> bb = (n [0]*n [0] + n [1]*n [1] + nn[0]*nn[0] + nn[1]*nn[1]) * 0.5; l = l/d * bb; // Step 13. dx = l*n dx[0] = l * n[0]; dx[1] = l * n[1]; // Step 14. dxx = l*nn dxx[0] = l * nn[0]; dxx[1] = l * nn[1]; // Step 15 v0.v[0] = x0[0] - dx[0]; v0.v[1] = x0[1] - dx[1]; v0.v[2] = val_withgrad_t<18>(1.0); // Step 16 v1.v[0] = x1[0] - dxx[0]; v1.v[1] = x1[1] - dxx[1]; v1.v[2] = val_withgrad_t<18>(1.0); // for debugging #if 0 { double Ex1[3] = { E[0].x*v1[0].x + E[1].x*v1[1].x + E[2].x, E[3].x*v1[0].x + E[4].x*v1[1].x + E[5].x, E[6].x*v1[0].x + E[7].x*v1[1].x + E[8].x }; double x0Ex1 = Ex1[0]*v0[0].x + Ex1[1]*v0[1].x + Ex1[2]; fprintf(stderr, "conj after: %f\n", x0Ex1); } #endif // Construct v0, v1 in a common coord system vec_withgrad_t<18,3> Rv1; Rv1.v[0] = R01.v[0]*v1.v[0] + R01.v[1]*v1.v[1] + R01.v[2]*v1.v[2]; Rv1.v[1] = R01.v[3]*v1.v[0] + R01.v[4]*v1.v[1] + R01.v[5]*v1.v[2]; Rv1.v[2] = R01.v[6]*v1.v[0] + R01.v[7]*v1.v[1] + R01.v[8]*v1.v[2]; // My two 3D rays now intersect exactly, and I use compute the intersection // with that assumption vec_withgrad_t<18,3> m; if(!triangulate_assume_intersect(m, v0, Rv1, t01)) return (mrcal_point3_t){0}; mrcal_point3_t _m; m.extract_value(_m.xyz); if(_dm_dv0 != NULL) m.extract_grad (_dm_dv0->xyz, 0,3, 0, 3*sizeof(double), sizeof(double), 3); if(_dm_dv1 != NULL) m.extract_grad (_dm_dv1->xyz, 3,3, 0, 3*sizeof(double), sizeof(double), 3); if(_dm_dRt01 != NULL) m.extract_grad (_dm_dRt01->xyz, 6,12,0, 12*sizeof(double), sizeof(double), 3); return _m; } // Minimize L1 angle error. Described in "Closed-Form Optimal Two-View // Triangulation Based on Angular Errors", Seong Hun Lee and Javier Civera. ICCV // 2019. extern "C" mrcal_point3_t mrcal_triangulate_leecivera_l1(// outputs // These all may be NULL mrcal_point3_t* _dm_dv0, mrcal_point3_t* _dm_dv1, mrcal_point3_t* _dm_dt01, // inputs // not-necessarily normalized vectors in the camera-0 // coord system const mrcal_point3_t* _v0, const mrcal_point3_t* _v1, const mrcal_point3_t* _t01) { // The paper has m0, m1 as the cam1-frame observation vectors. I do // everything in cam0-frame vec_withgrad_t<9,3> v0 (_v0 ->xyz, 0); vec_withgrad_t<9,3> v1 (_v1 ->xyz, 3); vec_withgrad_t<9,3> t01(_t01->xyz, 6); val_withgrad_t<9> dot_v0v0 = v0.norm2(); val_withgrad_t<9> dot_v1v1 = v1.norm2(); val_withgrad_t<9> dot_v0t = v0.dot(t01); val_withgrad_t<9> dot_v1t = v1.dot(t01); // I pick a bath based on which len(cross(normalize(m),t)) is larger: which // of m0 and m1 is most perpendicular to t. I can use a simpler dot product // here instead: the m that is most perpendicular to t will have the // smallest dot product. // // len(cross(m0/len(m0), t)) < len(cross(m1/len(m1), t)) ~ // len(cross(v0/len(v0), t)) < len(cross(v1/len(v1), t)) ~ // abs(dot(v0/len(v0), t)) > abs(dot(v1/len(v1), t)) ~ // (dot(v0/len(v0), t))^2 > (dot(v1/len(v1), t))^2 ~ // (dot(v0, t))^2 norm2(v1) > (dot(v1, t))^2 norm2(v0) ~ if(dot_v0t.x*dot_v0t.x * dot_v1v1.x > dot_v1t.x*dot_v1t.x * dot_v0v0.x ) { // Equation (12) vec_withgrad_t<9,3> n1 = cross<9>(v1, t01); v0 -= n1 * v0.dot(n1)/n1.norm2(); } else { // Equation (13) vec_withgrad_t<9,3> n0 = cross<9>(v0, t01); v1 -= n0 * v1.dot(n0)/n0.norm2(); } // My two 3D rays now intersect exactly, and I use compute the intersection // with that assumption vec_withgrad_t<9,3> m; if(!triangulate_assume_intersect(m, v0, v1, t01)) return (mrcal_point3_t){0}; mrcal_point3_t _m; m.extract_value(_m.xyz); if(_dm_dv0 != NULL) m.extract_grad (_dm_dv0->xyz, 0,3, 0, 3*sizeof(double), sizeof(double), 3); if(_dm_dv1 != NULL) m.extract_grad (_dm_dv1->xyz, 3,3, 0, 3*sizeof(double), sizeof(double), 3); if(_dm_dt01 != NULL) m.extract_grad (_dm_dt01->xyz, 6,3,0, 3*sizeof(double), sizeof(double), 3); return _m; } // Minimize L-infinity angle error. Described in "Closed-Form Optimal Two-View // Triangulation Based on Angular Errors", Seong Hun Lee and Javier Civera. ICCV // 2019. extern "C" mrcal_point3_t mrcal_triangulate_leecivera_linf(// outputs // These all may be NULL mrcal_point3_t* _dm_dv0, mrcal_point3_t* _dm_dv1, mrcal_point3_t* _dm_dt01, // inputs // not-necessarily normalized vectors in the camera-0 // coord system const mrcal_point3_t* _v0, const mrcal_point3_t* _v1, const mrcal_point3_t* _t01) { // The paper has m0, m1 as the cam1-frame observation vectors. I do // everything in cam0-frame vec_withgrad_t<9,3> v0 (_v0 ->xyz, 0); vec_withgrad_t<9,3> v1 (_v1 ->xyz, 3); vec_withgrad_t<9,3> t01(_t01->xyz, 6); v0 /= v0.mag(); v1 /= v1.mag(); vec_withgrad_t<9,3> na = cross<9>(v0 + v1, t01); vec_withgrad_t<9,3> nb = cross<9>(v0 - v1, t01); vec_withgrad_t<9,3>& n = ( na.norm2().x > nb.norm2().x ) ? na : nb; v0 -= n * v0.dot(n)/n.norm2(); v1 -= n * v1.dot(n)/n.norm2(); // My two 3D rays now intersect exactly, and I use compute the intersection // with that assumption vec_withgrad_t<9,3> m; if(!triangulate_assume_intersect(m, v0, v1, t01)) return (mrcal_point3_t){0}; mrcal_point3_t _m; m.extract_value(_m.xyz); if(_dm_dv0 != NULL) m.extract_grad (_dm_dv0->xyz, 0,3, 0, 3*sizeof(double), sizeof(double), 3); if(_dm_dv1 != NULL) m.extract_grad (_dm_dv1->xyz, 3,3, 0, 3*sizeof(double), sizeof(double), 3); if(_dm_dt01 != NULL) m.extract_grad (_dm_dt01->xyz, 6,3,0, 3*sizeof(double), sizeof(double), 3); return _m; } static bool chirality(const val_withgrad_t<9 >& l0, const vec_withgrad_t<9,3>& v0, const val_withgrad_t<9 >& l1, const vec_withgrad_t<9,3>& v1, const vec_withgrad_t<9,3>& t01) { double len2_nominal = 0.0; double len2; for(int i=0; i<3; i++) { double x = ( l1.x*v1.v[i].x + t01.v[i].x) - l0.x*v0.v[i].x; len2_nominal += x*x; } len2 = 0.0; for(int i=0; i<3; i++) { double x = ( l1.x*v1.v[i].x + t01.v[i].x) + l0.x*v0.v[i].x; len2 += x*x; } if( len2 < len2_nominal) return false; len2 = 0.0; for(int i=0; i<3; i++) { double x = (-l1.x*v1.v[i].x + t01.v[i].x) + l0.x*v0.v[i].x; len2 += x*x; } if( len2 < len2_nominal) return false; len2 = 0.0; for(int i=0; i<3; i++) { double x = (-l1.x*v1.v[i].x + t01.v[i].x) - l0.x*v0.v[i].x; len2 += x*x; } if( len2 < len2_nominal) return false; return true; } // The "Mid2" method in "Triangulation: Why Optimize?", Seong Hun Lee and Javier // Civera. https://arxiv.org/abs/1907.11917 extern "C" mrcal_point3_t mrcal_triangulate_leecivera_mid2(// outputs // These all may be NULL mrcal_point3_t* _dm_dv0, mrcal_point3_t* _dm_dv1, mrcal_point3_t* _dm_dt01, // inputs // not-necessarily normalized vectors in the camera-0 // coord system const mrcal_point3_t* _v0, const mrcal_point3_t* _v1, const mrcal_point3_t* _t01) { // The paper has m0, m1 as the cam1-frame observation vectors. I do // everything in cam0-frame vec_withgrad_t<9,3> v0 (_v0 ->xyz, 0); vec_withgrad_t<9,3> v1 (_v1 ->xyz, 3); vec_withgrad_t<9,3> t01(_t01->xyz, 6); val_withgrad_t<9> p_norm2_recip = val_withgrad_t<9>(1.0) / cross_norm2<9>(v0, v1); val_withgrad_t<9> l0 = (cross_norm2<9>(v1, t01) * p_norm2_recip).sqrt(); val_withgrad_t<9> l1 = (cross_norm2<9>(v0, t01) * p_norm2_recip).sqrt(); if(!chirality(l0, v0, l1, v1, t01)) return (mrcal_point3_t){0}; vec_withgrad_t<9,3> m = (v0*l0 + t01+v1*l1) / 2.0; mrcal_point3_t _m; m.extract_value(_m.xyz); if(_dm_dv0 != NULL) m.extract_grad (_dm_dv0->xyz, 0,3, 0, 3*sizeof(double), sizeof(double), 3); if(_dm_dv1 != NULL) m.extract_grad (_dm_dv1->xyz, 3,3, 0, 3*sizeof(double), sizeof(double), 3); if(_dm_dt01 != NULL) m.extract_grad (_dm_dt01->xyz, 6,3,0, 3*sizeof(double), sizeof(double), 3); return _m; } // The "wMid2" method in "Triangulation: Why Optimize?", Seong Hun Lee and // Javier Civera. https://arxiv.org/abs/1907.11917 extern "C" mrcal_point3_t mrcal_triangulate_leecivera_wmid2(// outputs // These all may be NULL mrcal_point3_t* _dm_dv0, mrcal_point3_t* _dm_dv1, mrcal_point3_t* _dm_dt01, // inputs // not-necessarily normalized vectors in the camera-0 // coord system const mrcal_point3_t* _v0, const mrcal_point3_t* _v1, const mrcal_point3_t* _t01) { // The paper has m0, m1 as the cam1-frame observation vectors. I do // everything in cam0-frame vec_withgrad_t<9,3> v0 (_v0 ->xyz, 0); vec_withgrad_t<9,3> v1 (_v1 ->xyz, 3); vec_withgrad_t<9,3> t01(_t01->xyz, 6); // Unlike Mid2 I need to normalize these here to make the math work. l0 and // l1 now have units of m, and I weigh by 1/l0 and 1/l1 v0 /= v0.mag(); v1 /= v1.mag(); val_withgrad_t<9> p_mag_recip = val_withgrad_t<9>(1.0) / cross_mag<9>(v0, v1); val_withgrad_t<9> l0 = cross_mag<9>(v1, t01) * p_mag_recip; val_withgrad_t<9> l1 = cross_mag<9>(v0, t01) * p_mag_recip; if(!chirality(l0, v0, l1, v1, t01)) return (mrcal_point3_t){0}; vec_withgrad_t<9,3> m = (v0*l0*l1 + t01*l0 + v1*l0*l1) / (l0 + l1); mrcal_point3_t _m; m.extract_value(_m.xyz); if(_dm_dv0 != NULL) m.extract_grad (_dm_dv0->xyz, 0,3, 0, 3*sizeof(double), sizeof(double), 3); if(_dm_dv1 != NULL) m.extract_grad (_dm_dv1->xyz, 3,3, 0, 3*sizeof(double), sizeof(double), 3); if(_dm_dt01 != NULL) m.extract_grad (_dm_dt01->xyz, 6,3,0, 3*sizeof(double), sizeof(double), 3); return _m; } mrcal-2.4.1/triangulation.h000066400000000000000000000135411456301662300156570ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #pragma once #include "basic-geometry.h" // All of these return (0,0,0) if the rays are parallel or divergent, or if the // intersection is behind either of the two cameras. No gradients are reported // in that case // Basic closest-approach-in-3D routine. This is the "Mid" method in // "Triangulation: Why Optimize?", Seong Hun Lee and Javier Civera // https://arxiv.org/abs/1907.11917 mrcal_point3_t mrcal_triangulate_geometric(// outputs // These all may be NULL mrcal_point3_t* dm_dv0, mrcal_point3_t* dm_dv1, mrcal_point3_t* dm_dt01, // inputs // not-necessarily normalized vectors in the camera-0 // coord system const mrcal_point3_t* v0, const mrcal_point3_t* v1, const mrcal_point3_t* t01); // Minimize L2 pinhole reprojection error. Described in "Triangulation Made // Easy", Peter Lindstrom, IEEE Conference on Computer Vision and Pattern // Recognition, 2010. This is the "L2 img 5-iteration" method (but with only 2 // iterations) in "Triangulation: Why Optimize?", Seong Hun Lee and Javier // Civera. https://arxiv.org/abs/1907.11917 // Lindstrom's paper recommends 2 iterations mrcal_point3_t mrcal_triangulate_lindstrom(// outputs // These all may be NULL mrcal_point3_t* dm_dv0, mrcal_point3_t* dm_dv1, mrcal_point3_t* dm_dRt01, // inputs // not-necessarily normalized vectors in the LOCAL // coordinate system. This is different from the other // triangulation routines const mrcal_point3_t* v0_local, const mrcal_point3_t* v1_local, const mrcal_point3_t* Rt01); // Minimize L1 angle error. Described in "Closed-Form Optimal Two-View // Triangulation Based on Angular Errors", Seong Hun Lee and Javier Civera. ICCV // 2019. This is the "L1 ang" method in "Triangulation: Why Optimize?", Seong // Hun Lee and Javier Civera. https://arxiv.org/abs/1907.11917 mrcal_point3_t mrcal_triangulate_leecivera_l1(// outputs // These all may be NULL mrcal_point3_t* dm_dv0, mrcal_point3_t* dm_dv1, mrcal_point3_t* dm_dt01, // inputs // not-necessarily normalized vectors in the camera-0 // coord system const mrcal_point3_t* v0, const mrcal_point3_t* v1, const mrcal_point3_t* t01); // Minimize L-infinity angle error. Described in "Closed-Form Optimal Two-View // Triangulation Based on Angular Errors", Seong Hun Lee and Javier Civera. ICCV // 2019. This is the "L-infinity ang" method in "Triangulation: Why Optimize?", // Seong Hun Lee and Javier Civera. https://arxiv.org/abs/1907.11917 mrcal_point3_t mrcal_triangulate_leecivera_linf(// outputs // These all may be NULL mrcal_point3_t* dm_dv0, mrcal_point3_t* dm_dv1, mrcal_point3_t* dm_dt01, // inputs // not-necessarily normalized vectors in the camera-0 // coord system const mrcal_point3_t* v0, const mrcal_point3_t* v1, const mrcal_point3_t* t01); // The "Mid2" method in "Triangulation: Why Optimize?", Seong Hun Lee and Javier // Civera. https://arxiv.org/abs/1907.11917 mrcal_point3_t mrcal_triangulate_leecivera_mid2(// outputs // These all may be NULL mrcal_point3_t* dm_dv0, mrcal_point3_t* dm_dv1, mrcal_point3_t* dm_dt01, // inputs // not-necessarily normalized vectors in the camera-0 // coord system const mrcal_point3_t* v0, const mrcal_point3_t* v1, const mrcal_point3_t* t01); // The "wMid2" method in "Triangulation: Why Optimize?", Seong Hun Lee and Javier // Civera. https://arxiv.org/abs/1907.11917 mrcal_point3_t mrcal_triangulate_leecivera_wmid2(// outputs // These all may be NULL mrcal_point3_t* dm_dv0, mrcal_point3_t* dm_dv1, mrcal_point3_t* dm_dt01, // inputs // not-necessarily normalized vectors in the camera-0 // coord system const mrcal_point3_t* v0, const mrcal_point3_t* v1, const mrcal_point3_t* t01); // I don't implement triangulate_leecivera_l2() yet because it requires // computing an SVD, which is far slower than what the rest of these functions // do mrcal-2.4.1/unpack_state.docstring000066400000000000000000000055021456301662300172230ustar00rootroot00000000000000Scales a state vector from the packed, unitless form used by the optimizer SYNOPSIS m = mrcal.cameramodel('xxx.cameramodel') optimization_inputs = m.optimization_inputs() b_packed = mrcal.optimizer_callback(**optimization_inputs)[0] b = b_packed.copy() mrcal.unpack_state(b, **optimization_inputs) In order to make the optimization well-behaved, we scale all the variables in the state and the gradients before passing them to the optimizer. The internal optimization library thus works only with unitless (or "packed") data. This function takes a packed numpy array of shape (...., Nstate), and scales it to produce full data with real units. This function applies the scaling directly to the input array; the input is modified, and nothing is returned. To unpack a state vector, you naturally call unpack_state(). To unpack a jacobian matrix, you would call pack_state() because in a jacobian, the state is in the denominator. Broadcasting is supported: any leading dimensions will be processed correctly, as long as the given array has shape (..., Nstate). In order to know what the scale factors should be, and how they should map to each variable in the state vector, we need quite a bit of context. If we have the full set of inputs to the optimization function, we can pass in those (as shown in the example above). Or we can pass the individual arguments that are needed (see ARGUMENTS section for the full list). If the optimization inputs and explicitly-given arguments conflict about the size of some array, the explicit arguments take precedence. If any array size is not specified, it is assumed to be 0. Thus most arguments are optional. ARGUMENTS - b: a numpy array of shape (..., Nstate). This is the packed state on input, and the full state on output. The input array is modified. - **kwargs: if the optimization inputs are available, they can be passed-in as kwargs. These inputs contain everything this function needs to operate. If we don't have these, then the rest of the variables will need to be given - lensmodel: string specifying the lensmodel we're using (this is always 'LENSMODEL_...'). The full list of valid models is returned by mrcal.supported_lensmodels(). This is required if we're not passing in the optimization inputs - do_optimize_intrinsics_core do_optimize_intrinsics_distortions do_optimize_extrinsics do_optimize_calobject_warp do_optimize_frames optional booleans; default to True. These specify what we're optimizing. See the documentation for mrcal.optimize() for details - Ncameras_intrinsics Ncameras_extrinsics Nframes Npoints Npoints_fixed optional integers; default to 0. These specify the sizes of various arrays in the optimization. See the documentation for mrcal.optimize() for details RETURNED VALUE None. The scaling is applied to the input array mrcal-2.4.1/util.h000066400000000000000000000006641456301662300137560ustar00rootroot00000000000000// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S. // Government sponsorship acknowledged. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 #pragma once #include #define MSG(fmt, ...) fprintf(stderr, "%s(%d): " fmt "\n", __FILE__, __LINE__, ##__VA_ARGS__)