From bbb94b59212c6a12e3ee4644ff0489e2bfc6d19b Mon Sep 17 00:00:00 2001 From: Joel Truher Date: Wed, 26 Nov 2025 12:26:08 -0800 Subject: [PATCH 01/13] fiddling with 3d splines --- .../team100/lib/geometry/GeometryUtil.java | 6 +- .../team100/lib/geometry/HolonomicPose3d.java | 18 ++++ .../lib/geometry/Pose3dWithMotion.java | 12 +++ .../path/spline/HolonomicSpline.java | 13 ++- .../path/spline/HolonomicSpline3d.java | 99 +++++++++++++++++++ .../org/team100/lib/testing/Timeless.java | 35 +++---- .../path/spline/HolonomicSplineTest.java | 20 +++- .../team100/lib/util/GeometryUtilTest.java | 12 +++ 8 files changed, 188 insertions(+), 27 deletions(-) create mode 100644 lib/src/main/java/org/team100/lib/geometry/HolonomicPose3d.java create mode 100644 lib/src/main/java/org/team100/lib/geometry/Pose3dWithMotion.java create mode 100644 lib/src/main/java/org/team100/lib/trajectory/path/spline/HolonomicSpline3d.java diff --git a/lib/src/main/java/org/team100/lib/geometry/GeometryUtil.java b/lib/src/main/java/org/team100/lib/geometry/GeometryUtil.java index 00adcbe7..0bb20f7b 100644 --- a/lib/src/main/java/org/team100/lib/geometry/GeometryUtil.java +++ b/lib/src/main/java/org/team100/lib/geometry/GeometryUtil.java @@ -264,7 +264,11 @@ public static double distanceM(Pose2d a, Pose2d b) { } public static double distanceM(Translation2d a, Translation2d b) { - return inverse(a).plus(b).getNorm(); + return a.getDistance(b); + } + + public static double distanceM(Translation3d a, Translation3d b) { + return a.getDistance(b); } public static Translation2d inverse(Translation2d a) { diff --git a/lib/src/main/java/org/team100/lib/geometry/HolonomicPose3d.java b/lib/src/main/java/org/team100/lib/geometry/HolonomicPose3d.java new file mode 100644 index 00000000..35a0eb53 --- /dev/null +++ b/lib/src/main/java/org/team100/lib/geometry/HolonomicPose3d.java @@ -0,0 +1,18 @@ +package org.team100.lib.geometry; + +import edu.wpi.first.math.geometry.Rotation3d; +import edu.wpi.first.math.geometry.Translation3d; + +/** + * For constructing 3d splines, paths, and trajectories. + * + * @param translation + * @param heading where we're facing, can include roll + * @param course where we're going, ignores roll. + */ +public record HolonomicPose3d( + Translation3d translation, + Rotation3d heading, + Rotation3d course) { + +} diff --git a/lib/src/main/java/org/team100/lib/geometry/Pose3dWithMotion.java b/lib/src/main/java/org/team100/lib/geometry/Pose3dWithMotion.java new file mode 100644 index 00000000..cb235742 --- /dev/null +++ b/lib/src/main/java/org/team100/lib/geometry/Pose3dWithMotion.java @@ -0,0 +1,12 @@ +package org.team100.lib.geometry; + +/** + * HolonomicPose3d with: + * + * * the spatial rate of change in heading + * * the spatial rate of change in course + * * the spatial rate of change in course curvature + */ +public class Pose3dWithMotion { + +} diff --git a/lib/src/main/java/org/team100/lib/trajectory/path/spline/HolonomicSpline.java b/lib/src/main/java/org/team100/lib/trajectory/path/spline/HolonomicSpline.java index 01bb02e0..5cab5802 100644 --- a/lib/src/main/java/org/team100/lib/trajectory/path/spline/HolonomicSpline.java +++ b/lib/src/main/java/org/team100/lib/trajectory/path/spline/HolonomicSpline.java @@ -78,11 +78,14 @@ public HolonomicSpline(HolonomicPose2d p0, HolonomicPose2d p1, double mN0, doubl if (DEBUG) { System.out.printf("scale %f %f\n", scale0, scale1); } + Translation2d course0 = new Translation2d(1,0).rotateBy(p0.course()); + Translation2d course1 = new Translation2d(1,0).rotateBy(p1.course()); + double x0 = p0.translation().getX(); double x1 = p1.translation().getX(); // first derivatives are just the course - double dx0 = p0.course().getCos() * scale0; - double dx1 = p1.course().getCos() * scale1; + double dx0 = course0.getX() * scale0; + double dx1 = course1.getX() * scale1; // second derivatives are zero at the ends double ddx0 = 0; double ddx1 = 0; @@ -90,8 +93,8 @@ public HolonomicSpline(HolonomicPose2d p0, HolonomicPose2d p1, double mN0, doubl double y0 = p0.translation().getY(); double y1 = p1.translation().getY(); // first derivatives are just the course - double dy0 = p0.course().getSin() * scale0; - double dy1 = p1.course().getSin() * scale1; + double dy0 = course0.getY() * scale0; + double dy1 = course1.getY() * scale1; // second derivatives are zero at the ends double ddy0 = 0; double ddy1 = 0; @@ -100,7 +103,7 @@ public HolonomicSpline(HolonomicPose2d p0, HolonomicPose2d p1, double mN0, doubl m_y = SplineR1.get(y0, y1, dy0, dy1, ddy0, ddy1); m_r0 = p0.heading(); - double delta = p0.heading().unaryMinus().rotateBy(p1.heading()).getRadians(); + double delta = p1.heading().minus(p0.heading()).getRadians(); // previously dtheta at the endpoints was zero, which is bad: it meant the omega // value varied all over the place, even for theta paths that should be diff --git a/lib/src/main/java/org/team100/lib/trajectory/path/spline/HolonomicSpline3d.java b/lib/src/main/java/org/team100/lib/trajectory/path/spline/HolonomicSpline3d.java new file mode 100644 index 00000000..341f3c4a --- /dev/null +++ b/lib/src/main/java/org/team100/lib/trajectory/path/spline/HolonomicSpline3d.java @@ -0,0 +1,99 @@ +package org.team100.lib.trajectory.path.spline; + +import org.team100.lib.geometry.GeometryUtil; +import org.team100.lib.geometry.HolonomicPose3d; + +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Rotation3d; +import edu.wpi.first.math.geometry.Translation3d; + +/** + * Holonomic spline in three dimensions, similar to the 2d version. + * + * Internally this is five one-dimensional splines (x, y, z, phi, theta), with + * respect to a parameter [0,1]. + * + * Elsewhere, we use Rotation3d to describe spherical angles, by applying the + * rotation to the translation (1,0,0), as Pose3d does. The coordinate system + * there is "roll pitch yaw" from the reference, not "spherical coordinates" + * (with a polar angle etc). + */ +public class HolonomicSpline3d { + private static final boolean DEBUG = false; + // curvature measurement performance scales with sample count so make it kinda + // low. most splines go between 0.5 and 5 meters so this is steps of 2 to 20 cm. + private static final int SAMPLES = 25; + + private final SplineR1 m_x; + private final SplineR1 m_y; + private final SplineR1 m_z; + private final SplineR1 m_pitch; + private final SplineR1 m_yaw; + private final Rotation2d m_pitch0; + private final Rotation2d m_yaw0; + + public HolonomicSpline3d(HolonomicPose3d p0, HolonomicPose3d p1) { + this(p0, p1, 1.2, 1.2); + } + + public HolonomicSpline3d(HolonomicPose3d p0, HolonomicPose3d p1, double mN0, double mN1) { + double scale0 = mN0 * GeometryUtil.distanceM(p0.translation(), p1.translation()); + double scale1 = mN1 * GeometryUtil.distanceM(p0.translation(), p1.translation()); + + Translation3d course0 = new Translation3d(1, 0, 0).rotateBy(p0.course()); + Translation3d course1 = new Translation3d(1, 0, 0).rotateBy(p1.course()); + + double x0 = p0.translation().getX(); + double x1 = p1.translation().getX(); + // first derivatives are just the course + double dx0 = course0.getX() * scale0; + double dx1 = course1.getX() * scale1; + // second derivatives are zero at the ends + double ddx0 = 0; + double ddx1 = 0; + + double y0 = p0.translation().getY(); + double y1 = p1.translation().getY(); + // first derivatives are just the course + double dy0 = course0.getY() * scale0; + double dy1 = course1.getY() * scale1; + // second derivatives are zero at the ends + double ddy0 = 0; + double ddy1 = 0; + + double z0 = p0.translation().getZ(); + double z1 = p1.translation().getZ(); + // first derivatives are just the course + double dz0 = course0.getZ() * scale0; + double dz1 = course1.getZ() * scale1; + // second derivatives are zero at the ends + double ddz0 = 0; + double ddz1 = 0; + + m_x = SplineR1.get(x0, x1, dx0, dx1, ddx0, ddx1); + m_y = SplineR1.get(y0, y1, dy0, dy1, ddy0, ddy1); + m_z = SplineR1.get(z0, z1, dz0, dz1, ddz0, ddz1); + + m_pitch0 = new Rotation2d(p0.heading().getY()); + m_yaw0 = new Rotation2d(p0.heading().getZ()); + + Rotation3d headingDelta = p1.heading().minus(p0.heading()); + double pitchDelta = headingDelta.getY(); + double yawDelta = headingDelta.getZ(); + + double dpitch0 = pitchDelta * mN0; + double dpitch1 = pitchDelta * mN1; + // second derivatives are zero at the ends + double ddpitch0 = 0; + double ddpitch1 = 0; + m_pitch = SplineR1.get(0.0, pitchDelta, dpitch0, dpitch1, ddpitch0, ddpitch1); + + double dyaw0 = yawDelta * mN0; + double dyaw1 = yawDelta * mN1; + // second derivatives are zero at the ends + double ddyaw0 = 0; + double ddyaw1 = 0; + m_yaw = SplineR1.get(0.0, yawDelta, dyaw0, dyaw1, ddyaw0, ddyaw1); + } + +} diff --git a/lib/src/test/java/org/team100/lib/testing/Timeless.java b/lib/src/test/java/org/team100/lib/testing/Timeless.java index f9ef94ab..79b020d7 100644 --- a/lib/src/test/java/org/team100/lib/testing/Timeless.java +++ b/lib/src/test/java/org/team100/lib/testing/Timeless.java @@ -1,7 +1,6 @@ package org.team100.lib.testing; import org.junit.jupiter.api.AfterEach; -import org.junit.jupiter.api.BeforeAll; import org.junit.jupiter.api.BeforeEach; import org.team100.lib.coherence.Cache; import org.team100.lib.coherence.Takt; @@ -23,31 +22,29 @@ */ public interface Timeless { - /** Make sure the cache doesn't try to update stale things. */ + /** One big method because Junit */ @BeforeEach - default void clearCache() { + default void setupSim() { + // Do any time-related setup *in your test method* ! + HAL.initialize(500, 0); + SimHooks.pauseTiming(); + Takt.update(); + + // Make sure the cache doesn't try to update stale things. Cache.clear(); - } - /* Simulated motors don't move unless enabled, so enable them. */ - @BeforeEach - default void enableMotors() { + // Simulated motors don't move unless enabled, so enable them. DriverStationSim.setEnabled(true); DriverStationSim.notifyNewData(); - } - /** Avoid mixing mutable values between tests. */ - @BeforeEach - default void unpublish() { + // Avoid mixing mutable values between tests. Mutable.unpublishAll(); - } - - /** Do any time-related setup *in your test method* ! */ - @BeforeEach - default void pauseTiming() { - HAL.initialize(500, 0); - SimHooks.pauseTiming(); - Takt.update(); + try { + // wait for CTRE threads + Thread.sleep(10); + } catch (InterruptedException e) { + e.printStackTrace(); + } } @AfterEach diff --git a/lib/src/test/java/org/team100/lib/trajectory/path/spline/HolonomicSplineTest.java b/lib/src/test/java/org/team100/lib/trajectory/path/spline/HolonomicSplineTest.java index 9a73f4ca..feb15392 100644 --- a/lib/src/test/java/org/team100/lib/trajectory/path/spline/HolonomicSplineTest.java +++ b/lib/src/test/java/org/team100/lib/trajectory/path/spline/HolonomicSplineTest.java @@ -27,7 +27,7 @@ import edu.wpi.first.math.geometry.Translation2d; class HolonomicSplineTest implements Timeless { - private static final boolean DEBUG = false; + private static final boolean DEBUG = true; private static final double DELTA = 0.001; private static final LoggerFactory logger = new TestLoggerFactory(new TestPrimitiveLogger()); @@ -71,7 +71,6 @@ void testLinear2() { @Test void testRotation() { - HolonomicSpline s = new HolonomicSpline( new HolonomicPose2d(new Translation2d(), new Rotation2d(), new Rotation2d()), new HolonomicPose2d(new Translation2d(1, 0), new Rotation2d(1), new Rotation2d())); @@ -107,6 +106,23 @@ void testRotation() { } + @Test + void testRotation2() { + // Make sure the rotation goes over +/- pi + HolonomicSpline s = new HolonomicSpline( + new HolonomicPose2d(new Translation2d(), new Rotation2d(2.5), new Rotation2d()), + new HolonomicPose2d(new Translation2d(1,0), new Rotation2d(-2.5), new Rotation2d())); + if (DEBUG) { + System.out.println("d, x, y, heading, course"); + for (double tt = 0; tt <= 1.0; tt += 0.01) { + var ss = s.getPose2dWithMotion(tt); + Pose2d pose = ss.getPose().pose(); + System.out.printf("%6.3f, %6.3f, %6.3f, %6.3f, %6.3f\n", + tt, pose.getX(), pose.getY(), pose.getRotation().getRadians(), ss.getCourse().getRadians()); + } + } + } + @Test void testCircle() { // four splines that make a circle should have nice even curvature and velocity diff --git a/lib/src/test/java/org/team100/lib/util/GeometryUtilTest.java b/lib/src/test/java/org/team100/lib/util/GeometryUtilTest.java index 2108560a..939bb852 100644 --- a/lib/src/test/java/org/team100/lib/util/GeometryUtilTest.java +++ b/lib/src/test/java/org/team100/lib/util/GeometryUtilTest.java @@ -11,6 +11,7 @@ import edu.wpi.first.math.geometry.Quaternion; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Rotation3d; +import edu.wpi.first.math.geometry.Translation2d; import edu.wpi.first.math.geometry.Translation3d; import edu.wpi.first.math.geometry.Twist2d; import edu.wpi.first.math.kinematics.ChassisSpeeds; @@ -85,6 +86,17 @@ void testSlog() { assertEquals(1.571, twist.dtheta, DELTA); } + @Test + void testDistance2() { + assertEquals(1, GeometryUtil.distanceM(new Translation2d(1, 0), new Translation2d(0, 0)), DELTA); + } + + @Test + void testDistance3() { + assertEquals(1, GeometryUtil.distanceM( + new Translation3d(1, 0, 0), new Translation3d(0, 0, 0)), DELTA); + } + @Test void testDistance() { // same pose => 0 From d96336a106f46c761670e32772d7a907425bdd46 Mon Sep 17 00:00:00 2001 From: Joel Truher Date: Thu, 27 Nov 2025 11:39:02 -0800 Subject: [PATCH 02/13] fiddling with redundant kinematics --- .../lib/geometry/Pose3dWithMotion.java | 19 +++++ .../lib/subsystems/2p_parallel/README.md | 72 ++++++++++++++++++ .../lib/subsystems/2p_parallel/chart.png | Bin 0 -> 33629 bytes .../lib/subsystems/2p_parallel/cost_fn.png | Bin 0 -> 28154 bytes .../path/spline/HolonomicSpline3d.java | 42 ++++++++++ .../path/spline/HolonomicSpline3dTest.java | 35 +++++++++ 6 files changed, 168 insertions(+) create mode 100644 lib/src/main/java/org/team100/lib/subsystems/2p_parallel/README.md create mode 100644 lib/src/main/java/org/team100/lib/subsystems/2p_parallel/chart.png create mode 100644 lib/src/main/java/org/team100/lib/subsystems/2p_parallel/cost_fn.png create mode 100644 lib/src/test/java/org/team100/lib/trajectory/path/spline/HolonomicSpline3dTest.java diff --git a/lib/src/main/java/org/team100/lib/geometry/Pose3dWithMotion.java b/lib/src/main/java/org/team100/lib/geometry/Pose3dWithMotion.java index cb235742..8b17c48a 100644 --- a/lib/src/main/java/org/team100/lib/geometry/Pose3dWithMotion.java +++ b/lib/src/main/java/org/team100/lib/geometry/Pose3dWithMotion.java @@ -8,5 +8,24 @@ * * the spatial rate of change in course curvature */ public class Pose3dWithMotion { + /** Position, heading and course. */ + private final HolonomicPose3d m_pose; + /** Change in yaw per meter of motion, rad/m. */ + private final double m_headingYawRate; + + public Pose3dWithMotion( + HolonomicPose3d pose, + double headingYawRate) { + m_pose = pose; + m_headingYawRate = headingYawRate; + } + + public HolonomicPose3d getPose() { + return m_pose; + } + + public double getHeadingYawRateRad_M() { + return m_headingYawRate; + } } diff --git a/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/README.md b/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/README.md new file mode 100644 index 00000000..262e72e7 --- /dev/null +++ b/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/README.md @@ -0,0 +1,72 @@ +# 2P Parallel + +This is a study of control of two parallel prismatic joints, the simplest "redundant" mechanism. + +## Trajectories + +Why would we want redundant joints? One reason is to allow "coarse" and "fine" joints: +the drivetrain could execute "coarse" motion (large, slow, approximate) and the +mechanism could execute "fine" motion (small, quick, accurate). + +Here's a use case for this capability: coming to a stop with higher acceleration than +the "coarse" mechanism can manage ([spreadsheet](https://docs.google.com/spreadsheets/d/1Z7twUzL8mwdp5JcAuysRHhibZrmlWo9Cy3-zGcI3sXY/edit?gid=1682330556#gid=1682330556)): + + + +In this example, the coarse joint, $q_1$, anticipates the approaching stop by +accelerating ahead of $x$, and then brakes gently for the rest of the time. +The fine joint, $q_2$, is capable of much faster acceleration, and so makes +up the difference. + +## Kinematics + +Redundant mechanisms have nonunique inverse kinematics, so the problem needs to be solved +as some sort of constrained optimization. + +The forward kinematics are trivial, for joint configurations $q_1$ and $q_2$, and end-effector position $x$: + +```math +x = q_1 + q_2 +``` + +To solve the underdetermined inverse kinematics, there are some trivial options, for example the +joints could split the distance: + +```math +q_1 = \tfrac{x}{2} +\\ +q_2 = \tfrac{x}{2} +``` +Another trivial option is for the first joint to do all the work: + +```math +q_1 = x +\\ +q_2 = 0 +``` + +A more realistic case might involve "coarse" and "fine" joints -- for example, $q_1$ could +be a robot drivetrain, and $q_2$ could be an attached mechanism. In this case, the range +of motion of $q_1$ is essentially unlimited, but $q_2$ has limits that could be expressed +as a cost function, with a soft minimum at the center of motion, and steep penalty near the +edges ([desmos](https://www.desmos.com/calculator/2l6ta0osg7)): + + + +Using this cost function alone would yield the same answer as the trivial case above: +$q_1$ would do all the work. + +## Control + +For a trajectory in $x$, we have two control strategies. + +* For the drivetrain, $q_1$, we take the sum of velocity feedforward and proportional +position feedback, supplied to a low-level velocity controller. +* For the mechanism, $q_2$, we supply the positional setpoint directly to a low-level +position controller, with the velocity feedforward as an extra voltage. + + +## Reference + +* [paper about redundant manipulator IK](https://www.mdpi.com/2227-7390/13/4/624) +* [FABRIK paper](http://www.andreasaristidou.com/publications/papers/FABRIK.pdf) \ No newline at end of file diff --git a/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/chart.png b/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/chart.png new file mode 100644 index 0000000000000000000000000000000000000000..cb266e449c617ac32a745ac84f4e20c762e27569 GIT binary patch literal 33629 zcmdpecT|(f8?I|vEUWwg5gS2z2SovqW&tS?kO0yoEKQ^`|G(#Y&K}PS^L_KZGxL_`dEW86t*&(R@ae;Q_Ut*TqO1Vh zvuE!r_|NI!@8Dm8vKEy0?0K|DMd6yZJA7dj5!~AwzvYu$_8_a#V83;hP>5Zv4DSOfmvbFT9C z9QcPvLP{t)@V^CTQz785M#pdu+7DYa|G)gLR}%snzTr!2sBI!E<=S)f5E;HLqQll55+xI} zNlx6-j}$SQgB;tV9|)u0gUHUvQ2zaoljm6A?k4RK>yP)*4b>!47ArN>FV(dre&@;1Jd_<`I%W< zt`qLfQKu9A_t71@q~{7l_752i`5t2xNKH*8_FHRgCX_lzkIL7ku%aHzXv>cqNtgEAGTWOB}~#B+)iT-lv*cY|zzduo=^xno+w2 zCBwdHX;#W@#@ghDa4NlSq?h0LbL(9Ss%yB1(#AZ#Ri&Uy_2Dbk=&ZDM$D6^+@l2mHbFG3z&^0wT1d{y?+kv-)v zVD#rKg$7QBcr#IH^Ue%~V%D#)?maT4I@>m?Ro%0u-4i*MDPVcDdVGl_gi+O6lGNS! zzTeLa@$iSur#3hHatwL5mf5!0al@ri-x`7{$A5qH<|>Nr5l=?EP7gkAi#om);ffm? zG|u9dN`qD6GaR#;ZH0>sZ<(c*-qBi$OOmRoQ3>N29Cjhjb~nsyS?>940IYTYI__x! zVXCcAbhX%{O!Oh0)dP)|5#d7ZkeJW=@tVA|j#}*9k|WOy@-~_G%ahe{CNhaJGyv z7Z#7~aXduZ-8~Sw)W!8a7@a1nzXzFi#r^wR>O7_2hpJmn9J0ZFes@DHaxiU7QbnLf zz8D%(*{C)5+oXW1?4C)#yP}2Vo0NTfM8O9%GL^$UoTwzaJ#fC&J;A(=n3bvZCHg&8 zz=NIBnDm%!TODWHv_z^;M6WvU^gs5dH_b9%Q|H^ zM_HY>WLb{0uTW8cbD14DfzUG!Rh`~AnsXVgoj)bxo+q1|mv{RZMCQJ6l#y!;btpMV zj^^foS;ftu)aNYl`%w>crfis*nFrC-wFY_h(}TeV1<9Z62J+r57Dou`4xv%pQsDQm zid-n^No;BggJ=|;J?*#dhKi?pw?qmPpB93{zh%baEIMampz}qz zB@-zO2^vPndl3g!I5EQTDm~ysTfv)t{=p(}W0+wh?u!C~s#IVhEE_m(*ogqqlBiC1 zzj{+wgs$%8v$;qNQ5`chCZ^-FR?9Xb`kO&U)86w35YJQ^Id8p_4)_$c-kYV{(&0_K zNN#iR2JY+Z!ZFNiRQdW`R%&*3E7djGn=(8;bilhURvefE94(^?XO+{l|1s8ZuGhm==c7)(I{aps zKP|Wr5C!* zMiVuq$Io7V@Sgl96W=PBnBQLIn-CL5{6Vdm_N4q&xa{XS5iBaw!{Y15=S2PjdFreN zPFSS(otEI8>m-HWxHyB(A3{9iced;tfH{D8bL$;4X-{Z~QuH&KkH;$t zl~JUtC|`bOjpJ9v@CUts9CumsX{$aa>s(4Pj?w%%fZYafJ-V#L%T?u)jIke;#H1C;Z#@ei^@$5#SsZx#CUI6^c37>MZQZGDIw5?n z$*f-9A@bQB;o_x~VMW=qu3Lg}IjxpWe*T}(;`1ft@}a-XoA{C?KKy&yDx=<|agi}* z4XTbR-AYK($ClIKD;{nGl|@lq!<2#fv8)DqmaP#*okHuylH=X}P zftAm#NH5lim_#M>RwZ_XHT?D>LiQY$XC0fSyWzMRP#vDDWLdP)A9`%p(j@EmbTJoy zl3AH`TyBdNinzfRRUl7_n6TMIU(-jsrBh$nq->ylA~Q8bU;4DaQn1=`^{s3I@m)WjqwN~4J+2<&kqhNjcm=mO8U8}J-eUKyvcRQ zYF>Z&(&n8fP?kaZ)FHRg-hC)bz6FiTuchu+Nm+B*3q;X^q_cIb%G>+B?ranrd) zN=fYAt#(}o1QGLgWJYsLI_P`TBh+uFF7fhlp75Ov6gMG1fNJ+`{x57Pr~$_<&TEsa zJ=^}v85`D<5$U8NxmE@bQ-169w}hbhmt;>LCst&AcjT`m@KBCnhD2ba`MOAqp?4z1 zQa#{s4R<2Wf2if&qKEkBw`Eybl#?|w-|t<$+5ZaR=A}?Q#1xjC`jDj2YyIolZ&=CC z6yUBxU@$(&-tX*0*Vpy&9aWZ<9!9JcDJ6j`9r0G-jx{DkDn1B@SBpZsk9odD&yB3imy~g z9`#4!bUbVvP-pSc7^TXgI9b;RK5S2m@@0{*Ul`pjIRNQL~mTOjH zF`JkaxAfn!Mn;(fx-!de*U~UT?|MOsKJ$o@-dyHb!+k{J<^uL&liRo6eL2=~O{vC8 zsbaz9HSG6AesP`nD?yzZ3N_>0j}JKEm|#$c%G_&+(xvyLg>%e7TZ*1&_3+OuiN)3q zB^W-lH>Ny|+hw7&= zM;R!=8MbM^Jga^3!s(F4b~FyhE|}o0=a0NQ`u07GTO~{Y;&av0LA|iQ&9K^<)M3h{ z(`V^(3gzZ+Q`+fGan^Ndkkg&nePBX!5ZdV(H%shFO8tb`oD(s&pNuA;>#l|U&2%T) zqGra}M&zF_A3I)evF7{EWBB%%obb6Ll1c^l;ys;yeV8z!=%Yzx9c3&!R*&B2#f|tL zmF!-on?vb&nO>8Hy`+Y3#HVOhbr$jy6FEv^>Dk7Q&+%<e;g=wmNnP+Rpo<|G61uMWW!21%xn zl>gj3i*m=a^H&o!jxN<@G0I!Kc~-N2U8tsmx}05X;&2P%-aTjt&xz9YyGQ$j>LgkD4F;RE>zX$UorP>6O7wq_Q<^)I$g=6iU7btc8Lt^8|H{;&tO0Gm3 zTU1B33kmEDH7Y!W42bt0Fnt-OohK_Lhj3Eb^XlHE_DKI4+0TC(c|I%^OmX~v4(S#<5OQNN zXzC3UHnOUSkBjw%RC;xFK9A7mZSS!dH=B7OiRU|$3l%p=&h5`|0$g^Jn;%n-q*g8; zh*BPW|Jy{|1w{^Hha9Voa!edlxL5)nzd1C!(id(Wpt`!pwmeZRQD{`(R%GYYxL6Ud zSmgyClg3p>0^RJyQGLz2N7*>uX+)}26?~+2zL`3rPmEu)QQ|%p2s6~m^qSU~Y_gYV zi+C+m^83!DsVhn5(>G$g>-fqc*p;_I^Y)(7{662+k%G-Lq{@-R)*~U&ja91*vr>Ih zzum!I^vS#IrtV{RM7Y`XwC2uS2{qMucnxw-}sC%p~IT)%<3Z>kp-4< zSbl8#<}xv36<&2>%OHv z@oDZ{QQtSreBz`5jL@Nz3=jUkE?R%scQmmT>8m;+=6o$9x0Q5qKB|2F@?`;5=Z?S~ z6Z!nnA8I~)4+W9GtGe!tGM=QkhRyjUa~F6OVhWF*7RW3z?+Fcd_T<-`s(iK5WRv(j z^-AOQIOk4T$sM7N!%RD5yh0`O)3HKQ0Gjl6URbuCG^a3_|KKr2OBwdH)Eu9g=k;f} z03qI5mAaN{!oR9H)vZPv*^!gKl+dXxn!+-`9KB4a96mMPFbz`3HhHr8ZDM>;; zx^xx7Bm^}lOKQ$ac7om3{ztQ<@1TvGmb2x~tUrfA8gX~Sp@!YUXVGxWq(3f~dAul! z8^mIgl1zwFh^Sk`~lrw%-mW@z0ZGIP$IDhu6%cy&e(8$>kzLu%tu3h$Y_gmN)s;0n42-efN zo(->rEcT<&5dDRuF%;q_p4O#?wUh!8?%s~hBNm{sDlRDt(b&V=m_ zSI1o%WXnAL!s#nC{11yf>}wi#4_t$LDVoxeD&@O)9HoMEu0hj$PDhGxGFrgnf0v$0 z4nD4{Iib5)r?a^UNxo4WYQV2 z*!eZCegn>h4Jpl6sd0O%@bRu}amr8c)^!_QXni+5R5KkKj}@29z=|_*yRPI>m<%Sb zLwZePb)=IWTg)wy%^-O*AHGJ6?cmv!6-E!6HUtf&mq)J5PK-o|R^0_&C1K!&n0=qo zH`|VH>zE7W^E&CR^wB4RMXS?WEjf2>{#IFH0zOeB%KsXv-w>_^0-fKejX?7#+l8AY zQx6+LqGc|%4BBjh%B5gsKBErtyM)cIT;6Q)HuQdG`s=9BG1f4M2NmQ?9%J6;B+i%{ zLP#w2SQJ7%W=XbPbjj|e^0PRCzQ(SNUwHQt$Gcv^Gb0hDr0}f=kM%&Z&vdgTQYL|~ z)O;W**!g56AHhh8jBV?vouGHJ`6V|pbM=qEY`?^2O!Fd@cr$qT%%a0+ZQ+Yqgb+a= zk1xn`KApfvcrGrlZg48nQQktXf7cE(JCQF$`FaOQ7x%=q-H2RCQTelTBfC=2hbL{S zlcm7?(_G%&i(;BnM_!Q4>n4KVWWQ~l7T9ITONkzNy<6=_uouoUBc`)nuAH4;5Z_urUX#+Z?aRHUEWi69Q3f}Y{gDr+iS5TEN>`3=Rh4qV z^}j+Am~J(hWv3PT6bTDRsy}Gn;4FNK$6aXltp2>~@YZI~8S4s16g=MdhR#^JBn;G5 zA>UsV6B*y!y>}fVPmvHPRdXT6)=aNHvK{Jhl_1~TwH$5#6Xj)${J;5L@hXi(glQ1m0vb@fTEhKhSKn>y(Y+E)wg$e3TAdBS^2p7V{E~5 z%c3gF;#<=~`Q-$jLm~)y(Wn7;s}`9%Yr-*AVzz82Q=6-5X%?%P%y@S>gqmlAGeWrdR(otb@MD#mfgFu;p1N?F3E^-z#yPE~h_JqCem3i#aoZts6bm3{rXPKO~Z&8(Ij+9H5XmTa| zXyZC29C69mrf>it{@WljVW!aE0)d*@OhKuR0opT0S_AUZw^LjfepZ;?DEdtCVQh|J~#4iO*Zu+-(b z^<{7UGARzt$hPE&*tmM<#>E(eVjG_Rtsx;EgGa|aL~+=tk;#Mj?~=5X6MemKC=DC)g@M8D|1W}zxInEl2=ei)CMV@ z_NSp(9QCrfuFV_N(!u$e5dC6=Hho1V9UOgT3HZUak+;-8g@O-NOn>SzDBuZ_!M{At z!ZK_unchR1@9%&}Bk<WWB4~{fpvm>OXY^iTD+ltwy}#5 z^;v-*av1yq@&9A6$f^*-jBN{hBewNE?zchj;2QpG_hu8$XxTLVeqS9`GZ_k9$e(`W zq>fo#$sBPQt>~4l0$AWrRJo-=<`aNfRt1w&%AiQgATn^Fjiu5fH$tu%}Z{wyn*))#v8^BdS!VIs8^A`RHPL(i|njEscM8eSJ0&vz#KBHfc;9AmZK zqMxAsY3{HY_Qw`1p_C@I)4S}ndlFR;h;l06e>bKVOHbFw|2=VEnNP3TA^<#iIlac! zHtO>Ex%YCU+vcA)wH_j@6PzAsFFo`=Rr6<}Lb(+EzL|tGhGU@@vx`&ZP6P}lZZ&Cm zPk3kjYXvNL7%PgO&>?M6J=KuOaD&@*G8oAxHsfB-Eh=(Y#n;47Y}}>D7;vr(J_F6O zG8~mN?WQe;jxWU1dyL(`J|_-*YlzpP`1|`W^m~&k$GHPnZvF+w7u;=4HkwkB<5i3o zacSPjU|EnReg@e|Q%lRoE-Uw>R+hev%LofSfenx{mq#m^^N#A@%HclqRw}jHXKRx< zz?X8 z;ybBrQTsI6kw2)>zM?SN04niF7v)yt_WjE>sjUsdJRFS?sa`WhWoO@7Pm%m*uU&_j z@diPAqigz&?_I1&YfZd71vc7YCB-qa0Eg_SE5lmH5TabZ{%6K*8&=*S+fh!5=HEbL+UX;&g!?TrTg4t&=GA21^dqU`imev`kTs#3`7*s2f`?=ZgQ9o zTFx%+`Lgac#Fbw0g;$B7K&kqno(MA1n7(m}igK_F3j|Ntnf6;~LB2&WPsGVx^GB1v z&3a7@t6;|yBL}|jTYT4;rv?Il0xj?l_dLqpl$e9`rPwxeI>zltX@$<i?WuhI2^%s97E)6EdyCR=639g&8(+w9$nVU;ZnY;fANKPZ6XKuM zxve`TnBaapN#1iBSXo-{Y}5xryx6!?_P96S9oe(Pr+KCs$cj5MmwV=rWX(gKWmjo+ ztsntQKh7D#Iy}M|V!|sZbSnR!xbFy(xwY#@OVe!+aS~ou?JN;43Is)R)6kFE9L#*P z=ODFI#l72uq-?HNJ|5~P_>uTnGqW{oUrNt47`A#PoNRCt%YfKf$=y?h)Sl^69UP_3 zHG9tDytr1#yo)A{=Y0l3CFSX%{hEF_e(665P0)brj!7~Y06p;|_U|kwD+nhCR|5eb z<7N~i3J48=&imCFuBC8yaWFE))Ub14KGEt~aZx@>zz}gOU{Pjo@vbM}GfLiN1H@Tt z3h5U9enZMs@grErw`JV4EPiCgUu%jjmN}eN2{vw1E$)nEc(4->wzv|s++~V7E!`?d z)rlZa}3Hll6-@QbdPZe809#8E|qKg$FI95AIRn{0W9Pn3_zU;OB znL?+in#xzI!$B!>bIp7`-2`=bPVc_cJ-ZO4x7<5lJ=A#m%ScntD)E^50zCj+kgeTVwB#B?|MpOvW^aSuhu7!Nn`z3 z?Q+Sam7XHpK!#S5NP(@C;%bz7L7R zu6*&BW*@jlQgL3Q2OIia3!{EHrvQ~l%3|}e9f;_Jo0`e* zAI^FY_o%&*=i%janTNjJ8GvPyouVx@enW1!Ld{IX{-M|%{wTXi<|gMvA}R8?TTQdn zAy@omATk1*=o&@69^2&h1^~cS#wToFDPL;Ydev(VdHlytWC?-2P~_@@sZAD0@Qx1q zQ(XGai6|D97b&%Q3NcGphC~aiUn-w_lUh1uRE0li9=hY*3%3BUIwH#abkVJ^ZT#WW zXOd_)`WwGTtP7p0xn#R^0p0BR^+Dn-ICEt4ReRt^ESovsKHc#IA*mp16}8p6PFT+@ z%yM+&qno}YTGQooXusSMXcP!%X!WP8#avv95#>M$aY24J;Vm6>=k62e7_BO2a+|hM z^;&%vVydH4;mdjBx@JiEJV%#VcA+fx^8t1#ZPQISA?L#ejeg%w)45iWUWbo51r&~N z0C0chJ)CsjTp3iMqGP8c**s?+TtlZwToN7-Gf3$)c!6#Kjp9}@=iQ! zq&Aq{`a)ZJWm1=qKX4vi7xxxe_;?F@nR?Us`+vc-;OQjI<&HS+`qA9HmJL*URDjQv zb3ULRmCYMJd0i-{h||D~)4}57ilepoy@Vfj11mYQ@Zu){in zNjK&uKSa2ffcFNX*RbDkntsz$7xVZ{cE8(aB3)e>M6LK#iG8`~;iOQRdt;B2%Kk`L z3MVI+QSpoGFBR}Mscol##9)V%0HFX-C(9SdjR{JXty$cXn{M|8p%1J>8d{|^O`5*b z-+(<>|B_(?Kn%c+F8kuw`l^on5H4){a5hG$U9MZ?P}SP2x`2R@+D5bA!zscsWgJ5B zFL;}))|Vr&Cj2DLsnMS@kbl2 zdrCC$a0glopdk4d1a{OgpLXT1%t9CT+?)BvD0*cU;(BxPf>%$jxHai?ae$g#jL%xm z+Xb1AOnE4d-GhB~boh0Wjf0b(K*49*U50W@m(e3y=-QT+}dS9L!R z4c%}BvAJ9SdZLgMy^REZK*kq3fgho~s}LJEdu2QZX9)==5gL^lb}zHn$GASI)fODM z;{&)9kB`dvp1q4E!q*{MTG|#(8Qko%Yp|qNw^OrWy7EV%I>FB+W)*gsz&yxZALVsl z8wZOk09X|u78Xr%u0t?7zYE1w2nfY1y#Y}nttZIvbZDq`v!~&?UDhvnWTEmsnLed# zy4R1+1WgTFn{F#0C22_F-S0il>3%Dufh2g}P{=c{ zIW(j6!x32_yGApw&RBU#uRMN$xYMG_GCMfk=Hu7No+5j}gdf`0H zvDXgmM;zBD-MF>*W^q9r4HQZ2gxv$3K+&sRBlB^r^OGEd>-$wk^1V2uUR?9EOlIZx zIeSmL7+tqn-G!GRqP$a*n`XGTJt90h^>JP>@SAepme*?e~jG19;1Zo8R7YZtfx;GKMfpe zx*35eE({#{dK2fo@8YBu#6)6yJ~YF0mz*EIBA{%mHMn~CP}SD!m#J>L5uT07Lt1d0 zFq#;xYXQeep@|8)$j`Mxk6T}|N^^jO+{n$X8c*i^kqV|6iC`}nbPvjp zF#Z)whOdz~FI&hNPQoA|quWEm=TF&XG~%GXe`9%t9Tv~MQg6Aa`Kj@_OlJM1#D!O? zTTP(2AhjKAjNE5y8D{6m9@Kbrdk%D8I=_}~Vbs=osh!4d-qE>tEW{cG(D7daN-%eU zY)~WXj=}qu%hsmb!zV;=AdWgz-1#_P;~XRg1L*j4Nc6_4Fvw!g7%#Up3@0;ApBl)H z%t0tDZr?UnJ?f7wMio#ToEF=I5Sl{9#mMOV0^uMa6~ebx0&HBoU6jzT#Pv}%?oF^A z7`%PkT#fA+i(h(ECQXBYo|W1@2oi&rOfD-t=dP9i<3|bZgX62IqEW{GE1hyuDVby_ z-vO}aut+;!ZT|h(1MqUB3ScN?g#@D$8XOb3nIe5tyT1bnNnZUf!w*=TB_=^>l79Qf zDSA>Nz15ywQAyzTs#I|&c#tx(O|2oltnMzn@X-)mi|Rk4JF2zNivyf)F|kUMY&!_`)iRu7OJEH*QsO6&>%wLBZeK2CqlLPMG!-3q zY2$Q(wPl=kbg)t}x@yR{x}-JBYr1!n&?wI{$#8r777LF35=u%f8)kM%|M;TcYY`I4 zHeWqg*+={T}x~DE~(}IaUu)$^4A2P)+FduH{sa zs)}{-qPazM=(uE|nup&^wh!qi~P+ zLC)%E%{7P~g`$GQf-c&$$n0$cBGiAgkNtutgXf}@dPd_#eP%j9Bxsctng%7*J`?CY zFNToZWTs&)*OOCWAakD7I~6eXHAfhKu;|(LR6-$X92eeYh~z!&^%XmjD4CUpowodX z%My}&A>_ar&MssX$lSt~_FIgjHZ~jrrl6LP$9>xqnMRxZ=rv1>06>$9k9dL7o2$Yh z2&oNMQGy8n%HBfS!d}blo!!n>hM-LwUMrLLmGUmOvlKA_>Q*s{fs|L(JtX5@F3sb1 z%MDN_gx*J<#lB)ekydt~%GrLz8I@RBDSz@`3b%#?MSj9Qr@!9y)j4KKVo21% z>r}`&!RX+ds40f~HURQsP8}-{njNhyedBUxu4d#vCEn4zKasCSmphk*dc!^`YkuJN z%MqX(Sl=jVgPUfKyK_C83e4tZArv3(aROU&|f}0#pOSL{@f8D zd6bHUf|iATh}VkdKd7K$?qQ*5!Fr>i;pf%PSK0hFzsDmFw!e>WxUFE`KJ?O=?VGIz zd4s|(1#4z|{h2rdP#M}s0ASjBu=QWK+l$tX~AX}k&@7^L$p4N<0T75g8B+O7QH~S@{VeDA*B2zfR{MgUZ1t7X=5X2+{ zzlcaljlDW*s~7EU5tKvCcATg?MEOgbj`@jeDvBI(&=chDXW=QyTo~2-XwzTj`}R@UDu9w3{z{E(N0_1F217Z^(~RS`mOdL;iK z1N`6oFHm`PGT(*1_Ku9i?TOTOwvCY3qewHymS&PhVYhfMWlK6l2Ccn}9tp+UI!=#bWs1wis zs`r~k9lRkYddYI z@!@S;i~fjXc64Qlt?Al>0u`4i8bs;tldm6)_jo z{vx2dpG)S3h0b5$CMMKW-v%X7rSE(0J0Kk#IuUV(_p-%i$lx_HQSX~Y^@)G_2mqd* z_wyh;&o{k5dF?qmMhKEWN7Iw=m3b2FwC&^OfU>1y{nleM}9X3YGQjX5i`S@v)`>o0V6iTHmEWvT<5P61{8 zM|5P=JKrz6KRq7kv?eElF~X?=1naoweqGXa|jU z+d?~_un`_Do;g)*oUe9QtE{HHuc3oprB_<)z1e zbl|RX{S;H6>gwdfcE>pOAU|xDYf!U|@#5StcjjYI1 z7odK{SA`kQ^O!W|3f?+Q|7r5EB%nYDTs7H43=t*z;!DD8_?HXUc2?*9B`3yKB0xWa zo?Eo`N@e^aJ7V6K=^=S|7+~T3fuxp?Z47=TxB`Smd4iHT%a5Lye?hmRQ-UJZlIbd% z*DC8wV4(egmQQ9>IRnMjE}HrWdX2S(ghcFGvCb0{%oecaf%kQeaj$W8^2nQNP5t@N zbwV^sntJ&sCEflvCEZGP2n#?c5O-U?LebSeD)bCmMX0pA`ZkB5WV!DotIm)PVo8ic zb4mxrM$l{&A*VGJ1KMvF8paXdvoCM%nx4)~3tP1zNRNRD6ou1);JOEYn(`$h7AjmR z1B&T6;kU!t0)6K@HX@|P)icJsWf6RTuSR_OuK$H)EiG+-f%&b0Sw zep<_O84kByT|G&~roP9N0q?SK-FO72ddO=z2B|!DJHV>vPPjF+c}NUhk_og2$jwJ# zI6#8^?2G#6v?$sk${#@RfxFSEyIS@mlYy+B)G6Cv;2Efy9LNs_foJ5(_$yQJLc76YV549%25DE8p(32ne*zdVFrN6N?Cb*hH-ux z2^ao))MoUCV|ytGB8|4RAi}$bO}5iS9#XFs;|_YXyAh4MYSD>*(L2Iure$%?M*dt} z%dry;*g+DYGXADU$I#43fG*(C}yeqf80=DvUYumEPHc z(o}5=xSf`inajXf3F9FH!oji~M=ICvBV2xK;ceYI8F&*Qa3cl3(OfJw?`r<3@15Jj z?-HzC9wfGuCK&WSX2;mqejMNgg@Yc7LT_)tqXxhELT`wlnl_oeB9Jd@;cFsys)Ub= zx0#<1*a>*F3){DK$gCen)ofM;b-HD-il4W?L&=nbCLu&W1U0or+mYtYBpL6$5{fbH zoL_dpv|>`40I#_<qMj!&5ZWIKG?|26J`T0w%K89U9i13bms%6Z?J?sCC7p z&SkmY>)+Up1M25@Ml(>5&H|50Vx^Z9Vd6=lt#7ucSse1igchs84u znyxkzKnGp?IK+N~$J;knmz1WSP6SMDrW$;CJB}M@bdkz^sKa_RwUaaCA)q{BVe+6x z4A<708oqu7RIfYyUW!f9OF)vPQjvqtt5Y;s{5&gbWx2BUb8-~cy!so0hOeFDQi2w4 zIk4V}%mropjsrCt&G+$4-;nh10G;ZnTNaHsxl!=Kul`Eh{u$LXu68hPP6e3Ot+=AIHV&{kuoRDj&#OWPw``9?S)re_Geb%*m1 zPT)&oK%FMvrS3~D=+Q-*I!tjpKztAKB*vq)WJ zzxkg;W@`>Y>k=>EV7C)J{^8(Eh*Y1_O3C=b2zFVZ#|OApqOhu0Lhz$ok=)vvL<&wB2aI4yXcwbt+YMTz_{=O-_$o?twm;rvs(qvW)NNRhn z@{%K;rDTMPIb^1R;f&jdyQ>|~H&aSkXg|XQ+$FQJ`}|GP|2Ur~aX9rWrZngQUG%#n z*BvvSVW!lkBb3f{?>HX$z<*dgJx*E(zI;0~Z6NE3LxrB2rE!(GfEOGn(%wq_g*RV{ zRJuyH{ajq`R$z#hZ-85yvGIw!2V?d(nEygu$`22k$6drSeBQB8p}dD(PTTfEI}+q> z&oM4zE{H$u$^0O(7|=9|1~hpI>NkC=U61S^`qxR4BD4`iB4hcVwUumvL0f|6RKF%kT_84t$#ge|hz1k(Ja^V&u$YfVO_R{I77v zcq%7I`B{X7)URVbB;g?>n$*UNB>cl8urE%6+qq(f9R=niDkefBrFtOtp7WV4WCnce(!fY!17H;edA zt7;~k*1KyorQt%BKjc-=Dytylo+91Uz$3I4@xLSRji|M=gr)o}MVvXEi!WgRkZ6Zqysq`SwSC5y``rrSdJ)I9$ZK;oL68u&P5ktKG z2G;$ji;-<=Xi#yY9S&GbGbB7}<4ptT@V2dF9*Wu8_|D$GNkFS-8_J`RNw@nvSt5R; zRS~__gfm3g6d~jgV!!pau+SJj;AaMN?GW~(P6KKcFyM0-v{TZ6<6rWZ&9Hs=ruGc4 z>q7XjcA35Q+omYS4n(rFZL25mGwfnH;sb9`Sf(zQfgZX+o9d1hZ(4V4l2BX+@(TXo zr5FD?WTm(QAzJU|apodub|TwG1|YkT;lg1|^+d#Qad-Y%4uN z?BD4?Q`d&%K|oj-+x)>RPQDs4O**(k@Ul+%2m~)?oibGbXnq{I{Q(l48QK~rWAyB` zoOA*`)w3TA$YyHJzTpE!C%uGX3dtRW)rRTcEjm=1WneVZ=WLrlC+mbFZ|cV5VWwdn zS1ZvEL2?i1tzcJp4i}sIfUe(_xXEyGP3s@c{k{V>f1$|RQncjakA@P;Dog5qI02w~ z0N7NyZ%RrrQ+)*+h!D<}XvFI35E~!ieoP-gfqAzbBH^@>tT(c?V}qZ@a`8>Rb(xvY zL8|&t;7wTIqk(8)!kh>d?~nvPgWIDm0=xkEToGA1(L<>oMcH0=??1Yw{>V?V=*)We70h<^D7+(v>mpmSWTyb@h-}x;XD%VVrRxHC^4^%Afy)+1 znBRI)h)w0w3Bzy06aT(HPRnK zVV>7|mH=VylAen|_7&C>_XPuilm3~t3{*wNU3*GLUjlVEF?n}Z#{F}(NacbUrC5p0 zt4Fpfp>)in1>!brS6V)9eL__>mQglOL)Bp^Y#_H_n3>UFbY+~Y_!%8t3%%oVfU0w5&5rxDgQ_ir^Zjk_2THLq&i4e08 zfRwnRA6%efQbTMp-W0Pkzd>DJEo@LrkkJ>Z*>FUj>R9sGLh55Yijf%r%x|wd{5-|F z=g6vt@6iLJwO!U)Z3@f41Fa-3fLdq#)gxP}_pTC+GTR)c8I($%PIO=)D09I`1{rC$ zQ2p%yIZg>VYUJ3&O}t#ZDTk272#^d*?Oo^{j;BKGX*6pkp6D27v&r`%m94@zWt2v- zT3lB#ieWo1e$J*Ex)kg6R?6Au+g{o=9e{`erjlRp3|io@=Z+6$0`~>KE3MVQv8Zly3adDDF_1Y7YXQ9f!41gMqW3K3{_Z~;+%ml6Cc#M5k zOrBnttvZnn5N0)zOn@+d`hhT8{DUw9ka@PoS*)O^!8E_3a{lXsvc=UQ=~ZiF%ankq zXsJAfkhnEMy^~y~MPHxU^k;80OFULWR95iL`7e-2iJzP;0CF&&$QC0=3in6VGbgtN z^UlV9kY?x_N-KR1jyBTr=~QIl4pdjeu^souhb5McTLW7GQ>88}dZ$MXZzS%QH<$s- z|98xN!QH%3oVrCsEbIKD7yR{=L+S?~I-AL={~Aq5xF5a?$7&%UU+1|V#OExJV} z%baol2xS-etL-1!`eo(Zvgx5P}9!qVZ$Cy#V-@%~lUj<#5I?jB;S- zj;mZQmGlU1!=s~|U1oaxnFU8`PltP0{H4tv^f`FD@@ocWK8RKNj>9c2zE!d!=rSMH z9`aQgMTFHITLiHzqKq3)Ydv103240q`6^#az^80>+0AIqCAnvsu4M_d7bZAH4!`nd z$N8$Dys*8S_+pFA#s0m-O#-TG#|(c!)YH{7ZqlhMQxHF_#At3fxSwU@hJnQ{7FxAd zhcNaZSK3Im7Sw^;PCz0Tsb}vrp2H~ZS|^)XUo8)by5>(Mr*7FNP%`=v(q8_wQW8%MZ*#> z5i5&aKY$H`l>efk|8!y*dK0r_`G4S_a=r@56LG`>kiHZi@uD>g!3`E5y|xj*LDRAi zLrriWG{L<~8(n$f>s>%E`d^=L1E{(9E73mS6TVtZBwoBxXZ>}8*uD3^sA&Cp@3Bui zuSfb}hr+}wGMQ!b%&zZ5F{$Ya)uUe_T|%AFjg&Z!e~IWNR0&Y+{>Lf|w%~R8hmqBe z1Aijr*CPx5(lh<&vbxAOepcNJKo9?M&yZz04G8dXB6TA>jM+g~c)9PTmLZTgG=RK; zENxT0X{~Xu*;Dx6`-J{ZX}u!->g!0KwE5?v-A|U-e%a&4DnAE_D8Tue;@`&sd5I)w z7~XT>SHd_+!0A6NhCyU2>t&|D%91`+vhhJ0 zT*?%Uj86Z_0n+3kxRf23Qeevr)9TV#G`oUDUH{}%?v-qXM>ypK9{HmM@g#Soh|knb@qvxi2a(bf*9`u5A|l{m(r1I<>xQxLx1=;~ zOsQ3Oq(o_&m6Jw$>xOHBWo(#~Q|MPN-X_8=Jfa3pVAPmO;r8rss`3$ajeejk@4r;2UZ0GWmjcxOt=0XY||=iL|72{f?EZzdZ|48UPn?ok#;0a0OjM zNkT_A3=qq=jiyN61Wzk?0iTDeufMAlKG|}(FSce*cNM=L8(u~n-51Byz3;&PK$*vc zKWG>Yq{wpMj)_0qe2UMW+zKm66=>Ls@)lwl7PwnZs4o%o8N9KI@9H{XrP6*Y&NT+Y z_vk$SU|g`$z(;3r$=3zGRSX)jeBDb2E~*3GZsqx{cZMG)kVBmGxp%3lJnV^>Pv^c> zeC2^Q*!Y{zPy$05-QjZ}$pX@#lJlUc*6R;duO)D8PU=0p>}(dn8iI+{*z(StmqEDS zDg2{Gl8?Z-vE{YWb`O=ibjG4OV)pUggPcKm;EpZfTR_ju_7pZQZP1q;n(1J~csHI6 zQF3Wx7Eyz3h{9L!Xn1RV7GfD;3n!a|%}rLvsKH9)HxVip9&h)21V#rn#gT4s|5(G@ z9+D6mrDC0~rsBX=yo5}yAIz8aF!)_uagg1T z?B4mdbjeVU^+OEl-zxQ4YYJ=bM28BpSqTzKW&8Q&$L5Fsd;0re{3yye3U*=R)t9*q zH*{#v)X~mDvE$hqO)f#DIpRLuT1N{!4I9|@taJRwtC6WC_Mu*qcUkYo%P%>jkP{5c z2C>QMsX5;RC~X?W5o8-Sn_$FzXz4?3xAU^M_n1sFNU#UxJ)Z?4W3$_Hl_~HQg2 z5}BWMjgaL<|EIn0j%q6V{>5<=9Tcpf)KLZy5m1m0i3J2iinP#?0Ym{oIs}ras3?f2 z^sYflXrYJ*Bt%rC_W)9Z)DTL5B$SZyF4h_O{@!|Tt@p?GkHc+D2kWA`<6jtMAnQOCmow?c<(4|n*z2=auH?yulwJ{{-KS+-5bOps_8)OPyVG795qckyEOPV_Nxt0v{q($1&pswFi#9{rC z>?AqD-p!N;1-M!^!jv9|V^!0=HCdQ^Eg3}4je<2bd-s^pC3py@`{T_TPG8B6d$|j( zhK9U;*qj=m@l@aIGUv$iuooZW z)r!=A95U5=!>t9e(y-kUb5D+7`5&}v9sevQ_if%$G`e-Y*6tvqs9Wsu;8N9VId%bx zCRcS#Ot@>Z>cf9vZcmA8MfDbQ`&1G5eZ0onwU32G){Qn5Or9G8+AwB3O%A3N@iIX% zoo_R3sv{xRq6*REosAeo&hAWnOL4()p11R;l)m?TjT~Ze92(?tIpXx|yVW}@n>W9j z=d^T+L@@fznfSHFr!IO-3a&d@Pcqm|BXOx${4fiAHWAFOR$ZeFUPWEMlBORZ_p4k} zSB%N#bFo|Z!;`92?O`*!M`urT*qdb9#;!bF+2+hr$Keg(1-i%Gj!`sfetmyOx*lxI ztt)fsna`a(iv4=->E=LPyltVr^idq5O3M)4A)vh$mgHZW7p_auXxKDdL=Ri)7G_HD zH=&altn?vq53R)N4!@6$ylWq20b9&&phT8b#K;i@HpvGw7oTlx%pUZ7xx^^-OC+pE z?(H-^X^nSEQqhvExN0@96ypdV`177vz5*e6^XN=`p2Fk`Y$cc4y_UpD=0#^+h;#QF zrvsY@reD+b^Myvt&R-?uQMDZjTWN)Yt%6X8{BQ0@xyi=IbxXaxmMvNi>U!P7=#J`X z%2$x|s^IK7^ed+?*vruLxA{1cm9)15Dx4zbhf5S67pxWSoI&3lxY=k z`PJwWBQl32heX%OjLQRZv0#kd#fWg{&PU=Z0mep?ve4&tX?E>LX)QKM<@bKo+zi85 zXx&pfUwUjK7jEAPlb~r8W7<;F(!z|s9Ao%-bJPMmfHZrx&)zVxJaW@ubPPSN%*~0g z8SsYWCHY#6~xn zXr*+^zv3@lw{~MqAzWjGV)GR|)i%-S86Zyii6tvbluo60yu<4WkDxiKwvz~kO-4RJ zKhf}yO(XW{VNFW(b3Ln0X>?y5Sn-G}Uh%vbzm}Zt`sCn%MXUJrO{~{FPP03Y#WU%9 zQHQ*;WGI>Okx#CVU47ZaD2q}63PPcXT~GFGV*Se)D0Y%z#s~1OP0jXdWa3};$wpaC zjDu15CbxT%UJ2Kuul+h`*MJ_DGHlStj<)VJxexYisso_fik?qMB6jI%u9W2oLQh`5 z4cjU7MBl|ka?~b$EPQ zH}v8@n0>Yp=l@uS5_~^Z%n;^MVnex-*=*5wR5Gh&CHPlBAnN%8X&ddvs6ZuoaMPy4f}W;!^275({pcN2kWyA(!rT z>>s}kj%f%syOgA@zG>Y7vGn^BdM};uvC}BUZT7gc!XdA8UdLRXd@8W%-s(({S&419 z=i1rIWx-hWbZta zX|HEkmKaRq8K?EW)(KBkByRsVuk!Sm`Ie>QK)H!Hpe!)S@l%n5oJ(s8@%mijR7HWe zBrTIGzNs=#JG+U|*i`teHw|vhpHy)=YTof*w)fR*JRcul)8{Y|nJ__bosWyRc|y+o z!Nrx4?NUEg;oy~7?K-9?iCOINO(X<<-nP^$iLPg<%Cuyx|C_S~(zLOUkzHCLA0F&A zHa12^$+xMSfEE2`KM|)7F9ms61ZP%XHOxG*-WE&^2{M}u*u~DpoSNT>${7*2p#GcK z$g)iM>cZ#ByRx>GrE@((+qqr#xY4eB{!Uk z_UEheGV3h*Fy6sb-{*DzW(}}7Z6UuHna|SF($jTGNl8>kZ9y+hVzc|2x{~{7FFHm# zL%V($jj$7O^T1qGY)usFwBgk_NWA=Sp1J8UUxW$g>b>E!8X5AlWqxu96XI2sw+6NC z&P$+s>9(vTr$qJla@Mzk;U{74h|fBf^bds0s34r`g)GAQWf%kg?n=;XcHQ(C%Ni^L z#w|uKmCk_0ltL)!G_Srji6*V7)T8HFOfI_8cERs|%fdii`6%-SJ7;H9fS@+tO~2Dh zO4%Zw*#5$}oLL=ETVxXDt;`g0pl4gxs9EzKPy5?}G;2+({w(1mYnKpo&YwrAS0(s7soAaDceRUQ zFc@`a;0$JUzk%`*U;iwCk(nSrzi<;-J4fAtjv|F)eFfSR&Cf&D!>TBIy~_1>J=QOu zzB8XMBy_;v4?{^D*{WG{s&5-kzV4mjgVJ%XniZQBAupvU8u<4?K8D6JR?KeB>gnX` z^!>9={}%5Oyp%+$?=zXtl&LmDa2Cr_L(zM@{;LF7Wb45UUHb$=jFgLxuHG_Y883Xk zGB7miQ6ai&R7CH5j=?bvpCz$Z`nG}R6V(1()qfj~4mUY{{1{tJJOV<;1a?PgGQa|p zo213@Hwk zx2-Xwg{~-F9b5^#5;O^W+L4iUk`khzVQI^R*y_OAXuW!iY5`ho61I_K?8%>5&4u?( zhf!*WnAS`wNmwSLZyHKV%jdIMT>zV@HQ`Ro-zQHS4%$t)u_6M4sZ}f1nCmq_cmp_P z!yI!Lh1#7-ZtvNc=1LJk%{gPR>*raC*kxp_CxpRF+Lcw&%7%* z98rk=lqa=<3PQxw&gqL#K(pzT%q#O&4O>}U%d+%s1i}yTtNWcIX#1`^{1%|B7hOLu z_Gz3EVvUjhz_O$fwNf>WFb@-I)nS)!udu`09JlMX@e0tVfKv&_TXQLDaIcvXunv3s zTiX>|#K}MlFr;7)9`eJ|*Eubc6t|02FCdp?Nhrb~dad$}7*BZl3JnN#I(~~}q6Mk2k&prER;jHXx0;08-;e$A8*B8MWDVCuN?f-dBvXU_?i2rQ9GLp#)J3a%m zo@>gO%*eZ51r@{oF8?(ogssK@SX7RG?-`Jkq6Q8ZYBiIg4f94xw^UkF0Z7m!{f9b0{%e2*{OTHOwVMRa$; zFa3-QV4G3=N~32_kvdtm0cE8mz6|A^XINQ@suXV2#hd6izQ zM&$5tK)Zz$Ze%YH5d)@wM&gS3a%`uh?7R4C@Mf#jU?hEadF4@bL`ccJ+04#wYYwaI z(=K>8<56Ktz8HThAroyND3JfAlxeq^%SWw0`11_&$%lINnLxD!YK{FQ$jfa)Wpp0i z_{kG}!}*)EI4v5FcIV^OdR4RtuIvjoekScprJ>FWQZD{YA?JRu;1iY_JQz11R<^J| zQ48L{N3E4A^8tLtZ%-N5v~7`HcPzRd*MB5n{#HH`?QyhIX(SFem>GHchs)~7!t^7r zWUrL7B`H|9j)yfeg|3_sjO@3tUxprjkddnty2ZQJNEhp8>fc}=5^kqtAJ4!87*YM- zKQ@-C3*_0#8%Q>s+Sk02bFXeD!qipvkniJfL9`C(!3!F_!$ba2%6S)vEkz|4t1F-3 zg4|Eq*0GKD{ERpHWcyq4gfk=)$>+IPm)lZTmJhBGSvbNur9EO-z58RqO$q)Bz&+Exqe}z9_Fj>FC|BZ9+ zc|YGiC#zw;bmeB(4PWQfHTDS4LT@;PZWABZ`n$ISJ(6q33?#_CzaT(9;1AjMs*0-z z)@swa=4*2;55jn%55G~!A%dIpkMgq^Y$g89R{Zuq z{0`!l%xuRq24H#b$Or6>%@?9roVQ1b^0zH)ff7FF=|Bwvx^&I9L^ILSY%>|U>CKFp z;a*y`L{a>YRm~qdhCd*P-O{sEDo;4ccpo(NmzNS#hkUmwdHb+o!1!LG%){ofb%Rt! z$;K87S@)nO7A5=`?jdq4si}5=@<>^$m$+M}1U+j1wsMtdR6eyAIK?gH1o#Y{vP?0X zaxsi@dKwC<`7!+{?gME8?xsk8K^y-IJ!T;qeD-sy7RyNX)lwz8JN3LqlJ@iH{FV&+ zR%{9QL0-J*z3OK$ii*)n-4Foth0R`H2SbFgZ zVa*M6B}^KyDc3z5iw>^!qzk3wQp%qy72~+fyBEQ~2Xe-hMmvZ&>kDt0u2qLV1{X?G z>dMzcokOQ~Hwv=xm5Z(yTY9`k=aQ$Q;`KYow?KuxC7-rzKpz_J4$$XBqg*S@5;&r2 zk=KhiJ!Nfs_TxK_A1qY9Faq&=xvJy&XRJ^ptb$_7?!KN{7_KbBIP zO+4t135PHi7tT=Co~KV2pO}2Gfr{{013rRxj}8Ceq1T_qv6rq=cN^I^KyZ)EyZmzb zNNPlxh6KiD505%Zr}IB*g&&U!rG;xs~9Wg=N0O7q4qXEYu>7#Ppr(p z9v_(5HnY1Zr8d0<8jAN>>V`I3d-SRuy9l^pYH!ayY!Riul$k1aMh700|1iX`uVD#! z3MDFBP>BFfMcEU0JUnjn3o*IR+?R1FPBz-WAOILthO`Q1N2SaLJ98C~8je;dBo z0CV2+W^slKN2~q`h18CwbLMF`uiso2xKX41K@y`gcq4$b=~~vZHjWEwncgD04>hEo zyAGp%k~{JSRW|Zzw%B?2PsE^#A-Us49dEWc-S(Ejb)^XGPZB^QD^KYc$P`l?yoRwC zjUzyb%nRz;wk_;@WjEYh`brL>nqBIZoI%*BkwX~Y`>@D+O^vfI(tg_3GBtoD=GNR^ zhumK)$v=_4qI1&Y<`}3lak}^mlJ$jWk6fX$77i{H3$HkK@Uqn!$;gM&on;|_*mG$B zWt$P7e!h*^3w%HZ-@D>!9(999iFO%g4M8SYnel0)%p{+vg3EpiwUhy*Dt9 z^MI^vW9eeuUzX1Lvi)GD%Wkk%0)6Z)YP1kn177K^q*7i8izf&Re1QQ0MCtZBsDXab zfuYAh)B_!`I+)c+M+D6f++yxs684Ea?TTuV%gp zPUH4Z0jxz@)_&<@hn*+p3_0CMp7hH_gOkISqYCa(@Tm`?QOu~`BK;}L2`f)wNZdYEY*U)(OzLXgU#c~B8BD;2bE<= z%99d;?;=_yYhqUl0_f<7DO#9=mum*%T+}~+$_*p2&HK3rhpEp4DHl>QotnaoozmSn z^JpD|o?yJOGa0Z9P93)G1rBPkXmoE;cVnla@P3_Gf3P8N=)uN^R{7Z!UG7?vU0+i> zq88op9$aUspq@Y}G*3l^D7>lra7UoA;U^Zqp)a@9Q3Aeh5qFZe2V7c==#YlaKs5po z^S5SyJE*}cnC(gO8^)gVe3w}r23h9BKFaR3=$uh=e5T!$lbXO3B&x@N$Wx9bZ<67& zQxnNG{qsPSB^50(~yk-K_6Lm-Uq)9EFAG~-*Y2CuBRFltZg>^hAn*a1@9 zto2yzo=XvZss`*8Kl4a_Dh2+X?xJrzUP`f z`Mcm;?X8nGjUxm1;Cok;l%G zx=(EB?ZmZQmXe>dADwaupn7&?|0Ba-Lv4QB+5So!ErWy%UWPErhot8}iu|s(>$M$C zR#~xX&m{Cf2z4avHX@pIrwiCREf;QIVbac?>K6F}Uch#T<&5S=T?sdud0~F=;_umt zW8|S_vb-#lOq_>e<_NH%fY86I>7Ahy40|3{Gx!;^w3)V$o`;wut)s+Dm00cU()pb% z2G(o6=!wLAftJc+b4Xd-k&`+bkpP}#p!}%%UI|c znYues+iDd;a$@h`2`{oA1DhvZzMGnvkFyRCX0;X5&Oc?T7O1_c>|0ib;c{Ah&p zu#+Yt@DCBJ`172HM1JHdY$*62XWGahWth|0Gl@IN$GSOxD|>cvrkk{zz*T5oZXkBK zF8oE}M9^?pDHl4j4s$lK7BQhRjgVjp{Nd-m3Ln5#SrzLXq%`834D6Q>9z@GWKNAAJ z=-Hm0f*^O9mXt{(cbOd&TB*k)=sMj|pDx+r+<`m14{1%=G5*8p+l0@3^FDq}6#2r& zUy?VzYuZJ zq0ERNJv}{oaaNW%^V42!!M&>T1J|=tv)W83p|av7P-)!UAT_ zYCq4@tu;u&P#p_rNOjz5vqeDA`Z0)p4K_R$1ug{d!1wet#z>k_9pi1hb%Cd}q^Ov% zIY&pn|2onhu}vA=NO`GVG{gQk;KqF|*HBSDow^d! z`#=a5gX&01?{)-wV(v;!oO?6&xNB;zuT+9*0W|A{&jMYJxl?xngZ@efU>%^(XXRa< z!*ZJb^MfcJS{tc&=YDZb!?u%9DzGr2fWadQ3JS&$hy+mDyfaEaMfns|6&U;ET2CAu ziA3giyWwA$SNB!Jf|)iW3XG#3G5^jsN+F9<^JhpqP&X%^_Bkw#pci4 zyda=lc4NOy0hY;st8hWx5co)7$zTGNX9*m;T`2Xd59YI$LHwYQH^cI}a|qv$hh6IP z(AE4J1-4if#pSBI-=MiP+Bry7FE20e1;e%{Z9cbiLY7`RH9X6oDib~fvgwTl+Pb1l zf*K{7&ZHEMKV95AbbY3$VCe-9?3k2Zm@qU41GEh7=#r-{fBHn;2l5zHW^NTa_4nPF zm>A;uIjcNj0X2VjKnd5>`5rV%7`B1d^FidwnZgM8PGSk51{>X|CyL&4>*3bMkEWm4 zDm3jXd|0F-^+F_nCdC&hv8@ZJNlbiv6VS#QC89PFV}i_fA06Zf?{lOXTwgoE<|3CS=KJN}Q?JXV`mPL(j5v^Fy} zCDsAGw)X&#nP*gF1@;{M37`vh?2}SbQe9CfLpxG&O(N?Lxr!$PrvFi=$b+W1r>PulZ-s=^2`gu)3|-D zTrQe|EVp}iB&y4Skl7obhPaRltLDSulIOoodXJxDDBU5qYT6nl;DvW|9k%;U5TNC* zRr(5Ge`dBIU%xibx|E0%sRHWeBeS=r_E_EZergzZ+s0Qs>QNL?R|-;yS89bXM%d%m z!n+0>9X-%bK<~U#sBhZ`2UFk}nn`pLuJ`E%scD*Nxp{dspD2~d1Y-OxgQhazr?}fW zHk40$KWh7iZM3%41}*JXS^Th{b~;H}{Nu+$+_`-^Fk@pSg&dKqtM|it*7P?l0de-y zhLn&Vs+V#9sVy7?km^kKgcTBcwCRj#VbJW3G0~;W`3580HaayMEM4V47Y47uu)0 zJNE-p2w>P}OhG~X8qilDG9XA#l9KpQd3n*m_dwHi;sz;)G=zw+{{5CD6`!ou*7#~_ z=A-MUE53`dv8ic{pEgDnZ(IKbCR0*<;5%9Ic76I%8q(5Kz~a@gnFt84jsx1L-%Z=; ztAEeJZrj>OxzIx>H+w+4)D!`PMwBo zqtAwJpXRIX=NM^GB0NfqqlsuY&??Tzc(<4YTiR5IRO}K`HRa)UO-r{*4g#7@9G>E^ z?Y5h=DqAVDDc$9(6`bhSJ=}Xpq{9}!yP(5Z81$|`IA5vm?_3i`D@4c?~kMH`PKYZkH&Ypet?EAjgTKC!ptE)b^N}K}Dg22+=!Or526Z(aP zg}sxNgEQ`YlQg*L4s?_33kx%6YX|$A+SYa!1lm?EHw8p)syevd6yO&Sy2&ppE+ir@ zaQEhYm7D5X+Q{rZT>^re1Sq-t+U`lKlc;xW9UgqUO?)L!hWeF+YWw^~2#C$oi0`~( zYzfQ>AWEsWW)>10xL^CQ_PcTpVt^iF%S+p>ffmN(_XzaBRqpm%u}%+2zIYh?>m3CV zMdm%fbN32Xy>mP7w0@mje0L+5Xe7KS@5inH>&i)n5UEkEbmYdZ#tq^fbp$3z%(%&i zfsT&uVbqf;Qx`+|rbwFOz!OFvH*)f$-V@SVTvJn@yM=x_kCL-E0~}2oeu3ak3xOin z6a9;YE?B&)o7;Pf8>KuplDc7(o}QlHHtDSsgc)(2vE0?}c$S_NsZeZ3qzI#fAT6`M zpJcE6a?$Wgi$SPlFI^-xTCQoDCiIaGbx8WXC^i=}URuR8->K9qREH!Bp@wZ^%R1=*R*$ zrqE7KWq3W8N$W!S1CNAkmOWYhIC!|i$k^Cx&AdLnx@m7Rz7vNN?$Ttf-R6^B8D{HU zS{U-41}q5CGuWHh^g<|ecAt%fg+&~8fnc+@CfLSQ^PBCvpr9awdt8IN1@kNwd|XLE zj)!{w;F{GSXF11>f(ijHZFObhU~nNz{*#WHsNqN0Ije=TmtY(NU&ljHr_pxNFGIHi z6uHWAg4ZZ1`!s%KCuO;yX2%DtG_ot52+sqZesU+PA0E$)BmS?!Tn;9!Yc48AKs!da1Gc6zrFpM$&rx{ zb^KGF&UMBg6;-I ztrn}$h4NvP)(IhO0WQkHS6^pgJ#g>Yg7q{zNSZ zcGqRH&_;7)&2_e+1A}?{O{mvEq5&g($KQ_)mCdAXWuT)oaCJE=3TadLkcr%bEDKgp zF)}gXZ!h{Z%<(1J;;8!suX(c&Cg|#vBl~z<&<(U4G2xKGd%_Me5xa*}!2yVi82HE9 zP>u4!Umfh!y`C}*+P9W_47i7J?B^r2C9`1lJLdR;iUA)E%3iTc1nDju)M_^26tDkO z3ye!A>Y9=+C&pzD-u2f+f7oF(uqp8|F*VH^Q#{fxTSCR}i>pU+XU}3unZr`kF`~mY zwhIygc4Nd*VDm+=+oM>s0{EU&fep2fjT7u=sowtpexYk%+m|g^s7$gF|9QN6A`x5~ zGNp5h(Pa-nC*1~{JAE*V{p4AwD|^6U-epQk%8Gl5*E=c&xWZ=Gn8A;QpWzx!DkIsb z0`P=-UU=wBFv6eDL6nM)+3FX|kkGEaA9(a@trTp0TaA7dIXSrpVdpR_W*u4qUA#Sw z6@pyae$N(PI6!f9&U~Img-!19VS&%+1!i#NCAnQf<1dv)t(QBwsYbIzHbaVnrdD`bZa3IyKpV!2-3}VYP71?|_yIzc$ zfYiv>;oT>8NpM1USrmb(8S6wwwU+WgTlZ2hGs|1zM{z7DGyS-q2BB;L7W%3<9=40W z#8YDSjTEmEl=-sFwZq#l{@PDx)A5bMFNc2mb@7XiPK&2Z!-z;>M9CkzOv76NXH&|w zKVA;42cP^jS?}R3FjlK)BpZr0k{bEJ0`YF?1S>cajpAc3L zFU?}R0?)~A%rkMWUy3T4vEK`9l*SafX%fP?qe)djELaJ(!#hmxTK6HN!B(VPI~oy$ z_9vlBL~Evc^X{A1UAz~-g+7ULm$|$wlv&;O5!m?Y85zgvsPXc#$X#(rOCFoSZ=cO4q{*c*4-`R0~#Qr`~IrXK&x!7r)#(jpWN+f5HIH2#e( zzS$+1d}L3G2^B2Ik<;jyYPRX}lnahX1l@{Rj5DHfUWub~3vcqVh&w`5bj^s8p zG!*qY6jegR-t;igjfDQvjNRP)~EBEFTB zZ{~r_KBbBK?1lH0nme14y)^rtE3P!H<7%4bVVoi9@7+bP4S`N%82Ec16CLU#r-uVD z%m)nCxZa(z!Gyf7u8w86KAn>Sc`s+c`oHRK(@=Wk#n>YjV-aj$HNLwgbUZUn=>^_u z_)C!FN+q8C$cRg5Sg2*n6W8EG^ArG&N&80yn$ye9vjj;}p4a!zb^6x1Us55d7#fII zCRY^aTHSgH62NMJ=XdwvB4gRA@%E2*Ex$B0Ou9=hWqz5)eKp{Yf+=?7^Iabr^R9|z zLv8G@6r(*o>2@aFnEpz3EXtgC)Nha3{4~hOyKU>>kTJY+-zFUFizHFUa~>&JXbmEm zWFjPR_18k-*BmTG>CZK{^8MTTfL|}k$#oae8cs$iu$4UTNz1!klF6^4_3x$B1em@# zDs6{x(!L5HNKH`(^Ab}XoirY$OzYcmGBEj9-QC?7^j5Ly*GP(zlA7Q;B20|@&qxG)$ER@F27=4aKhXtw0Gw@8_-$3~EOl~*%-t&+QRF(@OFa<-VX!uR zY&TKuc%GTa*4B2$8|TSXWK{E7DV}$>TV&dQh<33j8LX;2SlI1tVew?L%Brf8AOzm^ z;u}JOAfrDk`X;&VQ=Tw+LUh=-YR$M?NlpXXqvf;DiP2YFU0vItDnkmPn0h+D|4{_URrdewWx_fbJ+J8K%#xb!o;&^%c}$Ffdo63F zwq`_1iyuvv$+Tk--|UKS-N12f)w!%JK3Fme`PaZHkb>A=o%*IytC*u|N`rFfWEt^igJG^52bTR-l-7IN8$Ox=OF? zOgQzboK)4}8tL4oy{n!F0|2i1!S->(>T7y+?y5}dN&9!F;G_+n#_~z0uD`%F)^%>p za#5KKg8A*At3;yZMoGbh0e7H#HL3{eGL<%ae96|2EdxuaX*uZFUwp*!Tl zOdYXRk+(S8aZC^ecosq#M3`oAR}We>Thq77~qHaa~0aXrI5$j~3`oGciU zm?b|BkGeKH2O7z^?mB6nGKDa_mO7`4j7?cxRA?hc(IFlqxY&MPl2j$L?^ybI> zeh>`=k4|~MN8IxFOXtiU{*--+#bz65zB6@}%4xvDhYha~W|$K_o?v3b#K2iY(mxzr z&NG&q)4;W}zHgi0QHXZ5jI?WV{LR&CHrFjH5a%peC{#W)XBX{KHKMmd>#)6;?pv%~ zZ`f|IQ)@VkNLYOF$`NzIf7DBLy|33UWzmV|33$IQ0XCGt4z88~Jd99RWLD9d_aGab zVbD(2p7-E=L1WNM@l>Dvg{5BHtx_J@IE(O(5QHig^8js2&Ze`1N@+U&p&k8Jt*mP*Ty17 zkv@kn=%SH?1JOV9kq6Fe?9+<;@@oSNQxo+G&^kP+8#@zvdU7Xmm5|cL4}6nF0fHl9ou&Md|rwZ+l*EE zOD4N-|C9kch#>3Ny?!Ge|2wj!*3dT0MY3^JZ)Hq3GeV`d@L@YCb3MANUU=&~DA^Kj zgxlNOGYx?iuItk-531zGXmDx&`YCGF%-D2{Xe;YL7{jUC?gM} zGVyx-c<}Vkm8~yzb=)s_L(}htQOawq))oH9fGTk)PZw?EErwpt$Wk7<YPn0COz# z&H3Sv&*D^;;6sE(=!<;1eh{k4#%>sRru7(vlJfG98Zds0Aftn;(fjJ()bfNlsrsGp z4ie^1JW8Bd>cZ~Eg{Oh~K08GRg?B^>#d@T zKi6E_Zx6C_Ny176?*nAkv#Edug;lb5M{4HBT`fH|5v5xJQ=U&iAh-|XfecXdGg5&S zC=2#gq4MRM2r@G(Pg&?C?$1@Yb(Vt?FQ!_3Vx;oSa73OEOO~i+{VF+$O zngxquqs*;?vxXr~6{R(ni$*quBMjbQjz;1bTv~ZX~ygYAqaR7ET!R`ug%EW+EUSp_8~xBxn+pE7LR(m20E|&?f#p zR=Hd~)RU#gwsz%| z94_Aj_x_uL{c@IFu!vuH3?grcdlgyTeexcJ!NVR2_5x8Y&Ic+_Nx}0$y7F@L#m}E= zaz1{Mp0VSVb6Ol9gxw3n=5*Xita|34De9ry`|&i6sSye{!=hnX<3cWjAYxeFHlJO; zK>`Sio@(2!9QP*|PXdTn(S}kY{P9}zU;=(1_Y9@hkTP%J5fIM_3xZ}0i+T1aVX&yb zQ8vleq&xR?d`e2J8woY$;C9tRiRjkvzX#3!;w?{ul7AHCafrL4qyb(gZ~v~FSJvq~ zJKVSMPtq=1l2~y1{EmR$Mm0&9^0priCd_wRDCL92X};rT!vyi~T`7Jx8Yk$=5C3tb zq>w>bKJ>ij&ZmdCZn40;zd_9DJc?J|p4YRX3x5=M%RG!9v$}$_DkPT*6$4c^21$HB z69H&M8+^9GL2}5pJ}*zs9Q+I@0YIKq#f(?}Z_$)s@EYPel|nxO;99AvLk&LcI)Z(w z=eelu{LT;>Q`hnTS2BODR^;fyF4XU^pcRP;FdON! zoa0Qsc0&uI4d&}PIj$PP9qvmmn<(X@JNL6-+F{ro61p%$rs4aMxGxssw)GyUj;Lqc zQH!M!C1Kd;o8G*`Qd6tF@+SalR)x4|FWXOI{ko&-jk}L1%9ArId$G*gzy^F5f(pH?T>>z9X4mfg)cJ>%UHi1Z1kqPwG=b(YZ!~n2v4kG5 z7PpHRMzs~mZ1sA~jmjI?K4756#89^WTWgvgHN-&BS1CqUl{-ydZ|tUmNvv2u@=CF3t;Z)^w=BxlJW{Pq zRr;a)tnd>hhmFdUo`qFz%gr{M1?08Q`0~}=gV#p3NDzYg%nCPuU3Trdo&b;{z2zQr zXZ>TS^p*47J%A~&2XyBzUeuZYJqTSw&bg8i8E0&(uAQ$H?2K_A;j+}_dg;@^B30&$W5E`%0iDLe9Cu`Y8YuJsl5t14^V|NZ84 z;3=QNwdbb7hS{J@Du(aSh9Jt<{ULBmo2c)7<&_i(O|EfPVYmnrb!@}kqGD}ZFYZ!B2MCh2BN0o zIN;>=JAetRaZ8Qnyt{m=wZv5xd01I!!u^(Zhzws&L9fryy{1YI5E+bnRi=T zr^0V;l~0!#TWIxqXG14Ip8l(6dpmanvld*0dW`6XE zv4icY<VXSrbq0(SJn&abSB^5MI`q#!R-S+B5IO`u=a@n zt}dz}19#lwv2hhP=?ys}C1uMa&X99vgdH0u_|8&Eb&fs*wQWxET|W(2yYu7tYWPqG zyU?I<$GF35DTjhm9)Q0A?sUlE3|aDsfzOAeQ!F`k1uZr(?W|GAjfFVbznqPI#@#$O z{=G1&^?z_YOz^$d{5R}#Y$6S z$c{BVVV+AR6roytfAgPH;^H2dc?jU@p@IhJE4ES1Dzvt777uBjU%^4@`2XrU9PO`3 zq8}IRthhL_OP_6xEm?N=NMS`qVbB&(!T{>yDQ3n5@pQHEHVzp)(I0Z>Spo~lnf2~8 z@CRT+1|W;}>n@j=^_AEQo%S{AcYYdtg$M;4{WuJ;aUi|MS)>n3KK4?*waoj=bXHxF z%|uE`Z>K4H5c>k#5tkk9wh6P13JT}iBI=dIud>`uUyspr6X*b&aFh~D!1q9>E>aCz)tN#>ls4JFdABF?3Xpx-WQ-Axlu5Hys0))Yt|_8)buwJuwG zF*&Aa>|kKi=l`g*@K-UdpxBam_{VzH&yT~DC2|k$g*g_v7aCcme_~IR{d?C93Ken8 z^k7hQ0Q;I^*_h7Q*ps{8z5zN6#qJM#lgUzg5a(t=(QcNzA03&}ueG2QXlK(c}#B z8Z-|s68IvAA|Z0x#UuvMX_g^U6-k-|plbG!1Y?EBjjULnmflh!wpuvkfogfyl5~I~ zJ{fsggZmyK!d)5((cwXX?|P)s^Z-{45c7=eDK>3)Cw#=ikIS*`$% zR4=Nge@ab6IH|_N1wL%z^dWn{V0(`A7MJAlF81Mo^Qb&~y35^l<6qU;-B9+mmp8{jvQ!cFzw#+Us+@>3F3n!lx+`=X-L{#mh@sm{#ScX+Qn-hi(t7^#fia zAO#Hd$Bta)kUvKArvbK|##AnfP1Ji|@MQzzdgFmT5E%jQ^rv{f&>3q%6CX6x=e)VR zeMhhaD4!soJ#la#PgcD&B%F#CU)<=-FP@7?Z~HRc5z1Fj;Eh$t0KF2RioQ%exOxLk zLAGc7yU&V<0BCjd#{Q@M#dmBdh_z1w?Fm{4Ai;jAs2FsIBtx`ZLiT|@_a^+xMSjf9 zu2Kwo5VXBmaI=8o$K8rz6Z=^Wq<$`Lg zB@l!T_cp7Ym#9p9_AHEQoi7*H|0PjP79X5>A3k^_*}EBVJXJdhbzC4}phpajmfQEx z(RtnjUK{kOBi&|OFZ?_329^9pH+RT6sM9!!K?hK%$K5I);-2g!?-C0v9b1O z*tg+)DHZls*63)K{M9uMy6{V3O!_qPgjv6ghKcIR%I>j|0$XdOpGzknjb7aT4{3LP_wy;lY;c>wY4=27R3?Zkpi^LIG7^lKP{6w z3l@gh?eGnLk#pgHUVy^~l1KjrcE3H4ehqDk@$qqWMW9Op^3w8{pil_NceRteVBLT~ z3i=*z3JdS>m;)*eG#7%iM(6*Btog-0UP3~`CK1+?sJHq^M~AbE3N%g^$mKO2gC=>O z=tB5PwfU8>ijgsCc7g0)C}#fY?$n0O9*IR><&?#dkr9fTpYayKn-Uze(L@S1tE;P@ z%1&P#G-L;sg06@Hp=gZx7FFovx%Z-rn5O^3tii%MT~;`xYRL5mh0%1++^ISilI6t9~5V z6I}xD+duQ(%RpdGV$GI-jea(R5?o(HwG^ z7>ZVBbMq7*dm2Z4zk%9`po+~^yKC+jZu;YQvgyJkJZ&{Q9yMLN1>wBG$c@Zi3vcOL zbAvMaZkuAZO$W=5nnIe6#+%w3cBVodys&h@fzWCxy?NvCFW-s4G5CYZ_b-R zo~ww%Uus9cA}b;-%44$!T{svV2FE+ix+`zwViOC$vKO87l$^8yG6OQ&#A#_azTbqda^qKh}lyqAf>v`zkguA-{igVhNQxuqI~v^P0bCT}UoF%f)Titeris7f>& z!;yT}(+YxPcTw31lB2foLE?WaKpXT52ZQ?7%bzVtVrga0uE+HeOMf!Hc8Ugj%)_v~ z8h_v{VhR3}hESPT*ow3p|?4ewhO&o=lqvq%E8+-z@(x;VAfQ16P z8~n7ZT$rnE{z;@r5CD!W290nGidp$UvtT>c9rbTSbvJ3nh=ukumCg1WZkZWwXA<^pg3$Lv!3IC6@ znqC3=pa6dUm;h)qofCZ4!+JO?@N>9a3hT|)mU#qeyd{S~*ajk5qEMvHg?u3vSb4=9 zS`h+mu9P&zwOWcs#5pBl9}A=z)nbLIJ-0_PBZ{RN`!=~K@_hf7+35a z@tFsctG(>qjXlkk{XOoQ#hLV3wKhCl+9V{Dirk#&wuq~G%7)g{hVQO*eyE~J@H=Zp z*O(Ir#a{YEYq;_=bDKTjrE6-dMf_WU*NE?3Q8%b~vE_K6XjFF5kJh)(->@G-TT$&4 z6t~Gag^s@|bd?vkT~nmHr;_~)^iUxr7Q}py>uOe_X;8UUp(;tNW>Di^LpT^M$e!b^ zA6)VizmNZfz?uq4&b0Jz>?x&_re>Xy`XtyK!2bHjd@}NE&x39)wu0>0-vmP_oV1_* zRW)mOIKzxVj(>Oc2)(>`9^`(vTu0uUPdOE!o**uMGO;qR{wWtB1Z5;3xICce6P`t0 zGgGwT{EQd8!*u$5X}h1E4gkMNT(FFAh9<2)d3fhL5FezHXQId>>9qRek4l5b>TzaK zCY?WLNdn>G@8)vO5ja>#+2v2v>G{p^rx!=fH?WbYNY4+t2nO_o+m)x{dt+%7e2O*d6cH zIFSKso%{kJ!NPMt;PkSdvgS!~BAfEGYG?}9Dcnkv7_<^hz!XMzv2PuCYePO0x=0~9 zK2$=}o8_GYfVci^z2rZaN_RWt97Hv@Cv|`K;daal1DuK=b+>*8!~)pym7u2skQfMZ zpct)lF!D?H$kz^DwbsJhXBSDJuRuNy@VUTOBF53*YuP~^Y-6GU+i2ViCMO{NPqfw1 z!Qz)~)Dp4*vjdG46T?swa(hu^5M@Adwq2GrLILy?A2))c*=HTiMwzdj^-Gjd{EyAm zh4cNur?LAhoCEZ>$wfDRz+U2j@&ycfD1fjA_M_E1qN;!PGA6d+11L_RBnv9diEK!C zcsu?^aU=1N%ZQ-O9nj75PGc;mVOY^ct3lI_xD^Y#ot2HwmeUlKD0*nLi6jONnh3M4 zJzE1QRbX^^>=mZMXvly4_C-$g;{j#c9|aug%QipFMtQn^^D2Ay#lq`zP-f<7;crP8 zb5*_sVXJi{A-wyf`6Iv*RG}c~v#rsK4!V=8mu|ydAchQw% zdbdo-OOh4Z!m4dwzyIL?)(M_@S?VElwsS|#g;2A< zYv@A4S1!b%LsOajD8ejCrJl2ofzpAglV6t`R@~b$G0C5HfrE5u8TS(x! zGdz!Xq^rsx1h?N#BrpiyA(~S@{RJwFvc;3YY5_BNuPYk)^-OENFvSYHP+sxVx^}gn zK7=7$0eCUfIUg4Wq(1qk@&f9604mx!F0*Q1NhUo=UYcZ+5} zf!^Zr(Y|GLNIJpu>QYAG6it%*H-q^?%=az-E7boapS{wtl-CIQS7XrzteBi6{y=8| z=BJG*HJ~&M9@+P;&HuN*r6Yl;bXKPcKIP?Mu+;JhI}Y8)phQoj+DMq|v9!O+fqMR^NxXh}u%brsaPh{mVA*k~v2gnt&KY+zU3Oc%qR#aco(L?cxd zpep{(;znn|c{@Snuy6gamxLWJ%7D=e>fLDRxqSn|?!{_gjRSG#rYaH&+L~0aV)eHi zK?y$Xicv+RJkGWxIK#yICFpH4s6ZwYw&QCm1M6oJz#pyPsTHgAywOy{e3s0^)2JTPs zILvIaf@jLMDLUlRy?;iE?dRj1RNgT@Vk^Fkz*H1SEcuv3cDwkRmJ<{7+}A%Jy_nu{ z9jW)w(0U7bE%|BmV8^X9U8TQmX143a-`#2e^2d^4PjAEsZ+z`@r*Q-^kbWy@iZ$+5 zjBuf`_r!AMPv;k$g|iQ2<$CW}gPLh2X1*{RYJRw@_s19~Z{wo*xs;xtwuFaZT?^{B zc2S*Ar<0MkH=oV-*X0Ocr|X5ioeerQiS_l%;btGS&*Kr%NJnf($3>qux6?Z5fn1>M zr23gasuFj9QH z0wju%bD%Jn@9`mo(k4-6!ah0tVI-iH0zr-_|CdU%Ujx{c(wYT+Lq=vw08q3OMV)|;u9?+FuMsFtgpOPgheY2XXll|xAX)Ys@WJ|0R$yp|e zYU^Z%$=h5*KE4`-jCT7JHhY#7R0?k2RQRLXxSCFHuo8_-woo_7pe3WMekBA_#%0pj zH+%}}L#@u@p!TPY=H>l9z6E?hdAB*UuB&H`cl@1dVz}EykfnZg|8pnR%NC2zSWuMV z*v4a3Z^rF|6JIybvj{`{tldj$$h!?mjKE0+yu`e>BDy_gj>>{ueI#^rnEh|MdTk+4 z^oGVj7KCKqN-8wWj=M~TX5lG1(s^=lksre;Q1r`Ap5;10AL4@hqENB53w>dQmCUd~ z=mNRQ0=JoV^V-&@!hoK?*7Uix`NdLYM@Rg&8Zajs3?y<;5;0DTLzW2*7)SxkD1t(b z)ipCgdh@=oNN-z%6>oBJ1DiHDc`Pi>;xfQ8Y6D45EHsmD9TGok#6AOMIBuc5P_Phk zthEC>P%ojdob=@*D3%wCh9bJTnLiCAq*7J#S5$AC zFeu$Nk@{3*GdW0O9PAF#PEE`+ZWm3?Q(w5b%Oe@psGyt*1!6)ByaaoGKB{#Tc*Y%E z(?3~*^9&8UHcQ-He^s&hRMXe8oYZf$?yf*J)V_@;5j(-`?m_V3h2diZdqllU|NSh#;SbJV} zORjus`6Dtp>&rM;vfBAwN6y4g)h{lz#CGwLQQrC9#n%+(yPxCRI(^tZJySP*#CtgJ z66L!W@7n?lsR2A){O~Iq;SOHsff(8urKBXcax*5{jU*Zt7a1APCslJkneF*-5wmF3 z>KsL1l%5U#r!4tw%OxhcIE#UkxYSs32g zvcpcQVsO0cekTg)IY*?O&}v-w_FLw=Ki_H(*6Z-I z2<`zR76nDI@z;F51|sbBs*yHGg8+uwp@Xipa0FoJjOMIsXQJ~J#oY5JM{kzT%%YRG zzq>-i37Vw;BnA%EJ=f)NlX%m=q0K|&0@2BCr~bdd`U4#;Jriz9LLZn8`rV-<4)n3Vs1^* zWmn2%VH8z~qK;yVfke2zQeab52T9OKz(8FSrKLoOHJcR^6Ix{Z`MD7ow9m3+t};P5lE=a%0R zyx}1;QClCy_o3^hsJ|vm@xMOkFVb%^rb@Z3PfP@W^FiXEn;}P551g_zffZD#_QdTNgCx4QJEMQ|YgAS6J~@qi@0l%SLHpm_LAh3+bE`7|!H9f&&M)DbG`d_^oAE0{)v zvHLW>HurC70B~b){;T@=?78xx>Xo9p=ZCwFkU6)wasM{3#XA1}apP1@2UPAialifinsNc^&|X%cW~gn<=rWVBl7TzC0!` z4%uQVHtL4c&_;UtPa{>9cVjdMurWa#F1C)Ee4uq`&qsyVbL$G@1!|Td`i~_2 zZ(etBRo1Vn)a-b_e5tFN{g?0cZ8m#RIhP}G=Qw65j~6fL%ZASdqw}%tVwq@+LC@YeguFe*j1gy_LbaRa}PO2%?(fnK>@3D2;yq)@++=IUJ;t_D5Co>nU&w=G)bsrxVH=1W8GR#l8dUHmYazi}J+Jrk0L5*8k?R@*%KR2GJs zy^T^!ecK}t6VK;Vj0DBuSrSu(x=9^L^y0Un89aWBE#P|znm;j-v)D+1Gt`165IjF* z1iz|bQbRJi)LMRM!`@7LE1(n3#-Yjr9I2DWZQmP>Kpl`HU6cYyMNj9U8hs$uNcv}M zn`qd%dp?WFKZRTVw0iiL8o4@x!K_pQO63MuT5O%o)ROdE9j}{%cKPZL_krcVa~J$y zN4^6x)aM(6pCaexE_~p5Q0oN5_%e!>SlE=uMR664B$?jRccR4}oQF9yUXHf-_O!8P z>Zwf}Z0d5d1vc|tDCBMU%I-@FG+@L)>%67w2K*NLp@>H8Zi24PpkRuep<_>rC*P1Ra1Vz$PNO@0 zCT&-9S5&zwHlX7Z4>VvbC4N=KmtAag-2snp&+oM!SQZ5hd>=+Mtcz(`T6!1{oLMwI z8OuA5Rg;miY@ereWSEISPf|Gh7ydWHqg58#iXBE~qW5G}$PbuWo%+KRrxDL>Q-ruL zV{!|@Q#6_xzipF}`K9rXqVbiLO->EBGCW&U_ECAP{NE{7jOY;;r5ZGIV7Drg$aTyr zy89gn>NE>LH}GzW6|a0rZ#WF%JL+K)TgRV$$sw%Xz_JsUzMIPr4{fl};G~ao&YQ!D z8nBwR#zWZQdKb$wp2RwS>jV}Rt^Zuikd+abBdT>qMQ|qsMXt4+rk+=aJTsl>(UVJM zJlE>FbRqrweOoRkNv8G7E~lD@2#mEMYM>nN?vk|gj5}1@trKwdHz}IW#Gj6drI4&Win9Qe1qf|z`Oze~wV?>4%^j-Z#%#sk z45` zpFD25F;JBLhfdKbI$FGO9}y{M&g@~kRbHtrS-AC&9QZE#U8=$=HD$Krp8+10D0m=> z0&b3fA8sHim>#i3I&A02N#^?8ob0tkcgMok*Ufi3mAV=uK%B;WDaF5Z4*A#i1sV=%Jh zvN<>QWp)X@nwnNw06^F1s+lyt;(wI~(|a%fvI#T2v;u)vU7~je>*L% zn0Q=R>LCM1y?saJ4WOIXwh_*_noBLQoP0+2IJ+!ppl+E#C;2|SVf%J^@y`a_(U*>h zJ9Q69t13~<1hyxu8DA0;tMNaYT5)T&H|CNozB<F+xlI# zj9N$ZS#pZw;xldww>+l)9vnS#{4wRxPsp8 zB!5NmW$&l#L)D_i4D<{!TL8iHzcNSXKz!w!9*|5dC>cG6xY&Val1$`^nm6g_$Gf82 zn@lFIjrQgibIea>p zk^M8Za}1`X@qh&gwXdU@j^I&ic1C+0#Vy87m8aXLFNCgPi@oT0VEEnI>dd^a7yW6P zhdvHTFtY!hJk4|Z2;Q)Nd%JPRcz5>ks66K%O zEGeAStI7U-lZ{LX8I_uwxF|lfDQGHmx}%-X_c9&1q<>Gt&N;<9k|_y?Js!P*|Mp_a zBk;@cOLmE&Azkj99gipP2xG(*d?6`qwKB-Ga>+tV4UG@G}aSNlwTkOd!;!k+E zcYImlQ8U@a&E5}J17$h09$(mAbL@eRgYd)YMNR&K?`!IW@Jiz*5AVsQ$a63B`KL~s zmB6kNgg~wwsT4dbB%jO$(2$_nQ$~e1QIMXD5_wNYC%hveJRYb71wf!|19lLEf;(;p z^hY#y2yx#3oj-vv9*c_zZTP8DqSyApUE=GkJL{3WDUZF2>=@(+U+FnJexj~JUB7ec zX$P~~r*(#d^lwa#BnHJtk&Ecn+BmQ@=*NA|Q{?dlu36KyHr(3Wn2hhWqj*!y@7^QH zALq##t!#;z9|QZmC_Mm#P{RaqwD`3&wA!63>r)I>4Mh(|+^YUx8!Bn9jRU_=ZrYM{ zvTyp+dp@V6q+%sjN3;t@iPDSe!18x}uCoY7t3=y#_q&LAO8FMENoZ4FzW#iL>rAVTVx^QUBVyKy{^|c`k!dP0F`5L`-g!8mo9Lie2tMh*ds^d7E@XmPPR`T zZxlMrjU4!#15t*%aduW19CkU){j^a|WS|WTxq;f@8amW}B_AYYhj(;s(u1qLo3a(L zZ}M>Q~WBCq$}; zs~ML}9#cW*8!79K{VB3V5;xl<1V~k$iT6705Bo4o?ldtyYWz!Wbh2GFdm-Buq#dh@ zfIi{|+-dmIB|GhyFJ`C}9fe@^AMkP!VGgdR9Jg^0${Fn@Heogbi*LUC=(Y?2!V3X@ zEvH}K-yL;>*-zrRO=O@f-q>p8KWUlT5_$ahM6RMLR6-h$vOW2c(ZxH|PrsB&0WVgV^7#Ac z`SP_?IgdRm-ot6%fMZg=n=uQep$cGttC!_pHTWJd_MDjdzWO^SKYHU)p49zh;2-en~j+C|~(<7lLIlVk}R!VN=Lk80du8aCfdp|7G$}#OtCld8rO}>O~ zUfWHw+Z$h-DaY!;zsX?5pfg;IU3N=pY3Dm)n26;T-NLKQ{X3bSs*&n&oY*-Ymy){c z+0MXrPZ7p9Bk%tts#dR(=fQiW(iffaF)P}8_50m?9?Ck$uMaPKbiJ82vPk`fy4@2@ zo$m~5kNEgd(BebXk3=3Swub~nU-VWjc)i8Q?@H;Zv&mD9Tzq&Wtz%dxQC2pc^0CqD zVEC?-!|?@0&(x9i%r)X~uqlOV8xdDu9AArn^ITIyK)}gnlg7c=Fy-N%%?1X8+e>=# z`X=$~o34xsHkqNMR`myD1}At%ZF;j|x28zENTUj6D_KqY2O6skU~>Z6i$KbR6MGRr7LC+~Mc?@@ z@2j(G@3`tok2m-+jYsUeKPj#sZ<#({Np^e3Tm1N6@9~xMIVpjk2P-9liSAPn-Jdu= zYVdU#*Yg-3e-bj3rSzFTp|!}NDL9SB#Q*bfm4t@`nLxl!Gj}ZiZbk7|?b}wz2X%T9 z2NH5l!#^9HDZiQ?T)Z7f=AG+c%mLmpC^<-#%30>%ny%`}b?zMBP-l-DveWJtwjAnT zzmLvoZh8_~Txa^{^TefCv|5HhBkADLLCL?Vx(_Gurk}j=R0<}0>~BrHD38B!eps|~ z6SxfCcupx?g9Lx5QsA>eNPFTp|vW+qKWi z%Ae|STs$Woo>qs$4wTa$WLL0GaIa(eD@mf45rRY*>o_K88J`DhkXUED8tPy&TlnYD zm$WBE@OXY@x_LvyofO<+GXGo=3mINK8LyM#rDyn(M+p4hYCTfRWMJv-fL^Ps= z+PaCUfeqCx7P#oa>AOIr@StNxWxZuAu<2{RgHL$Hrf=H})3M)j@U_p3sc+$M0{9!m z?^jz?nki!ZCk>ZcMBYn0Ou>< z93Hn+29N{tCaAw0>>h^nC0`bQZ=;9!8YIjjGf3||ZcqVcYpy{zFqshHZ?P$wov6lN z1`bwl_QPXJza^5dFokJ8q@n5Cn@5+Q>|QqTJtV@ zK&~cDLWWKLhAcn9B%SE9)n;2rFu_2KgA#_GY8rc;hmcUf z>b3t)@S$cYHP0<_v&-U_vfG`?35A8NLHABxiANRiBEU#?MDn=X1*Vq zr~hPhocaWrhL$Q_T&=;;(2xZ*T7cx4=Ls*Z=!tOdYPRBLp3{q~8M>0|iyPUCj;c?p zObW|u&wgcRDTqGyn0u5zp`=P1($5|&4P~`=?of^6B$?GuoUah}gYQKM3Ew*pn##WOyDK8E#!OHlu3VaG*Y62>WAUb+zCaR!ax(Yg@>n!?%OtkKI{lx2d9_aT=7OQ!5*yGJ!YQqCJihAa(#w>0vJ z>2b)p&;Ul0_q5it3{+s;91cwv%aw;;COv~~g(ullpq~&|!eG^N#l=6IEI(aCHV2Ib zA7aLltE;#?FReqS1`f=j|7gFbh!{5R#n?Ir@qeb|B_6%ssnG}4YpBT)uT(=aWTX1o ztRDnb-tz8uEXOBxCTY>f$~NoN6?Y2VQf_od=Ly%*w3QhXpu5`wO=Jls>pdL@!yx8 zF_4pxioW+K*b;@;wnp1?ahm72_b}m<<;n59bOIL_RyffKsbDY}6bI)MOEwT2Ve_ig z;Er-5X$ug=Zi4;5n}WCHid3!?AKpy7(8($Go{Wu_K~X?5%Kj8LAeKTP?Oi5#r+ZLr zaq*hBC*2H#(^~&ewt8READ0qw!5(Y2G;L?1Di>Mp-;2w09D(G4E;PD5aCbko!V4=6 zGzvj^lIFhsN->in>ue+9W!w_gzs09}bJ6m}bp^-$Sgd{Dn1Guby7fD9xRWzrreR!- z{W$4A+Y($elPu2gLnt+M3?IMDL%mqO2RTlEZ|BxA#B7UP4m|@lFh|6Nwyn$ojFdvM zf;^EsJ4mn8_7v&8&Z_+_(tVT%$kMY+F_O$erDWS2hxOZwR^uO&l4AI0dXk!MB+acz zuLlKG;^XhBspfj`u{ORXMb?qP1t5O*1lNPm#_7+?7)RGxvl>FyR@69&L3dVS zXAR^UzxbP*VpZ1Qmm?LATcsl!FG)j(;9p`XbWXOUT?UY6va-VLwLb@k=Gg4#6h+}- z=dG;xS$92AN2M;AHR&650;EI<;G#h$?zFS5kj{DN zWt()u>DD{F;&;it&>H#_#iDe~Vz@^nD5V$26c;NoL@pNmF10?|Jm*_Xe-z7C4iO+w zP^5^6%Bi$txm=(KijV)qC=oQA)%2twKs1U1_g(y7rLYGfM(t!>#iR4&Bp)07q##d< zVCH%6+#Rs?7ukmk3}bkCm6DP%vn}q0XC=fUQ#&mTx1T zqlYMN`EGviQ>EnO*b+VteFK^L463m=uGEgDgrn>J@9%>7*5`B({lL}pC206N!P|?h z06qRd4Wm9&I7FxYgD=WK{P7DcI}t~*u1Itv9~Lyf}`pOXZUr#5|6H%m*2y#=26Iu zD=-X(C6rQ|7vqh-m39@Imod*%J*K}rhsZTWwXGukrG!cR-axN4ZLtproMpc+;iR^A zlW+koeum4Dmu*-i#`Jy6z!dtbD(s|Go^>NYp2EDCbktI|b}Dpb<>T1cN5F1a0EzD4 zOqW~_kEPXQ6cE91CD=6UyM=0XF_1d1u7vLzz##tI-g{b>fpkYIsf2%|ZEtr#8g=-Gljy!fkkEkT-pXak z6zF_2IX~_^;S+aFtNSUoy6g0%ZK7^2qJ#nNj6?LHs1#RmA#-$VKFm4o2{)m0T6;cB zHSSOE2x;&0xYm4STigasV=LT-V8T9C(*&O=6oiCtZ-MIAY}SG7>7Js3W|>5+OJlLe zEeR4fp67cic#Uz9)1eZq^UKLNGuxFcpzN8k0a4f)6`;!IFgKyZ@ny5DWyms)T+f;j z4Mf+xA@Zb$=*8{8r>W1Alu6<_H67xfmqaS)K1MqrJ-8yS|;}82tLQ-S@NJD^V zkRYTWLASWPIStsN?(mV4<`|Y+Xde)e8=ZAEJdE!<48Jj{t257n+(8alV7YsDxN%7c z>t1%(dew2dWsyc;gKDAeY$!7Nqp2_=QzqjfeYr2PPlUhol<6@zJ}P3q*qjSNGwH)eAS%z62YWrLBipKgY?BJ zKp69=Xje_zZym}fA*DX>JI=j~79+Ac7sUB~bvzJES3UKoP?MgN3s;UdfS5(%Ci04f zUxM}K{vGTHuhbt$2g}R@xv3If7Sp|wUWi_a*z%>nOv_l+$#i<6-k}I-ZwjEQoIie! zG9f*$4rhFw#%&S#+i9#eQVVCRC3boL9vUB!cDGc;52D# z6b@O{jKIozuU?8@PD$-@i(EF;08uRKE%oxXqTr=>P{#w+kK&as;y*A%-3Su#hbkUQ9EhF`9AUw%<<8$^xobV#>n<3 zbrF@j7P60;I>bI-@m1X@Rb@$*>?goJI#bvTYGI4ivsSGI#uA~Cmp?t2eU3ay@{<+W zz0?Zz8aoahwNvO2R?vzzR?kV1jMXXgUaf+8LM#g0V13+}(g)Y$IJCVSX(v($e<1;M zn<&nK8xDTbgIgAm7bjk52zoG*{Y=`QljQJ~tCy~v!}#1|l8#kjh%O+PrN;kzvpi%X zpj5y*Lb-?c0?PU_wbTNF)BD>JE%>01HsZ(E-M?z435Tc0$D8=)#O3-A@fEBlG^648 zef)~H;Q7x$ELssh)ZbIHCb;G^8U+SUhm0$lK7~WmKJ=>-znYLCu3kHQ0R^1jttr-z z1K0JlZR`?cDCPa(G14h_xgLp^Sj-XOVD?7saUdTjK%xc8T`nR8ivuX)bU3Ii&g`4aY5`(BoJM&( z;qA<)-7lc59t$ocZn`yU<`IYr-w(Jof&ww^vF4OiL{>4%GGdY*F@RHbcyD&e;;jeW zb}$}^y1JRYy*+}-L-@%u{?K=4go-|2FGD)}h6w|2gM=N)p{YGB4qdl^)(UA(e;zqc zw8Dgfc9~x?4};jam{p3)?B4QRs9!gipRD$TK>8Pqo5DX^RY6;>$&Iobn&EQ>vJU(W$r_>O48%^uZ zH&Tg?rFtzQ1bXNoTVKQPTXj9f#}rYaD)i{HE7R#g6gdjvQTAx#=lEg%&%Be{6l|@5 z&=8@}DfU%Y#Gw$X=s-+5L1oWVHJb?!*a-5=X}#j0((j(+me|3{**%uHY zE~v%fD#uMfF1II3P71;bf&^#pEyDEgC{ ztZ@B0@0sF=(?9TxzOg*XT%i*28&9p|VX>81jk)gj{A$c7YVrgVO8U z)$WrgU4AEWJ&%kOOgXmyK5Y98AB3nR_V|nsxyhb3KTU12<%n9!C3PH{;07fF3GpZD zR!upi8;`V9IF+^DoH9&tz4+;C7F}QiqJKC5aGPhgs3qW3Ov>OwvR0|eee-JgNz!0kiKagpK=&u`TWN(LZ5kP}-;*oX@Ga*oH(}Bz&u1Asba?i@r`;mbJ zSARqAs16)!Bc8E|drxdT&pVJUc<4j=72-u`rL|Mk#WN-uJOsZgezWG>7O5VK(GnAP zqj`Yr?9z~I8_H93m|q*3)~PsVdn1nTZ74Tl(7kwSJ@X{h`pLD^GnK#+2W-^6M3vOP zH7kRaZL}+ZLX7f6!LAh6=(FaFK%{>Du!w8&q(JLFKWVECzEdDuHNLZ~+$mY%9vOy~ zfKXyUc78sLT7sMs0Hqyc(+2w(ToCdb23cj1F zG(3D8R89A1OYO>m-+WU_5n_s20RR|_fO9V!!SG-ORgU}xptk;Aa<9+0Ao}Cbn~#&$ ziyD6C@pqbp)v&C~GCsJ?dRUBvg)L3!zx!pdG*)T|;Dwb{MCvd+wxIYBqzWNAB_12w zJTe$$DKQzb0~N+@aHRK1w-_Y+FvKP9S*x7o6FpOjIT|CB8BW|DU6|?!(N*<>p6O}E z*A^DBg)nLwnu{{-0$hm2YJWi%!mVrrjw!C_?=fzeQHbNDrKfisS+V=9+!fbERr6C_-}L z(XeoK0W=i%T@_J3n4aKH4Dm1sw=#6>f4;uM%gam4#3Wy;yV-zb?1s#j1peA~1@lQQ z4LmNWjHu9rh}K#z^6%BIU$l@#|NO7d+JGBUXYM%n9yTOFrJ&i04i(?~rO z-~_vyp8%90ELPvhNDiD_3bfX} zF5X789UKVKN8*z)iT%>MUu>a>D>A|rYUg{Hp02K%H}s^&z(os-Q#s&mO*p84H#IS7 z4FkIhSU`0_o1zgcR9`BgjYv8{$6#v33qwQM&pM7;3w-zQo0^)YIFcg3O$84ycLZR? z$H#+N-Dp5k$^)iT9iGRJ-AZ+dWe6gnxk}RT z8@2ZJk)-|P0`nIX&#ghdNsIdCdCUV~x{*M~2-pOKg@eldt~SAYCeS)}%0hDqSbWde z_>qkS1BdpY_}?Oyd2xtS`L_4L5AKxIRIF7-#c1ZPushr$mn+kCPG(_p48-*zI0xvJ2N|+Gc?gUk?w#oq7k5o&Kg=S#2H2H|3!1B z%3y=JZUJ=2_M2n(fwcDZ^?lUgvH2FYgn7Yexo>c6Y;5l8>+%*>X1~|3U+Oan zS-O9rL7Buj$mz3YqJB@8d|eyN=g zF+@N@0#uXM7NkzlO^|f~<<`c~yMj*M)t(?XD5b{C)Q=y^8w+>vFw=K=Dd7uh^f3~C zHq~-vm?7oI3>x1r!--s?9T^!p+i`38@cHv+8+G_X+DMT`o)P~N;B1Bi9o|38zF`FX zupHV-(}_;2{iZH1RDQ>Le!-$q`{Xx!LifJ_1XfvmW6s;d}IET@+rhA z3n+DUbz2{I|M|lSw66)-4Y-uC%%914B_9_&P2Q`@z5-j~(%Jr!sN)}k8jY8ZJppHMRi2Lw>w`4vMq{IH(VP`BHqFA3n&4kTR>7W>hE6-AzhPhD%9B>lO$5T%4F%S`zm5_JVUf3=V#No)!Prtq;u2 znfBD*x%Q}JG$qgD<}V~e-oGER{aR638NjPo=I<0`+~8{CHXO&Z>A4!L1D7P2g)F&j%mR8uM(3*VuxVz`YZGr!g_XycdFL_5g1+<($;n zJdP2dq0aU>q4WLQ`_jzUml<=v2YBgMcw&&1>+WnMh8m>n^mSDjx#StduH{MuLo%X} z_wMs&m=bIsqf(t=cQB@FeWVBuR0>TCp>5ZFu!*q%O^&t> z&2|?6{5Qdvf)g|?a6pz4^^iH@(P3VWf4);Rf_Luuuq->$J!rWUjABL@lsri8#ZV#_ z78O-|`xd&eVA^VJ&koYwjrl$e;P$Zqz%k2-&N83hQR zftC6+zS+irz?SrN3WU@3T(EA1cqjnX!d)xZ7^iDf6uFg$;&)+kLxc{JcyN zG!+9)%ciygdi2-ZhZX~(Mcvajr2H&S77@~v@<6PBeE5uFH+M$YX{(sJx+d)~ayG}f zHbi!H0jIrsMwyLZ5sooMU^8>xW_8f8hWJ=N=I9j2j@#Mb>1SiIap~YeaU$-YCvL?bAMB+Fd zL@X`R3V|~RN)GBKIWf>$?Eb$#b3W7JR6T)loXYU@<_|>O8+Gl>PiYE&%s$@XDW4E; zp+%|lh+ZV%>8%bFWHnK*n)VK18t1IDmrra))OsoeHn=EV6u5D3IXLIwm3$=xUVsB5 z4LE&9q(3tL^YlW(LT_7R_c)dRGSKFZkOhmFf2|}U(_T(Iha+;7y;TkU^dCxjM7B7XAN_lw(&LI2Tq6EiE zz*E=hU{nn}W0f#Y<&QP4i!5McX6#mP3>>3>M)|l{8xY?vxsS|BTg&H+8py(y^VzB+ zgT{U<2agoHwA}I(DjeL2FJ7`d{n=Gfy)u%BEKdR{8vLmwaUf?a%HzxZK$2XpjaI0< zc4$%kCqHYD<%PtEWSf{?N0ZZD7o@|?EWn{m#cEiCAM?yLD76)XTc&}(Vh(f7yTH={ z0h$@_u&uII=<{0)Kc&zst^Qx-1U4$nFGF{^;z@> zuZW-)Phv&}Ai@ZOg6Lko8X^i@Y#9P9F!O&B9qUNuPQi8t4B-^(bDqRzt7C;S<26_T zYYQPx*xk4^arxqudsmFA4CUcM8%^# zVwq9#P5|Se;0Qva^|b#Aj{i5s&7in$#E-q869cRPqr;G){t7D`1;|<}pO;etXb32} zdq0edc;`gcf3Z7Rkgz8)5S9eT*HTe}eL(%vC`l^51aT7x5&=sBCL5SF?sgxg>Of-5 z*gNaA!c&fc(|~oZHP{69b<{NC@#G^zDXY@V1RO&}r+$`y`h7I>6S^ep$2K47zIWQm yM^-HVl&8B@*|?~pZPg@QKKG*O=NRt|i{m{pFMaxYdvGrsL|I;4u1v-x;Qs)lO{Mw( literal 0 HcmV?d00001 diff --git a/lib/src/main/java/org/team100/lib/trajectory/path/spline/HolonomicSpline3d.java b/lib/src/main/java/org/team100/lib/trajectory/path/spline/HolonomicSpline3d.java index 341f3c4a..678b7595 100644 --- a/lib/src/main/java/org/team100/lib/trajectory/path/spline/HolonomicSpline3d.java +++ b/lib/src/main/java/org/team100/lib/trajectory/path/spline/HolonomicSpline3d.java @@ -1,7 +1,10 @@ package org.team100.lib.trajectory.path.spline; import org.team100.lib.geometry.GeometryUtil; +import org.team100.lib.geometry.HolonomicPose2d; import org.team100.lib.geometry.HolonomicPose3d; +import org.team100.lib.geometry.Pose2dWithMotion; +import org.team100.lib.geometry.Pose3dWithMotion; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Rotation3d; @@ -96,4 +99,43 @@ public HolonomicSpline3d(HolonomicPose3d p0, HolonomicPose3d p1, double mN0, dou m_yaw = SplineR1.get(0.0, yawDelta, dyaw0, dyaw1, ddyaw0, ddyaw1); } + /** + * Cartesian coordinate in meters. + * + * @param t ranges from 0 to 1 + * @return the point on the spline for that t value + */ + protected Translation3d getPoint(double t) { + return new Translation3d(x(t), y(t), z(t)); + } + + double x(double t) { + return m_x.getPosition(t); + } + + double y(double t) { + return m_y.getPosition(t); + } + + double z(double t) { + return m_z.getPosition(t); + } + + public Pose3dWithMotion getPose3dWithMotion(double p) { + return null; + // return new Pose3dWithMotion( + // new HolonomicPose3d( + // getPoint(p), + // getHeading(p), + // getCourse(p).orElseThrow()), + // getDHeadingDs(p), + // getCurvature(p), + // getDCurvatureDs(p)); + } + + protected Rotation3d getHeading(double t) { + return null; + // return m_r0.rotateBy(Rotation2d.fromRadians(m_theta.getPosition(t))); + } + } diff --git a/lib/src/test/java/org/team100/lib/trajectory/path/spline/HolonomicSpline3dTest.java b/lib/src/test/java/org/team100/lib/trajectory/path/spline/HolonomicSpline3dTest.java new file mode 100644 index 00000000..12c9022d --- /dev/null +++ b/lib/src/test/java/org/team100/lib/trajectory/path/spline/HolonomicSpline3dTest.java @@ -0,0 +1,35 @@ +package org.team100.lib.trajectory.path.spline; + +import static org.junit.jupiter.api.Assertions.assertEquals; + +import org.junit.jupiter.api.Test; +import org.team100.lib.geometry.HolonomicPose3d; +import org.team100.lib.geometry.Pose3dWithMotion; +import org.team100.lib.testing.Timeless; + +import edu.wpi.first.math.geometry.Rotation3d; +import edu.wpi.first.math.geometry.Translation3d; + +public class HolonomicSpline3dTest implements Timeless { + private static final double DELTA = 0.001; + + @Test + void testLinear() { + HolonomicSpline3d s = new HolonomicSpline3d( + new HolonomicPose3d(new Translation3d(), new Rotation3d(), new Rotation3d()), + new HolonomicPose3d(new Translation3d(1, 0, 0), new Rotation3d(), new Rotation3d())); + Translation3d t = s.getPoint(0); + assertEquals(0, t.getX(), DELTA); + t = s.getPoint(1); + assertEquals(1, t.getX(), DELTA); + Pose3dWithMotion p = s.getPose3dWithMotion(0); + assertEquals(0, p.getPose().translation().getX(), DELTA); + assertEquals(0, p.getPose().heading().getZ(), DELTA); + assertEquals(0, p.getHeadingYawRateRad_M(), DELTA); + p = s.getPose3dWithMotion(1); + assertEquals(1, p.getPose().translation().getX(), DELTA); + assertEquals(0, p.getPose().heading().getZ(), DELTA); + assertEquals(0, p.getHeadingYawRateRad_M(), DELTA); + } + +} From f0f6849cb2103752c533d0c4bcff9d5d59aa38a5 Mon Sep 17 00:00:00 2001 From: Joel Truher Date: Thu, 27 Nov 2025 11:49:34 -0800 Subject: [PATCH 03/13] fix the build --- .../path/spline/HolonomicSpline3dTest.java | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/lib/src/test/java/org/team100/lib/trajectory/path/spline/HolonomicSpline3dTest.java b/lib/src/test/java/org/team100/lib/trajectory/path/spline/HolonomicSpline3dTest.java index 12c9022d..5eeaba87 100644 --- a/lib/src/test/java/org/team100/lib/trajectory/path/spline/HolonomicSpline3dTest.java +++ b/lib/src/test/java/org/team100/lib/trajectory/path/spline/HolonomicSpline3dTest.java @@ -22,14 +22,14 @@ void testLinear() { assertEquals(0, t.getX(), DELTA); t = s.getPoint(1); assertEquals(1, t.getX(), DELTA); - Pose3dWithMotion p = s.getPose3dWithMotion(0); - assertEquals(0, p.getPose().translation().getX(), DELTA); - assertEquals(0, p.getPose().heading().getZ(), DELTA); - assertEquals(0, p.getHeadingYawRateRad_M(), DELTA); - p = s.getPose3dWithMotion(1); - assertEquals(1, p.getPose().translation().getX(), DELTA); - assertEquals(0, p.getPose().heading().getZ(), DELTA); - assertEquals(0, p.getHeadingYawRateRad_M(), DELTA); + // Pose3dWithMotion p = s.getPose3dWithMotion(0); + // assertEquals(0, p.getPose().translation().getX(), DELTA); + // assertEquals(0, p.getPose().heading().getZ(), DELTA); + // assertEquals(0, p.getHeadingYawRateRad_M(), DELTA); + // p = s.getPose3dWithMotion(1); + // assertEquals(1, p.getPose().translation().getX(), DELTA); + // assertEquals(0, p.getPose().heading().getZ(), DELTA); + // assertEquals(0, p.getHeadingYawRateRad_M(), DELTA); } } From 8c2124f6110bc87d94e904eedca222ad90c64a56 Mon Sep 17 00:00:00 2001 From: Joel Truher Date: Thu, 27 Nov 2025 12:24:20 -0800 Subject: [PATCH 04/13] cascaded pid --- .../main/java/org/team100/lib/subsystems/2p_parallel/README.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/README.md b/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/README.md index 262e72e7..12e309e3 100644 --- a/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/README.md +++ b/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/README.md @@ -18,6 +18,9 @@ accelerating ahead of $x$, and then brakes gently for the rest of the time. The fine joint, $q_2$, is capable of much faster acceleration, and so makes up the difference. +Another use case is cascaded PID control: the coarse joint responds relatively +slowly, and the fine joint responds more quickly: + ## Kinematics Redundant mechanisms have nonunique inverse kinematics, so the problem needs to be solved From c4fa3dddb6af0e54a5a7c3fd5a9591a2e301282e Mon Sep 17 00:00:00 2001 From: Joel Truher Date: Thu, 27 Nov 2025 18:30:40 -0800 Subject: [PATCH 05/13] parallel joints --- .../lib/subsystems/2p_parallel/README.md | 39 +++++++++++++++--- .../lib/subsystems/2p_parallel/chart2.png | Bin 0 -> 29921 bytes .../lib/subsystems/2p_parallel/chart3.png | Bin 0 -> 22449 bytes .../lib/subsystems/2p_parallel/chart4.png | Bin 0 -> 22912 bytes 4 files changed, 34 insertions(+), 5 deletions(-) create mode 100644 lib/src/main/java/org/team100/lib/subsystems/2p_parallel/chart2.png create mode 100644 lib/src/main/java/org/team100/lib/subsystems/2p_parallel/chart3.png create mode 100644 lib/src/main/java/org/team100/lib/subsystems/2p_parallel/chart4.png diff --git a/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/README.md b/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/README.md index 12e309e3..46b11d5e 100644 --- a/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/README.md +++ b/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/README.md @@ -8,18 +8,47 @@ Why would we want redundant joints? One reason is to allow "coarse" and "fine" the drivetrain could execute "coarse" motion (large, slow, approximate) and the mechanism could execute "fine" motion (small, quick, accurate). -Here's a use case for this capability: coming to a stop with higher acceleration than -the "coarse" mechanism can manage ([spreadsheet](https://docs.google.com/spreadsheets/d/1Z7twUzL8mwdp5JcAuysRHhibZrmlWo9Cy3-zGcI3sXY/edit?gid=1682330556#gid=1682330556)): +### Tolerance + +A simple use case involves tolerances: within the loose tolerance of the coarse joint, +the fine joint does all the work: + + + +This might be applicable for the case where the drivetrain gets "close enough" to a target, +and then stops, to avoid upsetting a mechanism that's moving the rest of the way. + +### Cascaded PID + +A simple use case is cascaded PID control: the coarse joint responds relatively +slowly, and the fine joint responds more quickly, within its limits: + + + +The control scheme here is very simple, just "P" and "D," but it compares favorably to the same +coarse control, with the same "P" value, (but more "D") by itself: + + + +It's not a night-and-day difference, and not what we really want, but it is simple. + +### Planning + +A better use case involves planning: coming to a stop with higher acceleration than +the "coarse" mechanism can produce ([spreadsheet](https://docs.google.com/spreadsheets/d/1Z7twUzL8mwdp5JcAuysRHhibZrmlWo9Cy3-zGcI3sXY/edit?gid=1682330556#gid=1682330556)): In this example, the coarse joint, $q_1$, anticipates the approaching stop by accelerating ahead of $x$, and then brakes gently for the rest of the time. The fine joint, $q_2$, is capable of much faster acceleration, and so makes -up the difference. +up the difference, holding back during the $q_1$ acceleration and gentle +deceleration, and then taking most of the load for the final stop, which is much +four times more sudden than $q_1$ can handle alone. + +Because, in this case, the coarse joint anticipates the deceleration long before it occurs, it would +need to be planned in advance, part of a per-joint trajectory planner. -Another use case is cascaded PID control: the coarse joint responds relatively -slowly, and the fine joint responds more quickly: ## Kinematics diff --git a/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/chart2.png b/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/chart2.png new file mode 100644 index 0000000000000000000000000000000000000000..444f5970fb7c28444e740d5ca691aebbc5c02518 GIT binary patch literal 29921 zcmeFZc{r49_&==G6QPo(658y`ltT89WZ$=#@z|0*WZ#|=LMZ!^eI460WEsp%vXgz^ zCF>Yun87f-w|bJE@Avoq|GvksM|7t1qF@#qX!xk z6h{fbU#GuL0>25*$33E;c%Cc&KuXIEiW@r>$IzD~_$>C+<>;?Hac?4XFR{+vxx~H} zZ>DuKKKJVD%j$+|QIAGxf`TF*+`b-igyFdEnK~wr;hAT${ZAsZ%qfS`^cg*jmVNTE zdj#RW4dRlMC$fBdTtu7T>)WBJnyMmj*L|r6To2QfI|Iy5LE$!h7JKT)Pv0*@dHnbx zTn0wD|HJot|MwUBa`+*Srem$e^I@XPsVlyF+t{}`g^;QkyUGPNk;Q_N`8RjkQ@P>Q z5wq<{`A|TwwEGfly4`bk0eHHKXWfU3AS)}op20%q*qT$gBDq;ZHy;8OJE zqnK8cmp?^w@zy^o;smXUXwr*glr54SsEu*OKsuJ}?rx3Bxn$32q}^C0EcO`1KYnW1 zBNY7K2?Iv0S!_w7uGt25NdLV2{6wB5$=%iP1R29kbi59JO#qMl?0hf zq!kn>C2xPF^NkamW1H%@E`f1hn`Q0bHLOreu9{B|;b0EWF{GiGgm4fjCK*eOLxS`9 zCF=CH;fa^+>GI10-c0#jVwoZ-nXS!f2KmOH88CcS za{{YIoQgK{58;=nBNPsyy+xCJNDI$b>p_vm7xDUm%;FwR9qtR=S=bp0ie!HcItuh^ zL;6JsKmXg+YegLoOuTnyVvSU`iAx!_BW2AIgO3+%ZN&^~grMmWc6*UOo-x?-`kW~r zIW1t?7^WRq{ABsE)GBf>V*mf@GQuUeBpb`eJwhZlCy#BJB3}JP@ktdB+9x5rHn!^d z!u62JmT2zCx!I1C39BDtZ*dW9$!mp180h%dm7x-L*$j2(d)B~jwY9Y!<$G0qNt#IO zaJ}o!^PSfS{1g_W;^^bs9kvO$`29JA|z@3`YI^}zWe#iz9&E6Of>qmBW+{2|1f3iis%wU-Hh-x@SoV0g^fq4RXO zO3PC@yHEf{+Q?On`Z_rxJr9NSdLL_(kO^i z+~=<2<4ivt%%6DGCB(95o$aIG@`a(Dt%h(GaQR~OE@^S5_yYKh=+^5QA`4rPn}~bt4HOhRN3)nIt{wxt1uy&1BH5h{;!w}<(V`<+r`5*# zn_Wb6iYo4M#s&BCSW;bUP928-=4+68kdw)2icjEurx2POvoeEPOO4Dd&c_WuXJ5L3tUwx&yX zlRD4Jne8rIxNt!uoLPMS6}?KTX}EX{U&Z86(t3|7BSaGl<@0UJrtK@xFUhqYDC$L+ z%DF#Z8Bh8Z(kLhs=q8v?V+oIJz&^d%Ptv1eYu_e0L@Q>+-y6+^rXU)!(I&b+e;R9a%45zKjaLDYEpjXWBWaL-x$x(W~uAjxC&= zx<9uJU*a7yUg9MHkt&)+(q{0(G;*z7R5h92`Wrn4eeVI%2<7377g_yKc#kEdK4R|r zyVqju%%4x}ucZ_A<7G}lzD{8TUHk6NoMf!I*w;FG)hNttT@d}u*6{G-%R+YV#RjTe zSEik(ju<$o;66uQWu9c1tMk}X^2Rr_uLCE=w@<*KLVM-jv&rv64&NuGN=d?bw!Hd& zWig~u>w)fO_7o-HB#BXc@>o+}pVK!bQbk05cl6eq=@q8XhmixU%e^7ad-0@tuuod@ zQMNje==WDRcj;xXYo48~+c5?51_~%WM(}b&igUmINBap0=L-3tbH1Yvjm;?`RcljU zA3N|7YDVf3NIj~O;_gKP90V`ph&k$^wO6BC(!^9n7he4g8%1)Yssv|jgP~(HtCqTY z8m(dw#8G1pc@v=sMAG+>Vy?s?i&iIU5T8;qz2t>C4+1t?Y~XT~2l`g?n*YIi)?y0u z1+$<95YRyIxui<7hkY1dU-z-e8b4TecEHgW6rq;|6p|Tln>@f*?jN;IAjtExOJh~K z%u|h1qu;;QYWmd2r1h@(%O``)I_MpNW%}^}HUWAH>&-U}`aCxJ?ke@}(Cg$gsm8>$* z)c>rIgFq_{o1=~tGipj^pKb>gQ$p0ROs_OLKy2>lx8kZzNnkU&%G6%b|BfaFb3LOV zZWK2SXhQ6oEAZ_6OO2JQ{}JnntZ}LTXpLF{1>_=IpKo@6isw!t0ToDrqC9|<=11iQY5!0i7v#MhRORVP2D5SXIQo+2)I}M&&c_NS3eRs zwY#)+A+mBz&RRNIK22}0;fIsOJvG$T--%TM34I66<+~jA1EnYb6DXStSgo(eAid^9 zC(`2YSUl0jdalo3gF_G|viQ;c6jm7Vip}VMe-HoZ7@eA>C2Yq*Fl+Z?k4oeKn}iMr zA79LzittQSHROLDJS8!>qeD?7dX;-pP{v&# z@}EtK`MT;I+(8EI=M8^5_g;YJ=t%CTS&*we8uk|-;)kE!O%O||DB2xZQgl+AM?2Qp#7wdb6i@xVvX zJ3%+lf610X8eh`)>`Jz6>bd)P=-A%t-McXC^cr)knZ+InCSz*6m_1XJw=19Zy(1Eq zFfu#-hT;Rbv!gK*LQ~&yQiuTaVUdsH5s>RW8sOz@*ZEEV?6FyscJi$4DqObENl*~xg)x9^OW;f@m1hyFse;L^w@^nhi z$L=vwi8&vv$Q=?&`_BI{RwF$9_Cl6|I4vp`dN)C&?p!PzI!M4-%?v{_q8ClxNeFy@ zA4q5xd52i}c?q9~EK+#kkcwx<`1e4OGmx(f|JQO1MVlM*oAdOwb#d7(=bqYB#J^#f z>x=GO$prP3F^8a2pl0>g`XlmK%bGJhJ>qSb2X_M3P4by#GkQX7u@0LV>(Yt$@?vrr z2F>1u3hrb{Mq8HzR{xul{cDN)*^M>0a{l^ol`CAVF1#N3wKj0>r!mgN$d6OmTzA?t z+kR0BZ&v|N!Wyehm+-tX?+X|dPuZ0#t|nXH@CG|BGD9?W_8jF8)yTH`PKv}yo}bAD zzjZTTrv^;7QP5`a>I5<2Udp{X6#*a(Z69$il!DDEj@&fTEp8M4X2ux~djB3e3fkem z)at9!Kth`>yAAR!YPSZNm}B9`Z8Ld2JE?x853$(>#niBRacxc0J5Rp6wfA1?g+-1= zXjI>{BI1TZi<%pqd4Zu@yW}Mt|M`OIc&EO(xPA^Zt%R&=7~MXqFJK+Sqe*_+bX%^3 za^U`t^fYTB=Cu0@jSk&$cJ~|iP3AzReXPziWCKpuDbZ%i$Mp&BR4dw&R9D_^;A*0O zrdR(aMDB^x-?Yt^FUzm`@Aa!q&$-?-CDS;|?s{Lplj(E(9*_NyU;ZEIlA}a(V@uQM z?aVGdfrbIhwfs%q>lr$z%XeGciIb-e=U?#m%J{Bx{N-e2zI^$Ztv>M?+Pjk~!mZ3= zCl04k(IN8CQU7r84pb)IXk=s@cG8d+G~~B&^>C6lEYK`R95K*fYuQO?T}rb4L_ZuY z?snm4+WIs1$}fzpcAxAEAkR>vxi{WX+FM!^CvE>&Pyzeav$L1-Jq1RSj0OTZ9Mw=% zVpkV&HK0F4GNgpp*?J!UvAvLNvT~a)Ia--G$@0fIO6=}{Nd%$D1StBL(%HeMC{!?$mo2l_BH#Cu|= z7w_;sp+o!sF^)?__?4TcGh2kkIZR;eqb;?PAwT%OQc!!n0lZvAR^(hNEE(kTGcE1w zy=i}$<(|y4*Fpdj?+%!X{7`(|y3lOCc<)l885l`Tn+aOIA4*tack2G&<0O!{ZG9*V9B5vt=Ozk|%{ zIopG;MlI&v(5>0phuEB-yZ-D%9<<{tFy7I*iq4kfHt?X)prjiMfl z5~C9>_o&`A8^>XNA-k`B)(8<3lNqdLJlm>Oogf!hek(?!ztDb;jr6gj)*Ahn?FX$v z@MuxS<-b)8hSZ43NquT%ED6JE9F$5{97DQc4stbUDbA*2Y}v6>*H|(^#;X=KSQT=C z^Mb!iO?I~8QZ^ZoL|hshMJL720;Jjg`zjT`&dz7Pb>}^9AKKl!HHR-m zfU6^<{4QVH2%P|5+sunmiP8C4T+PJK+Gzm$Sr*@3&9mORt2vIKWd2T*oZ~eIJ^O)r zp|Vl~o!x}K!xtl-c>#a6XGvfrNMLwCGI5*VN4w?mx9#x{)Ej;)f}=GTtl!X^dwLkl z3_;NuX=b2k!6@9{cgs&01bSJ}bzb>ln|I6uV8x%t%QOnIK-Sn7bY6aQoIRuTu5INE zBXlOgpGBRtzs+!^bI^IU@y(_`$gdX}$=J>f5S{dmHvz3SW(z@u$i(h|qi8Ev5|iCi zX!g*t>B~RrvrENF{QU&PMw-!%404g?`%C-pJ5gE&>#HwAi%*AW?2O|tqN+df%}?>U zOtrhiyB7RKdontD2(FD29~F_CrHx)zU>W)I_$`8U8NKz#Rx9;}q<`SY&6m>q^C*Y1z6t30YD7xt_G$gj z`k2s3$<2gc^>CmzVI4o?YD0VP4DaE%7u0kl7%VZyw{CElJC^rN zBE0Fdgr^^w!qOp2c2x{zdG63@vYmoJ_>%jhEzZ`rM9kgZM@;VAV16+6*rvNW)WuRSHwKv zobK#ns9kD6J zaM~f)i3ua-jI%vAo{uPA!}dRL0LiT&T--s5Hrb$tr^@f7qM1>P;}?8dn2P;=;UL@L zhy}r_PG16jx?8l!`&WRJ;7`C*)fFLpE+J;_<8cxmF-i(SLw0i(iC<^#`GF8F6t??juv zd_KWwjQsLYte}$oR^CB|+;{)G^zvI405kgGRw!S+K5h<)JvV)9q0CBNtt9}Q%{1UP zq7sUuB+0T5(3vn;d0y~Qa7@SRSmCyb^EoJU_u#hdx zld?Dviwv!Bl4u3xFNABwdp0a^$$33Q^+xa&t-wS8xPyCHfEB9UQk}c2IcU6iAH+(G zS9}T?v#dMEh@fs84RsLF@($if zH>M6;csL`IZxsYmw5$tBh9MZ#-naFfIe+i%;Mg;L90d zWmLeHkWEmrK~fF=qWGp=93RVAMO}ynxP{DpLY-^WyeY}%KE`mGcKp>Zqw$PlxRLQ) zmncFiMb)1o1nU6e&F3AW%(%cid@cu(B0JwO*TZ6iB4?cmO`(tW{2VePG$~=*%(Qdl zKtXIyBUe3{$Pw)i5RT6G_6?@x?zZ<#_GsGdE~hc_6t4*P< z_Keo}9!O#Zq41=afn=}lwd>$$Pbvc-K3%6FMz*fu>wausLN)eIrG0c>H3{D=k8OBr zaJwvaJ$=>@NTP_TKNCDuJ=IdSTTL^t2~-EHRv+*pT`Qu=VpF}rX%DX_uZlE?A(&aq zZ9A_TAqV8n$!Z#-wS6r4=b6H6@~}zI9gPa}Arr7q`vDs*eO_;sP<4%O!+#}9Y+B@R zjYrGuU?{D5TH`hqdUhW{{&(KmQ9OH9CzyO&y;^~({W6<7w5~RPs;z(y!`|OGAjpL` zsgg&y?A|{S)3d7sjClTV^c@D*9B^*J){IyD zyH4B_FQ$y{%cEg)NB>yzRbmEs(~c}c0`+zY*4|uEeFBj)LiVJ-yK^Iy7``INb$?@k zVM|q~5jL4GfDJryY%}2puKXkFxC(QtJp2k@G8bATH$mVW;PPDsV(73ac?nWr|FV?aYFBhFC zL6)avW8DKB{O5XM^VfpGB7IOfjCH0+0)5;xDl2n19XOR>D{C~Z)(>DTc&WG;8vzcx zT$V1e|Ga!7O@=pMMg}I@@ z00>Xq?Kk){u+Q3!BL=w7-Pn4li;$2|pY;r<>8?Yni|ECNb4^hEM@cnYJ|lpTQ|a|< zY_ZRve@6_+h>eo)FF6Rz10SGJ9>iJjYpTZH{Iz3$zDOvMuHu9~i$LLKKjmYejsG3t z8sm00YEVwX8MTu#{#Q>ruLJUUqx_!>g~v0n??;~EM1oLWhP%J~_$44S@tFD+0Fn(N z;A^vG=Mzsu&qad|UNeMXE!q-fAyqC}KtHf0!*gT#uIsWPq4=)c6^92Qa?^0^Z#*aJ zx}0emCd^i7!}7C{c$t8I*c&b{9wxcFIqlpU3sz-Ry#gCvLuN|D1{(A99<91JHr3`C z7SPTy0izE(4`#{%J-6nEJmqIw?dtH1<@bN}IHra*B+Z)6=)d>;9}Pvk4r+V33UAsN z$`~sqWZrV#eYxMj-nQbyDJ02I4J#0&`=f>wAtlN5smuKx(ZTCL=~K5JAi9QnNI9({ zXzRUbEpgDTaj=E0bY%qcv~lYcJW5WyV-Y6C9#doX4d^sIp9*5{R`tQt^S=oYdO*u0 zqP6Sstub5`DFP{y0D39nbtHFW82Y=eBLqboH|=EV>n{(a&T1PZe(>^_@D%ziDp1VU z@dF1d;w9uHxg_wkWo2bGJJr|M<3~Aj-bXl^FP@~m!Xasg?S+N5Z!8X|Ca2soJ_>RB z>hBoThMY@QJaOVgXi;n59MJd?TbpDA;`YnP>2{&Yza#8f)Q3}cuS>`FOHzz{JLMU# ztY7Ha>UH#&oEDS-k?|I}49)UhiP?#349!%WQx)?s}oUcSyU~no@BT3fC^W zBDS>{RJuClOCQLw0bpS&(AfMAz^nCjo`UK@?>Q7v+G4UyF6Y^{%FcQ=V-OqAR1 z;z3!vu#W4`n`EtL4Gw}qed$l^GfTMibz(MW2a|KJIxs7aWp6WZCyqVYO`0h}(Xnn2 zXp@@D!wU8Owu<77VK$Yi#+fz5aQf zsn=6UyH;W?GGrmdf3c^i{$~Sq^w||LH?=~aFh_G3XmK1U&@#H7;=QJpD+V?A>C<2B zZDRn=&kT^avT<>9Ÿ%di=r6?hmep zO)}Qz&Dg9qT@0f&)4uB?Aq`T(7mn!Kbps`+jq1=|{TbfTg1MSm!-FQ@6fnnoZ{kq# zU9e%rEq4`wxv|)nuiFycM&AmlBZQ0LUyIyK^1#9z#Rw^i3JMC-NT+sTc6UBdO2|JN zD-;<4Z?Y_gfGJoC!mRw{(e5>`S<5rd(_w=7Cp>N5?lW5q_dGKkkN%2HA=ZlCCXERp ze3h?>%VXShtELWi07Q$OQLeZc%K}zWVnQZ$ zucw`nn})}uNIQ3g#-7+4A*ZSQW{zF5XbpYw>x^PW zovM0WQOh?zIt+Ai_0jbq$xk|x3!(isfW1uByCd?Iov5g(7p6kMF()9nfE&aj$!C-Q zc<48zC@QL9*Eot(rl>I%;Hn`>d8R(v$ZBO9b zW)Hkof8Eqs)pMwAIH2&+*zw3}RK79>bU9|Y`j)6dO)e&8`0j~cTKIYXuhouj7oc!Y zx;BE+X++N>PtD0gs|n7Va_^=!5L9Fp?Ij$z)@YAiML{}hz)s?))e-!&6|5?Jcq|wMT*IlfG)Z-7$ z6Lg=;0yK%86o<;&xiD?See`WXiIovEZMaq-B(V0Tk%noPj3(o9yClgtj_at{N_)=K zTk*`p8xlST&)kf-gEJSZV%C&{G_OSN;Ak8wtqQzd(Hj+4+eVtUm%X?!7Ieyo-$EMO zRMbOVG&i}gx2gp~n&FXNS53N1dl+5H&RWm4I=G_GVxG|P9)4xXf&rts*FQ+#Otl28 zt~ESzC&2sUm=_-bJ*YFJsx=9oTp4kzLcZAAp1*SMW`s@tv6&T-ws% z^)WV;H|$CR3XXY!&9!iIjsO=T=Fvhp)SRanbE+k`DVDX93jTy{$?uR+lvvnpTayh; zeHF}(_ZfG5pSp>$ik0$Cw$!sLv6Q^fQSJ{a2_znt-w=XpHm6#kOpS?n9;}QvF>Xr? zF>M~RW%d$M(w5>Wx8w$!(;@$uqjSCxaidSYW3}Zb%bUme6Bj+6IBxw)~XssRuwy47;_XmL-w{Q(cr8ApxMvgHA?`-Xi|@?AAg`R=LIfO^kvuai@8eDbsdB(r;{AwbdrWD7L`SLyqrM6i~2@29`9b!n!^Mr?OrG|tqM zw#1&965skB0WJQak4AzKJ`yRTQR4R~4|%Cj?df+2 z+!a9c{g~Vg^kj^@Pped9QNC|lFH@upJ{0lR$gY|B{b7(l@rfO>14x2#7_84Zoj~sz zn#i5vrIQeeVL%AwuHWw$XpX)WzejgymYkB7C(W!vt6Pnc+9f(nM4GY4oiExn_OF@9 z@~=)8R5-j@#z`HPGyHXonpYPL$b8dtdex1(1e!xUS0iU-BSlB6k@vEpN8PizJv*rn zO(FE805uGCDaorEZSU@Qu7rOA$zWN7q0G(08;`Bec;KF8_=Vx5Bo8Tb;?t;5*Erho z>&ENr+r7pU4jvKVj1OwFhy0-h8Q@X#+}M9)-nTQ49yv74NWrHk!5u3=V&uFj<2)Gq z{{3|A?FhQh!P5Ijtl-kd2Igf&Qsj`I=V22NdGhKF1Lng(m#6Q<-WEMq$x(0x~Fd~Ufx!Qr=twHi=vA?^PBA28m?7iL+byGX5 zUeFKuZU3HUIcuCNMdn8hX&2+vEw5f!ob*<{Kxwolf>PQ z9Xx8Hi)}k|snrL-cP6~bMOqa2*tf_tY-4Ih^D8OmVz#^eJZJblztbM5y{@n~F>$37 zC|9?^*Kg#~mPF*s`xpU>-yI@J?_Homfu^}UzhC(MJgnCsFlT6SelF#{&XR|7T#}&@ z-Xu1$E+UZ6x;^^*Ev#-S}_+18xC0 z&8h82hrO%8(fPGDrOpv>8iVHptuAR8Q^(g^^(L74B?CC>od2#XI3Sn*AL$iY+h*qK-yXYF*(*n<>9x85qz6g0z3Rl`r0EQY zbPU=SL;^Z&u*}Q;y!0662oB?DdX$_GXHfepp+(=?IuEGr}aP#Yu8 z@hjBhe|9IE;929N1XUpPq_donrOm6oKctM$kPK>)_HFBt;^LA`+o-ewI)Oji#`{o% z4-Y{{Rtms$Xw9NK)C1F?*^xT{YNtOBW?@R@rBt6MU+uxw82#S(ih}q0nR-x4fb;sL zCbNi?RcECOB<66+r}eZv#`q8=V05X2WD3niaAfihCpoW=&2*%>7b@eag&JYoxfIU% z+ytYd@ci0I<3e+~-JcA}{j6?}KMZMsqwap!G}7lJ^;7_T%&9zq-j79v{JfWyvS+ZM@iGl zA@gZ4Vr$k(B`S5>i{JKQC;og`7h6xA-EU|qd9kXP`rRdU z_&=w;tN%U*5pEb?m~E>c3`wR3+IRnYoo*~izvPMfKoJB6Fo5y%<0#R#BvD-ykFvYF zFq1>wS!L!tCEsu*xOLEg0t)G*N2bo+P1+A!0jHz;9zSmzRM4MiNeRMSbnvtP{x3f> zV%!m8GS{B;{LAge%xFAt;~}BHKtBUI-n37_mMDU0q%5qwTW~I1)qs^NJW=z4Qf{Bn zWLWDnZc@9e@_Z$q*dOg1e=hr8OjpV8QUBi%k%#+4YlL`}aP&s}J$5FDWSo&@yqs86|zH zMS34)W8|_2N*n02Bs}7#6h%fB=Y__y!=x`{^Od+(p0!?(zKgX)+b?T^0XoJYE`bid-Nb#lsIUrS)}AT?mpMNSeM|siV2d5+6KyI09IJv zXj-rAuR!%OCi)odH4L`n!^A(fp&cWOE|0k7Fdk;`0+^5_zUhX!Wm!Rhb5piui_<=} zttEOvMQrtf``A8au~k%9nC0-Tq1g%Lxd8wrKNWgO&?auj#Pu7(qS?qSExdhOcer9| z?4!e#cqYXdcs64S?5+Q92N5^aF* zElJFbREd!6_^|<{3W5qsn`B8=5n`Gy66zG3TJiGB2{2E?I61!l%sJ8(0(O}^^{bi; z;Z{Ud+!#-jq0~>HW3kga8KKt*AQd?|hDq@cge8|NzD;-B**6zHdOIMTEy1qN zhvA1g-GKc7r1+?;t@IGSbU?^0`N7R&ae$eAs`{hM>(5U zPnvDL<@pGi3PqTxl8!NCi;VvDAENmqSC~*p1F(hNQvf6-woW}{pxOJqVbFY}hvkj- zVgCPq41ONtk-u43DZR%F#PwR1+}gMP5tlu3t`%=6QvgpLP5KM?5M6`Brkx)885hu*_>*wV1mvvbilR>65x#ZNz`WYG zSr!&U;5h7t^jjvN`!5AvM7??6tqZx!0MN zq%njJz$-W}vsXG5qr!F(3vHOc^H~4K3<@Z1Cen$$M!xllQP%d{*!wY0?19=~!-M~R6|F^im;}Rrmc)^gH7>I5 zQ!9f=w96OmA|9nGOV^0xV_|xmwYyg8;Czq!KTAsWiuQ1taNE-0+)f*mdL_EP1PVJ# z_K5)Y5EMRA_P@-)0_0-1AH=w?mg$u|eIs((_GWN3$9g&HeEK6|;#lS%)(xm(=3}ox zfT0kWnp|z#EV3EkapGfF>>_Zun=G^?caQRz{`U^TOhIqrwSC$PHTk74>uLmN6Agle z%wUQm&s!8)Pl%AT{<{UkXwq~p1}!%aK}<->K@stNaM75RY&m(N#5w_baqZ_~&p8+h2<; ztX#SZM_5;E*9uIfQ3?T&l+VSTl6W6IruIvR9T@0=si`PL4R*P9p^--{IeGGWi+dg2XlH^r;_$1gD zVP-FUGYf*vr|!Gf)XARzt+>-jK=4suKGV~6piO`0;K2SVj&P8dTnuU0fli}s{_DMB zv0%B=8I~AEX_is`S7l_=r^9YVVZ*0XHNS_(Ml=$;_A2uL;00a?Ds{U+_9|PPAz?`A2|8CVyZqQ z3wpFo4^f+HcjH*^w;&2z;iq}E?y-W+K%rDm$x-Qb>I56+KEp9ewdSljA+9ZRZx6M< zyGzV)yjDAiNlwe5W7G$zP%bJ9YGcYd(6hHj>FmFv;e0Vc{p^SNVGG<6cMf0c9x+`<&j`M$fHuQnC#54B73dx+;+_0j0tLUXbb%OR`^nn}xRO zjMs9XSi;`AD}}RN>(uhxZo#1GVeNtOQEp}#7 z>kj#qAKGHH#~o<^5#f-iIu>n6QVixvhC`2V znm9A<7RAZ{K1tAjz~o|B#O|K)6r>$~(NK4}qokEQgNdQ*do0k0%}UiTDxtLhU4kwF zDfY8`lpJ~8H=30X?HTBCD$~uuPU`|`7aYJ*FgG;#5HHZ&=xUpTP4iXNcbW*5W>L-G zR!m(J-MQcMCn{p43j=RU$B;T(*_#XL5Y!55I!l7NBe@g=AUjH=tH>Cg^#pc0sG#l3 z7{{~0;5s3V2(|8Oz3&Im6qkROp~ITkHt%odFuFGq{w?;)g|srLgtxLnVixvBTm9!i zqv`NDplpmWkDl<-E*>2ayM3On$7)uKILY_hydYUVBUkmY*37%tw8b~soiAc(5-+^- z-$e`6nk|gr*g_)#1qP{2hQ?0Id~}p=w+E+pQrer!hq0+Vp<8}&fC>X^33c|yiDUPk z#f;`$>GnqO@lliQQ>Zi?qC+l=FT_uWPWfqxuiMioIxdr$>RoL#!G2;r@5JYSL$br# z*x0>t9>R=Jl1$pAmHb*9Q^CjimfHXtD9kv8{oo?PzBM15r8N%skyq*9JMU(GRR6YE zoY?baAQ7$dD1r`e; zFSSw{${}d1dt0y4J-49q_-#Rgv7{y`PtjJ@@JRnJVul6Kn&HHdrSb-%H@c`IV5}6! zRs(nmE|Esd!P98F$a`Zgml)69M0K*S^=jZ~g!sMRs99-guR*jTpeM|bJld>DTlF8S zvYAxQ@}lzwdPU=f8-)m7hrXLE;jNUGiXPCX6Q!6fuHYgl40=L%Di2q4`}fw`ve0h9 zJcJqxj3R^UcqVNLL(p0BvaIJ&sM}CfBGLh{nsIps--^;z$o84#;kg9HlE9tcsDdpo zVYcXOaqj@FWOSaK81TNpvJ>F-qHKX2v*U^D5!USPwW*V$@T}3&6=g&zAK6g6rF2LJ zdH^$|mc@9Oexm^7LMfs-*>?(iOA%m;>}U2yM6-Wfm|XUD7wuA}zg4-a)uYIa%fphA zz$KeUsMEurmWE_}{tz#GPdA1Xd_*!02>QLoE?mbhK(^nYyk{u6N7woXW86$4K(0#@ z9$8i(aqzgtqn_q0u`Tb3)aE z&h~fDZde1`Cf?Dc!QzIWfIazQioL~X&r>{c*|UdQit0gi31GK$Ky+Vw$hAi%gsu$B zISil$e43bx4~bO^TRzIJ=uMd1OP%Z$>NCE87XG_Ci(nrLscM{I>=vp8M^@{3(8uin zET8Qo1L`*4L-U^`D(sakG;LxO*wA*O#EFk8QQz0rLmDz-rO4Zq~S@NSX5+ zv&tULvA{B{_pq-5m>hiuDD5+BUxG^lb$%Obfg;LW189q#Pgw(N4KMnd1x-!o+XnEg zPZc7n6i0z3V9cg_M6BraXkQ1~+Q_w6jBs(gP*-zH*z+m#0kGRr*&DbqIHKRaBN)Ab zdB{W%SnVH_0Hi_gys_VIT4CREd;iiNrH~ct99@sbRVJV3jLU%5N34_tvi)9+4UnU% zUsd$pB&cW!Y<6Hjz{PitIr2zA|Z+EB$23 zr6pD^+j?Hl55E^uphyn81_XiAqQDvD3v>&*0c7MyQGuRhv_}b)v0h@cKsBQ@mQ~oRfT0SuZ1_UD-zNo|8pzA)i*DH@n@rvF$v-_32qWSAb~vRjgSq z7MzARC@O0O0_(J5@0UCU0{_I+dvS}O29{Z_8$0;x;|Av2^BLjU0@nSxu|mbBjkF@W zo8NjQh`@ck%!QsDcDMoB%Y9ftIhsWD;)50Q5xA?GG>jY;RhxN)3uw37^Y@YDZPb~} zR7$|>&n-t*yRF$w66BkKa1395_*GRhLR4&vX#4Ca_3l-9EaJbDR;T1-#g#IQlZBDX%1SAn{3j;Fb zj`57$0BUSYI7Xq!s#e0UGMuW(v=&Nd|7ha05?;`B51QxkT@^Stcc102#7-X&=>X^o zq-gQL5_;$o<>_qJAKzL~`9FPYA?k+=xCpBNm}#2gni^bXrz7Xhda*Qj!VNeHVnJ^E z$5GAA2|cr~hFn#vEoMkK^VVPSfgydZUPlhVCICdS%t>NXbh5Ox#J{gtFr~|{ zMPKjl2$2T&_k=hTd|t^*Br%*CQFP?ni$>kdS@t~!SH8)8MFUK@dr)5hkkQl;UG)T0 zL;#3R_WD_O6|v2PLWF5!OE{CDjUIl~eJ+W;<9|?`So1Y}=OO!<`g@*`FeBbk8+)T6 z>*xOvW41na(X(yEy!OV`Cz0wP+r{WuO*f(iTHi6?7o!AFJXEZgOQ9qhA3And*?l=T zBTNBV?EJrc6Ji_y4*&a22!OIyXT(tl@?>j7v-$%0Hxa?oIonL%-9Uc!#h^H*=puwy zk-XO9ni=|S(zzgoD6zChrfGKcP2CgtxVj|NT~zxo^~vo|7;!-CvaOzJQiUjAS=5)_ z;Zo~`=}6UV;8t%d>zzVaK|vIzQJy{Nrf+g<2Wz4zp`qbOaj)*!MEsP2Agnf-eb?vi zyzO=&VrmKD!;T)jcFcLt_;uB~xe!@Uf0>)5BG6>QMh(7x`nT+P2vcDdZmHT)v%P^3 z`o%$2N%DGBejStd+PYVOQr6OH8lv7u53HWeEl%gpga{63eZmwEjRvn)(Y|k)akQIO>+vSt3 zSLPz#Dg)lOV?bsm#OBH*mjh%|X4T`l1`rrP5B43=6+98?HS!wMc@mm*KTCH94q5gz zyf0w-@U6qu5=>^*kpnaeK+yN^b9Q@m$%4879^1?{AD(s^770UC^*dFGtp`wch3D9a zOWJ$8?9a5fbU5>alh0jv34(d9XEw^3_oOlKD7ZfmQ~%aWpIKe0LSy;09(VkbN*Gx8&cH| zxDX}E*lYb0y1M%q_^gwqd^V7l><*8&L#(I+m8W?NhF#KQ&|`0N=4d8ebVT z(w$|oHe8mYb9F|_9gyCJHNaouZp)yNrJ6Y^#aK(M#j@v517jV=mM}<$!x%l=4Db2DrrX2_kLHj5n!QOI@VnRsw2RGoBP2S zbLjyhbg@^l^ni-BU-m00q7VxkM3)%4_xiez*O%QBs7>q> zF=$huH0tdAup=xKH@&9lmDDRC$+qS47|Af3vXVKk8`7)D6!=Tr`~9v*rMFy1uW*aAx#z@bGvH~yWa+vp#%u?VY-?OnJtLE2Vu20^0(cBTK|2Q3* zta~6A0Ah_&hlT3`C%;eEi#)m0I&$Ky7ZLL@r-;O8`q_D;BKAVuv_McJC%^p#?bBD@ z@@!0{4P(#J370K1|8kyv2$CO&yKQ;XE-^0#fV*7D{Eh*@p$lAs;%MJsL%ouRVm4<( zwa6X5cg3{0V`fL4@Ayk3Kh(LE3r)WBpT(%!SP1W$xd(RTqYYUA9Jb}Q)UeSqdG6>i zb!4??+)Ngpx72)q_$bD6wP85HA%g?$T;kzgb-=~l7YiGJJqmOK=80fY^D3#lTl>Oo#wmy;Y04@sRMrmU@3DAY-lK9 zM4uMR!$MrUjQBFUtP9|2H!L3Z8kgN_u1ZAM)Agx%1+OxzUi!)c!+6^04r>?IIq6K=>|{$q{8fLW6Y98vN|oT2nSLw0=VgKW-XxC4JHW zuCcX3%H-`hh1$~@+cYM~BpiIuXWsw|V@Ph!j-su@b8`6^MLHU`U47qxovrYO!)kHH z5gTQL4W(Llh$&hgef2aaFx&20?t5d7WE22G`8+yzSVpBf02f0a-SbZR&bThXd%G31 z?0JKSnhe}DJr!ct4U9#J6th@8xUHh6!TxYc)53BSu0Gw}+u8JEYrOC1gE zFYP*)#D@T* zhGBALiq@tK0WdYRgA#Ufao%A6K9m_ThSjy}RJB-gi?6SD#!GNma22T;_1$z)r;l8C z$=-x0a%f3JR| zF?bysalQoT-onew>|i+I zYeQ$-j52zDK$E&}PHCufQpo^uVJ$iw7n%-nX=b?{*HW|?uY<3@Om4x9E4~&6bA7pejl`Dw?1SY=m7jM3)k3m-i1PnWd)FD( zbh7nvy^0Eos|bq-SXL1!SqmW2RMu7Lf`SkrN{J#(YD^%+hNuV#C>^4Uzyd;~g&Gi~ zM?eJ(A%rN>Nx=ZY6q0v>y6gHr`#kUc^xhBm>;IYm%$%9iX3m`RE9sToC37aSY>&*@ zpv6+ojbc|tvy0+D^<EckJVtr&ja} zNDYkw;wGi48~R`7*_nvS$^qduGv5me!l2Yc`O)V$EP9xpmE-YgYlv7A3W!b-H<8nF zYV{$B^j-tKr|oEV0x^VHlW_@l#gtjLgEi4wOgsav+>Utl!V;~1#Zw$w-WJ+L zmMa*yhBut1jRObnxl%0$Y)=xj6x>8tMZ+3YmJ3fCc-c8nL87CO(BUNtag=_994Sj%DGjkF=vQ!JZ$P)8X&a{thng_TM}PDT<#xU8bdR_`1!+%A3Wyy1l7g11KHs7nJ1{-j zn*Mm5=QdM;ht+^gOL)mD_*?jvi&6FVky|#!{0QP-i!J^2gpIp45+?#zf)#mMQlYVrL(gd& zULhOCKT|`ep`*ei>@~UVS*z`Nus@x^`3g=?C84aKUst4pxR-h zf?|0Fx9uHa&w!FPX;CJ>$1G$Kx`;5JJy;~%>dsM~ZA@NGSPuPI^=PmLT^lj?aR`fN(5D$c$?fI3nyYe^h zJHf0_3G-WXY|WT8xNdb%OvYjHBhCHrrKzKaaa!mNNo~6C-&$Tt&5smX_!g7jyr^!^x*)%&zDgGal48TseBV7> z&0%NaF1f#%3 z@5zr;{kEqa;RWaax|Tc*&MHH`#y{(GE=*YuF>t@+b@y;Ab-Tl^W%#ni`MGT_D#c~T z4K6D}`Q;ju4QdeE&dO7#=VxFe)bL_bxMRB?^ACs!1ew}mN*#3{(%^>P zj=b4(cwZzhJ4Elip2dtAH0?>52XI-#f2#P)^zIR&)KQZTY6{d^lk zubEQ2W48VQLa;mmc0b$MyFo2vOpQV{EK+FDs>d~zc!Ov9|YA5qW4itdjR1aH0e!#G*Wu3lCjA}WeZar-Qkq;x z{?%1xiUoL`^&8&!23b^8@>?z4+-w{#+y1z=MP-GDvrm?fHudSb$H5)vq=fkz#8^2> zHnhLtyqYom$TbCcGVB63lNg9(23}xpN#8#{7|G&4OkdS)SP|2m8#p#QhzzF-o!_5( z*K~(&e`nA01q0W|y^;?!=c%eRJoXJ%xbR~R`groO!$xtUvDpZyy_QpOM=hnXP~GHQ z94U$(Jis+25DH=+%;2LT6saJ_k>@*zFF*3-DZ^U15+~!5q)1dwJZs?T0B38@k zXFkDrKQ-6U)J1W(jG(Mjjt4P%Sc5mi0iDe=_e@p>uAAJV3z zNXrcP4+vhd59U5BP@xBZ`oxdGH<_h$%Lx|rQ^zbzMQIUHw^+|anIi+&hW(`9NUjRl z_7MkD*FSN8{Kt!kA@cG}>#5}(iM$wH`EBG zd);{Ly1}m+Tm&(2Rs4;J_~k3B#@@XorEfXV=65ju#>&uvQ!kYHw3K_7(8HJ8=+_RI zq7Rd8Xf6x#5jG+S#=Zo-wT-bS`&Bo{7ZSQb7JiqBKIQ@`A*uOQAu7r@5d-)XeV;pc z(z9FaGTI<98)DhNN@- z%!Q#*l5*@{N_($GDAm)>1YGuKZq1rG?=V!-8gau$#rk9(%U4%P@fO8~#$!v3<7KW^ z(}I!}S$=q#WL~r13!0RQ20Jy5U^(J@H&>QiEXr_IOXQ1kqe`7trOSF%t=pn3 zQ#dNQd!3{@d7I?bKP(^cuD;2x<2P{{kChlJc(Qy9tfvsc$qozh%3AY&e*S4`XFn|y z@6WHyYZ(OnQ~v2_qa!GHGiDxE@a&1KE=JT|vRxCgts{|%U3T_%@arY1LxbycaaCXE}USJmp@t1AHbAq@hu$Y9SDjSX8iCMDE85hK%`V@L#gNPFs`=KGPUQ-&5`wP4+9PXIQaDO(2p6xLy z@@SJAj(<&TFbz3?X5xra1~1le88+shiCeVS#cIy?*zOmQ1u&(t9FK^jqQPldUjJ9Z zP;rY6WLoB&_GZP7b(fufqvS-7N**5H8$W$4?B3gX2z=qFHR#IJbg^4?zy>qL^~-^O z`p8o`#8^>mGf`ikqPod$xg3(v=As$^Wcf#_Y@vG|7Ey{2;|Ye8e(2_H72Dvl)idAY1&&-?;(b}to3Dehab_mVgYX}j>{rp7PyoEG32) zWf4lX?g^f|%o$Z)q_z9b#&*kfVUtvw>&l{au*bifmzkUs5*!1PJYZ9=IkzkW`8y(d ze8voiT*EO}XUAvnE-9ZogMjUuZ2Ge6ii*0-({wuTDH{&NfLF~a(Tck8-1)Y7Lf!Zo zn}yER5&Rxw-JN`!J2@MvV>OUXzV>P#6pekgS@_Gsu*~AN>0_KjaWyXPv1jw~y)0@C zNm^0orS#?lf4DmZy*>tSjZq>`?sTF}hq}Nv*Xb6`oLsD~DTO!$u#m{@^l@d42goW> zt$+|^gbn?Mki>k=`6zh^z8Tq-t_KHM$06n!hx&XA3JW_eA@6xEv{~L8_V6meAK^7d z{CK1fBG=(r$>sd$dwdt~4@@2T_1`SLSzjU#RNbY#sr4Wx4&!+|RE>q@jl3o?jq}IW zp!waA3Oz$`(a_*qAE1_GRepXrm>)2%Z(u%k^u;&wlLykv&o}-HnwplHdY1x+O94PYgukSV(m7c#pC1&{Nv$^GvRP0U^!8X3P&=**rwPW$UA5{vB~yzeSg1R}mHm zHMdX(2IzQD#V_}3M{zcyv{txml)!?RYQczg>>Lnz>#90>&dTrmjw+B-OL;R$MHkUS zf`iFECby(dc4~|-Ee|`vk9sLlFdH~lU4uEF6aEo8W^0>6k+j+Sll00P4d;Gg8`|Mq zG77_wobkwG(dlIo4lN+Y6-7y~Y8_3CC-{qL(lXL!?CR+#%{o1tp!lceF*}op;{F;o z@#-=DfQnHVv%R1lN#CeyY2K+dDjwUZ?bMc_ZzcaUNUTm!wZdlubb`)iANB>Z4uUz@ z`!b-2HE)Q6JU|h?mB%yCDS1stceB~K$sP+gw=5;l9v?LMhCa99pV}iB10LA^J-W08hCczB*f7nPkyQQ4WH|{cjmR*&Xmse?F6rALvt*xDx;tOi1xYI(pqe=1= zJFycu$MTLaPARrLx8EtSQybosW08m8@g4s+xx^JkHmMW}B?=hW0lH4r%zRkk+2Y1J zM0@Ic6U~AQ18u!GD@qItA}T zp+}UGTtW*qKirW)Pnd8pED$&@qgZ7ccq)f~I$y&`g!-z9yL<|*=n600|HbNRJ^h$# zyr>3Uynfelss|gRY7!I@A}0z5#kYqABR&3A*-r`pY(pyGnUs?WyU4b19-CRi8o;#n z7rQZN=x|MdA@Th1AE3|&_BL@vA$wu2x#+X`)$lF&wJSQw>I1HFcugrrB%~7!O-%*2 zf7}5s_0XUHyW=>eo??J3(dB$D7L@<@6?lirT3lr_BR~kFObd zf^m)?+&K<#J@)ucvzFjKq@Rc#GdazYY$TX*PI2+;b=*>KXmyZh2x_$+!g;JcB5%?b zULvREba9*-$|8s%Epn==$b%TsVh9DjK($XNVR2$4jGrz7Lk|r1nGpNU3IP=MdX4j5Vhot01ycZ;NJ8R~-x3hk)^Pxf zBq4FQ>y#KF=4yHt0B(|y&^x|_mK6}Q)O2J^cHQ;r>O-N%s45oW-gh2ygA6jffle-E z>|Z^iu+lcieD5>~*KIi+=Vezn-T*;vp6|1VIdikeIXLC^OA#!!7do=hVLIHOS;BkzB5=hM|pV;j_JBu8+nUeJ`n8o1z zpeR!f)}!)rXUBrU91S3Axh_nXlU%$2vWAak#vu=7jKIH!(V>oe3B3EyYvHECPo`Gb zFaZ)1<17JHPUU=z#Te)lZi<(78Nr|LnSDPUwT*THiuYFYEx_R_C?oc64=d|PfSSEP z`_%Ylzf_IcqUTz%R_V|I?b7t6J;9ER!S{Q<`FR%9V|~uNprG}6V-T%Mi2g<1yBjia z*i?d-CD^@KkQ&yHR`)R4CK+5};Zo2fUc0M9m5XII7aMP`<|qO+CDv2r4?pXvQSl*1 zd1V)X!l4TjXMNQD#ngTZBsn91DKA>?^7SLkQ4PI1FNeN$HJ<{MnaVZm5Uq- zqYgcma={#+P7(0KlE$B|Q90QVwA$avb=s;%JHcQufCs%6LK)efZ~A4(yPMR(kW!O- zJ`cG~{$+bzhF)OKB$J89B)(tT^;eiA7gQb<=U2aoui}oSF;vR}Bt#$`53qp$5)1gV zM^4UyXO&bYWrXkC#Pw#rs@))K-$-|W#l!Slws-#8Z}STmE__UbhHpwb5tBTsWBd7x^3zYCq*z(S z!Gyr4qohZlhZmgCx|IkcsKzhSeGlXY_U~JGWgH6kN_(P~*yE2UEUev{_ERNJ>%k68M(s=pr0lXx zPfm625T79%>MhcA$b2~%fVP5zw>sn`;?g1r?xP1t6VXe2C&OJEO()G&y|iJvr=_R% zD3a2_w2YISLsF;}>^taTfDKnlF=EHXg7aj6m~$S*4}rHWx=6M=Ke`Oq<6#}3Y18x( zzL(&7qy=84Bqk98^Tklr#_d$}Lp1mSxGy?}Uxquiv}%t<@ij3Abadn@b~gLc`-}5Z zMx6qIHVAL4nj+gmpS&XqnbQU#;ssicvgPJJa20EI+KHZAs|qQCG#D-c)_G=Fe58BV zS{*!1uUi~ZHFjWoS%2QfYuoq^x1_|sn}`a5S!UWJe~XZ<2G!2wtr{wUFH+iLR=LFD z_f^|F>d@dRCp}m@U`y-qO$AdAq+?Ufr`CuE&Wi7_7^Ik(*6AmJ5IFLk|^=4v`%zr92$khmZC@7SjQxF44f1HmU-NL*cZ6qwN~_E4zT zZ_%3{Ql%w+0`Nl;R}nW>t}R(Ev3{kxmc(;?K=IAyyHXM}d(`G+LnT&4_Q^@S+XQgh z8r{lQNL)GoSn}$#v;NB@hJc0Ms$u5@{s*0`irOSE@lHwH%(YqEEbnWxwF>*15_vn0 z$GF3OkdT%D-9N99!F+mw?9lUN=LO!|!PXvahN+{EjgoSa?!4HD-hmhj>J(fa?# kt?)lPD*x_OnWAOVdO8?n`p`STcoHX%S^ipd^xXCT0pXODLjV8( literal 0 HcmV?d00001 diff --git a/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/chart3.png b/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/chart3.png new file mode 100644 index 0000000000000000000000000000000000000000..d316a85a4c7606c4836707945b6f53f39857f141 GIT binary patch literal 22449 zcmeIac|6qX`#9nbYHkE`@2%)H)ELn%LO=SzAh`}_bO`D=*7mhR-Vvd9u zGgHZuwQOUXnIeO+OpGyR#>{;08Pyq__vicg{rCHRzwbZJV>&PQ>v~=HeO>o;U(ai~ z?^>KRTE2ASQV9u(&(kM}Pr)R*HQBT9b;k} zz2}&TO;?VSE>spIG+SFZ-bV7ZtuW^U$(0V^~nJKKT? zMItz?SbL%~Jnvq0A9++lA_A<@%D>9Ww3$1R6Fa@A^@&<`G`l=|w=jL^Os_P=$0sib zgRz57zm={pz>byGVPz%G`~g<`N-&Q}Y(VV@7-)n@9r}7z8$NY`fZ`$O@H9>eg)JK! zA5WyS|DIrQvCMXdhN!?qbFDyHjMh{tt9&P7kLe`+7&0tb)9<8wcd<{hR6NxcPDl`*>T6?PvH9&rr+%%bg@$c(HxiWi*XOQ^N$F!e1$6 zKY@nyucZe`+}UHSd-ciqt32yg9=E}$js3QSEhGUIaEJ{9(=BOy8{R}b z;ehrljJ(qm7)452aO*0U3B$NpwcxPI(IWU?GMU&G&D7{ zqSQ4sR-6vKt*!3}9>+7dO3KO*#z2!Ma?1zRq~!+1#<;0IdBH&*xAX6_H&_QGj>@6r z4mVD>d8g3$^fU$zEVmV^1U=NOP8(=Uk$E}kWtbwL-wx%Os?Us*@bP4N^+hBSgXiRw zjaSLE^;Sl-y??wDm!;~!8mH&v%LX7+aTH9w6-NKptB!_13%3knpAD*I*Il@Wcc?#% z(savaoZa_?Lg6rn8%DMDc|+#Ob@opWQ{Edv!x-13t{g^uy&-=<-l#udi39;C=iZxs zSNdc!dsG~XO>t~$GPUvT5Ul67% zRqLDOhg~Ednuut$WSM8tKc?E3b%dH=h!z7CZ|QXURWpX!FN~d6Z8?p^?r|};AnFkJBDv} zYYp$X4JScwiA3pjV3Oh$>)kYdE9G++U3CPO>S|rgFiMk%M9%VaG0`74N#)R`B>aB| zTS>(_Kc4I;;Qe%1CH?<68zp_$iXt>k<9E%oEi-12Wmp*9wk}@P?(t4@+toWvElMb1 z*wFDxY51t;`SW}AJ&<)ukN(WAjF8S%w9ZT@y3nZxIdy7~Bs_3V5le8lOkuDR&dh+m z{+Z6PrjHp$ZO=|T=B#0Yf8`FO!c}m7KrazfldR#G*jV&cCFw<@4< zCYca7@~4^EgEHZ6JdO<`6r(+^#PBKst_<1PSLzEc^;MywbSG-IQ9FQkw^Va7RQo=1gGRez^=vIH&O{EG_yaN$@iRrP zM)-+XOg4uT${4?Bj6hBn@;T!H)cO4jR!`f+`um1nEYyf1PsX{VdaDjfR;g zG8z~5RwpMXx3!q-`$UognskQ{oW;eQ1iYmAy|AA!dYKp&%ey7hjK(BFJqk|kSr<`x zuD?S&Wa3!~=X79*a_6-=WoBh%B`wK2-x3@W>hbll2qpdgGCI-Ex~TxozTG~Dqb{%%kIR`@HmnYfXf{+LjNPkERI|CWreMQm&=xrJvO zJAHTc&LsI^j{#VR{imJ ztEtTiI`neu6g@;2yz5Vr!cIn-i52X9qCPT=(@`G6s4wv8E=ENSMKKFvmFzO3mWNxZ zN*g+>d}pVZprE7i#0rCPBEkdjHkP|q4Zm3;e}F3&Hhs3Owe^|3y?v`ol&*WEE@v=f z2$5@>r&b-e=k(J^d41nF{waBf5?`mPrh^BKagNJEN^6{V_{T?#e7;AB+w}8|*id?@ z&1bpus6ov~#-z?20Yk&|rc~WzvYnMx^S}zN&>IlbcXh8A zfw|_t9rEj@@o(l?mzfe*qcSYEZ9rcTVm-)<VD|->#U@()APmk8q}6#%u#x z6d?|FWbc&ho~+1C9nBu26h?U$w=0U{^gce#=6$@}hTyd`=0!WlEigsHY%XV$(#b>F zE2`q0r?mgTT0*KZF3SUCqZ;UpqI#+^{$(QjSc{f^r!Plr6Ib&(8RTT=FJ zPayuQ&z?92V4|8V;5zhU6mGx1Xv`b@n9<;jAU;{cyY7H6g{Gx}^*D_U%G)q0I_ASe zMuWA|i=n4f*Us4ZycgWxE}t*VJ3P)+uTJ+e6#(h-7L0;aJ}?L)o6o z*qq3QeYuK$UTJS#0@QcppFpah14oFOiA^ood(i2N99FNBPO9K3o44X+@dXa25>scP z#LtU>R@XUp7yGJ({C%sW82_@MiKv#G>q=kY$1JRcnymPVfWqhID&a~pGPWTOG3(3l zC-r5xGoKPeODE-{AKo2tTWUCFX2zs;j%VC1&b@)U8_{%!9^7?E#yLiyz}Pd*?^wzh zVZEPbQcwH&X{|Wdwlm*MKR4`PkP&ACOLv^x(p0rmlHfm-$jOVED*Gk#<#efYeBCA` zWCqbqJxk_fFmm{0_!fB0fy*W^@amu-K>FS|B6F8rm7i7M-9*Ga=0!WRUR>r)`Mb&* z`gHO;T;>(&wO2~b$Mq~Gyct@ux|9B8=SzxHnPHrBuG`?RqtYGx|D0B4b_x9$vbZ1P z?nC*$iAjX zfnDI{sU?1~6Z(W{24O2Sx87o`_vB~smZ78rCkgme@a0RWsILO3&;!goXMabOKf2Co%eJl zuvS3+z@8qBLQMBE`yJXHrzKyr8k*3U+r*~7(&%NES?V`sD2$6JLEI(-a&Ib{5Fn%J zdw|Z-4y4%xm>BbRShCq{+?1;e<;*v?lRK!>a>}K)sPuq4qk_s|zUZJQ);W|fCSe7n9e9&WLJ1IKP*5skazs(F&(^*N>L}LSpXTZ--shD`{ff{F5iNt z{Pddvt3csKpX^qJn~fqyDG+}KG#60-Z@oKRuIHv3FjVIf$>#(?o&+COfO5)qck<+O zMrv}Yi}M$45!pR4LL{_y0W@|UZ{pk^QG!RnNEMi$HP4&6{ySBdT)sqP zg%UP>QIYPfSZjd}l`Bq0HO2;v^rnd7^EZ2?7{Dae@H0-wV=dPxbY|ItNq^#G&kPU?Q<>w(3&&-h;C2A$+ ztfA;|N^f;I`b~sV&x`u+Yg7^kbfjf7r7g%P*))54u3%(xu6L{D>e$OAu>pF%qpY`@?Mv`13FrV ze*yxL{ibJ%8*0 zVDg7LE`?8V%2+rIug1}!#rC3G*}LIx^CX?Nkzo5aVk}(#)|Q*PFjpz@T@bzxju1>o zlbVuXUJX}{JI8Z)1yZ@-n_gpHH|nITdd@DHGhBh2I_4Yr_kpv%x}DL2smqUuB`Js2 zV}}hM3DUj1a#(uH;uZIlR_KYd<)6YUa5=X7^eg)|1$SoIasI`T6_CkVR$F3~7u|5B z1hKS2cFy=mxUe_5_)6DfBRt%_nY+`6Vy}3nztM z#Uv8nYi=i_?oAM$k@s*Pu(s4}btv6-Wsdl|JJWm*o+XnYgvZ|0zzI%q4C)xcW&o>= zle)IJvr+c*9G&m1={rFWx_NkI>9!>Cq2Aj& z<@el8_U_wHKNGOI*bx{xV-P$KDcN@Pc(l&b2jZ)6D;Z&Al)RhYK*;VZU=MA@q@@#K zf1`7>KanCIZuA|ikrh|0eoZbl?$-bg7FHk>u=kL;PVREyj&swl-qu6$13nR8|J^r$==qZJp% zeUJUJJVwV~UR;Sn3Ng?3>?`?eWX~p#d*xvn*}8YRtpyXV7{nb7zp;lm#AjyJX(va? zovIQzl+~B4GgT`=KS%5JhWz6H6NMpkx_{U;V!Lva(=J9D-hztR>&AEFyFzTf4p8kw zzo_5`gkhT>W+gReHJ1|V&bLZ5UpG@3t_JNV-P`nz1uUExn7ovOH&{EsgS9#D-I7r+ zFekGi>*vzZW2Isl~?H?kn)d>X>!WTGuzE>CPJ*q zmE8Ja>9^~4%Kb@@i2Lrxe>X-=x+IcQPVj&f1ku|yiJ-D7^)h!yjSdw>Ef}f1#ALPb zoOo6@^Qhw-Bq;bcEcwWMAT;nRuga3^B7ZWT{dj!14X+tSCACX_$1C5LPTr@%EUP}k z*&6mz>oKedcqGrXDV?85T}u{>Gy@Fg3~K6IWHHDgLy;Pbp|-${CFd>r5!m`}i!!pn z@k48XA~z$@4c9u=_V4K_f&Tt5JJuecPHKl<3Orpvx_;482 zD%p;hJlr3cNc7tpdu7Nw2ba-?4LtQdUiID7vM;u<;`CQJ#9ShAE;&>+tY!vJc|^Ms=?bvCSVod>D8FGq3FrQ%MwgZ8z-fXP$V~!*452 z7L9k(YOX1hmD3M@-#eUQ;=^4^O4fbVQFQC#>PXq#d-v{@cf-f^b_AFu9Z;MN^*3hO zW~vlLoQ8v z+~-T`KlC_VnF*2^ny3&ES|4&* zym&D+0l&=spqICI+e^=u)(4v8?6R`5=4$znFMlu?c~F9$3k-S$p(1j8x0S$HQNYu+ zu^wbP`9{VPK9g1%f0vKKOH^3<^V69Jh(svIgGr-#1zf1QzhQ&U?P9OC-Hcahf|&ta zBn2tpQK$De9m-gzZ11X4aQg2v*Sg9Ay)lUIABo2l7CNmR5O{L@lfmxJDJpu8Ret$h zxW?yAcwgQ>HuD_&5&hp`n((k7;39~m)9xwdTM(UKDYT)Xp}?`?Zr}a-X?P81fuGlq zf12rz7VdS9qezgd<~~lPp$wwD$lkAklrt#h4hBDL<;~*OC^_A(7;61iGKu69`C!BT z9WDc(_@CwZZw^t%tL0g#YVltN1B6)x1zc%qr(*ynYBs3=rU61P>XeZ^>%0exw8j^; zCA_Ly!^!Dj(oo6-TH)==a|NfK|NR`KlR|UTAnALU!0&1;q{_<1k7=cZ202o!nx&lH zQg~yqWUGAD`0)&3l3}AL$*_VJ@G&^kS%ufI0$HDY!iTNXb~?DS65IVwKfkf)KxoOa zUw*h=_ya1p9S^1IScjY!XO)CmvP!pTW0T!R!$1Bh)_V2H~pR%YW9y`c` za=VD-S@#q7dn7Ru1&&sBb{>%pY5MwzJ$IUpWeAa*eAl>3WsbHUaSey_u83CihOBxj zYWH_rvZ~7}t<0riF4WFr_|l0+`W(wbWM9<-vUSxBDZTTJ`ZHfEK)(1y(aV?F)pGFq zP4LN&MnJODjt4}_|7O&Le+YrC%_xw{xn&&-=J3yccc7UV8*_SMkElFt%z6UvECIkW@ z`{4DzQ$|5&>^E{NCYcNXe)~w#tA8jvWyk&JqQD(JkMm^pKt zPf!;ZBn!G?LU7UHNSDYHn|0x6ab$KvZi3Sp%zIw0!r+_^sAoQeV+5T3XJi&)?MqWYNlS+;#SJDP~hv6tMDXh6{9Q*3}U3yatl z{i0eyeAu&P>@QP0Z2&^{BYmc-R`z^$-)r^4$WMHXKcZ%M!a0Ue8^dmVduexRpC^4? zfxj+%GD>W2b}CZr#>ODXDnX3msHCmV`R-9~#FwGAatm_mLdtG{ZkHmQ&SmBt!V|HJcWV|_e-K~t{;r4m;4Fhw z`Kg8DcTed-92l7}NpiGzXN9~d=k`s!r3b#`o*XeJpku;HI`%(kBP-WDH0i9+pEE}7 zOI=+M`qn#av)}H(eAGwmV!6_2-CMWk%yJof+me!;%<^2*bc!@L!Ha&L>3c-qe+zt> zyx3`+pDo2UM1|xi2u3qMNbi)haB>>JIqbcf?GaTc9z0O0H4GD^4m9uv%+i|#)?|gC zgr`q*Rpydf!A87K%LVSRSvv5p!)c{o2z@wUx{OvYUska4+!f;goiOGq2?7? zyWFE5Z4-;`tS#CCodH3%!iznX27+d7y5};())z*5=g{%2ksh6H3^zcAD^4C$Mb^PL zR;)pd{IN-VsVp~4pbao~AC)Mq)GD_-##6to6QBI9W$bzbj4I*C-lq?BuN#R4OO!?o zQw`E|&o;?*9ua?BFMRBDwo$Hg&gwiDK1Q5vkn21qKKi~PelV79IjH=b%T$e?IAdpJ zCMtE1f2NmgztCB+V$NSSPAFiJ(P1t^r*2sH!PRg@c*mTN?J*34P6)C=oJ*Rb7{u)( zx71w!+f@oHzB=J&Yven)*S(Yyf(t$nChxEgyx6|1vtkYp`L}1%n-2x5ASWsfpwpUw z%vNG&#d2|GRBq2ay5RsZ;diS#8$!Rj(LG%g>qb7W5L-kQJ41Z=hg$kgZOR&J`F%#5W`+4X-P!yPi-xvQPR(n0Clm%x$cykU=<{p9u(rA zva&{a$?H|!o!d6e8MbM{W1}~S7#^}71RiqsRHQ9^-6_}o@S97-8FMh?JDOzdjv}2~ z%1bVAfOyw!0K?ps;5Q}3hshW^>u*CI3<56U&U2bM!1=~Ge7gEz?}k|7yWtxn-2n5_VqE24Sk8VbOVJ3&=bd?~eJbf|>ha%P0p~Jv z#w=qaFoG=Fo=vc`PU*%$f_LzZTOI+Vhrs$?FRzL8fOi_4u7%QgokQ z6E_zR4f!1fTLU%xI6_^BC%62TxVg~i@-s!uHUAb{layR^_ z_+sX7zI6qd`JDR{*QGpw`~vZX71+gF)*PL>BPXs`+hiwFQbuVO7w#%ft}S5Yw#V%! zEB}Um$NAZ2;z1>i+lzrBE zPzYbDqt?RBw|zMtt@|`WY=*@C73|&={R826+?k*KRMuL?C+j|aFlWFr_6>zg*3>|> zDw&NTx7@i?2fib26ue&~I{fX%03_0>VoW`j{eZkPbZ6fpX9X^R~oJW#vCGaZY!Bx>;H&o4jecD%9)NcvE?)T zjbW_ix2#m-)3#7rNO{J+NU+*>r~PuNnbu_GJDc@8x3Olaaf*BX0W`J$0GiIy0FSh4 zrX7tZq6Ml-0Ijs183@qZ)x_+_JEcO+w>_N!oX=XG{{hXwRfPzqlLZh=h&i*DMf{2t zR(OxpkmJhs zFKZmN3(vgyxhQbB-I@Cj<->;fGS1)HDXhkblKee0_gDw~Umpg-m_6bR9B4buQ!f|? zczAelPQl?=Ese8pZ{ANqkU&Y3dm5hV^baukLDLRth%ZGQNdZ35QXalTmm2<}MwjOn z)ibL~U@7HwLtiR3=<3FgeIy~$CkI_X@znc{P9nf>_4ws78VM7mo}TBaVI0qZkyQBD z2|9!8Jx$V#De@*J`30>TW)fk!(b8i;mq#io5FHr4xk*k~?No5e@-*Og(pEngIQv+D z0-N$-mmSN@VYJRm2$T1py)Ilh5Cw{j%Gd=IXa!wQe-?|RqO(6WnWbaQ9dl2%$qxsv zD6LG^b)8k~n=e|2J>FG6knu1M@bU5C1k<#qItx8KMy7T`8h4(2az1QCC~{FgG0_ko zJU~b?pxEy{5i1*_;3Dn+2lDl|4EgT>&rlnZJ&YN}KHbgLlhvG#+E}IiK~w4hRMSFL zM%ock$r_t6kQK$|sn3kbEJZozw?5PlJrC!c)PzI1k38nk0|2|oD^{_=ByNvob(FlO z3G#VVoq0D`1I%75NqqlUY?$oQMywJT2q4=QJJhCv{iJ!3=h|~q2FOC zWi1WRkdn$JP(mj(>v6nZp? z6XO|l0K9INP65dPP(4uY@GxU~(YJak0C{o6m->z~8uP5PPO2+75k6Xnh2dciX;zp~ zGR{HSsjPL4A3}2zg3igw$#I4sAP{a*5H|pDXbt#G_#z2QHh^v*oJjHZob)}iqE9OL zTP0b#3bPd00qY4ACfR_J@alNVp^y*ojarfVpT1QI%-YdH!n7c#@vV}L(dS^0RceB7 z{Q2wmsm>{Y$*qnhv+C{BphYZNPW5KUsB806Ay0{E5ERXboa)|ddXf;Exzj2QFs^|aX8rwMp? z!V(0V@1M^?=}@nvi{Qf=4oHEbBO^8F>u!~wnS;UfG!;sopCIg=vO$EiUcOntL+T

O)7|GZflvVm zVO^GAIFpXmg8Pb-)qR8vdxxe_bJjvmZheW&GE3J_);EKsbkKE4s=_Rtc%V&>6S=7; zr)z2c0s2M<`$;AG&`;t;h$5``F{muv802M~ubdsB5}2uSYs6{`MJ|oJ695El=^eLC z)AiS5O+-0}W%uSwFDl>lvzPFQE(B?vjr5@{3%_JzKWP%M9EXp?k9=K0_k=E3l|ikL ziN8wg9)!i=&sUe=vJfuwEB-P--q?||JacOM7$a2<$Zp<*?eDFYaxH&j^O!aH_g=Aj z%h{<~PSQfH2a_2XD@ZH~6tORmoRMKjr*}@#nP^2O*I8grAF6vhU%0oSLgyy32{-+= zV+KNQiC>_{QYER9g3$<)%Tk^&t;=p)L656j@TuDl{@lLI4*=>L3UhPjQNJx%cV{Ch zAM4S@s{!IYScIhSpb!1AU_mN|K)N%>q+YG5c_+xGvMz64u&Q5&z`k5^t`3NAjl)xs zVfuN2GTk-@1|-n{n)b>z#W#B*b;Ys;?5Kd019c-O^6j`NX4-OXK|N+g#%CLpS55Mz zacxeX0K>ZcX#q1A2Wi@v71d*V!^4mlP^I~L-3y2O3G&jj&Ynk8dx*Km;`yx5$=9N# z8v-Xesgq!dSgDO0=PLp^&zf1?I#dpGE{_Zo!lTpTbyFf^f(^juTFZh$mT>$5zGWN8 zA|}sgB@`AN4&4`y*VZ#q*G!p6ZPZ@yod=*~L}XThiz6&jAh*~q(7P!h;M}Tr>eSPm zr}2b-U7zLiC*&88kK~`fkghlhYN1%E#S3;<$#8SvBoPhLc686&1#H5n=pkfw;AG;0 zzv!H7v&*h3haDtD>aCvt)ieYyKO>6d!V8;RbawtuD^xWle)L!%;zFeh|N406{eOMD z?fJhyKK)8N=HLEu19pZknU4DxX62vP4-Y<8MYh1TZRSst^XYP6ik;E92y$5@f6T(! zDDCci^CWc=6qyhLWqF(0dM?+(wJ$HAab^<8U@d*fV!@n^#%y@|0=4NWeojV$XROQT z7nrtf8FVA$_TuTh;X(a%oZ-R!;v>KbefOw=vUB+8s^?Jp)uWpf!maex;>V2SAIu|+==T2ed%uBV zw@Y;-+*_+;bL?37X-R371J$+|=TQ>5j>n?-O_4xtV@_F_eOr5b4xEl7Zo-1* zmlkd+V(N6jNcwHLvdK?j_rCFhAPG5^$@1|!}(DS3H!FWWa+D`t5Xa9rv`?aPaxOA`>G%*m;jQ)ST`sy zC$~Hjw~YW;3`@VFHTV3eYaEisuOM2R>$=H-d2~${bo*i(Hnk9|h6QHIPGgVXyM{t7 z(j-w~!Nw73@L_GvU0TBnO0c=nQnB3!0_7NJYmP~Pc@wHm8Cc|of_*Mkt|ObeWctSuJ6{W2$7E~F{79)%pf+?voY?m%*dY z@73pDA*W9d>5?!uche4Dddj|Jkrr_r&C1$^j0FLfK4NZMTnkv}cVcHNz!=^PYQuh1 z24)JhOL5F3;K)C1w(T4@5Vq$8dnT z<2+KFRA&3x#l|X-TePl;jS>0e^xTOKIS?Mar^p283q~J$BECCB=P0Ya%l~-Fou>Wa z_=EI9KqPztk-Y8v6V`)uE|S8)KI`(y1&5952~c#PIO#EwZ>z5E258)#PlGTB(7z4* z%`YHX7T!e|2m!2!>yL;Pr9h!CyE9)MI76EHBf2StV&V~koMsb*9Wf+O6zBsUkqrzM z50WSI4E_mK=KHq<5Tgg>Ie}EuJizcgx9fxoQwUW=fw|o}6Zcq`8|RNuW&#&82L$)5 zX%WuseAdg~#6&B^DtA%Ngf}*BGdn;eZ9BgMZoh141Om2BP&->UO%lU>^M8NOw1D|!3SIi?~jK=7N z{F(9|%juOd^?}#J?YGb4<)#&-tLs^0H8ok7pYf!77R+1NQfC@d(#51VO)cD68t(M< z(jRlbv5RPe@b4CYzd}PZRNuT&n7bNJ9aWg9%BDo=Dw@dA^&Fp1-=3xvHEP+wmZt2} zCQkQo4JGD)j!x?=klE;vt*z6IbND(B zLs;g=a(c^~k_@1agE3wg4h`u(ST>)|Zl5a( z({Duq7?M20Tml^XOJs0zVK;j6&@ znt6)&)P@!%*Ol4WZ(bTaTsvwWZ0?dUPso;v%<5W-g$E-u83fp~s%yl(D1hLeTF`RM z<*c$+(KW)u%zO1j8HDR~^Eh1!N9zaDf;kPSscPFChEobz`IYHB3GI#N6nYG|j!)B{ zQ5^4XH7fM`B2-~%CM$291zxlnACw(;{BEL^!h#upOIlEd!OXF6ag7Q z&`e#5V3I%2XUPE#ibm~bVRkt z)-@c^ZvlY>zQ!&-JrC*npQbrDB)5Lc7PgB5=sKVq4?mN7YJlTf_07c1oLM(NFr> zWFE^JCOp1wQ!aG|4UWpFyaUA63fZ~K_bAT_3gCU4`YM$`_GUmOB4h9u9x5_tAtAEp+JGGC0n()vZmz?c<^d!k=MWx=mevLoooz`VN zR!DrIp+X5_8_(TJST**g&fLG$?4~$3{}HdS5f?siLER_{6vg5}sr^3Q$V}?AhfM|A zn67bilbCh@2N!BSYxiq07{QexA>ZlH2edq#-q7 zSW}j)Urso>`H+|>gz;Bl<8yEMxyq#w(DdH^He9lype@%9{)3DK3XjWxtQEN5$hkv$ zqQYokgBeX#x3Tk2(u0nQM^peugez=+>m=AeozHb=e(jrO=P(LiobRY0X_pJI^0T@t zPUqr4chkuf&*$U5M!$$_^c=A9ysWHiQ}RBS<5i9L89j|bgyBbUs-Fcd`Nwhw+n6~A z$FFK{Am}-LVQQ~(cs7OOrybg#<}z=N;HH9PfGKiQ&Tki% z0E_U7FsDI!nc&A}r+~K(!e||Uv^*X@rS+;-Fr~`bbJU9s@#pL9q^m zee0Vpcv?oDrn5xk_Ao&VFmvy4+sBWO^ioCjP5zt1t_RhoO}2<)Jsc^`da&ock(- z!7tU6kMoL`_wM&-Jixu2XpYX!-CtexKqg*qs%BeMg3B-wV=h131SV?wPbae|3I+TF zVZU>;BNUpZmzfqwtah(YcvR4mmXx%S(V-PUeHMjE{fML{dbB=07E!ODA-Qgk1-R{^ zA=vdIh|tY8wS7yMfx2gB!fQx8wXv~rvS4Z|D8Q8PHSkqxC{2;k0dnq{QNnaTD6{^z zI^=(@^#JEC=U86Z0oLT?vnY@#OP)>ZYrWJY2UnC|oQiYs-RE}5t?Q*Hb)XyEb)-d} zo8*_I1$4gje9U(Lad}Dmw=iD+%T^CPom6{!J3Bj0weX4(9@?XtsjR@;t)gN}bPRYP zEO#w+b>H>i!2>EWL73pb^e{~l+^F(!xv)NY!zJEzTV7wiG&Xa#jF{7L2GqZEI;UlP zUmXFLN`Vxk5~Np@&fnBJ@H2SPHKN5zKjGi%g?aGayF2Sq`(WgdENukmCF|v*GLw^3 z{rG2N(fg77naP4jVJd*aVU2L0M)pOuF;oSUxNJ~UpN!IPuWrwC7$A`&@Ig-W7FE-R z|J{`(Aod1mUA-XbgH}~k915`8h?^w2gA2Ieqh={4C)SQ#v%MF#8r_=WqZW_n^Fed- z5TZi#jzl+zX%{_^(M*E*rf3J|C{q48wgY*+5WkCIlH~gC?bC0H^$GpJwh~tg~M(lR+&y1jMoTQ5ZmvGB^WB zz6VGjup1Ny5x*TjBxeWfxpX@O1MajbJx&TFI(c!YM#(Ei6{8Z1ua6v4x2di1non$(qTSVdavZrz_+RW!pPAw6X9k-GC9{9dE$Og#|1PmA^htX5oof zd;&}TyuJ4iFVUaArWFKkhMUJ6r&*Hs;N?GeEC^aU&WPOj->QUHC=qSr*)iY}x_}Fy z0v|-8MeDipNnG4Ib=a6=V1KM#k{Dl2prM00%=z-zJk)&o``NYG0cvCL#bxzbgM?NP z)9yJVlJS|%eE!Q-=RunVRR%qqv+&NH%~^OrMZU1BIk+l{9XdShvqYo=TMi<53L- z=3x_$K~_k#ey$jvXSz2d|g?atDh0>LGZ^GxU`L7zUq0$U_S&=P9Td62V! za+>4oi5g5^KE_+{RvLe%ae0-W?GgH-Uwi51O4lYMTqiZ7`8RY?LX6Tv>{?MJ^rdf) z1ou7Ate5m)GK)iBuMoXaQKJs3-(UnTi8kto#A*kPBxq$48bjG4uvweFxFc3v3W$IU= zp7E=m`|Vd>DMSnMFEU=e>gee;g}USkHeB8tRw&e~N1^*(^0QbmtwiLmZ%@kl?%>yC zmrDusQQ2sTFT#!hnbck>aHVw>i>j-}M7ZMiCm&K-TTjXKkBg=dB1!&si=VWj=vUEZ15$#X zpCqa??A@KlCifvc8xPN_#DFY4_%^$X<}qRoE@O0w#0@*qYdboVXQ%J}Ngs6++;*7C zKHgRAd# zO11_TV;S${3ywFJL=PjD=O2e&XG966qo@gbn(Jp7xI@s-`(?MH;y!wBCLvKRo}UZ{ zcQasc=m160&iiGX`q3r!iRINI;ke$`q?nQeM3O#!QqYfhbA2%a-_Egz^U9J;h3|;0 zO*-ZL7-(7=WH8&SCrd@oh1#rCz@p zE_3GM35|>y>coViIqD6*PBm*$sB%?y+qagw z(4Tw}fDO|908hs|>>Jth6J z$ne~Dt%087)x@9o{U|oFCszIJS-IjZ+s^F!eaoqB@5VG;?Ak?!Zxo(C_eH^h! zfudQe^ped#&q1u`h8)oZ=tVG|RoBMF=J~(B2BwkMfZt<=xOMzLN1BR)pEnX1De!Y& z(+C27w)n;dgP*>=c`9a(im!F+&=8c-~QIWO^ zUYL~T704?pmd3AHC6P{E^UM9+d-k-s=uGcYb8UHcM}hV5rz6VJP2$8aYfDf(WE+|M z%!|OX^rdqdC=x+p)yFMB%BurEg^JhXWX-VWEzpZhtcAP#*smC_BqJ~^cvzc)v&^+o z`xs)rc5YUYwBR%CVn=P=EOGowB)1m5aF%*0b|mUF36*V?-zZ^Q=9QwU4rhC`_4Fi_ z>|XWxp{eK}SBe8N&0nW|)XNu5FD+FcE{ZDp2u?xHWX{^A4uS5@s-`>TSe z2qZPZg+8=ui!D%*wF7A^2#w|~wfO{-v$tiq1~sB5ZOUS?XeAx?Dl#{-TC~XvHzb2b z4&o=dsIC0|lIb;A$d^CYI5!Yx`rVd)uwe8r{YQGr1?HZ zeGf-$|Efbj^Lsh~!yu{k37PA4cni}B4({zay9$|`)pRe<$+Hg5PkQ!Ob)9&vi&_k6 z>+AD`irNy5xM_M}^>Pc3mTL<&{OF2Fi{6lF?ahH(slKXpo{J%)Z%n~P0_V#5%}&^*P{4MEG*7R z`L&`XeiTd|QB!$fhB!GnQJbU}KCZKXLZ4H7^iOg^3rTYg-t`~6#~fB& zI0Lr*(ckW_6LrpOPL-$L~)5S#yVeoSGcXe%pCkhlbHXOv`a?@2MgV z$Ro}*efLY+ALKQEo(=a&*rb<+3R&v@Mzjcl`4guGwEG)q_aN?rvG;%V@c%9Ab@{Ln zLO#w^dcL!UEQkFb6`gl*IsJFMnhzf;ZO?MBw@K-7$FYj3Z|V&m<5xzC>I zHzcYVN9@sPd{pi`jGvnFf$svA`Qv3Tc*IjjWt>;}(39;?#&6R*3-nTgs0o^gl&48!3ZO)j(50_Xs#1hnz1`%9a`gY)chvkrTBuGV;Q z>ko%}4*Im3Xe5+q^ap0RUB7-|euiPC(R<^rrhlzWykk3L;md1k=c~{SQM!SvjGr7n zHb!ki=hJAk`lp({nVO}6lh@#y{Nb5De?ott(=gQFjV$5-eK?w9s_WYFbCG5IT=Cnt z2EHETtcwW_0sTQ(&C-y$srrK3BdvkV3NTOS$hf$;1P4y61Zd|^?3E*3F-nM0V>}L5 zTLnor)!o9)At4vmieLU+^9j;`w>ZzRva<7w)2ybp7%N%0cjPq$KQoOv2vr|zVLZ%4 zt@$I$B>DI;cNzYu`fJM^YYc2?48n~4^eo0W-Z|1PXef^QR7XRHJ2RG6hd6!uv~vow zAXlfqwKYbwy{*kDa#Z}&YVfg6N{F$)$IqC>YH^sVQZj*FSa)t0RC_qtx1LfCjDv3# zfne7cKtWJD{W|R8t+B8x*-@j}U!IMMf1x>WLU?~j!Rg0XuQn(h-MR6HyDzUC74e|= zRd(bd&!=2AW`A@vMgaGuHPh?cM#h;n$f@YLy1E|YHU9SF_ImX82l`aX#Kc5njZuRDbclNSA@ek>r>b}?(9z1A9W0g;Gx@I3LR-9?;=;&!(V-!DI z;82sOJLWRXdg#t7po{lsHsR39PDa$u3x`-f1+{gj*~*VAFFT6D?sY^%c6;GS!>RCk z+%YQ{qC_k3%O4QWXZg`F+_7k;g-<3FovNws*{$m9(O2OI7RnRh@$$~v1P8q|a$U8o zl6Y60{)EqCNXU=<(U3joaUH{XV(E@)+k$~kIMLxuLl3%!z(65Q)B(dFM0}?fic5s@>`+KIOqq zMo!}G{wy*qHAzy(Y5G#1-pOksb#&xWid>*1weI(E3JrFSHBr*u$SofuDT&_{ zZmJ}nRCU==X?r=4*cYddPaakM@%5zB$lCh2_=hI;iiPnHdcmk?PvHXYfBjvkDPs%9 zUQs=${O^_9fa%|7M7ZoR<@1$SKMLGPQ1#|DRevsi~%n=jIauEl`GciJCN z{!WT`fhL*$p8@@&&i|3n*PG`*I`n_jE;IfX5EvU7k#nqz$S-aV)IZe@$dgx6DvJ*# zdL8}76ubn6o*$|B)E&wEu>Inta^^Q>kRi_Vi*P?#?DI`r*F-#Ghw7PR=o z*4Nq_(YmlU0N#%IQqTE%On$Bovegj#+8V_JFT5R*SO>7BGb>DY;p!y}5`+ZK<8LGO zsMNfF|GxehLd1mFzA02-=?{JSO$jrMJAxXO~ZaJ*~n|oHZCwI z&8TX2ana#*rTOPk+{>DK#=gAG5P98eixKpKnb9T*lr%F7mSzf<*3wC=f{TaLZ#09IHOcBjMF@klv4&@J5Pga#r1qtuaw z+T1cJr9!wAT_JCi=7W@E9u}3>XYv@agx13QUz1<5hKQKqr?V>a!i?l}{xN;n`2ymgAJIlhi zg}K3tbqs+-f(3ILZNX&r9^3h7F~g@-s|4|SrmY{VliQtIb-auzxku8yA8*s%U_Rf$ zi^HR+>K4;<4RU*gu9*@9mOLHs)90+-V(Lf@=aREW*Q`Q`=WD3)K*=UuQ*E?eyEh%l zQMceRbGdJcENQEVvHUR&wzT9C_k4*P#d!p>Slr1Pn(q7BhX4xw9Kkk`F3U!n@xA-^ zM_3Q^_ZO8`R%-j6;MP~@Ky{_Z?tDxLF2A);?}>T7X8eh{?s56ag-Qzs?IKsBM$N(E z+Q1G(lQU!Swvl9rDX#x6o3d?#qx3JsdA*c-Z$d_-E9edzcip8AZEo{jQ1z6)2VlU~ zV)B?vt6{`$r}ha7YT>l=sP9MYxrFF=zmpeeL+PEkfzyj|Bs0QTW0}!Hg8bwwiMSkV z=kpF1YZd343;sb&OHH}AW}2wDcjVf}Yi3f~YkoR>>Gv`}J|vO}h=EEfOrh)KrXCC{ zYTA4z`QJjanzvD|>OQ~nuEAbifZhI9BYqme-K8lt*Pqevc@JqTZCmPL-7nZ!@h?n> zGk+LOaEL}Hd@p)ErUbk;q&!j{Nnd5dmUlXXiP=PSi=2;uxs` zu=UqQFjWsiSnNbpC-kcgM2gR4RNLD;ZjzOOGYtiZZPyDK!{6Ck{y~=zYrvE4cBl&ZV8Qs+zS(eTUK<9 zxeN@XoC`B&(2gOT7HcQv%LlRx2>W7<3!0=3h6=x%tT9Kvy+1B6*bSBdER9TAU#9uY ztvo{c9R6@9(|7y#%1c<>S;n%9v=VFc8^N(5; zj%v42CE|Kn3`5a_^w9Nt?Yj;f7M{+vqS^q4*@N)4HRzOljsiw2peOt2#)4X@G+{uu zBg{m{?@Aoaj#ralY@W&HMG?L~xNmdUfe_)g_7iHc!RAvXJq>nO8j7ZOOxMpb*Bd@7 zGVK3dfbEySP&iE%P0PCYVAw^Xvan%~MIk#iV_ghe`Oz=tMTW?wDB!O*Kg*)KXKdRl z{ZCPfrlC*^Tzdq2+i!cryAJS{u=o<3IPD$-#W^-~M54XSxMwlJqFoQSL|=CjwfgEM z=NM>l_8VhqUH^)PopHTfX|~93hn2ft%Lx?bF9iI!b5MKC{Mu^_A{03uB;R(~EB_ZM z{r&LcOA5M#uIpxG(QZNSFK4zSdrkLhThQM5!+)H56Ttp*S7;I9n@n`dhh6Xi4V}bO zu(_+4VB2w-cL&g2ucd{1B&yFjHni0DU5&}-7MbFHBYYo3Re;Z)7Ho*W`kRwQ6;~ZB z>knR7TL70Tw)%7HaMyut!n4!t8;nVjpKM_vLKkZ_aOSN8Y?0%Gs&M_KefbyScS#EI zerQy6v@-ug{``SBEoKg3b);sU)Zk*3#RfX5@{V*8H z`~FvpdjKp;31y-ZM{YJn_j2{XJL)a;tx(}X8x+1+h-nq+?eQ2lfpjLZN5!P9J4%J-R2Yw@( z@U_=uZ?F#?`syvusT4o?$zCS$6p!3vjwf`3wnSnfBAbPKOjDmTx2ymOkrlTW;VF$^~ z|3F$u$k;@xvA^?F`y%_0hw#9Bz^1|)dCku|1Ux|8HEIvZ<(&{QIM3d4TS%%_Y}tI+ zs-(^@c@7g~F0@Sl@MY6q`HsJAhDB36 zUcarR23pp|S&P|bNOwB)OUT`?qVEfMD-4@!sE0*j*!!|b-|&c5*H><@oM@=I&; zd#ZC>&U{|^19MK-+?$8eA34*jC%@_p@yS@S|JwQ7Q9G51zyy?6MfY5NbVkfsxaRjC z_f!c*?wnU`NoTUerAf!k2I23UE+nB}8060OWzf*bE}YKHfWb8CUe!sq^1AXmNk^rC z6AQ%@c!MB#7tix-tIn)1i;uJ-@rK07JYv3)9k=22Qp)JJN8Wk#!m-hxSFDI{eaX373QdMF{3oe``l@ws^psV0_#kB0V`X$q&29xJkBWMtghbFAHZU)*%APtmp# z6oPz`ecsF6jVz{8smYpflkQrgQr96?s1v-|B9rWmTS$S#-4z;TbdUXk^vq0y2q}mb z)&q^?jN%J@K34i?c16`nxuga;FC}5Atp|F}^v8R|a$enh9u!5Blg4b0C!Y25lPbXa z3X6Kbtsp21pI(@owy?8H*`?yrs9N)rlD&tLbW1*xr7+z&KT)aVOaBxmtzPq!;^n}Q zPpe)9!@v+Trn-ix)*RaBsBW`0!bu_hQgTz0MpGSXRXvjA z_d-i2Q;1p2DQZ;4lw*fyF{>*pD(VZ4IlOhumAH&R5VQs!sgOg(?XygA=A?3k{Hm4( z1gAHU%VT~RBBrPBFH+2z2{nc7RQKkT2R*UZwUrk8rfq&8gwd?Le=z2(FTJ?+e4UNv zi~Nuw1?n-%BD-u{&ete1)wbYTsNCrI_&7Bgj-XeJ<<;eE7(-ZtTH4$-mp5?p6TuO3 ztZZpsaH9l2m%DRgf&-(U;Lq}vkH*-eXHt>vRZH;;{RQ!vRPzR}lKtDFP~ytJDDFWbdW26q)Yv8TSX^KDRb=7KcpxZD6W$y{QjEpxMFpPG`qVG$6>At4iE3^L<>etwM>uFMZs zNx0nH@iKLYOXbHq8|o)Pg1RkLnQ8K@#j3PcieFdF&CN~ldmRM(K@S&ImfIEuyqWDS z97OGB;TFBNM{eP6tR(u5%}x%O%(ZI-3lh93&&gxcpIJ8%7D?N?id|z8Ra_$FMmTQA zIo&Kcn_dvV7P-_e-U8JcKx^n8AXWbu{*^WO?XgBIXV&QFU<=>cxlA$xN4W+SeIWFT zARR0X%lDE~2}K4>YLDZ75jIN#yFO`Q%?Tx%dAEmDr;7Zx;$r}|P1T;9Q^p{zJVPOp z>xHyiVDxlS{i`ba#W;j&@h-F5!r6U+As@h{)1~Ln6Rf#TaQUM`ViEXL#KN=4#f}Rh zX>u%W_tYZn8V4Z_5_qT@sAt1lqV~HdRSjYbF~S*t0bGtkhqsj_nZm5uGi>s6VO?43 zeVFxGR}F)lFD?1k$4)bO@@6ARM*VJz?wZ?HSo}cTrJ`pHa#BlEkJ;#eY+K8&e|sDS^fd7lrI2xyr*@LXyw%luFm%Q0iS8I9Ii+Iq<>!hael084{`vF+g>yL6 z5GD?cV1@7vDMW-C0^1*(y1g5xv3teRbL87m+DtQV)fMZ?Y!l;#%CT(mz~vaMR4UK; zneqDM;MTrAS7_8qmFkvnr})zEnV}1@29H+E$y4pL72A%LNkh?bTUU;`WAUwxFU_O} zU!no(& zTs-h#SIv3CTnc2z?v)}^mDFZs5||!sZGBgvVfR+d6S4z}nCZl6po_7mRw{m~@ zBrRg4TK;5(?Z3W4m#^b4p`v2`ZLNywA)iIeXfPZ{8ZLip#fKx;uLm}WaoR1mn?s@T z5J{~SGr47+L#X4!o=~>A{R%zJ$jBSnW=1Qs)V&HFTDwArcGJePP13v-HDN5-VESm4 zun!Sf07Jd%#C&E-uo)+SZQj4K`A@9Ru9;*K+o&88r}6FRgLyPJ*wIj8fn&6h>~{98 zmEUu-FL9mBXbN>+Mc64}^D3~N3@h3QYE!j%qA6*h4GV@R40QyT~B?6=6V~Mvs8~nM3^7r-u8RvlFdMR53(khcUZ&`wHRcmRg7>og!6UuYe3~{B~vf zqrifK#!r;jr~0hWPKLczK$zPRh#@N$owj?oeGxWgg#oLanR-Z~Ro@mq;^*&K>f5!8E~VWHhAu3%9ea%ar6;yUi?lcm;hS zNLN&M;kk9$jZdfGc=R7UgAe>PZlzhlqAi$Le7JWZ_NyK7@96qvZ_sdxbKlfZ-8c?; zXK~NT4p19moVRP10Z~NXLKft!eFp$9a%!+PQ&mGv%_&k%RrRUE_Jil^Z4$;Zlf0D2 zCP+M_Uz>$hf|-jVfoWReKi-WTTW-{Vn-_m>dAqtQ39stoBZ9(&TmuABV{C0@6|br8 zT>msDt~{@5%Bbi(dODAXma6ErGB5f=k-32#E4+Q<-#y`& zK_P9iRCD<_%_rw%8wy&_YaelU%JXg1tjQ4|W(q*eG~)b(N=;tnL`8kYlKlRH&4b<^ z!B=D44k44|Snlt6DlVx43^`Z&f_zVsdfxNb&!DSYUe4*Xu>=y zL0QJ#@93zHjsPeN#s%{H)A@KN1B9QK5Mhv^9YPyU2Eh0vbpR?1weobMT#S&t+)6zhPe_9ZL8Uc`$NSN>{nI^ zD4>;<)$nD4fheLRp}V^q>E7z=%AsBuRcLpN!kJ<5?d|Ptnf?2hSf1JwWb!UxRAH0;Tu=xq%jo|64FpAY#YaP7U06cZAxd$F>6Pl-7!W4yUy17!x#^dK@J87SD4q~r@>~T5V}$$4}U9u z?mNQ5D^$WM5&*b#+?f>;it24o4+09HGcClSn~uk(+%RZ#LXM^I~#G?xzO&`e|y6=8+|l%5kw{yxC~zPrf(;= zI0)#QlmJf-i&BWacKh1_pnQNgG~*{SGB8g05XlWIWETV6ht%|8gx{p$IIeSr;-Zr| zpLJC*$T8}_J{F}!T6F-ykpjcZSD(MULNsCdc*m=h4UQcPNst{1D?0x)dOYNeq#`1w z{2?7g5A0hxDuU25ct1`s#mFfagm3h9h-+@%$uVO?u;bEb`P(?!UTOBRRY2G@GBVh6l@2HQLD z*6ab7FJ1YJyn~N+<6*N(|Mpm~XOb4ok0}=~2>@;9iUEj@W1^vw02W!%ahFyors%|l zI-RzQ{+R;YqdH!Qby%r`FF@c(*N!L7X0XlaD^>`4IPM(&-scSiQ`fNAw_dI=g3?w6oI1pCOMFOos{EN1Le!Cz^rU^jYk>TORb_3e z;=jBR*R=3KjMEVgDC#>_*f4@A$i0lq1&4t^S{~&M75|qvK!klP6zM(LWAZY7MSPG? zE=||u8#yilj{oBuJvpnys&s>ao#fZ{eOq(08&v$;Fn$z6bZg^HRCbxq>2{f|jr!UW zo$YpBSd;4e?ZL&t1QI=U=Zk+-$;%heZ^Vh1i7~-`CQi98%olqGrz@`S{g9jfQDvzmqbpBrC{D-M- z^o&dr*_6`OmzHSUsDU9;OR(dvTZMH8Kv+J}xH@QYVGf^{*Z3$w#U;_WNn?GnF+nStNz*9 zn0hU63Im+=XehXtVc-FGsoYo@UYwG%0a?N?|@#35~J@{m`c*6!4 zrAoT8+1u7e&0&e@ncPbSuOz&^y{%^Y0??ZNeSRGvnad)MNFQQ~SH>1(zF=JD5KfEZ zO_EZZ5?q!z&xc|Q0vPs{9L*iIrsy+2D>o$u1O&K5V$qTv@v$56c)U>xe4^ZqM#fQN z6Vi%{i=Uz#Uj6nXwdpERsU;OhvA$I<2i9=0Gj*FGsz6WnZ;tJ@T2Or2+M#qE41T^k zZ*;noPvj}#ykY(qROm1k@p?2UE5$z)K%QI7u(b1V8wugf09BoypG2jrNot0B7h2j~M~v<0LL zE580%uA#`K$+9wlp{_^DjXGjmS`VUFhbV}1`{=e5#QR6%{G|EV#EXH=ZSC!uo27Mf zCW!N1zH|^)z0cWGJ0ERggrf-jnyqCDR!gg!?h42g|InntwgIF*O)E^Z9?Ubdw6v7c z&Ae<=aRYt**=W)kOuk19ggG~}oGm|qA$!YlE>Mb?(0*6w1L5QrUo9;2F1t?jY9SW_ z&4{dsR3l^KaVJeDJ5peq;>WH7J((s+#`@F&EO0*K6RA)^AI<%P6(4oKVLQ>QM{&Wu{quJ}%P zYybR>la^&+(y_i0(_iyN|Du8 z-7y0(hWRH!)`B7K`kTiNK%{vVhFD6SbFiw~m2YDcNqM)S<{Q(!!wrYRjNC<7Raqk{ zA)yY!O92qPNCDZKQra%Y(aY|y_ZwaJQkHQZUui3|n~hJk!duL2*keA7uW2|wm5t6m zAj*C7sFcx<=_VE(RblR7E97+Br4%_Ww?lS=b&EnnXETsmGkd81H6pQ zJkk)JwFh?bNEtW6ZIN7pzqx3^Kd^Q2XvSy;LjxRq8;Mex58J>kaN%8OM)GFnc^4+@ z(Cqo!uO77=jO1N-tQHJIU?`$HyAHHyp_YOSqX=Re|3Hv|G5AS+ z?o(@%O@McZf!_i<9?wdGS*+8YIomdSJ78Fhl6vqdAk8N-Ca z9_xiL`0f-%FwA^c%fTia601E1^RY4)1n?a{I_Z(~xu^n==?4KPD;Vbo`9nBo)W# zYJGlz7S?WCspofMYEN76@Hp*H)bsz0qmCHsb7=qY2=&lxe)HUak#; z)A1cT&8xycGDx33QcG0^JMEIDZGS(tONqxO`9vOb z+*lZ|y{*!1Jhxd694H7irNz|#)@`?N9+>}B+pAEARi@#67j8Y)ovK^c_Ob~jk9{Nk zV)8ZBda&`cVME0!KqOeEi0lCNW?|tj7~v7(89t77-T2FtEGm6}KKeli2@f*XTc(h5LciFLHZfw4 zEOYb@O<;&~zYyG%AU(01aa)k5KX(5VWf1P}ULR+X_*4D+*g0xb$YsBUrhGsfy9zHq z6q*Y8!QgNDmDmj5jJTSOXo#a;rM}uC;uq5~TsKykt= zGX2=`znM*G$KyGP<4swqQ!3=gEjQgz4!MwsePZ3RXb(4Y&zZj5-NQ|E?P}`XBJ=qu zV)nL8a60Dm4jcCRdw&yR4&`C&Dc9W$n=2cNm^<8w*PsV}J=HbH(wrVwSme&Ss!uy- zl`;@^GBX;T#y8KUIYxb2=7WX1BE600$V6>wmjJbyFQy5xIzW470r=(M$AHuEUbPK`;rH(rOC zcbK`;opzp*D5`n4tVY$jWJZrwhSvK=bI4GJxo3j`eD~`uWhVA8Lgt)V2MeOjyB&}u z{?dq~I#e5O%U%yCGT^KY-x2g0@#AM89*~GB#vVO)6Nsm1+LOYwq?#w)Me|~5eWlg* z_paVIX0I1t{wmps+fF+O+`O${shew;JJjLn=jXLE?GqQ)>B99WGVLj3~`dd_P}?YS?g9PmD!> zEWJ#Cx(P4}rtIk{5~wxF$DQkLJ^tgxzCkljPduv;)tKzn>d(-yz-PDG-`jfMjr~q( zxx3>6omEwO)TZ=%Zhn3#_GWbYi`tp0g=noWwNcCzFW+&Awvy6b`#W3okHH6}m*+?} zMu6OZw;3~%s9mE2ssnG=>wCs94kOLg8cFZPf)SfI`fKu&-oUsQL(e&RTy~`xua5o$Sq(>{mc~y+!q_(o2*7dgm ziSZ)ISPezpjtIC%K&H}gdByR2p&>4!y8n#QhNh6ZkSNE@7l)el^0F#*A$IG2>7<3nFvzpr!}hKs+)wEK zd~eEUIStl5t710NV_cKnF$OEeZdK-UM5EleZ>>09hgdJI@$Qluu~QA!?E7NN zYLXQjjKFrj#&`n;!1T0eck8<~;z=R2cU%2N>R|P~`%1C$Jf7@5>VCMskUWeCIt|W% zaA1-KO3#lV5hrQ^jn+dmYjc0FFGWT{x8N7nL|}vcYUor7Bz^hl+944P5kKf`Hp227 zWo>Z!WT2xl=Qx0DTSx%R3QE+-L=#0kzFf7XXE|L&e>q^^SGshcX0XjM`XmpLn#;aADa#mmg;B zaDM{k;H_LzMAd}vj*Pe!!?3YS-#y#_il~S=0wCkQx4(0Lw=4Vp!M{~xpB08URle?A z8Us}7?7J48LN4tat%5YDV`rJeit%m*B3RveArIQ=i z)=GsgpCdR_Z%XND&9#?bd?v@_2M+NHNKd7czikBMmoWLHCMVa zZY=x9(2KM(Z-l9u7*tJABku-eP5V3RwVGuq1lPNoZ3g0;C)H(m@+ZJ~zc!)YmGOM} z(}-u}0Kb5&@IsX8aO0RD&rSx+3;3@6@-8t@jCl=X(M+uo?J9y8>ocx@=y);Er!Z{& z@{TxYOABZ}ffZB<=J+YL@PiEV2m1Mhja#1(Y7ZufX6f;KY$-dun0D7t!6do4L+6%h zw%bNcVWy_(&JBqea3sv-ZEv}+MNm*V!Q+>c(tFqyFE^HvXJmuxW#n5s&=iY>VSL_` zhW(K(Ng*@7P}~~nq>h<8of*6il)=@3zj?I$YGY#JZna?Mb-(v=Smquq8d-tQkytn} z^+(huc;AIPPdFf7$*(ul_L1OKLlr#hRQj|wD^mYgNPJ@Url zIAFQo#|Cjvb@CI|apz>|L-+6MpYqE+Vs(V~rK`SZx&bx)V_W5b1zbktA4)VxQT;39 z(swPwqjT(Dx-kOqA~?#iaZQR=7BXl{K;uo7n+o=jBN`A&{YtnO-st0VEhOhyO61#n z@@r$~GNbHs{X-lc82R~i*X>)i%)JI3p+O!nQ+0+ZL8^xd6^)mK)5XlFGk2Lx;2Kqx zr<+V(YWwoh$&EMj6RwnT*x}8s;(os{H_itb8}3XTXy&Oqr3xh}K~fAw!(kI!lHY61 z98Wlx=zvY}w`qTWc}Ym*g)fo_r4TNofcAyNd+f#?-e5j$(rPi#OWgMEKCcsX>%=6H zbfK*N#j6G9dxGNey+@OOt`Y5QYr>s*!qMM;$1}DVj&7GP!1hP>eN5Q1dIvWzl`nwb92DA zXCA)VzXERAS2tV;%FF+sT=wu^otO9l7(iJy@BS0OWw_t~OFwIuigQ+tG^&b{NToXS zUH8W09-#cv@{RrR>2cTp`(B#Z@m8p=orR@kcintffkT+qbiInN6dZU8yrERk&qZFZ z?`_g_|3RL`FXMc3Lwa}j_rMc0}=SN zw3Fi$60GmW>rK>7nfS}m)-zvTizYd25LZ00`0=|(gNRy#uP^QZzA7J@()_JEkC8P| z9=nwQb?5Vc3?g>NY5EVR1SC4t#Va*Q?0F|Rgq48%9rstBqyH`>722<$=M zoa}7CO;QSx%!4xs9Vh(3Y3>9EEBhdfW@b}F2M;Q0H=!UeuRJC=A@a5Px23Tj+W5Ji z$CxHK)H=3EfJ#qmq2=cBf4SbK>|d_85pSQL>U4-oQ1TbtWwUdm!PN)?e5SjtNiH9w zGv77I{J=j`($v@2m%tizsR5^L?t%i3DY#fBFHy@6uj%A`h)?XIJUx2#&YbU4#s+Z5 z&hMhYrE+%N(6vuge(5VOwi!*T29~ z*p1~2uFwoXLbQNPy*t3i>w>{B*gf7&A;i1u6D>N&wnXmnda-ZVH@Ak*zQl09Z;+$= zt*?QiIIYP|B~rm89xET^3EI7Gc{P8{`JX!j6mCBO7hw>eQvV`@eh7$dTRL;Kgv`Qj zj8uw@HH}AT^k?nfy_?ME6jHvhRLbuDDCjT`geEpA{@t$B=^Vo?CyPYjk_KKZS{rpb zxXURX=h;(=i;UdN%8=&1lYrM~_h03Ae*S8{-tm5RX<0&3uHsBeN{aIda5)~evxld! zdx)1`0<=|^Jn9habyTQ#RZzs94h5DvRx=Y_(pDpTKKW^hvek#0dxXt%f?D=m`*6=@ z*`;1}cymojO$<@wmo?KU$Q{9g9Q7IPI6u|_>r6AZ{V7B14tn8?e!2{G?HrzD}O329#aM#E`G(!oSKV1hU zY}mqQ@rGe_E-SCeoy2OlZRlOn>5uw%5M|rWkj@yO_KkYeUHNvhb+~)8EFZ6jEd(x= z#aVNu!FMIk@wGVYu{&Thdk59ol9T$GvfvIpV2e z;5LB*Ak8f-5{#2aeREj(C)aIP&3@joPhwPDZwyAjVsv?WOZpkf++oPX?F2`djyX+K zQn-1V?9`d68vE3(s#x&B3G{sLaQ!eFXkKZpovt>?qf6PBUfSbT6z?LC?w?ogEqclP zz9?r++G~p1=R~@sjPU9a970A!J|fSBBjwPoN2}e48LMPhkNx-)vF7bw>+~N!a67bZgq%zYNo54*mcrv^Po^ zi&y@*UDh$TeurS*5}eC^^W>lGzOaVjS<{_&`KIKf{trAwna=dn59`HS=v_q(2Kit; zq+3aed(H_|{!<{mpauvFXcS|{{li|t+y=uIPmFEVU($d|a3@{EumvUKlz0W-!prTH z=8hPS5B+6`!iX_Bi@l3q!gN*hvzxIWL%`jnK)=7zxU7nb?%rw>)G;SfZVX&F?vs4= zxL+TtTG&Tty+T_2V1S0XT5fRWSbuqWlo+5(reWM-HV)W+ijkCL0pbTWqv zF~co_kHK6Qz1BJmy^o`Mc@5M=X~ZYCXrO>sE{PusNpt6iw{}<-#h@9+}_^~uDIQD5O~eK=fU;1za(d^TlMSli@I8l-VLAY7aBfR Q@KxvR>GS$|r>@-jAHWt;jsO4v literal 0 HcmV?d00001 From 38b3fbfc476e4b562275deb8aae112d4ab8e320f Mon Sep 17 00:00:00 2001 From: Joel Truher Date: Fri, 28 Nov 2025 16:38:51 -0800 Subject: [PATCH 06/13] still ruminating on redundant controls --- .../lib/subsystems/2p_parallel/README.md | 150 +++++++++++++++--- .../lib/subsystems/2p_parallel/chart5.png | Bin 0 -> 54187 bytes .../lib/subsystems/2p_parallel/chart6.png | Bin 0 -> 54629 bytes 3 files changed, 130 insertions(+), 20 deletions(-) create mode 100644 lib/src/main/java/org/team100/lib/subsystems/2p_parallel/chart5.png create mode 100644 lib/src/main/java/org/team100/lib/subsystems/2p_parallel/chart6.png diff --git a/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/README.md b/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/README.md index 46b11d5e..ca96bc19 100644 --- a/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/README.md +++ b/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/README.md @@ -1,12 +1,15 @@ # 2P Parallel -This is a study of control of two parallel prismatic joints, the simplest "redundant" mechanism. +This is a study of control of two parallel prismatic joints, the simplest "redundant" mechanism, +to prepare for a more thorough analysis of the complete control problem -- drivetrain and +mechanism together. In the Calgames mech, this would be six DOF: PPRPRR. -## Trajectories +## Use Cases Why would we want redundant joints? One reason is to allow "coarse" and "fine" joints: the drivetrain could execute "coarse" motion (large, slow, approximate) and the mechanism could execute "fine" motion (small, quick, accurate). +([spreadsheet](https://docs.google.com/spreadsheets/d/1Z7twUzL8mwdp5JcAuysRHhibZrmlWo9Cy3-zGcI3sXY/edit?gid=1682330556#gid=1682330556)): ### Tolerance @@ -26,29 +29,54 @@ slowly, and the fine joint responds more quickly, within its limits: The control scheme here is very simple, just "P" and "D," but it compares favorably to the same -coarse control, with the same "P" value, (but more "D") by itself: +coarse control, with the same "P" value, (but more "D" to avoid oscillation) by itself: -It's not a night-and-day difference, and not what we really want, but it is simple. +The main benefit of this approach is simplicity. -### Planning +### Linger -A better use case involves planning: coming to a stop with higher acceleration than -the "coarse" mechanism can produce ([spreadsheet](https://docs.google.com/spreadsheets/d/1Z7twUzL8mwdp5JcAuysRHhibZrmlWo9Cy3-zGcI3sXY/edit?gid=1682330556#gid=1682330556)): +This scenario uses a fixed trajectory for the coarse axis, with a PID controller +on the fine axis, to produce a long linger time at the target (e.g. to do some task). +Here $q_1$ represents the drive base, executing a constant-acceleration U-turn, and $q_2$ +represents a mechanism driven to linger at the target for as long as possible. +Here the target is $0.75$, $q_1$ turns around with acceleration $2 m/s^2$, just +momentarily touching the target, and $q_2$ is uses a PD controller to maintain +$x$ within 0.01 m of the target for about 1 second. - + -In this example, the coarse joint, $q_1$, anticipates the approaching stop by -accelerating ahead of $x$, and then brakes gently for the rest of the time. -The fine joint, $q_2$, is capable of much faster acceleration, and so makes -up the difference, holding back during the $q_1$ acceleration and gentle -deceleration, and then taking most of the load for the final stop, which is much -four times more sudden than $q_1$ can handle alone. +In this chart, you can see the $q_2$ axis reaching forward at its +limit until the target is reached, and then $q_2$ mirrors $q_1$. -Because, in this case, the coarse joint anticipates the deceleration long before it occurs, it would -need to be planned in advance, part of a per-joint trajectory planner. +Since $q_1$ is moving fast when $q_2$ begins moving, the $q_2$ +acceleration determines the size of the little overshoot: in this +example, $q_2$ responds very fast. +This scheme also works if $q_2$ responds more slowly, though +the arrival on target is not quite as crisp. Notice +how $q_2$ anticipates the movement required (just by using +a softer P). The transition moving the other way is sudden, +as $q_2$ hits some sort of physical hard stop. + + + +## What to do + +The use cases above are all hierarchical: the two joints have +different purposes, and are controlled separately. As such, +the conventional redundant control principles aren't really +required. + +Instead, just control them as a cascade? + +Details of conventional redundant control follow. + +


+
+
+
## Kinematics @@ -77,10 +105,91 @@ q_1 = x q_2 = 0 ``` -A more realistic case might involve "coarse" and "fine" joints -- for example, $q_1$ could -be a robot drivetrain, and $q_2$ could be an attached mechanism. In this case, the range -of motion of $q_1$ is essentially unlimited, but $q_2$ has limits that could be expressed -as a cost function, with a soft minimum at the center of motion, and steep penalty near the +In general, the problem is of the form + +```math +A q = x +``` + +where + +```math +A = +\begin{bmatrix} +1 && 1 +\end{bmatrix} +``` + +and the solution is of the form: + +```math +q = q_p + q_n +``` + +where $q_p$ is a any particular solution, for example, +the first one above: + +```math +q = +\begin{bmatrix} +\frac{x}{2} +\\ +\space +\\ +\frac{x}{2} +\end{bmatrix} +``` + +and $q_n$ is any vector from the null space. The null space +$\bold{N}(A)$ of $A$ has basis + +```math +q = +\begin{bmatrix} +-1 +\\ +\space +\\ +1 +\end{bmatrix} +``` + +So the complete solution involves a parameter, $s$: + +```math +q = +\begin{bmatrix} +\frac{x}{2} +\\ +\space +\\ +\frac{x}{2} +\end{bmatrix} ++ +s +\begin{bmatrix} +-1 +\\ +\space +\\ +1 +\end{bmatrix} + +``` + +or, equivalently: + +```math +q_1 = \frac{x}{2} - s +\\ +\space +\\ +q_2 = \frac{x}{2} + s + +``` + +To express the limits on $q_2$ in the use cases above, +we could use a cost function with a soft minimum at the center of motion, and steep penalty near the edges ([desmos](https://www.desmos.com/calculator/2l6ta0osg7)): @@ -97,6 +206,7 @@ position feedback, supplied to a low-level velocity controller. * For the mechanism, $q_2$, we supply the positional setpoint directly to a low-level position controller, with the velocity feedforward as an extra voltage. +TODO: finish this section ## Reference diff --git a/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/chart5.png b/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/chart5.png new file mode 100644 index 0000000000000000000000000000000000000000..1183f249da86e1eb41b874b93c446f2d3a7a0f5f GIT binary patch literal 54187 zcmeFZXH?VQ)-H+-P>ey5E>#efra%CJ(5pyMs&qx9gP_zvP>?19(v{vpdT*gf?;S!X z(tAP=A(Zn2_usSMcc1r+`{{nT<1&UrN07DVnrp2&pY_aV;;*VK2f9Xcjevjvq#!T- zf`H)S9`NTqF(L3taQ3=90l`NC1!)O&XM^=A61UsKV`A^P$VnxdkQBN}8ae@-`4|*( zfVtGuh%}&?|uL z4N40SzwJUrK)^!q*_FW0vMO&dC0MlMlDmlaVMBxD;SAVg84q)rz}8}+I>m1TMeYy~ z%-)fN5;Wx&74cN9M zolfuk`@)GtM*?;!?8grUFL)AVfhfl)s!-ylF-?2w6qLg-krdC98Ej}al`p=RwwUXeFa(fS8aiT zw!KMGzGlBZUf_G(L_EM3h+6v=9^Q1?6(e99>Fb-8-Y?M{G;lsbN5|8uqwUU1aQYm5 zmxYM=4?^y9)vfsmw9qQ5P7J!;cK3hV)~riQyRw>bhw03^>Afuu7CK?auQ%vL+N55? zlFDmN-VN96J&XuEk^xKr%gCL=yFytN556zO!<5n2V&L;v?K9l&&bPGq&WfGlz^A;m zJ3Yd?z)o!DkKIa^ucdezF9pffp zn3|!!zCN@a0YNd-&?RwoY4#y7olv-Ms`W$}E-2Tqu6C+#!oZ^IxKnQ`gm96K;u=FQIguSOaU7NV?0Nz+qT) zTD=$14*2r64kqXe@LwZ2brcTD zA@^$aDD92sq-H=bA&_p%p|#c3@#{6uV8=7|@LhV1qZy}j@6VhZmsyQTM(NpK1<~?< zO_1OZFxX`_r@ka*W9624Bn8EfU&qiL#O4_utDbGf6~xLY-ZX+%_bz65yf>rtUyC8o zeT7IZ_}0{rLpi~jUb8u5P^a;E2di80jtP~w6RB%6)2XxmabvzQ5>*hR;(_Zl+|JKE zGR1QFz83ynl9raBqT70bpv&j%`fLxWsce1YvlzNBWIs=AxYmW_FQ<$jUn~EjdJ1oE zZ$BCtF@SMG_aeZ znVR|;mCtyJHR-fJvVCi_Q3td9YpR;Ic3W?(!H0gC-3io5WDq@c+{W1=AN5ochcDDO zo=;ps<+R~9A2>$T2SEM4&>6dHHs^hxbV9k;`l?Jh&jnuSO!@fR@GgcKQbKsCUUz&g5BHOtLA)J^qB#FmNsZ9+bz$3Slin~%KgQQ zTi}tGFJIOgpB+>xU9Q2%cqnY!j-w0qBu*LrbKXaE{@$t+j9~r?7MfEPB9*+4=Hs>x-Wn>S!o^MOABDmA7N8U-e;& zmO3Xr-N&YSOBRKxr@rSDDK6B*lmIt~ut`KWfEgk4zUz`#XpDq#2`%$SyUf+vO z$2AD*3e7D*1A5BhtvcPYQ?0GtKX`q8ogE$F$efo)qd>xA6TLSuvWeYEIMoxqOsZzZ zb3yeggg7gSPy#XxF>6=t?TK|-Lk9Y;4Gg?M*8Vgc&HGMC@lCDGvFXswn6%{Ov$EvBj*whIzfd#$Fcf8^C3TAUO-K+1llst<0LbPp_J9P+Zr zV!K5E*zZGgd02fUF-@vQ|35xul&rZ*x(axh>?#4^B`ILWEKAa)>C41>iP5Y6mkIvv zfS;=E#m}y)N_)~5KLP^+ZjD~0k`8+%{lo?Di@KY^=KSoPNMn*M3?lkmc`Gf%3I7&)&%e9~1CdK!Vdnewxs;9EHWrnZfNXcXaFzE*>s zo?IZRDup|2<|DspQL4GY6PE@NT4la`it79y+WLlxx* z`A}Qbyl*#AwlfXh@RY{0yHxrlWO*;1@g#&T93_k1tMQUTEPaoB{H-KcjMchTzF&kX z-W!)#c*1!+k-8AXdb~OJCOntfKB6uE`qk8Kn#+C{{$3?K7Snsl$;G7-qphHDRScPL zC{`D;5yNA0?X;GhUGwst1VKAyv0Af!=Bn8*><9JgS$%!C3VOijI66yn~ z`wf+>IO-dd)B&ayxdIy*C~j$RS5{X3HF|#Awxt`8%?N?x#3xp^2+!S=Uf9V^Iua_% zo4vjlQ`X4_z^5@Kv5)7Kg$3@Y z1h=#UCbn8pzW2Tmd0#DIhnkw4f?&OX_=qwzI_ZOS0RAy@c*LpmJlh@sHX{^dI#UfjzNr;ABx{o_n z?r<7*Fu>?E?o!WG=iM^0Zd+S{^O>#|+eAr;Z3=8jBsTBAA!*eyTgQe(N8%?IM`kxH zwoErI(O&~RPh!o?%${4Bqjud!QB1uY9hb;IuF{me$uuPd(KIzWxVlzhsPNHrw7hS> zqS}y!CXcO-=7Pnzoa`v|-d(_ObJ>WJXlrV=1cT^BMs43r0I`|%_;*UJfUtEhoiy6Q z#Sh9C8TP#L$L^e>JCkl_O;AZ!f_Lq4dW6pE4+#bWPn};xgfV<&ilIl?O}?eW6N%Qo zzAhWI(s6TLzS1Q>njoTQOj&=7vdYAwwRznR-aUNya5m7rJE%JvqDViTTxi_7y#-{O zP(+17*uAY2^TG7zN=l$7cWy*OVfPJ`5jT)L{rW3NqT)pPYPDVK}B#eEe>n_By$V3r0uP2)68Da zs7w_Y4~|MXsLn7s_7oH8Rdh(as0!qG(4LEniv(hzpvAHF!TtNhRBIby`pz@nM+awk zgewTz*MaB^@}L!b$Ecy@3oj!B0?MNfvAa$dPOm4_7j1E3m9&W(5jVWb=m(a)x@28f z*eRj=aOf01D-152ACw30xLNAh=_z#Bsk^s3lmXgxjSfJr+Yi>?ile!Cz;q{&Jk^?- z#q&6C>*$hL%K5ph|IK2>w0>O}_Qfhe)ZO{uEjUi6+$K&WXIQlt*<3tlr4@sGV`@6+ zck}Ln@0Bvz8xx3=CV#T+0)D0;sT}Iz37lidx{{LEcKEjc<(#!9^SA+Q<;w6L*CDpU zwQ9w?%nM(!v}(3(sqA_X=jv)7AxLsMPH0DX5};?dSesThUo3Sbb&(dEyySHeFS_r# zj;(YL36t%)0q3+uESeKdl@BSXz#2|`Uj`nn*A9|bTzULaECrp2F}PEf%jM;Aj-Kij zs2YG*S7B46TZMoD<8)VTZ7>6Xl0G_wtJCZ*C<}nw$PBEW{5tI+n|wJ6cZmxS-Tb`# z^%4!8&`&jM_g1eD_aWLk)_r*?G^eD$8cxX)`1)!Tb#EMTET5YH2=hoBg-fUSEXqX^ zylYw6JDMivrz~2qPa0wr=L4|QIVh0os!$0lb10}-kL7K_HfaK&C9|=|%yx8b(X_=D z_C&A=xOQ~V6F9Wy2Rc~^51~IyVG5~ZRbL)r2W`>KF_5$M1WO%^Q7tV1IDOptjMzrCQ`=ZGO#AIf?JY(6z zwWcxWvg(C#(~FIm3Y-JqTqEHj3nJuN$7@P>cb>%lD-+#XS;ZInyR8Cod{2d9dPRQ~ zu!DqyEm)u&cW!-!zk8TKxu#Yp<5Mh-CiJ5&UaEh`bdH){OH91i8q~BAW3&*Y=*w_r z{xm{MNjcJ7>TSaCgMsbRhllTT2%BhE(?60-%j`oNM z2RUD?Jqjc}y&hK*S4YMsQU*39n!ic#_~wR70rVVm`I_-QjSLX4OX8+3Maa;VA|)G*~4fU|0;^!fYZxy+cQ-s|-*$NvUvnY;c9f4={7l1>}|(=*1V(_{4O z0$sKSJPnQ?Ug29tAfuSCMG=-ep&{bS5AP77zJyGzuY$g>Tk*hF*%6PC zdF!fP>t44JTA!@(E4tGqO$uvR=E>GehM*$c`w8x5rD7t6t9LGw%49A5xp!V;yPji8 zrqNu?_FC;z62PmbPqa+2JNb5$t)WX9IqSr5i?X8C`0EUsH!2zWr8OZohC|hSOYvIG zMC@;1`0ad&lzUN=KcOPIh^4hVbX&#sRG;0JbgZ_PVZMC#skOy#}+HYzb3`sqT*2DiuZ8#f=9eCJGw@_UgB z2V#Ye$X1a03xAm>j(smcG#N<0w6C;>q{EaQQv~T2KM9T7|1U%YVj6~lp499t^;_19%L=6n{-TB12ccz+`9@jB9U<{b8>qAI(8#4gJ##jq%zOE{Wjv~ zj}7&vvi8es7P*9_)na~Otd%33`oO%ogvQN9Num!P`1`Kqn&oQin!|zTAoDuKt09!*WXoIw59Fj`iHO}`_Y>KH>na_(v zOr*IoE2wi!x&zFo7{?cH(X!(1HFGZed%vltoPo$)kX2Vbe3WYF2w9Ymom##F9?z0E zZdy|UZzF#3wrZZa-7K5XxV|Xq-)I#GAK#`i)OB~0cB~AjA@oz5#!67?e+XFu32p`= zb4J87ef{`i0Z1tjL(jA4KS_IQm`s6LNH1%U0cB-i(dbz6<_76Zn2&O-e2&O@>*2|Og>)7>`wHajsa3`==;MmlIbX% zj;a_ob-TBT zb*AJ!wAtwy`o@n{f0pO#_xs$y95f489oE|m{40jiS^YJ=){|agYscNv-cB!p)YXD@ zR3C)X3SxLe6F0dI56vtS;Njcs&i>_ORy`mzK<`zhCtK0LZ_sCIkps zx_Wx9=3XjmgeL}0b`{ue5#t&60ruIi924W4HJpJ*3aO;`Lo7F)y_G$5r`_&uc$RWm znAK{Kyk;4q;d?0HvN+A#R&&C^vwEX#ihz#70wfz?B30wm8a>nKtM>f)P1|)#M=O9k z+uo!Iq!W$|HY~M>m~8&BMRQ#e`nfZ6S{6Nob~AKMaV(#t<3F4Kb-nwTET#U=hn+Fp zUAsd*ZC(~vP?2u&bg$Js!;yB)rj3X0jP_g4meZN=K@iA!y!gj}?& zt|ZYnBvJN|nfmb?uH(Gb&}h=LMZb)j+lMObmPM_ZEj>@gsU{M}6oNnIr&hQL&p+F8 z6X*EZH1^w!q?|A?jJ-+r$_i=`oO#hty#iuZ_M7GUE2&IhRqCF*0MSr38dl5v5{-Uz zHmZ?8qv)RbPItk&Lb3yh_;r#bh;ZU%<`&o|CmxQ~qq7$E1N-$4h0qMyw|)uZa483( z=BqV%Q1sP5i1Hz)=~w4VWA8I2$!`vm`A?BYu6@AXDtzM!rQ>%9)}_C=Ar30*n!y3F@BILB`#*@d2yv~}z@9S`A(=)mu*{!Kx8Hpw_cLay?9{?By2G*%2S zqv6j{P4=-d@%bqmas_uNZsXJqkIh)J;PXBH6W2Yxd+{YpI zQ4h}SdtcO%*q-mdz;7IH*B2#RIC<|yW__RfF!gRPHac>y%du}FhNdtnS%LYdM9N#a zLHTjc0#!;5^ObXnZhhiF_L@Iuh|d*d{rw~?8?HS>Z_0T z;{~o*Jo;dzf?uExcJmunY~Lm zP^QPswMNku2~$dOWiAZhwx0?g+I`39SausR@tp`lRcno-L6Q3o-$mG~YX-W0m2QG$ z4u=W@m>@rZqOFEt<4XnM-OqoF42(Zzuv=u?@$mn;9QOryHfhJ9+n;jhzsDhai=j

a3OXiXPf3VYtz9h%*xhIqKzR$TI9@_d^h> zDRi$iK^89M{$Y=WZNDK1#@}dy9B-fVz)asI#`jTvofY_uwz%{&E6IgPI*{GP1$-yo zLbZ5eX(Ee9JnJ3(4fBiH3IQU9#idwMp+Sp24M}u~t$)p$qF6ZWf{uv}$dU99v7FA} zp`q6>#rLsIpVcWw8Q2^d7a5ws7)-eVHQrN>+@kM}727?GJHvXC21wAHfrr;pRjjte z{04?0?8%*3uOE=nn}2{a0jL>n>LMBnOF7$O2rU+Y(~RJtQaVkf$M?1pSoDcl`QF12 z4T#lgs0=H+F@n4+A#HhO2CR8yXne}#)jsC;mXF;2FwP$1Xp}&1YxQ&V7aHLHMYzRI zRcrkAEUjST*Hrad6w=8XwB`;l@)&u|7NMT>ZNk_QL^w&QQTY;0Nc`Fn{D+)wXWQD8cU3-N(vCtolns%4K(lvIyznq4AEY_Vg6YtvbmgMkPa) z*IiT1O=AmpR`279%c`xE)GfY=Sd$~Um<@2Bi{v)!37&FUit9#A zULfB4wM=xv)w67c*XT-+&2(jc-oA1bs&+bY$JLQ>_kKtlgv#2c_X7`pa1orlwwY8a z)1OtZEkb^0R;t9}kvf356%-Ui-kF-1;DT7$*mjJq6qI$*HCO{t8}uYVMScW$?8|XA z7-9f-XO)Kumm)Iu7*pP6Owu_3uSShg`dzi@+nr=KFIDAym0R{3Z}TY*(R@uC;pgMz zj@d|5aWZoG!4VC~^l(oQG%q&3?cWS1s84?Bl>`(GF@RnHJh`y2P;1P}%6g<-2R}ZN zB}D8FDB>#C*R3kqe*r8Gu0ke&qMuw#uRaQ|=Qw5(9vOKLY)vNV?#VluYNF4@)k}Yv zF-c1XSVR7hj&Q0@{qmt0M@~xU)9U`La6d?90}(*W#NX7!vX?QB;sY!|{F>i@r)jf@ zVf8cgmEXxaUQB1U3};h%m}Aww~WsCrlxlY)-A80icE)jo)$N zqWBcQas5RQbU8w?ght)mAt(mm1@=zg3fWBWesKiRuwuRhk`B~K%|8r7Tu3(X+9(7J znylmnkNTkQ?tRc-YOVUPGAqC{Dp0!x61CarjQ(R#9~OUeb!yWtI~b_G$ZzWXGR!xrz2texQ)n<4OX(V%?XzH@M@I zOE@bfjQjd#YdH1YzsYvzEu7wXdxX_i71Q}JzOrk$gR8Zg8%-4D<3p+g@NI;zo3ddH z8E!DmyJrRKEOU11rWS*X#0lDYqV5aZPK&_Tf%_WnOO%! z>E6LQhX_z&Tr6qEfAZuUyGjmh507%~$cG2}6ViE$LK+ePup(K%HyRU9`RN4UOLp{a ze+k`6BFy!(wtMn6k9c1t&q99LH@7*9aIe8MCQ|RDZHFXd5_FYA6EaEzVE4Cui4r1u z85tS)pu+sI!pFuf2Z7fYr=DbFX5wbVG&D3MOn-A%{Jsd!si+ur%E`(3%3!SMBPG$lS$F%`GOgG8lPDHMYIG~0<`==8#ZccYEr|) z!$+{uLRy=OdI6h(RE49_67#_WLElD+V$45qgPHZndn zSageYt`|i@G8vq;V<*S>`4+)C5PrSzV=SET~zR11i5_90gPFM#tP8-&+d;77@eV93T_E zbmqy$hr=R($B%SlznV~>?X}%go#!fn#JiCc!4NY!msY+*Yqf#|tc%x`yt^&RU6!iZ ztWGW7v&V_cCY6-8RDlm(uc+Em0xp*7Oww(y8(< zVNirkD1xy*GfRT|9I&xnJgWjWnIPT49dRAN?svTaxaQAM(dD^TX7EHlZN2ItBayM^ zzpw81`We+d8WYl@NRfF7;=dgxyb<#nb2t#ZU?9)fVNr1P9JtISz>gqy{tk0jq|r|+ zb)NvXQ9oR}UNuL~24?hdr~Nc-Gn+&>cXOh38vik?T%Z{%_Amn2OPSYfGXQufxFn>2F4<{%`8^ENSreHETp4wJF9~op*F`AaLr#jBgTjy7F~8oq z%)CxE?DN z5|+_uTpefr(kHLDpQfhk_3(8)FMp$ME`h+^BS1lS75l(t%O&N@Dh=NqSbI%vMg=Cz zA{&SW;trs5>QEF;ol$EwKKA=g@}Xqq1P=ht>C#r3unDH0;&anXEm!N~*LA%7=a0K& zPi#3?%!#a_w>@A@I!T0kjf2e!iCw2lE|>gK+01=B!)GR*tvKz8d?(d?t_*s233Tag zz(~1*gPwS|cFC5&-jOZ$mHJwM)bn311#z9&22F`05cg|6YgjE*^VzIB8MkVmZCq8QAbedN*}h(Q{r9-(op4>V z4e&Ek8pN;>Gw=0eHqo2)Cjb+bS-~S3S@ZHI;a&~aFHG`@f<0x^B4MGYSvkvYTx?V~i;z|&1U83z zJyJ4TzF^>|_SZJ=+=L}lZ63mHhdoE&pj;(~Q7OL|j33*oE;V2-QUpmB3q?tU8ItL? zpDb*++K;)Z-N_zKe7+qtYQ|KPz&0P%IYsJwF8KIAGocifdR);@-rqYbiw&j7fzL|* z%Mn@zA-*!ZGzP?bcB!@BFdrIw^I~=GVs#<`6mVPasY9(#)D=J0pIfINI;D+$X+9fe zSbz@Q2i0Ot-6wxVEsjQzTdHx$yG=u z<}^UiB^=td)8h5yG5sGYRZpDo&O7UasW16!LSo1?MasI6`r55P+f6$!BJkoV1~s}( zlYi#s2@~IA#{TsY$2YdDtv(D}{`<}?UJ}Plq;`!vk$&H+1%!KPAEevBO%K z^_cMTr)Cq8Q5Dyf+t%G3S82Q`;GI*oA*(OyI#IUQ_)pn088}6wpZ-y{NeWIx4|KvP z;;f-#6qq3Xxz^weGB)K+T9c*jnAYGkiL=|YR6tZ_y1Jn#w(T+7)s9SXh4(W$P51!$ zlVL)^*lG|Nfq65!<0DL*5Me>etfgk#m#WnSLi36hwFYT8W=f=3X$<;YUvjUcEZ0i|fMirhP z?;1Ml)D5Z!j&~1Sizdy5fd`Jy#)q9v`@+F)2Gob~la+8%diEj4@7#F57N^Enh*_(H z@$u74Yc(%WEAEHu$+yNL4SVj7Dl-942Z2Wbjr-C}?3v(}-xA3ING*Z4)s`LL z?$qdLnykFMMO0(Z)VoH|KcyCYze@E3u1_{c@oa(dkqB$KJ?RD!ymv*VO+$dg(SwL@ z+BvFTq;w3{meV&|I|OPbfCz6K&;;vCXCO6)*b9t?pHB_|!Z{U3lM54dh5F{#u3fv> z;)<^xrNIHZB#vd+m<~Qp*y*svdxyqaBD0)Y>p|sU9cNEytR53~JapB6zA zzsQk~aez&T971ftvQ&wyJMMpfrv&ra0i9H638Eo?;AUxp^(k(DM<0Tym;GnB+}^W- z;}Cs3a%yMqM&-o*YiLN$IG4@W8k;lv$xriH}zv0~b4jL81U{m696n)^0E-4%ZF*%632 z$((zk*L)?)IY({og_GIR#`?O+@@1N?S18EDt%a8u3tUHMNF_>%DOvk}Y0U<^jr?ES2se0)shgM`& zW9chNto}iR(^VyL0)7r(5FXr4%@NwqSh(|xr)hKwg0zPiwZl%K{8z4F3jKX)_+otl zFey-HhZL-lKobT48rySzt^8ifu9V#a-VI&pyjzvRdD1Xu1(a#`6xT1IWPL9q>uDf= z>ddAd%2o>S&!z$SGo!gZlhaG2E;9;I-|){)aklBpoavTKy5{mbYV6pe$=dw~h4fEz zv<2`AWywyK1=VIqMr}i{nB{4$=J)K{zqFWaEc(n?ICngn@gp-U_T1V)>^QG8*X%9h zPww}8u&V3W$v!ZAcq`ZcGxXX?eLB&z?j!kbTF5BCCXuesnN=#+#jz<9xK;A*udU7f zBn-^Tombuf^p4Q>ck2;|`s9DC%WcjapB12nb2_!AnJKZ5Aip^5mUA~;N>8-z&ypyh z#CZK2RWmg{z8(NPirh~Vn%aM^vp=}0tlWI*U%1hg8S-SHJ4+M-Wi39WP~Ix>VS1Xl0)e}Q+5kFzWvRqxVB{ZrL0nEG4QZtLp0epnmX;F>u%4!m(dvQtd<`IzAn za_#6zx{ zl4F61s@Im;IPG81A^WBLx`0RrelWea*DJUzZ@wF~*=!Bszq14Lo3*H<qU^u+O6_Op($>c6H8VwaA@& zZp&|WQJLmHHp%fH8=mH$RkNNLjT#dS=>7bJQ8g0P4|vgBs`G zHda(Okv7n#08o>(Ja32@T9K&YQ!GEl_S7|-W@zPTd( zno1g6r`C&dKCQW>^62xXjE)y+-RJ;{u`ON}`)6_B`w#5;#+;LX>vmAWoHfwR3-1zIPg$n%fvCcJlo~9zjyjjxX=t zmu2MvenSo}If|Yz7}--6vi4dsAy(){Vn{Jv$+7%yPqKttKq?{AN#Wr8K~2BxPim*S zz4=?*uhLFgaZ{}q<_p?fmo$;#h5qXY*r~KFVNFPpEo!-=-xUyvOfC#v2}i2 z?Qc(#gNoVNMIuOeM8uXc0ETY>jwW3-?#-MEEcJ#9359gwo~=K7jDxUM+J(|H_x00! zZYtt5ObLm9!e$=iwNDv?Xw+mLPAprxVfTU^D^y8x`wuWtOMf;q<9e_;qpq&rL<^`` zV<481A|k(16~YcG{tqhA&(J(TZuYpv=|V-aIpxQ?_L{3d?~=9q)F{E^dmT23nhB(n z??Q8o$m4SglUmjmhVVvz>?B$hJjaWJ; z2Q-~8fUe2Wvk=6fdsyhLgx@oePaSTXy82+!fBsE`1n^+gBQ%T)8&!<@b!P_2$ilTh zw2F`VV&d^$E2g~LBzZW|pgLy-$AMC8TPoHLImdgZnz=g73Ct52Dh%|sV^SH&TwOLW z$+f*_j*k3+RF6G9h>Z}F1<)0hSizf*?#0>xurHWt|4mKF`{ptK?cVw6&*VMQ4K}Ly z346Q7aSzd^{RpF=cNV0-%_@8HZxsO|-rb(-{#ssy=EAc6*+@eao0I270AUX#O>+S| zB{$(vtSwi8*Q{hu^5zYxP8e%L$=d=Iiecp)E_bQdBpHMksP?}J^HWX%ddE0NX;Dhn z*B}}PA|M+_ExB)9=TR0wc@bLx@3eDrtkviFKA^GqzOR(*vzeFPgivJ*ZLr@WrE*Ns zLB5)#CRw~%N_e4K`>V&UzTNQV7WQtP#rI5r&2o7fyFR{6*2~?c+jDv5pY$Gl!3k0+ z;BKh*R-{ZDt>m2ajKwBy`O}E;PKBeq2%y;fm{Z-7Xs3k5=8Tb#@x*@4m6(zlM=Cbs zjZdCcQoaVLfj^|v;qI{qg(-89N4HbmCvjjH+w=fBwv&Q_o*_Cmg72ypq=~E#Twb%~ z74{;xVh)5Kh5&@^T6clVtbZj@FZyHM7klK2BtKq zX6!`yY7F!}zlP?rS!Y*p6EE+{i89nMa`2|Vf!ATJZ&Q2zhE|C7$t8G04c? zHUDv{qNgcxR53}SG#)KaGbs&}Kss$AQ)hn`lG0fZGm68qR-+U6@%?2%P;34f%f3HI z1;4PBX3yOO2)@rjhx_jGmG{v$1T^zFnR$U1&Dmx5LZe22`;V<%oySXEl9tki5R-n% z_2m=Q3Uo;~1~*B8Zc(Q(@LAvA;$+tHp9DSsYZcuY)v*Q>upTZoKog4PDzQAdLSty( zNZ$@$esf?ON{|GIvMw|{#=I}QzLX>oo9g|t!8h}e3v{^3e@1f&XzZ`HU%z`LE=LZ5(5J<)DvZ)HIGlW zl-O1(Os^&90HZGZ#d&vYQ3Z$lz^mvXqt5^p|7%;tv5c6XfBG0?YE~aX*li9sSPO;c#0+_aJL#~Ou)lzB_1Skuhi5+ALDn#y)!1w99G?p9(91@fkli&;W+z}&2?>b8T z{^>rtkNMku^yckbLU%*OB+=0G`EJ$3mvoC!M3Iohhrp6R)BY^^ndY3UgExfkwCJdR zl>Z6m^*Y#Hr<|QmJgbGSa4(i-2=ER(+RX;(N2;d^n6RAE43$7J1}}9(K6n# z?_?H<+9gPq*^8lWD$fuj?|erO&xqI2_4cB%@>*j#BN7}Vgeza5y&rMn56S44Z4cb8 zLCm_fS~UK`yb1v3)lU9f(^3JGl+UJ}m9+@o!`6646lf+F;5y$E2I}Kc_Su2o=@_!g z>;)S$B4Kuq3D0XMKCL~-OPPs>-PdPz0|yhgxcy876VPTZ)Hf^&tPlMKqT^5PKP?5$ zl}v(|gbZMz@Z)-E`qg5f#eVq={($xX{$p`wd=tSdJK_M(QHJ;&nDI2n&E}lO_f1uZ`ZG_%30={sF{p&AK@j#qu# zR)D*lNH>nwZ4#=}w@7GstF>PLV*O`;RclPOv9>&TH50fkO^?=$f#6z*U0dK9G9vz3 zb!pzfg90Tqo;k_lBqdzS@oec6e2C4df5qo_#FamMS=TA}(?GogUi9v0zQn!vzsvSAUG( zFg|NaIJ>k>sxyz4oqGLE1Xu8r7u*58)UsSWDcfM#js2sGiu_U<3t3628raS1@+u>* z$!>rw{hw;Rj`de4H|?66n`@0tOiYeOf7g4tx1OC?u{xXkpqDNr$My@kC8xVLD`|C- zhrhuF!A;$Tt>e>a#5!d{t=*{6GtmU~k8bQ2g7dR;%lCA$wXAwq66DiHHvckl2~!vU z5uEfRVvh&B3%36LzzO$=rP@7y5jj)%rDz-Ijy zF9yv+jtXf_5_)gu}8PWV6eR99CgPFZRLjTX0W-@g2H zZ{MZRSKh^`Y|Hi%(T&vA)kTQvOtq}8cBbjtO1|MSBX}P}ugwX*ASS!V4-n%^_yO8d z#DWd+r|LZQ^Y+-!+S_#rW-5cn(wX&}%XoTHwh>1?rP-8QB~59N0VTtuA4>>rHj7T$)-MVoi zb=vLgkr-OFSc9n#p1H@lV>(-en(^qYA-#z4(r)R=PARf@d^7vJ4Vu()y?xAzt9nU; ztQdE!b9UX?&Y`uq=mJud=k*|Ot-qx;E{0XVGR#D-DH>+ zoUpy@yyE@7`NyYjN*H`59Fat)93@d+!x1?J{2B?D{I`F4h+pUShvlQ4o7J~kYe>pgupP5?t>aHyb3w7{*^^}psM?kALpLSFNohE- zu69M77)Jm%Q^%i9#cWgczJFg<_t2?aeoy4AEQ#|kVqh?64fs8-f=L-~srpzeoxbq( zCRuAdVxEh*{?n~E*>1-^h>GxXU;D3^0F6KW+a}XXv-Bx=!v|pq#@l<|^V5v<7tLdJ z*s=F=z+jK&;>qtS7&bX$Gj@_cZ64o%Uxx9)$zye{n(D17_l;#mb=h{0X4cwWxHQ+Z z>X`vhG9Y^F>{5K;g(cVg(`Oz*lOZ8c!x+h$H$`6I1pO>4c33UA0<_o4zX#qj8Ivy2 zJ|2AjOBF-Lx(jH{pXYrljJ~dm@_Ub~W{*)j4%)(<*!C&^w5{8f0&uO^EB9M2RSC_W z)oXnqcCY9leB5bRfb>7>X-^A>0tIi{#gXSGbdL5{W0FDuq+vI>UN5&W{duRiyLVgs z6sz=pK9B#;Jbf=RO(~Xgf6Lf)MtP*kLhX9#mth#|asD-$N)k!c7bblU@9B;}mb&mx zr|CauEpgl{KoKYM1W;|&tTBC%?G8%cNQXJs_Cz4aT3X1)l!U3LmDw66+f~o^#SZrMz5t<&&RGcHG~b zViy^mTEw?%^-ILjfw11i>iSE^bZaLHRi_m1nO>at;Uwm&_8y_iWUA%qwNDw~WY)=j zJEwO=w@gp+m&iOwNa~Z6AbW&UlOJ|QqJ$^lPJm|f{1**qdPPrH|NND`<|RP>ai4m@ z&@YgaKUPZJLmeHYYp8W6or&G{e^K_9VO4fp)Ubgd0#X7>ZIBX>E~!nov~+iebfchz zDBX>8cXxMpgLLO6HnHCumFGF%^_}xx*ZY?r+-t8j*IIMTG3Hn)S_O3x&lRz|=869_ z{Uq1RXzk^s1Lys*HVjD0Z5-7Ze>40P)$+9=vR`kYoWG{&+E^`6=?bmRQKQ(9ANLAe?Ut zFj(z$lofK1m?JPk9;tu{t2fN@245z}N2vI3+7 z->9KSWWPq{Gad@=JHa04fh&dWCUrkvUhGMx(5T(d9t=0n_7(FoS+U#E%I?s*?9()m z*37Bq0#CtWuk<_dtsYd0W4DTOeL(kzJ$`aWRPduf46y?ZSYEh-=RHfeMsGxH=)P!A z3xD+4Dj<_0JiKc~`t87AgJKEJI;ytYEw%rk=sgNq)>E4I4anWUA`InR@rj{OU&H;* zBH;@yH=7(O(rL|dJXomvfy?quPEKxB#{#hBu-i(HlFO88_8bR5fk$0BcA$&^x84L9 zVeW{7w6UtMW9r-!;&(3M8xoen0}e8pvVQ)FV}DMb{B+#-%aAHI6DR`22IotY^{!b1 zPk~M8oQ10)-49Ek|A+FwlxIq5FjWjr}BZDx;I#f4+r@M2Fn2{UD|kD4{#oY z*S26tWf}ENv3A>(soEH+kCj#KNdRlG6rf&AadQEPE-Juv67BcHQAP2n5!lu6+zGJ% zFp0J>_iXI6FDA+F{G3F(yS@VJ$6kk8ZnH9?R1J0rU_ABMQBg7SK-tEIk*6bawXAd5 zdZ_91!_%xtH6lx@I$>DDC7ihx&&bGPKuGR-x{-w0rjI0kk)-6xcYA) z*yMPK)t+=r1o}pon&Dr~szVfzeP1+6x77@K7Vb{fNdG+v&2r&`!neZ5>>5WFR^Ahq}~0 zab_-JU0E(%Vy9Gg7t*C{NG5#?f43G; zEF1(x0n1nX&g#jaW~JMulId7$BjZBknJN8@S6G3N-Tqt*f;rH~nk2vs$tm?~@Wdxo6#NcjWFQ8&JL3$d-W z-#!WE{a+98R|o_=KSm)0DQlV( zk;}W)0{bP*4otf@*+D0DES#>za~9uZOzC6!C2ANt1_u7qK_?da$3bTm<dP&*?}diXkv$3|NKTx}7}Ie9fA_>! zRc~7`<~cq0v1RAJj<}sqY4YV4&32CJ*%ENK^t#HDD5-4U6ZY*HBUE@$N2{tDZ_Y#-%0l-(v&ln^NRNso8Qao}E&v z?bnb`cyrof)Gk)v&+~d@d)2a+9mqSCJlzlmRl0@LRxL-rsCp0U{)aAA3b28xyVJ+2 zlp1!o&XW2%7v7m7tN;#TsetC70cCx6y7aP`BGHMTa3M!jfICb}K~P{3XQ$2~iG#>d zE#S)Tq@R&uAspBkAbo%LFp36s5lH{Jmm|+-A#XdHUrlr{?Jdn4GFX ztYgrkRIH&h7gDic_a1_-mESZgxK_E@(JhJP?bD#9=pF0gpDxc6-+e_|Oe0Q3j5RVu!^#-(E3o?wTaVNHalh1N%vtXJ=ofCSs zz{ks_y$%zv+Bst#aIYUn2s&prTbm7;H;Ya3|Nm;@NSck~s>bK0xjdYlad*x`fApsd z5DKX;=R}W6ft=1P4X^P6ldj=6*iqv@dHiPJTL6MgR@2!}BP&vAH{At1|NCiB^QMs6 zx%N?USlJDHWGhufihJ{E>Y?;3>sTmiqFoK%CUhM2SRJzedEBOQt0kYWv^?I9_^shr z7xG%>!SnFapEDTMYWbf;gm@^=`JYaW>Z&9gNeAUyM>|Fc{537&kn=vUM3*22=)zE> z-ksJ=pj~I>bqLZo%~00}SFqzN)YCh3>4FTlvjZB8?s|8a0Gfqq$3XMTZvab~4qSmr zU6prNV94TJjIrqsN{zv1Wrq{zg6adp`@1RxS06Q{#wvTNY^fZ@No(h6s$2QgJ3Rrd zpU~IUYBBDaCnjAzYMW8iR_QmHL0$8*!y&lLm_Sm}_Z*^7fLpU3R_k1(rBTGUuh?R} zyCPvZmkkuL`hshT;Z7P~%x2v{_FP5}1ZDoDj^%+9OMtK$mwlE`3_vab?K!yKL1J+Z z_i@B(B$2=>fR!A?v&Eu-4aFCtLeUi~+|-SCo5t0bR=D>&N(`mpBEku62@t+_AMl-_<@o5@WV*}m zYG^@==kRO~c46O*vUZes+9t<4#YtI=;ek&Hl8iCQk0dS$T_*M6tQAC$1T~V==38t7 zExC6%((=dVKH0D1{gNNU)pfal^RAFFZ9pN5srjOpM9G3pCutcD$mvGHvEZE+F8CMu zhRoXo85>4XdZpt6Y*+WQzWwP4^8zdtSIQ~2CPD94zsA_h4LisdU<_s+oWz3NJ&Az8 zSXdynY^yOV4#Q0?YxepZd;rA>5Sw77Aoq$usqtTS?ia`-C511PAm=c#{qHf289eQ_ zqm7k)QMEs5M{vL2bxQ%3jxh#Wo-F|5fIF99W#x^ryy1JMP zx$i1r15|GaF92JZ1?mlr?Ph1P>qNB{Ac1oP3LV*War?$RzFD_fb0~Y-8_t9tB6WOy zS6nq#Xn$A9P#7h0^5yk=?zqb77}uvs9!@pyUPWIvCbG3m(HP{I*bQw0n4#`e%;Vb} z0jA-YHYuRVM(dXu+|7O`D4-aasa5YuO_1|VwrT=D%>emD)No+K-Rw2YQJ$qWUVi1s z$qw32SO1%WFy+GYbYn}9Pvc&3DA{f7SEWscRTuVOGLM?a2{tK4~X zErq)TAo;yBQ|r&e)we1($H8ayY&=!ijjHc>ymAVUA)Ry}#25HWh z%IybIGMN>T-2JownZY!I#g2fpoFL0gMx(ED7S9D%j5aO}O1)vhz)diF-2VL8WWT+P zn8Imc4*mV2IiS#L(47@DdS-_)uR;%55?`NpoV4#dw-38M7#ra}I5B6w?QJ~#R2VwV z@{;zyVvd&D%jPwk;q)j?aiH7mT8U+aMHh%vPyN2N_A9>)SSlY-S-8+oUrY7n$R$#BA~?M}0J zy8E6R=?pK>sCzynn{JhJ{!n^6^Ji@vg(i&{mXQN_BlaxQomB7+f?)r^o%<-L?o7Zm z$=4oHTz!mdRTgj7-rd6O*sX!C!`3P#l`wEJ6gG?9Jufbp3g3zjWZk;|%a$>Kk&!VA zC{5@4xG-sY`x|5#f!~!y;xMS`9T?m7%oAj+Y0}*;uifzdo8%aenIr7c1?v2yfc){t z3s6J>-(**bY!5r?*#>>6V~7{&s$VwuSjm$`Ul8}J$m@|_R`IjYQ`sx&=~gmvH|Fq?~)cSL6Fe6IZEI{aJOd`*jFT1WqFyilxBv01LJWudPJxYa^^a`@z{=6 zxYL!+w$QqaQYFFFQx?rt@-9;NCI%rB(YV1KRx*TrRWPO zZ%Zti=%*q9(Wk-g(vF#&^X?0?3K9EuIiq5ZHZ?o(qX&bTgnIQ@uK2e%6R@#tms|k^ z(*h(UvvY00FK?vbY;TtHM_$tTf@@HqMuS_mn*8G2V9|<|yfhJHTWsD%u7$FG6B~5) z+?Fz0nydGDCwQ(&1Rd4yUFSA#ka`M&_oteUpO}bV$?)jI7joVrw56^hK5s__s+(c# znh;ULBGMc0%kP|8C$fc?>wR*jn>^yzpHUIpqi|2*lrnSCX39(i`T_C4-tvpoVbLo< zWx2;Z5&@MAu-!x2U>s4`Rd>#5Jgk)OaPg$u~u4)3BrZ@-$?1(P_ zqt2(&;7iiE+D=O?d!y|*=qs*L!~UP1!MB!Tl-)yYzcd^~NiDxh%!N5{Z{a}6a=}oz zGzyWbwqllrjDp^D|JyK>YFY+!z!s%7;|I3wFATWB{7;E#H7dI-QST}`)b_jCwqENx zw|KT(hTGB}bXa1jc-vs2x$LB|0|6&o#2X!gOYnI5U5TM zF*M#nb5je!@{93N|A`|3Z^O8t_@Y28 zp{eLkCx-ID&wiRdv*kk3c5CvTw@F>4t$QgofbrbhjO>-0GWrG3mz^RiFTFXIjma|U z@9!T7K4#iNLPY$CtAex8G&#A;3}JE-jDyPQJ%QW9llXDd+y@6%rwhF$j}E#CjEJV< zZuUh-Rd$FTPlFlTMjVDc{bwW+-bx_l6rTnB7^F^7q>V{T9SPLe2_|B<{|yt&Y!$$x5VP5Y1v65y9Lr z(XW28;iHUU&QdErhBED`c41>deJ27sYL(66&#W|Bju4`!rfBFtcv!O1ga{OL-FTI@ zw+y15gt(1;C16Xgk%2aPv^_cGAe`=vIHhH5F&JIAAfZVwA@@YT2nV z7dL49lq}k%Wp$-AYtx9Va87H-_da#ZG{?6=$q1E_Jiu9=$uAtzGG|F~D zh1Px}k;7HGDzWQ!HV*scfn8xerw!!mVNYUZb|d@ckf&#dWb@ze61^rN*+MA<8nIK? zD7wGO6c-m?(^qE9O9_0G=1CTp1ryYLI*h<4DWWjWPK(CqVl;oHd4 zCEqwIRL4)5kyx~)3Wo(-@|JJb&(3eO>I}VQo$ZV~;{fq#&cWzfg!c)@di^_Z~>j zj(SKI<6?t2-qkv~8Kn(bBe2(%lSOtNx341*RZy|l^)q?{IYuA$hvSp+_A?eV9=bek zW~u}>Zz_47V}nk>4>7u-IHSD}iaRONFKPpf4hRk$Wc>KQz$fs@(>)evgna20VoR~T zkl8FTgPWt&!?FG>gc>;ti>qI+sZ86aBO**$HER)~z<}dJdHoYTz1h#!Tw=Wo%Y{BV zoP{mxQEv0P^eyTMMa&7oysi9%oB+)7nvE!X^C3HyF`=jf(TD%kjrqi)x-IM>^}P5poB_nQCR7>V=8t~r8;@d1b+(} z!I)jwv*2UYZ)$JZ32g7KT|2*A{w5R-zxR8VVqG-KAM*bsm(y#czQLgfSy-6m^X61F zp$c(nTZV^_@6tKEDGiUjKW|>MI8iJ<1{rSkN^1Q-&sdxbZe(=RUI7BPgb$^wq6Tan@{V2d;F`mlsW3oPnfq$6x(x;r{uY2&8TD~s@}%i2E5rB ziH9b;uBW|6&L5;_^{mN2!nn=G@J_BQuK6`5c{X7I_rw0lVq7MPZk4Y)%iJ0k&Z+e# z#`RThirEFxMP`3xyr+{7DmCFSt{||q-&i0D=Sw69TDdhDljoRQG*Ruzh-SoR== zUCvR&rkq4ylE0I|1X*XKPuguVZ2&8a)LKRuHcQm{2y7hcSeIY0o+CXSY9m~Z3FN>_jCeAFY$?k2wV(W* zB$JEM3*V>6zups@g2pwU2}LDbwR z;HiV=#oIGBr|YB6WjfDGq&&b-AM^-N5FB=q1dYws@iAm9+}-t!rIQM;m@eOtb@yX3 zw7hfnR-oN%6h#$^*mgFcy8qP}ELCfyvpwvFKOW``Pu31?K7VA(9xZ(7N&xSaY; zpbWm=w$Ou=gygYmx#^m21;}-mK~zFw#dq@aOPAYoQMDR7lZ1~z&l|1YnE7_Tqh}tw z@-e8w)4H(-FpqGauQz)tWEHM`A#FY@x$0~`{u28>e*AHnXWh1|%JVi`G6dIfG!7{$ z#hJJ{b|}^k@+q&65FV@ufb-r6nhkNDZ;S8?2xM0S-tcVt1_r}-jb<}!?k=rtske|q z&-4|*t>7u(08s?c8qh)Daf&=9%bkh*GEbm2${t!TgqWc@vIu`t%*sNRjB#O2a3R0` zRL>bXSBwXu^f=!mm0a-e!77^rKUzvN#PlAaeq(D%Gv&B4_~LP{MJNI0m4T!}!we7y}G)( ztkC`HOo{}rL$|o8#GrTc;0H+S+@S=p;~%~q&s7otto64Xl5jMg9%5kNYHqEgTWsgE z$4%#EW5NiMYobwW+dXV&<5$io1B_Hj{Xp9c7H?4*1%&H6wg2&V}&YXTuDJj8-e5=BL1^*m>^VG^D8YoN; z^N6D7F9~{59fr1fR=07P*#4SInQlPGTs9XEl~CW=>++Wva<)pVKerzQ}usAcJ+ETunPy3OKIpodA zSQrh{nSyOtwgcxE_w>Z@%2W7bZQkdTp^FL3CK#Xs0l)x|;QVw{`h>XBPc=L0+sagK z){3;3e%ER%p{xZ<>tSos5Z!d_>EcDv`lUGnuo0{puT1$&dGCXd#hAWP-OB@Mnl(O+ z6B2GcMqgw4_=})qnup%`-b?T?F@3AAcJzeZ$AI>r$}59uteA0&WA6Gzh!boi759Aa%l(hh#_{jH+Iu3 zkM<)MH(F!KSQF}>5tMvDHE^+Se1>&@UeMsqh4odqHB`%?Ds1N@&b?hv&=NtpxyxrD zapWYaun;_8Ez`0o?6$}JV|Uux1VuoXF{fX@e0lf7?rXFM<33;&9|*Qtiah1MTn!6s zFiLWdJX>2`eFp^;?Z%5IgFFYDX2|Fnn)?*v)s$viQG4?jR=m$Xm0q^BVKPZ$?1c38 z!(h_P_vj!?$Xjvt1*bC!^*|AaW0i81$5_LA9B2prvDsx1*}sF@NmI?L=w>dvWLgzRHQctIMADb{6jwKH@Yh; zzub#sG721REY`WU*iP?}&;~=R^2;A(bA3f+^Y1a`KJ|Br!oBk2EOt}24c=oVO$ps& zQ~h@-O%5Frv0VDc`DCJ>Tdw64elKB*&c}Y~?1T%!$)$5u8cHR8tJG1{-e1<>Ci?RC zagvmnxGxvs!z_16&cswYpzPZBT*bK(dj37SC8j=^@JXVq_bP8exS67$dT!HRN=KS;|JU)Id4 zbWq;Yk&8a2h75j(^&b1xIUY+YG^r3RpRYaEgdLPehjH2Gtv^hwq5PfcXcVAtSebN0Q4%3= z96I%%H969;{<&LH;lmD;H{%7Veyv8BSXFx*AE}H<_lawE`|7va5c}w$F6gGgXp$}WOYIZIr-_-~i8>rrP+oyR!nXVC zD;K_Tv2(zwe=0lSGSZre>9dQ!=2Zt@jM#0$69>{83wn^5-iZhdUQX;0=#2XBmvpw% zuj_ZQZuuYm$ zeGd)~g`4rIr|BKfp3bmELj43($`z2^ze4td%!g0qzvy-ju(!c%}0 zP$m7A-PCYIdTa=&C)9;%mlnk~*_<8pQ5f{Crg{Jg%UxDhC|M8b_;3and(4>cu|gNA zG55YP+zNDwpXYI{UQL-3o(y|k@yzDfht=v3^M2|3aYnV@+q4}Aa!p-mZ=)rVyss1(fX#xAWJ-b>0l8kTwB0MOX-@P@% z%oX@du_o*jjaQ;4)>LY!Cwe{~GlX%8NuEx@n`{f1w=~Waw=uf-Zn1Q&fvEHEUicbd zkRn&6RdLUwLb?$FzOS&xrCa{{bDYN5`UJ5;!ERUeakRqbj*{k#6nASJLz0&e#vw?X z_VG#g^FB6i9pjgQ2SUCF!nL=$A^AA95!$0mnS$L%dH-r05DQ}A?X>0dimlH-e{nQ zM2=~nK{vOZz@%TgzB@q;Py*v0tdSFd6!F zlxmMwC?Zb1+6PQ-2r>v$4sOqRtym9rVDk2ZTO|YDZevD%6GX8tuYzaCB-quaa#Jxq z;j(Cdwekm>d)7NLhkKZKzN?HyrG6IB-zu#>sHs)JnNc5m3L(DVL6OYLvSh=@k@|$3 zcCypuJ4ndwho*3~{Sx{0B5mnPG*BxuPGpn*-$4hz$$-&R$mp0_L7?7MlibxIu~5-%4=r?! zz-5yptAc8fVIy1|t%O$ubNRCNk<G?C=6QNuE~D_F|!f%y9P$aw?zxK&qA&(C~-#wfFbp89B|UjGji zQox?H{QYglg6b2Xmg8Gb-V;A4f+b|y%%WQI&Ah$)t!I<(SM;O-O@-&GKYiuuZL}1i zkN#P-oMsI%bBV1i1s8g%te&+NB)qH?3I!`s2wuDH@a*+C%42;tjkr(wNgn^>*T0*U=?D9x)Vz zDCxe&Lh?Gn+M@j_KcgjjX0cbz{@K|%@c9*#4kPf2*E*7QjNf?FDH|kl&P6p`f3hjxz~h!hNtbf$mb*U;w#95S{V%F3IYz5V^^?t8P9j=0nG*a1&~*YJcrt*$R> z)`-`j-`8VZvKa~bL_n40kwg*H8>>zNA3p3PJFdc+?w%VsIl?#Ny!A6&Ys|31aTJRZ z{bxKS@K)<3jQv2pXvraQim`t+L)k{}Z49g%rNp!uDEp~#NxCMWcKiHZtS|+8-Gba) zGo}3h0XZ~UDJG4Wd&j~?rzz*B%u?_`N3uegQSPxG*{-|p2;XwWFN+qdqT6Y=H<`2$ zP`|a4bISg67TKc!L61WvweaSQzg??vFVz;d^jN;hShgeXaS;8QH~Udz$+nj>=VjJg zAW_hjbPvF$$*PWw4>toSg+<^w%WdWo9lvZCKq`oOS^7riocGdD`3FfL?b(eyanci` zOgM<#@3!{8N^Ot-;ajkrR|csFb5#faiQ`~jT4JyDY2!54Btujcz9i{4W{7?-GQ&h# z%=>cb&u0pDaxNoyekK$MTHOayvCRHw-IuQC%{J|yLw=7(D8Kky!J%FoGS%*wexnLX^=|*rZO;S zoReLtPS|ngsDaz#`=Px8?`kWm&hu2CKKe#UoH2LkS@VhA9d=jRzp8j2F>;^Lk;^c@ zGos@ZIP0f{B@%OnM~H4flil@F#*~|V6};0Lfs#&RDp_0l2&P+=3b0nMCAm`otE4e? z3UYD|D3Gnwk&?EVq*1p8hkZQXA5ZKe_tg>bjVMbQeb5_S7Yrd9?S z&o;}g@DnytnSxGq#&znixYa&zUn$Mhs%p*9 zhY78|%>m1;%fj6n;J2K^*}wpc)?9{O-N2s7ncT-XrYP>|IsQ9pXEK)4u%N+T0^4nd zt29PQM&R9jeDI9^pZW(kcf!K1IC6z8iGm4W{k`+OymNPTb+t)entScI_FufP;3h2K zWVW5p#$zb$M>%f{!OJgV-cy36Q{n?hHOikJoyKa+T=rDrQ@eaeUtJ%|Gx8JdG1QfD!3!rytwC2cTjmWUCx*T3Y&S98<6H zMwl5C`D5Da43p~B{ek>Q(tBW|XT;sEpie*Brx_u0#Mymi{3$rkC2x|VSZLy;@S*Dm zQ$k=U#`1;OT&$4LS8v5&+J&zBZv7%G&Drrtr@hiZ^1p3H2MI;m2!lO&By~%T_0PYT z^|q&Kx@?*(Y^d`d*dlo@{kU`-0YrrRhk13IZbfk$Gy9W1Ihk(fs~}BbE^jqX-8MJ* zvb26@k}$@&SQUH;GR1}ugCkKYvS35sFr`BlX!{Ee5Cu^bXWh=CS>QS7EV;=J>Y`;M zQ8XNWd>U95ShkVfn=r^HUi&)vg7%W`K?WCi7wb>T&cy%;U8ao=;^{UW!2t@5A7$RJC`+!r=+i5UOxHI~f)wQ;gpt(BF=jFXGHlO3SMP?QES3MkmJIwHP< zb$9u!e|BZsnT}UAVz#ZlYo#v6NSqR85hz9ABmiuMy(_T#DurZ zA72gGPm0!n=<*LaKxfg1X{NDR!uccKvI{icvG){pEbpZDHI`zn#}Ed0_;y@_2&8v3 zAS)%w!-fzv!W#PIZFjc6e-124VM`{f>UWbwrj!+wkxz!-8&%6Fu>-e+fPpR=y+1OUquLL~>} zToL)@6*uu6zIcD@+MM!q5%`s_pq`I`!YR?KeW29Vq@V8tuqL8mZBXjkOKU(+S4z$& z#7e{WYaK1=mqsBg$GH38#{}ZgsZI&y&)4u<_u?Z0d|lD zyg#u#2Al~B+U%qL^&Q>uy&{jlAw5x=wy>)eZmIv~>o!HxSx}P-9e!4F1u- zA9}?(SVEI)6+)A%Sx2N5UK4@~WhmD2VhNV$Q?b(qL-0?mrh6}qz5k@?S%YJ0ObvR{ zE@H6Bvov44=0={%Sn>d|&W2Q9W4zR#;$Cc~&u{Q+HiZc3Qv2sZJ-$eJ@O_yBcry!=UkilgmWJU)z@cbpr%i~R?5)MZE6DK)$8BHpnDa?{fs z#k}crY2Hg+h+|VC^V~hY8p?LT5gV};`90nu4+QU#+L$)Y8RJkh5c3p`%Zx+V-H%dr zGe$2jGXvBvt($bkK<(H-7t<MN=l#O42Kd_S{0#?PQh$Ay?_a|wd z-z60H_wSMIb|z3}Dl8<_faf^dIy+BVw*fEbCtlv(DUxxlLpAnhPC)wxAk}$n-|+$m zr7Xl)8TU_GDd;NLM&9UO@7gQg->1B-KvY~k+3N%cV znU43goAUrqdIU$Vo5Ckl+ipC+-gj)Yy_^T$rEY3)zrtS$4GmTAVD21KqYcWM_GF31 z`~0pH;_{)s5W0`00^B%2p+-6Xx5Q|Lw)oKrH`GdJ!5F!dn`a1CP-$HOigpgVkt%mU;VAXTEZ2ywQ^aTN% z&8lcufB#pYA^jzTF5KP~@HYAW%S!tl#ThokzUUb(%SUZv5?_Z|DAJQ2W%aE45=jLM zuv-yaekTuG!>Jqsmv|g@D=LP0bQ8~wZqWS4C^NIwoW5;#7b5;$MW;|R@>>SpVstnK*r;J}30Wp_qWhT&M_{xwC-ACy zS)oC1WMIP`C(;0LBJ9xEmR=352PfGu1^H3CCm`YNW=-%;`{A;6DKqBtwBp!PfvByN zk{$>a@d*9DgPO;*|2$p*x(y>d6-HbqE&S?feUjrp6;K^*_0lh)tpgd}%A?GH)9O+rT(bi04|^sPveyO1YjdwdA6SE`xc03Ox& z^yLd&=AwDLMd?f_MU}0_1Jb;SUz7pzY{O}cRO=Ez`ZoW`@fvp`&FVi6z-1@;7q9q7BEh$_o!TlnM1)^V@ATY$z*c&a5G-$}C$H zo7FnZ367o%x9Pnv%~9A!Zk*dF>5;Ipw^aow?a)1@I$fjsMakr`IK);}tx;dJbR+FHWy1 zSn1SGtCWmwoSl2osyLR&qTaEpA#EeG3taJ@rByBu1T8kVr+ysc)d5HsHQvg!Qfv2C z+*mw~WAX}@*-$#K&3Mk$jfaOtN=ATU%13Q^hwc;Q_D9p*-VE*yjKTQZhgRq}-(E}B zx9fh)i;a6=sgld!9U#PK`WL@bV2qe=?3eAR`u!- zQOpvWAZZp~o0jsv0sq=|x(sugQvUSz7318^v0jwhxBLo?*%G*#U3_?0S$`!H&lP&8 z$HlY(G9dUG-}fIIQ|hdE+&a;2uUjRjg{p6#h;K}`K66==>n`oy8Ay;ITn#%tx9tj^@TLo5gf=yVjj-`UHXzeaXc-lhykHSq-gT9$U)MYFR>w$d$~D> zBYaOQe@e2WQm3FI<0S!o2gnCW3ZVyG5YBiT-BYIc!j~fepX?wAzV-HL@Ttp~_T%8z zqJs`kfsJYDpquwr7N{|W-Uwt)&xDbJ|b+1bmlBKH(*5u4fDW>9*!cS&m!yoIJ5WdSmW7KLhbI67_jc53=f{#iI$dKMlCU z-#6iu@>$gY1;lyx$fK|ax%-`Sx$h(~2S;omiQ%mC)$>7sb=j%{&=aqa(34F&j;BaS zsqVJxeapVJPbBLdmB~Jxv%NItC(ebym3*U5F~rhYxU`?MB7zVr#3gUbya<2q78Y}r zjKkOHPQruCckQ*=jXcacF@n+Q5SP<>bxHq(MVUuPA^lLbjnmHKM=x05ss{xFS*6Ex z5>)+NVI$THvY=a`>IofufL-yD5}0Kc2;lNbt6(BZ5@B_Zt)}`LYYlzXjSUJ*R_3~H zuK-`O&Z-Vx`2&L5FqQf_S!#%kg4*0u#-5Ut-U9SHW=)-{P8N?BcWuJ!AUm4^Q}Z&u zkT-|%Pynqh(=V|P%|hT9x7*4<%cIK|KN)^!BX=|)J0;2Cb)J-`I!7(Yu&947YO7eW ze)3Mu3F84M=`*D=iQlX)Vn|5HDfYC(-i+*tByGaCANlV6I=*Z>t3)(bV>^K42zZaf zX|H^8v-Q!mr}S?=Mq^%)8Il;LM9$av)!d%wGVm*E>tK{;YPV6_vWa#@O-Bfn*#C=p zBPISJ?yM1XKTf;bxd~MOEs5BLQJ^f~s7tjYvt$ z^&lu=(6ML+a&oo;`1J8n@u04!=9}lUh(<(xF_Rh2(429nb!>?72l6ik9~qF8G(%w=r-CO$VP zgNRwpH81;wH$nY5y?a%!`h6);CGt+2-m<@QCC0=V0Tyz-EEY*r%j<-4F)jE`I^a6OKp)ocog9tc*sA3B?gc009+|n?m5q;)Mr#+M=KUZ~frrFiZD|?#y zs&8dEQ{MI~PhT_9;tB>E>Tf@iSHjTb10j8 zz~&)&PVID^^Efzsb0k>8^72;SJws71u>g$sDWlf5lQlmDDV&aHJH!#ClUY$os2hf2^H)t zWN_=cdiR$hpxT@yRQ;pJ++MP5xKeO$0p7F@JXZgc~4xBlvlvbTf z-o@K{k*D7keA+ghS$^`SrF6eP@1?4kfk1P$8=QZjlK8!4PUC|+iu@+DSZcurk}P6( z8(c>jBhs7wabvfSkH#IdpL-sj6j+2roOx?%Y@UfJ2U@qOvL-wq%Ozxn>@%o6=*TxH zgm`c--U zWp3_unn%J9WTS*Q7uQ9v*dWr3)u_IzZm{N%%QPbqh2wG2S&TN zk3X<2Yu|YHa9vDVMka@z&>rce`3PhBw?8t_au@vJeze(q`Wgogcwm;rkBE>+;lsO% z`AtX5*ehVc8eX6Unl{Z%AiY2RBCR?+dwDZKco{gq#$_X%4Akq zSJ`gpgxejW6Y}=Zu+J_wPf>HG!x#OKD@3_hJozGl*lr|^jVTtdQ1A;;;!-v|dK*DU zn^WgyQieGuvOY>=oZS$o&7%Yg5~g35MM}X~E+ul(>sBQ;K~8_^E#OP|HC?77jm7U# zu@w3}zdEL0u+j`dMhcd#bH`4&BR_kw`G1*XHf!ulx9MjDerakI5;>5K&@S8M;UjV-;Wn1Qh1uYfTQY#^* zA8uYntj<(Q&=%04`>n3hH_Qc+X30${=6;jnxPkWw>;4y+u}3va4V-Hvd(SamDve?i z#;11gjQdrlG|BY&K8_?O!w~Z-8QR*FnHl?7)ktW9EjdDjaj0wq;@5#GnGiA(a<=%^ zzeZyb{mvDG>0e9%uVvYVQmQXS!8Q;YXB6TCpj)9hXms?;O~A6J%wjgOA~~7JFX(*t zfvC9nGdKhUfjCx+Wc!_o!x0I(X25yyLZ=^!%xS#+s>Ae?Z0=M=+#%`Wc-77I*rV7s zFeiHw>XWyUlB8*F>PJ}*?*_ywIZlMpB&zr(fz^LK>6o4AB5M*Z7QR~%uVl@~yq;Li z+U@i3S^VLdX$8tgB~wG(WI2Ea|2GM>45*e4YZq?@)*Jyd(T7)Od$!;2%EI0miN$Ac zTz`5V;5=4d(@JyXRov_r=VmzTJfJvQ{*=b$&u(rGJRScIju0SF{t<<&UfdGQ@6R$Y$9xr(gwrVhjEaEYFG=dd zeRc!kZVHWR^+ivUjm_mFEuvqnM*QktQ{4U~P2R0a3@#L2Y+9TVA(SyPEk3<42Csdf z$Gt&dq0~kd;NkCNUlXr%3&O&}2;4t@{8$!b9%bTpr@8?Wt_3MRzK45e(LD}J8YY6<(J`58Y`^D1&nXq6(ZUrz|(pI5e*9w@D|l3di6tw z%kt&yS*3b|Mfm5Rd^W`|szI|(V z8lvDhGTGqnni-N95)~!lc`oe<4NH|S7<_6c5BeB5UP@5Sj|$H-QCctW5Hyj0fDe8_ zi!%=tufF2@!<|o(^z%JOdHtEMeWaRsF#P??hoNE(Uz2%E)1_UW+apxdnY}K^t5v?w*L?80aW&u|k7l0f;2n$;5eacIp9b`U zl2-nY)at*c>Z~d^22;W;_lLm2F577m_;{@5Q?Vl>f$ajCuzlvnIrWAivcUXh2k4y2 zX1x(t!ohlbp~G)xstT^zmU^>!`f%z_3unBoQKbBKOgYTZ#)ZX5ONb(!f_n{klIjpJ zi)gYPm&>c@s5jlQqUNX-`dZvE zPSorDtEo@r=t@k{h6zKldcaqo)+0&^d31b>^@VqE)g3-Ev7G*vgoGX-$yMoHnN+Mf zoDRa%FP}j<{_sF5>=X#9{?!iPUDL&bguQz~rygJ`$TZJO? z14@7dSpYQxI+@K6M~mAkV${YZS4$V>;1_6J3BS`yoyDl>uk;i_M>=pH`7BXh&+s?e zB2jCxm$4~JNL&=XHCFKk604Sg1#WpsfTQmy4KvU*^(izIiYaQ#(<((23r+V`an22@`0)99hh{)_x0s5O%Rsqv90gN5?Fy#i63>3g-u$nm}%Bph}*%MNS~G5_>l6H5Ksgk zD!eYn#^PO0PPF4M;81qOWAZw@5cl@0p+rS8SfgIVdm>kEwSi1yO0T5#v~brsV8Dz5 zM77f>eNcwt2zzogYaQ`t1epJ=D+Z@j>Us6Ca6MRF`tXzq_jU05n+o~ePklhMRkG@5 zEYfa16&vkH{CF}1DOD zWN@f@x7^P$IV&d|mD*=$9?);(JzXLM)8LRP2YI{t;psY-`(@l)IFdP?>zi2!+(Uub&Q`;eH|u25>SJ%FSm(UawJ*B_|o+~tK~mOp-*7T4b5hE`50p=Js^ zL20khnHrHS_QB{Nut&jwX`wl;G5LK4T8a7g<@&2&?~L>X@@`h)-ZD`XF!PV_+U?BIg�e zi42a@Sx7B_GSE>8Gsj3llXm`)vo7@5KMR~)Se{OPmiPGM{qL~X^)<;~clN|LEx(T< zhZqH(wFW?a5yaO%mj}1rFdBU|aQZzU66gCQcrkDRPnOZ=f>Y2E{XsM8B=Kw zP;Cu|nr$_l$myDG#RdPh1OTlp$Sdf_i!Z?8F`8{ilX6f*;ewj77z5GxkK|>1-7P** zp}gLSW}+FMG|s@lW~~T3kRBT*=hJ4p846ICI;yy^gRo2>eN;f~sSy*6O2}K#y_O(t z@h4_1H$@#}mbjPEsVxZ?r@EI_NtaD!>NW$e8OK*G&v?RoGDC2GoPX58MA`@U`BFE} z+t+B`S=_vJkw->(yYVi1oc$O@CqBkms0Q)&aJ~oK1?7^i0F{pExMQ0Mg?0>={h!S# zB$JgialI-Krkgx4)$xjj%_g&brvp%KBFlFs8J|Rc+L*{9Rf-(k$O4|@-D@|+EN^ZJ zk_7u0*ey>`iPZVkbL0iOqz z0>Nw=W@cb(k20$N2X;(wzoj40sHujcu-uq4ZxJ(ksugtb~d5|=gxFKav0$7182`R6b;1GEzUkYHad(@H*Z9)gc4mpdv8_(&xu*9}|Aij5?ie1_%nN zs6=Zk3j&>}5rn1cj%AZ&Ba%Jb5V{P~Eh+tW*z0hvU7P41 zQLW8IpueFGOUGHe*JDE&M-)k2>rg8fgI~~hV$ag}LqQ7p{cl@_V(Cm$@W2z5-=!6ybc_?4Z4m*w#1xIPCcHYu`EmmOTie9MS2Li1AWa}u@ zNFj|xdgMO1Z+*nVc=qd4tjKQ`#yGjb>$=4`NoKowJk3ZeCS4JNG%@cw%3n`8iD{!#$MJelun_(rbHSsuL;r z?`bh@gf71dG|QH#Gss5Y>VDoO;PTXbNS`R<^xmqTl9!l(-H$K;%i`gCvF`NV$V#iW z)PWCs039{53%eV?I}asL=IT|}DU&9>MYh9BM6CIOIj^sZ!2ujf9QHs*Cpxd){XVFb_U5Dqd-=yAUPZ1?DSN3_{z{ zobZ|)U*9LD-su=XyVNM82dBOqOF0%TQ#~fbhx{CCnj>tuVU}68xZ1C`Y~4e)`+FIE zuatN4Z{&D(qmqr>jiE2;eM>*KejrDwnXvb!3e4T9h(mWdm#`1iVMdN$y1|DneWwEi zQ`?>8&~~00Bmfb$Cv2CHaQFavnPkUw+fdAiNf9pD_vPb9A&}I_L!UBh!vCV@?EFsR zdw%#zC{mvdn_nmI93CCfQn+0x+?7y-!|Q|+>u`GcGA%v)L>4U~B9b7%6~?E0wp!NJ zdzz3y@mwDpl6#yUEhb8Eg^ z0Y-Gpu)Wip!sO$3COM&DMRV|5BB4)kEmmWF>uaeYwz1%FLx3 zAD|l7G!|XKx!gd07K(~0S`zEMsrm(P_6-{RZesq4H>ec^NhH)|*S^FCN zfuL|z)j44lgr|6beR%S!DyIYaVU24pSgdlArUH;z81% zXAEvRWs64_34ed;NUlDpR#WW|OvpmUU>RY(LGjv^EKyxef1)wqQrxJU+7eV9PZ;n# zKIeySxBjtOV*kR4>G%k^{@JOnAVXHSKVr3O=&RCvzhZ@2z_X3e>L&CvngGkf0kCKW zJd?#~C>?)Y2LgTYpS1`7PC2*Vw@5tWo@c8>#ikjYom=k(g>G%Xlh1M8b?J+d;C}Yc}P#3ec7aqoy6! zMBL+x5uD_D_s8$c1nI7a8-MX?%+vTAEsq7)5{K9=l=Kp6-V?Ii=z0I0yiHuC#VFu0 zF(@HWOQ;0JaRzc^1mU-8#+G&o;Be&ElEo=;YJiv?6gQSnUNhxaKH{E9B1*h`DYnGs zS!;2gdcYqaFxnPH*Hz|T((KaSAYU+XSh|1%V9|xI3?;@JP){T z?|b;gU2CQ)xSDzenbjy1P{+UmQl<6K_`?U1?v#RJPJmQC$$$}qV4^QS!k>Z!u$3M= z__OtiipTKQ2mKixLp(Z7`kJ2p_atxmiSB_8n^S|M7FJFkgwx#95^12&30T*hS7zU* zE8Ilh!*{R0nnlp=c~|kCCDP#A%L)tR<6gR9UybBvh(AK+SOaE#S5<7#Ib8 zebNM{Oo+tM@2=r?TQR2`O}Ot{?_chwOQJQxPL}x8YA~R*P`gT1S00?uNQSQ-WVd7Z zoggrh(Ld>s^yOy%J4pypH=s=s$zg)%{xENLC7&o@V~hQ;)E}p9^~#Blg7aiic=Xo#s1#&!{(*p1Li#PTkN}0vM z!Dny4n=A%-E*#-37w{2;yA?r?PdPApk?>{JfP)>w4$u^qp5q`oiP`X-u%2p`B)%VD z(mq4a!=L}LLQ0XW9F7%@Fh;R*5emMBdDv8(-W|w@C2rpz%rKhlnZq^%2P zSf$)#X3Qk3WuP>FmkB{9nhjt0Pz6e|Ibj=b^4juTuj;ylW-$CxB8WEP1q5ZDT#aV| zstb3CWUJ2#zyHlS2?_;37v+SQ+_oN^1@njOcd(_>-{>`tJneRyv?STHU_=m%8QEK1zybw`- zFzf=2M+*CUjL5*-2-wy06H(09TpCXHE!vX||Jc#U-+Rqopg`)RP`LDo{K7?0Pg7gH zHOXPbn6G;#nz3y)c&rWQ-{aH05)m1Bp-`(L&2+39b`F;N_=B*RG`}DJ!vi_{6Si=Q zWMPG%+_RT>#HV9S^91@GD%u?!tKF@fpNr)P7n?#5pDlb?d$!?8?ba>Gko^H=$Ew14BXg6hY3EOA`QH- z`b{^<$fP088x!^SSy+NA*>r2V8Rd2j)PxLfoq5zueTt)~sAwza1v0l`=F0lESW1pz6kTl3;bAbf@<4Znz?L}^ zOpJvH91ZH&ids*JK!LxP2Gc-^I)_$&N?gthKD(#8>`z4zo&wYZ{HMJJ?metEIijfE z59r;%jV~igXBm)!t8HjYPj-_jRrn*qP0vOpH1I~2IWjHEgJa+fWu?;V!}Kn|3JDKD`$oE zMYYP!g*%|RdPV^ho(x{b$>$-2z1NRF(F{Vnx0-;%)8ZP*;UDtNsl{v>B17sF15X9o zUfUHbh?DC_!il-Bt1Fm(GlW63X)5#Mxt~$FZghUaT~zL@4rzQK&*#Z?qvl zPS!xafOz2Ew~*l7rnVlEZ!8`YX+KUKUocbe6M&tK$O(eA*(Nfu?DJJ^8j8_?8X1Ej zKiQ=#jqF!+V#r+%wcyG`3*G#JPq9#i!^pBKR^;)nc22;Fy$S2!u@*cOE2^c|sa0tEJ`=1VfU_^p2gk< z?=7QRZw&jmVXTvr{TY6-;jSlU!H)Nf1qywT@GL!gm>l?sLT8Q-ix~K z`q=ZC&77GJEpKFC3iE>z!&OLaC2%UbE~nv&r%aY6StglJ-mHix#N%w}ohq1%0hDGC zxD(#L`2K}z66tmfF02LUy}bka%QK>^KH-e9Xc~ ze-PBHV9Y ztiAwZOB%<)raP5ZhVA#y>^uqy_07A*TFv9Y+TFU3se6 z02&$uuG~k%*yAJJ6!5*Bnto) z1Ugj2n%w_s{Npo&Dn*2HIug$4OG-P zrVro(2!%ayEENQnw6jm4c8LPVIP~>)I{|7DGVofv*6uM%0PJ+^#}x=+iuS`B`rIsE zrP?D}P76Mk1As~_abDY+3TSf;S!Gr{|MH+d4p67%_{pRh1E`ffJ$L|NK8>@WMOg8)YeokjK%UZo z`8rYEmk=9e0Z*yl2NE|RTzFXGk&H5Rl8W3F^Z+yLZi_96Xq=Gg(WRvtEBf)+&uUA2 zMi0R#ZwN*p1ay&RxJI)B=$7yT4@O8S77`hgYnI&Ak= z;v?YrwFH;|%8?@P+=ATkM_jFYcn3_sz|CS705%{B(n!|%Lv4eNp2xU?m$xDo%oXg4 z-g+N1_VCy5+|gUjH2p*BxhYq@GI^y3e0&4j61yy>Cr(}R(v^A6pb-A|tab71*%D8Oxf``)CpOtyDJfBs$&^fE9hoj&o|CAH6CA-YN2( zipiVp&-zFzNu2}Y2_cqCIl^5udkZqz^{u<4Cq#Gmt$`4oT*gDPa>+Y)NuGjh-hu8I zu&6CVzkKn!`Wq8H&k`~%gK+0BgSFpgfm$PF+D&5Izj)<4Hw6$qctHh1E#DdDBQ^=5 zL`jtZdf(HkjxewNxisbivq^phc&L#y43vI623M0e@cPx+wnZaMyKh5mtEr?MwgHRh zP0tL1MEAQOmf_>#UD7T{>cS-sw@))yrY0u7G+yHbue2HMy#p@S+S*D|y|Ovy0@VGd zv7GuUH@HsL#8KWXD)8?+r2P}^UsD&bu4CJF{2gtsK)L!6} z3A3Sfb0dtG?408&Fp&p2M`VbK=7sr5uLUL#&1z2p$p<=LcJ3ezFgJJf_U8j+^|_Rb zC+lwf%0pkZgB}8rxKj2KnxC`3Sqb*kirJAsBEv3rrM^F9%oR)VF*j#|4%T}d_!ksB z8mVzy7CFw6PwpfvhG!#c|CvBz{|W8kr&cqc1;jvm%X)gO5(@{@myDl)6oZOpoPMc_ zBW=$`fZJ6V$|i^EGi-#Wfogr1Fr?#oKMJlot37sfA)$^UvEy7K079a0I6N1yX^Q0D{=rV=TU?d*aas8Nx!kTl zPc^I|t6N7|K8aj#qRFzCod@X&4`8CsH}G3Z>D)UBa zS(d77zKNDoy(KH~qxeyz!!@|IpS@ewzWe6Uj5dG2L3J+CTe{Z1liD*j+iHT#LCg$G zh(McWp4ZJTs#jqBDa8r}xf|W7m!M;QetuyMV`Dlae}Gg)uISoyiO@8!eDz}gBHh|v zRzCK+&5QK(^v`~{ia5w&d^rKTXviL>qIR_3e>07uh-5O=1gVF`631&w$bq>dLPiv7 zEHQCwJaOav^mJph`Q{BIO*&eO_cr3`yTrbwKFIajsy_H|;Kr5;9Mo)q{@>}B&z@I% zIF8wo?yU7a+>=uB&?Ocyaic&}7=mThG~)h4Q>Q5z#z z3wtw2lM6$*C8nnljW_ub!o6FFAxT|`Cbo-XFrreHk{MMRVbdW(?lRq5zl=N`Y=06% z&_pe9Xh0ZKfV1-4qs+GvVfaI$kyPi$i~~4P(0-w2nSb2r&!5s7rN-CR$e+DRG14*m z9S03Q73Rv68~r46h08=YN#=U|{%Ed)8I5b#Gs{)d?`Nw-tq&@7pLyZ0dp{ljV(H_v z%JJ3l72?-3Yu|A;@#l@0$D+fR47!6O9xsxAjYyb#awC4onTz2XT3j~c$oa*XJs{w$ zRl%<~?5o)->A}{QUBapVjy4Aa3XpR-*|Z7i3PUq(7#IE=_SE?Jm^40qQA) z1m+hN;ZZhvJ%##GP~mc6P9?AQovOOPI?k*{=rW>5hYu)!D%iAe&-(uKzpQ5Qs)_f~ zCll|Zkx#f@p@5#RY4|s#v7<2WSD-U?7@-~a5|y8KK?3MF z**Y^GH#jq=SvT<32fpCyd+~c-lnR84moG-?b?uJ~BFPwI@$M1BYPsodUgd=J;??)S zDKnW_)Y;O=gunMh;BI`J3;;C`p~cPAS6={=SK{K;4{L6=yIrd{tv7rS=}N>z z=$Ze*AW$wl;vjmHVWOFm-2vY_=kIK@4%YUiAi(zhPf}#q4Giv+^?GXh`wfs0=w5cb zdFPJAF|anXyLQ%h?c^|pI@nxY3gGRGb$*bS4XkI66a>vVUX28XSS6c7gV!)w0F8P*32o zV}*JJ>bIu*9);kxJtS{$VP(==`G!7K%{4WjpZ0@}785I74)f|g(60tAOBUnG4jWP^ zi}9snHY~N#?i+rzz-rl&coGKHywi7$28XA#jg&nmpA;JPg%! zsE_Vf2W^+YB2v5>f8ytQO8EB-3oP;@fTLl8Jfbo*#lCRJQk&l|DQw`v^@f9Fn0kH1GS zLBJaCxEPh*w0F_bzouH|%JFCw|J)c!^S;pA?{A+oGi=T{xO+R(k4-vgFZpXx>qzY? zK`I9ZB*%le=QdSI#X803le45|%?iS1O!9Eyg~HXgv(_+MfwDy>Gtv~@GuCTAk9ICS zIgNbd>5*f_@@bd~@7f;Q5);x#aV#y^xGDX@(fX^wpv$mWtuR)jH3%AF+20V_Iex1W zkLZ&!Av=CuspL;~D#~loBz#*A^lUaYZ*3D? z1;TdZo=C;c-d?R5R{83TjCXN^T$B*Eeysw{rfc=({GE5}<=ENYs-C7!4R_ExPFbN| zOffq?@Ri?-N7|{$Mb3;UE!uW~@pme#2lw-@2R)1xyJ&ip@kOcj@Serd^r3Q5J#C^@ z$?}e_66V_@uUV@(bs2n zdF>vlr=f(R+jBoVc@iWTTg^McuqE-5d~~iRz4}^)0g= z8|HP)gZ9*yhPWD@@{Ke1nb!Om#PR2)d=Z(5e0{#=^D+BAMdp8X8jMm9=09R{Ku?9) zp2XfwJWHAR6KHD7SLCDx;pUkN=uqb4|% z)Ayd{zb=rK#h`aILFvw~^6Sj|WAeu8MaR!TU9a$M`u3OudB?g9YW+3GEnr;JL@~|7 zsnF#O?TKnP4I#6-&6Xz^3Fq~^6=OTq$UWc753`C?HjcKW_n@S$m&Zy&rrkeFR0M^g z@26B0b-FoLy#l?sO%HXFz)-W;)$#71gDSCkEee#=)gA#z0TG)7It*Y@l5K zc~k0XSyMMO;GI}5LYVF=vx2sic zEiRE5AW7EI&|jI$f*v&tON=|F17tbGIynvm2D*I zhn86^m3X1+YmQereQN>Kmwfee7&zjc=Vhk)Ni$GgKGCJu=w>e3FG(N7D8V)ayxMa`_^W6+8>>49C}{nNMlGW`YG znd=?u8My{7v1huQ$@7zS`K|SeEX9#;nJ1ENObsJ^5Vmv@A>E^5dCcl2>e;PpPLvoaYj2%gcS%NiGWaiD!PW35@gf35v=msJzN&c1#o zl3u?xX??F@M*66Ko5gt6g}Nn#yz&ysiItgRuwI(yjM0UMxz~AJo(~l@mP7VtTf+yZ z-2oLW(#Flr%{@Mjt?yQ!k=!xEcK(+SCS!CL+CNc8)Mu_GTc_}WW4mo`RiT8sVFusr zbcZ{W$GqWkENg%01+N$zOjZ1RHB82MARv61TA?Zb*s(IS>r_P`-y&w|L!eKbWFp634JDRvXl zE_RHh%I~J}m(`|UsG8qs8&rSOAM^|b*+7qZWPYtg4tJ12p^}Bjovz}6w$*Sd!8=)Y z?>#<**^(9|7o8Eh_#Eb(u=;#CMa)wWoS`-pk|kF8wiAg9jl@G6rh0~oXa^-6h2&a^-@t6-s zBWu*EcbB_4SL)tYW?%X<1Aw73I9-#we0Y-S?+=dk@5J&UsC!-KYd6I0t3;7o!wVE- z@bQ(gJ5-Va>}Oi~UTTepW2%Fw{Hff5yVkwxQ?ctEksbo>Y2!G>r(Vk3odfc1UPr%T zqSQ~`dn&8aLs(BHJqIc_scn!0#X*ZI+y`e3V>z$o-nWoiS^ZQ<3a%JUQP zxqTgXuTsDZEw&e8c5WK{!)x_APuHmT#@xv|+{w3Ccvx1dS}*Mqlm7h7oxo@oMn*L` z7|OL^&9f5cFkdh{JNG-AExK%??h)I!u6_5&YUPbtfOv}-DdW3(S65T6}%n{$$d zeq2}^V9{y18BS&ejEPNk}>;Eu@Yf2~rYmjC13;%GjX{d_eFse58ZKFA}~;b3%R6$zuzGoNv@Ay zsC)MF<7^oWjCI5x4Zw;^uK*Lv{2?3LfE-58CZ5lwsLbQ~xeXA>39w0|ltgmIjco|@ zs?X`4ZD@JL=)zJJb*s;I1_BtYMjhOPLecl9X5qEFmQO3>)&>1;pY{xsT^^Hw(8e^J z2rw;n5w;yZzoevcN2_z}&-uf|)GhCJYx`ome0&UlQZsfAOiT!vvalB*uH%er2A(|Fh`$mCq)b%MGbPD@-S&JekZCP02pnjT&0N4k7J@Wk|IBcaFz|4$?v(&{{i4EolQxxB5r4Yz_gVVC z{B!?<_rg<|mL}p3G=@x9uK)9U!M3=n<1Uxl)FiSzSgfxzBryGs*cjmWJJ%n}hL2a; zXzNgm!0Oumx!WZU%TPZc3*z)OiNo;i>LfzH3fu&?Wb@Rl(-G@>tVS`&>{eRzWl;)# z{g*Lw*oa~dw`QHDCIA)ISX)moX(B7D-|_qI5J-gA+e|n4McU{J|MSbYF4KiukfZPj zsR}N+fOE}Q+rlDug3G)+<$UubJ~0WJs5I}Py~kspkyPsNUxAZw=xoBd41=Xv<5Uaq4;9pN93e^BeZ7PKq#4!r9B@>+pc z0%k@VZ*^c`psmt?Bd2O_xsNf=jK9xFUf{^M-ezm2g?D#wVBqK5D+IfhfQBKCW{CO# zNWS!;66rm_J{Fo)f}B4u-Aidr$X<_nYqOk%g~j`m>Mvg&_X>Je=&~vfCmDyS=H=x% zB9ve7v{Vz|;NVEgSlmPPlk5Y{FO(qGj`a%ivwH(O7HRXMog)9857V>dj1LL5;Hz)S zjiE>vV<79wt7A7_11&wb0?%H*ROxcfYE5z;v2Y&+3Y~PL;BMvJN{~;5l|ryBn1Km4 z`~4}kc@JpOWPbgs!M*2EVY5C~eZC9;?=x?L%dC?kH#av@h=yiov1@P?i1Cx|abE<# zUS_co^#T{gjOB6W<@Q_s!wTe6Nt5V3WUPTu@~Y(J=hI=ZJ#_q7nX1>`2~M-OlpxuB zV-nS<2<{H)w0)hb_ZY?{D5(D<sFKmAY7X7ZV)j5?v-|-nDaA zwd%N0KZ<8#w9+P+k8LdNbA!Ky;Gr_d-Dm&|tI`x*dt7)Ad?mR?2_6D})eK(o9HZco z)R^1Gcx_dIZtcJ@%pcnX`>nDK8fw5PMe65VBYw~Z*0B?)!l?ekC;qD;nU9ZpFkqMq zAT_cJl|63s@jjf!tDcLJ$&gPLKzrt!Hl2^_Y}pb!E{JlLY|r8$D!=$+Z?6)M<5Gld z62GS1aSOZmH0VF}tFeK@E)n55;hIQNi+}i*=%IAFtk#-w!qceVZe2fr_G0d^=`8)d zQDkc^s4nCcXji>Rw(FPuG!O!2Tu`@A_=oV<>GHl8eTy1?MPq*l!R$ zKEAOX2^Q!IyApP%$D^;w*^qOZE1WOizZxUd*VHICj|`#UQS#Ao`D?qsME{xDu5p)1 zN}dhWe;a37ZH|06((P=x%Nsi}|1_-l`$$r-tRI#ZrltzpDRWB!Q>5|NT!QN$2Qf%~ zzCEk2x!e`tG6?a%TG9R*_ScZ?5_7?j9Am*?rIQcvs6D%@S^nvTDRK+tut(L53doM< zq*vy;c~L%w4Xk-@#u|4Xw=*Ue9JA`xY4|k%SCjE)B=NkHd7nAXSH~o;GFTl;H~3uE zk=&i9+p!3wQ~#~LxYxD%w5F570zJLGME9PNk(1MnHVZ;>kG$6YYGwV|hN`M6dI*>j z@w4Ic<#5*I6cLDBQG};vTJSYP3b7~PQV=>p%(A@6Qg^ERh|F_Ys~>CL4{A;+=Y&y= zG)_BkG_CmL-CIdjoW^YtITK%G!<}lWPcr#BJzRybmS;CvPQSUF`b0j_uAk`7dOnl2 zDuID6Gdr>Sqjwh<1<$G}p1t~3%@>Akx=U;j0q3^_RtgXV#5)_)2z-a%LnIO+^p(E(#+C~Z4ViRFE6tKh*%6L zV=b;b|I=E+xEZKx*){%kTWGbvB@G60}S{ zL2CNP&?NF~OnVukd~Z+J&ZWo4;c4jVQZAdJ$+9q0cAdPz3u9(lPi+t22%eQkaSqgA zL^p4AtW}tI+GIgzoe^Rqr#H5%!3{2$j3OXBg7Ot+T}_UUUs=85LPXMMG!AUkW7vjG zzX8C?h1`28;Zv6H_QtYf0jNWM68K}*d@5AU3~kn)p06gvNM2b<<^JOvw3;Yf6|=xF z+n$jTQ)~}bBu6KOf#t;EhyPDz^(xj7ziGXNx&WTx{|EN?|Jxr%l!MyS;sYEZeC(j4 zKJz$a?QTp?R^P*k5CLb2kP>j6GRbkiQArqre}G{aP^WX?r2J~~O)?8DB zn6hQxTX%6HZeN7q47D;{$C1Pb$I`0NZCo6BKk(`PWBf}vQ6k{rI=<@%nz@g>^u{Zs z3Fl1)(A0b$fCkoZkqt*E=q9!gJb>Nil%tNgh_gxqPQ0knSJNW*I1JugC*y1bUO@!y nUuWF^w{!Zh$MOH8t{w}%yy=-eqSe`jU8+*zFT{#O4Bq}P=*pgd literal 0 HcmV?d00001 diff --git a/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/chart6.png b/lib/src/main/java/org/team100/lib/subsystems/2p_parallel/chart6.png new file mode 100644 index 0000000000000000000000000000000000000000..7ce253372d14da7e81fb8aea520dee7dabbea127 GIT binary patch literal 54629 zcmeFZcTiL9*EWg`Pz<0*3%v*mB1%U}qzWiSs)7)t_bQXH;s|nuw{Ks` z+$Wd5DXmb7GAZNVJvm5hpX%mFsO{W{L*d}ZqA87uzT7(wi&gyQ-EUZdRS*!Al&j2M z`12dp2aoe#f@N}u&c71*|35f8hqLo|`ytyBJn4hS?XBDU=%Gu?B|I^`46YMWki!PD z<^HFkqX{{jI80X$eMoPmK6|cha$I}NVbrb7i(?_JX zqa{-Gqyz+4Nz)h!Zfa|3QBFGdNW5vk9n1bICq>8>jK_(eY&B`Ve5p7zG_=<%L$+<4 zE+2X`;1a>(_hyTx*gii)~=y^j`R2Ym1cJ_E5(Z#Mr z&tJWwFF`lMhjg#61MZa(9}hmAtHh?K2@Xc9J95ppwg#{!PNxJ;#u*xWpYEmv>(4k3 zM-6M4y6~3x+OQ$^C%-DW6NjBcDypEsY!j>C|#rSR|Fj$)5ozf z-5Ts_KJHZf1rjr6-ELRq*;*Yw?KT%GVEBW;W3TUtFC!7b12ABK=H_ud-DRw~4U4dl z;~XE1Nw9hjf8 zgk(bE3Y4T8v7L6f1i`oC8K&U}`dHvZ4#QD5zgpB*`hfInvBT%<@&Sx{G95W-D&n$w zt6th?v-V)eIGCCj6XJ|NnsA+l4^B)>%s3Jdq_YfOdi<=JYmkgiC?p^wNzBzF%yz6i zx2bphxz9Hv%2hTTZhgEe96H0qZ+2ajo)jTwgSfW8)SWc<^y{eltx9V$y>2J$o~7f9 zQQ&_UBR3wMPA9<|oQ!9Z8H}H1OaP`jIyy==ZV0J^8pNd0qid=R`w4O)_4RVWRNL#1 z?2+q2bpsjT74Hvy_`ZE-h9cNQipR`>d2=P}VBlzruLBH%_T;FJYZ~J5>H{H98 zc>ln4t*{CkdLx0hx~ly9DR%8B!TY5##H{T_3ayr==GGErGrrE|W!Pp@=Q_^Se)FHT zIw>hB9mWiF+((9Z_lHVQ=fxay^8AAdvJdSbdNss|`9mzC`eLnHg|U z;OpLm|MBayp!k9wxD5Dt+X6WB|JOfA%$0##S#g1wBojRjHoC@_`_k`9Na)iKXMyO1 zdU<`0p018p@xpf#rZb+W%lCce(QAJF9DbI@3Et9v5gMeXqRs1JyN8p zrp8Qqu-i&!fBEFm@FUlaXZbqCn2_K_{F}3M@9bU#FJzZV#wil1h+dTG` zXZZQlWMnSkX2^Vg&yBhbkB%J$FnR6eYT@4TlD-{raWU<9Oh4@a_^3HiYy|pB(kJBl=_Qc(wD=A;KQM zrgyT`=k3q?!6QN$BYW{J_%ce(mpK6q7BI~*CnRI+Y;w`o{=7tU{7_5?hJKL}`EJz1 z&GG0u$su|KTND$%$nV86=xbBTd6Qs}`KLc{xyeYXr3|jza=`5yBamieVq&(>!U!T$ zprJ&#z0|Sz`_8qY!NINDB0ZAF_x{=rO1uv|H0UzHf9+vR4f^86&uR3pi-!S# z6F&Zrb$#%-#Qfh6i&?t%0{JRnHHxbQz@;+43QDcX)20ai<3s}0>CEf`C+l9`N=)P7&d_^&hLIG4KdY|N516b*k3$@#w}_1vllbTY*iu z!1~rIeTRlC$&LWhx`5lDBK?oOUFWTB?F*sh2OJ5&1~H#LZ3)?oKJd1|?ybyjkrwJ! ze8i6(?JjwS6~3yDVnQBoAZstN{ii9iK>K&^-W7LPT3qx9%goH&Hnvez5#i$I&b6Pe zd(%Rx6Y=#<@|-FJCxBn#(JlXJ{^syM4AKikupe(Ph&$-$=y-;mmi{?~aY@_BicsBCN83f&M9@5fzZf2G>{VnW2tPZ>)@M42nx8HV_mfQ5! zc6N(@Bh5DoPL*EwrKBgZ`Y>9{_{9<7H_K|LJ;rN$lh!LQjb|hwkZF6H2Y-)wHs|QF zrSk35E?7i)S)6UvuZoN$4>1dkaD2y*S-|keQ^nPH(?sQYJQNqh{Kh`Pt0GH1Z-I3! z3b#mEyY8NL{SYVaKYw4a-AQ7*Z`bLXwX_!6YTm5O^7DP;O!11s#{+TVqrR6S>6%{6 zo4feN-rn9HBNJuD6dcdU1FEbSJL68sZh}BOqIyzO9AijliS_ZLy9~eFL#xuo76-Q1 z%iOp-PAQUpdIwew=y7fnbdJUG)PEi8OiLavSs^l+7Wgp`&wroY96JKs`Ga=NdgR;s z01FE<3%)qM!7`W4jr>K@fF|b&cxJM#J?%A&-|yLA-bE<+Xn&I0;PCKH&+}Jnk9{C5>C%OM|TFeA;bW*11*%l~TemJK3FjJRS{nAID0Z zqP%U}B7Wq@ZB%Yz-g3`fD6}y9O?d@kTPkgZyZ zV1FZ}hV^~ULdlf!)gDD29}TiBsKn!6$m7AVTd&vp4 zX-A_JQ)*sD2;oj`?|CL&8={lXLlI@#CzD^OtjK5OP(IXn&+J<#W1Av>f=|}<{m$PF zzV6?;fBo8_KLcE?VGL{hrEr^<*Xi(s8mdA16SreuH6E)bJz5Y2scR&CCkJ$4ovaj(Nq!oC#g>&WoKhZDu{mJf!y2e_~yb zXl7(NcCyG2N1EG~%x*euuh?E2pO_%?!ntl?JY)Xk3v_5sD#>pzx#aa_`+3%%?k_43;x^4@50ZVI;M+nSROmg1BV8X_%*toG6cq^OhsiLd6!e z3K!Uj7v;3lbnL`n zLD2o$J$3Jst(hhx>NW$5g(=gvDiBy8aCLRHd1hVuPiByx6|2_tUcR=;uYmI8hSoEZ z55o1debjgSqf7C2r`DtKdfsxieftLn6~TBnhujLw^0^#orup*TeCVU)_Jf4wx)Jo= z+7jIgQ1v~uuHv!CfYeXQ_IUL_vp0EU(PY5MkgJw^JFP(F{X!eZ9amQB|p1E8~_5M}-Ad{X)^u!VS@$k9b+~ zPbpe=*HWVm#^+NxhXwk0c!|h1C=6^ea*M}TB3%=fr`PuKw~FnDi+}hSq(ZCh^LdW< z?%<<-wARjIzy9!MI2OnBR68S*m3fkkxf1%Mg)<= zZW;UTUv?G55=5`>N@4~ zPk!uMW2&k-1p!`}!#{FimTnVHcNwlJ7 zRZ^;wUYmIhfAdEp9vz;rQnz4B+xlH>98<4t!oGq^?byX-W0Q#zeWqHE+^8PRWMar8&b;w2St z(~~g2cPyu$W5FxAfXxf<5!p&)Z1pmc^bH!8t%=d;wc*=0sB|M%Qv;^UchxqJj}_vq z(;@Zgcu7*7oLR`lsF+n|(>DCp(Yy)9*NFG=D>;5L@P&UNMzc&sG|cQ$E)o8*N~Kl? z%`9qzk7(m|#R*S8x~&-sV#%`|EN(4Z;1L#IV)Ewfw9m+f*kpz8>gIgo@}3!42Ae>& zVN`d^?=?yJxOJ$c`{f^@NvfBmaY$ z6q6L_wY-FBVJ#BBO`quzZ84Z1!Xj*9X#;7-WBk{-c7OijsDIn>x#(ob#YS0$gdsl! z8c5wzLrBMfZK~z9cj#SjEMb=L-YdCFp(T!%tuU8^ihIb90 z{C!#rob@^Q5EG@;5IWzvJVQN?lH9ZzS2$(nmX&icrJyn~FS1?iP@Q0bg{-yVUraU^ z50@p`bTUr~y8X^j>JS#S_;nKr{efT45A_OCX%TfkaeXJ^n9O#Zb?QZGL`_Rz5_lkf z=dXRKVuNIDISN;e>z;gf*08saFz2-$RDuSg_3##R{cO8{4$@;FIFt_-UkaIik0H1T8ZwRyijMSNZilu>KP%^OQ-q z@AW_6vGR)wyK-g*qo?#};i7om6M=DxDcme|AZhRlI`3o;FK~2a!1ME%<$f5|qXEM@ z=1uM_K^nqJhQ$fh1WUB|rjJbJcu)TuBCVmg<9Zg^fFWk&j~|;fR4P=+3q~p!@xREE zhl(Ny#xdmb{(D>^?PTp!YbPIRs}--Wi_x}0ddMBf$#LKfqQbGaS)!d%sDFXzva{slB)gW0*<_Z%=(W+Ny&~6b0t5_?n z>cZUMs6ZVho9E~d!voZi31(OaV_2Xir|;|dqfP-~PB~hclDweYfi7PmXoRzF4W?#A zl#ix$(*W_BDAU*u-_LpL8J&C5%9MPfmxi_j*;2hCJWCps;>0^^9RvLqo$7Agl(F zuJ%)BRME-`LqM2H(xWT3b*#ASXH}ZsGDT1;^zy=lQ;=}yW?gc5SwizW^4l1Kd*f!? zBR!s%=0eEga};Jtz8c-#0}C)^uZ5ey>!LYoS8-(?%OJ6J9y#*zsJCEEn~d^0lr9gv zy`GGj@S@d&?q_tX!5=^7cphwAc=!EZR)OslJPm8OLhW`|rPl$#yi$$hW}zMRUH2w< zQ768ia}#;qY~QBgOi{6TcB;mRqJ`t(z2TKU@BP%)oV zubzkLl9zzYNAf6ABu@didcn!;&48+%Uj0+u7Ub-m2S0Qc@}{XiqOCUTO6R|g(UlYO zw8CQ-T8D3IpwrAMHExV^P;}J#sSBOOsws2YKs=~^c5<&V8W-Us&3-v$Zz9pdS|ODLWb-kJu{SePLcr|<|0kj zBshcuSjL4*gj){!`ugjl+RvXigzs-oPn(;xWhp1L`b@44<>SKW_G!<||3kK4^Vjs@ z>Pst)2g&8F>8HlbR`(_fCsB=1supRcanxeyGa^*<)8Yd;ul$!u1;kgmVq$X>~fq2I8-(%FErt1cilnjU_zxwrFW5 zf+#qbfpR|`-~u~cE@B{k;PYi9Y|1u%9v0!R@2eR!ds`=Qn`YxhrV@~Tkc0l~7S7mL zJAUrMD9$oB!()`HmA-wCfk{ic7;QCN}~@cV?qDWBQ911-2Yq zJAy09oto0#I$8vwDi`JlG`LlF4z8C#@Z->;%mZO>$_J!fUWE@_c`8iy=6k3aI^88w znLu5E9MN}WB=iot-wRs*DSXaZplejaymg00j8mvmFcfeHU+#V8@tH)qlM62xm-&w) zJyvZUiD?X75wq^E`z&;FjP3oETQh}hBjJ3(!kGS&V}sqPT=&y5vpjogo}agrKzVKE zYfo>wUU$Sbdu|XtkiH{G^Aso>?uDGQM%I{!`~=V1;~(!X!R4!XIXMHu>wz{z%l#%v zUx0409BnFTOLj=g=(e8Ba=L6eTG{2G%p=QdYk|4^jp+0EilOMR=5Z99FZ$iOJ>Cu$ zyu{OhzOXW3{34v~se<70wVhvK_~FQ(NLAR4Re(DBJ@=wQ@^vHfvyfpN!0E4jL_u^5Ab?GMY5^!d0EE< zHSC{XS+yk``5uDevFDZ$rN5x#RnQnz;-o1YxL$|g;q3^Mhd2%?@Wa~pg zcFuAIxb<6AeS7bPA9hK@&s{r|>*tJ;b^h9lECYEmJH7Pxt+%~3762ZktgbtptbbL^ zfbrW}=lNDf!TWkBb@$%%R1|O1T^|kfl|Y3Tf;5-jDUQmHQo=C)Ba(3J);cGOBu&U} z;tr{`@ZbR&70qOCVSzUlOY@co$Odv=ui}M}-TlWsQ(?;mb8V)o>_I?OAK2yS6QdI9 zPgc)3QcESQ9i{$pdxf-zRCM4Kl$_hjQBY*Ku~2G#Z*>@%gl~bWT_G=YuAf&$IBrwK>yJNC^9h7~%I8sbH563|kyZD#sd})qDCy-r z)SdBhlHhev24U!jbJi`8*1T|uC$PIS_^=3M8z~X_;-zkyYc*)x_50rSn>y@jz76n* z@y2QCj#YGzz3_7viH(c2JpEwJr%P)(YgOs*MZ+Rli=>oUZXaZ0 z`&-$P&=$dyFO|RumAlxcmo} zMV61*)X`lc+e6B46^=Y&^<+gv!A-AC?v#30e5%!4rNJZ%U$%Pi#zyrx2E`*#?r=Q~LdU~CA$2U+`&$sUnM5d9;KMhGt@L1#g46oV_Fp*&a?)tHZ zB=J)})`=NbaSJ(4LnKI3mn3&>nlfOB4e6|@72pvfKPZ?Z5W(*mQFlGt=G`bsZ(5G^ z1EoKFE1N|OQ}so-D(-`mh3*TTj{q%fmR(cY4-|1dSog{R5i!D6DUf^?I^@^1WXI~x za4cQ!*5zT;lV5@0!92)Fit(5i%X5v~Q4sm38-g^T^UceYmk;D0>Z-uWus(s43{eu1 zUtYqa<$XL=p-tjuMWJ;Q0sFg%x8RUhzWMS@ySaTJ&*$lp5Aq0O8pZaInVxnxkp%Dg z@(9`d{ba&rZfz8Q` zmLjIIiUaaTO;)|nrMf%qS3O5`yzgKxmUjTim;8^{tFN|?yn0ucz_=W|1l$s!r@uUZ z9Vbn(cwC^39s!V9;vQLcLsNa zTQ&lJ0_%7ymuyOljh}yBgqec9N)G27Ox^AlaDzs*CSMg*e`hZJK1dFfC#Skb)>Rry zkVlH3`=NTz>H+;s=7)6?yiKB~A)_R}IXMJr{I~k8>ASu>^bJ^hXxyp>$Smxe{6TYVS*j`b zNe`kUBOBUqhi#B7nE=wrNxN(vC_IJ9PC3csHt=(6}r2X4g^kai$AfU3ukQZNZ$Ru0h^bn^ig8 zx#z$!uxSg@aQ%g^-<+MDCEEJ?`wt&hvU7d`i1_gE1Y!H+(S@az>=e>(9!yt1cq|8M zS9BxE;M>kdu7kjfSz02ooL!sAtNP7Wij6@cbm3|#yEUkFU@bu}Hnt1V$B9IIe|D<_ ztXW?Jh5DCy3akX<2rjmi63PHwItZYCVEmS!pD)n{nBfp{iaS0Ix&CG$MrX&--QC?N zHl;n9bJr12BxG3^Rr~WERIldc-{I%ipal zhha72vQJe`B$t)r*Ob198@38)9a z*WdjYlfSK^+tt-|LgTq5_=SY`dqntny$>Xm36kuALANt~fiESwp0t7(9(@W2=zJ6& zNk?)3NEf_~0Z0{qu`nLO@5Nsmvn>m8s~ki%J9Rkt zdh4gOWc{Q+ggwxkOrF~i+`mLbx<|{feAZc*^BS2e%iluN=*3fn9FttpE2ZH2;ITEA z!)iKCw*MHqWvwIC=AC^FMWHBO5@2ZWu1L0rKd_^i-Y4v2qqXV{8KsIfURr55onDKN z#+q7h=Sfw}Ux9m1V=j%TqK$;v5pF|8w2_m zl5ZD%0DaV!akfg*4t;)J-fY`h(*x)s1Q@ZIF7@nR^;zmU?3t6o$lkP;i{Y9SfRgR0 z7Fe=ALDzFieYsgn*kuEalb$o^#e1_mmxSwqtW?yUe7-`sUG^Li)KM=ctV$Sw-q=8v z^4yFEK*)s#hai4sEQJ zwns`UFrFCnc8D==xzlFp+&Cc!++0um0pO--4kTNyp>s3~yRPq zsK)Fhdd>G0_)4vMLFah3J*Y6j)eINQxEwCQ0&9yw2Q}Y` zaRDoP3?Xez%MSed4V{A2eS=I~5!|DYY@%a1%OL#XOH08~uaAjw)4c~p#U~1AKX%qa zLOqtVCcETSQENri_H?0+xn0a@1YpW$;)+o4WJPoLrJv9#snn`?*_;O1W(>l$K6N#z zFbEf`WCqIP{Jh%XQ0YD5;!O-s2Pxd+vyPBD)9_QB6g^vLcCc!V*cN7j`l40)>v1=V+ohBhY{vFW2%6{YP! zKy&?Knq+lO0KUJ*Wx+KtUa7_IE|5X`46PUOHKjpBq_E6neFV`O!U@FT3-U}7__gn9 z^ND*Ro0?i;YeDXa86 zXcN+NQ9|!&&+wqH;L8fa==Nh#o|8@8Uu8mLjsn}5KtUOxls7A%YQgyweMXom%w> zxJ_w1-tW}ZRRXeN4s*e*spQ8GVrhDQSbv{ge!OoN}i?)Ax7$FU_y@ z#r-Mf06Cqsx;{*X$;xZ^%s)Tjgs6M9J1Azv%YNq{3p8gYzxWEFK^{rhmA!ij#4qU< z1OMp$8gm${ePL`!fx7SSq2*qS)itbksgHMd5IxoOtu`CMpUJheOW_5lMG;UQn9Ri} zecvq7{oLGK0k1=c)k&nVefpE|ti8QAjxQ4ENr}1=MWfI9gR6b%MEZ^`l;tMvHyvMS zrp)-OrFJO`+Bs6hZ?dG)rz`7P z+=riZd0B>O#UTh|PU!Z;YKb-|k<1tVbS3|&F2r0`2iuEX*2iM5UAxvibAdxS{??ZD zOTBW7Nb_gq=MQ~LA2UCJmB2NOvJJEt3;-p`n~WNRIX&&t-#>-m@4rMT{CjNW*T9g5Ls(}xJ-B`ks0^a0uyL3VG%e!DF8 zS%o1jT$;}rB;7W8X>B7D=+VA(woH6!t;XZ60!gtsW|?-oa5EMVFWKg(Dk{#*JQ5Zj zalQwL8<~tdOy5^;)*T;ybKhMI()R}RVgQ>RBqy=+rH<5T?J?^UzfoHyz_&3a0o#n8 zsy;NE$)-Wu4;ah43IvJMjP2tqc4W|5g;HILK$o*nj}>wkBYiOvFf?fY65;jVGc`41 z#}0~ea#tY3^*%m;PO9kpj*{ekUS3u74n>#wp>&Qaz3zf8+-D|aS22H*1D5a^9h4!l zJG?f&sO(i8$<@u$%gI+Z%=}>qGQPKN*4ACt*Wk2kJ53i7XRVgs;gY0Nv$FKrUm8Jo z^TYWLH;3}6$wqj1rpDj?-@{G@ylv*+{l2R=8t$vxs7~w+$f+L;U4z!Vtsjx`%~^BUDzMheD8^ zTlU9K9z%4E1mgZmpG|W*4S$@>;`C(QZh`gFi~vy_i5m9$P1@)cC+^6JiJC|ys;G?PVRezB%w0hYBtaVXxb0F!R97n{x3H=(KFi;eDn>dvNYgu2|#PP4Q&dW zd^4b&?AYgZCMOIwI_}#9=RzOerRgCJWVA~d|Q zw-IQ(7%)``#P^^UfNJ##SIDJCHhevgCGgj;S$xX4Nk;2J*OfG0y+R8QPcF3%|Ae{> zX3EEvy((0I;? z(=inD^(ZpT2f2dYzbf`#>2*bVR76_YE*`4eFMu_H>^?2kT`z^cNb>K(2rA*GQ@neM zWm_tUk)2u5NHio(?bjENBvtI$5^mtU% z@yq4A=>Xe|_`6ME$o^sdo~bY@wz^xs!l-JY#hNu2VfkkKB2KFM_KMpBs_(N}zJ`o- zyA4JZokZHjQtN}`Sa++AmZAtBc{Cx(zc&)D)cV4o9#CgHih70+V`(;KeXX;2igq?t z5o}{{eGud}$owTdZe!xMG>GfyF3>n8^5%uTyYjQ>PwPA33sBY_8^WW+v91W=*TCg3 zzx8=pTQrEzKKC_Lsp}cN_0+4ClZuOh6RZi7pFjL$)+$Xs~etkY|nu%oVPZ_-j)fCRg4}5as2B- zD!Tg~aQJMNK?aI6aPsQy&lHMBFJoHkQ;QRDBC7o;@H5`ez}-gB>@}N$xLV44zdIrx z2EVH5*=dXm; zfm)#VE}yjX0Tt6e2>}!xgvVlK^Q6`%NKfg%IBWELsJ|1V0KB^AJZIOFyC+HB$4&=# zMtW}g;9LthqORm(A7RC)=dNgwzbddIFKEFTabbp0ZuL#9eO77`drxrUpIv!wH@V-t z@$WeYYgcPSVP!|s{pc1WSLu%}va`srQw2FM)ow!xM2=KR))Hj5sJKdOmRg>oh%m`z ze&Uf@{hXIm+$aeLI}j58Pi^v**%AUlLBT;l6ECF4KKBS93~HeOI-HIDvQ!n_Me}q{4}(cA7*|5U5Ps^E>;}` zYhtFpri@^eZz6w~00J<#6~QpG&Mys3`(GX!=VWAjsCwPxzim8_tx6qm{Ic5VHk0eY zq-(Igw=~1ZjSn8qy(-0awO{+fb8>Dn78dT%CH`bO}WPt~<`@cEBVwY^* zeCNYFJ-k^-n4lWr>TK&syF8jVsJf@s1Ba!=j@LoP&-GK(Th=$rV5~ zn8}Mg>s2Yc$t$z#k*;vg(7ocENzXR+x#{2hS`#E~wjTt0lTLZx#n&%vD;_6)R*du5&OcW|TlA0A&>iorfW_63ri1*9? zg2^TTOymzuebkZjzcN6R_iGgOfP+aWzhpfIuMVvz^91&3}QaK`$m0v5MY> zar#+s-c)Aun4jeEo`oBMrVNQ^f-4DG91)qq=nbX>Xek-DQPpdJ)~WEXo$nNx9;%7f zj^%{;UIiTcZ}<9bA)>rbNlVMS;A!lANw!P->*KNE=ek{1KwbNIcd2KojpNxDa?H1| zPM`+COMPvrU!ROq>Y~ND4g2@+{OSD(uEJ!2>8&{6`Z@G}%RvOTIV=i5xB43eHTj$LAe z7EXf_Pg6L&U3)DQpZhAY-5vK%1)7-dQs^t~06qXZ<;X|Vg?hq_Mcmxn5^a;#t3;&q z%lwZ7Hh8ZA6N|TyCm$YlQ%lzZ$eT#=_#l}a8LgB7q{WBV#~1vQEU2?R>mOhGz}*l2 zF#p_oz+$!o>nxUENr#_MDIH7&I77&R?Wsrqcf&reKTqQa=E4|@%1TSc+eX7t2!wGP z7GRyvSUSgS6?f>M+FvOx`yT_RX8I@U)ulrVMXFz+l^;c_uscJBT(iDlYmySbDUdx6 zEGJ~CM&DDn_+;I!2qaON?2yUV+;LWFC?B1*MRMVf`pl8%Q2%T~l5B)cJ|wlYlyB-NQ&;6^m2Np_MK<&gC z6=bseZdf8?33V83MDX>7B1qav_fu9q$z0KGn0Hn09YrnQFr^-$Zh%uZ;#FWhM}H(F zB$r^BuS3_p{)Jx#nhR4B|LR#A8G-nKJ?!t!z)pDFyNQfe|3=XcbRBVvayX$w?8)Kx z^&2$48#-r=Lf1j{_CNc*Me}uDTCf9rU0`Ve=7sFBLz;P4v zb_}YsN>+f|m9c?dZ3UX_7nJg~ykjG}WYC$e@(Oj}!NW-_Z^@HYZv+K9kiUUqUHhFH z69lMpRy*uqq|RODFD`FTb<6H}tB^nEs&UrJk z?cLaXd`VHSJwGEEj%Cs0#xL1f%^*fEHpyb^fO!ff(8a*KHNp5^tXGeJZ68mQ;uu(y zAp`wQ9Ri{1y5-3d_Rq?URV6SVyl=BE;kU0|Kk?&>{2r6JDYA`}3-#X+x$xtIx-WsP zBJZHR$!1&%K{qS=4=+?%?q6HfzUrm3rlLEkf}qQp3;Iwi zh|wvu51rKUHx)Mg9%e<({3XtM-_`5{&@$ezS5HI(l&jZ^`ooH~M~&J&PXA=)wg@1i z?k-_%TbjZHYkRpyW%~h?;h9^9HhW39;q=(%a=z5tute*+=-tCltuZUx#j` zTyFcO@)7N)L4e>GW_~O{m9g4$(XZ?}k>Ik7h63t{A1Cf%QZq_Ic&vvJXI$RIqpu>k zi_V3%_V@OGz<~%qnSOQL$*=XmWOz{8i`N4tebQ68We2?^d+pt|kmjk(83X^_DNOI; z!@*QYVcpwAT8X{&)HT=ONyCWFXfgLxbDh-zXQALpN7Gfcl=yfhU_>q(7$Vvg^4POb zQUzejm7Lt%G(enKfs&0pA7PubFc+@Ah;yHx7z_raX-2~3O$R26Q|tb<5<-LAuL%02 zQ!l2kKPsAb{La!m>7eHOZjdc}g}U9z=U4HRF9MtdtJxmN6(1}X-SOK4e+!=N1FvMv2HPA&H#e=2R`oVMit;yd%N zap6aD=8b89$afv-Uv zw>RK5@l`Ik`R@v_%Rp#rk8`ZccVR2+K3=+z_8Q2sdiQ+V2c5)39b+kHpPj8Bb}3VH z*GAL35+@ds(}20_=ekPWb*(j6pZtQH#&X!;$_W>)v3AoVtmFIu{*Qvh)c?J$i}>5t z9k72T0B}5Ml1lMPN=t>PzBIb5(=)c*n~PEPAV9Dln-B)Aqg3}y zMZ&+24{l(t<}@(VXCG1Zd2M0`teXvp2R;@{F1|a>>dAUuHe1Vo|2z$P?yt5qxjYR% zfaw9_qmbeBCu9J}=TFM;s|``HjmA%g`W>H~c=ddb+Xf;XHB!-WE(9pr^C;?jy>$qJ+(e@HSC;g^$ zMgTYK+b%x1lsvUI!g;<7G1raGri#T~laRc;lNYh~^}XZ?&t`R*s@|-qGxh_llf~)D z(aGqCs}$mMXPlo8d}FiRYVFAh83oVxO4lVqtM26{&iHgO1LEZ;Yu~zF>Nl#si8hdY zDk`>n&cOBFOsm~LVgWil6CS^QPSN#-4?pinAL~rn*|l95)*Ak_%{rr~yxWJQYc>}4S>lkAV35kK;d9tEUI?}pvJ0ImAp zdQYq?^jhqee^B3kDc&1?ddT=_oc>$s<8yMXjC%=~_ne!lDJ|`Ho~WII|Nik#GF@hl zbQ?f{^AO=3{vv}1$#|CfS6h{%SEMYoQkJVO^6Nv(<5fRS_FjPbtn_ROY*S27Y$lQ; zFU%?d28xmiRZgG&p2OSJ{%Cn`O$OvIFCnQ{|E1D6aEf`f_ps=F~%?(^e6&=;rdSPx4kBS%22#5FE8&9!6M`D7Ivm)_I8?k z0IpdS!lL5GS9(!%K){mAqCa!yWqudsdPN$68>Gdk0M5oN<2uvd2e7^HD zVh0Ew-bpoI7N;xjRLe(4Ba~Y#0%cCrJCE^Oi*ZJ=0sl`>ozDwW(fL-hf0?3er5P+yewr$5#N- zAZU{LXa2p6l%iyX5w9&hF6$g}q{KgD-s>M5f&~bD%a4Djc}Ic2;2<`BSSjU8_*_59 z6{LB_+I(8u64Y%!zHR{fAYXJB|w1)4EzRiPA>&v zsw7oEfUk#pY)Ro}$2Qg!@p+eR9q;hG=~(iaJ=*BHWZhy10a&*3wB(mnb__mE)+v&3 zHwAOv4`bgP(?#wv5Ap+&5do)p1;$>KorujQ79f!8A3g)-f7rxLps8>j2dII};3uP2m! zwzqHZX^3yfU|&QyB3@MnG~KaY>6q}&^21xo%w~P8Z^8-8l1BS;=Vu2 zn{&}eZt0iB=y9~ga(qzvX6I{!*xU1d*<1S@$bjZkwvnk8U$`y`mhwCm6&~%pJ92dS z>rh7UB>DRmOKeOoFh&&JvqqWmXQukKYLImLE9Y5I59*F!2VU+mIXKhsyEmc`VBffN zEsOAzv8U`k&d#p29Iz_IKT{Ulp`}a=<3EFc`>Sqb`+t_NuQSP-4AG*nC=6;&a-*y&r6Vjl!qRMiZP>C(k!@GmdtRsBgW!15yF;mH}uow zg;wt!0+g<_-b-drMxg!omSz=Ig(Tujo^5%+X`c&)miBXMgz5hJ=hbV@oWr0gcZgrg)&`G@9_{v~K+h<1*fU?G=Li z4r=#|;TpTP-`U?d^!<+A@htD)SB}l0O8}B895=%$q2H5hCJrpOx(j(Xj=dbjL?8U! z52m+YNm8}@s2S-h@j)ejda`En4cSOIN%KYqB2&EBg|kU)<;@o{+F$3RBfSPWt~oq! ztkul86Aw{u28EQf7YxZB)#gOSr9rN4g-puch>9Z^XA7{*|K ze3AHaHe*~7^uzcOzxTc*O5jm~#Y8sQ&P3(v){>EHfJx68b!@>q$dAk?b(@mb)@Ayp z>MgC2posGJ^A;7x<|8$1 z<~tcPQmQ(r0&A~s`ke^7r`B7~O)KtC8r_%uGih^~WWTc>c7IWB=XaLRPJl(UpYEP2 zj?SkWUsJbTg&?PYpJ(5{JUkpwUpGo|f@c3a-d{jSIfTspVV!VMnDT9ycL_*K zcMaVQGsM8acM4u>UUd*)TG?Xgz!O%&Yt+TP1&XJp^LX>aG$%8}{2_w^e4c2=Z2aaw9xJ%FPAzAnnI#^~MHgbtM13mh;HW zcMa4*J!{W64A$>=VvG}}?h)jx=Fo#t$bO&o+td1!J+;Jv7h}ch8-!mk7aL6ggt^p( zojXR2Zc2(@Y5CU{M(U@c^;pzqwbZ~bWt;}MIy!*Od}$oE@w}Dg!QUtC=QadTBPo$e zUce6Zxy=A@XuS2A+xj|Rk9sijM2>KKtVqR9Zt}Bkiq{VlUoN+&xX9m0MQ2^1OPMs> zp+>keqLt6ld$>1-6Oalox*NoS2?T`rz9F*eymwP; zdY9C8G7=5p5H7li-sL?fg9k<@vlfXxZkij!)lCe4HmL;cJG`y&QSOpP9{6zD3hh>} zy%BIbXEepww94{p0`{pYpmG2CXLWx2XaGToj z^2`WY;{GoVP>Rn@v&roFHIYKDw@!11f%X#f_NA}iQLWugb=dt9T?AHN7pjSC=E9L& zy&KJ4d6&OcHsIxbW=N#?pU6{IX7hSUA3c_KmyR#k==O~+x84(P!%cz0iMB(vZL9Nv73*%9C!R6p3lQHVWOK5M^cMpW^kkg$?gW*T$OeL}_Hmp?L!DS`V!o zBz@Ud9MoiXlfoW#O{>ovJWNYEm+>$@0?Y~*Eh}(T%8(Sjyd>R(dWbn0Vh!E-jbpL&pEh01DP{a}#g{9DP&Cbxw;4zNcH&+Z5G} zB+4+$52FI@E}yZSUKtNpm2YO7alf0{2aM9FU~Z7Ql!ixn$mM|=ky}f3YEfS2j^51Y zQ#W_^aAsFs7q;|GOPc;D&Um1&%~3`T&c~X6z_a>I`l2h#_ zT0fSO}m^qT&+Q58F6xX5g5M5ueU+^0H| z!Eg6$@TO45NgikVbQJ1(RZg#e9VN=%!u#I{iD z`R+baBjW@}z^%L3Iws_EcxPC*qNk^aGN_zAQnkm9wP#)i*-5mWHV_8q=8j1b1ghNi z>p9&Kbin-4AAYHmYRXRnrwuGK#67&4zf>x3MvZB`jk-lQCx(%r{7VWlXfG?74t~BNS?+UO7D-1rT<4 zNS~8~#a1Ba=&0x6EYq#3g;|7drl@GRlI z%*w4(f!D@8-BRu^ejngeq+aNW=K=us4wAN&gSmz%xIyH{k5bi>%~y`9J2;K>WLN zg2SJzq(n~+JdCUA@GZCUMt(VH^egB0AEx!7xB*XRDCN6Aqi9Q=<+0$Gju1rkqrb7+ z0LHItc>$~tQ!RCqmK)#JEWXFoBpVM-9Nc6`SKAOs;8iMhLCd-C#z$+H8EptWzZl4m{y8q2vmUhs4ja9=jhZiWE<%u9%i63X|nBn+KeniE;~ z(fx7CSxEVGM>4Mtytfb#Hn`wJA!2s5eU%9uI0mQjoQl~elWaejZJHO&#aW#GdK_mV zQs*N^g!pLpmC@}kTRhc=fS+l$Bmn^d*Q@&rTHNaX6l6`juyVJ}Ppa+hsO<~~o1aVo z{iTANCSFRzEMqndnnNA>1LfK>*?>u8>L}AL(j2z-&Y*UC+AjF&cT(}y^cg^bMs0CH zV@~&QlC;W-yTwYYT{9Y{)nq=nQ{k6mg;9KQQL?ybT=ahs;6ITDn*na+Cg{Ie%Gt}e zn}JOSdEDGY+cFrk0g#~nry##GxfkAGT3vRxIR8UTGD@ajcn>X1y!whs+c!Rj34gkp zs0w~vU+qPr-$mG#?v&KdZy$`of{-*jpA(v%AJ55G7k>rv^!LkIhlKf*)dZ9d1XQ`3 zX?UiO*nk`g60sJkz&Xju$-X8nU z3l-T)t$v(^dAFWd_>!QT654-!mrtFbSm|^SW9K>80Lp~^G-~=ZNbiL^gziKt;k}st zu&>WlvW7&p+>JXS;g1fU>c1yqAT2dADJyQ^EKDQhWw;R@eDyS;!6fIwfqb#LSnLyI za~$B`*D95B=-&8*F z0?sWsGMX;9*70!byNYKZRsET1U7pyBluSuR;8FAx-xI&a2*yz^iaWm`uAWm6J+AV# zwO_x+V3|8gK=YbS`jBe?yqz~n5;swO^;Sv*0s^*ttK>eO3spu~8@%!F2BSLliyI|I zg1Hei7-4Q5+Rg4&rpMM3ncjuMKdv67{r$|M$r{y+9p!1dlo(TD^f|Q=xp|T@44$TY zUwhl%y=;xhY^r!rne)-O31CtG(^)Jfw_&5{R#J9rZSONns@Iib-c+ofBWvzRBDC7Z zhq!tR(I)2s(uw6zqeqnX1hRNQ?geyh{C&a4HG2+N4#4z+yR_gYpBvkA*B6*CGD%W? zHe;uzvgZ>TRH@P`dzW3vUP%+2?MwM|&Sr>zn2rpSP8lNv2@aq!i-&IFKK=VbA7Bk@kT9T{VPBxyiD*{iV^=RX*3xPIy7Zm;^yf%U0jlCHvBX$0 zE(OZ!`NsEDAFzNl&kQJaMf1y91IamJ{}7y!x;#ggM^4Q;21QI*rE`Y@Uyu7>#jAfB z<-|AyYCh1;`x`&*YC-9ifkMVHsuNi`yXCESX#$^$d$q@H^{RTfVK(0rf9UKG3kdMJrft~rN5aZLDCG@nq z!Jzpy*QrURecg<<>V8{hk_LR^hMlp?fR#(mbf-)DO= z@*WTbEC^(80E=T62l;%dJ)y=b-@uDSYs~hSgSpkMdZ8Y09L;guDBk^1y|nG**MP@J zD?Su$L@s;vYIzNdafsS=I$Z}AOkfdmTDDa#n)w{oXcT%~AKXK4@7wY1hKldM;g0I# zzr&>wgc=;wq!ROfg4~*lEALB{(||xch{T`VBdpr%Uxi6W&v6fhatI?WxviMX0hBWPEix5u&>z_n&=?#A_y1_M^@ zx>;FmKb^LGit1Etb>r^X$x|1kbVt4ry<2MnFq*uws61S<%l?a=cMk0@Wr^O{cOnO) z=84AakJotT?yilILjV&x=1CWebMw{;U-V9b!%_JfZ=um#6fEZDijLclI@)P=;j0)B zN;Tu742wtH* z$NIe`UA^1cRQOsZ{rtgKtrT=p2maKe8UA1did2B=5b5P4Ki_Hq>i4`3b%$A2PZt=y z)_v47fvy^*A>Kq#p(*s1WTe9f%s?)0He+^n;!yVEGS<7(oL7;{ObdEZeQ+9Cm-9GR zb?cjbwmLx3Q4*8`6rDVRl5s3FJ@0(QArV@~(M3_69;`(W$Oa(PUvIA8^r*lFgzHRlnx%j}tUN!}s zcUlqrA@n%!>2FoMQ6N_qsn#NFa$O18$@6n3b~P~qp~&} zMWVd=pxmR_@=IrfH_F=WiNH2CJfuSM2vd8+<2OX~4#prq1Is}T6Q zMwD?UOm=*v&c`e0Q};b#w-4c7$RQocn3u6Bb^Oz_?{U;rMqeLWt__-}zJlu6cyfBK zwp4Erpyt?rZb{0Be21wAO0ti#DK~D$oYU$CR0EiPcrp3aWYGCiAQyu@0nnV)!3fJr{Z zhe-ua4m9A{X%#;srUiPBRd~ft)vYNEmLr5cfJ&ql?*0+ZM}oLm@9LWfgMa0?7gY~9 zF!`#`Jst>dr59zLY!A;p7BE-5PJp00Q=PE@sxpBlr)PaB%Eo~+543uNG(n+tTNbUu z-t13!W4IW!ThPW8U%VUI;fBIV@z>A?Drr@g@*A=&)l}b}#YgAeD$wO{yRWREK3Iz@ySG@s&!Zh(>-dT>h=?*ho z%-<LPx3&z+S50_)Xnh}tmLe00wzt1hI<`b96 zZHIrLr7_WQt>Ren2lkS;+;;+q1OnJ(MD+y06J?y_BLM+O1NJiSL!jhU=!3(1B^YQ3 zC-<0;_ESn?0sSuZ+QPuR2- zvMe&>JBO(%HAfmcI`B55cvM|P#OV|lWg!bA@5D7NEo}(FUCQJHC*u*L>b-U8*TWo(!r7Ga#MM~sKr7f zs$X%pK^4YqlIJgl^!qo|!xhLx-xFP~bJ=%9zJ;+vc|>@v<4Df8gV`*u>+;t2m5+l# zQg&OOS=KLb{qPiQIy{TlZqGu)lVLj7_=6!%xI8%hlbriHP3e`;u+r)ed3o zz;5C$`273PI?@EDH8Pou%LLU*I;H!eQWQH@9n0h=hlv(0OoHZonr}<-?!^j$V5-K! zSU74c0>to1&BasGlhX{63P7`Ie)`kz9QhkGI*^a?4Vtvg%?5_tA1Yj}z7+2WLj`er zYWBo}`}#D^q$Pod5dWA_fus$bqWh%%A>dI;mSVQ;-6pNjhjb-xFW%(gnk)0oclY9- z2cY4I?FR3Z+S1aSm23fYAr%dgP+6)1@ne~U^b+a6d!4Z#dz(z5*FBifpJJV!(b)T| zIj33Wfq;>Bj{GW7YPiocWakpX_}DZ{HjRixb&&lHm5k`@Laj7P6#*B<-%AyK<6=uF zj^PLm)uUirk&0QTuQyCEcyqOyh&Q3r2_~iM8Q$P)cx#ZJN90h!I$pcrQ=%-R7vg(j zg9_c4;)5To=%m&1ui20z-;MQYtTgTJHUJdgj1Bw)AG8mDXNkEiw@O&Dwn66Khwf+TxH^Bcr-s}{}Rp70!q^a=gNch808SK@gVCd{UbN@W&& ztoM6M_m;0|ILdDE<({@{e$7?rl_e1SVpv`*Y*I;hOS7st`xRWY@{Li7=S&j4QCwS` z*2jNij42th@*U^iON6i#2=Hy^i`#T0$)2Uv^uCIY)pjg9$xrVT&MzurSVddk znpg%y|4s-A(&<<*C};+9Gp(QIwot4y&jmBqtlz{!`rZ|RzqT=lLAX=LePk$Tf+KZ#UzIZe1 zH)c(AVS1=`jCqBdLdwRQ%LBQ)>`0WvQ0A?$s8uK}Z&BWz?Z**sFHT zYfzzFN0A1LV-5+(C_KMx_S0SLYv#0IZSoYKUS8yy)KX89O0#RdFPa|cH&q5O<-K)+ z&fn_pBJ=&w>@?-}69TZDoOiD4!+rJco8zSo6~JW@{b#%Lt)P`dGXD1vJwNK-EW(4) zZ$jp~2xe5iGJbGX%V9=;*u>ID%PRg`(z#+^5^dj#g}U~FGYPjSvc&^_Q9c`%ck@PM zxN04j?Y?5+hz%;1>10p!h|0RX3C$u$HZ(M7zGivwVC=-q%*={TzI_)XL0L|G1n_lZ zq46jq)Z42%UT;0XyfRkIqIBrFRk=*h zmA4x0K--t{qT@W+UMb-WeC>xie1l}7%RV$x|4=>E^|v;`dAD|%C<@JL@9^;oCCGM( z=^8OMwYhTC?(d}k%ri2Ealef{sFz0uv4Ex&E2+N>3!boKS78Vj11(g#uQ@nE z@mBDxzNmb}-`K-8YC(HZs>jECCaGHPXLDnAjiAZVqKI%CpF`Aj8-6O=f6Lm9?n8CA z%?OcEdXT!&Ox{S3VDaZ$D3$KK86_n~MU%>2=*tI_rxE2@H~Pe2`fAfZl&IMXUIs0^ zl8>~SZXy!j;3=|x4?CZyJAWn)0?Z%ZLd@rbSrU`cKrk`N?_<|zqwe1q>}%iJ-aK0E>;=n{a|#};@2)Gm z*#Xz^C&j+lHk*`|BdirxR3%yhHc6w+I4AgB_I*md1zDj2p-%;N#Ms@ zurvLU9sAngJUw-hXR*N-Cf*N12lsv21TxM$;?Rj7eNFjSV`-g?IG^GD+XZ-Hy1J}Q zKgl@=Say{eAKXLVNoc=zADcy^ws6~x4D3d|dLZIvCD5K#YvF32A9^6E6#`*soG7zb zY<4v@_2G0iP!=_AZlSR=LuY0r&M6TT)T&-k5H;-&o=VqRT4t<<`}GPh8{g-LyD zAWm6HbSfXP5u#HPdjZEkTi*Qq{HD)>Wj`ee$sAArT?SNpMYa3(_(|JagZ@K6Hkdd` z^hH^Z$0j9#x7mSKJwCv7139(%g3|9H>C>7Q0E({6-Ao)?@LKm0DY42g5!{^C{F1Z! zB&&bN1v%a49F2_<`=Kva*vg3909MA4$?yn}9?>ud?Hm!Cx&IP^?@7wTym+f~i!Nq+oMU`W$L0pcc@QEI%5 zXsfHM%39XX7^A^|(umSAyNGD_iTk>(2Pf0#v<~nZYdSfuk|M1!N4p-8ef-*z4kK^2 zwOS99u)v{+&&ogOJRR}P{yVn0RLm-U{%>*r%&X(PWC=RmQiMm8ab}X7eR$SUW;?5C zfG_;`rVZz%|W86~Nahf?7%C zTU;s~c>(?K;RBXAPJ4U%P6vB_Z!G2>gM`h<@}j33K_Rz{Pm@rtR!!y5Z=u?EV&2X@ zxpPXs*ID)C6?7scQ2T0)td+t>Zi$g1#VXWtC5-Lr$>yFX>MkR&7Mxf~Bv|bEdlfTIF|W>j zt3K?gE!~xPX|_2L*iQW-$~vPFmWZP`{xgoODU#$@5oKO|Q=E7BC8nq&LB@18>79*6 ztJTP>`PO=V5qk$^oOazty$XxaVv^iZr@6>UZ4c4U`k+UDiH?#rs4=aHWzEv&LDF%| z>nFnDHo$1~ElmyR`K8Sf7y$&j~Z@YJ{|&sxg9%$;2` zL2!t+X*|o!bnHv&4RS=L(|Hy%-ybS|WoKy(T2DF6AAj?23fG`7g}%ZcD=uYdjFcFM zg{eB^_$S{ag@r%)reWONYw%3ZxLBrV|J)QETH$4R359p6V4zEIF`;-Uu&$rd zahms5)%IQ7kn}Czsx%<~Zb!PVCDv0mi`$w(x$2(rp zKhpFA8`#I#+P>nS*EFd7+bai>4D;fX?G8_jU8N@#ib*1F7A}}@2-169&?jC5m8bW< zsFYytx3@|R8!dN!-+Ps>ZvLn-qRm=!bo=*{wm5z%-6x$o z@%26Rd*n34R|osB&yGVd270aA$Eba1>BeUOG&T{cWK_+zuGjCr%4eMN_{i!1!u#%M zb|e@`UmmWJ|FlhcA@KIW?s?H>n()47w#pNLw4&>#JPdkTmlpxbPINBUefd_B9jU6h zc!E8ta}~&2=)89_1~{}_8r`vYY*k0V6{oyI_!sn<48;z&N#3>nuUyYTQ_~#=wSN~L zoCK+U&|d|mo67McF7G%!KITWED&j2UY@hB)S-@fZ%FnA3=#o?u(o9 zvac1)e<)kZogjCg4X9n)Hcz*xy{1B*dQ*XUFwrH&) zQDX5dR$trCFVt+wvSyo6uT4&ioc)B*F+8hJovK&C|38CMf>xsBie;ujb=kT zQRPLOot!M_d}bf>f0L8sU63XFW0A96#EnmBs&qXRKYhpPNp_#n)MibQX#_r#A!BU8 z#UcfRXEpNVcC}TpVl|B6-5616V$Jc!TvBaLGz9M`i!tJBDBoR$kJCQv<*iqx>-8b3 zmYa~G$0~f+^)gx54{W6J6mISZ9}Ew7qnvMnweS5wXGveb;sTf+3S6uNlk{5nBsbHa zu6VkGbz8E>FT4b}ij42h$hYm+(yVISv5Cpp=Iz(@#*(`Y41*)+JP|ihx51TFK_I;4 zC}Z7ghTf_P*Lw~A%>kWHLGshU>#lfOl#ho>Rb`x(VHEs z_IV9vP-G>Tf?=nIWEti?JAQi$qK*vItXJctsMRt?gMZ|257zWdBANEVwzhaq=@8{`kW92ZHkyH1&D4*6pqLj2ZsN(re$Kya=@{!0EPWNB&o-bS zJl(HLb&4*pPu`9`?ppYv>txRH^}L;+NWUTSjM+e>mhU}?HSk}~VF=_L*?@%fKXVS% z9abbwE(vnM#m$MkjPvuOsPe3DUnZRq-+htg<;f*K;z1`LO76L-$pQQVKqLx`20#5b zlr3nS*=Rt>Kv{6Ds^barrpp$cn}^UH&b3j&*P-K2d0NjYwT*Tf9N<|vml>K;oPefb zCt)JHJjtfl(QFWqpAirv{Z8lUR+nYN@5yU8+C4pu3dC=Ct3pO_lWR?a>Cw z_T&kl6A>5;KDC)0*>YkM?iE?fPa(6TtrU^Z?hoX8k^$(-Q%(4W ztM3O(c1qInJ3sGz2}O`y9Sa!#M9hjq9CoN zqlht2Wi~8VwuC54eUOwGUS@B=mIsuSZlcS)-RnZagg?i|4)lm22Q?7e3chlRGPR2x z&tj%sJu$%jWYv!e`+~e*FYxhv@zGIuoT2LvF!U?My4X6~p5@P@$FGiCrR1ZTlIwK#+J!dYU68lNW^PK^EflRs zT=)K`u?&ymrHGWm09O2zN;%ov425c)C3Ag5z#(%LbaN_nnrim$iUtV_SGBhV9Dudk~+?Xi*l*KnT zHb&4gZYQv}zds8k%db%z+kWR>6`uP)eBxQA`^XYQAgfE*8w8IkDRX`2xpOK@62uS| zLy0+Xuh2-F>3nq<&A-(XNz^~JMq^hF>3X#Nqn4TS#{jfY^f2u0PImJ4Tl$AoBVBUug}sePiT~8gJH4k z+&nBoyAN|!wpAj$A(1*N@6bJWKh@|xqPW$;qWKSd;PTPAi0H&@r8~bYr62{86=?VR zL|(xDt1iZ=FC7$m+;ulLv@%_Rp=gCda%ak5v0Wzer`Qu)mHT(WNWAW)jNYIm&0nm& zBgSj#WZ^95p&0R}I_y`_23MNSPW5^>UX|}awDC&37;2P*NAbncjlN6K^+)HP?@TT& z<2be&z<^f+bd6p&9H$4}jH0{=KA>JoFjj*849cL~|DkOPi#GiYiE$(K{eITSBklcH zM|!&gWzO!Vtsj$EZcea_PN3vvclr)U4ZS`+I2G#ZNmU!*Hll+;a<1c^Yo$aU#d3dv zS~x70K+i-B`6OH3n5r`l9TNG?3DU_yeDJ7p+0!|63>GTB4~ls|JHDQF%k z?zyI`Uv`J}&#Xv9rNA|BEDiWsfc=i^D!<5cT4=$ciC(R}-ZhHNAdljS4SBvk3Gym6 zBH5Q3SZJ(&OTCJy<;Ba=bz_6vASa(rXH9X@^2l2#LCcsu=5yJyHxDv}h55YJ&Eabl zDL%JlYH#p8SWCAh9g8!z;Q`+Q3c;qOpiOP5bZ_MMyphQlXr|MZPt~Xm(G+!f>*|fD z5R%#S=g~uX=O~j-n~|h$#k_2jLuRryMUUcXMxAv3V`*VqTQK^V1nfX@$<-SMLn=2u zYxSP9@FZs% zERHtCK0J%+?u&e3gfm|k6h@Z(pO=X+{j?UUXeYS(!ZCO~-97mv@zYKtTRM;_RPZI_H~=By;rf95BeDj(Q_yG%|Zv@*fM$@CcXkpw&+qJobWHw0qBMt(wed0 zXgOWaJiTh0Ne@hkE8+nvru#7$-(`n{W|Gye3cp0AOahQAgv9-#%A!En95D#hvL|r@ zpFx$Ql&iW55B$7HC`F>CbYX{#ph zc>eQ{(FlURjmDNk;GV?B7C@v}nG`|nc&VB%_d{Xsby8A;%}!({W;@Dczu zO4`|Ri07z9Mn&C!^5l+?%gQz23g{rp7arFM>BJ^Yo?Bb9iU4 z-EyyYM%l#)*aPJC%>&2a;9zBQea1CT9odmZV}f~E`tXe!$AZ4xy6OicN|mbsDp{?B zt%yoqp~n?y7%4?}H>_(~XCV1px7%8X^6=RHX%uVW+wh#~>q}Af=F3c-J$p-7z@q9I z%qIFO?k7e*0{GRT@$vV@FS?kYT(s9E0!vs~J){8vmEaE_K77;I`1HaFvUvjVbPjao z&dbWyepyruGxpo z871;h~HxDht^(#JWc9psR2MnmF zTfU!BR!}H9Z2tADS1dAefb8PpOd7dgHDN%z$?*{Y;CW5^W8zs&0~h*j`f$!RC-%HO z-Z;<7wysJ9F@~A2Cn3#D6}qoo)1sG`mef2=RJ)*v2#wA7SLJesq+G-HDem|G_f&Q@ zkZD)@4uT-P)Gu{EmwdW~a#!Jco&DS8C*$1)r!(;{-JPhA@^OGh0hAh`)%AD(>WYd{ zxSaNs{G~=x)e4y4S1ivF8RBCncI+r%PW=-_z4~2}mJ_`Q=jP__iH(U=HwqPlD)2z1Qab>IfrAa>EThq8x6f*V3eNAXM4UGF=%Znh>cmGVq4s=?~Xua{Y%_q?a=k7|| z%U$i?wGPvXMg2cua_yYN) ze!YMR`i{asWT?Dh-DI$jnY1e)TQH#Gp*gq3efT#TcuQ^u>?=FJ%bj{bvNRZ!3tUr& zA{0=d&rUN3?${}nk4tg)$xMzj0#x3KyYhkUMEM@qx(48LY5%Ux0B9z2 zS&>YAbwPB#qox-7z*Y6V(BgBT%lt~{+c1_y5C5}$0Wkde3DAw*6uCB30$x!)!JhkgQo8YZE=-2PUZA&-WrdfaIZP-)kA#`&2*i8(Fj$31?5fULH= zBwP4Tfgu2YmYH0f(AAFe?Jx6Qq3JHWsWPcJ6I2;yXnsu*F8VFTT!a`i5G^i+EVoUb zD<;a^aVI%;&2>3lS1mOo9=s=t6H`5QDy~fmfDLJ=*n5vC;7Tv5e8oV_x0>1=ajYxQ zy!%0>)4}NY?&4w{=cSL0^LO~JFUKT0~e&; z0{WfTd^O9CjJgnNinZE355_Dn66X*|Po);UxTNkTXo$#@3itrS&eIvix<@4nw4LK;8XQ9he~>rGhMx75z@A6r?Zu z>>DHY%C8jdzq_|arukHmk5noofvU{;!q-YH)>rHb-OJkX-DxKkH6lqc?s zncZEAvAV@prti1abB*E;Tm|T&fq{X9to{gDwrLAXOVAzL;<18YKb{9n0@^($OTKdX|LYs?A4KEW1Z_Fkf5`RuUytvlN4V^%weG) zt#0^!G1Yc7{@$vOq-Bh2h(w$NY~_Trb?haP16a&@4J?3O#nR27N*6XEpl-Vfi+i|T zQvU@E#Jq<4AKfR?Pvwv9qg_reQ+px;i!hzJRVEbS(%Kkj>Ws?gJGu}*zcB4)W2<}K z9lR%u5xp<&Zx)n=*9zRTQe;JYl#ohGj{mSb}xf+k^ zKLaI8Y}ZVj?sDh2q5GxQ^kMzCoEBwxlB_K4H-Y*hj>!x6M(K?Z$lM-}+EMAzgQz+YiO5HEg-=*hD8BuqQGKzcWRnmown@c%nBtoD?J{bTj|$U zY)|85Y5T~4tC8eSzTQs(qTpx$NjmjC2oGQf#b55?lBCO7hUhW7O!Jalh(wP&iaeZe za%k5Aegy5Bxf2b5XQa>j6v~(h1GR{C$9dlZ+*T55(<0d)i}v*BwsIU5Q*^$%lprXG z57NkDDR`!98p=XX#CkA%d-qk3w?A6B(tx2+cNu`(NSf8o8e~z3anB(dOo))g(u?*3 z#3Gk7!?*)du*2td&r1vF1EDrHm)fk46)jFL`7{$CG1~{MKstL(#%CaHS>LK)rCbx+ zU2&3#qOfw=T9qNaB7`7pnm<{VIdztV66$ zC`#C3^14q%A^ZI81mPfQRY(JI%SL#5TWQL>hf@2OwuVVckLf%)>O(PN*{kX3rug9HFSZ2!YaZpWt4|&M#b~^ z!f$v@i?2WDe4_iu?9nuxcAagjZWJ^V!$3~{bSOmTpyZx9p+>zqdmGlGL-$`Fi#2%> zK6z5N$&kZR&up&4TQQs+$hQ4hUn)ri6Wa+wH2M9E`s)J-6Ytm3U}q z6I7CoeX+}dctz}v&ml(wyD{2c--q52%R3 zES2|OmE&5_<>U-W*1wl`N&L|EVX=!=QhTLcLG){Vdxz+p*k$6L40B(yqRN&(M*%YC zP>C-dcQFGcWP^ra>hMFd>jwIIB(F_1=cmsNgXj`Wi>T#gLY%)Z#`!d6BlMn@BISXBqf0@jgs9v6PEPI1rN<8O$qrw(5p zNZO8mx@%HW^87T5pfZajOWRkTeIY_V7m+)w>hY1ND| z0+fzMXdb(-DPyLuRMt#{r#IU1{0rFU?bQdQ-gCvsmKS#~FFN*MZpSwd?@DPriz`W} z(Hr=Z_d{|_*nE>!P^+_1Vpwax$&levlbT~)5-zvW;wgglMKo+NNiFjW(7Ea$R3O$6W`gU&VuiBq*dX6Y=@4T`% zFMQ+ML->$(hrytdO8Cz6%=S~5>|Yvq7o)OlxGq8s-Q@(IWVq3X9UQ^ppNQkduoE3P z$)mXB;xx}u=}BP?cp+gnYINk}n6(h3e>jbBKLr^XMq%L=%{6&t<-nO4la=1@H%q|N zv@bknF`sxJ@rdVWO`G175pA-%fiu0_Ivo8R z=m+oZ?Y?v}qhdPzj;xy2I5gJd*=QxIF6~XIadNEoCmUjszsq%tJ~~FCeZ7J2$K8Xi zxvpG>2=9o`xlI0vp9`55IcmEip&L1qt@RI!v*+@GMFjA~kwQ|xT-DVhYq^=30}npA zeEs2pTFqE}!mwlyluq^40V>}32_S5SV^qOdG8QuI%_p3x&Ar_feC7At`Cy-@4$@+3 z>z{TQYJ*?k$w+R<>Z^|=*2n+Nn$z@FatpVMp8!pw1Uw%;OFp8n)D1D@ky#RVn*GcT z>+R&RBT&o_lh+Y*pEka9xm={Bb5;M3wDdD7T!IogOQ|b5abfu0F%>m%s^0i1rD1Jy zBFGpCI-&WYNcr8u!q4r!n+47nu8dLpzh9@zbo87z)OcZdv>)ZE!+N6`TU@+8u-l97 zmtR+0O~)?##@W|d0C-vNOc~}s_%nf`f-?%gO4~L4c$%#E`o)}fhBUNu^<~7VDJWiT zYpe<1&>N)G>fo`$^zu@v*gTQSw%pgSdhO-t_i#a*a_3b&)Xpfj$Fp3FW_j7(rBv~f z@knF+?e5Tj529c9corY5{Z3-10XT3D1i6iMe#O;x%ZV4q&Be+H7}eZYy-d{?RN09~ zikc4MndD2hXM^b6?u?1Bva%v(HpI_%iP*;N0jX?3=ItrN&BCrx)ElvxKXoULK&2MLb(T$Sel4^3RTaO?qx1yFdSsT-wjV33q*Zy>{x&NB6Y zlanA3vc~GM^wrYJCXC=gJ)^45+B~=*x8gnkztlM$*z-Elpb^k0>*R@O$M=B4t+X9i z^>Gb%!o&R_Y>*xewq#A%N;|$9x0Y>8?-Ln9bQB5!Z=Ck&)$Ts-nx}&fK5M`*-UX_1 zoP@UwZVsA3d@i=ypRyYkZ2jO0H<1mSPQct&n%!hI@~gSIfmB80y5HG;(k#3-kX-#U zits65L{Cr){Isq+u4IvQlrbI?IAA-i+m_ie-{l*ssfn}5%hHEi?D4byrw2m_oj<*p zB*G#PMmoPr${`kjxZyl(56^iBsIP!vgy@%XI-WxoJ%?{-{2o3GmN(FK{6IHXa~SzU z=5koy4ayxf4O?4VCr;XW(zuzJewkX#a~PC;_|aPf+!L#+t=$sGnu{i+e*183bw^tSf!^nmzVB4w6gjVioZX8+LVWM|dl2+R-A&dyxA`BSDd6m#fco5rT(=H>=16o?~;<8dFd^8iY9h@Yh-+Epv% zOt_sqf+O*w9+KeoZ^Wv<)Lz(oRo_hU3^>+QA9KLC{9N&MZ{1)a$0ZKESUi+N(;OL& zFyJ_+U$6BOBxwMg4HCxq+?#&T5EQTH8tQOBIBk|zfjB8J8|!kT-)CU(hwqGMYOv`0 zMjGOf)6jGgIg_j}M6h!YQj;Pv-0M?WZ^#dB3w08<)gW`PKd;L-S)~Y#0u5YyR>sa* zq;Rgn_Q9O~z5zU)RBmVpx;2rUDC+Nlckx|lKR6b0e5~{1=9#W)h^q}0N6q96gsyrE z{Hfl#rEFQ?e;29~!ujPp1u&Q_nObceGBv+?P5-k_my*v~`r(k~BDmd~hED@l^rvUz zV(^XFowx7O;F{iIp^IaO>$v=n8n zg*uJX{(xEq&!GZr_@(PjjYCmXOt&t@jTA zzz4!q1WZL3LvjCKb6*)2_1CV8qF})w2q-OrNFx%`-5@0(jnXaBLrEhc4GNNyLpPEl zQX*1Acf-&z3^j1p=>Pw|``!E9=UnGH=fn2P2+VJ-^;`Ko>$&gy8R2{h4(tPg<`o&5 zkXKv?e_7Ffnn>?{K@ju?AfW;!=qk7?U_$uRFK8dWEn$SgngjOESdnZ;#{gE0;Z$4} zgUjd_*Hb}@s9;=ggbw!Nwk<^|ylhC|^2i#T(+5gd3Dul4^VsY2U{-CkI;^;2aXF0O zjr8ue4DWkn&!(Si6cW$z9yJ9GpRznvTBf5W#qS@`tCO!66>w+;| zH=8;a{8spjaE|#^MUD7N`y@SAW5)M$Gu&ns3ORpu3^|q}{>*?} zwKoS|<1D-I2Tjk`rom4dV>|CDt7vtd&pbrRY01blhqNSHwf<3)_pX>`?0KxAm0K+0 zexg%DX`5nQo+ymdq~pZ1~RNrqcr zH%sKX%2WHpd*`$Mz*fZ2dq_X?ozo@V8EA<_$aR ztdi^`22T^%W_yI&s6C_ZxYFzot;5yYCdZ^X4cSa1(z4Zemi$g6JzAv8BYcF>ATlx`As0WP*oclKWAiI!+_@ zF9=@T*mJMw?JtMKw3cqC>WQx8Ny(ABSLDbRPs~x5>fv4`o0_v{{Nr^Tea`DWXq~L> z+)(E-B6LWzCq6!x47+@t(fx~qhJIJ~O3P~_h{$EJ$s8%+5Q~KIEJrT8s2@62UGEyS zujw4NNN6*xo!y~$44{;ffJ+pHS}PeB2pb{$Yj}87m7kRhF-kb#v zUm-+qQC7Yex{a#au4)ty2>Hwn3csmv?)AufQ-kcufr$M=&$m7pBw_fuXxhxfzAtMa z3Nl?N_rn=qW53uc*UG^9FYM!tB-+vWsF7i7##q@F)DeV_YjdhLV-R5?9^ifk!N zXIZ`HWM^?@b%xb^;ap}y*#ML#Zy@}Kx z%bkeRykr^duQ-s>dlIOM#2fmE8B4AOM8oR0#lwU@7^Ospq+g6QsX!0A(`Y!ohuK_+ z(4nobAgZTe=lQp;MJnZLtm(ZV2sJ)LXz{E>M@L8gl-xRXRyouAT=)z6fLTzUIdjswNzgM~W^HDQiXg8{%|N z*-W!g6dluip>bH9L#^snE=XSib9w7;0+O@Txc-ISBPS43gytA{$(orxth65aC1)eD z*ZJV}+5o+`+h^IBD}dVR%m^nUB1$4)P_*(o2DTz(HJ&S`sb;u76xOhR4HK;M!t}*1|_h z5wZxvpp@3?Xd&$%a4@hNg07v#*X1W6P84}UA! zZ+!=m8zYcUYGp=@OauG4mvCNi31uX21W%wRehpCRVK_sL zHSc%Llro%X?u(~hgVy!f5g$peK9E&^wCNuLAV#Fhk`A6!lf#|1y4F9{CW-=Ky`6;|?oKOW`zwSoPzkly7Ld9dw2UD(r_F@1w>v6O|6%ewn>ky7JVh!{a=jVHnF zkg+RE)QV>2Hf9ZY<#JO6g*v+}hW1n$j=$0+)VT##Dg%aOv^P&6F7Q5y%JUElYA4M) zCcu)ye~w`W<CI|TO9o(q78Cj8Pp)MR5Kb5J zSI+teo)EfOiqub?IT>);A6h#}-;*vjwrq;dKi94YX8}L6eth3=LXaGijC^sHdF_Gw zUh1qoTx9ny6^F$N zsfFU-&Uc z-v*8bt92}`wr>z)u!t*$6y$RBaEJmsQL80?-xByV7PJna=usuW>AOS6Q zd-yS{&fHyET5{TmRTl0_*2^42_$~HSaj&|aG`iWA;e-k5hP_PH6b=*y0 z9HS^cuCDoh(HGe522mT<(a#62U%3${ugPkKYKcV=u2BpMcv9RU|KaBN zb!Uu9li#D?{#=V+w-Qp9>*RGyJLMk&0Ev%B{|Z9YxeMM#R+ENyPgWkCHvX z8+e+#&o)4#$c7`wrU(KH65v>xsk=m9f?E;ex~-h`4ePq1-bawJeh z(c_xl94MKgdKtx40Za=c`Y z%w`S?JGz}D79m`_sq-{NCW!K*SU1B1yfKPywx&-f{=UW2)|CCiqqPH4g5u1XO~bc1 z?1(0|PL>355|?Re&Ks#Oi19j!UM>5{scpMdu8PvelSqs$mbtt%`jXrO5jz8r_K?b3 zQ?4_8E7fkD%tpWJdXl*V$2~b}>fTOkp7%~Y;3`{Sz8s@WUFVyP4b(xK*!~zoqRg48 zdTdfupIocSRChT(OfY1N{WdSr=T4Kk+8;4ynFU5@N-p9V6$-tqO z6l^6ZON`Ik92sP{3)4)7JQE<6UU^@dh1YQ1VOBgR&?*){#&*)hC%Tb;Od$&~xH+*L zL4zc&7s>kUxYzT8)Ykwu3f(j&RhKf$2LQZP(N_}1MS(w#smtP9X)#LUXDpUdwHiAq@J;4GEDkSGu}UiZ>1?-u(j*aKX!J+Uk~ zt5~8{gkX^rxUU9~Q24w*fb?GD=kWb?PsS0^{pLY2;~?f5T%ncES*bChcfKqFO+RrE2$j3RwBloXGz-#BP%(0-JOEoZ#yJ^DSsOU1Qsd%7k0wunT8 zaL7~RI_Q}9mpfg#CEqfZWR(Q_EMSeL zYpVJjJ`_-WrilnEfZrEJUsB827@BDx{MtCT$2QG!rQbJ;PcczF-R+U?eU>zCViSFC zkt_XA!C@jQ&BRzfL*HT-HsrnbwH;i6lCxdt)x-*rvy>lR$=5kr<5IYnx|4G0C)sK5 zqd!ANCe_%a8Pvb7J>KJMa&c>x_RG%fjfPU!I4gYdcldN$M!%Y{=|AJDyj10}49{Wz zBKE1@4}wFxm|(uw&`*lEXYa3PJR5w3N9(oY(x%VP5S83nl3-Oo-E0wp2?MN>((Y6R z$Wqh&miYj#LwXwvR<+S_tNaF9 z(feAaYURAYZ-Ac0RnzVF70t3lzT3Sadtxy`$1Xnw`KhD)Zpg0R&*!DP8k{vB6-QA- z^8?owQ&ZKu6LNRLE3Cu)bq5~<$KCH%h8RnI^3=Z%{9{lN13|{i`mE5b#Sdz+$M-{U z`ePtCmlru}%PsBuR|)|d<6zj_M=~CmEkE^&R9v_PW2}9SMc2S{H z=$;rk2vCYDWlsNLA=wrbG3<(F);JV~?4LxV0`)mTK*sGxW0qCFp5|V;p>m<=Hm*ev zF8ZE!$>)5Y=Y7rGf<|gnl1E0-8FviuePVxI%H3kvHOnH7Do@C2pznW@HJMHFPl=S1 zsp}hWyONV{8Nu71q`PjoC!_5o)d;l!9`l8Ov}!;=Zk>6^xzvVrD|1P zWN4_LK_gVG<2|M2%^NrTMn_+GzliPBoZ|plmEBe|+AlQXkMOHPPR`!k6Hi!Q#g2-} zE_<**mJ5)){tt5dXN5t?6olUuK%0h*o>r#mYbjfqvm0JBYOhgc%`~MxAT{yV=3 z*7%=9CFy9o>p9O-tS(q031`Gq!tyQ_Ntcfl@L@B%=;%){!PR~8dNNOkJ+tWz4NP;? zlHEu`aT|ZiZ+RV1DN&171`d0vtVh9kmMU^M#HjhNuv|SpBWUhO6qa?d0DPr)D7sv# zU8<|ZoVW6HOB(4hdZXKtqAH){&iHn%YHT7G}imD~vb(3KP&qn;;;oXtUA z@63t;#jmQFmlBnEC0v~x4O<*tyUZWzXp(AANihiA1K3VyVJwCe2b%NJJ<8BNJbek0It?UP|=0kN`TZPCCbxr zaz2?dr=6i>+x-%f&*udG%-zE zKGSPWCJ-C78Wm|azw@a_d9Ek)0e{q^>vE0x9|U6K8#ZQcTD^J?ke0;r%EEcXS>hGu|I_;Jw_3Y2q46>n;x*RgrC!TO%bwZea+)Gg|{Sb_c)Xr6U~@W zqeGuzU5pEm9Ht7b0&z2^?$J`58|zF9i=G@;)d+tHM6?94_UVl88mn-Wi+HhZMUvy^ z@8*7LH&Sn+R0#2<@{k^c|Ip7x35=DwH>W7e2aaeZs!vsz`Q*gv<0;YolGnQWf`z1> zprokCho~ATp?SJ1TPVVrk0~=X5jAaPyu)(3w~X4Qpc=Hg7d1eDjA_FV$T|Ta$pkK_gREQ1#I=c>ScZAJ{!Xw3ZQ4`_D*l`T&9CMvV7aAhCC~&w}|@gBuR0- zhV}XBExnB3Z}QHpBOVjD$r6A+Rrm?0k0gYyfBSY4_Qd9R3y3Z{-<=YScn76#mI%n} zWs9M4%f|=adCQOof^GNCYE%*uaL}`2#V`V3n%R4}V*t}-Z`{?B!)rXy`u4%8|C$w< z$d%jS&8O*P95b~y=vz-Y#V-1}blM5?JCcRnxENB~cL3QseKLeyEmQk|TtMMyjLJEM z{vZcZ=MMry|1JWv&jo-|VB(ZW3AwYU91|7DH6PwxKCrw5E^oARNeAUJ00V=jMrTan zC1{SJD9rP@r(nvTyY^t8gXwJtF=D-!SY%f)U8EbUH)( z?hRET18Q@CXODWunneUmT-OXyLqq5MDzMyz{VCGXE)i%f+aW}o8+MWWwY$`JM0=vK zRqmW!-ajTbj5$;FzIJ(fzXh1LTz1L=#O=uhzLGgG<(ux^xKnKyPYn1u(24@3s0p%s z`Ph_{DWgK>e!JHAsn~6c8-}4LF;@3*N=)o?cX?HQTHyJQU5kAsQlq8pmL63~N-66Z z@%ZrW9mtWEzQL{lh&}H}5Kt3Y2(K~&U}r(eW#k~qbokR*Jn9Bup$OeofPG+WYz?i% zPpT^QH)Smpwp#2F-wA?1{r>iBf<}O6)4vzHD4w^vYT^Asq2KN^V|_hfOEuj=-dx}7 zY#J>n7UcZy1%NLN#Art1LkZekvDD&oMHvNvZIBeTPp5nmvNRS+CAuGR+u=$k1WF99 zKr~ri`3WCg%>#j;NYSTphhpXR{6HU#te{5!=1Nbeg#DY^S^iZ)W+S`N1cm0y)VF*1{4I~Wxp1C+K)KtXNKOj7DYp}6;%8TOEjKyT=f z4ETzI=$|^tDeY8S!?@AGWMR=%O|;*HpT44MSInJwh+YUd-^fe zSG=+%v~}a>+=f2)0YTBVf7Hu}VAaGES@NhZI+(g%sIXB2R9}7q1)OJei_2r(ZTHTi z9)hui2iO$)!m@8}tUVpFPV}?+X5KN84yh(k%W+os`Z$bGDzK!U=aWA&D$BS94UYU= zc7!26h39<$)TojYQ_CL!B%6<)7XYco!3aqxsWvn8OHv+0L_j%0m53!8!lkN5?Nia< zGCTw$dNxl8UNj=AJ3mxn^oRLaoQh({F6XL$>VtJy#{3{^6SvX&J>_CB4OKeO=6mCE zHKN5N`f5K_nHIP+9MN3Q&|5i0Lg_tAxiPl0{ks#t8~1QnMpSVdqZp55dFP1$^RfiQ zCgqlng+9-Un%xq~QUx1X)vKnIOW6yC=4(%}4FZy6Srk@S`*4L?KY0Z&_e|h_Pa0s~ zl^}pv7C~YH?+|(zj$iyHMLo&9EsXw6mrCEZ9;q3|)x8POg*yp(H3DV<+muANyAujL zRu{#|j=%7MTDTvK+(oQ=#Uh^G6u$K3#(sP}j#rJZ5lz0d z^pBgdAL>tsZ%>C?g!lp56hR^xTj5zxGfqbR{4%B=@l<^>?QUA;rL)pW3Yx^H77oYC z1r<)mYItIF9dy3BF_DD^H+<8S?znY%aOt`CwSgObxXCiW8wdE+F++~7?i`!%Qsmhd z5s+fVDQV-)qg7=~;K@vEJR^v$oBXSqbYNS-@T<=3D+#9JaO^Kf0daM7-%=;Vb#>H#L2gsY zas|@)ZguoLhYubEcNw>M;<6`NvH}SC<5b~GZT=qWJ`cpSV8R%Q@71V)?PL^ppgkR!Efo6%WrcbJIzhD&7ZKABk z;vHnG_O{ppqOW!P%j9*b%I+Ww7l#!Ok(1^5Uzqyx{yYBC{kLM6&>|U;84jW>H~MN%PzL6yB!ECtm|giS!oK_Gv$J_333=8eUA|7YCIhzr%(&gi!wZW@h zig;12rAtqy&4lk92tN0z$FYBMct7=Mw(Qd&mv_v*JkTVZ4nMm0a&Dt={>+OT=;;XV zirJ^@s8UlAkh$MFsxz-wk#Ma`6_6^OCa>|U67uQrr@e6f|uSH*MCjT z=mJIHTQB@VTNkh8Hj(9qV4QOd?*ngHxvE?KTIF1y2JcN5xGfh$pf`s?PuTS9R9f`) z^lY}7A3aL<0z!5!ch|z})9~={vc3N1C&i`w#ZTHWp3JDqJl~-Qja=jh@;Gj;*4K8~ z%bB)YfH}XmD0#)(+23&b`pc^m1yV|IrbNg@qMfb^- zDvXsz2YO`Cd6QBtQDBC$eA(+-ey*}WL~Bm5^e-yBTWN~Min4i(VhfF0oPN@uuDI0 z7~;Y|L7?P7;H~`I-vSNmkc+Xs`QJpNy8A`PEG>s>JEO*tyAKm9CE+6gr26qGQH$pSlL*T! zSUc{-a+g~(UO&1wors=3MP8Yzwl6D>_+jw_x9j);AyGXr^ejR2^$DRUTxVvb-K%@+ z%E|Gk@{VvEQjSTd!+S9SzH1DLtrInGDAz}>7(>%>w- zg9SHKZRIL^0F2QJ=Jrx4-rxTQ0y~7}=c6CBEgxDKDJiM-q%#u)AGBslziu(T;?Saf z7ZpeocHiWV9)Zbq2}!AUEwb0>=%TVDhJU&5iEP@|*)yySt|be53Cu(~hrT}5d$n|a zy69@3=3(b5jxP7>`#7Jb`N;zEa!bqiyAxMbr@DFW#nF+YW%-*HY?UMHE;cj~P{ zRftvY*j9B8E7BhIqNPUE%7iMOnO{!I#B-$5NSffgWHbYnN` z^!KJO7^mchRjWa_zNvyt zF}@NHDJ3QKxL`mwcF0;@UOp3K_~BDT#RseLF)vA0&$R{@B$4e0tI`o7mS7EfDT(6H z;l3j2DqH_xcY z!F42@xC94H`$9h(k?JMb@X2y%$yh@9uHEjTG1RT(GnwG{YsCl;1}D|e=}uv%rU$RM z8OGt23=)Isyc@gARAC@-Ry^qAFaS10(~Y+H+kGy@pT1r7`C zYhT$5<~qlbrl#+_0#ar3e5|c2*l0c~v+pA=v46m)Gt?k0NcKLvt255MzCEC<8OMAg zYp{-@hndZxq5SXh1GK``kr$pBT7|lHI{s@+ZVftDQ+?{t0UMcpL&t|imE#Olnk~jd zTg9^KltZ)VG~tYnx_S}lcQj!-4@ux~aWhP4lDb6soK{PQ`-8kCB?A483r;OOougG3 zeR;gPc?iwfXA5rF*X4QgnTIDy@KMeBuE9D!Mo;FZAF$4NX1|~DF?T}*>22Z(UWDJ! zq;z)ex%+O|s4hxb{W7~Sxi?v1Ws*B8KOqJU+TgfFc2;W>Of|#ieTt)DFmsyoz2#?P zNzibykBRdhbK4hdj-hKvDh@oPqXC5Ymw!PFI|YrJD^ARCwI({`fZ4~Bwy3gTc&a#e zsnc54z)>}W-+Q|-cJ93VG0a8oy_L`l#1_J1Dqk%5ApSTpZID6l*KRc50qZI1OZ_(n zTIY zT`otq>z&5ZBDK9;0*A;-@uBfSc0IG_!*ZO&JLme5rrO6Shi!s+sI7v9mD6xJ5$y51 zHDq;%n0O=ZeBeo45RWrbJp%~t-H6R2NhdP6MaPMh&YA5L^kA6mw&HWFW>F0+T;I6< zMZ5$%yF%xgM?n*-0(W7zhHb?8`IX)b$&jidc9F zKASky2338#KV7TorH@W2ASEc^&V%=`2a!B>Uu)fBfAz|Pf)4IMV~}T9E?j9dkfz1+ zsF*aJ!A&U2)7vew4izhdWS3%?RqjnLnm*xC9^x`RS4tC7S{}wVIGgASzSjl+l)r$4 zF~6Z7i)<(sW3L<d#CMl&WQz@jA?BBz!RbDqB_}!tT*zuBV9^l-?~AqX!4(`W~WZ< zCmCFRvWGxVQ7^4(IFjk0y`0B*+-WV1TTV~%E9aOy69cGT!=q|)gyL`}>$8edVJ%x0 z(~S}$w^$ltlsp8Wn|CxW#zmg%79GE7+ab+wi8m}6UWjA4^7SY{5^XE7+LB&#u@E3= z%<=Ni`0(FEvKGlt9eJ)UeDd*xqaz(bYoIii*Q;S?+ajv2Hr|gA2y~!*j|#-|FzzJJ zCfMpmxwJK>PH3}+vodR_PN3AXSNG&;d!$Go1J+t$t~E!hQQK{ei)~^UB8d63a@5ur zCGK;E5;X2lc!y%mT*YPQ{)s0Cqm@g2Y^ZKgJ*1K?qRw1=Fx%0U?p&bf_k0yK&p0=v z4z_EkbvV9Gx#OD}^TRi*u1s3F)q$#hi|g1F+S?JPVdvo6^eu9$UtN0Iu&6cf=P5q! z8FPF7cn8&Ur3n#rTctJ99d&L0_rnsnNdJuYQ|^w>qeS@8Z-|dh-=I}E4yc~Y+*GPR z?oMEsV!zZbJT?NWn6RfR(TcBnr(az27+;ze?t#gK3gybno$Mr(yFjN(My8rt(?nOL zU7Rn~&+!#Tvle(w>}8G&rG7qrL0ggRC&LVXS7Xr6J18AA{KL?&(0(tD+{Qnicx$Rq zRs-(`1KFNvNvHeXi8<#It;T+z;Q?OR)X5}8Q}x`b@uSitmY<49Y4Ku zMM+qD%P#_i&@4W3Z+&qqKEuz=lhW~|Z{G$&Ctm!kgo#b1Ld4+C`8B~krt{5Y5?CUt z>9dQLcXpD$Vxa8vb;wM?+W>8?uZfyo>v&8%d*yu^XD3ipF=M|v_bBuz%F69RNJ!>< z71{hAe{XM1>eNL@DF1PpVN)jsx03IUm&l&n{V0|%;_O-o`i`!64|O4K{3OsXUnvnI z+xSIt7ZbS%4O?uj@ZT-6<7_^!*qcK1r?5-0Mz3*w4D*=?-XE&C@RIU!drdy*Oh~7- zLq1%h$?el9V^|e=3$md?lCzG+@r%eX^Z1g&CiB}&y9Ybxmn7T zd@Qs|b9?F}mFm7{f$Cf7KB(msLiNHTxR+;de^h7JezrW?t>;0M8tyMg1C}}`ocd;E ze!haZxhwU?5-Gk~>!B!N_kD1{}SCOB_QxTnb zm4vUcdqpU9q|66aM`=8fbm+I)bt|dQ@yLf^3HD8Up898!)}@=0jaJ8p))wMcy+Z>+C3yloLV4}Y zr>7sH*ljliv=I<;0FMA*yuxY$gSEKEu9FW9WW7`XPOz5>{An zu=lYllC6(7fu~S6J4tvZv$bN53?uZ)2Z6n0gv=z_32lU56~^I!-j* zO{A~U_Xo%A{@xxOBuRp&i}^bxbG-Cpdc={;ZeCYn*3T5(A>qqpwynX?IV^D?LN0qpwY zQJ;k#u{Ugq;~pt@U$5Tz=#?Qv20i(VQc>ue|{d1Zy&>9L!_SQlBy_ zr*4LBk||E880zU2;@rBM4kV9>hMw^)-O+gQVs(qE&B<`kdsjBk-bT}^eW0&0nYZR) zQ#E7MtqE*7WxnAT1!;Dt<4sje=BIDGhP=PQ$c@FD>cL6P05o;NCX zN2jwjA8ntn-j0v=F%)kRDNngrt~w!lYq`GF$8fnE+Iwc(i+GrZ(}{Aoo#FRVqfu&V z{&csqEBMo0+3rPTMZQ>8D4^hO%YFG`@N9B)A#WK-+Vl- zU7$v`*Iu*T*B>5FoIRg7#9|klrrc??_$B8zXre)Locb&_mS82T#qy1D*(X8CYH+~g zr^(hPJHG1IWe4(ZIn(~@WdDz+S^gA_m)L`<2{d7Gy!X!vqA&U$OCMefpz6ZlogXiVrpzL= zR;JzMoa$H9xc7YJD61W*(N+AYGPd!3^�-mo4VOSC{!C%(BtzOx$lK-OIKa$yl#$ z&e!v-8~Mz!+P5_TMHfL=NyYriTgalKBK{W&)>iy{*==7!*%Xvr+A)j$;iBkep0Or= ztPjIR?p~%p;Z$U-(Zgenj5*xb=oXBeRc1Jtd4Fv&Sw=v6z^j=89ljOxDQaZyq%-=# z+~zM&6cERkI(Tme_CgV&0O+Wh2hF8Cu~BI}S`CBaN^QfUUg%bURpXISk9z7HuGZ zhIY76n_n-IQb034Ap!Bwu)F%|O_JJrna95;;J;KJe@Jx;rts#n)qLh#ru=KH=60ZZ z9ylp6@ft(D{MYw3Q z>q=t&y*L{I9CS$8jZ)C9)WBPf>RNnS+V&O+5h4)tbe;IWw7saQOiBM#(PHytNFcdr z#7HL?+D!8w%jfYta0Y+vrY_N<_N<#gzmdO<5E2DtoN@Ytm$&(h^Rj!ghRmt7c|H3L zN`X--4~3OMRlVDNt6J5+G=eOEmAJ|l!5bNvGdC*vpZ}(0eNz{%zI~^jH}?*(%R#ra zvp)d?f_bs(v0{w-at&G9b0~UQ<#$=O)z(oe+n2Q9-l{+*fJKJI zeQg2^saZYFbtKilyvP4zafAHum8GTp$Hwh>V*WU5JTJdp0eFttt>OEzUIj4Na||2M z=G}j;vE}=K^$lWD(t=CaINt*{)t~W65tESAVWxrW`f$->uWQJi2mcsK(8S*l^rQ%A z1+UA+KFr6)#b0%4xk|cf3*fU`TdImE{V#8_r+L6tO00k@Ht6RuDp@ShSD>pgbKW*D z?Wsd1{v=47aMOOG*5UK?!$GUMS9RM!GUlKfFuH?koN@onQ`G!UdH9n+XL!!`Up7nE z_V9bq2_T&VU+w>lj7xF+#V2DsUdcGwapm8Y^7M5&{$x*2&zx-ph}cblJPl<1PZHLe zK1)XoOqdimo~?0RM}a%O8>q10|2$q`#-lbTv~V}7tE+dajX3gZkn1DtzZV=3{Bmlv zJ>Fa5KLAOP^XU~5Rxue3@lavrJxSarq5~FOWD#J8f|^g%*ry55=EM!DP`f)%T4q*N zai5`ba&lh#tXS2vsE&O!IV1+?u0iy#rwg}G3RqZJqB`>3D(qULr>O0c3-86w=+{2x z24^6R#(aFgLX;%c?c8n;SmReMgkB_(P9%mSQ*s2Gq{J23H z2+AWUIPF5E|Z4~K0M#6K)}ZlMFti4*x?fw0w1%E0Z{Pq zb>$ioe7x;N{!mFvOw1iAqUN%QvLkw^r~*{>w(Kau`MU1i$ucFh1(ahSLlo9m`S89S zczigNFtf6@Rv*k!S}zUaH`aM#fRZqiuf(~BJ4fuU*$=D<~yA(*9*`!nNQdF-S ztZ3c7?ydjM3)iG}e*P7=(bu;hd__}5b^o^hN>1-r&^b=l*iDgDqz%%3^o9(2cPh3R zsZ2rFiztUx%zqcqsR-_F+Qr;nUYw&53?j#JKOHb9o=%lje7(n=!KB?fLqW6c^jn;+ zTY6~!BreMs{@1f_?e-S6#}ZOfHhzMMWIh9?lqZ|kffDs-f+&*IH)5yfmt|jxHLUlynHD&rR%<$~nlu)Q; zkJ}VGRfVexPIRR9VsNGH1eo^`Lfzl19hSC+ z;@AxS2`D}rI}V8ptUUpk#zQ{l)^m404N0Xbn)2=&3~hnXH-6e!it(rezFz0b~_lFrm7s;sqY|Egpe9{pE0>eBu$eGf!eRu_Z; z<`AWz`ukmXKQ#JthD>7J7oqzyF@2vG(aH01WCWO>ja$J#V}3e_pbrL}o0qy1*Lgkl z^;2}pP2NrOI3wV%Mg9z%()$`NB21r%m{dzzfuRz52~2WuVFxl_CDs+!y~0e-u#OGN zxcfS~x~9f68xMS2BW*(uU60QVX~!ZhN%fGhb~^{yq0RpHY7QGqabU z6t(=~z^AU)o;ulfCqN13_SRP%m3^E7drhi%LeJS@`kOX!p_Xf`+qm)#=i+kC^t)KlZ>ijnb|# zTcaKrEi=}zw9L2LtFqB8HS)zQslP{|_s5R`G!T^h3>Lly4S@<^+CeA21>S5$|992B z#O&sGBPsYet;WNCPl7*dQw?l@jvWnLU+QcBxdHxOly4?eMkw|~Z>+E#cRt+5vbM7N z_IK&7DN=8m&HijOjw9N1DC=n~rvoXF_|+TSp?Kg&ki zZ&S&U0GLXc9qO^r7P#XEfykj+hlPV={pCwPl6ruCoT^vApCvJ*n!?8q?fEk_e}0H? zAn1xASDCucUoM5PNXD#`5@yO~f3R<29pU`%Hr3m|x8bx0aLi^d{C}|<|Bro;#u6L@ zTS{1O@6dvmiit@{DZ;_0Se?FwC3_#7D>RH=CkOp_SVoY~9N-6V#FR#=-o@&(eU{EJ ziv3nU{43U5JJ21XP@^k2SagA+5Uj(;H$Xw+;G{ae8+Zvz?mis*tylOrthXTb_@%GH z(l4<@)xa5LME$!&%)Xq_l$rSrO^8J!1%CfF>y!KPM}ByB8Wxto@1I%p>z?D00U@Y+ toFIhp=UbQ)?tg5b{@26!|5H;@7q9aw>`iX=S7D~AoYXVPVsRtC{{ Date: Fri, 28 Nov 2025 16:39:19 -0800 Subject: [PATCH 07/13] working on offset control --- .../swerve/SwerveDriveSubsystem.java | 1 + .../org/team100/lib/subsystems/test/README.md | 3 + .../subsystems/test/TrivialDrivetrain.java | 57 +++ .../visualization/RobotPoseVisualization.java | 37 ++ .../src/main/java/frc/robot/Main.java | 9 +- studies/offset_control/.gitignore | 187 ++++++++ studies/offset_control/.vscode/launch.json | 21 + studies/offset_control/.vscode/settings.json | 60 +++ .../.wpilib/wpilib_preferences.json | 6 + studies/offset_control/README.md | 9 + studies/offset_control/WPILib-License.md | 24 + studies/offset_control/build.gradle | 112 +++++ .../gradle/wrapper/gradle-wrapper.jar | Bin 0 -> 43583 bytes .../gradle/wrapper/gradle-wrapper.properties | 7 + studies/offset_control/gradlew | 252 +++++++++++ studies/offset_control/gradlew.bat | 94 ++++ .../offset_control.code-workspace | 73 +++ studies/offset_control/settings.gradle | 30 ++ studies/offset_control/simgui-ds.json | 112 +++++ .../src/main/deploy/example.txt | 3 + .../src/main/java/frc/robot/Main.java | 14 + .../org/team100/offset_control/Robot.java | 75 ++++ .../vendordeps/Phoenix5-frc2025-latest.json | 171 +++++++ .../vendordeps/Phoenix6-frc2025-latest.json | 419 ++++++++++++++++++ studies/offset_control/vendordeps/REVLib.json | 71 +++ .../vendordeps/ReduxLib-2025.0.0.json | 72 +++ .../vendordeps/WPILibNewCommands.json | 38 ++ .../vendordeps/libgrapplefrc2025.json | 74 ++++ 28 files changed, 2027 insertions(+), 4 deletions(-) create mode 100644 lib/src/main/java/org/team100/lib/subsystems/test/README.md create mode 100644 lib/src/main/java/org/team100/lib/subsystems/test/TrivialDrivetrain.java create mode 100644 lib/src/main/java/org/team100/lib/visualization/RobotPoseVisualization.java create mode 100644 studies/offset_control/.gitignore create mode 100644 studies/offset_control/.vscode/launch.json create mode 100644 studies/offset_control/.vscode/settings.json create mode 100644 studies/offset_control/.wpilib/wpilib_preferences.json create mode 100644 studies/offset_control/README.md create mode 100644 studies/offset_control/WPILib-License.md create mode 100644 studies/offset_control/build.gradle create mode 100644 studies/offset_control/gradle/wrapper/gradle-wrapper.jar create mode 100644 studies/offset_control/gradle/wrapper/gradle-wrapper.properties create mode 100755 studies/offset_control/gradlew create mode 100644 studies/offset_control/gradlew.bat create mode 100644 studies/offset_control/offset_control.code-workspace create mode 100644 studies/offset_control/settings.gradle create mode 100644 studies/offset_control/simgui-ds.json create mode 100644 studies/offset_control/src/main/deploy/example.txt create mode 100644 studies/offset_control/src/main/java/frc/robot/Main.java create mode 100644 studies/offset_control/src/main/java/org/team100/offset_control/Robot.java create mode 100644 studies/offset_control/vendordeps/Phoenix5-frc2025-latest.json create mode 100644 studies/offset_control/vendordeps/Phoenix6-frc2025-latest.json create mode 100644 studies/offset_control/vendordeps/REVLib.json create mode 100644 studies/offset_control/vendordeps/ReduxLib-2025.0.0.json create mode 100644 studies/offset_control/vendordeps/WPILibNewCommands.json create mode 100644 studies/offset_control/vendordeps/libgrapplefrc2025.json diff --git a/lib/src/main/java/org/team100/lib/subsystems/swerve/SwerveDriveSubsystem.java b/lib/src/main/java/org/team100/lib/subsystems/swerve/SwerveDriveSubsystem.java index 70f00439..5c939d84 100644 --- a/lib/src/main/java/org/team100/lib/subsystems/swerve/SwerveDriveSubsystem.java +++ b/lib/src/main/java/org/team100/lib/subsystems/swerve/SwerveDriveSubsystem.java @@ -47,6 +47,7 @@ public class SwerveDriveSubsystem extends SubsystemBase implements VelocitySubsy private final ModelR3Logger m_log_state; private final DoubleLogger m_log_turning; private final DoubleArrayLogger m_log_pose_array; + // TODO: pull the field logger out into a separate observer. private final DoubleArrayLogger m_log_field_robot; private final EnumLogger m_log_skill; private final GlobalVelocityR3Logger m_log_input; diff --git a/lib/src/main/java/org/team100/lib/subsystems/test/README.md b/lib/src/main/java/org/team100/lib/subsystems/test/README.md new file mode 100644 index 00000000..e638bb8e --- /dev/null +++ b/lib/src/main/java/org/team100/lib/subsystems/test/README.md @@ -0,0 +1,3 @@ +# lib.subsystems.test + +Subsystems only useful for testing. \ No newline at end of file diff --git a/lib/src/main/java/org/team100/lib/subsystems/test/TrivialDrivetrain.java b/lib/src/main/java/org/team100/lib/subsystems/test/TrivialDrivetrain.java new file mode 100644 index 00000000..c82a347c --- /dev/null +++ b/lib/src/main/java/org/team100/lib/subsystems/test/TrivialDrivetrain.java @@ -0,0 +1,57 @@ +package org.team100.lib.subsystems.test; + +import org.team100.lib.coherence.Cache; +import org.team100.lib.coherence.ObjectCache; +import org.team100.lib.framework.TimedRobot100; +import org.team100.lib.geometry.GlobalVelocityR3; +import org.team100.lib.state.ModelR3; +import org.team100.lib.subsystems.r3.VelocitySubsystemR3; + +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; + +/** + * Executes desired velocity exactly. + * Visualizes drivetrain pose. + */ +public class TrivialDrivetrain implements VelocitySubsystemR3 { + private static final double DT = TimedRobot100.LOOP_PERIOD_S; + private final ObjectCache m_stateCache; + private GlobalVelocityR3 m_setpoint; + private ModelR3 m_state; + + public TrivialDrivetrain() { + m_setpoint = new GlobalVelocityR3(0, 0, 0); + m_state = new ModelR3(Pose2d.kZero); + m_stateCache = Cache.of(this::update); + } + + @Override + public ModelR3 getState() { + return m_stateCache.get(); + } + + @Override + public void stop() { + m_setpoint = new GlobalVelocityR3(0, 0, 0); + } + + @Override + public void setVelocity(GlobalVelocityR3 setpoint) { + m_setpoint = setpoint; + } + + private ModelR3 update() { + double vx = m_setpoint.x(); + double vy = m_setpoint.y(); + double omega = m_setpoint.theta(); + m_state = new ModelR3( + new Pose2d( + m_state.pose().getX() + vx * DT, + m_state.pose().getY() + vy * DT, + m_state.pose().getRotation().plus(new Rotation2d(omega * DT))), + new GlobalVelocityR3(vx, vy, omega)); + return m_state; + } + +} diff --git a/lib/src/main/java/org/team100/lib/visualization/RobotPoseVisualization.java b/lib/src/main/java/org/team100/lib/visualization/RobotPoseVisualization.java new file mode 100644 index 00000000..f812f2ec --- /dev/null +++ b/lib/src/main/java/org/team100/lib/visualization/RobotPoseVisualization.java @@ -0,0 +1,37 @@ +package org.team100.lib.visualization; + +import java.util.function.Supplier; + +import org.team100.lib.logging.Level; +import org.team100.lib.logging.LoggerFactory; +import org.team100.lib.logging.LoggerFactory.DoubleArrayLogger; + +import edu.wpi.first.math.geometry.Pose2d; + +/** + * Observes a pose supplier, publishes to the glass Field2d widget. + */ +public class RobotPoseVisualization implements Runnable { + private final DoubleArrayLogger m_log_field_robot; + private final Supplier m_pose; + + public RobotPoseVisualization( + LoggerFactory fieldLogger, + Supplier pose) { + m_log_field_robot = fieldLogger.doubleArrayLogger(Level.COMP, "robot"); + m_pose = pose; + } + + @Override + public void run() { + m_log_field_robot.log(this::poseArray); + } + + private double[] poseArray() { + Pose2d pose = m_pose.get(); + return new double[] { + pose.getX(), + pose.getY(), + pose.getRotation().getDegrees() }; + } +} diff --git a/studies/ballerina/src/main/java/frc/robot/Main.java b/studies/ballerina/src/main/java/frc/robot/Main.java index 071fe388..afde3cd6 100644 --- a/studies/ballerina/src/main/java/frc/robot/Main.java +++ b/studies/ballerina/src/main/java/frc/robot/Main.java @@ -5,9 +5,10 @@ import edu.wpi.first.wpilibj.RobotBase; public final class Main { - private Main() {} + private Main() { + } - public static void main(String... args) { - RobotBase.startRobot(Robot::new); - } + public static void main(String... args) { + RobotBase.startRobot(Robot::new); + } } diff --git a/studies/offset_control/.gitignore b/studies/offset_control/.gitignore new file mode 100644 index 00000000..9a9ca7be --- /dev/null +++ b/studies/offset_control/.gitignore @@ -0,0 +1,187 @@ +# This gitignore has been specially created by the WPILib team. +# If you remove items from this file, intellisense might break. + +### C++ ### +# Prerequisites +*.d + +# Compiled Object files +*.slo +*.lo +*.o +*.obj + +# Precompiled Headers +*.gch +*.pch + +# Compiled Dynamic libraries +*.so +*.dylib +*.dll + +# Fortran module files +*.mod +*.smod + +# Compiled Static libraries +*.lai +*.la +*.a +*.lib + +# Executables +*.exe +*.out +*.app + +### Java ### +# Compiled class file +*.class + +# Log file +*.log + +# BlueJ files +*.ctxt + +# Mobile Tools for Java (J2ME) +.mtj.tmp/ + +# Package Files # +*.jar +*.war +*.nar +*.ear +*.zip +*.tar.gz +*.rar + +# virtual machine crash logs, see http://www.java.com/en/download/help/error_hotspot.xml +hs_err_pid* + +### Linux ### +*~ + +# temporary files which can be created if a process still has a handle open of a deleted file +.fuse_hidden* + +# KDE directory preferences +.directory + +# Linux trash folder which might appear on any partition or disk +.Trash-* + +# .nfs files are created when an open file is removed but is still being accessed +.nfs* + +### macOS ### +# General +.DS_Store +.AppleDouble +.LSOverride + +# Icon must end with two \r +Icon + +# Thumbnails +._* + +# Files that might appear in the root of a volume +.DocumentRevisions-V100 +.fseventsd +.Spotlight-V100 +.TemporaryItems +.Trashes +.VolumeIcon.icns +.com.apple.timemachine.donotpresent + +# Directories potentially created on remote AFP share +.AppleDB +.AppleDesktop +Network Trash Folder +Temporary Items +.apdisk + +### VisualStudioCode ### +.vscode/* +!.vscode/settings.json +!.vscode/tasks.json +!.vscode/launch.json +!.vscode/extensions.json + +### Windows ### +# Windows thumbnail cache files +Thumbs.db +ehthumbs.db +ehthumbs_vista.db + +# Dump file +*.stackdump + +# Folder config file +[Dd]esktop.ini + +# Recycle Bin used on file shares +$RECYCLE.BIN/ + +# Windows Installer files +*.cab +*.msi +*.msix +*.msm +*.msp + +# Windows shortcuts +*.lnk + +### Gradle ### +.gradle +/build/ + +# Ignore Gradle GUI config +gradle-app.setting + +# Avoid ignoring Gradle wrapper jar file (.jar files are usually ignored) +!gradle-wrapper.jar + +# Cache of project +.gradletasknamecache + +# # Work around https://youtrack.jetbrains.com/issue/IDEA-116898 +# gradle/wrapper/gradle-wrapper.properties + +# # VS Code Specific Java Settings +# DO NOT REMOVE .classpath and .project +.classpath +.project +.settings/ +bin/ + +# IntelliJ +*.iml +*.ipr +*.iws +.idea/ +out/ + +# Fleet +.fleet + +# Simulation GUI and other tools window save file +networktables.json +simgui.json +*-window.json + +# Simulation data log directory +logs/ + +# Folder that has CTRE Phoenix Sim device config storage +ctre_sim/ + +# clangd +/.cache +compile_commands.json + +# Eclipse generated file for annotation processors +.factorypath diff --git a/studies/offset_control/.vscode/launch.json b/studies/offset_control/.vscode/launch.json new file mode 100644 index 00000000..5b804e84 --- /dev/null +++ b/studies/offset_control/.vscode/launch.json @@ -0,0 +1,21 @@ +{ + // Use IntelliSense to learn about possible attributes. + // Hover to view descriptions of existing attributes. + // For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387 + "version": "0.2.0", + "configurations": [ + + { + "type": "wpilib", + "name": "WPILib Desktop Debug", + "request": "launch", + "desktop": true, + }, + { + "type": "wpilib", + "name": "WPILib roboRIO Debug", + "request": "launch", + "desktop": false, + } + ] +} diff --git a/studies/offset_control/.vscode/settings.json b/studies/offset_control/.vscode/settings.json new file mode 100644 index 00000000..dccbc7c3 --- /dev/null +++ b/studies/offset_control/.vscode/settings.json @@ -0,0 +1,60 @@ +{ + "java.configuration.updateBuildConfiguration": "automatic", + "java.server.launchMode": "Standard", + "files.exclude": { + "**/.git": true, + "**/.svn": true, + "**/.hg": true, + "**/CVS": true, + "**/.DS_Store": true, + "bin/": true, + "**/.classpath": true, + "**/.project": true, + "**/.settings": true, + "**/.factorypath": true, + "**/*~": true + }, + "java.test.config": [ + { + "name": "WPIlibUnitTests", + "workingDirectory": "${workspaceFolder}/build/jni/release", + "vmargs": [ "-Djava.library.path=${workspaceFolder}/build/jni/release" ], + "env": { + "LD_LIBRARY_PATH": "${workspaceFolder}/build/jni/release" , + "DYLD_LIBRARY_PATH": "${workspaceFolder}/build/jni/release" + } + }, + ], + "java.test.defaultConfig": "WPIlibUnitTests", + "java.import.gradle.annotationProcessing.enabled": false, + "java.completion.favoriteStaticMembers": [ + "org.junit.Assert.*", + "org.junit.Assume.*", + "org.junit.jupiter.api.Assertions.*", + "org.junit.jupiter.api.Assumptions.*", + "org.junit.jupiter.api.DynamicContainer.*", + "org.junit.jupiter.api.DynamicTest.*", + "org.mockito.Mockito.*", + "org.mockito.ArgumentMatchers.*", + "org.mockito.Answers.*", + "edu.wpi.first.units.Units.*" + ], + "java.completion.filteredTypes": [ + "java.awt.*", + "com.sun.*", + "sun.*", + "jdk.*", + "org.graalvm.*", + "io.micrometer.shaded.*", + "java.beans.*", + "java.util.Base64.*", + "java.util.Timer", + "java.sql.*", + "javax.swing.*", + "javax.management.*", + "javax.smartcardio.*", + "edu.wpi.first.math.proto.*", + "edu.wpi.first.math.**.proto.*", + "edu.wpi.first.math.**.struct.*", + ] +} diff --git a/studies/offset_control/.wpilib/wpilib_preferences.json b/studies/offset_control/.wpilib/wpilib_preferences.json new file mode 100644 index 00000000..e90d9cfd --- /dev/null +++ b/studies/offset_control/.wpilib/wpilib_preferences.json @@ -0,0 +1,6 @@ +{ + "enableCppIntellisense": false, + "currentLanguage": "java", + "projectYear": "2025", + "teamNumber": 100 +} \ No newline at end of file diff --git a/studies/offset_control/README.md b/studies/offset_control/README.md new file mode 100644 index 00000000..006cb769 --- /dev/null +++ b/studies/offset_control/README.md @@ -0,0 +1,9 @@ +# Offset Control + +In 2025 we learned that 254 drivetrain control operated on the error +in the end-effector pose, rather than the robot pose, in order to avoid +controlling the drivetrain unnecessarily. In particular, the +rotation error of the end effector was relatively unimportant. + +How could we do the same thing? + diff --git a/studies/offset_control/WPILib-License.md b/studies/offset_control/WPILib-License.md new file mode 100644 index 00000000..e7cd597b --- /dev/null +++ b/studies/offset_control/WPILib-License.md @@ -0,0 +1,24 @@ +Copyright (c) 2009-2024 FIRST and other WPILib contributors +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * 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. + * Neither the name of FIRST, WPILib, nor the names of other WPILib + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY FIRST AND OTHER WPILIB CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR +PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST 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. diff --git a/studies/offset_control/build.gradle b/studies/offset_control/build.gradle new file mode 100644 index 00000000..37612152 --- /dev/null +++ b/studies/offset_control/build.gradle @@ -0,0 +1,112 @@ +plugins { + id "java" + id "edu.wpi.first.GradleRIO" version "2025.3.2" +} + +sourceSets { + main { + java { + srcDir "../../lib/src/main/java" + } + } +} + +java { + sourceCompatibility = JavaVersion.VERSION_17 + targetCompatibility = JavaVersion.VERSION_17 +} + +def ROBOT_MAIN_CLASS = "frc.robot.Main" + +// Define my targets (RoboRIO) and artifacts (deployable files) +// This is added by GradleRIO's backing project DeployUtils. +deploy { + targets { + roborio(getTargetTypeClass('RoboRIO')) { + // Team number is loaded either from the .wpilib/wpilib_preferences.json + // or from command line. If not found an exception will be thrown. + // You can use getTeamOrDefault(team) instead of getTeamNumber if you + // want to store a team number in this file. + team = project.frc.getTeamNumber() + debug = project.frc.getDebugOrDefault(false) + + artifacts { + // First part is artifact name, 2nd is artifact type + // getTargetTypeClass is a shortcut to get the class type using a string + + frcJava(getArtifactTypeClass('FRCJavaArtifact')) { + } + + // Static files artifact + frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { + files = project.fileTree('src/main/deploy') + directory = '/home/lvuser/deploy' + deleteOldFiles = false // Change to true to delete files on roboRIO that no + // longer exist in deploy directory of this project + } + } + } + } +} + +def deployArtifact = deploy.targets.roborio.artifacts.frcJava + +// Set to true to use debug for JNI. +wpi.java.debugJni = false + +// Set this to true to enable desktop support. +def includeDesktopSupport = true + +// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries. +// Also defines JUnit 5. +dependencies { + annotationProcessor wpi.java.deps.wpilibAnnotations() + implementation wpi.java.deps.wpilib() + implementation wpi.java.vendor.java() + + roborioDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.roborio) + roborioDebug wpi.java.vendor.jniDebug(wpi.platforms.roborio) + + roborioRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.roborio) + roborioRelease wpi.java.vendor.jniRelease(wpi.platforms.roborio) + + nativeDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.desktop) + nativeDebug wpi.java.vendor.jniDebug(wpi.platforms.desktop) + simulationDebug wpi.sim.enableDebug() + + nativeRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.desktop) + nativeRelease wpi.java.vendor.jniRelease(wpi.platforms.desktop) + simulationRelease wpi.sim.enableRelease() + + testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1' + testRuntimeOnly 'org.junit.platform:junit-platform-launcher' +} + +test { + useJUnitPlatform() + systemProperty 'junit.jupiter.extensions.autodetection.enabled', 'true' +} + +// Simulation configuration (e.g. environment variables). +wpi.sim.addGui().defaultEnabled = true +wpi.sim.addDriverstation() + +// Setting up my Jar File. In this case, adding all libraries into the main jar ('fat jar') +// in order to make them all available at runtime. Also adding the manifest so WPILib +// knows where to look for our Robot Class. +jar { + from { configurations.runtimeClasspath.collect { it.isDirectory() ? it : zipTree(it) } } + from sourceSets.main.allSource + manifest edu.wpi.first.gradlerio.GradleRIOPlugin.javaManifest(ROBOT_MAIN_CLASS) + duplicatesStrategy = DuplicatesStrategy.INCLUDE +} + +// Configure jar and deploy tasks +deployArtifact.jarTask = jar +wpi.java.configureExecutableTasks(jar) +wpi.java.configureTestTasks(test) + +// Configure string concat to always inline compile +tasks.withType(JavaCompile) { + options.compilerArgs.add '-XDstringConcat=inline' +} diff --git a/studies/offset_control/gradle/wrapper/gradle-wrapper.jar b/studies/offset_control/gradle/wrapper/gradle-wrapper.jar new file mode 100644 index 0000000000000000000000000000000000000000..a4b76b9530d66f5e68d973ea569d8e19de379189 GIT binary patch literal 43583 zcma&N1CXTcmMvW9vTb(Rwr$&4wr$(C?dmSu>@vG-+vuvg^_??!{yS%8zW-#zn-LkA z5&1^$^{lnmUON?}LBF8_K|(?T0Ra(xUH{($5eN!MR#ZihR#HxkUPe+_R8Cn`RRs(P z_^*#_XlXmGv7!4;*Y%p4nw?{bNp@UZHv1?Um8r6)Fei3p@ClJn0ECfg1hkeuUU@Or zDaPa;U3fE=3L}DooL;8f;P0ipPt0Z~9P0)lbStMS)ag54=uL9ia-Lm3nh|@(Y?B`; zx_#arJIpXH!U{fbCbI^17}6Ri*H<>OLR%c|^mh8+)*h~K8Z!9)DPf zR2h?lbDZQ`p9P;&DQ4F0sur@TMa!Y}S8irn(%d-gi0*WxxCSk*A?3lGh=gcYN?FGl z7D=Js!i~0=u3rox^eO3i@$0=n{K1lPNU zwmfjRVmLOCRfe=seV&P*1Iq=^i`502keY8Uy-WNPwVNNtJFx?IwAyRPZo2Wo1+S(xF37LJZ~%i)kpFQ3Fw=mXfd@>%+)RpYQLnr}B~~zoof(JVm^^&f zxKV^+3D3$A1G;qh4gPVjhrC8e(VYUHv#dy^)(RoUFM?o%W-EHxufuWf(l*@-l+7vt z=l`qmR56K~F|v<^Pd*p~1_y^P0P^aPC##d8+HqX4IR1gu+7w#~TBFphJxF)T$2WEa zxa?H&6=Qe7d(#tha?_1uQys2KtHQ{)Qco)qwGjrdNL7thd^G5i8Os)CHqc>iOidS} z%nFEDdm=GXBw=yXe1W-ShHHFb?Cc70+$W~z_+}nAoHFYI1MV1wZegw*0y^tC*s%3h zhD3tN8b=Gv&rj}!SUM6|ajSPp*58KR7MPpI{oAJCtY~JECm)*m_x>AZEu>DFgUcby z1Qaw8lU4jZpQ_$;*7RME+gq1KySGG#Wql>aL~k9tLrSO()LWn*q&YxHEuzmwd1?aAtI zBJ>P=&$=l1efe1CDU;`Fd+_;&wI07?V0aAIgc(!{a z0Jg6Y=inXc3^n!U0Atk`iCFIQooHqcWhO(qrieUOW8X(x?(RD}iYDLMjSwffH2~tB z)oDgNBLB^AJBM1M^c5HdRx6fBfka`(LD-qrlh5jqH~);#nw|iyp)()xVYak3;Ybik z0j`(+69aK*B>)e_p%=wu8XC&9e{AO4c~O1U`5X9}?0mrd*m$_EUek{R?DNSh(=br# z#Q61gBzEpmy`$pA*6!87 zSDD+=@fTY7<4A?GLqpA?Pb2z$pbCc4B4zL{BeZ?F-8`s$?>*lXXtn*NC61>|*w7J* z$?!iB{6R-0=KFmyp1nnEmLsA-H0a6l+1uaH^g%c(p{iT&YFrbQ$&PRb8Up#X3@Zsk zD^^&LK~111%cqlP%!_gFNa^dTYT?rhkGl}5=fL{a`UViaXWI$k-UcHJwmaH1s=S$4 z%4)PdWJX;hh5UoK?6aWoyLxX&NhNRqKam7tcOkLh{%j3K^4Mgx1@i|Pi&}<^5>hs5 zm8?uOS>%)NzT(%PjVPGa?X%`N2TQCKbeH2l;cTnHiHppPSJ<7y-yEIiC!P*ikl&!B z%+?>VttCOQM@ShFguHVjxX^?mHX^hSaO_;pnyh^v9EumqSZTi+#f&_Vaija0Q-e*| z7ulQj6Fs*bbmsWp{`auM04gGwsYYdNNZcg|ph0OgD>7O}Asn7^Z=eI>`$2*v78;sj-}oMoEj&@)9+ycEOo92xSyY344^ z11Hb8^kdOvbf^GNAK++bYioknrpdN>+u8R?JxG=!2Kd9r=YWCOJYXYuM0cOq^FhEd zBg2puKy__7VT3-r*dG4c62Wgxi52EMCQ`bKgf*#*ou(D4-ZN$+mg&7$u!! z-^+Z%;-3IDwqZ|K=ah85OLwkO zKxNBh+4QHh)u9D?MFtpbl)us}9+V!D%w9jfAMYEb>%$A;u)rrI zuBudh;5PN}_6J_}l55P3l_)&RMlH{m!)ai-i$g)&*M`eN$XQMw{v^r@-125^RRCF0 z^2>|DxhQw(mtNEI2Kj(;KblC7x=JlK$@78`O~>V!`|1Lm-^JR$-5pUANAnb(5}B}JGjBsliK4& zk6y(;$e&h)lh2)L=bvZKbvh@>vLlreBdH8No2>$#%_Wp1U0N7Ank!6$dFSi#xzh|( zRi{Uw%-4W!{IXZ)fWx@XX6;&(m_F%c6~X8hx=BN1&q}*( zoaNjWabE{oUPb!Bt$eyd#$5j9rItB-h*5JiNi(v^e|XKAj*8(k<5-2$&ZBR5fF|JA z9&m4fbzNQnAU}r8ab>fFV%J0z5awe#UZ|bz?Ur)U9bCIKWEzi2%A+5CLqh?}K4JHi z4vtM;+uPsVz{Lfr;78W78gC;z*yTch~4YkLr&m-7%-xc ztw6Mh2d>_iO*$Rd8(-Cr1_V8EO1f*^@wRoSozS) zy1UoC@pruAaC8Z_7~_w4Q6n*&B0AjOmMWa;sIav&gu z|J5&|{=a@vR!~k-OjKEgPFCzcJ>#A1uL&7xTDn;{XBdeM}V=l3B8fE1--DHjSaxoSjNKEM9|U9#m2<3>n{Iuo`r3UZp;>GkT2YBNAh|b z^jTq-hJp(ebZh#Lk8hVBP%qXwv-@vbvoREX$TqRGTgEi$%_F9tZES@z8Bx}$#5eeG zk^UsLBH{bc2VBW)*EdS({yw=?qmevwi?BL6*=12k9zM5gJv1>y#ML4!)iiPzVaH9% zgSImetD@dam~e>{LvVh!phhzpW+iFvWpGT#CVE5TQ40n%F|p(sP5mXxna+Ev7PDwA zamaV4m*^~*xV+&p;W749xhb_X=$|LD;FHuB&JL5?*Y2-oIT(wYY2;73<^#46S~Gx| z^cez%V7x$81}UWqS13Gz80379Rj;6~WdiXWOSsdmzY39L;Hg3MH43o*y8ibNBBH`(av4|u;YPq%{R;IuYow<+GEsf@R?=@tT@!}?#>zIIn0CoyV!hq3mw zHj>OOjfJM3F{RG#6ujzo?y32m^tgSXf@v=J$ELdJ+=5j|=F-~hP$G&}tDZsZE?5rX ztGj`!S>)CFmdkccxM9eGIcGnS2AfK#gXwj%esuIBNJQP1WV~b~+D7PJTmWGTSDrR` zEAu4B8l>NPuhsk5a`rReSya2nfV1EK01+G!x8aBdTs3Io$u5!6n6KX%uv@DxAp3F@{4UYg4SWJtQ-W~0MDb|j-$lwVn znAm*Pl!?Ps&3wO=R115RWKb*JKoexo*)uhhHBncEDMSVa_PyA>k{Zm2(wMQ(5NM3# z)jkza|GoWEQo4^s*wE(gHz?Xsg4`}HUAcs42cM1-qq_=+=!Gk^y710j=66(cSWqUe zklbm8+zB_syQv5A2rj!Vbw8;|$@C!vfNmNV!yJIWDQ>{+2x zKjuFX`~~HKG~^6h5FntRpnnHt=D&rq0>IJ9#F0eM)Y-)GpRjiN7gkA8wvnG#K=q{q z9dBn8_~wm4J<3J_vl|9H{7q6u2A!cW{bp#r*-f{gOV^e=8S{nc1DxMHFwuM$;aVI^ zz6A*}m8N-&x8;aunp1w7_vtB*pa+OYBw=TMc6QK=mbA-|Cf* zvyh8D4LRJImooUaSb7t*fVfih<97Gf@VE0|z>NcBwBQze);Rh!k3K_sfunToZY;f2 z^HmC4KjHRVg+eKYj;PRN^|E0>Gj_zagfRbrki68I^#~6-HaHg3BUW%+clM1xQEdPYt_g<2K+z!$>*$9nQ>; zf9Bei{?zY^-e{q_*|W#2rJG`2fy@{%6u0i_VEWTq$*(ZN37|8lFFFt)nCG({r!q#9 z5VK_kkSJ3?zOH)OezMT{!YkCuSSn!K#-Rhl$uUM(bq*jY? zi1xbMVthJ`E>d>(f3)~fozjg^@eheMF6<)I`oeJYx4*+M&%c9VArn(OM-wp%M<-`x z7sLP1&3^%Nld9Dhm@$3f2}87!quhI@nwd@3~fZl_3LYW-B?Ia>ui`ELg z&Qfe!7m6ze=mZ`Ia9$z|ARSw|IdMpooY4YiPN8K z4B(ts3p%2i(Td=tgEHX z0UQ_>URBtG+-?0E;E7Ld^dyZ;jjw0}XZ(}-QzC6+NN=40oDb2^v!L1g9xRvE#@IBR zO!b-2N7wVfLV;mhEaXQ9XAU+>=XVA6f&T4Z-@AX!leJ8obP^P^wP0aICND?~w&NykJ#54x3_@r7IDMdRNy4Hh;h*!u(Ol(#0bJdwEo$5437-UBjQ+j=Ic>Q2z` zJNDf0yO6@mr6y1#n3)s(W|$iE_i8r@Gd@!DWDqZ7J&~gAm1#~maIGJ1sls^gxL9LLG_NhU!pTGty!TbhzQnu)I*S^54U6Yu%ZeCg`R>Q zhBv$n5j0v%O_j{QYWG!R9W?5_b&67KB$t}&e2LdMvd(PxN6Ir!H4>PNlerpBL>Zvyy!yw z-SOo8caEpDt(}|gKPBd$qND5#a5nju^O>V&;f890?yEOfkSG^HQVmEbM3Ugzu+UtH zC(INPDdraBN?P%kE;*Ae%Wto&sgw(crfZ#Qy(<4nk;S|hD3j{IQRI6Yq|f^basLY; z-HB&Je%Gg}Jt@={_C{L$!RM;$$|iD6vu#3w?v?*;&()uB|I-XqEKqZPS!reW9JkLewLb!70T7n`i!gNtb1%vN- zySZj{8-1>6E%H&=V}LM#xmt`J3XQoaD|@XygXjdZ1+P77-=;=eYpoEQ01B@L*a(uW zrZeZz?HJsw_4g0vhUgkg@VF8<-X$B8pOqCuWAl28uB|@r`19DTUQQsb^pfqB6QtiT z*`_UZ`fT}vtUY#%sq2{rchyfu*pCg;uec2$-$N_xgjZcoumE5vSI{+s@iLWoz^Mf; zuI8kDP{!XY6OP~q5}%1&L}CtfH^N<3o4L@J@zg1-mt{9L`s^z$Vgb|mr{@WiwAqKg zp#t-lhrU>F8o0s1q_9y`gQNf~Vb!F%70f}$>i7o4ho$`uciNf=xgJ>&!gSt0g;M>*x4-`U)ysFW&Vs^Vk6m%?iuWU+o&m(2Jm26Y(3%TL; zA7T)BP{WS!&xmxNw%J=$MPfn(9*^*TV;$JwRy8Zl*yUZi8jWYF>==j~&S|Xinsb%c z2?B+kpet*muEW7@AzjBA^wAJBY8i|#C{WtO_or&Nj2{=6JTTX05}|H>N2B|Wf!*3_ z7hW*j6p3TvpghEc6-wufFiY!%-GvOx*bZrhZu+7?iSrZL5q9}igiF^*R3%DE4aCHZ zqu>xS8LkW+Auv%z-<1Xs92u23R$nk@Pk}MU5!gT|c7vGlEA%G^2th&Q*zfg%-D^=f z&J_}jskj|Q;73NP4<4k*Y%pXPU2Thoqr+5uH1yEYM|VtBPW6lXaetokD0u z9qVek6Q&wk)tFbQ8(^HGf3Wp16gKmr>G;#G(HRBx?F`9AIRboK+;OfHaLJ(P>IP0w zyTbTkx_THEOs%Q&aPrxbZrJlio+hCC_HK<4%f3ZoSAyG7Dn`=X=&h@m*|UYO-4Hq0 z-Bq&+Ie!S##4A6OGoC~>ZW`Y5J)*ouaFl_e9GA*VSL!O_@xGiBw!AF}1{tB)z(w%c zS1Hmrb9OC8>0a_$BzeiN?rkPLc9%&;1CZW*4}CDDNr2gcl_3z+WC15&H1Zc2{o~i) z)LLW=WQ{?ricmC`G1GfJ0Yp4Dy~Ba;j6ZV4r{8xRs`13{dD!xXmr^Aga|C=iSmor% z8hi|pTXH)5Yf&v~exp3o+sY4B^^b*eYkkCYl*T{*=-0HniSA_1F53eCb{x~1k3*`W zr~};p1A`k{1DV9=UPnLDgz{aJH=-LQo<5%+Em!DNN252xwIf*wF_zS^!(XSm(9eoj z=*dXG&n0>)_)N5oc6v!>-bd(2ragD8O=M|wGW z!xJQS<)u70m&6OmrF0WSsr@I%T*c#Qo#Ha4d3COcX+9}hM5!7JIGF>7<~C(Ear^Sn zm^ZFkV6~Ula6+8S?oOROOA6$C&q&dp`>oR-2Ym3(HT@O7Sd5c~+kjrmM)YmgPH*tL zX+znN>`tv;5eOfX?h{AuX^LK~V#gPCu=)Tigtq9&?7Xh$qN|%A$?V*v=&-2F$zTUv z`C#WyIrChS5|Kgm_GeudCFf;)!WH7FI60j^0o#65o6`w*S7R@)88n$1nrgU(oU0M9 zx+EuMkC>(4j1;m6NoGqEkpJYJ?vc|B zOlwT3t&UgL!pX_P*6g36`ZXQ; z9~Cv}ANFnJGp(;ZhS(@FT;3e)0)Kp;h^x;$*xZn*k0U6-&FwI=uOGaODdrsp-!K$Ac32^c{+FhI-HkYd5v=`PGsg%6I`4d9Jy)uW0y%) zm&j^9WBAp*P8#kGJUhB!L?a%h$hJgQrx!6KCB_TRo%9{t0J7KW8!o1B!NC)VGLM5! zpZy5Jc{`r{1e(jd%jsG7k%I+m#CGS*BPA65ZVW~fLYw0dA-H_}O zrkGFL&P1PG9p2(%QiEWm6x;U-U&I#;Em$nx-_I^wtgw3xUPVVu zqSuKnx&dIT-XT+T10p;yjo1Y)z(x1fb8Dzfn8e yu?e%!_ptzGB|8GrCfu%p?(_ zQccdaaVK$5bz;*rnyK{_SQYM>;aES6Qs^lj9lEs6_J+%nIiuQC*fN;z8md>r_~Mfl zU%p5Dt_YT>gQqfr@`cR!$NWr~+`CZb%dn;WtzrAOI>P_JtsB76PYe*<%H(y>qx-`Kq!X_; z<{RpAqYhE=L1r*M)gNF3B8r(<%8mo*SR2hu zccLRZwGARt)Hlo1euqTyM>^!HK*!Q2P;4UYrysje@;(<|$&%vQekbn|0Ruu_Io(w4#%p6ld2Yp7tlA`Y$cciThP zKzNGIMPXX%&Ud0uQh!uQZz|FB`4KGD?3!ND?wQt6!n*f4EmCoJUh&b?;B{|lxs#F- z31~HQ`SF4x$&v00@(P+j1pAaj5!s`)b2RDBp*PB=2IB>oBF!*6vwr7Dp%zpAx*dPr zb@Zjq^XjN?O4QcZ*O+8>)|HlrR>oD*?WQl5ri3R#2?*W6iJ>>kH%KnnME&TT@ZzrHS$Q%LC?n|e>V+D+8D zYc4)QddFz7I8#}y#Wj6>4P%34dZH~OUDb?uP%-E zwjXM(?Sg~1!|wI(RVuxbu)-rH+O=igSho_pDCw(c6b=P zKk4ATlB?bj9+HHlh<_!&z0rx13K3ZrAR8W)!@Y}o`?a*JJsD+twZIv`W)@Y?Amu_u zz``@-e2X}27$i(2=9rvIu5uTUOVhzwu%mNazS|lZb&PT;XE2|B&W1>=B58#*!~D&) zfVmJGg8UdP*fx(>Cj^?yS^zH#o-$Q-*$SnK(ZVFkw+er=>N^7!)FtP3y~Xxnu^nzY zikgB>Nj0%;WOltWIob|}%lo?_C7<``a5hEkx&1ku$|)i>Rh6@3h*`slY=9U}(Ql_< zaNG*J8vb&@zpdhAvv`?{=zDedJ23TD&Zg__snRAH4eh~^oawdYi6A3w8<Ozh@Kw)#bdktM^GVb zrG08?0bG?|NG+w^&JvD*7LAbjED{_Zkc`3H!My>0u5Q}m!+6VokMLXxl`Mkd=g&Xx z-a>m*#G3SLlhbKB!)tnzfWOBV;u;ftU}S!NdD5+YtOjLg?X}dl>7m^gOpihrf1;PY zvll&>dIuUGs{Qnd- zwIR3oIrct8Va^Tm0t#(bJD7c$Z7DO9*7NnRZorrSm`b`cxz>OIC;jSE3DO8`hX955ui`s%||YQtt2 z5DNA&pG-V+4oI2s*x^>-$6J?p=I>C|9wZF8z;VjR??Icg?1w2v5Me+FgAeGGa8(3S z4vg*$>zC-WIVZtJ7}o9{D-7d>zCe|z#<9>CFve-OPAYsneTb^JH!Enaza#j}^mXy1 z+ULn^10+rWLF6j2>Ya@@Kq?26>AqK{A_| zQKb*~F1>sE*=d?A?W7N2j?L09_7n+HGi{VY;MoTGr_)G9)ot$p!-UY5zZ2Xtbm=t z@dpPSGwgH=QtIcEulQNI>S-#ifbnO5EWkI;$A|pxJd885oM+ zGZ0_0gDvG8q2xebj+fbCHYfAXuZStH2j~|d^sBAzo46(K8n59+T6rzBwK)^rfPT+B zyIFw)9YC-V^rhtK`!3jrhmW-sTmM+tPH+;nwjL#-SjQPUZ53L@A>y*rt(#M(qsiB2 zx6B)dI}6Wlsw%bJ8h|(lhkJVogQZA&n{?Vgs6gNSXzuZpEyu*xySy8ro07QZ7Vk1!3tJphN_5V7qOiyK8p z#@jcDD8nmtYi1^l8ml;AF<#IPK?!pqf9D4moYk>d99Im}Jtwj6c#+A;f)CQ*f-hZ< z=p_T86jog%!p)D&5g9taSwYi&eP z#JuEK%+NULWus;0w32-SYFku#i}d~+{Pkho&^{;RxzP&0!RCm3-9K6`>KZpnzS6?L z^H^V*s!8<>x8bomvD%rh>Zp3>Db%kyin;qtl+jAv8Oo~1g~mqGAC&Qi_wy|xEt2iz zWAJEfTV%cl2Cs<1L&DLRVVH05EDq`pH7Oh7sR`NNkL%wi}8n>IXcO40hp+J+sC!W?!krJf!GJNE8uj zg-y~Ns-<~D?yqbzVRB}G>0A^f0!^N7l=$m0OdZuqAOQqLc zX?AEGr1Ht+inZ-Qiwnl@Z0qukd__a!C*CKuGdy5#nD7VUBM^6OCpxCa2A(X;e0&V4 zM&WR8+wErQ7UIc6LY~Q9x%Sn*Tn>>P`^t&idaOEnOd(Ufw#>NoR^1QdhJ8s`h^|R_ zXX`c5*O~Xdvh%q;7L!_!ohf$NfEBmCde|#uVZvEo>OfEq%+Ns7&_f$OR9xsihRpBb z+cjk8LyDm@U{YN>+r46?nn{7Gh(;WhFw6GAxtcKD+YWV?uge>;+q#Xx4!GpRkVZYu zzsF}1)7$?%s9g9CH=Zs+B%M_)+~*j3L0&Q9u7!|+T`^O{xE6qvAP?XWv9_MrZKdo& z%IyU)$Q95AB4!#hT!_dA>4e@zjOBD*Y=XjtMm)V|+IXzjuM;(l+8aA5#Kaz_$rR6! zj>#&^DidYD$nUY(D$mH`9eb|dtV0b{S>H6FBfq>t5`;OxA4Nn{J(+XihF(stSche7$es&~N$epi&PDM_N`As;*9D^L==2Q7Z2zD+CiU(|+-kL*VG+&9!Yb3LgPy?A zm7Z&^qRG_JIxK7-FBzZI3Q<;{`DIxtc48k> zc|0dmX;Z=W$+)qE)~`yn6MdoJ4co;%!`ddy+FV538Y)j(vg}5*k(WK)KWZ3WaOG!8 z!syGn=s{H$odtpqFrT#JGM*utN7B((abXnpDM6w56nhw}OY}0TiTG1#f*VFZr+^-g zbP10`$LPq_;PvrA1XXlyx2uM^mrjTzX}w{yuLo-cOClE8MMk47T25G8M!9Z5ypOSV zAJUBGEg5L2fY)ZGJb^E34R2zJ?}Vf>{~gB!8=5Z) z9y$>5c)=;o0HeHHSuE4U)#vG&KF|I%-cF6f$~pdYJWk_dD}iOA>iA$O$+4%@>JU08 zS`ep)$XLPJ+n0_i@PkF#ri6T8?ZeAot$6JIYHm&P6EB=BiaNY|aA$W0I+nz*zkz_z zkEru!tj!QUffq%)8y0y`T&`fuus-1p>=^hnBiBqD^hXrPs`PY9tU3m0np~rISY09> z`P3s=-kt_cYcxWd{de@}TwSqg*xVhp;E9zCsnXo6z z?f&Sv^U7n4`xr=mXle94HzOdN!2kB~4=%)u&N!+2;z6UYKUDqi-s6AZ!haB;@&B`? z_TRX0%@suz^TRdCb?!vNJYPY8L_}&07uySH9%W^Tc&1pia6y1q#?*Drf}GjGbPjBS zbOPcUY#*$3sL2x4v_i*Y=N7E$mR}J%|GUI(>WEr+28+V z%v5{#e!UF*6~G&%;l*q*$V?&r$Pp^sE^i-0$+RH3ERUUdQ0>rAq2(2QAbG}$y{de( z>{qD~GGuOk559Y@%$?N^1ApVL_a704>8OD%8Y%8B;FCt%AoPu8*D1 zLB5X>b}Syz81pn;xnB}%0FnwazlWfUV)Z-~rZg6~b z6!9J$EcE&sEbzcy?CI~=boWA&eeIa%z(7SE^qgVLz??1Vbc1*aRvc%Mri)AJaAG!p z$X!_9Ds;Zz)f+;%s&dRcJt2==P{^j3bf0M=nJd&xwUGlUFn?H=2W(*2I2Gdu zv!gYCwM10aeus)`RIZSrCK=&oKaO_Ry~D1B5!y0R=%!i2*KfXGYX&gNv_u+n9wiR5 z*e$Zjju&ODRW3phN925%S(jL+bCHv6rZtc?!*`1TyYXT6%Ju=|X;6D@lq$8T zW{Y|e39ioPez(pBH%k)HzFITXHvnD6hw^lIoUMA;qAJ^CU?top1fo@s7xT13Fvn1H z6JWa-6+FJF#x>~+A;D~;VDs26>^oH0EI`IYT2iagy23?nyJ==i{g4%HrAf1-*v zK1)~@&(KkwR7TL}L(A@C_S0G;-GMDy=MJn2$FP5s<%wC)4jC5PXoxrQBFZ_k0P{{s@sz+gX`-!=T8rcB(=7vW}^K6oLWMmp(rwDh}b zwaGGd>yEy6fHv%jM$yJXo5oMAQ>c9j`**}F?MCry;T@47@r?&sKHgVe$MCqk#Z_3S z1GZI~nOEN*P~+UaFGnj{{Jo@16`(qVNtbU>O0Hf57-P>x8Jikp=`s8xWs^dAJ9lCQ z)GFm+=OV%AMVqVATtN@|vp61VVAHRn87}%PC^RAzJ%JngmZTasWBAWsoAqBU+8L8u z4A&Pe?fmTm0?mK-BL9t+{y7o(7jm+RpOhL9KnY#E&qu^}B6=K_dB}*VlSEiC9fn)+V=J;OnN)Ta5v66ic1rG+dGAJ1 z1%Zb_+!$=tQ~lxQrzv3x#CPb?CekEkA}0MYSgx$Jdd}q8+R=ma$|&1a#)TQ=l$1tQ z=tL9&_^vJ)Pk}EDO-va`UCT1m#Uty1{v^A3P~83_#v^ozH}6*9mIjIr;t3Uv%@VeW zGL6(CwCUp)Jq%G0bIG%?{_*Y#5IHf*5M@wPo6A{$Um++Co$wLC=J1aoG93&T7Ho}P z=mGEPP7GbvoG!uD$k(H3A$Z))+i{Hy?QHdk>3xSBXR0j!11O^mEe9RHmw!pvzv?Ua~2_l2Yh~_!s1qS`|0~0)YsbHSz8!mG)WiJE| z2f($6TQtt6L_f~ApQYQKSb=`053LgrQq7G@98#igV>y#i==-nEjQ!XNu9 z~;mE+gtj4IDDNQJ~JVk5Ux6&LCSFL!y=>79kE9=V}J7tD==Ga+IW zX)r7>VZ9dY=V&}DR))xUoV!u(Z|%3ciQi_2jl}3=$Agc(`RPb z8kEBpvY>1FGQ9W$n>Cq=DIpski};nE)`p3IUw1Oz0|wxll^)4dq3;CCY@RyJgFgc# zKouFh!`?Xuo{IMz^xi-h=StCis_M7yq$u) z?XHvw*HP0VgR+KR6wI)jEMX|ssqYvSf*_3W8zVTQzD?3>H!#>InzpSO)@SC8q*ii- z%%h}_#0{4JG;Jm`4zg};BPTGkYamx$Xo#O~lBirRY)q=5M45n{GCfV7h9qwyu1NxOMoP4)jjZMxmT|IQQh0U7C$EbnMN<3)Kk?fFHYq$d|ICu>KbY_hO zTZM+uKHe(cIZfEqyzyYSUBZa8;Fcut-GN!HSA9ius`ltNebF46ZX_BbZNU}}ZOm{M2&nANL9@0qvih15(|`S~z}m&h!u4x~(%MAO$jHRWNfuxWF#B)E&g3ghSQ9|> z(MFaLQj)NE0lowyjvg8z0#m6FIuKE9lDO~Glg}nSb7`~^&#(Lw{}GVOS>U)m8bF}x zVjbXljBm34Cs-yM6TVusr+3kYFjr28STT3g056y3cH5Tmge~ASxBj z%|yb>$eF;WgrcOZf569sDZOVwoo%8>XO>XQOX1OyN9I-SQgrm;U;+#3OI(zrWyow3 zk==|{lt2xrQ%FIXOTejR>;wv(Pb8u8}BUpx?yd(Abh6? zsoO3VYWkeLnF43&@*#MQ9-i-d0t*xN-UEyNKeyNMHw|A(k(_6QKO=nKMCxD(W(Yop zsRQ)QeL4X3Lxp^L%wzi2-WVSsf61dqliPUM7srDB?Wm6Lzn0&{*}|IsKQW;02(Y&| zaTKv|`U(pSzuvR6Rduu$wzK_W-Y-7>7s?G$)U}&uK;<>vU}^^ns@Z!p+9?St1s)dG zK%y6xkPyyS1$~&6v{kl?Md6gwM|>mt6Upm>oa8RLD^8T{0?HC!Z>;(Bob7el(DV6x zi`I)$&E&ngwFS@bi4^xFLAn`=fzTC;aimE^!cMI2n@Vo%Ae-ne`RF((&5y6xsjjAZ zVguVoQ?Z9uk$2ON;ersE%PU*xGO@T*;j1BO5#TuZKEf(mB7|g7pcEA=nYJ{s3vlbg zd4-DUlD{*6o%Gc^N!Nptgay>j6E5;3psI+C3Q!1ZIbeCubW%w4pq9)MSDyB{HLm|k zxv-{$$A*pS@csolri$Ge<4VZ}e~78JOL-EVyrbxKra^d{?|NnPp86!q>t<&IP07?Z z^>~IK^k#OEKgRH+LjllZXk7iA>2cfH6+(e&9ku5poo~6y{GC5>(bRK7hwjiurqAiZ zg*DmtgY}v83IjE&AbiWgMyFbaRUPZ{lYiz$U^&Zt2YjG<%m((&_JUbZcfJ22(>bi5 z!J?<7AySj0JZ&<-qXX;mcV!f~>G=sB0KnjWca4}vrtunD^1TrpfeS^4dvFr!65knK zZh`d;*VOkPs4*-9kL>$GP0`(M!j~B;#x?Ba~&s6CopvO86oM?-? zOw#dIRc;6A6T?B`Qp%^<U5 z19x(ywSH$_N+Io!6;e?`tWaM$`=Db!gzx|lQ${DG!zb1Zl&|{kX0y6xvO1o z220r<-oaS^^R2pEyY;=Qllqpmue|5yI~D|iI!IGt@iod{Opz@*ml^w2bNs)p`M(Io z|E;;m*Xpjd9l)4G#KaWfV(t8YUn@A;nK^#xgv=LtnArX|vWQVuw3}B${h+frU2>9^ z!l6)!Uo4`5k`<<;E(ido7M6lKTgWezNLq>U*=uz&s=cc$1%>VrAeOoUtA|T6gO4>UNqsdK=NF*8|~*sl&wI=x9-EGiq*aqV!(VVXA57 zw9*o6Ir8Lj1npUXvlevtn(_+^X5rzdR>#(}4YcB9O50q97%rW2me5_L=%ffYPUSRc z!vv?Kv>dH994Qi>U(a<0KF6NH5b16enCp+mw^Hb3Xs1^tThFpz!3QuN#}KBbww`(h z7GO)1olDqy6?T$()R7y%NYx*B0k_2IBiZ14&8|JPFxeMF{vW>HF-Vi3+ZOI=+qP}n zw(+!WcTd~4ZJX1!ZM&y!+uyt=&i!+~d(V%GjH;-NsEEv6nS1TERt|RHh!0>W4+4pp z1-*EzAM~i`+1f(VEHI8So`S`akPfPTfq*`l{Fz`hS%k#JS0cjT2mS0#QLGf=J?1`he3W*;m4)ce8*WFq1sdP=~$5RlH1EdWm|~dCvKOi4*I_96{^95p#B<(n!d?B z=o`0{t+&OMwKcxiBECznJcfH!fL(z3OvmxP#oWd48|mMjpE||zdiTBdWelj8&Qosv zZFp@&UgXuvJw5y=q6*28AtxZzo-UUpkRW%ne+Ylf!V-0+uQXBW=5S1o#6LXNtY5!I z%Rkz#(S8Pjz*P7bqB6L|M#Er{|QLae-Y{KA>`^} z@lPjeX>90X|34S-7}ZVXe{wEei1<{*e8T-Nbj8JmD4iwcE+Hg_zhkPVm#=@b$;)h6 z<<6y`nPa`f3I6`!28d@kdM{uJOgM%`EvlQ5B2bL)Sl=|y@YB3KeOzz=9cUW3clPAU z^sYc}xf9{4Oj?L5MOlYxR{+>w=vJjvbyO5}ptT(o6dR|ygO$)nVCvNGnq(6;bHlBd zl?w-|plD8spjDF03g5ip;W3Z z><0{BCq!Dw;h5~#1BuQilq*TwEu)qy50@+BE4bX28+7erX{BD4H)N+7U`AVEuREE8 z;X?~fyhF-x_sRfHIj~6f(+^@H)D=ngP;mwJjxhQUbUdzk8f94Ab%59-eRIq?ZKrwD z(BFI=)xrUlgu(b|hAysqK<}8bslmNNeD=#JW*}^~Nrswn^xw*nL@Tx!49bfJecV&KC2G4q5a!NSv)06A_5N3Y?veAz;Gv+@U3R% z)~UA8-0LvVE{}8LVDOHzp~2twReqf}ODIyXMM6=W>kL|OHcx9P%+aJGYi_Om)b!xe zF40Vntn0+VP>o<$AtP&JANjXBn7$}C@{+@3I@cqlwR2MdwGhVPxlTIcRVu@Ho-wO` z_~Or~IMG)A_`6-p)KPS@cT9mu9RGA>dVh5wY$NM9-^c@N=hcNaw4ITjm;iWSP^ZX| z)_XpaI61<+La+U&&%2a z0za$)-wZP@mwSELo#3!PGTt$uy0C(nTT@9NX*r3Ctw6J~7A(m#8fE)0RBd`TdKfAT zCf@$MAxjP`O(u9s@c0Fd@|}UQ6qp)O5Q5DPCeE6mSIh|Rj{$cAVIWsA=xPKVKxdhg zLzPZ`3CS+KIO;T}0Ip!fAUaNU>++ZJZRk@I(h<)RsJUhZ&Ru9*!4Ptn;gX^~4E8W^TSR&~3BAZc#HquXn)OW|TJ`CTahk+{qe`5+ixON^zA9IFd8)kc%*!AiLu z>`SFoZ5bW-%7}xZ>gpJcx_hpF$2l+533{gW{a7ce^B9sIdmLrI0)4yivZ^(Vh@-1q zFT!NQK$Iz^xu%|EOK=n>ug;(7J4OnS$;yWmq>A;hsD_0oAbLYhW^1Vdt9>;(JIYjf zdb+&f&D4@4AS?!*XpH>8egQvSVX`36jMd>$+RgI|pEg))^djhGSo&#lhS~9%NuWfX zDDH;3T*GzRT@5=7ibO>N-6_XPBYxno@mD_3I#rDD?iADxX`! zh*v8^i*JEMzyN#bGEBz7;UYXki*Xr(9xXax(_1qVW=Ml)kSuvK$coq2A(5ZGhs_pF z$*w}FbN6+QDseuB9=fdp_MTs)nQf!2SlROQ!gBJBCXD&@-VurqHj0wm@LWX-TDmS= z71M__vAok|@!qgi#H&H%Vg-((ZfxPAL8AI{x|VV!9)ZE}_l>iWk8UPTGHs*?u7RfP z5MC&=c6X;XlUzrz5q?(!eO@~* zoh2I*%J7dF!!_!vXoSIn5o|wj1#_>K*&CIn{qSaRc&iFVxt*^20ngCL;QonIS>I5^ zMw8HXm>W0PGd*}Ko)f|~dDd%;Wu_RWI_d;&2g6R3S63Uzjd7dn%Svu-OKpx*o|N>F zZg=-~qLb~VRLpv`k zWSdfHh@?dp=s_X`{yxOlxE$4iuyS;Z-x!*E6eqmEm*j2bE@=ZI0YZ5%Yj29!5+J$4h{s($nakA`xgbO8w zi=*r}PWz#lTL_DSAu1?f%-2OjD}NHXp4pXOsCW;DS@BC3h-q4_l`<))8WgzkdXg3! zs1WMt32kS2E#L0p_|x+x**TFV=gn`m9BWlzF{b%6j-odf4{7a4y4Uaef@YaeuPhU8 zHBvRqN^;$Jizy+ z=zW{E5<>2gp$pH{M@S*!sJVQU)b*J5*bX4h>5VJve#Q6ga}cQ&iL#=(u+KroWrxa%8&~p{WEUF0il=db;-$=A;&9M{Rq`ouZ5m%BHT6%st%saGsD6)fQgLN}x@d3q>FC;=f%O3Cyg=Ke@Gh`XW za@RajqOE9UB6eE=zhG%|dYS)IW)&y&Id2n7r)6p_)vlRP7NJL(x4UbhlcFXWT8?K=%s7;z?Vjts?y2+r|uk8Wt(DM*73^W%pAkZa1Jd zNoE)8FvQA>Z`eR5Z@Ig6kS5?0h;`Y&OL2D&xnnAUzQz{YSdh0k zB3exx%A2TyI)M*EM6htrxSlep!Kk(P(VP`$p0G~f$smld6W1r_Z+o?=IB@^weq>5VYsYZZR@` z&XJFxd5{|KPZmVOSxc@^%71C@;z}}WhbF9p!%yLj3j%YOlPL5s>7I3vj25 z@xmf=*z%Wb4;Va6SDk9cv|r*lhZ`(y_*M@>q;wrn)oQx%B(2A$9(74>;$zmQ!4fN; z>XurIk-7@wZys<+7XL@0Fhe-f%*=(weaQEdR9Eh6>Kl-EcI({qoZqyzziGwpg-GM#251sK_ z=3|kitS!j%;fpc@oWn65SEL73^N&t>Ix37xgs= zYG%eQDJc|rqHFia0!_sm7`@lvcv)gfy(+KXA@E{3t1DaZ$DijWAcA)E0@X?2ziJ{v z&KOYZ|DdkM{}t+@{@*6ge}m%xfjIxi%qh`=^2Rwz@w0cCvZ&Tc#UmCDbVwABrON^x zEBK43FO@weA8s7zggCOWhMvGGE`baZ62cC)VHyy!5Zbt%ieH+XN|OLbAFPZWyC6)p z4P3%8sq9HdS3=ih^0OOlqTPbKuzQ?lBEI{w^ReUO{V?@`ARsL|S*%yOS=Z%sF)>-y z(LAQdhgAcuF6LQjRYfdbD1g4o%tV4EiK&ElLB&^VZHbrV1K>tHTO{#XTo>)2UMm`2 z^t4s;vnMQgf-njU-RVBRw0P0-m#d-u`(kq7NL&2T)TjI_@iKuPAK-@oH(J8?%(e!0Ir$yG32@CGUPn5w4)+9@8c&pGx z+K3GKESI4*`tYlmMHt@br;jBWTei&(a=iYslc^c#RU3Q&sYp zSG){)V<(g7+8W!Wxeb5zJb4XE{I|&Y4UrFWr%LHkdQ;~XU zgy^dH-Z3lmY+0G~?DrC_S4@=>0oM8Isw%g(id10gWkoz2Q%7W$bFk@mIzTCcIB(K8 zc<5h&ZzCdT=9n-D>&a8vl+=ZF*`uTvQviG_bLde*k>{^)&0o*b05x$MO3gVLUx`xZ z43j+>!u?XV)Yp@MmG%Y`+COH2?nQcMrQ%k~6#O%PeD_WvFO~Kct za4XoCM_X!c5vhRkIdV=xUB3xI2NNStK*8_Zl!cFjOvp-AY=D;5{uXj}GV{LK1~IE2 z|KffUiBaStRr;10R~K2VVtf{TzM7FaPm;Y(zQjILn+tIPSrJh&EMf6evaBKIvi42-WYU9Vhj~3< zZSM-B;E`g_o8_XTM9IzEL=9Lb^SPhe(f(-`Yh=X6O7+6ALXnTcUFpI>ekl6v)ZQeNCg2 z^H|{SKXHU*%nBQ@I3It0m^h+6tvI@FS=MYS$ZpBaG7j#V@P2ZuYySbp@hA# ze(kc;P4i_-_UDP?%<6>%tTRih6VBgScKU^BV6Aoeg6Uh(W^#J^V$Xo^4#Ekp ztqQVK^g9gKMTHvV7nb64UU7p~!B?>Y0oFH5T7#BSW#YfSB@5PtE~#SCCg3p^o=NkMk$<8- z6PT*yIKGrvne7+y3}_!AC8NNeI?iTY(&nakN>>U-zT0wzZf-RuyZk^X9H-DT_*wk= z;&0}6LsGtfVa1q)CEUPlx#(ED@-?H<1_FrHU#z5^P3lEB|qsxEyn%FOpjx z3S?~gvoXy~L(Q{Jh6*i~=f%9kM1>RGjBzQh_SaIDfSU_9!<>*Pm>l)cJD@wlyxpBV z4Fmhc2q=R_wHCEK69<*wG%}mgD1=FHi4h!98B-*vMu4ZGW~%IrYSLGU{^TuseqVgV zLP<%wirIL`VLyJv9XG_p8w@Q4HzNt-o;U@Au{7%Ji;53!7V8Rv0^Lu^Vf*sL>R(;c zQG_ZuFl)Mh-xEIkGu}?_(HwkB2jS;HdPLSxVU&Jxy9*XRG~^HY(f0g8Q}iqnVmgjI zfd=``2&8GsycjR?M%(zMjn;tn9agcq;&rR!Hp z$B*gzHsQ~aXw8c|a(L^LW(|`yGc!qOnV(ZjU_Q-4z1&0;jG&vAKuNG=F|H?@m5^N@ zq{E!1n;)kNTJ>|Hb2ODt-7U~-MOIFo%9I)_@7fnX+eMMNh>)V$IXesJpBn|uo8f~#aOFytCT zf9&%MCLf8mp4kwHTcojWmM3LU=#|{3L>E}SKwOd?%{HogCZ_Z1BSA}P#O(%H$;z7XyJ^sjGX;j5 zrzp>|Ud;*&VAU3x#f{CKwY7Vc{%TKKqmB@oTHA9;>?!nvMA;8+Jh=cambHz#J18x~ zs!dF>$*AnsQ{{82r5Aw&^7eRCdvcgyxH?*DV5(I$qXh^zS>us*I66_MbL8y4d3ULj z{S(ipo+T3Ag!+5`NU2sc+@*m{_X|&p#O-SAqF&g_n7ObB82~$p%fXA5GLHMC+#qqL zdt`sJC&6C2)=juQ_!NeD>U8lDVpAOkW*khf7MCcs$A(wiIl#B9HM%~GtQ^}yBPjT@ z+E=|A!Z?A(rwzZ;T}o6pOVqHzTr*i;Wrc%&36kc@jXq~+w8kVrs;%=IFdACoLAcCAmhFNpbP8;s`zG|HC2Gv?I~w4ITy=g$`0qMQdkijLSOtX6xW%Z9Nw<;M- zMN`c7=$QxN00DiSjbVt9Mi6-pjv*j(_8PyV-il8Q-&TwBwH1gz1uoxs6~uU}PrgWB zIAE_I-a1EqlIaGQNbcp@iI8W1sm9fBBNOk(k&iLBe%MCo#?xI$%ZmGA?=)M9D=0t7 zc)Q0LnI)kCy{`jCGy9lYX%mUsDWwsY`;jE(;Us@gmWPqjmXL+Hu#^;k%eT>{nMtzj zsV`Iy6leTA8-PndszF;N^X@CJrTw5IIm!GPeu)H2#FQitR{1p;MasQVAG3*+=9FYK zw*k!HT(YQorfQj+1*mCV458(T5=fH`um$gS38hw(OqVMyunQ;rW5aPbF##A3fGH6h z@W)i9Uff?qz`YbK4c}JzQpuxuE3pcQO)%xBRZp{zJ^-*|oryTxJ-rR+MXJ)!f=+pp z10H|DdGd2exhi+hftcYbM0_}C0ZI-2vh+$fU1acsB-YXid7O|=9L!3e@$H*6?G*Zp z%qFB(sgl=FcC=E4CYGp4CN>=M8#5r!RU!u+FJVlH6=gI5xHVD&k;Ta*M28BsxfMV~ zLz+@6TxnfLhF@5=yQo^1&S}cmTN@m!7*c6z;}~*!hNBjuE>NLVl2EwN!F+)0$R1S! zR|lF%n!9fkZ@gPW|x|B={V6x3`=jS*$Pu0+5OWf?wnIy>Y1MbbGSncpKO0qE(qO=ts z!~@&!N`10S593pVQu4FzpOh!tvg}p%zCU(aV5=~K#bKi zHdJ1>tQSrhW%KOky;iW+O_n;`l9~omqM%sdxdLtI`TrJzN6BQz+7xOl*rM>xVI2~# z)7FJ^Dc{DC<%~VS?@WXzuOG$YPLC;>#vUJ^MmtbSL`_yXtNKa$Hk+l-c!aC7gn(Cg ze?YPYZ(2Jw{SF6MiO5(%_pTo7j@&DHNW`|lD`~{iH+_eSTS&OC*2WTT*a`?|9w1dh zh1nh@$a}T#WE5$7Od~NvSEU)T(W$p$s5fe^GpG+7fdJ9=enRT9$wEk+ZaB>G3$KQO zgq?-rZZnIv!p#>Ty~}c*Lb_jxJg$eGM*XwHUwuQ|o^}b3^T6Bxx{!?va8aC@-xK*H ztJBFvFfsSWu89%@b^l3-B~O!CXs)I6Y}y#0C0U0R0WG zybjroj$io0j}3%P7zADXOwHwafT#uu*zfM!oD$6aJx7+WL%t-@6^rD_a_M?S^>c;z zMK580bZXo1f*L$CuMeM4Mp!;P@}b~$cd(s5*q~FP+NHSq;nw3fbWyH)i2)-;gQl{S zZO!T}A}fC}vUdskGSq&{`oxt~0i?0xhr6I47_tBc`fqaSrMOzR4>0H^;A zF)hX1nfHs)%Zb-(YGX;=#2R6C{BG;k=?FfP?9{_uFLri~-~AJ;jw({4MU7e*d)?P@ zXX*GkNY9ItFjhwgAIWq7Y!ksbMzfqpG)IrqKx9q{zu%Mdl+{Dis#p9q`02pr1LG8R z@As?eG!>IoROgS!@J*to<27coFc1zpkh?w=)h9CbYe%^Q!Ui46Y*HO0mr% zEff-*$ndMNw}H2a5@BsGj5oFfd!T(F&0$<{GO!Qdd?McKkorh=5{EIjDTHU`So>8V zBA-fqVLb2;u7UhDV1xMI?y>fe3~4urv3%PX)lDw+HYa;HFkaLqi4c~VtCm&Ca+9C~ zge+67hp#R9`+Euq59WhHX&7~RlXn=--m8$iZ~~1C8cv^2(qO#X0?vl91gzUKBeR1J z^p4!!&7)3#@@X&2aF2-)1Ffcc^F8r|RtdL2X%HgN&XU-KH2SLCbpw?J5xJ*!F-ypZ zMG%AJ!Pr&}`LW?E!K~=(NJxuSVTRCGJ$2a*Ao=uUDSys!OFYu!Vs2IT;xQ6EubLIl z+?+nMGeQQhh~??0!s4iQ#gm3!BpMpnY?04kK375e((Uc7B3RMj;wE?BCoQGu=UlZt!EZ1Q*auI)dj3Jj{Ujgt zW5hd~-HWBLI_3HuO) zNrb^XzPsTIb=*a69wAAA3J6AAZZ1VsYbIG}a`=d6?PjM)3EPaDpW2YP$|GrBX{q*! z$KBHNif)OKMBCFP5>!1d=DK>8u+Upm-{hj5o|Wn$vh1&K!lVfDB&47lw$tJ?d5|=B z^(_9=(1T3Fte)z^>|3**n}mIX;mMN5v2F#l(q*CvU{Ga`@VMp#%rQkDBy7kYbmb-q z<5!4iuB#Q_lLZ8}h|hPODI^U6`gzLJre9u3k3c#%86IKI*^H-@I48Bi*@avYm4v!n0+v zWu{M{&F8#p9cx+gF0yTB_<2QUrjMPo9*7^-uP#~gGW~y3nfPAoV%amgr>PSyVAd@l)}8#X zR5zV6t*uKJZL}?NYvPVK6J0v4iVpwiN|>+t3aYiZSp;m0!(1`bHO}TEtWR1tY%BPB z(W!0DmXbZAsT$iC13p4f>u*ZAy@JoLAkJhzFf1#4;#1deO8#8d&89}en&z!W&A3++^1(;>0SB1*54d@y&9Pn;^IAf3GiXbfT`_>{R+Xv; zQvgL>+0#8-laO!j#-WB~(I>l0NCMt_;@Gp_f0#^c)t?&#Xh1-7RR0@zPyBz!U#0Av zT?}n({(p?p7!4S2ZBw)#KdCG)uPnZe+U|0{BW!m)9 zi_9$F?m<`2!`JNFv+w8MK_K)qJ^aO@7-Ig>cM4-r0bi=>?B_2mFNJ}aE3<+QCzRr*NA!QjHw# z`1OsvcoD0?%jq{*7b!l|L1+Tw0TTAM4XMq7*ntc-Ived>Sj_ZtS|uVdpfg1_I9knY z2{GM_j5sDC7(W&}#s{jqbybqJWyn?{PW*&cQIU|*v8YGOKKlGl@?c#TCnmnAkAzV- zmK={|1G90zz=YUvC}+fMqts0d4vgA%t6Jhjv?d;(Z}(Ep8fTZfHA9``fdUHkA+z3+ zhh{ohP%Bj?T~{i0sYCQ}uC#5BwN`skI7`|c%kqkyWIQ;!ysvA8H`b-t()n6>GJj6xlYDu~8qX{AFo$Cm3d|XFL=4uvc?Keb zzb0ZmMoXca6Mob>JqkNuoP>B2Z>D`Q(TvrG6m`j}-1rGP!g|qoL=$FVQYxJQjFn33lODt3Wb1j8VR zlR++vIT6^DtYxAv_hxupbLLN3e0%A%a+hWTKDV3!Fjr^cWJ{scsAdfhpI)`Bms^M6 zQG$waKgFr=c|p9Piug=fcJvZ1ThMnNhQvBAg-8~b1?6wL*WyqXhtj^g(Ke}mEfZVM zJuLNTUVh#WsE*a6uqiz`b#9ZYg3+2%=C(6AvZGc=u&<6??!slB1a9K)=VL zY9EL^mfyKnD zSJyYBc_>G;5RRnrNgzJz#Rkn3S1`mZgO`(r5;Hw6MveN(URf_XS-r58Cn80K)ArH4 z#Rrd~LG1W&@ttw85cjp8xV&>$b%nSXH_*W}7Ch2pg$$c0BdEo-HWRTZcxngIBJad> z;C>b{jIXjb_9Jis?NZJsdm^EG}e*pR&DAy0EaSGi3XWTa(>C%tz1n$u?5Fb z1qtl?;_yjYo)(gB^iQq?=jusF%kywm?CJP~zEHi0NbZ);$(H$w(Hy@{i>$wcVRD_X|w-~(0Z9BJyh zhNh;+eQ9BEIs;tPz%jSVnfCP!3L&9YtEP;svoj_bNzeGSQIAjd zBss@A;)R^WAu-37RQrM%{DfBNRx>v!G31Z}8-El9IOJlb_MSoMu2}GDYycNaf>uny z+8xykD-7ONCM!APry_Lw6-yT>5!tR}W;W`C)1>pxSs5o1z#j7%m=&=7O4hz+Lsqm` z*>{+xsabZPr&X=}G@obTb{nPTkccJX8w3CG7X+1+t{JcMabv~UNv+G?txRqXib~c^Mo}`q{$`;EBNJ;#F*{gvS12kV?AZ%O0SFB$^ zn+}!HbmEj}w{Vq(G)OGAzH}R~kS^;(-s&=ectz8vN!_)Yl$$U@HNTI-pV`LSj7Opu zTZ5zZ)-S_{GcEQPIQXLQ#oMS`HPu{`SQiAZ)m1at*Hy%3xma|>o`h%E%8BEbi9p0r zVjcsh<{NBKQ4eKlXU|}@XJ#@uQw*$4BxKn6#W~I4T<^f99~(=}a`&3(ur8R9t+|AQ zWkQx7l}wa48-jO@ft2h+7qn%SJtL%~890FG0s5g*kNbL3I&@brh&f6)TlM`K^(bhr zJWM6N6x3flOw$@|C@kPi7yP&SP?bzP-E|HSXQXG>7gk|R9BTj`e=4de9C6+H7H7n# z#GJeVs1mtHhLDmVO?LkYRQc`DVOJ_vdl8VUihO-j#t=0T3%Fc1f9F73ufJz*adn*p zc%&vi(4NqHu^R>sAT_0EDjVR8bc%wTz#$;%NU-kbDyL_dg0%TFafZwZ?5KZpcuaO54Z9hX zD$u>q!-9`U6-D`E#`W~fIfiIF5_m6{fvM)b1NG3xf4Auw;Go~Fu7cth#DlUn{@~yu z=B;RT*dp?bO}o%4x7k9v{r=Y@^YQ^UUm(Qmliw8brO^=NP+UOohLYiaEB3^DB56&V zK?4jV61B|1Uj_5fBKW;8LdwOFZKWp)g{B%7g1~DgO&N& z#lisxf?R~Z@?3E$Mms$$JK8oe@X`5m98V*aV6Ua}8Xs2#A!{x?IP|N(%nxsH?^c{& z@vY&R1QmQs83BW28qAmJfS7MYi=h(YK??@EhjL-t*5W!p z^gYX!Q6-vBqcv~ruw@oMaU&qp0Fb(dbVzm5xJN%0o_^@fWq$oa3X?9s%+b)x4w-q5Koe(@j6Ez7V@~NRFvd zfBH~)U5!ix3isg`6be__wBJp=1@yfsCMw1C@y+9WYD9_C%{Q~7^0AF2KFryfLlUP# zwrtJEcH)jm48!6tUcxiurAMaiD04C&tPe6DI0#aoqz#Bt0_7_*X*TsF7u*zv(iEfA z;$@?XVu~oX#1YXtceQL{dSneL&*nDug^OW$DSLF0M1Im|sSX8R26&)<0Fbh^*l6!5wfSu8MpMoh=2l z^^0Sr$UpZp*9oqa23fcCfm7`ya2<4wzJ`Axt7e4jJrRFVf?nY~2&tRL* zd;6_njcz01c>$IvN=?K}9ie%Z(BO@JG2J}fT#BJQ+f5LFSgup7i!xWRKw6)iITjZU z%l6hPZia>R!`aZjwCp}I zg)%20;}f+&@t;(%5;RHL>K_&7MH^S+7<|(SZH!u zznW|jz$uA`P9@ZWtJgv$EFp>)K&Gt+4C6#*khZQXS*S~6N%JDT$r`aJDs9|uXWdbg zBwho$phWx}x!qy8&}6y5Vr$G{yGSE*r$^r{}pw zVTZKvikRZ`J_IJrjc=X1uw?estdwm&bEahku&D04HD+0Bm~q#YGS6gp!KLf$A{%Qd z&&yX@Hp>~(wU{|(#U&Bf92+1i&Q*-S+=y=3pSZy$#8Uc$#7oiJUuO{cE6=tsPhwPe| zxQpK>`Dbka`V)$}e6_OXKLB%i76~4N*zA?X+PrhH<&)}prET;kel24kW%+9))G^JI zsq7L{P}^#QsZViX%KgxBvEugr>ZmFqe^oAg?{EI=&_O#e)F3V#rc z8$4}0Zr19qd3tE4#$3_f=Bbx9oV6VO!d3(R===i-7p=Vj`520w0D3W6lQfY48}!D* z&)lZMG;~er2qBoI2gsX+Ts-hnpS~NYRDtPd^FPzn!^&yxRy#CSz(b&E*tL|jIkq|l zf%>)7Dtu>jCf`-7R#*GhGn4FkYf;B$+9IxmqH|lf6$4irg{0ept__%)V*R_OK=T06 zyT_m-o@Kp6U{l5h>W1hGq*X#8*y@<;vsOFqEjTQXFEotR+{3}ODDnj;o0@!bB5x=N z394FojuGOtVKBlVRLtHp%EJv_G5q=AgF)SKyRN5=cGBjDWv4LDn$IL`*=~J7u&Dy5 zrMc83y+w^F&{?X(KOOAl-sWZDb{9X9#jrQtmrEXD?;h-}SYT7yM(X_6qksM=K_a;Z z3u0qT0TtaNvDER_8x*rxXw&C^|h{P1qxK|@pS7vdlZ#P z7PdB7MmC2}%sdzAxt>;WM1s0??`1983O4nFK|hVAbHcZ3x{PzytQLkCVk7hA!Lo` zEJH?4qw|}WH{dc4z%aB=0XqsFW?^p=X}4xnCJXK%c#ItOSjdSO`UXJyuc8bh^Cf}8 z@Ht|vXd^6{Fgai8*tmyRGmD_s_nv~r^Fy7j`Bu`6=G)5H$i7Q7lvQnmea&TGvJp9a|qOrUymZ$6G|Ly z#zOCg++$3iB$!6!>215A4!iryregKuUT344X)jQb3|9qY>c0LO{6Vby05n~VFzd?q zgGZv&FGlkiH*`fTurp>B8v&nSxNz)=5IF$=@rgND4d`!AaaX;_lK~)-U8la_Wa8i?NJC@BURO*sUW)E9oyv3RG^YGfN%BmxzjlT)bp*$<| zX3tt?EAy<&K+bhIuMs-g#=d1}N_?isY)6Ay$mDOKRh z4v1asEGWoAp=srraLW^h&_Uw|6O+r;wns=uwYm=JN4Q!quD8SQRSeEcGh|Eb5Jg8m zOT}u;N|x@aq)=&;wufCc^#)5U^VcZw;d_wwaoh9$p@Xrc{DD6GZUqZ ziC6OT^zSq@-lhbgR8B+e;7_Giv;DK5gn^$bs<6~SUadiosfewWDJu`XsBfOd1|p=q zE>m=zF}!lObA%ePey~gqU8S6h-^J2Y?>7)L2+%8kV}Gp=h`Xm_}rlm)SyUS=`=S7msKu zC|T!gPiI1rWGb1z$Md?0YJQ;%>uPLOXf1Z>N~`~JHJ!^@D5kSXQ4ugnFZ>^`zH8CAiZmp z6Ms|#2gcGsQ{{u7+Nb9sA?U>(0e$5V1|WVwY`Kn)rsnnZ4=1u=7u!4WexZD^IQ1Jk zfF#NLe>W$3m&C^ULjdw+5|)-BSHwpegdyt9NYC{3@QtMfd8GrIWDu`gd0nv-3LpGCh@wgBaG z176tikL!_NXM+Bv#7q^cyn9$XSeZR6#!B4JE@GVH zoobHZN_*RF#@_SVYKkQ_igme-Y5U}cV(hkR#k1c{bQNMji zU7aE`?dHyx=1`kOYZo_8U7?3-7vHOp`Qe%Z*i+FX!s?6huNp0iCEW-Z7E&jRWmUW_ z67j>)Ew!yq)hhG4o?^z}HWH-e=es#xJUhDRc4B51M4~E-l5VZ!&zQq`gWe`?}#b~7w1LH4Xa-UCT5LXkXQWheBa2YJYbyQ zl1pXR%b(KCXMO0OsXgl0P0Og<{(@&z1aokU-Pq`eQq*JYgt8xdFQ6S z6Z3IFSua8W&M#`~*L#r>Jfd6*BzJ?JFdBR#bDv$_0N!_5vnmo@!>vULcDm`MFU823 zpG9pqjqz^FE5zMDoGqhs5OMmC{Y3iVcl>F}5Rs24Y5B^mYQ;1T&ks@pIApHOdrzXF z-SdX}Hf{X;TaSxG_T$0~#RhqKISGKNK47}0*x&nRIPtmdwxc&QT3$8&!3fWu1eZ_P zJveQj^hJL#Sn!*4k`3}(d(aasl&7G0j0-*_2xtAnoX1@9+h zO#c>YQg60Z;o{Bi=3i7S`Ic+ZE>K{(u|#)9y}q*j8uKQ1^>+(BI}m%1v3$=4ojGBc zm+o1*!T&b}-lVvZqIUBc8V}QyFEgm#oyIuC{8WqUNV{Toz`oxhYpP!_p2oHHh5P@iB*NVo~2=GQm+8Yrkm2Xjc_VyHg1c0>+o~@>*Qzo zHVBJS>$$}$_4EniTI;b1WShX<5-p#TPB&!;lP!lBVBbLOOxh6FuYloD%m;n{r|;MU3!q4AVkua~fieeWu2 zQAQ$ue(IklX6+V;F1vCu-&V?I3d42FgWgsb_e^29ol}HYft?{SLf>DrmOp9o!t>I^ zY7fBCk+E8n_|apgM|-;^=#B?6RnFKlN`oR)`e$+;D=yO-(U^jV;rft^G_zl`n7qnM zL z*-Y4Phq+ZI1$j$F-f;`CD#|`-T~OM5Q>x}a>B~Gb3-+9i>Lfr|Ca6S^8g*{*?_5!x zH_N!SoRP=gX1?)q%>QTY!r77e2j9W(I!uAz{T`NdNmPBBUzi2{`XMB^zJGGwFWeA9 z{fk33#*9SO0)DjROug+(M)I-pKA!CX;IY(#gE!UxXVsa)X!UftIN98{pt#4MJHOhY zM$_l}-TJlxY?LS6Nuz1T<44m<4i^8k@D$zuCPrkmz@sdv+{ciyFJG2Zwy&%c7;atIeTdh!a(R^QXnu1Oq1b42*OQFWnyQ zWeQrdvP|w_idy53Wa<{QH^lFmEd+VlJkyiC>6B#s)F;w-{c;aKIm;Kp50HnA-o3lY z9B~F$gJ@yYE#g#X&3ADx&tO+P_@mnQTz9gv30_sTsaGXkfNYXY{$(>*PEN3QL>I!k zp)KibPhrfX3%Z$H6SY`rXGYS~143wZrG2;=FLj50+VM6soI~up_>fU(2Wl@{BRsMi zO%sL3x?2l1cXTF)k&moNsHfQrQ+wu(gBt{sk#CU=UhrvJIncy@tJX5klLjgMn>~h= zg|FR&;@eh|C7`>s_9c~0-{IAPV){l|Ts`i=)AW;d9&KPc3fMeoTS%8@V~D8*h;&(^>yjT84MM}=%#LS7shLAuuj(0VAYoozhWjq z4LEr?wUe2^WGwdTIgWBkDUJa>YP@5d9^Rs$kCXmMRxuF*YMVrn?0NFyPl}>`&dqZb z<5eqR=ZG3>n2{6v6BvJ`YBZeeTtB88TAY(x0a58EWyuf>+^|x8Qa6wA|1Nb_p|nA zWWa}|z8a)--Wj`LqyFk_a3gN2>5{Rl_wbW?#by7&i*^hRknK%jwIH6=dQ8*-_{*x0j^DUfMX0`|K@6C<|1cgZ~D(e5vBFFm;HTZF(!vT8=T$K+|F)x3kqzBV4-=p1V(lzi(s7jdu0>LD#N=$Lk#3HkG!a zIF<7>%B7sRNzJ66KrFV76J<2bdYhxll0y2^_rdG=I%AgW4~)1Nvz=$1UkE^J%BxLo z+lUci`UcU062os*=`-j4IfSQA{w@y|3}Vk?i;&SSdh8n+$iHA#%ERL{;EpXl6u&8@ zzg}?hkEOUOJt?ZL=pWZFJ19mI1@P=$U5*Im1e_8Z${JsM>Ov?nh8Z zP5QvI!{Jy@&BP48%P2{Jr_VgzW;P@7)M9n|lDT|Ep#}7C$&ud&6>C^5ZiwKIg2McPU(4jhM!BD@@L(Gd*Nu$ji(ljZ<{FIeW_1Mmf;76{LU z-ywN~=uNN)Xi6$<12A9y)K%X|(W0p|&>>4OXB?IiYr||WKDOJPxiSe01NSV-h24^L z_>m$;|C+q!Mj**-qQ$L-*++en(g|hw;M!^%_h-iDjFHLo-n3JpB;p?+o2;`*jpvJU zLY^lt)Un4joij^^)O(CKs@7E%*!w>!HA4Q?0}oBJ7Nr8NQ7QmY^4~jvf0-`%waOLn zdNjAPaC0_7c|RVhw)+71NWjRi!y>C+Bl;Z`NiL^zn2*0kmj5gyhCLCxts*cWCdRI| zjsd=sT5BVJc^$GxP~YF$-U{-?kW6r@^vHXB%{CqYzU@1>dzf#3SYedJG-Rm6^RB7s zGM5PR(yKPKR)>?~vpUIeTP7A1sc8-knnJk*9)3t^e%izbdm>Y=W{$wm(cy1RB-19i za#828DMBY+ps#7Y8^6t)=Ea@%Nkt)O6JCx|ybC;Ap}Z@Zw~*}3P>MZLPb4Enxz9Wf zssobT^(R@KuShj8>@!1M7tm|2%-pYYDxz-5`rCbaTCG5{;Uxm z*g=+H1X8{NUvFGzz~wXa%Eo};I;~`37*WrRU&K0dPSB$yk(Z*@K&+mFal^?c zurbqB-+|Kb5|sznT;?Pj!+kgFY1#Dr;_%A(GIQC{3ct|{*Bji%FNa6c-thbpBkA;U zURV!Dr&X{0J}iht#-Qp2=xzuh(fM>zRoiGrYl5ttw2#r34gC41CCOC31m~^UPTK@s z6;A@)7O7_%C)>bnAXerYuAHdE93>j2N}H${zEc6&SbZ|-fiG*-qtGuy-qDelH(|u$ zorf8_T6Zqe#Ub!+e3oSyrskt_HyW_^5lrWt#30l)tHk|j$@YyEkXUOV;6B51L;M@=NIWZXU;GrAa(LGxO%|im%7F<-6N;en0Cr zLH>l*y?pMwt`1*cH~LdBPFY_l;~`N!Clyfr;7w<^X;&(ZiVdF1S5e(+Q%60zgh)s4 zn2yj$+mE=miVERP(g8}G4<85^-5f@qxh2ec?n+$A_`?qN=iyT1?U@t?V6DM~BIlBB z>u~eXm-aE>R0sQy!-I4xtCNi!!qh?R1!kKf6BoH2GG{L4%PAz0{Sh6xpuyI%*~u)s z%rLuFl)uQUCBQAtMyN;%)zFMx4loh7uTfKeB2Xif`lN?2gq6NhWhfz0u5WP9J>=V2 zo{mLtSy&BA!mSzs&CrKWq^y40JF5a&GSXIi2= z{EYb59J4}VwikL4P=>+mc6{($FNE@e=VUwG+KV21;<@lrN`mnz5jYGASyvz7BOG_6(p^eTxD-4O#lROgon;R35=|nj#eHIfJBYPWG>H>`dHKCDZ3`R{-?HO0mE~(5_WYcFmp8sU?wr*UkAQiNDGc6T zA%}GOLXlOWqL?WwfHO8MB#8M8*~Y*gz;1rWWoVSXP&IbKxbQ8+s%4Jnt?kDsq7btI zCDr0PZ)b;B%!lu&CT#RJzm{l{2fq|BcY85`w~3LSK<><@(2EdzFLt9Y_`;WXL6x`0 zDoQ?=?I@Hbr;*VVll1Gmd8*%tiXggMK81a+T(5Gx6;eNb8=uYn z5BG-0g>pP21NPn>$ntBh>`*})Fl|38oC^9Qz>~MAazH%3Q~Qb!ALMf$srexgPZ2@&c~+hxRi1;}+)-06)!#Mq<6GhP z-Q?qmgo${aFBApb5p}$1OJKTClfi8%PpnczyVKkoHw7Ml9e7ikrF0d~UB}i3vizos zXW4DN$SiEV9{faLt5bHy2a>33K%7Td-n5C*N;f&ZqAg#2hIqEb(y<&f4u5BWJ>2^4 z414GosL=Aom#m&=x_v<0-fp1r%oVJ{T-(xnomNJ(Dryv zh?vj+%=II_nV+@NR+(!fZZVM&(W6{6%9cm+o+Z6}KqzLw{(>E86uA1`_K$HqINlb1 zKelh3-jr2I9V?ych`{hta9wQ2c9=MM`2cC{m6^MhlL2{DLv7C^j z$xXBCnDl_;l|bPGMX@*tV)B!c|4oZyftUlP*?$YU9C_eAsuVHJ58?)zpbr30P*C`T z7y#ao`uE-SOG(Pi+`$=e^mle~)pRrdwL5)N;o{gpW21of(QE#U6w%*C~`v-z0QqBML!!5EeYA5IQB0 z^l01c;L6E(iytN!LhL}wfwP7W9PNAkb+)Cst?qg#$n;z41O4&v+8-zPs+XNb-q zIeeBCh#ivnFLUCwfS;p{LC0O7tm+Sf9Jn)~b%uwP{%69;QC)Ok0t%*a5M+=;y8j=v z#!*pp$9@!x;UMIs4~hP#pnfVc!%-D<+wsG@R2+J&%73lK|2G!EQC)O05TCV=&3g)C!lT=czLpZ@Sa%TYuoE?v8T8`V;e$#Zf2_Nj6nvBgh1)2 GZ~q4|mN%#X literal 0 HcmV?d00001 diff --git a/studies/offset_control/gradle/wrapper/gradle-wrapper.properties b/studies/offset_control/gradle/wrapper/gradle-wrapper.properties new file mode 100644 index 00000000..8e975a5f --- /dev/null +++ b/studies/offset_control/gradle/wrapper/gradle-wrapper.properties @@ -0,0 +1,7 @@ +distributionBase=GRADLE_USER_HOME +distributionPath=permwrapper/dists +distributionUrl=https\://services.gradle.org/distributions/gradle-8.11-bin.zip +networkTimeout=10000 +validateDistributionUrl=true +zipStoreBase=GRADLE_USER_HOME +zipStorePath=permwrapper/dists diff --git a/studies/offset_control/gradlew b/studies/offset_control/gradlew new file mode 100755 index 00000000..f5feea6d --- /dev/null +++ b/studies/offset_control/gradlew @@ -0,0 +1,252 @@ +#!/bin/sh + +# +# Copyright © 2015-2021 the original authors. +# +# 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 +# +# https://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. +# +# SPDX-License-Identifier: Apache-2.0 +# + +############################################################################## +# +# Gradle start up script for POSIX generated by Gradle. +# +# Important for running: +# +# (1) You need a POSIX-compliant shell to run this script. If your /bin/sh is +# noncompliant, but you have some other compliant shell such as ksh or +# bash, then to run this script, type that shell name before the whole +# command line, like: +# +# ksh Gradle +# +# Busybox and similar reduced shells will NOT work, because this script +# requires all of these POSIX shell features: +# * functions; +# * expansions «$var», «${var}», «${var:-default}», «${var+SET}», +# «${var#prefix}», «${var%suffix}», and «$( cmd )»; +# * compound commands having a testable exit status, especially «case»; +# * various built-in commands including «command», «set», and «ulimit». +# +# Important for patching: +# +# (2) This script targets any POSIX shell, so it avoids extensions provided +# by Bash, Ksh, etc; in particular arrays are avoided. +# +# The "traditional" practice of packing multiple parameters into a +# space-separated string is a well documented source of bugs and security +# problems, so this is (mostly) avoided, by progressively accumulating +# options in "$@", and eventually passing that to Java. +# +# Where the inherited environment variables (DEFAULT_JVM_OPTS, JAVA_OPTS, +# and GRADLE_OPTS) rely on word-splitting, this is performed explicitly; +# see the in-line comments for details. +# +# There are tweaks for specific operating systems such as AIX, CygWin, +# Darwin, MinGW, and NonStop. +# +# (3) This script is generated from the Groovy template +# https://github.com/gradle/gradle/blob/HEAD/platforms/jvm/plugins-application/src/main/resources/org/gradle/api/internal/plugins/unixStartScript.txt +# within the Gradle project. +# +# You can find Gradle at https://github.com/gradle/gradle/. +# +############################################################################## + +# Attempt to set APP_HOME + +# Resolve links: $0 may be a link +app_path=$0 + +# Need this for daisy-chained symlinks. +while + APP_HOME=${app_path%"${app_path##*/}"} # leaves a trailing /; empty if no leading path + [ -h "$app_path" ] +do + ls=$( ls -ld "$app_path" ) + link=${ls#*' -> '} + case $link in #( + /*) app_path=$link ;; #( + *) app_path=$APP_HOME$link ;; + esac +done + +# This is normally unused +# shellcheck disable=SC2034 +APP_BASE_NAME=${0##*/} +# Discard cd standard output in case $CDPATH is set (https://github.com/gradle/gradle/issues/25036) +APP_HOME=$( cd -P "${APP_HOME:-./}" > /dev/null && printf '%s +' "$PWD" ) || exit + +# Use the maximum available, or set MAX_FD != -1 to use that value. +MAX_FD=maximum + +warn () { + echo "$*" +} >&2 + +die () { + echo + echo "$*" + echo + exit 1 +} >&2 + +# OS specific support (must be 'true' or 'false'). +cygwin=false +msys=false +darwin=false +nonstop=false +case "$( uname )" in #( + CYGWIN* ) cygwin=true ;; #( + Darwin* ) darwin=true ;; #( + MSYS* | MINGW* ) msys=true ;; #( + NONSTOP* ) nonstop=true ;; +esac + +CLASSPATH=$APP_HOME/gradle/wrapper/gradle-wrapper.jar + + +# Determine the Java command to use to start the JVM. +if [ -n "$JAVA_HOME" ] ; then + if [ -x "$JAVA_HOME/jre/sh/java" ] ; then + # IBM's JDK on AIX uses strange locations for the executables + JAVACMD=$JAVA_HOME/jre/sh/java + else + JAVACMD=$JAVA_HOME/bin/java + fi + if [ ! -x "$JAVACMD" ] ; then + die "ERROR: JAVA_HOME is set to an invalid directory: $JAVA_HOME + +Please set the JAVA_HOME variable in your environment to match the +location of your Java installation." + fi +else + JAVACMD=java + if ! command -v java >/dev/null 2>&1 + then + die "ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. + +Please set the JAVA_HOME variable in your environment to match the +location of your Java installation." + fi +fi + +# Increase the maximum file descriptors if we can. +if ! "$cygwin" && ! "$darwin" && ! "$nonstop" ; then + case $MAX_FD in #( + max*) + # In POSIX sh, ulimit -H is undefined. That's why the result is checked to see if it worked. + # shellcheck disable=SC2039,SC3045 + MAX_FD=$( ulimit -H -n ) || + warn "Could not query maximum file descriptor limit" + esac + case $MAX_FD in #( + '' | soft) :;; #( + *) + # In POSIX sh, ulimit -n is undefined. That's why the result is checked to see if it worked. + # shellcheck disable=SC2039,SC3045 + ulimit -n "$MAX_FD" || + warn "Could not set maximum file descriptor limit to $MAX_FD" + esac +fi + +# Collect all arguments for the java command, stacking in reverse order: +# * args from the command line +# * the main class name +# * -classpath +# * -D...appname settings +# * --module-path (only if needed) +# * DEFAULT_JVM_OPTS, JAVA_OPTS, and GRADLE_OPTS environment variables. + +# For Cygwin or MSYS, switch paths to Windows format before running java +if "$cygwin" || "$msys" ; then + APP_HOME=$( cygpath --path --mixed "$APP_HOME" ) + CLASSPATH=$( cygpath --path --mixed "$CLASSPATH" ) + + JAVACMD=$( cygpath --unix "$JAVACMD" ) + + # Now convert the arguments - kludge to limit ourselves to /bin/sh + for arg do + if + case $arg in #( + -*) false ;; # don't mess with options #( + /?*) t=${arg#/} t=/${t%%/*} # looks like a POSIX filepath + [ -e "$t" ] ;; #( + *) false ;; + esac + then + arg=$( cygpath --path --ignore --mixed "$arg" ) + fi + # Roll the args list around exactly as many times as the number of + # args, so each arg winds up back in the position where it started, but + # possibly modified. + # + # NB: a `for` loop captures its iteration list before it begins, so + # changing the positional parameters here affects neither the number of + # iterations, nor the values presented in `arg`. + shift # remove old arg + set -- "$@" "$arg" # push replacement arg + done +fi + + +# Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. +DEFAULT_JVM_OPTS='"-Xmx64m" "-Xms64m"' + +# Collect all arguments for the java command: +# * DEFAULT_JVM_OPTS, JAVA_OPTS, JAVA_OPTS, and optsEnvironmentVar are not allowed to contain shell fragments, +# and any embedded shellness will be escaped. +# * For example: A user cannot expect ${Hostname} to be expanded, as it is an environment variable and will be +# treated as '${Hostname}' itself on the command line. + +set -- \ + "-Dorg.gradle.appname=$APP_BASE_NAME" \ + -classpath "$CLASSPATH" \ + org.gradle.wrapper.GradleWrapperMain \ + "$@" + +# Stop when "xargs" is not available. +if ! command -v xargs >/dev/null 2>&1 +then + die "xargs is not available" +fi + +# Use "xargs" to parse quoted args. +# +# With -n1 it outputs one arg per line, with the quotes and backslashes removed. +# +# In Bash we could simply go: +# +# readarray ARGS < <( xargs -n1 <<<"$var" ) && +# set -- "${ARGS[@]}" "$@" +# +# but POSIX shell has neither arrays nor command substitution, so instead we +# post-process each arg (as a line of input to sed) to backslash-escape any +# character that might be a shell metacharacter, then use eval to reverse +# that process (while maintaining the separation between arguments), and wrap +# the whole thing up as a single "set" statement. +# +# This will of course break if any of these variables contains a newline or +# an unmatched quote. +# + +eval "set -- $( + printf '%s\n' "$DEFAULT_JVM_OPTS $JAVA_OPTS $GRADLE_OPTS" | + xargs -n1 | + sed ' s~[^-[:alnum:]+,./:=@_]~\\&~g; ' | + tr '\n' ' ' + )" '"$@"' + +exec "$JAVACMD" "$@" diff --git a/studies/offset_control/gradlew.bat b/studies/offset_control/gradlew.bat new file mode 100644 index 00000000..9b42019c --- /dev/null +++ b/studies/offset_control/gradlew.bat @@ -0,0 +1,94 @@ +@rem +@rem Copyright 2015 the original author or authors. +@rem +@rem Licensed under the Apache License, Version 2.0 (the "License"); +@rem you may not use this file except in compliance with the License. +@rem You may obtain a copy of the License at +@rem +@rem https://www.apache.org/licenses/LICENSE-2.0 +@rem +@rem Unless required by applicable law or agreed to in writing, software +@rem distributed under the License is distributed on an "AS IS" BASIS, +@rem WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +@rem See the License for the specific language governing permissions and +@rem limitations under the License. +@rem +@rem SPDX-License-Identifier: Apache-2.0 +@rem + +@if "%DEBUG%"=="" @echo off +@rem ########################################################################## +@rem +@rem Gradle startup script for Windows +@rem +@rem ########################################################################## + +@rem Set local scope for the variables with windows NT shell +if "%OS%"=="Windows_NT" setlocal + +set DIRNAME=%~dp0 +if "%DIRNAME%"=="" set DIRNAME=. +@rem This is normally unused +set APP_BASE_NAME=%~n0 +set APP_HOME=%DIRNAME% + +@rem Resolve any "." and ".." in APP_HOME to make it shorter. +for %%i in ("%APP_HOME%") do set APP_HOME=%%~fi + +@rem Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. +set DEFAULT_JVM_OPTS="-Xmx64m" "-Xms64m" + +@rem Find java.exe +if defined JAVA_HOME goto findJavaFromJavaHome + +set JAVA_EXE=java.exe +%JAVA_EXE% -version >NUL 2>&1 +if %ERRORLEVEL% equ 0 goto execute + +echo. 1>&2 +echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. 1>&2 +echo. 1>&2 +echo Please set the JAVA_HOME variable in your environment to match the 1>&2 +echo location of your Java installation. 1>&2 + +goto fail + +:findJavaFromJavaHome +set JAVA_HOME=%JAVA_HOME:"=% +set JAVA_EXE=%JAVA_HOME%/bin/java.exe + +if exist "%JAVA_EXE%" goto execute + +echo. 1>&2 +echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME% 1>&2 +echo. 1>&2 +echo Please set the JAVA_HOME variable in your environment to match the 1>&2 +echo location of your Java installation. 1>&2 + +goto fail + +:execute +@rem Setup the command line + +set CLASSPATH=%APP_HOME%\gradle\wrapper\gradle-wrapper.jar + + +@rem Execute Gradle +"%JAVA_EXE%" %DEFAULT_JVM_OPTS% %JAVA_OPTS% %GRADLE_OPTS% "-Dorg.gradle.appname=%APP_BASE_NAME%" -classpath "%CLASSPATH%" org.gradle.wrapper.GradleWrapperMain %* + +:end +@rem End local scope for the variables with windows NT shell +if %ERRORLEVEL% equ 0 goto mainEnd + +:fail +rem Set variable GRADLE_EXIT_CONSOLE if you need the _script_ return code instead of +rem the _cmd.exe /c_ return code! +set EXIT_CODE=%ERRORLEVEL% +if %EXIT_CODE% equ 0 set EXIT_CODE=1 +if not ""=="%GRADLE_EXIT_CONSOLE%" exit %EXIT_CODE% +exit /b %EXIT_CODE% + +:mainEnd +if "%OS%"=="Windows_NT" endlocal + +:omega diff --git a/studies/offset_control/offset_control.code-workspace b/studies/offset_control/offset_control.code-workspace new file mode 100644 index 00000000..d3d4fbf1 --- /dev/null +++ b/studies/offset_control/offset_control.code-workspace @@ -0,0 +1,73 @@ +{ + "folders": [ + { + "path": "." + }, + { + "path": "../../lib" + } + ], + "settings": { + "chat.disableAIFeatures": true, + "debug.console.collapseIdenticalLines": false, + "editor.acceptSuggestionOnEnter": "off", + "editor.autoClosingBrackets": "never", + "editor.autoClosingComments": "never", + "editor.autoClosingDelete": "never", + "editor.autoClosingOvertype": "never", + "editor.autoClosingQuotes": "never", + "editor.codeLens": false, + "editor.detectIndentation": false, + "editor.hover.above": true, + "editor.inlayHints.enabled": "off", + "editor.inlineSuggest.enabled": false, + "editor.minimap.enabled": false, + "editor.parameterHints.cycle": false, + "editor.snippetSuggestions": "none", + "editor.stickyScroll.enabled": false, + "editor.stickyScroll.scrollWithEditor": false, + "editor.suggest.showSnippets": false, + "files.autoSave": "afterDelay", + "java.completion.favoriteStaticMembers": [ + "edu.wpi.first.wpilibj2.command.Commands.*", + "org.junit.jupiter.api.Assertions.*", + ], + "java.completion.filteredTypes": [ + "java.awt.*", + "com.sun.*", + "sun.*", + "jdk.*", + "org.graalvm.*", + "io.micrometer.shaded.*", + "java.beans.*", + "java.util.Base64.*", + "java.util.Timer", + "java.sql.*", + "javax.swing.*", + "javax.management.*", + "javax.smartcardio.*", + "edu.wpi.first.math.proto.*", + "edu.wpi.first.math.**.proto.*", + "edu.wpi.first.math.**.struct.*" + ], + "java.completion.guessMethodArguments": "insertBestGuessedArguments", + "java.completion.postfix.enabled": false, + "java.configuration.updateBuildConfiguration": "automatic", + "java.import.gradle.annotationProcessing.enabled": false, + "java.jdt.ls.vmargs": "-XX:+UseParallelGC -XX:GCTimeRatio=4 -XX:AdaptiveSizePolicyWeight=90 -Dsun.zip.disableMemoryMapping=true -Xmx64G -Xms100m -Xlog:disable", + "java.saveActions.organizeImports": false, + "java.server.launchMode": "Standard", + "java.signatureHelp.description.enabled": true, + "java.signatureHelp.enabled": true, + "markdown.preview.scrollEditorWithPreview": false, + "markdown.preview.scrollPreviewWithEditor": false, + "terminal.integrated.scrollback": 100000, + "vsintellicode.java.completionsEnabled": true, + "workbench.colorCustomizations": { + "debugConsole.infoForeground": "#000000" + }, + "workbench.colorTheme": "Default Light Modern", + "workbench.editor.revealIfOpen": true, + "workbench.tree.enableStickyScroll": false + } +} diff --git a/studies/offset_control/settings.gradle b/studies/offset_control/settings.gradle new file mode 100644 index 00000000..3bc070a1 --- /dev/null +++ b/studies/offset_control/settings.gradle @@ -0,0 +1,30 @@ +import org.gradle.internal.os.OperatingSystem + +pluginManagement { + repositories { + mavenLocal() + gradlePluginPortal() + String frcYear = '2025' + File frcHome + if (OperatingSystem.current().isWindows()) { + String publicFolder = System.getenv('PUBLIC') + if (publicFolder == null) { + publicFolder = "C:\\Users\\Public" + } + def homeRoot = new File(publicFolder, "wpilib") + frcHome = new File(homeRoot, frcYear) + } else { + def userFolder = System.getProperty("user.home") + def homeRoot = new File(userFolder, "wpilib") + frcHome = new File(homeRoot, frcYear) + } + def frcHomeMaven = new File(frcHome, 'maven') + maven { + name = 'frcHome' + url = frcHomeMaven + } + } +} + +Properties props = System.getProperties(); +props.setProperty("org.gradle.internal.native.headers.unresolved.dependencies.ignore", "true"); diff --git a/studies/offset_control/simgui-ds.json b/studies/offset_control/simgui-ds.json new file mode 100644 index 00000000..387c8b1e --- /dev/null +++ b/studies/offset_control/simgui-ds.json @@ -0,0 +1,112 @@ +{ + "FMS": { + "window": { + "visible": false + } + }, + "Joysticks": { + "window": { + "visible": false + } + }, + "System Joysticks": { + "window": { + "visible": false + } + }, + "keyboardJoysticks": [ + { + "axisConfig": [ + { + "decKey": 65, + "incKey": 68 + }, + { + "decKey": 87, + "incKey": 83 + }, + { + "decKey": 69, + "decayRate": 0.0, + "incKey": 82, + "keyRate": 0.009999999776482582 + } + ], + "axisCount": 3, + "buttonCount": 4, + "buttonKeys": [ + 90, + 88, + 67, + 86 + ], + "povConfig": [ + { + "key0": 328, + "key135": 323, + "key180": 322, + "key225": 321, + "key270": 324, + "key315": 327, + "key45": 329, + "key90": 326 + } + ], + "povCount": 1 + }, + { + "axisConfig": [ + { + "decKey": 74, + "incKey": 76 + }, + { + "decKey": 73, + "incKey": 75 + } + ], + "axisCount": 2, + "buttonCount": 4, + "buttonKeys": [ + 77, + 44, + 46, + 47 + ], + "povCount": 0 + }, + { + "axisConfig": [ + { + "decKey": 263, + "incKey": 262 + }, + { + "decKey": 265, + "incKey": 264 + } + ], + "axisCount": 2, + "buttonCount": 6, + "buttonKeys": [ + 260, + 268, + 266, + 261, + 269, + 267 + ], + "povCount": 0 + }, + { + "axisCount": 0, + "buttonCount": 0, + "povCount": 0 + } + ], + "robotJoysticks": [ + { + "guid": "Keyboard0" + } + ] +} diff --git a/studies/offset_control/src/main/deploy/example.txt b/studies/offset_control/src/main/deploy/example.txt new file mode 100644 index 00000000..bb82515d --- /dev/null +++ b/studies/offset_control/src/main/deploy/example.txt @@ -0,0 +1,3 @@ +Files placed in this directory will be deployed to the RoboRIO into the +'deploy' directory in the home folder. Use the 'Filesystem.getDeployDirectory' wpilib function +to get a proper path relative to the deploy directory. \ No newline at end of file diff --git a/studies/offset_control/src/main/java/frc/robot/Main.java b/studies/offset_control/src/main/java/frc/robot/Main.java new file mode 100644 index 00000000..cd91dc0b --- /dev/null +++ b/studies/offset_control/src/main/java/frc/robot/Main.java @@ -0,0 +1,14 @@ +package frc.robot; + +import org.team100.offset_control.Robot; + +import edu.wpi.first.wpilibj.RobotBase; + +public final class Main { + private Main() { + } + + public static void main(String... args) { + RobotBase.startRobot(Robot::new); + } +} diff --git a/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java b/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java new file mode 100644 index 00000000..089e187c --- /dev/null +++ b/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java @@ -0,0 +1,75 @@ + +package org.team100.offset_control; + +import org.team100.lib.coherence.Cache; +import org.team100.lib.coherence.Takt; +import org.team100.lib.controller.r3.ControllerFactoryR3; +import org.team100.lib.controller.r3.ControllerR3; +import org.team100.lib.experiments.Experiments; +import org.team100.lib.hid.DriverXboxControl; +import org.team100.lib.logging.LoggerFactory; +import org.team100.lib.logging.Logging; +import org.team100.lib.profile.HolonomicProfile; +import org.team100.lib.subsystems.r3.VelocitySubsystemR3; +import org.team100.lib.subsystems.r3.commands.DriveToPoseWithProfile; +import org.team100.lib.subsystems.test.TrivialDrivetrain; +import org.team100.lib.util.Banner; +import org.team100.lib.visualization.RobotPoseVisualization; + +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.wpilibj.TimedRobot; +import edu.wpi.first.wpilibj2.command.CommandScheduler; +import edu.wpi.first.wpilibj2.command.button.Trigger; + +public class Robot extends TimedRobot { + private final VelocitySubsystemR3 m_subsystem; + private final Runnable m_robotViz; + private final DriverXboxControl m_controller; + + public Robot() { + Banner.printBanner(); + Experiments.instance.show(); + Logging log = Logging.instance(); + LoggerFactory fieldLogger = log.fieldLogger; + LoggerFactory rootLogger = log.rootLogger; + m_subsystem = new TrivialDrivetrain(); + m_robotViz = new RobotPoseVisualization( + fieldLogger, () -> m_subsystem.getState().pose()); + m_controller = new DriverXboxControl(0); + + HolonomicProfile profile = HolonomicProfile.currentLimitedExponential( + 1, 2, 4, 5, 10, 5); + ControllerR3 controller = ControllerFactoryR3 + .auto2025LooseTolerance(rootLogger); + DriveToPoseWithProfile driveCmd = new DriveToPoseWithProfile( + rootLogger, m_subsystem, controller, + profile, + () -> new Pose2d(1, 1, Rotation2d.kZero)); + + new Trigger(m_controller::a).whileTrue( + driveCmd.until(driveCmd::isDone)); + } + + @Override + public void robotPeriodic() { + Takt.update(); + Cache.refresh(); + CommandScheduler.getInstance().run(); + m_robotViz.run(); + } + + @Override + public void teleopInit() { + + } + + @Override + public void teleopPeriodic() { + } + + @Override + public void teleopExit() { + } + +} diff --git a/studies/offset_control/vendordeps/Phoenix5-frc2025-latest.json b/studies/offset_control/vendordeps/Phoenix5-frc2025-latest.json new file mode 100644 index 00000000..c1098dcc --- /dev/null +++ b/studies/offset_control/vendordeps/Phoenix5-frc2025-latest.json @@ -0,0 +1,171 @@ +{ + "fileName": "Phoenix5-frc2025-latest.json", + "name": "CTRE-Phoenix (v5)", + "version": "5.35.1", + "frcYear": "2025", + "uuid": "ab676553-b602-441f-a38d-f1296eff6537", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2025-latest.json", + "requires": [ + { + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", + "errorMessage": "Phoenix 5 requires low-level libraries from Phoenix 6. Please add the Phoenix 6 vendordep before adding Phoenix 5.", + "offlineFileName": "Phoenix6-frc2025-latest.json", + "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json" + } + ], + "conflictsWith": [ + { + "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", + "errorMessage": "Users must use the Phoenix 5 replay vendordep when using the Phoenix 6 replay vendordep.", + "offlineFileName": "Phoenix6-replay-frc2025-latest.json" + }, + { + "uuid": "fbc886a4-2cec-40c0-9835-71086a8cc3df", + "errorMessage": "Users cannot have both the replay and regular Phoenix 5 vendordeps in their robot program.", + "offlineFileName": "Phoenix5-replay-frc2025-latest.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-java", + "version": "5.35.1" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-java", + "version": "5.35.1" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.35.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.35.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-cpp", + "version": "5.35.1", + "libName": "CTRE_Phoenix_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-cpp", + "version": "5.35.1", + "libName": "CTRE_Phoenix", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.35.1", + "libName": "CTRE_PhoenixCCI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "5.35.1", + "libName": "CTRE_Phoenix_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "api-cpp-sim", + "version": "5.35.1", + "libName": "CTRE_PhoenixSim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.35.1", + "libName": "CTRE_PhoenixCCISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ] +} \ No newline at end of file diff --git a/studies/offset_control/vendordeps/Phoenix6-frc2025-latest.json b/studies/offset_control/vendordeps/Phoenix6-frc2025-latest.json new file mode 100644 index 00000000..cf873578 --- /dev/null +++ b/studies/offset_control/vendordeps/Phoenix6-frc2025-latest.json @@ -0,0 +1,419 @@ +{ + "fileName": "Phoenix6-frc2025-latest.json", + "name": "CTRE-Phoenix (v6)", + "version": "25.2.1", + "frcYear": "2025", + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json", + "conflictsWith": [ + { + "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", + "errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.", + "offlineFileName": "Phoenix6-replay-frc2025-latest.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-java", + "version": "25.2.1" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "api-cpp", + "version": "25.2.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "25.2.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "api-cpp-sim", + "version": "25.2.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "25.2.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "25.2.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "25.2.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "25.2.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "25.2.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "25.2.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFXS", + "version": "25.2.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "25.2.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "25.2.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANrange", + "version": "25.2.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-cpp", + "version": "25.2.1", + "libName": "CTRE_Phoenix6_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "25.2.1", + "libName": "CTRE_PhoenixTools", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "25.2.1", + "libName": "CTRE_Phoenix6_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "25.2.1", + "libName": "CTRE_PhoenixTools_Sim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "25.2.1", + "libName": "CTRE_SimTalonSRX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "25.2.1", + "libName": "CTRE_SimVictorSPX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "25.2.1", + "libName": "CTRE_SimPigeonIMU", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "25.2.1", + "libName": "CTRE_SimCANCoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "25.2.1", + "libName": "CTRE_SimProTalonFX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFXS", + "version": "25.2.1", + "libName": "CTRE_SimProTalonFXS", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "25.2.1", + "libName": "CTRE_SimProCANcoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "25.2.1", + "libName": "CTRE_SimProPigeon2", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANrange", + "version": "25.2.1", + "libName": "CTRE_SimProCANrange", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ] +} \ No newline at end of file diff --git a/studies/offset_control/vendordeps/REVLib.json b/studies/offset_control/vendordeps/REVLib.json new file mode 100644 index 00000000..86ad287c --- /dev/null +++ b/studies/offset_control/vendordeps/REVLib.json @@ -0,0 +1,71 @@ +{ + "fileName": "REVLib.json", + "name": "REVLib", + "version": "2025.0.1", + "frcYear": "2025", + "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", + "mavenUrls": [ + "https://maven.revrobotics.com/" + ], + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2025.json", + "javaDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-java", + "version": "2025.0.1" + } + ], + "jniDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2025.0.1", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-cpp", + "version": "2025.0.1", + "libName": "REVLib", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2025.0.1", + "libName": "REVLibDriver", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ] +} \ No newline at end of file diff --git a/studies/offset_control/vendordeps/ReduxLib-2025.0.0.json b/studies/offset_control/vendordeps/ReduxLib-2025.0.0.json new file mode 100644 index 00000000..f15ff901 --- /dev/null +++ b/studies/offset_control/vendordeps/ReduxLib-2025.0.0.json @@ -0,0 +1,72 @@ +{ + "fileName": "ReduxLib-2025.0.0.json", + "name": "ReduxLib", + "version": "2025.0.0", + "frcYear": "2025", + "uuid": "151ecca8-670b-4026-8160-cdd2679ef2bd", + "mavenUrls": [ + "https://maven.reduxrobotics.com/" + ], + "jsonUrl": "https://frcsdk.reduxrobotics.com/ReduxLib_2025.json", + "javaDependencies": [ + { + "groupId": "com.reduxrobotics.frc", + "artifactId": "ReduxLib-java", + "version": "2025.0.0" + } + ], + "jniDependencies": [ + { + "groupId": "com.reduxrobotics.frc", + "artifactId": "ReduxLib-driver", + "version": "2025.0.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "linuxathena", + "linuxx86-64", + "linuxarm32", + "linuxarm64", + "osxuniversal", + "windowsx86-64" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.reduxrobotics.frc", + "artifactId": "ReduxLib-cpp", + "version": "2025.0.0", + "libName": "ReduxLib", + "headerClassifier": "headers", + "sourcesClassifier": "sources", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena", + "linuxx86-64", + "linuxarm32", + "linuxarm64", + "osxuniversal", + "windowsx86-64" + ] + }, + { + "groupId": "com.reduxrobotics.frc", + "artifactId": "ReduxLib-driver", + "version": "2025.0.0", + "libName": "ReduxCore", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena", + "linuxx86-64", + "linuxarm32", + "linuxarm64", + "osxuniversal", + "windowsx86-64" + ] + } + ] +} \ No newline at end of file diff --git a/studies/offset_control/vendordeps/WPILibNewCommands.json b/studies/offset_control/vendordeps/WPILibNewCommands.json new file mode 100644 index 00000000..3718e0ac --- /dev/null +++ b/studies/offset_control/vendordeps/WPILibNewCommands.json @@ -0,0 +1,38 @@ +{ + "fileName": "WPILibNewCommands.json", + "name": "WPILib-New-Commands", + "version": "1.0.0", + "uuid": "111e20f7-815e-48f8-9dd6-e675ce75b266", + "frcYear": "2025", + "mavenUrls": [], + "jsonUrl": "", + "javaDependencies": [ + { + "groupId": "edu.wpi.first.wpilibNewCommands", + "artifactId": "wpilibNewCommands-java", + "version": "wpilib" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "edu.wpi.first.wpilibNewCommands", + "artifactId": "wpilibNewCommands-cpp", + "version": "wpilib", + "libName": "wpilibNewCommands", + "headerClassifier": "headers", + "sourcesClassifier": "sources", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena", + "linuxarm32", + "linuxarm64", + "windowsx86-64", + "windowsx86", + "linuxx86-64", + "osxuniversal" + ] + } + ] +} diff --git a/studies/offset_control/vendordeps/libgrapplefrc2025.json b/studies/offset_control/vendordeps/libgrapplefrc2025.json new file mode 100644 index 00000000..a49af315 --- /dev/null +++ b/studies/offset_control/vendordeps/libgrapplefrc2025.json @@ -0,0 +1,74 @@ +{ + "fileName": "libgrapplefrc2025.json", + "name": "libgrapplefrc", + "version": "2025.1.3", + "frcYear": "2025", + "uuid": "8ef3423d-9532-4665-8339-206dae1d7168", + "mavenUrls": [ + "https://storage.googleapis.com/grapple-frc-maven" + ], + "jsonUrl": "https://storage.googleapis.com/grapple-frc-maven/libgrapplefrc2025.json", + "javaDependencies": [ + { + "groupId": "au.grapplerobotics", + "artifactId": "libgrapplefrcjava", + "version": "2025.1.3" + } + ], + "jniDependencies": [ + { + "groupId": "au.grapplerobotics", + "artifactId": "libgrapplefrcdriver", + "version": "2025.1.3", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ], + "cppDependencies": [ + { + "groupId": "au.grapplerobotics", + "artifactId": "libgrapplefrccpp", + "version": "2025.1.3", + "libName": "grapplefrc", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "au.grapplerobotics", + "artifactId": "libgrapplefrcdriver", + "version": "2025.1.3", + "libName": "grapplefrcdriver", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ] +} \ No newline at end of file From df1749a84ccef6a9133185fcc69a75554b0803ef Mon Sep 17 00:00:00 2001 From: Joel Truher Date: Fri, 28 Nov 2025 20:41:56 -0800 Subject: [PATCH 08/13] offset control WIP --- .../lib/geometry/GlobalVelocityR3.java | 8 +++ .../lib/subsystems/test/OffsetDrivetrain.java | 49 +++++++++++++++++++ .../subsystems/test/TrivialDrivetrain.java | 11 +---- .../org/team100/offset_control/Robot.java | 8 ++- 4 files changed, 65 insertions(+), 11 deletions(-) create mode 100644 lib/src/main/java/org/team100/lib/subsystems/test/OffsetDrivetrain.java diff --git a/lib/src/main/java/org/team100/lib/geometry/GlobalVelocityR3.java b/lib/src/main/java/org/team100/lib/geometry/GlobalVelocityR3.java index 30d6853d..a199d489 100644 --- a/lib/src/main/java/org/team100/lib/geometry/GlobalVelocityR3.java +++ b/lib/src/main/java/org/team100/lib/geometry/GlobalVelocityR3.java @@ -59,6 +59,14 @@ public GlobalVelocityR3 minus(GlobalVelocityR3 other) { return new GlobalVelocityR3(x - other.x, y - other.y, theta - other.theta); } + /** Integrate the velocity from the initial pose for time dt */ + public Pose2d integrate(Pose2d initial, double dt) { + return new Pose2d( + initial.getX() + x * dt, + initial.getY() + y * dt, + initial.getRotation().plus(new Rotation2d(theta * dt))); + } + public GlobalAccelerationR3 accel(GlobalVelocityR3 previous, double dt) { GlobalVelocityR3 v = minus(previous).div(dt); return new GlobalAccelerationR3(v.x(), v.y(), v.theta()); diff --git a/lib/src/main/java/org/team100/lib/subsystems/test/OffsetDrivetrain.java b/lib/src/main/java/org/team100/lib/subsystems/test/OffsetDrivetrain.java new file mode 100644 index 00000000..6e0ac7b7 --- /dev/null +++ b/lib/src/main/java/org/team100/lib/subsystems/test/OffsetDrivetrain.java @@ -0,0 +1,49 @@ +package org.team100.lib.subsystems.test; + +import org.team100.lib.geometry.GlobalVelocityR3; +import org.team100.lib.state.ModelR3; +import org.team100.lib.subsystems.r3.VelocitySubsystemR3; + +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Translation2d; + +public class OffsetDrivetrain implements VelocitySubsystemR3 { + private final VelocitySubsystemR3 m_delegate; + private final Translation2d m_offset; + + public OffsetDrivetrain(VelocitySubsystemR3 delegate, Translation2d offset) { + m_delegate = delegate; + m_offset = offset; + } + + @Override + public ModelR3 getState() { + ModelR3 state = m_delegate.getState(); + Pose2d statePose = state.pose(); + Rotation2d rotation = statePose.getRotation(); + Pose2d pose = new Pose2d( + statePose.getTranslation().minus(m_offset), rotation); + GlobalVelocityR3 v = state.velocity(); + double vx = v.x() - v.theta() * m_offset.rotateBy(rotation).getY(); + double vy = v.y() + v.theta() * m_offset.rotateBy(rotation).getX(); + double vtheta = v.theta(); + GlobalVelocityR3 vv = new GlobalVelocityR3(vx, vy, vtheta); + return new ModelR3(pose, vv); + } + + @Override + public void stop() { + m_delegate.stop(); + } + + @Override + public void setVelocity(GlobalVelocityR3 setpoint) { + Rotation2d rotation = m_delegate.getState().pose().getRotation(); + double vx = setpoint.x() + setpoint.theta() * m_offset.rotateBy(rotation).getY(); + double vy = setpoint.y() - setpoint.theta() * m_offset.rotateBy(rotation).getX(); + double vtheta = setpoint.theta(); + m_delegate.setVelocity(new GlobalVelocityR3(vx, vy, vtheta)); + } + +} diff --git a/lib/src/main/java/org/team100/lib/subsystems/test/TrivialDrivetrain.java b/lib/src/main/java/org/team100/lib/subsystems/test/TrivialDrivetrain.java index c82a347c..72beb31c 100644 --- a/lib/src/main/java/org/team100/lib/subsystems/test/TrivialDrivetrain.java +++ b/lib/src/main/java/org/team100/lib/subsystems/test/TrivialDrivetrain.java @@ -8,7 +8,6 @@ import org.team100.lib.subsystems.r3.VelocitySubsystemR3; import edu.wpi.first.math.geometry.Pose2d; -import edu.wpi.first.math.geometry.Rotation2d; /** * Executes desired velocity exactly. @@ -42,15 +41,9 @@ public void setVelocity(GlobalVelocityR3 setpoint) { } private ModelR3 update() { - double vx = m_setpoint.x(); - double vy = m_setpoint.y(); - double omega = m_setpoint.theta(); m_state = new ModelR3( - new Pose2d( - m_state.pose().getX() + vx * DT, - m_state.pose().getY() + vy * DT, - m_state.pose().getRotation().plus(new Rotation2d(omega * DT))), - new GlobalVelocityR3(vx, vy, omega)); + m_setpoint.integrate(m_state.pose(), DT), + m_setpoint); return m_state; } diff --git a/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java b/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java index 089e187c..274f3dcb 100644 --- a/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java +++ b/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java @@ -12,12 +12,14 @@ import org.team100.lib.profile.HolonomicProfile; import org.team100.lib.subsystems.r3.VelocitySubsystemR3; import org.team100.lib.subsystems.r3.commands.DriveToPoseWithProfile; +import org.team100.lib.subsystems.test.OffsetDrivetrain; import org.team100.lib.subsystems.test.TrivialDrivetrain; import org.team100.lib.util.Banner; import org.team100.lib.visualization.RobotPoseVisualization; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Translation2d; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj2.command.CommandScheduler; import edu.wpi.first.wpilibj2.command.button.Trigger; @@ -33,7 +35,9 @@ public Robot() { Logging log = Logging.instance(); LoggerFactory fieldLogger = log.fieldLogger; LoggerFactory rootLogger = log.rootLogger; - m_subsystem = new TrivialDrivetrain(); + m_subsystem = new OffsetDrivetrain( + new TrivialDrivetrain(), + new Translation2d(4, 0)); m_robotViz = new RobotPoseVisualization( fieldLogger, () -> m_subsystem.getState().pose()); m_controller = new DriverXboxControl(0); @@ -45,7 +49,7 @@ public Robot() { DriveToPoseWithProfile driveCmd = new DriveToPoseWithProfile( rootLogger, m_subsystem, controller, profile, - () -> new Pose2d(1, 1, Rotation2d.kZero)); + () -> new Pose2d(4, 4, Rotation2d.kZero)); new Trigger(m_controller::a).whileTrue( driveCmd.until(driveCmd::isDone)); From 00dfa3f524ae43306a00eeaed4e55f7cbedfdd76 Mon Sep 17 00:00:00 2001 From: Joel Truher Date: Fri, 28 Nov 2025 20:52:45 -0800 Subject: [PATCH 09/13] more WIP --- .../lib/visualization/RobotPoseVisualization.java | 5 +++-- .../java/org/team100/offset_control/Robot.java | 15 ++++++++++++--- 2 files changed, 15 insertions(+), 5 deletions(-) diff --git a/lib/src/main/java/org/team100/lib/visualization/RobotPoseVisualization.java b/lib/src/main/java/org/team100/lib/visualization/RobotPoseVisualization.java index f812f2ec..30c6bd2f 100644 --- a/lib/src/main/java/org/team100/lib/visualization/RobotPoseVisualization.java +++ b/lib/src/main/java/org/team100/lib/visualization/RobotPoseVisualization.java @@ -17,8 +17,9 @@ public class RobotPoseVisualization implements Runnable { public RobotPoseVisualization( LoggerFactory fieldLogger, - Supplier pose) { - m_log_field_robot = fieldLogger.doubleArrayLogger(Level.COMP, "robot"); + Supplier pose, + String label) { + m_log_field_robot = fieldLogger.doubleArrayLogger(Level.COMP, label); m_pose = pose; } diff --git a/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java b/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java index 274f3dcb..267434ba 100644 --- a/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java +++ b/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java @@ -27,6 +27,7 @@ public class Robot extends TimedRobot { private final VelocitySubsystemR3 m_subsystem; private final Runnable m_robotViz; + private final Runnable m_ctrlViz; private final DriverXboxControl m_controller; public Robot() { @@ -35,11 +36,18 @@ public Robot() { Logging log = Logging.instance(); LoggerFactory fieldLogger = log.fieldLogger; LoggerFactory rootLogger = log.rootLogger; + TrivialDrivetrain delegate = new TrivialDrivetrain(); m_subsystem = new OffsetDrivetrain( - new TrivialDrivetrain(), + delegate, new Translation2d(4, 0)); m_robotViz = new RobotPoseVisualization( - fieldLogger, () -> m_subsystem.getState().pose()); + fieldLogger, + () -> delegate.getState().pose(), + "robot"); + m_ctrlViz = new RobotPoseVisualization( + fieldLogger, + () -> m_subsystem.getState().pose(), + "ctrl"); m_controller = new DriverXboxControl(0); HolonomicProfile profile = HolonomicProfile.currentLimitedExponential( @@ -49,7 +57,7 @@ public Robot() { DriveToPoseWithProfile driveCmd = new DriveToPoseWithProfile( rootLogger, m_subsystem, controller, profile, - () -> new Pose2d(4, 4, Rotation2d.kZero)); + () -> new Pose2d(4, 4, Rotation2d.k180deg)); new Trigger(m_controller::a).whileTrue( driveCmd.until(driveCmd::isDone)); @@ -61,6 +69,7 @@ public void robotPeriodic() { Cache.refresh(); CommandScheduler.getInstance().run(); m_robotViz.run(); + m_ctrlViz.run(); } @Override From aa3925f8b6a28b2f521acff70b5a56f4457f969c Mon Sep 17 00:00:00 2001 From: Joel Truher Date: Fri, 28 Nov 2025 21:08:23 -0800 Subject: [PATCH 10/13] WIP --- .../lib/subsystems/test/OffsetDrivetrain.java | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/lib/src/main/java/org/team100/lib/subsystems/test/OffsetDrivetrain.java b/lib/src/main/java/org/team100/lib/subsystems/test/OffsetDrivetrain.java index 6e0ac7b7..61ff2db7 100644 --- a/lib/src/main/java/org/team100/lib/subsystems/test/OffsetDrivetrain.java +++ b/lib/src/main/java/org/team100/lib/subsystems/test/OffsetDrivetrain.java @@ -6,6 +6,7 @@ import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Transform2d; import edu.wpi.first.math.geometry.Translation2d; public class OffsetDrivetrain implements VelocitySubsystemR3 { @@ -22,11 +23,10 @@ public ModelR3 getState() { ModelR3 state = m_delegate.getState(); Pose2d statePose = state.pose(); Rotation2d rotation = statePose.getRotation(); - Pose2d pose = new Pose2d( - statePose.getTranslation().minus(m_offset), rotation); + Pose2d pose = statePose.transformBy(new Transform2d(m_offset.unaryMinus(), Rotation2d.kZero)); GlobalVelocityR3 v = state.velocity(); - double vx = v.x() - v.theta() * m_offset.rotateBy(rotation).getY(); - double vy = v.y() + v.theta() * m_offset.rotateBy(rotation).getX(); + double vx = v.x() + v.theta() * m_offset.rotateBy(rotation).getY(); + double vy = v.y() - v.theta() * m_offset.rotateBy(rotation).getX(); double vtheta = v.theta(); GlobalVelocityR3 vv = new GlobalVelocityR3(vx, vy, vtheta); return new ModelR3(pose, vv); @@ -40,8 +40,8 @@ public void stop() { @Override public void setVelocity(GlobalVelocityR3 setpoint) { Rotation2d rotation = m_delegate.getState().pose().getRotation(); - double vx = setpoint.x() + setpoint.theta() * m_offset.rotateBy(rotation).getY(); - double vy = setpoint.y() - setpoint.theta() * m_offset.rotateBy(rotation).getX(); + double vx = setpoint.x() - setpoint.theta() * m_offset.rotateBy(rotation).getY(); + double vy = setpoint.y() + setpoint.theta() * m_offset.rotateBy(rotation).getX(); double vtheta = setpoint.theta(); m_delegate.setVelocity(new GlobalVelocityR3(vx, vy, vtheta)); } From beae70f58630ba8efe4d6a8197e45db4856d1102 Mon Sep 17 00:00:00 2001 From: Joel Truher Date: Sat, 29 Nov 2025 12:12:50 -0800 Subject: [PATCH 11/13] more WIP --- .../team100/lib/geometry/GeometryUtil.java | 5 ++ .../lib/geometry/GlobalVelocityR3.java | 10 +++ .../lib/subsystems/test/OffsetDrivetrain.java | 75 ++++++++++++++----- .../subsystems/test/TrivialDrivetrain.java | 5 +- .../org/team100/offset_control/Robot.java | 8 +- 5 files changed, 79 insertions(+), 24 deletions(-) diff --git a/lib/src/main/java/org/team100/lib/geometry/GeometryUtil.java b/lib/src/main/java/org/team100/lib/geometry/GeometryUtil.java index 0bb20f7b..22d57647 100644 --- a/lib/src/main/java/org/team100/lib/geometry/GeometryUtil.java +++ b/lib/src/main/java/org/team100/lib/geometry/GeometryUtil.java @@ -372,4 +372,9 @@ public static Vector toVec(Twist3d twist) { public static Vector toVec(Translation2d t) { return VecBuilder.fill(t.getX(), t.getY()); } + + /** 3-vector for translation */ + public static Vector toVec3(Translation2d t) { + return VecBuilder.fill(t.getX(), t.getY(), 0); + } } diff --git a/lib/src/main/java/org/team100/lib/geometry/GlobalVelocityR3.java b/lib/src/main/java/org/team100/lib/geometry/GlobalVelocityR3.java index a199d489..4e5bd6ee 100644 --- a/lib/src/main/java/org/team100/lib/geometry/GlobalVelocityR3.java +++ b/lib/src/main/java/org/team100/lib/geometry/GlobalVelocityR3.java @@ -123,4 +123,14 @@ public static GlobalVelocityR3 fromVector(Matrix v) { public Vector toVector() { return VecBuilder.fill(x, y, theta); } + + /** Angular velocity vector, i.e. just the theta component. */ + public Vector omegaVector() { + return VecBuilder.fill(0, 0, theta); + } + + /** Cartesian velocity vector, i.e. just the x and y components. */ + public Vector vVector() { + return VecBuilder.fill(x, y, 0); + } } \ No newline at end of file diff --git a/lib/src/main/java/org/team100/lib/subsystems/test/OffsetDrivetrain.java b/lib/src/main/java/org/team100/lib/subsystems/test/OffsetDrivetrain.java index 61ff2db7..e115f685 100644 --- a/lib/src/main/java/org/team100/lib/subsystems/test/OffsetDrivetrain.java +++ b/lib/src/main/java/org/team100/lib/subsystems/test/OffsetDrivetrain.java @@ -1,35 +1,47 @@ package org.team100.lib.subsystems.test; +import org.team100.lib.geometry.GeometryUtil; import org.team100.lib.geometry.GlobalVelocityR3; import org.team100.lib.state.ModelR3; import org.team100.lib.subsystems.r3.VelocitySubsystemR3; +import edu.wpi.first.math.Vector; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Transform2d; import edu.wpi.first.math.geometry.Translation2d; +import edu.wpi.first.math.numbers.N3; public class OffsetDrivetrain implements VelocitySubsystemR3 { private final VelocitySubsystemR3 m_delegate; private final Translation2d m_offset; - public OffsetDrivetrain(VelocitySubsystemR3 delegate, Translation2d offset) { + /** + * @param delgate the real drivetrain + * @param offset from delegate to toolpoint + */ + public OffsetDrivetrain( + VelocitySubsystemR3 delegate, Translation2d offset) { m_delegate = delegate; m_offset = offset; } @Override public ModelR3 getState() { - ModelR3 state = m_delegate.getState(); - Pose2d statePose = state.pose(); - Rotation2d rotation = statePose.getRotation(); - Pose2d pose = statePose.transformBy(new Transform2d(m_offset.unaryMinus(), Rotation2d.kZero)); - GlobalVelocityR3 v = state.velocity(); - double vx = v.x() + v.theta() * m_offset.rotateBy(rotation).getY(); - double vy = v.y() - v.theta() * m_offset.rotateBy(rotation).getX(); - double vtheta = v.theta(); - GlobalVelocityR3 vv = new GlobalVelocityR3(vx, vy, vtheta); - return new ModelR3(pose, vv); + return new ModelR3(toolpointPose(), toolpointVelocity()); + } + + /** + * Set delegate velocity from toolpoint velocity and offset. + * r is from toolpoint to delegate, so invert offset. + * + * @param setpoint toolpoint velocity + */ + @Override + public void setVelocity(GlobalVelocityR3 setpoint) { + Translation2d inverseOffset = m_offset.unaryMinus(); + m_delegate.setVelocity(setpoint.plus( + tangentialVelocity(omega(setpoint), r(inverseOffset)))); } @Override @@ -37,13 +49,40 @@ public void stop() { m_delegate.stop(); } - @Override - public void setVelocity(GlobalVelocityR3 setpoint) { - Rotation2d rotation = m_delegate.getState().pose().getRotation(); - double vx = setpoint.x() - setpoint.theta() * m_offset.rotateBy(rotation).getY(); - double vy = setpoint.y() + setpoint.theta() * m_offset.rotateBy(rotation).getX(); - double vtheta = setpoint.theta(); - m_delegate.setVelocity(new GlobalVelocityR3(vx, vy, vtheta)); + /** Compute toolpoint pose from delegate pose and offset. */ + private Pose2d toolpointPose() { + return m_delegate.getState().pose().transformBy( + new Transform2d(m_offset, Rotation2d.kZero)); + } + + /** Compute toolpoint velocity from delegate velocity, pose, and offset. */ + private GlobalVelocityR3 toolpointVelocity() { + GlobalVelocityR3 delegateVelocity = m_delegate.getState().velocity(); + return delegateVelocity.plus( + tangentialVelocity(omega(delegateVelocity), r(m_offset))); + } + + private Rotation2d delegateRotation() { + return m_delegate.getState().rotation(); + } + + /** radial vector */ + private Vector r(Translation2d offset) { + return GeometryUtil.toVec3( + offset.rotateBy(delegateRotation())); + } + + private Vector omega(GlobalVelocityR3 v) { + return v.omegaVector(); + } + + /** + * v = omega \cross r + */ + private GlobalVelocityR3 tangentialVelocity( + Vector omega, Vector r) { + return GlobalVelocityR3.fromVector( + Vector.cross(omega, r)); } } diff --git a/lib/src/main/java/org/team100/lib/subsystems/test/TrivialDrivetrain.java b/lib/src/main/java/org/team100/lib/subsystems/test/TrivialDrivetrain.java index 72beb31c..5fae2836 100644 --- a/lib/src/main/java/org/team100/lib/subsystems/test/TrivialDrivetrain.java +++ b/lib/src/main/java/org/team100/lib/subsystems/test/TrivialDrivetrain.java @@ -11,7 +11,6 @@ /** * Executes desired velocity exactly. - * Visualizes drivetrain pose. */ public class TrivialDrivetrain implements VelocitySubsystemR3 { private static final double DT = TimedRobot100.LOOP_PERIOD_S; @@ -19,9 +18,9 @@ public class TrivialDrivetrain implements VelocitySubsystemR3 { private GlobalVelocityR3 m_setpoint; private ModelR3 m_state; - public TrivialDrivetrain() { + public TrivialDrivetrain(Pose2d initial) { m_setpoint = new GlobalVelocityR3(0, 0, 0); - m_state = new ModelR3(Pose2d.kZero); + m_state = new ModelR3(initial); m_stateCache = Cache.of(this::update); } diff --git a/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java b/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java index 267434ba..7d36235b 100644 --- a/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java +++ b/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java @@ -36,10 +36,12 @@ public Robot() { Logging log = Logging.instance(); LoggerFactory fieldLogger = log.fieldLogger; LoggerFactory rootLogger = log.rootLogger; - TrivialDrivetrain delegate = new TrivialDrivetrain(); + // real robot starts at (-4,0) + TrivialDrivetrain delegate = new TrivialDrivetrain( + new Pose2d(-4, 0, Rotation2d.kZero)); + // offset is x+4 so tool point should be at zero m_subsystem = new OffsetDrivetrain( - delegate, - new Translation2d(4, 0)); + delegate, new Translation2d(4, 0)); m_robotViz = new RobotPoseVisualization( fieldLogger, () -> delegate.getState().pose(), From 925fbde03e27c1a6b3e8423803da41b48a9a3506 Mon Sep 17 00:00:00 2001 From: Joel Truher Date: Sat, 29 Nov 2025 13:30:32 -0800 Subject: [PATCH 12/13] ok, kinda does what i expect --- .../r3/commands/test/DriveToStateSimple.java | 3 +- .../lib/subsystems/test/OffsetDrivetrain.java | 77 +++++++++++++++++-- .../org/team100/offset_control/Robot.java | 42 ++++++++-- 3 files changed, 109 insertions(+), 13 deletions(-) diff --git a/lib/src/main/java/org/team100/lib/subsystems/r3/commands/test/DriveToStateSimple.java b/lib/src/main/java/org/team100/lib/subsystems/r3/commands/test/DriveToStateSimple.java index 34c4b8c6..03f73e06 100644 --- a/lib/src/main/java/org/team100/lib/subsystems/r3/commands/test/DriveToStateSimple.java +++ b/lib/src/main/java/org/team100/lib/subsystems/r3/commands/test/DriveToStateSimple.java @@ -15,8 +15,7 @@ * * There's no profile, no trajectory, just give it a point * you want to go to, and it will go there. It makes no attempt to - * impose feasibility constraints or coordinate the axes, so it tries - * to use the setpoint generator to moderate the output. + * impose feasibility constraints or coordinate the axes. * * This is really only intended for testing. */ diff --git a/lib/src/main/java/org/team100/lib/subsystems/test/OffsetDrivetrain.java b/lib/src/main/java/org/team100/lib/subsystems/test/OffsetDrivetrain.java index e115f685..26863a9a 100644 --- a/lib/src/main/java/org/team100/lib/subsystems/test/OffsetDrivetrain.java +++ b/lib/src/main/java/org/team100/lib/subsystems/test/OffsetDrivetrain.java @@ -12,7 +12,27 @@ import edu.wpi.first.math.geometry.Translation2d; import edu.wpi.first.math.numbers.N3; +/** + * Demo of offset control, without actually changing any control + * classes. + * + * The controlled state is the "toolpoint" of the robot. + * + * The drivetrain is the delegate, and its velocity commands are + * derived from the toolpoint velocities using a fixed offset. + * + * Some of the toolpoint desired velocity is perpendicular to the offset, and so + * by adding a rotation to the delegate, we can move the toolpoint in its + * desired direction a bit faster, in exchange for some theta error. This + * essentially edits the output of the controller, so we can leave the + * controller alone. + */ public class OffsetDrivetrain implements VelocitySubsystemR3 { + /** + * How much of the perpendicular speed to mix in. This interacts with the + * controller "P" values, so should be tuned together with them. + */ + private static final double OMEGA_MIXER = 2.0; private final VelocitySubsystemR3 m_delegate; private final Translation2d m_offset; @@ -39,9 +59,21 @@ public ModelR3 getState() { */ @Override public void setVelocity(GlobalVelocityR3 setpoint) { - Translation2d inverseOffset = m_offset.unaryMinus(); - m_delegate.setVelocity(setpoint.plus( - tangentialVelocity(omega(setpoint), r(inverseOffset)))); + // the component of the cartesian part that tries to spin + // the delegate + // adding some of this will make the toolpoint move more rapidly + // towards the cartesian goal, while injecting theta error. + GlobalVelocityR3 perpendicularOmega = omega(r(m_offset), velocity(setpoint)); + + // the component of the rotation part that tries to move the + // delegate in x and y + // respecting 100% of this velocity will keep the toolpoint + // where it wants to go (if the delegate responds perfectly) + GlobalVelocityR3 tangentialVelocity = tangentialVelocity(omega(setpoint), r(m_offset.unaryMinus())); + + m_delegate.setVelocity(setpoint + .plus(tangentialVelocity) + .plus(perpendicularOmega.times(OMEGA_MIXER))); } @Override @@ -49,13 +81,29 @@ public void stop() { m_delegate.stop(); } - /** Compute toolpoint pose from delegate pose and offset. */ + /** + * The perpendicular component of v across r, as an angular velocity. + * + * omega = (r \cross v) / r^2 + * + * Cartesian components are always zero. + */ + private GlobalVelocityR3 omega(Vector r, Vector v) { + return GlobalVelocityR3.fromVector( + Vector.cross(r, v).div(r.norm() * r.norm())); + } + + /** + * Computes toolpoint pose from delegate pose and offset. + */ private Pose2d toolpointPose() { return m_delegate.getState().pose().transformBy( new Transform2d(m_offset, Rotation2d.kZero)); } - /** Compute toolpoint velocity from delegate velocity, pose, and offset. */ + /** + * Computes toolpoint velocity from delegate velocity, pose, and offset. + */ private GlobalVelocityR3 toolpointVelocity() { GlobalVelocityR3 delegateVelocity = m_delegate.getState().velocity(); return delegateVelocity.plus( @@ -66,18 +114,35 @@ private Rotation2d delegateRotation() { return m_delegate.getState().rotation(); } - /** radial vector */ + /** + * Vector form of the offset, rotated by the delegate pose rotation. + */ private Vector r(Translation2d offset) { return GeometryUtil.toVec3( offset.rotateBy(delegateRotation())); } + /** + * Cartesian component of velocity. + */ + private Vector velocity(GlobalVelocityR3 v) { + return v.vVector(); + } + + /** + * Omega component of the velocity + */ private Vector omega(GlobalVelocityR3 v) { return v.omegaVector(); } /** + * Computes the cartesian velocity created by the rotational velocity omega, + * through the radius r. + * * v = omega \cross r + * + * Omega component is always zero. */ private GlobalVelocityR3 tangentialVelocity( Vector omega, Vector r) { diff --git a/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java b/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java index 7d36235b..52f3339e 100644 --- a/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java +++ b/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java @@ -3,15 +3,18 @@ import org.team100.lib.coherence.Cache; import org.team100.lib.coherence.Takt; -import org.team100.lib.controller.r3.ControllerFactoryR3; +import org.team100.lib.commands.MoveAndHold; import org.team100.lib.controller.r3.ControllerR3; +import org.team100.lib.controller.r3.FullStateControllerR3; import org.team100.lib.experiments.Experiments; import org.team100.lib.hid.DriverXboxControl; import org.team100.lib.logging.LoggerFactory; import org.team100.lib.logging.Logging; import org.team100.lib.profile.HolonomicProfile; +import org.team100.lib.state.ModelR3; import org.team100.lib.subsystems.r3.VelocitySubsystemR3; import org.team100.lib.subsystems.r3.commands.DriveToPoseWithProfile; +import org.team100.lib.subsystems.r3.commands.test.DriveToStateSimple; import org.team100.lib.subsystems.test.OffsetDrivetrain; import org.team100.lib.subsystems.test.TrivialDrivetrain; import org.team100.lib.util.Banner; @@ -54,15 +57,44 @@ public Robot() { HolonomicProfile profile = HolonomicProfile.currentLimitedExponential( 1, 2, 4, 5, 10, 5); - ControllerR3 controller = ControllerFactoryR3 - .auto2025LooseTolerance(rootLogger); + ControllerR3 controller = new FullStateControllerR3( + rootLogger, + 7.2, // p cartesian + 3.5, // p theta + 0.055, // p cartesian v + 0.01, // p theta v + 0.035, // x tol + 0.1, // theta tol + 1, // xdot tol + 1); + DriveToPoseWithProfile driveCmd = new DriveToPoseWithProfile( rootLogger, m_subsystem, controller, profile, - () -> new Pose2d(4, 4, Rotation2d.k180deg)); - + () -> new Pose2d(4, 4, Rotation2d.kCW_90deg)); new Trigger(m_controller::a).whileTrue( driveCmd.until(driveCmd::isDone)); + + ControllerR3 gentleController = new FullStateControllerR3( + rootLogger, + 3, // p cartesian + 1, // p theta + 0.04, // p cartesian v + 0.01, // p theta v + 0.05, // x tol + 0.05, // theta tol + 1, // xdot tol + 1); // omega tol + MoveAndHold driveSimple = new DriveToStateSimple( + rootLogger, gentleController, m_subsystem, new ModelR3()); + new Trigger(m_controller::b).whileTrue( + driveSimple.until(driveSimple::isDone)); + + MoveAndHold driveSimple2 = new DriveToStateSimple( + rootLogger, gentleController, m_subsystem, + new ModelR3(new Pose2d(4, 4, Rotation2d.kCW_90deg))); + new Trigger(m_controller::x).whileTrue( + driveSimple2.until(driveSimple2::isDone)); } @Override From fee6f107e112fd8913a280f4d9fcde9bf90f27ca Mon Sep 17 00:00:00 2001 From: Joel Truher Date: Sat, 29 Nov 2025 19:28:34 -0800 Subject: [PATCH 13/13] offset control kinda works --- .../org/team100/offset_control/Robot.java | 98 +++++++++++-------- 1 file changed, 59 insertions(+), 39 deletions(-) diff --git a/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java b/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java index 52f3339e..00e31c4a 100644 --- a/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java +++ b/studies/offset_control/src/main/java/org/team100/offset_control/Robot.java @@ -28,55 +28,75 @@ import edu.wpi.first.wpilibj2.command.button.Trigger; public class Robot extends TimedRobot { - private final VelocitySubsystemR3 m_subsystem; + private static final double REEF_X = 3.089; + private static final double REEF_Y = 4.026; private final Runnable m_robotViz; - private final Runnable m_ctrlViz; + private final Runnable m_toolpointViz; private final DriverXboxControl m_controller; public Robot() { Banner.printBanner(); Experiments.instance.show(); - Logging log = Logging.instance(); - LoggerFactory fieldLogger = log.fieldLogger; - LoggerFactory rootLogger = log.rootLogger; - // real robot starts at (-4,0) - TrivialDrivetrain delegate = new TrivialDrivetrain( - new Pose2d(-4, 0, Rotation2d.kZero)); - // offset is x+4 so tool point should be at zero - m_subsystem = new OffsetDrivetrain( - delegate, new Translation2d(4, 0)); + LoggerFactory field = Logging.instance().fieldLogger; + LoggerFactory log = Logging.instance().rootLogger; + + Translation2d offset = new Translation2d(1, 0); + TrivialDrivetrain robot = new TrivialDrivetrain( + new Pose2d(offset.unaryMinus(), Rotation2d.kZero)); + VelocitySubsystemR3 toolpoint = new OffsetDrivetrain( + robot, offset); + m_robotViz = new RobotPoseVisualization( - fieldLogger, - () -> delegate.getState().pose(), - "robot"); - m_ctrlViz = new RobotPoseVisualization( - fieldLogger, - () -> m_subsystem.getState().pose(), - "ctrl"); + field, () -> robot.getState().pose(), "robot"); + m_toolpointViz = new RobotPoseVisualization( + field, () -> toolpoint.getState().pose(), "ctrl"); m_controller = new DriverXboxControl(0); + setup1(log, toolpoint); + + setup2(log, toolpoint); + } + + /** Setup profiles to A and to B */ + private void setup1(LoggerFactory log, VelocitySubsystemR3 toolpoint) { + // this is intended to be *fast* HolonomicProfile profile = HolonomicProfile.currentLimitedExponential( - 1, 2, 4, 5, 10, 5); + 5, // v cartesian + 10, // a cartesian + 20, // stall a cartesian + 10, // omega + 10, // alpha + 20); // stall alpha + // this should try to control cartesian much harder than rotation ControllerR3 controller = new FullStateControllerR3( - rootLogger, - 7.2, // p cartesian - 3.5, // p theta + log, + 10, // p cartesian + 4, // p theta 0.055, // p cartesian v - 0.01, // p theta v - 0.035, // x tol - 0.1, // theta tol - 1, // xdot tol - 1); + 0.005, // p theta v + 0.03, // x tol + 0.03, // theta tol + 0.1, // xdot tol + 0.1); + + // these aren't actually A and B, they're further apart to make the demo look + // better. + Pose2d A = new Pose2d(REEF_X, REEF_Y + 0.5, Rotation2d.kZero); + Pose2d B = new Pose2d(REEF_X, REEF_Y - 0.5, Rotation2d.kZero); + + DriveToPoseWithProfile toA = new DriveToPoseWithProfile( + log, toolpoint, controller, profile, () -> A); + new Trigger(m_controller::a).whileTrue(toA.until(toA::isDone)); - DriveToPoseWithProfile driveCmd = new DriveToPoseWithProfile( - rootLogger, m_subsystem, controller, - profile, - () -> new Pose2d(4, 4, Rotation2d.kCW_90deg)); - new Trigger(m_controller::a).whileTrue( - driveCmd.until(driveCmd::isDone)); + DriveToPoseWithProfile toB = new DriveToPoseWithProfile( + log, toolpoint, controller, profile, () -> B); + new Trigger(m_controller::b).whileTrue(toB.until(toB::isDone)); + } + /** Setup pure PID examples */ + private void setup2(LoggerFactory log, VelocitySubsystemR3 toolpoint) { ControllerR3 gentleController = new FullStateControllerR3( - rootLogger, + log, 3, // p cartesian 1, // p theta 0.04, // p cartesian v @@ -86,14 +106,14 @@ public Robot() { 1, // xdot tol 1); // omega tol MoveAndHold driveSimple = new DriveToStateSimple( - rootLogger, gentleController, m_subsystem, new ModelR3()); - new Trigger(m_controller::b).whileTrue( + log, gentleController, toolpoint, new ModelR3()); + new Trigger(m_controller::x).whileTrue( driveSimple.until(driveSimple::isDone)); MoveAndHold driveSimple2 = new DriveToStateSimple( - rootLogger, gentleController, m_subsystem, + log, gentleController, toolpoint, new ModelR3(new Pose2d(4, 4, Rotation2d.kCW_90deg))); - new Trigger(m_controller::x).whileTrue( + new Trigger(m_controller::y).whileTrue( driveSimple2.until(driveSimple2::isDone)); } @@ -103,7 +123,7 @@ public void robotPeriodic() { Cache.refresh(); CommandScheduler.getInstance().run(); m_robotViz.run(); - m_ctrlViz.run(); + m_toolpointViz.run(); } @Override