From f3bfbd87b1f6faef6bac75c9f94b590bb8b504b6 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Fri, 7 Jun 2013 14:02:18 -0400 Subject: [PATCH 01/80] Added sine test. --- src/drivers/md25/md25.cpp | 38 ++++++++++++++++++++++++++++++++++ src/drivers/md25/md25.hpp | 3 +++ src/drivers/md25/md25_main.cpp | 18 ++++++++++++++++ 3 files changed, 59 insertions(+) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index 71932ad65d..f9f5d70ab5 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -45,6 +45,7 @@ #include "md25.hpp" #include #include +#include #include #include @@ -550,4 +551,41 @@ int md25Test(const char *deviceName, uint8_t bus, uint8_t address) return 0; } +int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) +{ + printf("md25 sine: starting\n"); + + // setup + MD25 md25("/dev/md25", bus, address); + + // print status + char buf[200]; + md25.status(buf, sizeof(buf)); + printf("%s\n", buf); + + // setup for test + md25.setSpeedRegulation(true); + md25.setTimeout(true); + float dt = 0.1; + float amplitude = 0.2; + float t = 0; + float omega = 0.1; + + // sine wave for motor 1 + md25.resetEncoders(); + while (true) { + float prev_revolution = md25.getRevolutions1(); + md25.setMotor1Speed(amplitude*sinf(omega*t)); + usleep(1000000 * dt); + t += dt; + float speed_rpm = 60*(md25.getRevolutions1() - prev_revolution)/dt; + md25.readData(); + if (t > 2.0f) break; + } + md25.setMotor1Speed(0); + + printf("md25 sine complete\n"); + return 0; +} + // vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78 diff --git a/src/drivers/md25/md25.hpp b/src/drivers/md25/md25.hpp index e77511b163..cac3ffd293 100644 --- a/src/drivers/md25/md25.hpp +++ b/src/drivers/md25/md25.hpp @@ -290,4 +290,7 @@ private: // unit testing int md25Test(const char *deviceName, uint8_t bus, uint8_t address); +// sine testing +int md25Sine(const char *deviceName, uint8_t bus, uint8_t address); + // vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78 diff --git a/src/drivers/md25/md25_main.cpp b/src/drivers/md25/md25_main.cpp index e62c46b0d7..701452f2d5 100644 --- a/src/drivers/md25/md25_main.cpp +++ b/src/drivers/md25/md25_main.cpp @@ -136,6 +136,24 @@ int md25_main(int argc, char *argv[]) exit(0); } + if (!strcmp(argv[1], "sine")) { + + if (argc < 4) { + printf("usage: md25 sine bus address\n"); + exit(0); + } + + const char *deviceName = "/dev/md25"; + + uint8_t bus = strtoul(argv[2], nullptr, 0); + + uint8_t address = strtoul(argv[3], nullptr, 0); + + md25Sine(deviceName, bus, address); + + exit(0); + } + if (!strcmp(argv[1], "probe")) { if (argc < 4) { printf("usage: md25 probe bus address\n"); From 764310620837461857d511144738a521e3840f97 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 15 Jun 2013 16:37:15 -0400 Subject: [PATCH 02/80] Added log print ability to md25 driver. --- src/drivers/md25/md25.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index f9f5d70ab5..4e7e2694a6 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -49,6 +49,7 @@ #include #include +#include // registers enum { @@ -73,6 +74,9 @@ enum { REG_COMMAND_RW, }; +// File descriptors +static int mavlink_fd; + MD25::MD25(const char *deviceName, int bus, uint16_t address, uint32_t speed) : I2C("MD25", deviceName, bus, address, speed), @@ -579,6 +583,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) usleep(1000000 * dt); t += dt; float speed_rpm = 60*(md25.getRevolutions1() - prev_revolution)/dt; + mavlink_log_info(mavlink_fd, "rpm: %10.4f\n", (double)speed_rpm); md25.readData(); if (t > 2.0f) break; } From 42f09c4b547052d9fe2ef49f40a2df6910cf75b1 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 22 Jun 2013 13:41:38 -0400 Subject: [PATCH 03/80] Working on sysid. Added debug values. --- src/drivers/md25/BlockSysIdent.cpp | 8 ++++++++ src/drivers/md25/BlockSysIdent.hpp | 10 +++++++++ src/drivers/md25/md25.cpp | 33 +++++++++++++++++++++++++++--- 3 files changed, 48 insertions(+), 3 deletions(-) create mode 100644 src/drivers/md25/BlockSysIdent.cpp create mode 100644 src/drivers/md25/BlockSysIdent.hpp diff --git a/src/drivers/md25/BlockSysIdent.cpp b/src/drivers/md25/BlockSysIdent.cpp new file mode 100644 index 0000000000..23b0724d8c --- /dev/null +++ b/src/drivers/md25/BlockSysIdent.cpp @@ -0,0 +1,8 @@ +#include "BlockSysIdent.hpp" + +BlockSysIdent::BlockSysIdent() : + Block(NULL, "SYSID"), + _freq(this, "FREQ"), + _ampl(this, "AMPL") +{ +} diff --git a/src/drivers/md25/BlockSysIdent.hpp b/src/drivers/md25/BlockSysIdent.hpp new file mode 100644 index 0000000000..270635f407 --- /dev/null +++ b/src/drivers/md25/BlockSysIdent.hpp @@ -0,0 +1,10 @@ +#include +#include + +class BlockSysIdent : public control::Block { +public: + BlockSysIdent(); +private: + control::BlockParam _freq; + control::BlockParam _ampl; +}; diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index 4e7e2694a6..13d5c7eeb3 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -46,11 +46,16 @@ #include #include #include +#include #include #include #include +#include +#include +#include + // registers enum { // RW: read/write @@ -572,17 +577,39 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) md25.setTimeout(true); float dt = 0.1; float amplitude = 0.2; - float t = 0; float omega = 0.1; + // input signal + control::UOrbPublication input_signal(NULL, + ORB_ID(debug_key_value)); + strncpy(input_signal.key, "md25 in ", 10); + input_signal.timestamp_ms = hrt_absolute_time(); + input_signal.value = 0; + + // output signal + control::UOrbPublication output_signal(NULL, + ORB_ID(debug_key_value)); + strncpy(output_signal.key, "md25 out ", 10); + output_signal.timestamp_ms = hrt_absolute_time(); + output_signal.value = 0; + // sine wave for motor 1 md25.resetEncoders(); while (true) { float prev_revolution = md25.getRevolutions1(); - md25.setMotor1Speed(amplitude*sinf(omega*t)); usleep(1000000 * dt); - t += dt; + + // input + uint64_t timestamp = hrt_absolute_time(); + float t = timestamp/1000; + input_signal.timestamp_ms = timestamp; + input_signal.value = amplitude*sinf(omega*t); + md25.setMotor1Speed(input_signal.value); + + // output + output_signal.timestamp_ms = timestamp; float speed_rpm = 60*(md25.getRevolutions1() - prev_revolution)/dt; + output_signal.value = speed_rpm; mavlink_log_info(mavlink_fd, "rpm: %10.4f\n", (double)speed_rpm); md25.readData(); if (t > 2.0f) break; From e7cc6e71ad5d53d940a0e5c6961e5ea6c3a59e27 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 22 Jun 2013 13:45:12 -0400 Subject: [PATCH 04/80] Added pub update. --- src/drivers/md25/md25.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index 13d5c7eeb3..582b871c78 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -605,11 +605,13 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) input_signal.timestamp_ms = timestamp; input_signal.value = amplitude*sinf(omega*t); md25.setMotor1Speed(input_signal.value); + input_signal.update(); // output output_signal.timestamp_ms = timestamp; float speed_rpm = 60*(md25.getRevolutions1() - prev_revolution)/dt; output_signal.value = speed_rpm; + output_signal.update(); mavlink_log_info(mavlink_fd, "rpm: %10.4f\n", (double)speed_rpm); md25.readData(); if (t > 2.0f) break; From f2a0cce958db1c97eb70d43c3151992ccaed4cab Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 29 Jun 2013 15:21:17 -0400 Subject: [PATCH 05/80] Fixed timing issues. --- src/drivers/md25/md25.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index 582b871c78..7a1e7b7f47 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -577,7 +577,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) md25.setTimeout(true); float dt = 0.1; float amplitude = 0.2; - float omega = 0.1; + float frequency = 0.3; // input signal control::UOrbPublication input_signal(NULL, @@ -601,9 +601,9 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) // input uint64_t timestamp = hrt_absolute_time(); - float t = timestamp/1000; + float t = timestamp/1000000; input_signal.timestamp_ms = timestamp; - input_signal.value = amplitude*sinf(omega*t); + input_signal.value = amplitude*sinf(2*M_PI*frequency*t); md25.setMotor1Speed(input_signal.value); input_signal.update(); From 78ef6f5265d5f4e84d4e36be37fc7329587df0a3 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 29 Jun 2013 15:31:23 -0400 Subject: [PATCH 06/80] Changed final time. --- src/drivers/md25/md25.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index 7a1e7b7f47..375072bb03 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -578,6 +578,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) float dt = 0.1; float amplitude = 0.2; float frequency = 0.3; + float t_final = 30.0; // input signal control::UOrbPublication input_signal(NULL, @@ -614,7 +615,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) output_signal.update(); mavlink_log_info(mavlink_fd, "rpm: %10.4f\n", (double)speed_rpm); md25.readData(); - if (t > 2.0f) break; + if (t > t_final) break; } md25.setMotor1Speed(0); From 76d086e0773bda8252b9a59b737b902ddc52b59f Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 29 Jun 2013 15:58:58 -0400 Subject: [PATCH 07/80] Working with debug messages. --- src/drivers/md25/md25.cpp | 49 +++++++++++++++++++++------------------ 1 file changed, 26 insertions(+), 23 deletions(-) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index 375072bb03..4cb005721c 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -579,43 +579,46 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) float amplitude = 0.2; float frequency = 0.3; float t_final = 30.0; + float prev_revolution = md25.getRevolutions1(); - // input signal - control::UOrbPublication input_signal(NULL, + // debug publication + control::UOrbPublication debug_msg(NULL, ORB_ID(debug_key_value)); - strncpy(input_signal.key, "md25 in ", 10); - input_signal.timestamp_ms = hrt_absolute_time(); - input_signal.value = 0; - - // output signal - control::UOrbPublication output_signal(NULL, - ORB_ID(debug_key_value)); - strncpy(output_signal.key, "md25 out ", 10); - output_signal.timestamp_ms = hrt_absolute_time(); - output_signal.value = 0; // sine wave for motor 1 md25.resetEncoders(); while (true) { - float prev_revolution = md25.getRevolutions1(); - usleep(1000000 * dt); // input uint64_t timestamp = hrt_absolute_time(); float t = timestamp/1000000; - input_signal.timestamp_ms = timestamp; - input_signal.value = amplitude*sinf(2*M_PI*frequency*t); - md25.setMotor1Speed(input_signal.value); - input_signal.update(); + + float input_value = amplitude*sinf(2*M_PI*frequency*t); + md25.setMotor1Speed(input_value); // output - output_signal.timestamp_ms = timestamp; - float speed_rpm = 60*(md25.getRevolutions1() - prev_revolution)/dt; - output_signal.value = speed_rpm; - output_signal.update(); - mavlink_log_info(mavlink_fd, "rpm: %10.4f\n", (double)speed_rpm); md25.readData(); + float current_revolution = md25.getRevolutions1(); + float output_speed_rpm = 60*(current_revolution - prev_revolution)/dt; + float prev_revolution = current_revolution; + mavlink_log_info(mavlink_fd, "rpm: %10.4f\n", (double)output_speed_rpm); + + // send input message + strncpy(debug_msg.key, "md25 in ", sizeof(10)); + debug_msg.timestamp_ms = 1000*timestamp; + debug_msg.value = input_value; + debug_msg.update(); + + // send output message + strncpy(debug_msg.key, "md25 out ", sizeof(10)); + debug_msg.timestamp_ms = 1000*timestamp; + debug_msg.value = output_speed_rpm;; + debug_msg.update(); + if (t > t_final) break; + + // sleep + usleep(1000000 * dt); } md25.setMotor1Speed(0); From 77c084a4cf6d5ac1131fae493230fcea2b11700c Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 29 Jun 2013 16:00:27 -0400 Subject: [PATCH 08/80] Fixed typo with strncpy. --- src/drivers/md25/md25.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index 4cb005721c..f265ec4515 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -604,13 +604,13 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) mavlink_log_info(mavlink_fd, "rpm: %10.4f\n", (double)output_speed_rpm); // send input message - strncpy(debug_msg.key, "md25 in ", sizeof(10)); + strncpy(debug_msg.key, "md25 in ", 10); debug_msg.timestamp_ms = 1000*timestamp; debug_msg.value = input_value; debug_msg.update(); // send output message - strncpy(debug_msg.key, "md25 out ", sizeof(10)); + strncpy(debug_msg.key, "md25 out ", 10); debug_msg.timestamp_ms = 1000*timestamp; debug_msg.value = output_speed_rpm;; debug_msg.update(); From 4cfcea176785975590d1d2952eb0b0270a6949b3 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 29 Jun 2013 16:53:24 -0400 Subject: [PATCH 09/80] Working on debug output. --- src/drivers/md25/md25.cpp | 25 ++++++++++++++----------- 1 file changed, 14 insertions(+), 11 deletions(-) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index f265ec4515..9dac5e5ea8 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -575,10 +575,10 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) // setup for test md25.setSpeedRegulation(true); md25.setTimeout(true); - float dt = 0.1; - float amplitude = 0.2; - float frequency = 0.3; - float t_final = 30.0; + float dt = 0.01; + float amplitude = 0.5; + float frequency = 1.0; + float t_final = 120.0; float prev_revolution = md25.getRevolutions1(); // debug publication @@ -591,7 +591,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) // input uint64_t timestamp = hrt_absolute_time(); - float t = timestamp/1000000; + float t = timestamp/1000000.0f; float input_value = amplitude*sinf(2*M_PI*frequency*t); md25.setMotor1Speed(input_value); @@ -600,23 +600,26 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) md25.readData(); float current_revolution = md25.getRevolutions1(); float output_speed_rpm = 60*(current_revolution - prev_revolution)/dt; - float prev_revolution = current_revolution; mavlink_log_info(mavlink_fd, "rpm: %10.4f\n", (double)output_speed_rpm); // send input message - strncpy(debug_msg.key, "md25 in ", 10); - debug_msg.timestamp_ms = 1000*timestamp; - debug_msg.value = input_value; - debug_msg.update(); + //strncpy(debug_msg.key, "md25 in ", 10); + //debug_msg.timestamp_ms = 1000*timestamp; + //debug_msg.value = input_value; + //debug_msg.update(); // send output message strncpy(debug_msg.key, "md25 out ", 10); debug_msg.timestamp_ms = 1000*timestamp; - debug_msg.value = output_speed_rpm;; + debug_msg.value = current_revolution - prev_revolution; + //debug_msg.value = output_speed_rpm; debug_msg.update(); if (t > t_final) break; + // update for next step + prev_revolution = current_revolution; + // sleep usleep(1000000 * dt); } From 308f1dbfa4787e84665a3e822ddf7d1979f023ca Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 29 Jun 2013 17:04:43 -0400 Subject: [PATCH 10/80] Added amplitude frequency to md25sine command. --- src/drivers/md25/md25.cpp | 11 +++-------- src/drivers/md25/md25.hpp | 2 +- src/drivers/md25/md25_main.cpp | 8 ++++++-- 3 files changed, 10 insertions(+), 11 deletions(-) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index 9dac5e5ea8..1079005c05 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -560,7 +560,7 @@ int md25Test(const char *deviceName, uint8_t bus, uint8_t address) return 0; } -int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) +int md25Sine(const char *deviceName, uint8_t bus, uint8_t address, float amplitude, float frequency) { printf("md25 sine: starting\n"); @@ -576,9 +576,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) md25.setSpeedRegulation(true); md25.setTimeout(true); float dt = 0.01; - float amplitude = 0.5; - float frequency = 1.0; - float t_final = 120.0; + float t_final = 60.0; float prev_revolution = md25.getRevolutions1(); // debug publication @@ -599,8 +597,6 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) // output md25.readData(); float current_revolution = md25.getRevolutions1(); - float output_speed_rpm = 60*(current_revolution - prev_revolution)/dt; - mavlink_log_info(mavlink_fd, "rpm: %10.4f\n", (double)output_speed_rpm); // send input message //strncpy(debug_msg.key, "md25 in ", 10); @@ -611,8 +607,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) // send output message strncpy(debug_msg.key, "md25 out ", 10); debug_msg.timestamp_ms = 1000*timestamp; - debug_msg.value = current_revolution - prev_revolution; - //debug_msg.value = output_speed_rpm; + debug_msg.value = current_revolution; debug_msg.update(); if (t > t_final) break; diff --git a/src/drivers/md25/md25.hpp b/src/drivers/md25/md25.hpp index cac3ffd293..2fc317f5e4 100644 --- a/src/drivers/md25/md25.hpp +++ b/src/drivers/md25/md25.hpp @@ -291,6 +291,6 @@ private: int md25Test(const char *deviceName, uint8_t bus, uint8_t address); // sine testing -int md25Sine(const char *deviceName, uint8_t bus, uint8_t address); +int md25Sine(const char *deviceName, uint8_t bus, uint8_t address, float amplitude, float frequency); // vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78 diff --git a/src/drivers/md25/md25_main.cpp b/src/drivers/md25/md25_main.cpp index 701452f2d5..b395088a38 100644 --- a/src/drivers/md25/md25_main.cpp +++ b/src/drivers/md25/md25_main.cpp @@ -139,7 +139,7 @@ int md25_main(int argc, char *argv[]) if (!strcmp(argv[1], "sine")) { if (argc < 4) { - printf("usage: md25 sine bus address\n"); + printf("usage: md25 sine bus address amp freq\n"); exit(0); } @@ -149,7 +149,11 @@ int md25_main(int argc, char *argv[]) uint8_t address = strtoul(argv[3], nullptr, 0); - md25Sine(deviceName, bus, address); + float amplitude = atof(argv[4]); + + float frequency = atof(argv[5]); + + md25Sine(deviceName, bus, address, amplitude, frequency); exit(0); } From 95aa82f586a8c44c53ae48517efdeb5e5673b7b5 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 29 Jun 2013 17:05:41 -0400 Subject: [PATCH 11/80] Fixed arg number. --- src/drivers/md25/md25_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/md25/md25_main.cpp b/src/drivers/md25/md25_main.cpp index b395088a38..3260705c1c 100644 --- a/src/drivers/md25/md25_main.cpp +++ b/src/drivers/md25/md25_main.cpp @@ -138,7 +138,7 @@ int md25_main(int argc, char *argv[]) if (!strcmp(argv[1], "sine")) { - if (argc < 4) { + if (argc < 6) { printf("usage: md25 sine bus address amp freq\n"); exit(0); } From 1980d9dd63e29390f7c3ba9b31be576c07706f73 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sun, 28 Jul 2013 01:35:43 -0400 Subject: [PATCH 12/80] Working on segway controller, restructure of fixedwing. --- makefiles/config_px4fmu-v1_default.mk | 1 + src/drivers/md25/md25.cpp | 2 +- src/drivers/md25/md25.hpp | 2 +- .../att_pos_estimator_ekf/KalmanNav.hpp | 4 +- src/modules/controllib/block/Block.cpp | 4 +- src/modules/controllib/blocks.hpp | 1 + src/modules/controllib/module.mk | 8 +- .../{block => uorb}/UOrbPublication.cpp | 0 .../{block => uorb}/UOrbPublication.hpp | 4 +- .../{block => uorb}/UOrbSubscription.cpp | 0 .../{block => uorb}/UOrbSubscription.hpp | 4 +- src/modules/controllib/uorb/blocks.cpp | 64 +++++++ src/modules/controllib/uorb/blocks.hpp | 90 +++++++++ .../fixedwing.cpp | 18 -- .../fixedwing.hpp | 45 +---- .../fixedwing_backside_main.cpp | 3 +- src/modules/fixedwing_backside/module.mk | 1 + src/modules/segway/BlockSegwayController.cpp | 56 ++++++ src/modules/segway/BlockSegwayController.hpp | 18 ++ src/modules/segway/module.mk | 42 +++++ src/modules/segway/params.c | 72 ++++++++ src/modules/segway/segway_main.cpp | 173 ++++++++++++++++++ 22 files changed, 536 insertions(+), 76 deletions(-) rename src/modules/controllib/{block => uorb}/UOrbPublication.cpp (100%) rename src/modules/controllib/{block => uorb}/UOrbPublication.hpp (98%) rename src/modules/controllib/{block => uorb}/UOrbSubscription.cpp (100%) rename src/modules/controllib/{block => uorb}/UOrbSubscription.hpp (98%) create mode 100644 src/modules/controllib/uorb/blocks.cpp create mode 100644 src/modules/controllib/uorb/blocks.hpp rename src/modules/{controllib => fixedwing_backside}/fixedwing.cpp (93%) rename src/modules/{controllib => fixedwing_backside}/fixedwing.hpp (87%) create mode 100644 src/modules/segway/BlockSegwayController.cpp create mode 100644 src/modules/segway/BlockSegwayController.hpp create mode 100644 src/modules/segway/module.mk create mode 100644 src/modules/segway/params.c create mode 100644 src/modules/segway/segway_main.cpp diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk index 74be1cd23f..cbca4f6a69 100644 --- a/makefiles/config_px4fmu-v1_default.mk +++ b/makefiles/config_px4fmu-v1_default.mk @@ -71,6 +71,7 @@ MODULES += examples/flow_position_estimator # # Vehicle Control # +MODULES += modules/segway MODULES += modules/fixedwing_backside MODULES += modules/fixedwing_att_control MODULES += modules/fixedwing_pos_control diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index 1079005c05..d6dd64a094 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -52,7 +52,7 @@ #include #include -#include +#include #include #include diff --git a/src/drivers/md25/md25.hpp b/src/drivers/md25/md25.hpp index 2fc317f5e4..780978514e 100644 --- a/src/drivers/md25/md25.hpp +++ b/src/drivers/md25/md25.hpp @@ -46,7 +46,7 @@ #include #include -#include +#include #include #include diff --git a/src/modules/att_pos_estimator_ekf/KalmanNav.hpp b/src/modules/att_pos_estimator_ekf/KalmanNav.hpp index 49d0d157da..f01ee03553 100644 --- a/src/modules/att_pos_estimator_ekf/KalmanNav.hpp +++ b/src/modules/att_pos_estimator_ekf/KalmanNav.hpp @@ -47,8 +47,8 @@ #include #include #include -#include -#include +#include +#include #include #include diff --git a/src/modules/controllib/block/Block.cpp b/src/modules/controllib/block/Block.cpp index 5994d23154..b964d40a31 100644 --- a/src/modules/controllib/block/Block.cpp +++ b/src/modules/controllib/block/Block.cpp @@ -43,8 +43,8 @@ #include "Block.hpp" #include "BlockParam.hpp" -#include "UOrbSubscription.hpp" -#include "UOrbPublication.hpp" +#include "../uorb/UOrbSubscription.hpp" +#include "../uorb/UOrbPublication.hpp" namespace control { diff --git a/src/modules/controllib/blocks.hpp b/src/modules/controllib/blocks.hpp index 7a785d12e2..fefe99702d 100644 --- a/src/modules/controllib/blocks.hpp +++ b/src/modules/controllib/blocks.hpp @@ -42,6 +42,7 @@ #include #include #include +#include #include #include "block/Block.hpp" diff --git a/src/modules/controllib/module.mk b/src/modules/controllib/module.mk index 13d1069c7a..d815a8feb5 100644 --- a/src/modules/controllib/module.mk +++ b/src/modules/controllib/module.mk @@ -37,7 +37,7 @@ SRCS = test_params.c \ block/Block.cpp \ block/BlockParam.cpp \ - block/UOrbPublication.cpp \ - block/UOrbSubscription.cpp \ - blocks.cpp \ - fixedwing.cpp + uorb/UOrbPublication.cpp \ + uorb/UOrbSubscription.cpp \ + uorb/blocks.cpp \ + blocks.cpp diff --git a/src/modules/controllib/block/UOrbPublication.cpp b/src/modules/controllib/uorb/UOrbPublication.cpp similarity index 100% rename from src/modules/controllib/block/UOrbPublication.cpp rename to src/modules/controllib/uorb/UOrbPublication.cpp diff --git a/src/modules/controllib/block/UOrbPublication.hpp b/src/modules/controllib/uorb/UOrbPublication.hpp similarity index 98% rename from src/modules/controllib/block/UOrbPublication.hpp rename to src/modules/controllib/uorb/UOrbPublication.hpp index 0a8ae2ff7d..6f1f3fc1c0 100644 --- a/src/modules/controllib/block/UOrbPublication.hpp +++ b/src/modules/controllib/uorb/UOrbPublication.hpp @@ -39,8 +39,8 @@ #pragma once #include -#include "Block.hpp" -#include "List.hpp" +#include "../block/Block.hpp" +#include "../block/List.hpp" namespace control diff --git a/src/modules/controllib/block/UOrbSubscription.cpp b/src/modules/controllib/uorb/UOrbSubscription.cpp similarity index 100% rename from src/modules/controllib/block/UOrbSubscription.cpp rename to src/modules/controllib/uorb/UOrbSubscription.cpp diff --git a/src/modules/controllib/block/UOrbSubscription.hpp b/src/modules/controllib/uorb/UOrbSubscription.hpp similarity index 98% rename from src/modules/controllib/block/UOrbSubscription.hpp rename to src/modules/controllib/uorb/UOrbSubscription.hpp index 22cc2e1145..d337d89a88 100644 --- a/src/modules/controllib/block/UOrbSubscription.hpp +++ b/src/modules/controllib/uorb/UOrbSubscription.hpp @@ -39,8 +39,8 @@ #pragma once #include -#include "Block.hpp" -#include "List.hpp" +#include "../block/Block.hpp" +#include "../block/List.hpp" namespace control diff --git a/src/modules/controllib/uorb/blocks.cpp b/src/modules/controllib/uorb/blocks.cpp new file mode 100644 index 0000000000..6e5ade5199 --- /dev/null +++ b/src/modules/controllib/uorb/blocks.cpp @@ -0,0 +1,64 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file uorb_blocks.cpp + * + * uorb block library code + */ + +#include "blocks.hpp" + +namespace control +{ + +BlockUorbEnabledAutopilot::BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name) : + SuperBlock(parent, name), + // subscriptions + _att(&getSubscriptions(), ORB_ID(vehicle_attitude), 20), + _attCmd(&getSubscriptions(), ORB_ID(vehicle_attitude_setpoint), 20), + _ratesCmd(&getSubscriptions(), ORB_ID(vehicle_rates_setpoint), 20), + _pos(&getSubscriptions() , ORB_ID(vehicle_global_position), 20), + _posCmd(&getSubscriptions(), ORB_ID(vehicle_global_position_set_triplet), 20), + _manual(&getSubscriptions(), ORB_ID(manual_control_setpoint), 20), + _status(&getSubscriptions(), ORB_ID(vehicle_status), 20), + _param_update(&getSubscriptions(), ORB_ID(parameter_update), 1000), // limit to 1 Hz + // publications + _actuators(&getPublications(), ORB_ID(actuator_controls_0)) +{ +} + +BlockUorbEnabledAutopilot::~BlockUorbEnabledAutopilot() {}; + +} // namespace control + diff --git a/src/modules/controllib/uorb/blocks.hpp b/src/modules/controllib/uorb/blocks.hpp new file mode 100644 index 0000000000..54f31735ce --- /dev/null +++ b/src/modules/controllib/uorb/blocks.hpp @@ -0,0 +1,90 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file uorb_blocks.h + * + * uorb block library code + */ + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include "../blocks.hpp" +#include "UOrbSubscription.hpp" +#include "UOrbPublication.hpp" + +namespace control +{ + +/** + * UorbEnabledAutopilot + */ +class __EXPORT BlockUorbEnabledAutopilot : public SuperBlock +{ +protected: + // subscriptions + UOrbSubscription _att; + UOrbSubscription _attCmd; + UOrbSubscription _ratesCmd; + UOrbSubscription _pos; + UOrbSubscription _posCmd; + UOrbSubscription _manual; + UOrbSubscription _status; + UOrbSubscription _param_update; + // publications + UOrbPublication _actuators; +public: + BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name); + virtual ~BlockUorbEnabledAutopilot(); +}; + +} // namespace control + diff --git a/src/modules/controllib/fixedwing.cpp b/src/modules/fixedwing_backside/fixedwing.cpp similarity index 93% rename from src/modules/controllib/fixedwing.cpp rename to src/modules/fixedwing_backside/fixedwing.cpp index 77b2ac8063..d5dc746e0d 100644 --- a/src/modules/controllib/fixedwing.cpp +++ b/src/modules/fixedwing_backside/fixedwing.cpp @@ -123,24 +123,6 @@ void BlockWaypointGuidance::update(vehicle_global_position_s &pos, _xtYawLimit.update(_xt2Yaw.update(xtrackError.distance))); } -BlockUorbEnabledAutopilot::BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name) : - SuperBlock(parent, name), - // subscriptions - _att(&getSubscriptions(), ORB_ID(vehicle_attitude), 20), - _attCmd(&getSubscriptions(), ORB_ID(vehicle_attitude_setpoint), 20), - _ratesCmd(&getSubscriptions(), ORB_ID(vehicle_rates_setpoint), 20), - _pos(&getSubscriptions() , ORB_ID(vehicle_global_position), 20), - _posCmd(&getSubscriptions(), ORB_ID(vehicle_global_position_set_triplet), 20), - _manual(&getSubscriptions(), ORB_ID(manual_control_setpoint), 20), - _status(&getSubscriptions(), ORB_ID(vehicle_status), 20), - _param_update(&getSubscriptions(), ORB_ID(parameter_update), 1000), // limit to 1 Hz - // publications - _actuators(&getPublications(), ORB_ID(actuator_controls_0)) -{ -} - -BlockUorbEnabledAutopilot::~BlockUorbEnabledAutopilot() {}; - BlockMultiModeBacksideAutopilot::BlockMultiModeBacksideAutopilot(SuperBlock *parent, const char *name) : BlockUorbEnabledAutopilot(parent, name), _stabilization(this, ""), // no name needed, already unique diff --git a/src/modules/controllib/fixedwing.hpp b/src/modules/fixedwing_backside/fixedwing.hpp similarity index 87% rename from src/modules/controllib/fixedwing.hpp rename to src/modules/fixedwing_backside/fixedwing.hpp index e4028c40d7..eb5d383810 100644 --- a/src/modules/controllib/fixedwing.hpp +++ b/src/modules/fixedwing_backside/fixedwing.hpp @@ -39,27 +39,8 @@ #pragma once -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -#include -#include - -#include "blocks.hpp" -#include "block/UOrbSubscription.hpp" -#include "block/UOrbPublication.hpp" +#include +#include extern "C" { #include @@ -269,28 +250,6 @@ public: float getPsiCmd() { return _psiCmd; } }; -/** - * UorbEnabledAutopilot - */ -class __EXPORT BlockUorbEnabledAutopilot : public SuperBlock -{ -protected: - // subscriptions - UOrbSubscription _att; - UOrbSubscription _attCmd; - UOrbSubscription _ratesCmd; - UOrbSubscription _pos; - UOrbSubscription _posCmd; - UOrbSubscription _manual; - UOrbSubscription _status; - UOrbSubscription _param_update; - // publications - UOrbPublication _actuators; -public: - BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name); - virtual ~BlockUorbEnabledAutopilot(); -}; - /** * Multi-mode Autopilot */ diff --git a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp index 4803a526eb..f4ea050880 100644 --- a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp +++ b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp @@ -45,12 +45,13 @@ #include #include #include -#include #include #include #include #include +#include "fixedwing.hpp" + static bool thread_should_exit = false; /**< Deamon exit flag */ static bool thread_running = false; /**< Deamon status flag */ static int deamon_task; /**< Handle of deamon task / thread */ diff --git a/src/modules/fixedwing_backside/module.mk b/src/modules/fixedwing_backside/module.mk index ec958d7cbb..133728781d 100644 --- a/src/modules/fixedwing_backside/module.mk +++ b/src/modules/fixedwing_backside/module.mk @@ -38,4 +38,5 @@ MODULE_COMMAND = fixedwing_backside SRCS = fixedwing_backside_main.cpp \ + fixedwing.cpp \ params.c diff --git a/src/modules/segway/BlockSegwayController.cpp b/src/modules/segway/BlockSegwayController.cpp new file mode 100644 index 0000000000..b7a0bbbccb --- /dev/null +++ b/src/modules/segway/BlockSegwayController.cpp @@ -0,0 +1,56 @@ +#include "BlockSegwayController.hpp" + +void BlockSegwayController::update() { + // wait for a sensor update, check for exit condition every 100 ms + if (poll(&_attPoll, 1, 100) < 0) return; // poll error + + uint64_t newTimeStamp = hrt_absolute_time(); + float dt = (newTimeStamp - _timeStamp) / 1.0e6f; + _timeStamp = newTimeStamp; + + // check for sane values of dt + // to prevent large control responses + if (dt > 1.0f || dt < 0) return; + + // set dt for all child blocks + setDt(dt); + + // check for new updates + if (_param_update.updated()) updateParams(); + + // get new information from subscriptions + updateSubscriptions(); + + // default all output to zero unless handled by mode + for (unsigned i = 2; i < NUM_ACTUATOR_CONTROLS; i++) + _actuators.control[i] = 0.0f; + + // only update guidance in auto mode + if (_status.state_machine == SYSTEM_STATE_AUTO) { + // update guidance + } + + // XXX handle STABILIZED (loiter on spot) as well + // once the system switches from manual or auto to stabilized + // the setpoint should update to loitering around this position + + // handle autopilot modes + if (_status.state_machine == SYSTEM_STATE_AUTO || + _status.state_machine == SYSTEM_STATE_STABILIZED) { + + float spdCmd = phi2spd.update(_att.phi); + + // output + _actuators.control[0] = spdCmd; + _actuators.control[1] = spdCmd; + + } else if (_status.state_machine == SYSTEM_STATE_MANUAL) { + _actuators.control[0] = _manual.roll; + _actuators.control[1] = _manual.roll; + } + + // update all publications + updatePublications(); + +} + diff --git a/src/modules/segway/BlockSegwayController.hpp b/src/modules/segway/BlockSegwayController.hpp new file mode 100644 index 0000000000..b16d38338b --- /dev/null +++ b/src/modules/segway/BlockSegwayController.hpp @@ -0,0 +1,18 @@ +#pragma once + +#include + +using namespace control; + +class BlockSegwayController : public control::BlockUorbEnabledAutopilot { +public: + BlockSegwayController() : + BlockUorbEnabledAutopilot(NULL,"SEG"), + phi2spd(this, "PHI2SPD") + { + } + void update(); +private: + BlockP phi2spd; +}; + diff --git a/src/modules/segway/module.mk b/src/modules/segway/module.mk new file mode 100644 index 0000000000..d5da856010 --- /dev/null +++ b/src/modules/segway/module.mk @@ -0,0 +1,42 @@ +############################################################################ +# +# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +# +# segway controller +# + +MODULE_COMMAND = segway + +SRCS = segway_main.cpp \ + BlockSegwayController.cpp \ + params.c diff --git a/src/modules/segway/params.c b/src/modules/segway/params.c new file mode 100644 index 0000000000..db30af4160 --- /dev/null +++ b/src/modules/segway/params.c @@ -0,0 +1,72 @@ +#include + +// currently tuned for easystar from arkhangar in HIL +//https://github.com/arktools/arkhangar + +// 16 is max name length + +// gyro low pass filter +PARAM_DEFINE_FLOAT(FWB_P_LP, 300.0f); // roll rate low pass cut freq +PARAM_DEFINE_FLOAT(FWB_Q_LP, 300.0f); // pitch rate low pass cut freq +PARAM_DEFINE_FLOAT(FWB_R_LP, 300.0f); // yaw rate low pass cut freq + +// yaw washout +PARAM_DEFINE_FLOAT(FWB_R_HP, 1.0f); // yaw rate high pass + +// stabilization mode +PARAM_DEFINE_FLOAT(FWB_P2AIL, 0.3f); // roll rate 2 aileron +PARAM_DEFINE_FLOAT(FWB_Q2ELV, 0.1f); // pitch rate 2 elevator +PARAM_DEFINE_FLOAT(FWB_R2RDR, 0.1f); // yaw rate 2 rudder + +// psi -> phi -> p +PARAM_DEFINE_FLOAT(FWB_PSI2PHI, 0.5f); // heading 2 roll +PARAM_DEFINE_FLOAT(FWB_PHI2P, 1.0f); // roll to roll rate +PARAM_DEFINE_FLOAT(FWB_PHI_LIM_MAX, 0.3f); // roll limit, 28 deg + +// velocity -> theta +PARAM_DEFINE_FLOAT(FWB_V2THE_P, 1.0f); // velocity to pitch angle PID, prop gain +PARAM_DEFINE_FLOAT(FWB_V2THE_I, 0.0f); // integral gain +PARAM_DEFINE_FLOAT(FWB_V2THE_D, 0.0f); // derivative gain +PARAM_DEFINE_FLOAT(FWB_V2THE_D_LP, 0.0f); // derivative low-pass +PARAM_DEFINE_FLOAT(FWB_V2THE_I_MAX, 0.0f); // integrator wind up guard +PARAM_DEFINE_FLOAT(FWB_THE_MIN, -0.5f); // the max commanded pitch angle +PARAM_DEFINE_FLOAT(FWB_THE_MAX, 0.5f); // the min commanded pitch angle + + +// theta -> q +PARAM_DEFINE_FLOAT(FWB_THE2Q_P, 1.0f); // pitch angle to pitch-rate PID +PARAM_DEFINE_FLOAT(FWB_THE2Q_I, 0.0f); +PARAM_DEFINE_FLOAT(FWB_THE2Q_D, 0.0f); +PARAM_DEFINE_FLOAT(FWB_THE2Q_D_LP, 0.0f); +PARAM_DEFINE_FLOAT(FWB_THE2Q_I_MAX, 0.0f); + +// h -> thr +PARAM_DEFINE_FLOAT(FWB_H2THR_P, 0.01f); // altitude to throttle PID +PARAM_DEFINE_FLOAT(FWB_H2THR_I, 0.0f); +PARAM_DEFINE_FLOAT(FWB_H2THR_D, 0.0f); +PARAM_DEFINE_FLOAT(FWB_H2THR_D_LP, 0.0f); +PARAM_DEFINE_FLOAT(FWB_H2THR_I_MAX, 0.0f); + +// crosstrack +PARAM_DEFINE_FLOAT(FWB_XT2YAW_MAX, 1.57f); // cross-track to yaw angle limit 90 deg +PARAM_DEFINE_FLOAT(FWB_XT2YAW, 0.005f); // cross-track to yaw angle gain + +// speed command +PARAM_DEFINE_FLOAT(FWB_V_MIN, 10.0f); // minimum commanded velocity +PARAM_DEFINE_FLOAT(FWB_V_CMD, 12.0f); // commanded velocity +PARAM_DEFINE_FLOAT(FWB_V_MAX, 16.0f); // maximum commanded velocity + +// rate of climb +// this is what rate of climb is commanded (in m/s) +// when the pitch stick is fully defelcted in simple mode +PARAM_DEFINE_FLOAT(FWB_CR_MAX, 1.0f); + +// climb rate -> thr +PARAM_DEFINE_FLOAT(FWB_CR2THR_P, 0.01f); // rate of climb to throttle PID +PARAM_DEFINE_FLOAT(FWB_CR2THR_I, 0.0f); +PARAM_DEFINE_FLOAT(FWB_CR2THR_D, 0.0f); +PARAM_DEFINE_FLOAT(FWB_CR2THR_D_LP, 0.0f); +PARAM_DEFINE_FLOAT(FWB_CR2THR_I_MAX, 0.0f); + +PARAM_DEFINE_FLOAT(FWB_TRIM_THR, 0.8f); // trim throttle (0,1) +PARAM_DEFINE_FLOAT(FWB_TRIM_V, 12.0f); // trim velocity, m/s diff --git a/src/modules/segway/segway_main.cpp b/src/modules/segway/segway_main.cpp new file mode 100644 index 0000000000..8be1cc7aaf --- /dev/null +++ b/src/modules/segway/segway_main.cpp @@ -0,0 +1,173 @@ +/**************************************************************************** + * + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. + * Author: James Goppert + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file segway_main.cpp + * @author James Goppert + * + * Segway controller using control library + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "BlockSegwayController.hpp" + +static bool thread_should_exit = false; /**< Deamon exit flag */ +static bool thread_running = false; /**< Deamon status flag */ +static int deamon_task; /**< Handle of deamon task / thread */ + +/** + * Deamon management function. + */ +extern "C" __EXPORT int segway_main(int argc, char *argv[]); + +/** + * Mainloop of deamon. + */ +int control_demo_thread_main(int argc, char *argv[]); + +/** + * Test function + */ +void test(); + +/** + * Print the correct usage. + */ +static void usage(const char *reason); + +static void +usage(const char *reason) +{ + if (reason) + fprintf(stderr, "%s\n", reason); + + fprintf(stderr, "usage: segway {start|stop|status} [-p ]\n\n"); + exit(1); +} + +/** + * The deamon app only briefly exists to start + * the background job. The stack size assigned in the + * Makefile does only apply to this management task. + * + * The actual stack size should be set in the call + * to task_create(). + */ +int segway_main(int argc, char *argv[]) +{ + + if (argc < 1) + usage("missing command"); + + if (!strcmp(argv[1], "start")) { + + if (thread_running) { + warnx("already running"); + /* this is not an error */ + exit(0); + } + + thread_should_exit = false; + + deamon_task = task_spawn_cmd("segway", + SCHED_DEFAULT, + SCHED_PRIORITY_MAX - 10, + 5120, + control_demo_thread_main, + (argv) ? (const char **)&argv[2] : (const char **)NULL); + exit(0); + } + + if (!strcmp(argv[1], "test")) { + test(); + exit(0); + } + + if (!strcmp(argv[1], "stop")) { + thread_should_exit = true; + exit(0); + } + + if (!strcmp(argv[1], "status")) { + if (thread_running) { + warnx("is running"); + + } else { + warnx("not started"); + } + + exit(0); + } + + usage("unrecognized command"); + exit(1); +} + +int control_demo_thread_main(int argc, char *argv[]) +{ + + warnx("starting"); + + using namespace control; + + BlockSegwayController autopilot; + + thread_running = true; + + while (!thread_should_exit) { + autopilot.update(); + } + + warnx("exiting."); + + thread_running = false; + + return 0; +} + +void test() +{ + warnx("beginning control lib test"); + control::basicBlocksTest(); +} From dc542b2a4818bfc1c3c1cd24c5ee513d5b5ea0c4 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sun, 28 Jul 2013 22:27:05 -0400 Subject: [PATCH 13/80] Segway stabilized. --- src/drivers/md25/md25.cpp | 17 +++-- src/drivers/md25/md25.hpp | 13 ++++ src/drivers/md25/md25_main.cpp | 27 +++++++- src/modules/controllib/uorb/blocks.cpp | 37 ++++++++++ src/modules/controllib/uorb/blocks.hpp | 23 +++++++ src/modules/fixedwing_backside/fixedwing.cpp | 37 ---------- src/modules/fixedwing_backside/fixedwing.hpp | 23 ------- src/modules/segway/BlockSegwayController.cpp | 19 +++--- src/modules/segway/BlockSegwayController.hpp | 13 +++- src/modules/segway/params.c | 72 ++------------------ src/modules/segway/segway_main.cpp | 22 +----- 11 files changed, 138 insertions(+), 165 deletions(-) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index d6dd64a094..d43e3aef9e 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -116,7 +116,8 @@ MD25::MD25(const char *deviceName, int bus, setMotor2Speed(0); resetEncoders(); _setMode(MD25::MODE_UNSIGNED_SPEED); - setSpeedRegulation(true); + setSpeedRegulation(false); + setMotorAccel(10); setTimeout(true); } @@ -308,6 +309,12 @@ int MD25::setDeviceAddress(uint8_t address) return OK; } +int MD25::setMotorAccel(uint8_t accel) +{ + return _writeUint8(REG_ACCEL_RATE_RW, + accel); +} + int MD25::setMotor1Speed(float value) { return _writeUint8(REG_SPEED1_RW, @@ -461,12 +468,12 @@ int md25Test(const char *deviceName, uint8_t bus, uint8_t address) MD25 md25("/dev/md25", bus, address); // print status - char buf[200]; + char buf[400]; md25.status(buf, sizeof(buf)); printf("%s\n", buf); // setup for test - md25.setSpeedRegulation(true); + md25.setSpeedRegulation(false); md25.setTimeout(true); float dt = 0.1; float speed = 0.2; @@ -568,12 +575,12 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address, float amplitu MD25 md25("/dev/md25", bus, address); // print status - char buf[200]; + char buf[400]; md25.status(buf, sizeof(buf)); printf("%s\n", buf); // setup for test - md25.setSpeedRegulation(true); + md25.setSpeedRegulation(false); md25.setTimeout(true); float dt = 0.01; float t_final = 60.0; diff --git a/src/drivers/md25/md25.hpp b/src/drivers/md25/md25.hpp index 780978514e..1661f67f9a 100644 --- a/src/drivers/md25/md25.hpp +++ b/src/drivers/md25/md25.hpp @@ -212,6 +212,19 @@ public: */ int setDeviceAddress(uint8_t address); + /** + * set motor acceleration + * @param accel + * controls motor speed change (1-10) + * accel rate | time for full fwd. to full rev. + * 1 | 6.375 s + * 2 | 1.6 s + * 3 | 0.675 s + * 5(default) | 1.275 s + * 10 | 0.65 s + */ + int setMotorAccel(uint8_t accel); + /** * set motor 1 speed * @param normSpeed normalize speed between -1 and 1 diff --git a/src/drivers/md25/md25_main.cpp b/src/drivers/md25/md25_main.cpp index 3260705c1c..7e5904d050 100644 --- a/src/drivers/md25/md25_main.cpp +++ b/src/drivers/md25/md25_main.cpp @@ -82,7 +82,7 @@ usage(const char *reason) if (reason) fprintf(stderr, "%s\n", reason); - fprintf(stderr, "usage: md25 {start|stop|status|search|test|change_address}\n\n"); + fprintf(stderr, "usage: md25 {start|stop|read|status|search|test|change_address}\n\n"); exit(1); } @@ -184,6 +184,29 @@ int md25_main(int argc, char *argv[]) exit(0); } + if (!strcmp(argv[1], "read")) { + if (argc < 4) { + printf("usage: md25 read bus address\n"); + exit(0); + } + + const char *deviceName = "/dev/md25"; + + uint8_t bus = strtoul(argv[2], nullptr, 0); + + uint8_t address = strtoul(argv[3], nullptr, 0); + + MD25 md25(deviceName, bus, address); + + // print status + char buf[400]; + md25.status(buf, sizeof(buf)); + printf("%s\n", buf); + + exit(0); + } + + if (!strcmp(argv[1], "search")) { if (argc < 3) { printf("usage: md25 search bus\n"); @@ -268,7 +291,7 @@ int md25_thread_main(int argc, char *argv[]) uint8_t address = strtoul(argv[4], nullptr, 0); // start - MD25 md25("/dev/md25", bus, address); + MD25 md25(deviceName, bus, address); thread_running = true; diff --git a/src/modules/controllib/uorb/blocks.cpp b/src/modules/controllib/uorb/blocks.cpp index 6e5ade5199..448a42a996 100644 --- a/src/modules/controllib/uorb/blocks.cpp +++ b/src/modules/controllib/uorb/blocks.cpp @@ -42,6 +42,43 @@ namespace control { +BlockWaypointGuidance::BlockWaypointGuidance(SuperBlock *parent, const char *name) : + SuperBlock(parent, name), + _xtYawLimit(this, "XT2YAW"), + _xt2Yaw(this, "XT2YAW"), + _psiCmd(0) +{ +} + +BlockWaypointGuidance::~BlockWaypointGuidance() {}; + +void BlockWaypointGuidance::update(vehicle_global_position_s &pos, + vehicle_attitude_s &att, + vehicle_global_position_setpoint_s &posCmd, + vehicle_global_position_setpoint_s &lastPosCmd) +{ + + // heading to waypoint + float psiTrack = get_bearing_to_next_waypoint( + (double)pos.lat / (double)1e7d, + (double)pos.lon / (double)1e7d, + (double)posCmd.lat / (double)1e7d, + (double)posCmd.lon / (double)1e7d); + + // cross track + struct crosstrack_error_s xtrackError; + get_distance_to_line(&xtrackError, + (double)pos.lat / (double)1e7d, + (double)pos.lon / (double)1e7d, + (double)lastPosCmd.lat / (double)1e7d, + (double)lastPosCmd.lon / (double)1e7d, + (double)posCmd.lat / (double)1e7d, + (double)posCmd.lon / (double)1e7d); + + _psiCmd = _wrap_2pi(psiTrack - + _xtYawLimit.update(_xt2Yaw.update(xtrackError.distance))); +} + BlockUorbEnabledAutopilot::BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name) : SuperBlock(parent, name), // subscriptions diff --git a/src/modules/controllib/uorb/blocks.hpp b/src/modules/controllib/uorb/blocks.hpp index 54f31735ce..9c0720aa5e 100644 --- a/src/modules/controllib/uorb/blocks.hpp +++ b/src/modules/controllib/uorb/blocks.hpp @@ -57,6 +57,10 @@ #include #include +extern "C" { +#include +} + #include "../blocks.hpp" #include "UOrbSubscription.hpp" #include "UOrbPublication.hpp" @@ -64,6 +68,25 @@ namespace control { +/** + * Waypoint Guidance block + */ +class __EXPORT BlockWaypointGuidance : public SuperBlock +{ +private: + BlockLimitSym _xtYawLimit; + BlockP _xt2Yaw; + float _psiCmd; +public: + BlockWaypointGuidance(SuperBlock *parent, const char *name); + virtual ~BlockWaypointGuidance(); + void update(vehicle_global_position_s &pos, + vehicle_attitude_s &att, + vehicle_global_position_setpoint_s &posCmd, + vehicle_global_position_setpoint_s &lastPosCmd); + float getPsiCmd() { return _psiCmd; } +}; + /** * UorbEnabledAutopilot */ diff --git a/src/modules/fixedwing_backside/fixedwing.cpp b/src/modules/fixedwing_backside/fixedwing.cpp index d5dc746e0d..f655a13bd7 100644 --- a/src/modules/fixedwing_backside/fixedwing.cpp +++ b/src/modules/fixedwing_backside/fixedwing.cpp @@ -86,43 +86,6 @@ void BlockStabilization::update(float pCmd, float qCmd, float rCmd, _yawDamper.update(rCmd, r, outputScale); } -BlockWaypointGuidance::BlockWaypointGuidance(SuperBlock *parent, const char *name) : - SuperBlock(parent, name), - _xtYawLimit(this, "XT2YAW"), - _xt2Yaw(this, "XT2YAW"), - _psiCmd(0) -{ -} - -BlockWaypointGuidance::~BlockWaypointGuidance() {}; - -void BlockWaypointGuidance::update(vehicle_global_position_s &pos, - vehicle_attitude_s &att, - vehicle_global_position_setpoint_s &posCmd, - vehicle_global_position_setpoint_s &lastPosCmd) -{ - - // heading to waypoint - float psiTrack = get_bearing_to_next_waypoint( - (double)pos.lat / (double)1e7d, - (double)pos.lon / (double)1e7d, - (double)posCmd.lat / (double)1e7d, - (double)posCmd.lon / (double)1e7d); - - // cross track - struct crosstrack_error_s xtrackError; - get_distance_to_line(&xtrackError, - (double)pos.lat / (double)1e7d, - (double)pos.lon / (double)1e7d, - (double)lastPosCmd.lat / (double)1e7d, - (double)lastPosCmd.lon / (double)1e7d, - (double)posCmd.lat / (double)1e7d, - (double)posCmd.lon / (double)1e7d); - - _psiCmd = _wrap_2pi(psiTrack - - _xtYawLimit.update(_xt2Yaw.update(xtrackError.distance))); -} - BlockMultiModeBacksideAutopilot::BlockMultiModeBacksideAutopilot(SuperBlock *parent, const char *name) : BlockUorbEnabledAutopilot(parent, name), _stabilization(this, ""), // no name needed, already unique diff --git a/src/modules/fixedwing_backside/fixedwing.hpp b/src/modules/fixedwing_backside/fixedwing.hpp index eb5d383810..3876e46301 100644 --- a/src/modules/fixedwing_backside/fixedwing.hpp +++ b/src/modules/fixedwing_backside/fixedwing.hpp @@ -42,10 +42,6 @@ #include #include -extern "C" { -#include -} - namespace control { @@ -231,25 +227,6 @@ public: * than frontside at high speeds. */ -/** - * Waypoint Guidance block - */ -class __EXPORT BlockWaypointGuidance : public SuperBlock -{ -private: - BlockLimitSym _xtYawLimit; - BlockP _xt2Yaw; - float _psiCmd; -public: - BlockWaypointGuidance(SuperBlock *parent, const char *name); - virtual ~BlockWaypointGuidance(); - void update(vehicle_global_position_s &pos, - vehicle_attitude_s &att, - vehicle_global_position_setpoint_s &posCmd, - vehicle_global_position_setpoint_s &lastPosCmd); - float getPsiCmd() { return _psiCmd; } -}; - /** * Multi-mode Autopilot */ diff --git a/src/modules/segway/BlockSegwayController.cpp b/src/modules/segway/BlockSegwayController.cpp index b7a0bbbccb..682758a14b 100644 --- a/src/modules/segway/BlockSegwayController.cpp +++ b/src/modules/segway/BlockSegwayController.cpp @@ -30,23 +30,24 @@ void BlockSegwayController::update() { // update guidance } - // XXX handle STABILIZED (loiter on spot) as well - // once the system switches from manual or auto to stabilized - // the setpoint should update to loitering around this position + // compute speed command + float spdCmd = -theta2spd.update(_att.pitch) - q2spd.update(_att.pitchspeed); // handle autopilot modes if (_status.state_machine == SYSTEM_STATE_AUTO || _status.state_machine == SYSTEM_STATE_STABILIZED) { - - float spdCmd = phi2spd.update(_att.phi); - - // output _actuators.control[0] = spdCmd; _actuators.control[1] = spdCmd; } else if (_status.state_machine == SYSTEM_STATE_MANUAL) { - _actuators.control[0] = _manual.roll; - _actuators.control[1] = _manual.roll; + if (_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) { + _actuators.control[CH_LEFT] = _manual.throttle; + _actuators.control[CH_RIGHT] = _manual.pitch; + + } else if (_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) { + _actuators.control[0] = spdCmd; + _actuators.control[1] = spdCmd; + } } // update all publications diff --git a/src/modules/segway/BlockSegwayController.hpp b/src/modules/segway/BlockSegwayController.hpp index b16d38338b..e2faa49169 100644 --- a/src/modules/segway/BlockSegwayController.hpp +++ b/src/modules/segway/BlockSegwayController.hpp @@ -8,11 +8,20 @@ class BlockSegwayController : public control::BlockUorbEnabledAutopilot { public: BlockSegwayController() : BlockUorbEnabledAutopilot(NULL,"SEG"), - phi2spd(this, "PHI2SPD") + theta2spd(this, "THETA2SPD"), + q2spd(this, "Q2SPD"), + _attPoll(), + _timeStamp(0) { + _attPoll.fd = _att.getHandle(); + _attPoll.events = POLLIN; } void update(); private: - BlockP phi2spd; + enum {CH_LEFT, CH_RIGHT}; + BlockPI theta2spd; + BlockP q2spd; + struct pollfd _attPoll; + uint64_t _timeStamp; }; diff --git a/src/modules/segway/params.c b/src/modules/segway/params.c index db30af4160..1669785d31 100644 --- a/src/modules/segway/params.c +++ b/src/modules/segway/params.c @@ -1,72 +1,8 @@ #include -// currently tuned for easystar from arkhangar in HIL -//https://github.com/arktools/arkhangar - // 16 is max name length +PARAM_DEFINE_FLOAT(SEG_THETA2SPD_P, 10.0f); // pitch to speed +PARAM_DEFINE_FLOAT(SEG_THETA2SPD_I, 0.0f); // pitch integral to speed +PARAM_DEFINE_FLOAT(SEG_THETA2SPD_I_MAX, 0.0f); // integral limiter +PARAM_DEFINE_FLOAT(SEG_Q2SPD, 1.0f); // pitch rate to speed -// gyro low pass filter -PARAM_DEFINE_FLOAT(FWB_P_LP, 300.0f); // roll rate low pass cut freq -PARAM_DEFINE_FLOAT(FWB_Q_LP, 300.0f); // pitch rate low pass cut freq -PARAM_DEFINE_FLOAT(FWB_R_LP, 300.0f); // yaw rate low pass cut freq - -// yaw washout -PARAM_DEFINE_FLOAT(FWB_R_HP, 1.0f); // yaw rate high pass - -// stabilization mode -PARAM_DEFINE_FLOAT(FWB_P2AIL, 0.3f); // roll rate 2 aileron -PARAM_DEFINE_FLOAT(FWB_Q2ELV, 0.1f); // pitch rate 2 elevator -PARAM_DEFINE_FLOAT(FWB_R2RDR, 0.1f); // yaw rate 2 rudder - -// psi -> phi -> p -PARAM_DEFINE_FLOAT(FWB_PSI2PHI, 0.5f); // heading 2 roll -PARAM_DEFINE_FLOAT(FWB_PHI2P, 1.0f); // roll to roll rate -PARAM_DEFINE_FLOAT(FWB_PHI_LIM_MAX, 0.3f); // roll limit, 28 deg - -// velocity -> theta -PARAM_DEFINE_FLOAT(FWB_V2THE_P, 1.0f); // velocity to pitch angle PID, prop gain -PARAM_DEFINE_FLOAT(FWB_V2THE_I, 0.0f); // integral gain -PARAM_DEFINE_FLOAT(FWB_V2THE_D, 0.0f); // derivative gain -PARAM_DEFINE_FLOAT(FWB_V2THE_D_LP, 0.0f); // derivative low-pass -PARAM_DEFINE_FLOAT(FWB_V2THE_I_MAX, 0.0f); // integrator wind up guard -PARAM_DEFINE_FLOAT(FWB_THE_MIN, -0.5f); // the max commanded pitch angle -PARAM_DEFINE_FLOAT(FWB_THE_MAX, 0.5f); // the min commanded pitch angle - - -// theta -> q -PARAM_DEFINE_FLOAT(FWB_THE2Q_P, 1.0f); // pitch angle to pitch-rate PID -PARAM_DEFINE_FLOAT(FWB_THE2Q_I, 0.0f); -PARAM_DEFINE_FLOAT(FWB_THE2Q_D, 0.0f); -PARAM_DEFINE_FLOAT(FWB_THE2Q_D_LP, 0.0f); -PARAM_DEFINE_FLOAT(FWB_THE2Q_I_MAX, 0.0f); - -// h -> thr -PARAM_DEFINE_FLOAT(FWB_H2THR_P, 0.01f); // altitude to throttle PID -PARAM_DEFINE_FLOAT(FWB_H2THR_I, 0.0f); -PARAM_DEFINE_FLOAT(FWB_H2THR_D, 0.0f); -PARAM_DEFINE_FLOAT(FWB_H2THR_D_LP, 0.0f); -PARAM_DEFINE_FLOAT(FWB_H2THR_I_MAX, 0.0f); - -// crosstrack -PARAM_DEFINE_FLOAT(FWB_XT2YAW_MAX, 1.57f); // cross-track to yaw angle limit 90 deg -PARAM_DEFINE_FLOAT(FWB_XT2YAW, 0.005f); // cross-track to yaw angle gain - -// speed command -PARAM_DEFINE_FLOAT(FWB_V_MIN, 10.0f); // minimum commanded velocity -PARAM_DEFINE_FLOAT(FWB_V_CMD, 12.0f); // commanded velocity -PARAM_DEFINE_FLOAT(FWB_V_MAX, 16.0f); // maximum commanded velocity - -// rate of climb -// this is what rate of climb is commanded (in m/s) -// when the pitch stick is fully defelcted in simple mode -PARAM_DEFINE_FLOAT(FWB_CR_MAX, 1.0f); - -// climb rate -> thr -PARAM_DEFINE_FLOAT(FWB_CR2THR_P, 0.01f); // rate of climb to throttle PID -PARAM_DEFINE_FLOAT(FWB_CR2THR_I, 0.0f); -PARAM_DEFINE_FLOAT(FWB_CR2THR_D, 0.0f); -PARAM_DEFINE_FLOAT(FWB_CR2THR_D_LP, 0.0f); -PARAM_DEFINE_FLOAT(FWB_CR2THR_I_MAX, 0.0f); - -PARAM_DEFINE_FLOAT(FWB_TRIM_THR, 0.8f); // trim throttle (0,1) -PARAM_DEFINE_FLOAT(FWB_TRIM_V, 12.0f); // trim velocity, m/s diff --git a/src/modules/segway/segway_main.cpp b/src/modules/segway/segway_main.cpp index 8be1cc7aaf..061fbf9b9d 100644 --- a/src/modules/segway/segway_main.cpp +++ b/src/modules/segway/segway_main.cpp @@ -64,12 +64,7 @@ extern "C" __EXPORT int segway_main(int argc, char *argv[]); /** * Mainloop of deamon. */ -int control_demo_thread_main(int argc, char *argv[]); - -/** - * Test function - */ -void test(); +int segway_thread_main(int argc, char *argv[]); /** * Print the correct usage. @@ -114,16 +109,11 @@ int segway_main(int argc, char *argv[]) SCHED_DEFAULT, SCHED_PRIORITY_MAX - 10, 5120, - control_demo_thread_main, + segway_thread_main, (argv) ? (const char **)&argv[2] : (const char **)NULL); exit(0); } - if (!strcmp(argv[1], "test")) { - test(); - exit(0); - } - if (!strcmp(argv[1], "stop")) { thread_should_exit = true; exit(0); @@ -144,7 +134,7 @@ int segway_main(int argc, char *argv[]) exit(1); } -int control_demo_thread_main(int argc, char *argv[]) +int segway_thread_main(int argc, char *argv[]) { warnx("starting"); @@ -165,9 +155,3 @@ int control_demo_thread_main(int argc, char *argv[]) return 0; } - -void test() -{ - warnx("beginning control lib test"); - control::basicBlocksTest(); -} From a569cd834c13052ef3210ab9b8c1afd03b81fef6 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sun, 28 Jul 2013 22:28:04 -0400 Subject: [PATCH 14/80] Added segway rc script. --- ROMFS/px4fmu_common/init.d/40_io_segway | 122 ++++++++++++++++++++++++ 1 file changed, 122 insertions(+) create mode 100644 ROMFS/px4fmu_common/init.d/40_io_segway diff --git a/ROMFS/px4fmu_common/init.d/40_io_segway b/ROMFS/px4fmu_common/init.d/40_io_segway new file mode 100644 index 0000000000..5742d685aa --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/40_io_segway @@ -0,0 +1,122 @@ +#!nsh +# +# Flight startup script for PX4FMU+PX4IO +# + +# disable USB and autostart +set USB no +set MODE custom + +# +# Start the ORB (first app to start) +# +uorb start + +# +# Load microSD params +# +echo "[init] loading microSD params" +param select /fs/microsd/params +if [ -f /fs/microsd/params ] +then + param load /fs/microsd/params +fi + +# +# Load default params for this platform +# +if param compare SYS_AUTOCONFIG 1 +then + # Set all params here, then disable autoconfig + param set SYS_AUTOCONFIG 0 + param save /fs/microsd/params +fi + +# +# Force some key parameters to sane values +# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor +# see https://pixhawk.ethz.ch/mavlink/ +# +param set MAV_TYPE 10 + +# +# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell) +# +if [ -f /fs/microsd/px4io.bin ] +then + echo "PX4IO Firmware found. Checking Upgrade.." + if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current + then + echo "No newer version, skipping upgrade." + else + echo "Loading /fs/microsd/px4io.bin" + if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log + then + cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current + echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log + else + echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log + echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode" + fi + fi +fi + +# +# Start MAVLink (depends on orb) +# +mavlink start -d /dev/ttyS1 -b 57600 +usleep 5000 + +# +# Start the commander (depends on orb, mavlink) +# +commander start + +# +# Start PX4IO interface (depends on orb, commander) +# +px4io start + +# +# Allow PX4IO to recover from midair restarts. +# this is very unlikely, but quite safe and robust. +px4io recovery + +# +# Disable px4io topic limiting +# +px4io limit 200 + +# +# Start the sensors (depends on orb, px4io) +# +sh /etc/init.d/rc.sensors + +# +# Start GPS interface (depends on orb) +# +gps start + +# +# Start the attitude estimator (depends on orb) +# +attitude_estimator_ekf start + +# +# Load mixer and start controllers (depends on px4io) +# +md25 start 3 0x58 +segway start + +# +# Start logging +# +sdlog2 start -r 50 -a -b 14 + +# +# Start system state +# +if blinkm start +then + blinkm systemstate +fi From c14a71c09564567936707edd96d4e266f9b67c74 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sat, 3 Aug 2013 10:06:10 -0700 Subject: [PATCH 15/80] Move NuttX configurations out of the NuttX tree proper. This reduces the diffs we have to carry against the NuttX upstream repo to just our local patches to the NuttX code itself. --- Makefile | 87 +- makefiles/setup.mk | 1 + makefiles/upload.mk | 2 - nuttx-configs/px4fmu-v1/include/board.h | 395 ++++++++ .../px4fmu-v1/include/nsh_romfsimg.h | 42 + nuttx-configs/px4fmu-v1/nsh/Make.defs | 179 ++++ nuttx-configs/px4fmu-v1/nsh/defconfig | 957 ++++++++++++++++++ nuttx-configs/px4fmu-v1/nsh/setenv.sh | 75 ++ nuttx-configs/px4fmu-v1/scripts/ld.script | 149 +++ nuttx-configs/px4fmu-v1/src/Makefile | 84 ++ nuttx-configs/px4fmu-v1/src/empty.c | 4 + nuttx-configs/px4io-v1/include/README.txt | 1 + nuttx-configs/px4io-v1/include/board.h | 172 ++++ nuttx-configs/px4io-v1/nsh/Make.defs | 166 +++ nuttx-configs/px4io-v1/nsh/appconfig | 32 + nuttx-configs/px4io-v1/nsh/defconfig | 559 ++++++++++ nuttx-configs/px4io-v1/nsh/setenv.sh | 47 + nuttx-configs/px4io-v1/scripts/ld.script | 129 +++ nuttx-configs/px4io-v1/src/Makefile | 84 ++ nuttx-configs/px4io-v1/src/empty.c | 4 + 20 files changed, 3126 insertions(+), 43 deletions(-) create mode 100644 nuttx-configs/px4fmu-v1/include/board.h create mode 100644 nuttx-configs/px4fmu-v1/include/nsh_romfsimg.h create mode 100644 nuttx-configs/px4fmu-v1/nsh/Make.defs create mode 100644 nuttx-configs/px4fmu-v1/nsh/defconfig create mode 100755 nuttx-configs/px4fmu-v1/nsh/setenv.sh create mode 100644 nuttx-configs/px4fmu-v1/scripts/ld.script create mode 100644 nuttx-configs/px4fmu-v1/src/Makefile create mode 100644 nuttx-configs/px4fmu-v1/src/empty.c create mode 100755 nuttx-configs/px4io-v1/include/README.txt create mode 100755 nuttx-configs/px4io-v1/include/board.h create mode 100644 nuttx-configs/px4io-v1/nsh/Make.defs create mode 100644 nuttx-configs/px4io-v1/nsh/appconfig create mode 100755 nuttx-configs/px4io-v1/nsh/defconfig create mode 100755 nuttx-configs/px4io-v1/nsh/setenv.sh create mode 100755 nuttx-configs/px4io-v1/scripts/ld.script create mode 100644 nuttx-configs/px4io-v1/src/Makefile create mode 100644 nuttx-configs/px4io-v1/src/empty.c diff --git a/Makefile b/Makefile index 7f98ffaf22..a2dcd97b8b 100644 --- a/Makefile +++ b/Makefile @@ -100,7 +100,7 @@ all: $(STAGED_FIRMWARES) # is taken care of. # $(STAGED_FIRMWARES): $(IMAGE_DIR)%.px4: $(BUILD_DIR)%.build/firmware.px4 - @echo %% Copying $@ + @$(ECHO) %% Copying $@ $(Q) $(COPY) $< $@ $(Q) $(COPY) $(patsubst %.px4,%.bin,$<) $(patsubst %.px4,%.bin,$@) @@ -111,9 +111,9 @@ $(STAGED_FIRMWARES): $(IMAGE_DIR)%.px4: $(BUILD_DIR)%.build/firmware.px4 $(BUILD_DIR)%.build/firmware.px4: config = $(patsubst $(BUILD_DIR)%.build/firmware.px4,%,$@) $(BUILD_DIR)%.build/firmware.px4: work_dir = $(BUILD_DIR)$(config).build/ $(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4: - @echo %%%% - @echo %%%% Building $(config) in $(work_dir) - @echo %%%% + @$(ECHO) %%%% + @$(ECHO) %%%% Building $(config) in $(work_dir) + @$(ECHO) %%%% $(Q) mkdir -p $(work_dir) $(Q) make -r -C $(work_dir) \ -f $(PX4_MK_DIR)firmware.mk \ @@ -132,8 +132,6 @@ $(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4: # XXX Should support fetching/unpacking from a separate directory to permit # downloads of the prebuilt archives as well... # -# XXX PX4IO configuration name is bad - NuttX configs should probably all be "px4" -# NUTTX_ARCHIVES = $(foreach board,$(BOARDS),$(ARCHIVE_DIR)$(board).export) .PHONY: archives archives: $(NUTTX_ARCHIVES) @@ -146,15 +144,22 @@ endif $(ARCHIVE_DIR)%.export: board = $(notdir $(basename $@)) $(ARCHIVE_DIR)%.export: configuration = nsh -$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC) $(NUTTX_APPS) - @echo %% Configuring NuttX for $(board) +$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC) + @$(ECHO) %% Configuring NuttX for $(board) $(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export) $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean + $(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)/nuttx-configs/$(board) .) $(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration)) - @echo %% Exporting NuttX for $(board) + @$(ECHO) %% Exporting NuttX for $(board) $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) export $(Q) mkdir -p $(dir $@) $(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@ + $(Q) (cd $(NUTTX_SRC)/configs && $(RMDIR) $(board)) + +$(NUTTX_SRC): + @$(ECHO) "" + @$(ECHO) "NuttX sources missing - clone https://github.com/PX4/NuttX.git and try again." + @$(ECHO) "" # # Cleanup targets. 'clean' should remove all built products and force @@ -176,40 +181,40 @@ distclean: clean # .PHONY: help help: - @echo "" - @echo " PX4 firmware builder" - @echo " ====================" - @echo "" - @echo " Available targets:" - @echo " ------------------" - @echo "" - @echo " archives" - @echo " Build the NuttX RTOS archives that are used by the firmware build." - @echo "" - @echo " all" - @echo " Build all firmware configs: $(CONFIGS)" - @echo " A limited set of configs can be built with CONFIGS=" - @echo "" + @$(ECHO) "" + @$(ECHO) " PX4 firmware builder" + @$(ECHO) " ====================" + @$(ECHO) "" + @$(ECHO) " Available targets:" + @$(ECHO) " ------------------" + @$(ECHO) "" + @$(ECHO) " archives" + @$(ECHO) " Build the NuttX RTOS archives that are used by the firmware build." + @$(ECHO) "" + @$(ECHO) " all" + @$(ECHO) " Build all firmware configs: $(CONFIGS)" + @$(ECHO) " A limited set of configs can be built with CONFIGS=" + @$(ECHO) "" @for config in $(CONFIGS); do \ echo " $$config"; \ echo " Build just the $$config firmware configuration."; \ echo ""; \ done - @echo " clean" - @echo " Remove all firmware build pieces." - @echo "" - @echo " distclean" - @echo " Remove all compilation products, including NuttX RTOS archives." - @echo "" - @echo " upload" - @echo " When exactly one config is being built, add this target to upload the" - @echo " firmware to the board when the build is complete. Not supported for" - @echo " all configurations." - @echo "" - @echo " Common options:" - @echo " ---------------" - @echo "" - @echo " V=1" - @echo " If V is set, more verbose output is printed during the build. This can" - @echo " help when diagnosing issues with the build or toolchain." - @echo "" + @$(ECHO) " clean" + @$(ECHO) " Remove all firmware build pieces." + @$(ECHO) "" + @$(ECHO) " distclean" + @$(ECHO) " Remove all compilation products, including NuttX RTOS archives." + @$(ECHO) "" + @$(ECHO) " upload" + @$(ECHO) " When exactly one config is being built, add this target to upload the" + @$(ECHO) " firmware to the board when the build is complete. Not supported for" + @$(ECHO) " all configurations." + @$(ECHO) "" + @$(ECHO) " Common options:" + @$(ECHO) " ---------------" + @$(ECHO) "" + @$(ECHO) " V=1" + @$(ECHO) " If V is set, more verbose output is printed during the build. This can" + @$(ECHO) " help when diagnosing issues with the build or toolchain." + @$(ECHO) "" diff --git a/makefiles/setup.mk b/makefiles/setup.mk index 92461fafbe..168e41a5cb 100644 --- a/makefiles/setup.mk +++ b/makefiles/setup.mk @@ -65,6 +65,7 @@ export INCLUDE_DIRS := $(PX4_MODULE_SRC) \ export MKFW = $(PX4_BASE)/Tools/px_mkfw.py export UPLOADER = $(PX4_BASE)/Tools/px_uploader.py export COPY = cp +export COPYDIR = cp -Rf export REMOVE = rm -f export RMDIR = rm -rf export GENROMFS = genromfs diff --git a/makefiles/upload.mk b/makefiles/upload.mk index 4b01b447d0..3aebef8637 100644 --- a/makefiles/upload.mk +++ b/makefiles/upload.mk @@ -27,8 +27,6 @@ all: upload-$(METHOD)-$(BOARD) upload-serial-px4fmu-v1: $(BUNDLE) $(UPLOADER) $(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE) -upload-serial-px4fmuv2: $(BUNDLE) $(UPLOADER) - $(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE) # # JTAG firmware uploading with OpenOCD diff --git a/nuttx-configs/px4fmu-v1/include/board.h b/nuttx-configs/px4fmu-v1/include/board.h new file mode 100644 index 0000000000..0fa93a1965 --- /dev/null +++ b/nuttx-configs/px4fmu-v1/include/board.h @@ -0,0 +1,395 @@ +/************************************************************************************ + * configs/stm32f4discovery/include/board.h + * include/arch/board/board.h + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +#ifndef __CONFIG_PX4FMU_V1_INCLUDE_BOARD_H +#define __CONFIG_PX4FMU_V1_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdio.h" +#include "stm32.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The PX4FMU uses a 24MHz crystal connected to the HSE. + * + * This is the canonical configuration: + * System Clock source : PLL (HSE) + * SYSCLK(Hz) : 168000000 Determined by PLL configuration + * HCLK(Hz) : 168000000 (STM32_RCC_CFGR_HPRE) + * AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE) + * APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1) + * APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2) + * HSE Frequency(Hz) : 24000000 (STM32_BOARD_XTAL) + * PLLM : 24 (STM32_PLLCFG_PLLM) + * PLLN : 336 (STM32_PLLCFG_PLLN) + * PLLP : 2 (STM32_PLLCFG_PLLP) + * PLLQ : 7 (STM32_PLLCFG_PLLQ) + * Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK + * Flash Latency(WS) : 5 + * Prefetch Buffer : OFF + * Instruction cache : ON + * Data cache : ON + * Require 48MHz for USB OTG FS, : Enabled + * SDIO and RNG clock + */ + +/* HSI - 16 MHz RC factory-trimmed + * LSI - 32 KHz RC + * HSE - On-board crystal frequency is 24MHz + * LSE - not installed + */ + +#define STM32_BOARD_XTAL 24000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +//#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE + * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * = (8,000,000 / 8) * 336 + * = 336,000,000 + * SYSCLK = PLL_VCO / PLLP + * = 336,000,000 / 2 = 168,000,000 + * USB OTG FS, SDIO and RNG Clock + * = PLL_VCO / PLLQ + * = 48,000,000 + */ + +#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(24) +#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336) +#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2 +#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(7) + +#define STM32_SYSCLK_FREQUENCY 168000000ul + +/* AHB clock (HCLK) is SYSCLK (168MHz) */ + +#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/4 (42MHz) */ + +#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4) + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */ + +#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx + * otherwise frequency is 2xAPBx. + * Note: TIM1,8 are on APB2, others on APB1 + */ + +#define STM32_TIM18_FREQUENCY (2*STM32_PCLK2_FREQUENCY) +#define STM32_TIM27_FREQUENCY (2*STM32_PCLK1_FREQUENCY) + +/* High-resolution timer + */ +#ifdef CONFIG_HRT_TIMER +# define HRT_TIMER 1 /* use timer1 for the HRT */ +# define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */ +#endif + +/* LED definitions ******************************************************************/ +/* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any + * way. The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with stm32_setled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_NLEDS 2 + +#define BOARD_LED_BLUE BOARD_LED1 +#define BOARD_LED_RED BOARD_LED2 + +/* LED bits for use with stm32_setleds() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) + +/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 2 LEDs on board the + * px4fmu-v1. The following definitions describe how NuttX controls the LEDs: + */ + +#define LED_STARTED 0 /* LED1 */ +#define LED_HEAPALLOCATE 1 /* LED2 */ +#define LED_IRQSENABLED 2 /* LED1 */ +#define LED_STACKCREATED 3 /* LED1 + LED2 */ +#define LED_INIRQ 4 /* LED1 */ +#define LED_SIGNAL 5 /* LED2 */ +#define LED_ASSERTION 6 /* LED1 + LED2 */ +#define LED_PANIC 7 /* LED1 + LED2 */ + +/* Alternate function pin selections ************************************************/ + +/* + * UARTs. + * + * Note that UART5 has no optional pinout, so it is not listed here. + */ +#define GPIO_USART1_RX GPIO_USART1_RX_2 +#define GPIO_USART1_TX GPIO_USART1_TX_2 + +#define GPIO_USART2_RX GPIO_USART2_RX_1 +#define GPIO_USART2_TX GPIO_USART2_TX_1 +#define GPIO_USART2_RTS GPIO_USART2_RTS_1 +#define GPIO_USART2_CTS GPIO_USART2_CTS_1 + +#define GPIO_USART6_RX GPIO_USART6_RX_1 +#define GPIO_USART6_TX GPIO_USART6_TX_1 + +/* UART DMA configuration for USART1/6 */ +#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2 +#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2 + +/* + * PWM + * + * Four PWM outputs can be configured on pins otherwise shared with + * USART2; two can take the flow control pins if they are not being used. + * + * Pins: + * + * CTS - PA0 - TIM2CH1 + * RTS - PA1 - TIM2CH2 + * TX - PA2 - TIM2CH3 + * RX - PA3 - TIM2CH4 + * + */ +#define GPIO_TIM2_CH1OUT GPIO_TIM2_CH1OUT_1 +#define GPIO_TIM2_CH2OUT GPIO_TIM2_CH2OUT_1 +#define GPIO_TIM2_CH3OUT GPIO_TIM2_CH3OUT_1 +#define GPIO_TIM2_CH4OUT GPIO_TIM2_CH4OUT_1 + +/* + * PPM + * + * PPM input is handled by the HRT timer. + */ +#if defined(CONFIG_HRT_TIMER) && defined (CONFIG_HRT_PPM) +# define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */ +# define GPIO_PPM_IN (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10) +#endif + +/* + * CAN + * + * CAN2 is routed to the expansion connector. + */ + +#define GPIO_CAN2_RX GPIO_CAN2_RX_2 +#define GPIO_CAN2_TX GPIO_CAN2_TX_2 + +/* + * I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + */ +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11) + +#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1 +#define GPIO_I2C3_SDA GPIO_I2C3_SDA_1 +#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN8) +#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN9) + +/* + * I2C busses + */ +#define PX4_I2C_BUS_ESC 1 +#define PX4_I2C_BUS_ONBOARD 2 +#define PX4_I2C_BUS_EXPANSION 3 + +/* + * Devices on the onboard bus. + * + * Note that these are unshifted addresses. + */ +#define PX4_I2C_OBDEV_HMC5883 0x1e +#define PX4_I2C_OBDEV_MS5611 0x76 +#define PX4_I2C_OBDEV_EEPROM NOTDEFINED + +#define PX4_I2C_OBDEV_PX4IO_BL 0x18 +#define PX4_I2C_OBDEV_PX4IO 0x1a + +/* + * SPI + * + * There are sensors on SPI1, and SPI3 is connected to the microSD slot. + */ +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_1 +#define GPIO_SPI3_SCK GPIO_SPI3_SCK_2 +#define GPIO_SPI3_NSS GPIO_SPI3_NSS_2 + +/* SPI DMA configuration for SPI3 (microSD) */ +#define DMACHAN_SPI3_RX DMAMAP_SPI3_RX_1 +#define DMACHAN_SPI3_TX DMAMAP_SPI3_TX_2 +/* XXX since we allocate the HP work stack from CCM RAM on normal system startup, + SPI1 will never run in DMA mode - so we can just give it a random config here. + What we really need to do is to make DMA configurable per channel, and always + disable it for SPI1. */ +#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_1 +#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_2 + +/* + * Use these in place of the spi_dev_e enumeration to + * select a specific SPI device on SPI1 + */ +#define PX4_SPIDEV_GYRO 1 +#define PX4_SPIDEV_ACCEL 2 +#define PX4_SPIDEV_MPU 3 + +/* + * Optional devices on IO's external port + */ +#define PX4_SPIDEV_ACCEL_MAG 2 + +/* + * Tone alarm output + */ +#define TONE_ALARM_TIMER 3 /* timer 3 */ +#define TONE_ALARM_CHANNEL 3 /* channel 3 */ +#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8) +#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8) + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +EXTERN void stm32_boardinitialize(void); + +/************************************************************************************ + * Name: stm32_ledinit, stm32_setled, and stm32_setleds + * + * Description: + * If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board LEDs. If + * CONFIG_ARCH_LEDS is not defined, then the following interfacesare available to + * control the LEDs from user applications. + * + ************************************************************************************/ + +#ifndef CONFIG_ARCH_LEDS +EXTERN void stm32_ledinit(void); +EXTERN void stm32_setled(int led, bool ledon); +EXTERN void stm32_setleds(uint8_t ledset); +#endif + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIG_PX4FMU_V1_INCLUDE_BOARD_H */ diff --git a/nuttx-configs/px4fmu-v1/include/nsh_romfsimg.h b/nuttx-configs/px4fmu-v1/include/nsh_romfsimg.h new file mode 100644 index 0000000000..15e4e7a8d5 --- /dev/null +++ b/nuttx-configs/px4fmu-v1/include/nsh_romfsimg.h @@ -0,0 +1,42 @@ +/**************************************************************************** + * + * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * nsh_romfsetc.h + * + * This file is a stub for 'make export' purposes; the actual ROMFS + * must be supplied by the library client. + */ + +extern unsigned char romfs_img[]; +extern unsigned int romfs_img_len; diff --git a/nuttx-configs/px4fmu-v1/nsh/Make.defs b/nuttx-configs/px4fmu-v1/nsh/Make.defs new file mode 100644 index 0000000000..7b2ea703a2 --- /dev/null +++ b/nuttx-configs/px4fmu-v1/nsh/Make.defs @@ -0,0 +1,179 @@ +############################################################################ +# configs/px4fmu-v1/nsh/Make.defs +# +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name NuttX nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk + +# +# We only support building with the ARM bare-metal toolchain from +# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS. +# +CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI + +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +MAXOPTIMIZATION = -O3 +ARCHCPUFLAGS = -mcpu=cortex-m4 \ + -mthumb \ + -march=armv7e-m \ + -mfpu=fpv4-sp-d16 \ + -mfloat-abi=hard + + +# enable precise stack overflow tracking +INSTRUMENTATIONDEFINES = -finstrument-functions \ + -ffixed-r10 + +# pull in *just* libm from the toolchain ... this is grody +LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}" +EXTRA_LIBS += $(LIBM) + +# use our linker script +LDSCRIPT = ld.script + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" +else + ifeq ($(PX4_WINTOOL),y) + # Windows-native toolchains (MSYS) + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) + else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps.sh + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) + endif +endif + +# tool versions +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +# optimisation flags +ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ + -fno-strict-aliasing \ + -fno-strength-reduce \ + -fomit-frame-pointer \ + -funsafe-math-optimizations \ + -fno-builtin-printf \ + -ffunction-sections \ + -fdata-sections + +ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ARCHOPTIMIZATION += -g +endif + +ARCHCFLAGS = -std=gnu99 +ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x +ARCHWARNINGS = -Wall \ + -Wextra \ + -Wdouble-promotion \ + -Wshadow \ + -Wfloat-equal \ + -Wframe-larger-than=1024 \ + -Wpointer-arith \ + -Wlogical-op \ + -Wmissing-declarations \ + -Wpacked \ + -Wno-unused-parameter +# -Wcast-qual - generates spurious noreturn attribute warnings, try again later +# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code +# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives + +ARCHCWARNINGS = $(ARCHWARNINGS) \ + -Wbad-function-cast \ + -Wstrict-prototypes \ + -Wold-style-declaration \ + -Wmissing-parameter-type \ + -Wmissing-prototypes \ + -Wnested-externs \ + -Wunsuffixed-float-constants +ARCHWARNINGSXX = $(ARCHWARNINGS) \ + -Wno-psabi +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +# this seems to be the only way to add linker flags +EXTRA_LIBS += --warn-common \ + --gc-sections + +CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +OBJEXT = .o +LIBEXT = .a +EXEEXT = + + +# produce partially-linked $1 from files in $2 +define PRELINK + @echo "PRELINK: $1" + $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1 +endef + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = + diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig new file mode 100644 index 0000000000..49ccfd41bc --- /dev/null +++ b/nuttx-configs/px4fmu-v1/nsh/defconfig @@ -0,0 +1,957 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# +CONFIG_NUTTX_NEWCONFIG=y + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +# CONFIG_HOST_LINUX is not set +CONFIG_HOST_OSX=y +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +CONFIG_APPS_DIR="../apps" +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +# CONFIG_INTELHEX_BINARY is not set +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y + +# +# Customize Header Files +# +# CONFIG_ARCH_STDBOOL_H is not set +CONFIG_ARCH_MATH_H=y +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set + +# +# Debug Options +# +# CONFIG_DEBUG is not set +CONFIG_DEBUG_SYMBOLS=y + +# +# System Type +# +# CONFIG_ARCH_8051 is not set +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_RGMP is not set +# CONFIG_ARCH_SH is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_CALYPSO is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_IMX is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAM3U is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STR71X is not set +CONFIG_ARCH_CORTEXM4=y +CONFIG_ARCH_HAVE_FPU=y +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARCH_HAVE_CMNVECTOR=y +CONFIG_ARMV7M_CMNVECTOR=y +CONFIG_ARMV7M_STACKCHECK=y +CONFIG_ARCH_FPU=y +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARMV7M_MPU is not set + +# +# ARMV7M Configuration Options +# +# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set +CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SERIAL_DISABLE_REORDERING=y +CONFIG_SERIAL_IFLOWCONTROL=y +CONFIG_SERIAL_OFLOWCONTROL=y + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32L151C6 is not set +# CONFIG_ARCH_CHIP_STM32L151C8 is not set +# CONFIG_ARCH_CHIP_STM32L151CB is not set +# CONFIG_ARCH_CHIP_STM32L151R6 is not set +# CONFIG_ARCH_CHIP_STM32L151R8 is not set +# CONFIG_ARCH_CHIP_STM32L151RB is not set +# CONFIG_ARCH_CHIP_STM32L151V6 is not set +# CONFIG_ARCH_CHIP_STM32L151V8 is not set +# CONFIG_ARCH_CHIP_STM32L151VB is not set +# CONFIG_ARCH_CHIP_STM32L152C6 is not set +# CONFIG_ARCH_CHIP_STM32L152C8 is not set +# CONFIG_ARCH_CHIP_STM32L152CB is not set +# CONFIG_ARCH_CHIP_STM32L152R6 is not set +# CONFIG_ARCH_CHIP_STM32L152R8 is not set +# CONFIG_ARCH_CHIP_STM32L152RB is not set +# CONFIG_ARCH_CHIP_STM32L152V6 is not set +# CONFIG_ARCH_CHIP_STM32L152V8 is not set +# CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100RC is not set +# CONFIG_ARCH_CHIP_STM32F100RD is not set +# CONFIG_ARCH_CHIP_STM32F100RE is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F100VC is not set +# CONFIG_ARCH_CHIP_STM32F100VD is not set +# CONFIG_ARCH_CHIP_STM32F100VE is not set +# CONFIG_ARCH_CHIP_STM32F103C4 is not set +# CONFIG_ARCH_CHIP_STM32F103C8 is not set +# CONFIG_ARCH_CHIP_STM32F103RET6 is not set +# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set +# CONFIG_ARCH_CHIP_STM32F103VET6 is not set +# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set +# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F302CB is not set +# CONFIG_ARCH_CHIP_STM32F302CC is not set +# CONFIG_ARCH_CHIP_STM32F302RB is not set +# CONFIG_ARCH_CHIP_STM32F302RC is not set +# CONFIG_ARCH_CHIP_STM32F302VB is not set +# CONFIG_ARCH_CHIP_STM32F302VC is not set +# CONFIG_ARCH_CHIP_STM32F303CB is not set +# CONFIG_ARCH_CHIP_STM32F303CC is not set +# CONFIG_ARCH_CHIP_STM32F303RB is not set +# CONFIG_ARCH_CHIP_STM32F303RC is not set +# CONFIG_ARCH_CHIP_STM32F303VB is not set +# CONFIG_ARCH_CHIP_STM32F303VC is not set +CONFIG_ARCH_CHIP_STM32F405RG=y +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +# CONFIG_ARCH_CHIP_STM32F407VG is not set +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +# CONFIG_ARCH_CHIP_STM32F427V is not set +# CONFIG_ARCH_CHIP_STM32F427Z is not set +# CONFIG_ARCH_CHIP_STM32F427I is not set +# CONFIG_STM32_STM32L15XX is not set +# CONFIG_STM32_ENERGYLITE is not set +# CONFIG_STM32_STM32F10XX is not set +# CONFIG_STM32_VALUELINE is not set +# CONFIG_STM32_CONNECTIVITYLINE is not set +# CONFIG_STM32_PERFORMANCELINE is not set +# CONFIG_STM32_HIGHDENSITY is not set +# CONFIG_STM32_MEDIUMDENSITY is not set +# CONFIG_STM32_LOWDENSITY is not set +# CONFIG_STM32_STM32F20XX is not set +# CONFIG_STM32_STM32F30XX is not set +CONFIG_STM32_STM32F40XX=y +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +CONFIG_STM32_ADC1=y +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_ADC3 is not set +CONFIG_STM32_BKPSRAM=y +# CONFIG_STM32_CAN1 is not set +# CONFIG_STM32_CAN2 is not set +CONFIG_STM32_CCMDATARAM=y +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_CRYP is not set +CONFIG_STM32_DMA1=y +CONFIG_STM32_DMA2=y +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +# CONFIG_STM32_DCMI is not set +# CONFIG_STM32_ETHMAC is not set +# CONFIG_STM32_FSMC is not set +# CONFIG_STM32_HASH is not set +CONFIG_STM32_I2C1=y +CONFIG_STM32_I2C2=y +CONFIG_STM32_I2C3=y +CONFIG_STM32_OTGFS=y +# CONFIG_STM32_OTGHS is not set +CONFIG_STM32_PWR=y +# CONFIG_STM32_RNG is not set +# CONFIG_STM32_SDIO is not set +CONFIG_STM32_SPI1=y +# CONFIG_STM32_SPI2 is not set +CONFIG_STM32_SPI3=y +CONFIG_STM32_SYSCFG=y +# CONFIG_STM32_TIM1 is not set +# CONFIG_STM32_TIM2 is not set +# CONFIG_STM32_TIM3 is not set +CONFIG_STM32_TIM4=y +CONFIG_STM32_TIM5=y +CONFIG_STM32_TIM6=y +CONFIG_STM32_TIM7=y +# CONFIG_STM32_TIM8 is not set +CONFIG_STM32_TIM9=y +CONFIG_STM32_TIM10=y +CONFIG_STM32_TIM11=y +CONFIG_STM32_TIM12=y +CONFIG_STM32_TIM13=y +CONFIG_STM32_TIM14=y +CONFIG_STM32_USART1=y +CONFIG_STM32_USART2=y +# CONFIG_STM32_USART3 is not set +# CONFIG_STM32_UART4 is not set +CONFIG_STM32_UART5=y +CONFIG_STM32_USART6=y +# CONFIG_STM32_IWDG is not set +CONFIG_STM32_WWDG=y +CONFIG_STM32_ADC=y +CONFIG_STM32_SPI=y +CONFIG_STM32_I2C=y + +# +# Alternate Pin Mapping +# +CONFIG_STM32_FLASH_PREFETCH=y +# CONFIG_STM32_JTAG_DISABLE is not set +CONFIG_STM32_JTAG_FULL_ENABLE=y +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +# CONFIG_STM32_JTAG_SW_ENABLE is not set +CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set +# CONFIG_STM32_CCMEXCLUDE is not set +# CONFIG_STM32_TIM4_PWM is not set +# CONFIG_STM32_TIM5_PWM is not set +# CONFIG_STM32_TIM9_PWM is not set +# CONFIG_STM32_TIM10_PWM is not set +# CONFIG_STM32_TIM11_PWM is not set +# CONFIG_STM32_TIM12_PWM is not set +# CONFIG_STM32_TIM13_PWM is not set +# CONFIG_STM32_TIM14_PWM is not set +# CONFIG_STM32_TIM4_ADC is not set +# CONFIG_STM32_TIM5_ADC is not set +CONFIG_STM32_USART=y + +# +# U[S]ART Configuration +# +# CONFIG_USART1_RS485 is not set +# CONFIG_USART1_RXDMA is not set +# CONFIG_USART2_RS485 is not set +CONFIG_USART2_RXDMA=y +# CONFIG_USART3_RXDMA is not set +# CONFIG_UART4_RXDMA is not set +# CONFIG_UART5_RS485 is not set +CONFIG_UART5_RXDMA=y +# CONFIG_USART6_RS485 is not set +CONFIG_USART6_RXDMA=y +# CONFIG_USART7_RXDMA is not set +# CONFIG_USART8_RXDMA is not set +CONFIG_STM32_USART_SINGLEWIRE=y + +# +# SPI Configuration +# +# CONFIG_STM32_SPI_INTERRUPTS is not set +# CONFIG_STM32_SPI_DMA is not set + +# +# I2C Configuration +# +# CONFIG_STM32_I2C_DYNTIMEO is not set +CONFIG_STM32_I2CTIMEOSEC=0 +CONFIG_STM32_I2CTIMEOMS=10 +CONFIG_STM32_I2CTIMEOTICKS=500 +# CONFIG_STM32_I2C_DUTY16_9 is not set + +# +# USB Host Configuration +# + +# +# USB Device Configuration +# + +# +# External Memory Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +CONFIG_ARCH_DMA=y +CONFIG_ARCH_IRQPRIO=y +# CONFIG_CUSTOM_STACK is not set +# CONFIG_ADDRENV is not set +CONFIG_ARCH_HAVE_VFORK=y +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +CONFIG_ARCH_HAVE_RAMVECTORS=y +# CONFIG_ARCH_RAMVECTORS is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=16717 +# CONFIG_ARCH_CALIBRATION is not set +CONFIG_DRAM_START=0x20000000 +CONFIG_DRAM_SIZE=196608 +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_PX4FMU_V1=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="px4fmu-v1" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +# CONFIG_ARCH_LEDS is not set +CONFIG_NSH_MMCSDMINOR=0 +CONFIG_NSH_MMCSDSLOTNO=0 +CONFIG_NSH_MMCSDSPIPORTNO=3 + +# +# Board-Specific Options +# +CONFIG_HRT_TIMER=y +CONFIG_HRT_PPM=y + +# +# RTOS Features +# +# CONFIG_BOARD_INITIALIZE is not set +CONFIG_MSEC_PER_TICK=1 +CONFIG_RR_INTERVAL=0 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_TASK_NAME_SIZE=24 +# CONFIG_SCHED_HAVE_PARENT is not set +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=1970 +CONFIG_START_MONTH=1 +CONFIG_START_DAY=1 +# CONFIG_DEV_CONSOLE is not set +# CONFIG_MUTEX_TYPES is not set +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SEM_NNESTPRIO=8 +# CONFIG_FDCLONE_DISABLE is not set +CONFIG_FDCLONE_STDIO=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_SCHED_WAITPID=y +# CONFIG_SCHED_STARTHOOK is not set +CONFIG_SCHED_ATEXIT=y +CONFIG_SCHED_ATEXIT_MAX=1 +# CONFIG_SCHED_ONEXIT is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_CLOCK is not set +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_ENVIRON is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 +CONFIG_SIG_SIGWORK=4 + +# +# Sizes of configurable things (0 disables) +# +CONFIG_MAX_TASKS=32 +CONFIG_MAX_TASK_ARGS=10 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=32 +CONFIG_NFILE_STREAMS=25 +CONFIG_NAME_MAX=32 +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=50 +CONFIG_PREALLOC_TIMERS=50 + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=6000 +CONFIG_USERMAIN_STACKSIZE=4096 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_PTHREAD_STACK_DEFAULT=2048 + +# +# Device Drivers +# +# CONFIG_DISABLE_POLL is not set +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_PWM is not set +CONFIG_I2C=y +# CONFIG_I2C_SLAVE is not set +CONFIG_I2C_TRANSFER=y +# CONFIG_I2C_WRITEREAD is not set +# CONFIG_I2C_POLLED is not set +# CONFIG_I2C_TRACE is not set +CONFIG_ARCH_HAVE_I2CRESET=y +CONFIG_I2C_RESET=y +CONFIG_SPI=y +# CONFIG_SPI_OWNBUS is not set +CONFIG_SPI_EXCHANGE=y +# CONFIG_SPI_CMDDATA is not set +# CONFIG_RTC is not set +CONFIG_WATCHDOG=y +# CONFIG_ANALOG is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set +# CONFIG_LCD is not set +CONFIG_MMCSD=y +CONFIG_MMCSD_NSLOTS=1 +# CONFIG_MMCSD_READONLY is not set +# CONFIG_MMCSD_MULTIBLOCK_DISABLE is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_HAVECARDDETECT is not set +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SPICLOCK=24000000 +# CONFIG_MMCSD_SDIO is not set +# CONFIG_MTD is not set +CONFIG_PIPES=y +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +CONFIG_SERIAL_REMOVABLE=y +# CONFIG_16550_UART is not set +CONFIG_ARCH_HAVE_UART5=y +CONFIG_ARCH_HAVE_USART1=y +CONFIG_ARCH_HAVE_USART2=y +CONFIG_ARCH_HAVE_USART6=y +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +CONFIG_SERIAL_NPOLLWAITERS=2 +# CONFIG_USART1_SERIAL_CONSOLE is not set +# CONFIG_USART2_SERIAL_CONSOLE is not set +# CONFIG_UART5_SERIAL_CONSOLE is not set +# CONFIG_USART6_SERIAL_CONSOLE is not set +CONFIG_NO_SERIAL_CONSOLE=y + +# +# USART1 Configuration +# +CONFIG_USART1_RXBUFSIZE=512 +CONFIG_USART1_TXBUFSIZE=512 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_BITS=8 +CONFIG_USART1_PARITY=0 +CONFIG_USART1_2STOP=0 + +# +# USART2 Configuration +# +CONFIG_USART2_RXBUFSIZE=512 +CONFIG_USART2_TXBUFSIZE=512 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_BITS=8 +CONFIG_USART2_PARITY=0 +CONFIG_USART2_2STOP=0 + +# +# UART5 Configuration +# +CONFIG_UART5_RXBUFSIZE=32 +CONFIG_UART5_TXBUFSIZE=32 +CONFIG_UART5_BAUD=57600 +CONFIG_UART5_BITS=8 +CONFIG_UART5_PARITY=0 +CONFIG_UART5_2STOP=0 + +# +# USART6 Configuration +# +CONFIG_USART6_RXBUFSIZE=512 +CONFIG_USART6_TXBUFSIZE=512 +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_BITS=8 +CONFIG_USART6_PARITY=0 +CONFIG_USART6_2STOP=0 +CONFIG_USBDEV=y + +# +# USB Device Controller Driver Options +# +# CONFIG_USBDEV_ISOCHRONOUS is not set +# CONFIG_USBDEV_DUALSPEED is not set +CONFIG_USBDEV_SELFPOWERED=y +# CONFIG_USBDEV_BUSPOWERED is not set +CONFIG_USBDEV_MAXPOWER=500 +# CONFIG_USBDEV_DMA is not set +# CONFIG_USBDEV_TRACE is not set + +# +# USB Device Class Driver Options +# +# CONFIG_USBDEV_COMPOSITE is not set +# CONFIG_PL2303 is not set +CONFIG_CDCACM=y +CONFIG_CDCACM_CONSOLE=y +CONFIG_CDCACM_EP0MAXPACKET=64 +CONFIG_CDCACM_EPINTIN=1 +CONFIG_CDCACM_EPINTIN_FSSIZE=64 +CONFIG_CDCACM_EPINTIN_HSSIZE=64 +CONFIG_CDCACM_EPBULKOUT=3 +CONFIG_CDCACM_EPBULKOUT_FSSIZE=64 +CONFIG_CDCACM_EPBULKOUT_HSSIZE=512 +CONFIG_CDCACM_EPBULKIN=2 +CONFIG_CDCACM_EPBULKIN_FSSIZE=64 +CONFIG_CDCACM_EPBULKIN_HSSIZE=512 +CONFIG_CDCACM_NWRREQS=4 +CONFIG_CDCACM_NRDREQS=4 +CONFIG_CDCACM_RXBUFSIZE=256 +CONFIG_CDCACM_TXBUFSIZE=256 +CONFIG_CDCACM_VENDORID=0x26ac +CONFIG_CDCACM_PRODUCTID=0x0010 +CONFIG_CDCACM_VENDORSTR="3D Robotics" +CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v1.x" +# CONFIG_USBMSC is not set +# CONFIG_USBHOST is not set +# CONFIG_WIRELESS is not set + +# +# System Logging Device Options +# + +# +# System Logging +# +# CONFIG_RAMLOG is not set + +# +# Networking Support +# +# CONFIG_NET is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_RAMMAP is not set +CONFIG_FS_FAT=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_MAXFNAME=32 +CONFIG_FS_FATTIME=y +# CONFIG_FAT_DMAMEMORY is not set +CONFIG_FS_NXFFS=y +CONFIG_NXFFS_PREALLOCATED=y +CONFIG_NXFFS_ERASEDSTATE=0xff +CONFIG_NXFFS_PACKTHRESHOLD=32 +CONFIG_NXFFS_MAXNAMLEN=32 +CONFIG_NXFFS_TAILTHRESHOLD=2048 +CONFIG_FS_ROMFS=y +# CONFIG_FS_SMARTFS is not set +CONFIG_FS_BINFS=y + +# +# System Logging +# +# CONFIG_SYSLOG_ENABLE is not set +CONFIG_SYSLOG=y +CONFIG_SYSLOG_CHAR=y +CONFIG_SYSLOG_DEVPATH="/dev/ttyS0" + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_MULTIHEAP is not set +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=2 +CONFIG_GRAN=y +CONFIG_GRAN_SINGLE=y +CONFIG_GRAN_INTR=y + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Binary Formats +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_BUILTIN=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +CONFIG_LIB_HOMEDIR="/" +# CONFIG_NOPRINTF_FIELDWIDTH is not set +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIB_RAND_ORDER=1 +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048 +CONFIG_LIBC_STRERROR=y +# CONFIG_LIBC_STRERROR_SHORT is not set +# CONFIG_LIBC_PERROR_STDOUT is not set +CONFIG_ARCH_LOWPUTC=y +CONFIG_LIB_SENDFILE_BUFSIZE=512 +# CONFIG_ARCH_ROMGETC is not set +CONFIG_ARCH_OPTIMIZED_FUNCTIONS=y +CONFIG_ARCH_MEMCPY=y +# CONFIG_ARCH_MEMCMP is not set +# CONFIG_ARCH_MEMMOVE is not set +# CONFIG_ARCH_MEMSET is not set +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_ARCH_STRCHR is not set +# CONFIG_ARCH_STRCMP is not set +# CONFIG_ARCH_STRCPY is not set +# CONFIG_ARCH_STRNCPY is not set +# CONFIG_ARCH_STRLEN is not set +# CONFIG_ARCH_STRNLEN is not set +# CONFIG_ARCH_BZERO is not set + +# +# Non-standard Library Support +# +CONFIG_SCHED_WORKQUEUE=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_WORKPRIORITY=192 +CONFIG_SCHED_WORKPERIOD=5000 +CONFIG_SCHED_WORKSTACKSIZE=2048 +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKPERIOD=50000 +CONFIG_SCHED_LPWORKSTACKSIZE=2048 +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +# CONFIG_CXX_NEWLONG is not set + +# +# uClibc++ Standard C++ Library +# +# CONFIG_UCLIBCXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# +CONFIG_BUILTIN_PROXY_STACKSIZE=1024 + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CAN is not set +CONFIG_EXAMPLES_CDCACM=y +# CONFIG_EXAMPLES_COMPOSITE is not set +# CONFIG_EXAMPLES_CXXTEST is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_LCDRW is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +CONFIG_EXAMPLES_MOUNT=y +CONFIG_EXAMPLES_NSH=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXCONSOLE is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXFLAT is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PASHELLO is not set +# CONFIG_EXAMPLES_PIPE is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_QENCODER is not set +# CONFIG_EXAMPLES_RGMP is not set +# CONFIG_EXAMPLES_ROMFS is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART_TEST is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_THTTPD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_UDP is not set +# CONFIG_EXAMPLES_UIP is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_USBMSC is not set +# CONFIG_EXAMPLES_USBTERM is not set +# CONFIG_EXAMPLES_WATCHDOG is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# Network Utilities +# + +# +# Networking Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_DHCPC is not set +# CONFIG_NETUTILS_DHCPD is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_FTPD is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_RESOLV is not set +# CONFIG_NETUTILS_SMTP is not set +# CONFIG_NETUTILS_TELNETD is not set +# CONFIG_NETUTILS_TFTPC is not set +# CONFIG_NETUTILS_THTTPD is not set +# CONFIG_NETUTILS_UIPLIB is not set +# CONFIG_NETUTILS_WEBCLIENT is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MKFIFO is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MW is not set +# CONFIG_NSH_DISABLE_NSFMOUNT is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PING is not set +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set + +# +# Configure Command Options +# +# CONFIG_NSH_CMDOPT_DF_H is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=12 +CONFIG_NSH_NESTDEPTH=8 +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_ROMFSETC=y +# CONFIG_NSH_ROMFSRC is not set +CONFIG_NSH_ROMFSMOUNTPT="/etc" +CONFIG_NSH_INITSCRIPT="init.d/rcS" +CONFIG_NSH_ROMFSDEVNO=0 +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_ARCHROMFS=y +CONFIG_NSH_FATDEVNO=1 +CONFIG_NSH_FATSECTSIZE=512 +CONFIG_NSH_FATNSECTORS=1024 +CONFIG_NSH_FATMOUNTPT="/tmp" +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_USBCONSOLE is not set + +# +# USB Trace Support +# +# CONFIG_NSH_CONDEV is not set +CONFIG_NSH_ARCHINIT=y + +# +# NxWidgets/NxWM +# + +# +# System NSH Add-Ons +# + +# +# Custom Free Memory Command +# +# CONFIG_SYSTEM_FREE is not set + +# +# I2C tool +# +# CONFIG_SYSTEM_I2CTOOL is not set + +# +# FLASH Program Installation +# +# CONFIG_SYSTEM_INSTALL is not set + +# +# FLASH Erase-all Command +# + +# +# readline() +# +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y + +# +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# CONFIG_SYSTEM_RAMTRON is not set + +# +# SD Card +# +# CONFIG_SYSTEM_SDCARD is not set + +# +# Sysinfo +# +CONFIG_SYSTEM_SYSINFO=y + +# +# USB Monitor +# diff --git a/nuttx-configs/px4fmu-v1/nsh/setenv.sh b/nuttx-configs/px4fmu-v1/nsh/setenv.sh new file mode 100755 index 0000000000..db372217cd --- /dev/null +++ b/nuttx-configs/px4fmu-v1/nsh/setenv.sh @@ -0,0 +1,75 @@ +#!/bin/bash +# configs/px4fmu-v1/usbnsh/setenv.sh +# +# Copyright (C) 2013 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name NuttX nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the RIDE +# toolchain under windows. You will also have to edit this if you install +# the RIDE toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" + +# This is the Cygwin path to the location where I build the buildroot +# toolchain. +#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/nuttx-configs/px4fmu-v1/scripts/ld.script b/nuttx-configs/px4fmu-v1/scripts/ld.script new file mode 100644 index 0000000000..ced5b21b7c --- /dev/null +++ b/nuttx-configs/px4fmu-v1/scripts/ld.script @@ -0,0 +1,149 @@ +/**************************************************************************** + * configs/px4fmu-v1/scripts/ld.script + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The STM32F405RG has 1024Kb of FLASH beginning at address 0x0800:0000 and + * 192Kb of SRAM. SRAM is split up into three blocks: + * + * 1) 112Kb of SRAM beginning at address 0x2000:0000 + * 2) 16Kb of SRAM beginning at address 0x2001:c000 + * 3) 64Kb of CCM SRAM beginning at address 0x1000:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The first 0x4000 of flash is reserved for the bootloader. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08004000, LENGTH = 1008K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K +} + +OUTPUT_ARCH(arm) + +ENTRY(__start) /* treat __start as the anchor for dead code stripping */ +EXTERN(_vectors) /* force the vectors to be included in the output */ + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + /* + * This is a hack to make the newlib libm __errno() call + * use the NuttX get_errno_ptr() function. + */ + __errno = get_errno_ptr; + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + /* + * Construction data for parameters. + */ + __param ALIGN(4): { + __param_start = ABSOLUTE(.); + KEEP(*(__param*)) + __param_end = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/nuttx-configs/px4fmu-v1/src/Makefile b/nuttx-configs/px4fmu-v1/src/Makefile new file mode 100644 index 0000000000..6ef8b7d6af --- /dev/null +++ b/nuttx-configs/px4fmu-v1/src/Makefile @@ -0,0 +1,84 @@ +############################################################################ +# configs/px4fmu-v1/src/Makefile +# +# Copyright (C) 2013 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name NuttX nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +-include $(TOPDIR)/Make.defs + +CFLAGS += -I$(TOPDIR)/sched + +ASRCS = +AOBJS = $(ASRCS:.S=$(OBJEXT)) + +CSRCS = empty.c +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) + +ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ifeq ($(WINTOOL),y) + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}" +else + CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m +endif + +all: libboard$(LIBEXT) + +$(AOBJS): %$(OBJEXT): %.S + $(call ASSEMBLE, $<, $@) + +$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +libboard$(LIBEXT): $(OBJS) + $(call ARCHIVE, $@, $(OBJS)) + +.depend: Makefile $(SRCS) + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ + +depend: .depend + +clean: + $(call DELFILE, libboard$(LIBEXT)) + $(call CLEAN) + +distclean: clean + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) + +-include Make.dep + diff --git a/nuttx-configs/px4fmu-v1/src/empty.c b/nuttx-configs/px4fmu-v1/src/empty.c new file mode 100644 index 0000000000..ace900866c --- /dev/null +++ b/nuttx-configs/px4fmu-v1/src/empty.c @@ -0,0 +1,4 @@ +/* + * There are no source files here, but libboard.a can't be empty, so + * we have this empty source file to keep it company. + */ diff --git a/nuttx-configs/px4io-v1/include/README.txt b/nuttx-configs/px4io-v1/include/README.txt new file mode 100755 index 0000000000..2264a80aa8 --- /dev/null +++ b/nuttx-configs/px4io-v1/include/README.txt @@ -0,0 +1 @@ +This directory contains header files unique to the PX4IO board. diff --git a/nuttx-configs/px4io-v1/include/board.h b/nuttx-configs/px4io-v1/include/board.h new file mode 100755 index 0000000000..668602ea89 --- /dev/null +++ b/nuttx-configs/px4io-v1/include/board.h @@ -0,0 +1,172 @@ +/************************************************************************************ + * configs/px4io/include/board.h + * include/arch/board/board.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +#ifndef __ARCH_BOARD_BOARD_H +#define __ARCH_BOARD_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#ifndef __ASSEMBLY__ +# include +# include +#endif +#include +#include +#include + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ + +/* On-board crystal frequency is 24MHz (HSE) */ + +#define STM32_BOARD_XTAL 24000000ul + +/* Use the HSE output as the system clock */ + +#define STM32_SYSCLK_SW RCC_CFGR_SW_HSE +#define STM32_SYSCLK_SWS RCC_CFGR_SWS_HSE +#define STM32_SYSCLK_FREQUENCY STM32_BOARD_XTAL + +/* AHB clock (HCLK) is SYSCLK (24MHz) */ + +#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK +#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB2 clock (PCLK2) is HCLK (24MHz) */ + +#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK +#define STM32_PCLK2_FREQUENCY STM32_HCLK_FREQUENCY +#define STM32_APB2_CLKIN (STM32_PCLK2_FREQUENCY) /* Timers 2-4 */ + +/* APB2 timer 1 will receive PCLK2. */ + +#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY) + +/* APB1 clock (PCLK1) is HCLK (24MHz) */ + +#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY) + +/* All timers run off PCLK */ + +#define STM32_APB1_TIM1_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB1_TIM2_CLKIN (STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (STM32_PCLK1_FREQUENCY) + +/* + * Some of the USART pins are not available; override the GPIO + * definitions with an invalid pin configuration. + */ +#undef GPIO_USART2_CTS +#define GPIO_USART2_CTS 0xffffffff +#undef GPIO_USART2_RTS +#define GPIO_USART2_RTS 0xffffffff +#undef GPIO_USART2_CK +#define GPIO_USART2_CK 0xffffffff +#undef GPIO_USART3_TX +#define GPIO_USART3_TX 0xffffffff +#undef GPIO_USART3_CK +#define GPIO_USART3_CK 0xffffffff +#undef GPIO_USART3_CTS +#define GPIO_USART3_CTS 0xffffffff +#undef GPIO_USART3_RTS +#define GPIO_USART3_RTS 0xffffffff + +/* + * High-resolution timer + */ +#ifdef CONFIG_HRT_TIMER +# define HRT_TIMER 1 /* use timer1 for the HRT */ +# define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */ +#endif + +/* + * PPM + * + * PPM input is handled by the HRT timer. + * + * Pin is PA8, timer 1, channel 1 + */ +#if defined(CONFIG_HRT_TIMER) && defined (CONFIG_HRT_PPM) +# define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */ +# define GPIO_PPM_IN GPIO_TIM1_CH1IN +#endif + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +EXTERN void stm32_boardinitialize(void); + +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_BOARD_BOARD_H */ diff --git a/nuttx-configs/px4io-v1/nsh/Make.defs b/nuttx-configs/px4io-v1/nsh/Make.defs new file mode 100644 index 0000000000..712631f471 --- /dev/null +++ b/nuttx-configs/px4io-v1/nsh/Make.defs @@ -0,0 +1,166 @@ +############################################################################ +# configs/px4io-v1/nsh/Make.defs +# +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name NuttX nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk + +# +# We only support building with the ARM bare-metal toolchain from +# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS. +# +CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI + +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +MAXOPTIMIZATION = -O3 +ARCHCPUFLAGS = -mcpu=cortex-m3 \ + -mthumb \ + -march=armv7-m + +# use our linker script +LDSCRIPT = ld.script + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" +else + ifeq ($(PX4_WINTOOL),y) + # Windows-native toolchains (MSYS) + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) + else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps.sh + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) + endif +endif + +# tool versions +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +# optimisation flags +ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ + -fno-strict-aliasing \ + -fno-strength-reduce \ + -fomit-frame-pointer \ + -funsafe-math-optimizations \ + -fno-builtin-printf \ + -ffunction-sections \ + -fdata-sections + +ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ARCHOPTIMIZATION += -g +endif + +ARCHCFLAGS = -std=gnu99 +ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x +ARCHWARNINGS = -Wall \ + -Wextra \ + -Wdouble-promotion \ + -Wshadow \ + -Wfloat-equal \ + -Wframe-larger-than=1024 \ + -Wpointer-arith \ + -Wlogical-op \ + -Wmissing-declarations \ + -Wpacked \ + -Wno-unused-parameter +# -Wcast-qual - generates spurious noreturn attribute warnings, try again later +# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code +# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives + +ARCHCWARNINGS = $(ARCHWARNINGS) \ + -Wbad-function-cast \ + -Wstrict-prototypes \ + -Wold-style-declaration \ + -Wmissing-parameter-type \ + -Wmissing-prototypes \ + -Wnested-externs \ + -Wunsuffixed-float-constants +ARCHWARNINGSXX = $(ARCHWARNINGS) +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +# this seems to be the only way to add linker flags +EXTRA_LIBS += --warn-common \ + --gc-sections + +CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +# produce partially-linked $1 from files in $2 +define PRELINK + @echo "PRELINK: $1" + $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1 +endef + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = + diff --git a/nuttx-configs/px4io-v1/nsh/appconfig b/nuttx-configs/px4io-v1/nsh/appconfig new file mode 100644 index 0000000000..48a41bcdb8 --- /dev/null +++ b/nuttx-configs/px4io-v1/nsh/appconfig @@ -0,0 +1,32 @@ +############################################################################ +# +# Copyright (C) 2012 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ diff --git a/nuttx-configs/px4io-v1/nsh/defconfig b/nuttx-configs/px4io-v1/nsh/defconfig new file mode 100755 index 0000000000..5256722333 --- /dev/null +++ b/nuttx-configs/px4io-v1/nsh/defconfig @@ -0,0 +1,559 @@ +############################################################################ +# configs/px4io-v1/nsh/defconfig +# +# Copyright (C) 2012 PX4 Development Team. All rights reserved. +# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name NuttX nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +# +# architecture selection +# +# CONFIG_ARCH - identifies the arch subdirectory and, hence, the +# processor architecture. +# CONFIG_ARCH_family - for use in C code. This identifies the +# particular chip family that the architecture is implemented +# in. +# CONFIG_ARCH_architecture - for use in C code. This identifies the +# specific architecture within the chip family. +# CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory +# CONFIG_ARCH_CHIP_name - For use in C code +# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence, +# the board that supports the particular chip or SoC. +# CONFIG_ARCH_BOARD_name - for use in C code +# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) +# CONFIG_BOARD_LOOPSPERMSEC - for delay loops +# CONFIG_DRAM_SIZE - Describes the installed DRAM. +# CONFIG_DRAM_START - The start address of DRAM (physical) +# CONFIG_ARCH_IRQPRIO - The ST32F100CB supports interrupt prioritization +# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt +# stack. If defined, this symbol is the size of the interrupt +# stack in bytes. If not defined, the user task stacks will be +# used during interrupt handling. +# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions +# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader. +# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. +# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture. +# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that +# cause a 100 second delay during boot-up. This 100 second delay +# serves no purpose other than it allows you to calibrate +# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure +# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until +# the delay actually is 100 seconds. +# CONFIG_ARCH_DMA - Support DMA initialization +# +CONFIG_ARCH="arm" +CONFIG_ARCH_ARM=y +CONFIG_ARCH_CORTEXM3=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32F100C8=y +# +# Board Selection +# +CONFIG_ARCH_BOARD_PX4IO_V1=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="px4io-v1" +CONFIG_BOARD_LOOPSPERMSEC=2000 +CONFIG_DRAM_SIZE=0x00002000 +CONFIG_DRAM_START=0x20000000 +CONFIG_ARCH_IRQPRIO=y +CONFIG_ARCH_INTERRUPTSTACK=n +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARCH_BOOTLOADER=n +CONFIG_ARCH_LEDS=n +CONFIG_ARCH_BUTTONS=n +CONFIG_ARCH_CALIBRATION=n +CONFIG_ARCH_DMA=y +CONFIG_ARCH_MATH_H=y + +CONFIG_ARMV7M_CMNVECTOR=y +# CONFIG_ARMV7M_STACKCHECK is not set + +# +# JTAG Enable settings (by default JTAG-DP and SW-DP are disabled): +# +# CONFIG_STM32_DFU - Use the DFU bootloader, not JTAG +# +# JTAG Enable options: +# +# CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) +# but without JNTRST. +# CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled +# +CONFIG_STM32_DFU=n +CONFIG_STM32_JTAG_FULL_ENABLE=y +CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n +CONFIG_STM32_JTAG_SW_ENABLE=n + +# +# Individual subsystems can be enabled: +# +# AHB: +CONFIG_STM32_DMA1=y +CONFIG_STM32_DMA2=n +CONFIG_STM32_CRC=n +# APB1: +# Timers 2,3 and 4 are owned by the PWM driver +CONFIG_STM32_TIM2=n +CONFIG_STM32_TIM3=n +CONFIG_STM32_TIM4=n +CONFIG_STM32_TIM5=n +CONFIG_STM32_TIM6=n +CONFIG_STM32_TIM7=n +CONFIG_STM32_WWDG=n +CONFIG_STM32_SPI2=n +CONFIG_STM32_USART2=y +CONFIG_STM32_USART3=y +CONFIG_STM32_I2C1=y +CONFIG_STM32_I2C2=n +CONFIG_STM32_BKP=n +CONFIG_STM32_PWR=n +CONFIG_STM32_DAC=n +# APB2: +# We use our own ADC driver, but leave this on for clocking purposes. +CONFIG_STM32_ADC1=y +CONFIG_STM32_ADC2=n +# TIM1 is owned by the HRT +CONFIG_STM32_TIM1=n +CONFIG_STM32_SPI1=n +CONFIG_STM32_TIM8=n +CONFIG_STM32_USART1=y +CONFIG_STM32_ADC3=n + + +# +# STM32F100 specific serial device driver settings +# +# CONFIG_USARTn_SERIAL_CONSOLE - selects the USARTn for the +# console and ttys0 (default is the USART1). +# CONFIG_USARTn_RXBUFSIZE - Characters are buffered as received. +# This specific the size of the receive buffer +# CONFIG_USARTn_TXBUFSIZE - Characters are buffered before +# being sent. This specific the size of the transmit buffer +# CONFIG_USARTn_BAUD - The configure BAUD of the UART. Must be +# CONFIG_USARTn_BITS - The number of bits. Must be either 7 or 8. +# CONFIG_USARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity +# CONFIG_USARTn_2STOP - Two stop bits +# +CONFIG_SERIAL_TERMIOS=y +CONFIG_STANDARD_SERIAL=y + +CONFIG_USART1_SERIAL_CONSOLE=y +CONFIG_USART2_SERIAL_CONSOLE=n +CONFIG_USART3_SERIAL_CONSOLE=n + +CONFIG_USART1_TXBUFSIZE=64 +CONFIG_USART2_TXBUFSIZE=64 +CONFIG_USART3_TXBUFSIZE=64 + +CONFIG_USART1_RXBUFSIZE=64 +CONFIG_USART2_RXBUFSIZE=64 +CONFIG_USART3_RXBUFSIZE=64 + +CONFIG_USART1_BAUD=115200 +CONFIG_USART2_BAUD=115200 +CONFIG_USART3_BAUD=115200 + +CONFIG_USART1_BITS=8 +CONFIG_USART2_BITS=8 +CONFIG_USART3_BITS=8 + +CONFIG_USART1_PARITY=0 +CONFIG_USART2_PARITY=0 +CONFIG_USART3_PARITY=0 + +CONFIG_USART1_2STOP=0 +CONFIG_USART2_2STOP=0 +CONFIG_USART3_2STOP=0 + +CONFIG_USART1_RXDMA=y +SERIAL_HAVE_CONSOLE_DMA=y +# Conflicts with I2C1 DMA +CONFIG_USART2_RXDMA=n +CONFIG_USART3_RXDMA=y + +# +# PX4IO specific driver settings +# +# CONFIG_HRT_TIMER +# Enables the high-resolution timer. The board definition must +# set HRT_TIMER and HRT_TIMER_CHANNEL to the timer and capture/ +# compare channels to be used. +# CONFIG_HRT_PPM +# Enables R/C PPM input using the HRT. The board definition must +# set HRT_PPM_CHANNEL to the timer capture/compare channel to be +# used, and define GPIO_PPM_IN to configure the appropriate timer +# GPIO. +# CONFIG_PWM_SERVO +# Enables the PWM servo driver. The driver configuration must be +# supplied by the board support at initialisation time. +# Note that USART2 must be disabled on the PX4 board for this to +# be available. +# +# +CONFIG_HRT_TIMER=y +CONFIG_HRT_PPM=y + +# +# General build options +# +# CONFIG_RRLOAD_BINARY - make the rrload binary format used with +# BSPs from www.ridgerun.com using the tools/mkimage.sh script +# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_MOTOROLA_SREC - make the Motorola S-Record binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_RAW_BINARY - make a raw binary format file used with many +# different loaders using the GNU objcopy program. This option +# should not be selected if you are not using the GNU toolchain. +# CONFIG_HAVE_LIBM - toolchain supports libm.a +# +CONFIG_RRLOAD_BINARY=n +CONFIG_INTELHEX_BINARY=n +CONFIG_MOTOROLA_SREC=n +CONFIG_RAW_BINARY=y +CONFIG_HAVE_LIBM=n + +# +# General OS setup +# +# CONFIG_APPS_DIR - Identifies the relative path to the directory +# that builds the application to link with NuttX. Default: ../apps +# CONFIG_DEBUG - enables built-in debug options +# CONFIG_DEBUG_VERBOSE - enables verbose debug output +# CONFIG_DEBUG_SYMBOLS - build without optimization and with +# debug symbols (needed for use with a debugger). +# CONFIG_HAVE_CXX - Enable support for C++ +# CONFIG_HAVE_CXXINITIALIZE - The platform-specific logic includes support +# for initialization of static C++ instances for this architecture +# and for the selected toolchain (via up_cxxinitialize()). +# CONFIG_MM_REGIONS - If the architecture includes multiple +# regions of memory to allocate from, this specifies the +# number of memory regions that the memory manager must +# handle and enables the API mm_addregion(start, end); +# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot +# time console output +# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz +# or MSEC_PER_TICK=10. This setting may be defined to +# inform NuttX that the processor hardware is providing +# system timer interrupts at some interrupt interval other +# than 10 msec. +# CONFIG_RR_INTERVAL - The round robin timeslice will be set +# this number of milliseconds; Round robin scheduling can +# be disabled by setting this value to zero. +# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in +# scheduler to monitor system performance +# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a +# task name to save in the TCB. Useful if scheduler +# instrumentation is selected. Set to zero to disable. +# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - +# Used to initialize the internal time logic. +# CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions. +# You would only need this if you are concerned about accurate +# time conversions in the past or in the distant future. +# CONFIG_JULIAN_TIME - Enables Julian time conversions. You +# would only need this if you are concerned about accurate +# time conversion in the distand past. You must also define +# CONFIG_GREGORIAN_TIME in order to use Julian time. +# CONFIG_DEV_CONSOLE - Set if architecture-specific logic +# provides /dev/console. Enables stdout, stderr, stdin. +# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console +# driver (minimul support) +# CONFIG_MUTEX_TYPES: Set to enable support for recursive and +# errorcheck mutexes. Enables pthread_mutexattr_settype(). +# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority +# inheritance on mutexes and semaphores. +# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority +# inheritance is enabled. It defines the maximum number of +# different threads (minus one) that can take counts on a +# semaphore with priority inheritance support. This may be +# set to zero if priority inheritance is disabled OR if you +# are only using semaphores as mutexes (only one holder) OR +# if no more than two threads participate using a counting +# semaphore. +# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, +# then this setting is the maximum number of higher priority +# threads (minus 1) than can be waiting for another thread +# to release a count on a semaphore. This value may be set +# to zero if no more than one thread is expected to wait for +# a semaphore. +# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors +# by task_create() when a new task is started. If set, all +# files/drivers will appear to be closed in the new task. +# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first +# three file descriptors (stdin, stdout, stderr) by task_create() +# when a new task is started. If set, all files/drivers will +# appear to be closed in the new task except for stdin, stdout, +# and stderr. +# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket +# desciptors by task_create() when a new task is started. If +# set, all sockets will appear to be closed in the new task. +# CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to +# handle delayed processing from interrupt handlers. This feature +# is required for some drivers but, if there are not complaints, +# can be safely disabled. The worker thread also performs +# garbage collection -- completing any delayed memory deallocations +# from interrupt handlers. If the worker thread is disabled, +# then that clean will be performed by the IDLE thread instead +# (which runs at the lowest of priority and may not be appropriate +# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE +# is enabled, then the following options can also be used: +# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker +# thread. Default: 50 +# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for +# work in units of microseconds. Default: 50*1000 (50 MS). +# CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker +# thread. Default: CONFIG_IDLETHREAD_STACKSIZE. +# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up +# the worker thread. Default: 4 +# CONFIG_SCHED_WAITPID - Enable the waitpid() API +# CONFIG_SCHED_ATEXIT - Enabled the atexit() API +# +CONFIG_USER_ENTRYPOINT="user_start" +#CONFIG_APPS_DIR= +CONFIG_DEBUG=n +CONFIG_DEBUG_VERBOSE=n +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_FS=n +CONFIG_DEBUG_GRAPHICS=n +CONFIG_DEBUG_LCD=n +CONFIG_DEBUG_USB=n +CONFIG_DEBUG_NET=n +CONFIG_DEBUG_RTC=n +CONFIG_DEBUG_ANALOG=n +CONFIG_DEBUG_PWM=n +CONFIG_DEBUG_CAN=n +CONFIG_DEBUG_I2C=n +CONFIG_DEBUG_INPUT=n + +CONFIG_MSEC_PER_TICK=1 +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_MM_REGIONS=1 +CONFIG_MM_SMALL=y +CONFIG_ARCH_LOWPUTC=y +CONFIG_RR_INTERVAL=0 +CONFIG_SCHED_INSTRUMENTATION=n +CONFIG_TASK_NAME_SIZE=8 +CONFIG_START_YEAR=1970 +CONFIG_START_MONTH=1 +CONFIG_START_DAY=1 +CONFIG_GREGORIAN_TIME=n +CONFIG_JULIAN_TIME=n +# this eats ~1KiB of RAM ... work out why +CONFIG_DEV_CONSOLE=y +CONFIG_DEV_LOWCONSOLE=n +CONFIG_MUTEX_TYPES=n +CONFIG_PRIORITY_INHERITANCE=n +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SEM_NNESTPRIO=0 +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_SCHED_WORKQUEUE=n +CONFIG_SCHED_WORKPRIORITY=50 +CONFIG_SCHED_WORKPERIOD=50000 +CONFIG_SCHED_WORKSTACKSIZE=1024 +CONFIG_SIG_SIGWORK=4 +CONFIG_SCHED_WAITPID=n +CONFIG_SCHED_ATEXIT=n + +# +# The following can be used to disable categories of +# APIs supported by the OS. If the compiler supports +# weak functions, then it should not be necessary to +# disable functions unless you want to restrict usage +# of those APIs. +# +# There are certain dependency relationships in these +# features. +# +# o mq_notify logic depends on signals to awaken tasks +# waiting for queues to become full or empty. +# o pthread_condtimedwait() depends on signals to wake +# up waiting tasks. +# +CONFIG_DISABLE_CLOCK=n +CONFIG_DISABLE_POSIX_TIMERS=y +CONFIG_DISABLE_PTHREAD=y +CONFIG_DISABLE_SIGNALS=y +CONFIG_DISABLE_MQUEUE=y +CONFIG_DISABLE_MOUNTPOINT=y +CONFIG_DISABLE_ENVIRON=y +CONFIG_DISABLE_POLL=y + +# +# Misc libc settings +# +# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a +# little smaller if we do not support fieldwidthes +# +CONFIG_NOPRINTF_FIELDWIDTH=n + +# +# Allow for architecture optimized implementations +# +# The architecture can provide optimized versions of the +# following to improve system performance +# +CONFIG_ARCH_MEMCPY=n +CONFIG_ARCH_MEMCMP=n +CONFIG_ARCH_MEMMOVE=n +CONFIG_ARCH_MEMSET=n +CONFIG_ARCH_STRCMP=n +CONFIG_ARCH_STRCPY=n +CONFIG_ARCH_STRNCPY=n +CONFIG_ARCH_STRLEN=n +CONFIG_ARCH_STRNLEN=n +CONFIG_ARCH_BZERO=n + +# +# Sizes of configurable things (0 disables) +# +# CONFIG_MAX_TASKS - The maximum number of simultaneously +# active tasks. This value must be a power of two. +# CONFIG_MAX_TASK_ARGS - This controls the maximum number of +# of parameters that a task may receive (i.e., maxmum value +# of 'argc') +# CONFIG_NPTHREAD_KEYS - The number of items of thread- +# specific data that can be retained +# CONFIG_NFILE_DESCRIPTORS - The maximum number of file +# descriptors (one for each open) +# CONFIG_NFILE_STREAMS - The maximum number of streams that +# can be fopen'ed +# CONFIG_NAME_MAX - The maximum size of a file name. +# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate +# on fopen. (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_STDIO_LINEBUFFER - If standard C buffered I/O is enabled +# (CONFIG_STDIO_BUFFER_SIZE > 0), then this option may be added +# to force automatic, line-oriented flushing the output buffer +# for putc(), fputc(), putchar(), puts(), fputs(), printf(), +# fprintf(), and vfprintf(). When a newline is encountered in +# the output string, the output buffer will be flushed. This +# (slightly) increases the NuttX footprint but supports the kind +# of behavior that people expect for printf(). +# CONFIG_NUNGET_CHARS - Number of characters that can be +# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message +# structures. The system manages a pool of preallocated +# message structures to minimize dynamic allocations +# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with +# a fixed payload size given by this settin (does not include +# other message structure overhead. +# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that +# can be passed to a watchdog handler +# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog +# structures. The system manages a pool of preallocated +# watchdog structures to minimize dynamic allocations +# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX +# timer structures. The system manages a pool of preallocated +# timer structures to minimize dynamic allocations. Set to +# zero for all dynamic allocations. +# +CONFIG_MAX_TASKS=4 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=2 +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=0 +CONFIG_NAME_MAX=12 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STDIO_LINEBUFFER=n +CONFIG_NUNGET_CHARS=2 +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=4 +CONFIG_PREALLOC_TIMERS=0 + + +# +# Settings for apps/nshlib +# +# CONFIG_NSH_BUILTIN_APPS - Support external registered, +# "named" applications that can be executed from the NSH +# command line (see apps/README.txt for more information). +# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer +# CONFIG_NSH_STRERROR - Use strerror(errno) +# CONFIG_NSH_LINELEN - Maximum length of one command line +# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi +# CONFIG_NSH_DISABLESCRIPT - Disable scripting support +# CONFIG_NSH_DISABLEBG - Disable background commands +# CONFIG_NSH_ROMFSETC - Use startup script in /etc +# CONFIG_NSH_CONSOLE - Use serial console front end +# CONFIG_NSH_TELNET - Use telnetd console front end +# CONFIG_NSH_ARCHINIT - Platform provides architecture +# specific initialization (nsh_archinitialize()). +# + +# Disable NSH completely +CONFIG_NSH_CONSOLE=n + +# +# Stack and heap information +# +# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP +# operation from FLASH but must copy initialized .data sections to RAM. +# (should also be =n for the STM3210E-EVAL which always runs from flash) +# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH +# but copy themselves entirely into RAM for better performance. +# CONFIG_CUSTOM_STACK - The up_ implementation will handle +# all stack operations outside of the nuttx model. +# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only) +# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. +# This is the thread that (1) performs the inital boot of the system up +# to the point where user_start() is spawned, and (2) there after is the +# IDLE thread that executes only when there is no other thread ready to +# run. +# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate +# for the main user thread that begins at the user_start() entry point. +# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size +# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size +# CONFIG_HEAP_BASE - The beginning of the heap +# CONFIG_HEAP_SIZE - The size of the heap +# +CONFIG_BOOT_RUNFROMFLASH=n +CONFIG_BOOT_COPYTORAM=n +CONFIG_CUSTOM_STACK=n +CONFIG_STACK_POINTER= +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=1200 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_PTHREAD_STACK_DEFAULT=1024 +CONFIG_HEAP_BASE= +CONFIG_HEAP_SIZE= + +# +# NSH Library +# +# CONFIG_NSH_LIBRARY is not set +# CONFIG_NSH_BUILTIN_APPS is not set diff --git a/nuttx-configs/px4io-v1/nsh/setenv.sh b/nuttx-configs/px4io-v1/nsh/setenv.sh new file mode 100755 index 0000000000..ff9a4bf8ae --- /dev/null +++ b/nuttx-configs/px4io-v1/nsh/setenv.sh @@ -0,0 +1,47 @@ +#!/bin/bash +# configs/stm3210e-eval/dfu/setenv.sh +# +# Copyright (C) 2009 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name NuttX nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# + +if [ "$(basename $0)" = "setenv.sh" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi + +WD=`pwd` +export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" +export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/nuttx-configs/px4io-v1/scripts/ld.script b/nuttx-configs/px4io-v1/scripts/ld.script new file mode 100755 index 0000000000..69c2f9cb2e --- /dev/null +++ b/nuttx-configs/px4io-v1/scripts/ld.script @@ -0,0 +1,129 @@ +/**************************************************************************** + * configs/stm3210e-eval/nsh/ld.script + * + * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The STM32F100C8 has 64Kb of FLASH beginning at address 0x0800:0000 and + * 8Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH, + * FLASH memory is aliased to address 0x0000:0000 where the code expects to + * begin execution by jumping to the entry point in the 0x0800:0000 address + * range. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08001000, LENGTH = 60K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 8K +} + +OUTPUT_ARCH(arm) +ENTRY(__start) /* treat __start as the anchor for dead code stripping */ +EXTERN(_vectors) /* force the vectors to be included in the output */ + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + /* The STM32F100CB has 8Kb of SRAM beginning at the following address */ + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/nuttx-configs/px4io-v1/src/Makefile b/nuttx-configs/px4io-v1/src/Makefile new file mode 100644 index 0000000000..bb9539d16a --- /dev/null +++ b/nuttx-configs/px4io-v1/src/Makefile @@ -0,0 +1,84 @@ +############################################################################ +# configs/stm3210e-eval/src/Makefile +# +# Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name NuttX nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +-include $(TOPDIR)/Make.defs + +CFLAGS += -I$(TOPDIR)/sched + +ASRCS = +AOBJS = $(ASRCS:.S=$(OBJEXT)) + +CSRCS = empty.c + +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) + +ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ifeq ($(WINTOOL),y) + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}" +else + CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m +endif + +all: libboard$(LIBEXT) + +$(AOBJS): %$(OBJEXT): %.S + $(call ASSEMBLE, $<, $@) + +$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +libboard$(LIBEXT): $(OBJS) + $(call ARCHIVE, $@, $(OBJS)) + +.depend: Makefile $(SRCS) + @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ + +depend: .depend + +clean: + $(call DELFILE, libboard$(LIBEXT)) + $(call CLEAN) + +distclean: clean + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) + +-include Make.dep diff --git a/nuttx-configs/px4io-v1/src/empty.c b/nuttx-configs/px4io-v1/src/empty.c new file mode 100644 index 0000000000..ace900866c --- /dev/null +++ b/nuttx-configs/px4io-v1/src/empty.c @@ -0,0 +1,4 @@ +/* + * There are no source files here, but libboard.a can't be empty, so + * we have this empty source file to keep it company. + */ From ce2fa29fe3f0abeb01482e9932078f3cb25378a6 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sat, 3 Aug 2013 10:06:34 -0700 Subject: [PATCH 16/80] Add a missing module -> module makefile dependency --- makefiles/firmware.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk index f1c1b496a0..3ad13088b0 100644 --- a/makefiles/firmware.mk +++ b/makefiles/firmware.mk @@ -385,7 +385,7 @@ define BUILTIN_DEF endef # Don't generate until modules have updated their command files -$(BUILTIN_CSRC): $(GLOBAL_DEPS) $(MODULE_OBJS) $(BUILTIN_COMMAND_FILES) +$(BUILTIN_CSRC): $(GLOBAL_DEPS) $(MODULE_OBJS) $(MODULE_MKFILES) $(BUILTIN_COMMAND_FILES) @$(ECHO) "CMDS: $@" $(Q) $(ECHO) '/* builtin command list - automatically generated, do not edit */' > $@ $(Q) $(ECHO) '#include ' >> $@ From 97b75951b13b9f4a79058d11f4c8923444ebc544 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 3 Aug 2013 14:33:43 -0400 Subject: [PATCH 17/80] Shortened segway param names. --- src/modules/segway/BlockSegwayController.cpp | 2 +- src/modules/segway/BlockSegwayController.hpp | 8 ++++---- src/modules/segway/params.c | 8 ++++---- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/modules/segway/BlockSegwayController.cpp b/src/modules/segway/BlockSegwayController.cpp index 682758a14b..b1dc39445f 100644 --- a/src/modules/segway/BlockSegwayController.cpp +++ b/src/modules/segway/BlockSegwayController.cpp @@ -31,7 +31,7 @@ void BlockSegwayController::update() { } // compute speed command - float spdCmd = -theta2spd.update(_att.pitch) - q2spd.update(_att.pitchspeed); + float spdCmd = -th2v.update(_att.pitch) - q2v.update(_att.pitchspeed); // handle autopilot modes if (_status.state_machine == SYSTEM_STATE_AUTO || diff --git a/src/modules/segway/BlockSegwayController.hpp b/src/modules/segway/BlockSegwayController.hpp index e2faa49169..4a01f785c5 100644 --- a/src/modules/segway/BlockSegwayController.hpp +++ b/src/modules/segway/BlockSegwayController.hpp @@ -8,8 +8,8 @@ class BlockSegwayController : public control::BlockUorbEnabledAutopilot { public: BlockSegwayController() : BlockUorbEnabledAutopilot(NULL,"SEG"), - theta2spd(this, "THETA2SPD"), - q2spd(this, "Q2SPD"), + th2v(this, "TH2V"), + q2v(this, "Q2V"), _attPoll(), _timeStamp(0) { @@ -19,8 +19,8 @@ public: void update(); private: enum {CH_LEFT, CH_RIGHT}; - BlockPI theta2spd; - BlockP q2spd; + BlockPI th2v; + BlockP q2v; struct pollfd _attPoll; uint64_t _timeStamp; }; diff --git a/src/modules/segway/params.c b/src/modules/segway/params.c index 1669785d31..d729237174 100644 --- a/src/modules/segway/params.c +++ b/src/modules/segway/params.c @@ -1,8 +1,8 @@ #include // 16 is max name length -PARAM_DEFINE_FLOAT(SEG_THETA2SPD_P, 10.0f); // pitch to speed -PARAM_DEFINE_FLOAT(SEG_THETA2SPD_I, 0.0f); // pitch integral to speed -PARAM_DEFINE_FLOAT(SEG_THETA2SPD_I_MAX, 0.0f); // integral limiter -PARAM_DEFINE_FLOAT(SEG_Q2SPD, 1.0f); // pitch rate to speed +PARAM_DEFINE_FLOAT(SEG_TH2V_P, 10.0f); // pitch to voltage +PARAM_DEFINE_FLOAT(SEG_TH2V_I, 0.0f); // pitch integral to voltage +PARAM_DEFINE_FLOAT(SEG_TH2V_I_MAX, 0.0f); // integral limiter +PARAM_DEFINE_FLOAT(SEG_Q2V, 1.0f); // pitch rate to voltage From 9a97001cc849038223aa5eda6a76ac0fc6f1094f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 4 Aug 2013 01:50:58 +0200 Subject: [PATCH 18/80] Added queue to mpu6k driver --- src/drivers/mpu6000/mpu6000.cpp | 254 +++++++++++++++++++++++++------- 1 file changed, 201 insertions(+), 53 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index 1fd6cb17e7..d37d39a7ab 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -181,13 +181,21 @@ private: struct hrt_call _call; unsigned _call_interval; - struct accel_report _accel_report; + unsigned _num_accel_reports; + volatile unsigned _next_accel_report; + volatile unsigned _oldest_accel_report; + struct accel_report *_accel_reports; + struct accel_scale _accel_scale; float _accel_range_scale; float _accel_range_m_s2; orb_advert_t _accel_topic; - struct gyro_report _gyro_report; + unsigned _num_gyro_reports; + volatile unsigned _next_gyro_report; + volatile unsigned _oldest_gyro_report; + struct gyro_report *_gyro_reports; + struct gyro_scale _gyro_scale; float _gyro_range_scale; float _gyro_range_rad_s; @@ -306,14 +314,25 @@ private: /** driver 'main' command */ extern "C" { __EXPORT int mpu6000_main(int argc, char *argv[]); } +/* helper macro for handling report buffer indices */ +#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0) + MPU6000::MPU6000(int bus, spi_dev_e device) : SPI("MPU6000", ACCEL_DEVICE_PATH, bus, device, SPIDEV_MODE3, 10000000), _gyro(new MPU6000_gyro(this)), _product(0), _call_interval(0), + _num_accel_reports(0), + _next_accel_report(0), + _oldest_accel_report(0), + _accel_reports(nullptr), _accel_range_scale(0.0f), _accel_range_m_s2(0.0f), _accel_topic(-1), + _num_gyro_reports(0), + _next_gyro_report(0), + _oldest_gyro_report(0), + _gyro_reports(nullptr), _gyro_range_scale(0.0f), _gyro_range_rad_s(0.0f), _gyro_topic(-1), @@ -340,8 +359,6 @@ MPU6000::MPU6000(int bus, spi_dev_e device) : _gyro_scale.z_offset = 0; _gyro_scale.z_scale = 1.0f; - memset(&_accel_report, 0, sizeof(_accel_report)); - memset(&_gyro_report, 0, sizeof(_gyro_report)); memset(&_call, 0, sizeof(_call)); } @@ -353,6 +370,12 @@ MPU6000::~MPU6000() /* delete the gyro subdriver */ delete _gyro; + /* free any existing reports */ + if (_accel_reports != nullptr) + delete[] _accel_reports; + if (_gyro_reports != nullptr) + delete[] _gyro_reports; + /* delete the perf counter */ perf_free(_sample_perf); } @@ -361,6 +384,7 @@ int MPU6000::init() { int ret; + int gyro_ret; /* do SPI init (and probe) first */ ret = SPI::init(); @@ -371,6 +395,21 @@ MPU6000::init() return ret; } + /* allocate basic report buffers */ + _num_accel_reports = 2; + _oldest_accel_report = _next_accel_report = 0; + _accel_reports = new struct accel_report[_num_accel_reports]; + + if (_accel_reports == nullptr) + goto out; + + _num_gyro_reports = 2; + _oldest_gyro_report = _next_gyro_report = 0; + _gyro_reports = new struct gyro_report[_num_gyro_reports]; + + if (_gyro_reports == nullptr) + goto out; + // Chip reset write_reg(MPUREG_PWR_MGMT_1, BIT_H_RESET); up_udelay(10000); @@ -462,7 +501,10 @@ MPU6000::init() usleep(1000); /* do CDev init for the gyro device node, keep it optional */ - int gyro_ret = _gyro->init(); + gyro_ret = _gyro->init(); + + memset(&_accel_reports[0], 0, sizeof(_accel_reports[0])); + memset(&_gyro_reports[0], 0, sizeof(_gyro_reports[0])); /* ensure we got real values to share */ measure(); @@ -470,12 +512,13 @@ MPU6000::init() if (gyro_ret != OK) { _gyro_topic = -1; } else { - _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &_gyro_report); + _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &_gyro_reports[0]); } - /* advertise sensor topics */ - _accel_topic = orb_advertise(ORB_ID(sensor_accel), &_accel_report); + /* advertise accel topic */ + _accel_topic = orb_advertise(ORB_ID(sensor_accel), &_accel_reports[0]); +out: return ret; } @@ -555,19 +598,40 @@ MPU6000::_set_dlpf_filter(uint16_t frequency_hz) ssize_t MPU6000::read(struct file *filp, char *buffer, size_t buflen) { + unsigned count = buflen / sizeof(struct accel_report); int ret = 0; /* buffer must be large enough */ - if (buflen < sizeof(_accel_report)) + if (count < 1) return -ENOSPC; - /* if automatic measurement is not enabled */ - if (_call_interval == 0) - measure(); + /* if automatic measurement is enabled */ + if (_call_interval > 0) { - /* copy out the latest reports */ - memcpy(buffer, &_accel_report, sizeof(_accel_report)); - ret = sizeof(_accel_report); + /* + * While there is space in the caller's buffer, and reports, copy them. + * Note that we may be pre-empted by the measurement code while we are doing this; + * we are careful to avoid racing with it. + */ + while (count--) { + if (_oldest_accel_report != _next_accel_report) { + memcpy(buffer, _accel_reports + _oldest_accel_report, sizeof(*_accel_reports)); + ret += sizeof(_accel_reports[0]); + INCREMENT(_oldest_accel_report, _num_accel_reports); + } + } + + /* if there was no data, warn the caller */ + return ret ? ret : -EAGAIN; + } + + /* manual measurement */ + _oldest_accel_report = _next_accel_report = 0; + measure(); + + /* measurement will have generated a report, copy it out */ + memcpy(buffer, _accel_reports, sizeof(*_accel_reports)); + ret = sizeof(*_accel_reports); return ret; } @@ -586,19 +650,40 @@ MPU6000::self_test() ssize_t MPU6000::gyro_read(struct file *filp, char *buffer, size_t buflen) { + unsigned count = buflen / sizeof(struct gyro_report); int ret = 0; /* buffer must be large enough */ - if (buflen < sizeof(_gyro_report)) + if (count < 1) return -ENOSPC; - /* if automatic measurement is not enabled */ - if (_call_interval == 0) - measure(); + /* if automatic measurement is enabled */ + if (_call_interval > 0) { - /* copy out the latest report */ - memcpy(buffer, &_gyro_report, sizeof(_gyro_report)); - ret = sizeof(_gyro_report); + /* + * While there is space in the caller's buffer, and reports, copy them. + * Note that we may be pre-empted by the measurement code while we are doing this; + * we are careful to avoid racing with it. + */ + while (count--) { + if (_oldest_gyro_report != _next_gyro_report) { + memcpy(buffer, _gyro_reports + _oldest_gyro_report, sizeof(*_gyro_reports)); + ret += sizeof(_gyro_reports[0]); + INCREMENT(_oldest_gyro_report, _num_gyro_reports); + } + } + + /* if there was no data, warn the caller */ + return ret ? ret : -EAGAIN; + } + + /* manual measurement */ + _oldest_gyro_report = _next_gyro_report = 0; + measure(); + + /* measurement will have generated a report, copy it out */ + memcpy(buffer, _gyro_reports, sizeof(*_gyro_reports)); + ret = sizeof(*_gyro_reports); return ret; } @@ -661,14 +746,32 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg) return 1000000 / _call_interval; - case SENSORIOCSQUEUEDEPTH: - /* XXX not implemented */ - return -EINVAL; + case SENSORIOCSQUEUEDEPTH: { + /* account for sentinel in the ring */ + arg++; + + /* lower bound is mandatory, upper bound is a sanity check */ + if ((arg < 2) || (arg > 100)) + return -EINVAL; + + /* allocate new buffer */ + struct accel_report *buf = new struct accel_report[arg]; + + if (nullptr == buf) + return -ENOMEM; + + /* reset the measurement state machine with the new buffer, free the old */ + stop(); + delete[] _accel_reports; + _num_accel_reports = arg; + _accel_reports = buf; + start(); + + return OK; + } case SENSORIOCGQUEUEDEPTH: - /* XXX not implemented */ - return -EINVAL; - + return _num_accel_reports - 1; case ACCELIOCGSAMPLERATE: return _sample_rate; @@ -726,11 +829,36 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg) /* these are shared with the accel side */ case SENSORIOCSPOLLRATE: case SENSORIOCGPOLLRATE: - case SENSORIOCSQUEUEDEPTH: - case SENSORIOCGQUEUEDEPTH: case SENSORIOCRESET: return ioctl(filp, cmd, arg); + case SENSORIOCSQUEUEDEPTH: { + /* account for sentinel in the ring */ + arg++; + + /* lower bound is mandatory, upper bound is a sanity check */ + if ((arg < 2) || (arg > 100)) + return -EINVAL; + + /* allocate new buffer */ + struct gyro_report *buf = new struct gyro_report[arg]; + + if (nullptr == buf) + return -ENOMEM; + + /* reset the measurement state machine with the new buffer, free the old */ + stop(); + delete[] _gyro_reports; + _num_gyro_reports = arg; + _gyro_reports = buf; + start(); + + return OK; + } + + case SENSORIOCGQUEUEDEPTH: + return _num_gyro_reports - 1; + case GYROIOCGSAMPLERATE: return _sample_rate; @@ -959,10 +1087,16 @@ MPU6000::measure() report.gyro_x = gyro_xt; report.gyro_y = gyro_yt; + /* + * Get references to the current reports + */ + accel_report *accel_report = &_accel_reports[_next_accel_report]; + gyro_report *gyro_report = &_gyro_reports[_next_gyro_report]; + /* * Adjust and scale results to m/s^2. */ - _gyro_report.timestamp = _accel_report.timestamp = hrt_absolute_time(); + gyro_report->timestamp = accel_report->timestamp = hrt_absolute_time(); /* @@ -983,40 +1117,54 @@ MPU6000::measure() /* NOTE: Axes have been swapped to match the board a few lines above. */ - _accel_report.x_raw = report.accel_x; - _accel_report.y_raw = report.accel_y; - _accel_report.z_raw = report.accel_z; + accel_report->x_raw = report.accel_x; + accel_report->y_raw = report.accel_y; + accel_report->z_raw = report.accel_z; - _accel_report.x = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale; - _accel_report.y = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale; - _accel_report.z = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale; - _accel_report.scaling = _accel_range_scale; - _accel_report.range_m_s2 = _accel_range_m_s2; + accel_report->x = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale; + accel_report->y = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale; + accel_report->z = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale; + accel_report->scaling = _accel_range_scale; + accel_report->range_m_s2 = _accel_range_m_s2; - _accel_report.temperature_raw = report.temp; - _accel_report.temperature = (report.temp) / 361.0f + 35.0f; + accel_report->temperature_raw = report.temp; + accel_report->temperature = (report.temp) / 361.0f + 35.0f; - _gyro_report.x_raw = report.gyro_x; - _gyro_report.y_raw = report.gyro_y; - _gyro_report.z_raw = report.gyro_z; + gyro_report->x_raw = report.gyro_x; + gyro_report->y_raw = report.gyro_y; + gyro_report->z_raw = report.gyro_z; - _gyro_report.x = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale; - _gyro_report.y = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale; - _gyro_report.z = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale; - _gyro_report.scaling = _gyro_range_scale; - _gyro_report.range_rad_s = _gyro_range_rad_s; + gyro_report->x = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale; + gyro_report->y = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale; + gyro_report->z = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale; + gyro_report->scaling = _gyro_range_scale; + gyro_report->range_rad_s = _gyro_range_rad_s; - _gyro_report.temperature_raw = report.temp; - _gyro_report.temperature = (report.temp) / 361.0f + 35.0f; + gyro_report->temperature_raw = report.temp; + gyro_report->temperature = (report.temp) / 361.0f + 35.0f; + + /* ACCEL: post a report to the ring - note, not locked */ + INCREMENT(_next_accel_report, _num_accel_reports); + + /* ACCEL: if we are running up against the oldest report, fix it */ + if (_next_accel_report == _oldest_accel_report) + INCREMENT(_oldest_accel_report, _num_accel_reports); + + /* GYRO: post a report to the ring - note, not locked */ + INCREMENT(_next_gyro_report, _num_gyro_reports); + + /* GYRO: if we are running up against the oldest report, fix it */ + if (_next_gyro_report == _oldest_gyro_report) + INCREMENT(_oldest_gyro_report, _num_gyro_reports); /* notify anyone waiting for data */ poll_notify(POLLIN); _gyro->parent_poll_notify(); /* and publish for subscribers */ - orb_publish(ORB_ID(sensor_accel), _accel_topic, &_accel_report); + orb_publish(ORB_ID(sensor_accel), _accel_topic, accel_report); if (_gyro_topic != -1) { - orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &_gyro_report); + orb_publish(ORB_ID(sensor_gyro), _gyro_topic, gyro_report); } /* stop measuring */ From 234ad240818e6486d39a3149597956a534d59ea0 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 21 Jul 2013 23:46:37 -0700 Subject: [PATCH 19/80] Simple ring-buffer template class, because re-implementing the wheel in every driver is silly. --- src/drivers/device/ringbuffer.h | 192 ++++++++++++++++++++++++++++++++ 1 file changed, 192 insertions(+) create mode 100644 src/drivers/device/ringbuffer.h diff --git a/src/drivers/device/ringbuffer.h b/src/drivers/device/ringbuffer.h new file mode 100644 index 0000000000..37686fdbe3 --- /dev/null +++ b/src/drivers/device/ringbuffer.h @@ -0,0 +1,192 @@ +/**************************************************************************** + * + * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * Author: Lorenz Meier + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file ringbuffer.h + * + * A simple ringbuffer template. + */ + +#pragma once + +template +class RingBuffer { +public: + RingBuffer(unsigned size); + virtual ~RingBuffer(); + + /** + * Put an item into the buffer. + * + * @param val Item to put + * @return true if the item was put, false if the buffer is full + */ + bool put(T &val); + + /** + * Put an item into the buffer. + * + * @param val Item to put + * @return true if the item was put, false if the buffer is full + */ + bool put(const T &val); + + /** + * Get an item from the buffer. + * + * @param val Item that was gotten + * @return true if an item was got, false if the buffer was empty. + */ + bool get(T &val); + + /** + * Get an item from the buffer (scalars only). + * + * @return The value that was fetched, or zero if the buffer was + * empty. + */ + T get(void); + + /* + * Get the number of slots free in the buffer. + * + * @return The number of items that can be put into the buffer before + * it becomes full. + */ + unsigned space(void); + + /* + * Get the number of items in the buffer. + * + * @return The number of items that can be got from the buffer before + * it becomes empty. + */ + unsigned count(void); + + /* + * Returns true if the buffer is empty. + */ + bool empty() { return _tail == _head; } + + /* + * Returns true if the buffer is full. + */ + bool full() { return _next(_head) == _tail; } + +private: + T *const _buf; + const unsigned _size; + volatile unsigned _head; /**< insertion point */ + volatile unsigned _tail; /**< removal point */ + + unsigned _next(unsigned index); +}; + +template +RingBuffer::RingBuffer(unsigned size) : + _buf(new T[size + 1]), + _size(size), + _head(size), + _tail(size) +{} + +template +RingBuffer::~RingBuffer() +{ + if (_buf != nullptr) + delete[] _buf; +} + +template +bool RingBuffer::put(T &val) +{ + unsigned next = _next(_head); + if (next != _tail) { + _buf[_head] = val; + _head = next; + return true; + } else { + return false; + } +} + +template +bool RingBuffer::put(const T &val) +{ + unsigned next = _next(_head); + if (next != _tail) { + _buf[_head] = val; + _head = next; + return true; + } else { + return false; + } +} + +template +bool RingBuffer::get(T &val) +{ + if (_tail != _head) { + val = _buf[_tail]; + _tail = _next(_tail); + return true; + } else { + return false; + } +} + +template +T RingBuffer::get(void) +{ + T val; + return get(val) ? val : 0; +} + +template +unsigned RingBuffer::space(void) +{ + return (_tail >= _head) ? (_size - (_tail - _head)) : (_head - _tail - 1); +} + +template +unsigned RingBuffer::count(void) +{ + return _size - space(); +} + +template +unsigned RingBuffer::_next(unsigned index) +{ + return (0 == index) ? _size : (index - 1); +} From a3ab88872cbca30be62b04461c8294399923ec89 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sat, 3 Aug 2013 19:02:54 -0700 Subject: [PATCH 20/80] Add some more useful methods to the ringbuffer class. --- src/drivers/device/ringbuffer.h | 21 ++++++++++++++++----- 1 file changed, 16 insertions(+), 5 deletions(-) diff --git a/src/drivers/device/ringbuffer.h b/src/drivers/device/ringbuffer.h index 37686fdbe3..dc0c84052b 100644 --- a/src/drivers/device/ringbuffer.h +++ b/src/drivers/device/ringbuffer.h @@ -104,6 +104,17 @@ public: */ bool full() { return _next(_head) == _tail; } + /* + * Returns the capacity of the buffer, or zero if the buffer could + * not be allocated. + */ + unsigned size() { return (_buf != nullptr) ? _size : 0; } + + /* + * Empties the buffer. + */ + void flush() { _head = _tail = _size; } + private: T *const _buf; const unsigned _size; @@ -114,11 +125,11 @@ private: }; template -RingBuffer::RingBuffer(unsigned size) : - _buf(new T[size + 1]), - _size(size), - _head(size), - _tail(size) +RingBuffer::RingBuffer(unsigned with_size) : + _buf(new T[with_size + 1]), + _size(with_size), + _head(with_size), + _tail(with_size) {} template From 02f5b79948742d6b7121399e39444286cc01f161 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sat, 3 Aug 2013 19:03:24 -0700 Subject: [PATCH 21/80] Try to save our sanity a bit and use the generic ringbuffer class rather than re-implementing the wheel. --- src/drivers/mpu6000/mpu6000.cpp | 255 +++++++++++++------------------- 1 file changed, 104 insertions(+), 151 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index d37d39a7ab..f848cca6b8 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -67,6 +67,7 @@ #include #include +#include #include #include @@ -181,20 +182,16 @@ private: struct hrt_call _call; unsigned _call_interval; - unsigned _num_accel_reports; - volatile unsigned _next_accel_report; - volatile unsigned _oldest_accel_report; - struct accel_report *_accel_reports; + typedef RingBuffer AccelReportBuffer; + AccelReportBuffer *_accel_reports; struct accel_scale _accel_scale; float _accel_range_scale; float _accel_range_m_s2; orb_advert_t _accel_topic; - unsigned _num_gyro_reports; - volatile unsigned _next_gyro_report; - volatile unsigned _oldest_gyro_report; - struct gyro_report *_gyro_reports; + typedef RingBuffer GyroReportBuffer; + GyroReportBuffer *_gyro_reports; struct gyro_scale _gyro_scale; float _gyro_range_scale; @@ -227,7 +224,7 @@ private: static void measure_trampoline(void *arg); /** - * Fetch measurements from the sensor and update the report ring. + * Fetch measurements from the sensor and update the report buffers. */ void measure(); @@ -314,24 +311,15 @@ private: /** driver 'main' command */ extern "C" { __EXPORT int mpu6000_main(int argc, char *argv[]); } -/* helper macro for handling report buffer indices */ -#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0) - MPU6000::MPU6000(int bus, spi_dev_e device) : SPI("MPU6000", ACCEL_DEVICE_PATH, bus, device, SPIDEV_MODE3, 10000000), _gyro(new MPU6000_gyro(this)), _product(0), _call_interval(0), - _num_accel_reports(0), - _next_accel_report(0), - _oldest_accel_report(0), _accel_reports(nullptr), _accel_range_scale(0.0f), _accel_range_m_s2(0.0f), _accel_topic(-1), - _num_gyro_reports(0), - _next_gyro_report(0), - _oldest_gyro_report(0), _gyro_reports(nullptr), _gyro_range_scale(0.0f), _gyro_range_rad_s(0.0f), @@ -372,9 +360,9 @@ MPU6000::~MPU6000() /* free any existing reports */ if (_accel_reports != nullptr) - delete[] _accel_reports; + delete _accel_reports; if (_gyro_reports != nullptr) - delete[] _gyro_reports; + delete _gyro_reports; /* delete the perf counter */ perf_free(_sample_perf); @@ -396,17 +384,11 @@ MPU6000::init() } /* allocate basic report buffers */ - _num_accel_reports = 2; - _oldest_accel_report = _next_accel_report = 0; - _accel_reports = new struct accel_report[_num_accel_reports]; - + _accel_reports = new AccelReportBuffer(2); if (_accel_reports == nullptr) goto out; - _num_gyro_reports = 2; - _oldest_gyro_report = _next_gyro_report = 0; - _gyro_reports = new struct gyro_report[_num_gyro_reports]; - + _gyro_reports = new GyroReportBuffer(2); if (_gyro_reports == nullptr) goto out; @@ -503,20 +485,22 @@ MPU6000::init() /* do CDev init for the gyro device node, keep it optional */ gyro_ret = _gyro->init(); - memset(&_accel_reports[0], 0, sizeof(_accel_reports[0])); - memset(&_gyro_reports[0], 0, sizeof(_gyro_reports[0])); - - /* ensure we got real values to share */ + /* fetch an initial set of measurements for advertisement */ measure(); if (gyro_ret != OK) { _gyro_topic = -1; } else { - _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &_gyro_reports[0]); + gyro_report gr; + _gyro_reports->get(gr); + + _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &gr); } /* advertise accel topic */ - _accel_topic = orb_advertise(ORB_ID(sensor_accel), &_accel_reports[0]); + accel_report ar; + _accel_reports->get(ar); + _accel_topic = orb_advertise(ORB_ID(sensor_accel), &ar); out: return ret; @@ -598,42 +582,31 @@ MPU6000::_set_dlpf_filter(uint16_t frequency_hz) ssize_t MPU6000::read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(struct accel_report); - int ret = 0; + unsigned count = buflen / sizeof(accel_report); /* buffer must be large enough */ if (count < 1) return -ENOSPC; - /* if automatic measurement is enabled */ - if (_call_interval > 0) { - - /* - * While there is space in the caller's buffer, and reports, copy them. - * Note that we may be pre-empted by the measurement code while we are doing this; - * we are careful to avoid racing with it. - */ - while (count--) { - if (_oldest_accel_report != _next_accel_report) { - memcpy(buffer, _accel_reports + _oldest_accel_report, sizeof(*_accel_reports)); - ret += sizeof(_accel_reports[0]); - INCREMENT(_oldest_accel_report, _num_accel_reports); - } - } - - /* if there was no data, warn the caller */ - return ret ? ret : -EAGAIN; + /* if automatic measurement is not enabled, get a fresh measurement into the buffer */ + if (_call_interval == 0) { + _accel_reports->flush(); + measure(); } - /* manual measurement */ - _oldest_accel_report = _next_accel_report = 0; - measure(); + /* if no data, error (we could block here) */ + if (_accel_reports->empty()) + return -EAGAIN; - /* measurement will have generated a report, copy it out */ - memcpy(buffer, _accel_reports, sizeof(*_accel_reports)); - ret = sizeof(*_accel_reports); + /* copy reports out of our buffer to the caller */ + accel_report *arp = reinterpret_cast(buffer); + while (count--) { + if (!_accel_reports->get(*arp++)) + break; + } - return ret; + /* return the number of bytes transferred */ + return (buflen - (count * sizeof(accel_report))); } int @@ -651,41 +624,30 @@ ssize_t MPU6000::gyro_read(struct file *filp, char *buffer, size_t buflen) { unsigned count = buflen / sizeof(struct gyro_report); - int ret = 0; /* buffer must be large enough */ if (count < 1) return -ENOSPC; - /* if automatic measurement is enabled */ - if (_call_interval > 0) { - - /* - * While there is space in the caller's buffer, and reports, copy them. - * Note that we may be pre-empted by the measurement code while we are doing this; - * we are careful to avoid racing with it. - */ - while (count--) { - if (_oldest_gyro_report != _next_gyro_report) { - memcpy(buffer, _gyro_reports + _oldest_gyro_report, sizeof(*_gyro_reports)); - ret += sizeof(_gyro_reports[0]); - INCREMENT(_oldest_gyro_report, _num_gyro_reports); - } - } - - /* if there was no data, warn the caller */ - return ret ? ret : -EAGAIN; + /* if automatic measurement is not enabled, get a fresh measurement into the buffer */ + if (_call_interval == 0) { + _gyro_reports->flush(); + measure(); } - /* manual measurement */ - _oldest_gyro_report = _next_gyro_report = 0; - measure(); + /* if no data, error (we could block here) */ + if (_gyro_reports->empty()) + return -EAGAIN; - /* measurement will have generated a report, copy it out */ - memcpy(buffer, _gyro_reports, sizeof(*_gyro_reports)); - ret = sizeof(*_gyro_reports); + /* copy reports out of our buffer to the caller */ + gyro_report *arp = reinterpret_cast(buffer); + while (count--) { + if (!_gyro_reports->get(*arp++)) + break; + } - return ret; + /* return the number of bytes transferred */ + return (buflen - (count * sizeof(gyro_report))); } int @@ -747,23 +709,23 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg) return 1000000 / _call_interval; case SENSORIOCSQUEUEDEPTH: { - /* account for sentinel in the ring */ - arg++; - /* lower bound is mandatory, upper bound is a sanity check */ - if ((arg < 2) || (arg > 100)) + if ((arg < 1) || (arg > 100)) return -EINVAL; /* allocate new buffer */ - struct accel_report *buf = new struct accel_report[arg]; + AccelReportBuffer *buf = new AccelReportBuffer(arg); if (nullptr == buf) return -ENOMEM; + if (buf->size() == 0) { + delete buf; + return -ENOMEM; + } /* reset the measurement state machine with the new buffer, free the old */ stop(); - delete[] _accel_reports; - _num_accel_reports = arg; + delete _accel_reports; _accel_reports = buf; start(); @@ -771,14 +733,14 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg) } case SENSORIOCGQUEUEDEPTH: - return _num_accel_reports - 1; + return _accel_reports->size(); case ACCELIOCGSAMPLERATE: return _sample_rate; case ACCELIOCSSAMPLERATE: - _set_sample_rate(arg); - return OK; + _set_sample_rate(arg); + return OK; case ACCELIOCSLOWPASS: case ACCELIOCGLOWPASS: @@ -833,23 +795,23 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg) return ioctl(filp, cmd, arg); case SENSORIOCSQUEUEDEPTH: { - /* account for sentinel in the ring */ - arg++; - /* lower bound is mandatory, upper bound is a sanity check */ - if ((arg < 2) || (arg > 100)) + if ((arg < 1) || (arg > 100)) return -EINVAL; /* allocate new buffer */ - struct gyro_report *buf = new struct gyro_report[arg]; + GyroReportBuffer *buf = new GyroReportBuffer(arg); if (nullptr == buf) return -ENOMEM; + if (buf->size() == 0) { + delete buf; + return -ENOMEM; + } /* reset the measurement state machine with the new buffer, free the old */ stop(); - delete[] _gyro_reports; - _num_gyro_reports = arg; + delete _gyro_reports; _gyro_reports = buf; start(); @@ -857,7 +819,7 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg) } case SENSORIOCGQUEUEDEPTH: - return _num_gyro_reports - 1; + return _gyro_reports->size(); case GYROIOCGSAMPLERATE: return _sample_rate; @@ -993,6 +955,10 @@ MPU6000::start() /* make sure we are stopped first */ stop(); + /* discard any stale data in the buffers */ + _accel_reports->flush(); + _gyro_reports->flush(); + /* start polling at the specified rate */ hrt_call_every(&_call, 1000, _call_interval, (hrt_callout)&MPU6000::measure_trampoline, this); } @@ -1006,7 +972,7 @@ MPU6000::stop() void MPU6000::measure_trampoline(void *arg) { - MPU6000 *dev = (MPU6000 *)arg; + MPU6000 *dev = reinterpret_cast(arg); /* make another measurement */ dev->measure(); @@ -1088,15 +1054,15 @@ MPU6000::measure() report.gyro_y = gyro_yt; /* - * Get references to the current reports + * Report buffers. */ - accel_report *accel_report = &_accel_reports[_next_accel_report]; - gyro_report *gyro_report = &_gyro_reports[_next_gyro_report]; + accel_report arb; + gyro_report grb; /* * Adjust and scale results to m/s^2. */ - gyro_report->timestamp = accel_report->timestamp = hrt_absolute_time(); + grb.timestamp = arb.timestamp = hrt_absolute_time(); /* @@ -1117,54 +1083,43 @@ MPU6000::measure() /* NOTE: Axes have been swapped to match the board a few lines above. */ - accel_report->x_raw = report.accel_x; - accel_report->y_raw = report.accel_y; - accel_report->z_raw = report.accel_z; + arb.x_raw = report.accel_x; + arb.y_raw = report.accel_y; + arb.z_raw = report.accel_z; - accel_report->x = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale; - accel_report->y = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale; - accel_report->z = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale; - accel_report->scaling = _accel_range_scale; - accel_report->range_m_s2 = _accel_range_m_s2; + arb.x = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale; + arb.y = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale; + arb.z = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale; + arb.scaling = _accel_range_scale; + arb.range_m_s2 = _accel_range_m_s2; - accel_report->temperature_raw = report.temp; - accel_report->temperature = (report.temp) / 361.0f + 35.0f; + arb.temperature_raw = report.temp; + arb.temperature = (report.temp) / 361.0f + 35.0f; - gyro_report->x_raw = report.gyro_x; - gyro_report->y_raw = report.gyro_y; - gyro_report->z_raw = report.gyro_z; + grb.x_raw = report.gyro_x; + grb.y_raw = report.gyro_y; + grb.z_raw = report.gyro_z; - gyro_report->x = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale; - gyro_report->y = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale; - gyro_report->z = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale; - gyro_report->scaling = _gyro_range_scale; - gyro_report->range_rad_s = _gyro_range_rad_s; + grb.x = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale; + grb.y = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale; + grb.z = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale; + grb.scaling = _gyro_range_scale; + grb.range_rad_s = _gyro_range_rad_s; - gyro_report->temperature_raw = report.temp; - gyro_report->temperature = (report.temp) / 361.0f + 35.0f; + grb.temperature_raw = report.temp; + grb.temperature = (report.temp) / 361.0f + 35.0f; - /* ACCEL: post a report to the ring - note, not locked */ - INCREMENT(_next_accel_report, _num_accel_reports); - - /* ACCEL: if we are running up against the oldest report, fix it */ - if (_next_accel_report == _oldest_accel_report) - INCREMENT(_oldest_accel_report, _num_accel_reports); - - /* GYRO: post a report to the ring - note, not locked */ - INCREMENT(_next_gyro_report, _num_gyro_reports); - - /* GYRO: if we are running up against the oldest report, fix it */ - if (_next_gyro_report == _oldest_gyro_report) - INCREMENT(_oldest_gyro_report, _num_gyro_reports); + _accel_reports->put(arb); + _gyro_reports->put(grb); /* notify anyone waiting for data */ poll_notify(POLLIN); _gyro->parent_poll_notify(); /* and publish for subscribers */ - orb_publish(ORB_ID(sensor_accel), _accel_topic, accel_report); + orb_publish(ORB_ID(sensor_accel), _accel_topic, &arb); if (_gyro_topic != -1) { - orb_publish(ORB_ID(sensor_gyro), _gyro_topic, gyro_report); + orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &grb); } /* stop measuring */ @@ -1267,21 +1222,19 @@ fail: void test() { - int fd = -1; - int fd_gyro = -1; - struct accel_report a_report; - struct gyro_report g_report; + accel_report a_report; + gyro_report g_report; ssize_t sz; /* get the driver */ - fd = open(ACCEL_DEVICE_PATH, O_RDONLY); + int fd = open(ACCEL_DEVICE_PATH, O_RDONLY); if (fd < 0) err(1, "%s open failed (try 'mpu6000 start' if the driver is not running)", ACCEL_DEVICE_PATH); /* get the driver */ - fd_gyro = open(GYRO_DEVICE_PATH, O_RDONLY); + int fd_gyro = open(GYRO_DEVICE_PATH, O_RDONLY); if (fd_gyro < 0) err(1, "%s open failed", GYRO_DEVICE_PATH); From f45e74265e3952f350970d665adccdf539e136f2 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 4 Aug 2013 15:15:41 +0200 Subject: [PATCH 22/80] Fixed driver test / direct read, looks good --- src/drivers/mpu6000/mpu6000.cpp | 111 ++++++++++++++++++++------------ 1 file changed, 70 insertions(+), 41 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index f848cca6b8..9dcb4be9ed 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -212,6 +212,13 @@ private: */ void stop(); + /** + * Reset chip. + * + * Resets the chip and measurements ranges, but not scale and offset. + */ + void reset(); + /** * Static trampoline from the hrt_call context; because we don't have a * generic hrt wrapper yet. @@ -392,6 +399,50 @@ MPU6000::init() if (_gyro_reports == nullptr) goto out; + reset(); + + /* Initialize offsets and scales */ + _accel_scale.x_offset = 0; + _accel_scale.x_scale = 1.0f; + _accel_scale.y_offset = 0; + _accel_scale.y_scale = 1.0f; + _accel_scale.z_offset = 0; + _accel_scale.z_scale = 1.0f; + + _gyro_scale.x_offset = 0; + _gyro_scale.x_scale = 1.0f; + _gyro_scale.y_offset = 0; + _gyro_scale.y_scale = 1.0f; + _gyro_scale.z_offset = 0; + _gyro_scale.z_scale = 1.0f; + + /* do CDev init for the gyro device node, keep it optional */ + gyro_ret = _gyro->init(); + + /* fetch an initial set of measurements for advertisement */ + measure(); + + if (gyro_ret != OK) { + _gyro_topic = -1; + } else { + gyro_report gr; + _gyro_reports->get(gr); + + _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &gr); + } + + /* advertise accel topic */ + accel_report ar; + _accel_reports->get(ar); + _accel_topic = orb_advertise(ORB_ID(sensor_accel), &ar); + +out: + return ret; +} + +void MPU6000::reset() +{ + // Chip reset write_reg(MPUREG_PWR_MGMT_1, BIT_H_RESET); up_udelay(10000); @@ -423,12 +474,6 @@ MPU6000::init() // 2000 deg/s = (2000/180)*PI = 34.906585 rad/s // scaling factor: // 1/(2^15)*(2000/180)*PI - _gyro_scale.x_offset = 0; - _gyro_scale.x_scale = 1.0f; - _gyro_scale.y_offset = 0; - _gyro_scale.y_scale = 1.0f; - _gyro_scale.z_offset = 0; - _gyro_scale.z_scale = 1.0f; _gyro_range_scale = (0.0174532 / 16.4);//1.0f / (32768.0f * (2000.0f / 180.0f) * M_PI_F); _gyro_range_rad_s = (2000.0f / 180.0f) * M_PI_F; @@ -461,12 +506,6 @@ MPU6000::init() // Correct accel scale factors of 4096 LSB/g // scale to m/s^2 ( 1g = 9.81 m/s^2) - _accel_scale.x_offset = 0; - _accel_scale.x_scale = 1.0f; - _accel_scale.y_offset = 0; - _accel_scale.y_scale = 1.0f; - _accel_scale.z_offset = 0; - _accel_scale.z_scale = 1.0f; _accel_range_scale = (9.81f / 4096.0f); _accel_range_m_s2 = 8.0f * 9.81f; @@ -482,28 +521,6 @@ MPU6000::init() // write_reg(MPUREG_PWR_MGMT_1,MPU_CLK_SEL_PLLGYROZ); usleep(1000); - /* do CDev init for the gyro device node, keep it optional */ - gyro_ret = _gyro->init(); - - /* fetch an initial set of measurements for advertisement */ - measure(); - - if (gyro_ret != OK) { - _gyro_topic = -1; - } else { - gyro_report gr; - _gyro_reports->get(gr); - - _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &gr); - } - - /* advertise accel topic */ - accel_report ar; - _accel_reports->get(ar); - _accel_topic = orb_advertise(ORB_ID(sensor_accel), &ar); - -out: - return ret; } int @@ -600,13 +617,15 @@ MPU6000::read(struct file *filp, char *buffer, size_t buflen) /* copy reports out of our buffer to the caller */ accel_report *arp = reinterpret_cast(buffer); + int transferred = 0; while (count--) { if (!_accel_reports->get(*arp++)) break; + transferred++; } /* return the number of bytes transferred */ - return (buflen - (count * sizeof(accel_report))); + return (transferred * sizeof(accel_report)); } int @@ -623,7 +642,7 @@ MPU6000::self_test() ssize_t MPU6000::gyro_read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(struct gyro_report); + unsigned count = buflen / sizeof(gyro_report); /* buffer must be large enough */ if (count < 1) @@ -641,13 +660,15 @@ MPU6000::gyro_read(struct file *filp, char *buffer, size_t buflen) /* copy reports out of our buffer to the caller */ gyro_report *arp = reinterpret_cast(buffer); + int transferred = 0; while (count--) { if (!_gyro_reports->get(*arp++)) break; + transferred++; } /* return the number of bytes transferred */ - return (buflen - (count * sizeof(gyro_report))); + return (transferred * sizeof(gyro_report)); } int @@ -655,6 +676,10 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg) { switch (cmd) { + case SENSORIOCRESET: + reset(); + return OK; + case SENSORIOCSPOLLRATE: { switch (arg) { @@ -674,8 +699,8 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg) /* set default/max polling rate */ case SENSOR_POLLRATE_MAX: case SENSOR_POLLRATE_DEFAULT: - /* XXX 500Hz is just a wild guess */ - return ioctl(filp, SENSORIOCSPOLLRATE, 500); + /* set to same as sample rate per default */ + return ioctl(filp, SENSORIOCSPOLLRATE, _sample_rate); /* adjust to a legal polling interval in Hz */ default: { @@ -1246,8 +1271,10 @@ test() /* do a simple demand read */ sz = read(fd, &a_report, sizeof(a_report)); - if (sz != sizeof(a_report)) + if (sz != sizeof(a_report)) { + warnx("ret: %d, expected: %d", sz, sizeof(a_report)); err(1, "immediate acc read failed"); + } warnx("single read"); warnx("time: %lld", a_report.timestamp); @@ -1263,8 +1290,10 @@ test() /* do a simple demand read */ sz = read(fd_gyro, &g_report, sizeof(g_report)); - if (sz != sizeof(g_report)) + if (sz != sizeof(g_report)) { + warnx("ret: %d, expected: %d", sz, sizeof(g_report)); err(1, "immediate gyro read failed"); + } warnx("gyro x: \t% 9.5f\trad/s", (double)g_report.x); warnx("gyro y: \t% 9.5f\trad/s", (double)g_report.y); From 9bcabc5ba90d225f63e16f00595682fd4a4b857a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 4 Aug 2013 19:09:10 +0200 Subject: [PATCH 23/80] Hotfix for attitude estimator EKF init --- .../attitude_estimator_ekf_main.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp index 1eff60e88f..9e533ccdfb 100755 --- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp +++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp @@ -224,8 +224,8 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds /* subscribe to raw data */ int sub_raw = orb_subscribe(ORB_ID(sensor_combined)); - /* rate-limit raw data updates to 200Hz */ - orb_set_interval(sub_raw, 4); + /* rate-limit raw data updates to 333 Hz (sensors app publishes at 200, so this is just paranoid) */ + orb_set_interval(sub_raw, 3); /* subscribe to param changes */ int sub_params = orb_subscribe(ORB_ID(parameter_update)); @@ -236,7 +236,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds /* advertise attitude */ orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att); - int loopcounter = 0; int printcounter = 0; @@ -384,7 +383,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds static bool const_initialized = false; /* initialize with good values once we have a reasonable dt estimate */ - if (!const_initialized && dt < 0.05f && dt > 0.005f) { + if (!const_initialized && dt < 0.05f && dt > 0.001f) { dt = 0.005f; parameters_update(&ekf_param_handles, &ekf_params); @@ -424,7 +423,8 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds continue; } - if (last_data > 0 && raw.timestamp - last_data > 12000) printf("[attitude estimator ekf] sensor data missed! (%llu)\n", raw.timestamp - last_data); + if (last_data > 0 && raw.timestamp - last_data > 12000) + printf("[attitude estimator ekf] sensor data missed! (%llu)\n", raw.timestamp - last_data); last_data = raw.timestamp; From 36cca7a31b428408eb686df592f092ba5fc24006 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 4 Aug 2013 19:10:56 +0200 Subject: [PATCH 24/80] Added rate limit in sensors app. Just pending accel filters now --- src/modules/sensors/sensors.cpp | 66 +++++++++++++++++++++++++++++++-- 1 file changed, 63 insertions(+), 3 deletions(-) diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 7ff9e19b4c..0f1782fca6 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -92,8 +92,35 @@ #define BARO_HEALTH_COUNTER_LIMIT_OK 5 #define ADC_HEALTH_COUNTER_LIMIT_OK 5 -#define ADC_BATTERY_VOLTAGE_CHANNEL 10 -#define ADC_AIRSPEED_VOLTAGE_CHANNEL 11 +/** + * Analog layout: + * FMU: + * IN2 - battery voltage + * IN3 - battery current + * IN4 - 5V sense + * IN10 - spare (we could actually trim these from the set) + * IN11 - spare (we could actually trim these from the set) + * IN12 - spare (we could actually trim these from the set) + * IN13 - aux1 + * IN14 - aux2 + * IN15 - pressure sensor + * + * IO: + * IN4 - servo supply rail + * IN5 - analog RSSI + */ + +#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 + #define ADC_BATTERY_VOLTAGE_CHANNEL 10 + #define ADC_AIRSPEED_VOLTAGE_CHANNEL 11 +#endif + +#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2 + #define ADC_BATTERY_VOLTAGE_CHANNEL 2 + #define ADC_BATTERY_CURRENT_CHANNEL 3 + #define ADC_5V_RAIL_SENSE 4 + #define ADC_AIRSPEED_VOLTAGE_CHANNEL 15 +#endif #define BAT_VOL_INITIAL 0.f #define BAT_VOL_LOWPASS_1 0.99f @@ -731,12 +758,27 @@ Sensors::accel_init() errx(1, "FATAL: no accelerometer found"); } else { + + // XXX do the check more elegantly + + #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 + /* set the accel internal sampling rate up to at leat 500Hz */ ioctl(fd, ACCELIOCSSAMPLERATE, 500); /* set the driver to poll at 500Hz */ ioctl(fd, SENSORIOCSPOLLRATE, 500); + #else + + /* set the accel internal sampling rate up to at leat 800Hz */ + ioctl(fd, ACCELIOCSSAMPLERATE, 800); + + /* set the driver to poll at 800Hz */ + ioctl(fd, SENSORIOCSPOLLRATE, 800); + + #endif + warnx("using system accel"); close(fd); } @@ -754,12 +796,27 @@ Sensors::gyro_init() errx(1, "FATAL: no gyro found"); } else { + + // XXX do the check more elegantly + + #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 + /* set the gyro internal sampling rate up to at leat 500Hz */ ioctl(fd, GYROIOCSSAMPLERATE, 500); /* set the driver to poll at 500Hz */ ioctl(fd, SENSORIOCSPOLLRATE, 500); + #else + + /* set the gyro internal sampling rate up to at leat 800Hz */ + ioctl(fd, GYROIOCSSAMPLERATE, 800); + + /* set the driver to poll at 800Hz */ + ioctl(fd, SENSORIOCSPOLLRATE, 800); + + #endif + warnx("using system gyro"); close(fd); } @@ -1360,6 +1417,9 @@ Sensors::task_main() /* rate limit vehicle status updates to 5Hz */ orb_set_interval(_vstatus_sub, 200); + /* rate limit gyro to 250 Hz (the gyro signal is lowpassed accordingly earlier) */ + orb_set_interval(_gyro_sub, 4); + /* * do advertisements */ @@ -1395,7 +1455,7 @@ Sensors::task_main() while (!_task_should_exit) { - /* wait for up to 500ms for data */ + /* wait for up to 100ms for data */ int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100); /* timed out - periodic check for _task_should_exit, etc. */ From ac89322d74ac1f5a29a6665feb4220aba3025f82 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 4 Aug 2013 15:09:16 +1000 Subject: [PATCH 25/80] mathlib: added LowPassFilter2p object used in gyro and accel drivers for better filtering --- .../mathlib/math/filter/LowPassFilter2p.cpp | 77 ++++++++++++++++++ .../mathlib/math/filter/LowPassFilter2p.hpp | 78 +++++++++++++++++++ src/modules/mathlib/math/filter/module.mk | 44 +++++++++++ 3 files changed, 199 insertions(+) create mode 100644 src/modules/mathlib/math/filter/LowPassFilter2p.cpp create mode 100644 src/modules/mathlib/math/filter/LowPassFilter2p.hpp create mode 100644 src/modules/mathlib/math/filter/module.mk diff --git a/src/modules/mathlib/math/filter/LowPassFilter2p.cpp b/src/modules/mathlib/math/filter/LowPassFilter2p.cpp new file mode 100644 index 0000000000..efb17225d2 --- /dev/null +++ b/src/modules/mathlib/math/filter/LowPassFilter2p.cpp @@ -0,0 +1,77 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- + +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/// @file LowPassFilter.cpp +/// @brief A class to implement a second order low pass filter +/// Author: Leonard Hall + +#include "LowPassFilter2p.hpp" +#include "math.h" + +namespace math +{ + +void LowPassFilter2p::set_cutoff_frequency(float sample_freq, float cutoff_freq) +{ + _cutoff_freq = cutoff_freq; + float fr = sample_freq/_cutoff_freq; + float ohm = tanf(M_PI_F/fr); + float c = 1.0f+2.0f*cosf(M_PI_F/4.0f)*ohm + ohm*ohm; + _b0 = ohm*ohm/c; + _b1 = 2.0f*_b0; + _b2 = _b0; + _a1 = 2.0f*(ohm*ohm-1.0f)/c; + _a2 = (1.0f-2.0f*cosf(M_PI_F/4.0f)*ohm+ohm*ohm)/c; +} + +float LowPassFilter2p::apply(float sample) +{ + // do the filtering + float delay_element_0 = sample - _delay_element_1 * _a1 - _delay_element_2 * _a2; + if (isnan(delay_element_0) || isinf(delay_element_0)) { + // don't allow bad values to propogate via the filter + delay_element_0 = sample; + } + float output = delay_element_0 * _b0 + _delay_element_1 * _b1 + _delay_element_2 * _b2; + + _delay_element_2 = _delay_element_1; + _delay_element_1 = delay_element_0; + + // return the value. Should be no need to check limits + return output; +} + +} // namespace math + diff --git a/src/modules/mathlib/math/filter/LowPassFilter2p.hpp b/src/modules/mathlib/math/filter/LowPassFilter2p.hpp new file mode 100644 index 0000000000..208ec98d4e --- /dev/null +++ b/src/modules/mathlib/math/filter/LowPassFilter2p.hpp @@ -0,0 +1,78 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- + +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/// @file LowPassFilter.h +/// @brief A class to implement a second order low pass filter +/// Author: Leonard Hall +/// Adapted for PX4 by Andrew Tridgell + +#pragma once + +namespace math +{ +class __EXPORT LowPassFilter2p +{ +public: + // constructor + LowPassFilter2p(float sample_freq, float cutoff_freq) { + // set initial parameters + set_cutoff_frequency(sample_freq, cutoff_freq); + _delay_element_1 = _delay_element_2 = 0; + } + + // change parameters + void set_cutoff_frequency(float sample_freq, float cutoff_freq); + + // apply - Add a new raw value to the filter + // and retrieve the filtered result + float apply(float sample); + + // return the cutoff frequency + float get_cutoff_freq(void) const { + return _cutoff_freq; + } + +private: + float _cutoff_freq; + float _a1; + float _a2; + float _b0; + float _b1; + float _b2; + float _delay_element_1; // buffered sample -1 + float _delay_element_2; // buffered sample -2 +}; + +} // namespace math diff --git a/src/modules/mathlib/math/filter/module.mk b/src/modules/mathlib/math/filter/module.mk new file mode 100644 index 0000000000..fe92c8c70f --- /dev/null +++ b/src/modules/mathlib/math/filter/module.mk @@ -0,0 +1,44 @@ +############################################################################ +# +# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +# +# filter library +# +SRCS = LowPassFilter2p.cpp + +# +# In order to include .config we first have to save off the +# current makefile name, since app.mk needs it. +# +APP_MAKEFILE := $(lastword $(MAKEFILE_LIST)) +-include $(TOPDIR)/.config From 7c3ee6714c0e184c297ffced880488a41e7d255d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 4 Aug 2013 19:14:25 +0200 Subject: [PATCH 26/80] Enabled mathlib --- makefiles/config_px4fmu-v1_default.mk | 1 + 1 file changed, 1 insertion(+) diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk index e6ec840f9a..38cf437e03 100644 --- a/makefiles/config_px4fmu-v1_default.mk +++ b/makefiles/config_px4fmu-v1_default.mk @@ -94,6 +94,7 @@ MODULES += modules/sdlog2 MODULES += modules/systemlib MODULES += modules/systemlib/mixer MODULES += modules/mathlib +MODULES += modules/mathlib/math/filter MODULES += modules/controllib MODULES += modules/uORB From 97e4909d9e7c835b73c2eebdf4991d395c4ffb3f Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 4 Aug 2013 19:40:57 -0700 Subject: [PATCH 27/80] Improvements to the HX stream protocol implementation. --- src/modules/systemlib/hx_stream.c | 191 ++++++++++++++++++++---------- src/modules/systemlib/hx_stream.h | 42 ++++++- 2 files changed, 167 insertions(+), 66 deletions(-) diff --git a/src/modules/systemlib/hx_stream.c b/src/modules/systemlib/hx_stream.c index 8d77f14a8d..8e9c2bfcf6 100644 --- a/src/modules/systemlib/hx_stream.c +++ b/src/modules/systemlib/hx_stream.c @@ -53,14 +53,26 @@ struct hx_stream { - uint8_t buf[HX_STREAM_MAX_FRAME + 4]; - unsigned frame_bytes; - bool escaped; - bool txerror; + /* RX state */ + uint8_t rx_buf[HX_STREAM_MAX_FRAME + 4]; + unsigned rx_frame_bytes; + bool rx_escaped; + hx_stream_rx_callback rx_callback; + void *rx_callback_arg; + /* TX state */ int fd; - hx_stream_rx_callback callback; - void *callback_arg; + bool tx_error; + uint8_t *tx_buf; + unsigned tx_resid; + uint32_t tx_crc; + enum { + TX_IDLE = 0, + TX_SEND_START, + TX_SEND_DATA, + TX_SENT_ESCAPE, + TX_SEND_END + } tx_state; perf_counter_t pc_tx_frames; perf_counter_t pc_rx_frames; @@ -81,21 +93,7 @@ static void hx_tx_raw(hx_stream_t stream, uint8_t c) { if (write(stream->fd, &c, 1) != 1) - stream->txerror = true; -} - -static void -hx_tx_byte(hx_stream_t stream, uint8_t c) -{ - switch (c) { - case FBO: - case CEO: - hx_tx_raw(stream, CEO); - c ^= 0x20; - break; - } - - hx_tx_raw(stream, c); + stream->tx_error = true; } static int @@ -105,11 +103,11 @@ hx_rx_frame(hx_stream_t stream) uint8_t b[4]; uint32_t w; } u; - unsigned length = stream->frame_bytes; + unsigned length = stream->rx_frame_bytes; /* reset the stream */ - stream->frame_bytes = 0; - stream->escaped = false; + stream->rx_frame_bytes = 0; + stream->rx_escaped = false; /* not a real frame - too short */ if (length < 4) { @@ -122,11 +120,11 @@ hx_rx_frame(hx_stream_t stream) length -= 4; /* compute expected CRC */ - u.w = crc32(&stream->buf[0], length); + u.w = crc32(&stream->rx_buf[0], length); /* compare computed and actual CRC */ for (unsigned i = 0; i < 4; i++) { - if (u.b[i] != stream->buf[length + i]) { + if (u.b[i] != stream->rx_buf[length + i]) { perf_count(stream->pc_rx_errors); return 0; } @@ -134,7 +132,7 @@ hx_rx_frame(hx_stream_t stream) /* frame is good */ perf_count(stream->pc_rx_frames); - stream->callback(stream->callback_arg, &stream->buf[0], length); + stream->rx_callback(stream->rx_callback_arg, &stream->rx_buf[0], length); return 1; } @@ -150,8 +148,8 @@ hx_stream_init(int fd, if (stream != NULL) { memset(stream, 0, sizeof(struct hx_stream)); stream->fd = fd; - stream->callback = callback; - stream->callback_arg = arg; + stream->rx_callback = callback; + stream->rx_callback_arg = arg; } return stream; @@ -179,49 +177,112 @@ hx_stream_set_counters(hx_stream_t stream, stream->pc_rx_errors = rx_errors; } +void +hx_stream_reset(hx_stream_t stream) +{ + stream->rx_frame_bytes = 0; + stream->rx_escaped = false; + + stream->tx_buf = NULL; + stream->tx_resid = 0; + stream->tx_state = TX_IDLE; +} + +int +hx_stream_start(hx_stream_t stream, + const void *data, + size_t count) +{ + if (count > HX_STREAM_MAX_FRAME) + return -EINVAL; + + stream->tx_buf = data; + stream->tx_resid = count; + stream->tx_state = TX_SEND_START; + stream->tx_crc = crc32(data, count); + return OK; +} + +int +hx_stream_send_next(hx_stream_t stream) +{ + int c; + + /* sort out what we're going to send */ + switch (stream->tx_state) { + + case TX_SEND_START: + stream->tx_state = TX_SEND_DATA; + return FBO; + + case TX_SEND_DATA: + c = *stream->tx_buf; + + switch (c) { + case FBO: + case CEO: + stream->tx_state = TX_SENT_ESCAPE; + return CEO; + } + break; + + case TX_SENT_ESCAPE: + c = *stream->tx_buf ^ 0x20; + stream->tx_state = TX_SEND_DATA; + break; + + case TX_SEND_END: + stream->tx_state = TX_IDLE; + return FBO; + + case TX_IDLE: + default: + return -1; + } + + /* if we are here, we have consumed a byte from the buffer */ + stream->tx_resid--; + stream->tx_buf++; + + /* buffer exhausted */ + if (stream->tx_resid == 0) { + uint8_t *pcrc = (uint8_t *)&stream->tx_crc; + + /* was the buffer the frame CRC? */ + if (stream->tx_buf == (pcrc + sizeof(stream->tx_crc))) { + stream->tx_state = TX_SEND_END; + } else { + /* no, it was the payload - switch to sending the CRC */ + stream->tx_buf = pcrc; + stream->tx_resid = sizeof(stream->tx_crc); + } + } + return c; +} + int hx_stream_send(hx_stream_t stream, const void *data, size_t count) { - union { - uint8_t b[4]; - uint32_t w; - } u; - const uint8_t *p = (const uint8_t *)data; - unsigned resid = count; + int result; - if (resid > HX_STREAM_MAX_FRAME) - return -EINVAL; + result = hx_stream_start(stream, data, count); + if (result != OK) + return result; - /* start the frame */ - hx_tx_raw(stream, FBO); - - /* transmit the data */ - while (resid--) - hx_tx_byte(stream, *p++); - - /* compute the CRC */ - u.w = crc32(data, count); - - /* send the CRC */ - p = &u.b[0]; - resid = 4; - - while (resid--) - hx_tx_byte(stream, *p++); - - /* and the trailing frame separator */ - hx_tx_raw(stream, FBO); + int c; + while ((c = hx_stream_send_next(stream)) >= 0) + hx_tx_raw(stream, c); /* check for transmit error */ - if (stream->txerror) { - stream->txerror = false; + if (stream->tx_error) { + stream->tx_error = false; return -EIO; } perf_count(stream->pc_tx_frames); - return 0; + return OK; } void @@ -234,17 +295,17 @@ hx_stream_rx(hx_stream_t stream, uint8_t c) } /* escaped? */ - if (stream->escaped) { - stream->escaped = false; + if (stream->rx_escaped) { + stream->rx_escaped = false; c ^= 0x20; } else if (c == CEO) { - /* now escaped, ignore the byte */ - stream->escaped = true; + /* now rx_escaped, ignore the byte */ + stream->rx_escaped = true; return; } /* save for later */ - if (stream->frame_bytes < sizeof(stream->buf)) - stream->buf[stream->frame_bytes++] = c; + if (stream->rx_frame_bytes < sizeof(stream->rx_buf)) + stream->rx_buf[stream->rx_frame_bytes++] = c; } diff --git a/src/modules/systemlib/hx_stream.h b/src/modules/systemlib/hx_stream.h index 128689953a..1f3927222a 100644 --- a/src/modules/systemlib/hx_stream.h +++ b/src/modules/systemlib/hx_stream.h @@ -58,7 +58,8 @@ __BEGIN_DECLS * Allocate a new hx_stream object. * * @param fd The file handle over which the protocol will - * communicate. + * communicate, or -1 if the protocol will use + * hx_stream_start/hx_stream_send_next. * @param callback Called when a frame is received. * @param callback_arg Passed to the callback. * @return A handle to the stream, or NULL if memory could @@ -80,6 +81,7 @@ __EXPORT extern void hx_stream_free(hx_stream_t stream); * * Any counter may be set to NULL to disable counting that datum. * + * @param stream A handle returned from hx_stream_init. * @param tx_frames Counter for transmitted frames. * @param rx_frames Counter for received frames. * @param rx_errors Counter for short and corrupt received frames. @@ -89,6 +91,44 @@ __EXPORT extern void hx_stream_set_counters(hx_stream_t stream, perf_counter_t rx_frames, perf_counter_t rx_errors); +/** + * Reset a stream. + * + * Forces the local stream state to idle. + * + * @param stream A handle returned from hx_stream_init. + */ +__EXPORT extern void hx_stream_reset(hx_stream_t stream); + +/** + * Prepare to send a frame. + * + * Use this in conjunction with hx_stream_send_next to + * set the frame to be transmitted. + * + * Use hx_stream_send() to write to the stream fd directly. + * + * @param stream A handle returned from hx_stream_init. + * @param data Pointer to the data to send. + * @param count The number of bytes to send. + * @return Zero on success, -errno on error. + */ +__EXPORT extern int hx_stream_start(hx_stream_t stream, + const void *data, + size_t count); + +/** + * Get the next byte to send for a stream. + * + * This requires that the stream be prepared for sending by + * calling hx_stream_start first. + * + * @param stream A handle returned from hx_stream_init. + * @return The byte to send, or -1 if there is + * nothing left to send. + */ +__EXPORT extern int hx_stream_send_next(hx_stream_t stream); + /** * Send a frame. * From c33048b52186b88ddab2a9c9fdad24c7b64e7e22 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 4 Aug 2013 19:42:16 -0700 Subject: [PATCH 28/80] Add the ability to cancel a begin/end perf counter if the begin turns out to have been in error. --- src/modules/systemlib/perf_counter.c | 41 +++++++++++++++++++++++----- src/modules/systemlib/perf_counter.h | 14 +++++++++- 2 files changed, 47 insertions(+), 8 deletions(-) diff --git a/src/modules/systemlib/perf_counter.c b/src/modules/systemlib/perf_counter.c index 879f4715af..3c1e10287d 100644 --- a/src/modules/systemlib/perf_counter.c +++ b/src/modules/systemlib/perf_counter.c @@ -201,23 +201,50 @@ perf_end(perf_counter_t handle) switch (handle->type) { case PC_ELAPSED: { struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle; - hrt_abstime elapsed = hrt_absolute_time() - pce->time_start; - pce->event_count++; - pce->time_total += elapsed; + if (pce->time_start != 0) { + hrt_abstime elapsed = hrt_absolute_time() - pce->time_start; - if ((pce->time_least > elapsed) || (pce->time_least == 0)) - pce->time_least = elapsed; + pce->event_count++; + pce->time_total += elapsed; - if (pce->time_most < elapsed) - pce->time_most = elapsed; + if ((pce->time_least > elapsed) || (pce->time_least == 0)) + pce->time_least = elapsed; + + if (pce->time_most < elapsed) + pce->time_most = elapsed; + + pce->time_start = 0; + } } + break; default: break; } } +void +perf_cancel(perf_counter_t handle) +{ + if (handle == NULL) + return; + + switch (handle->type) { + case PC_ELAPSED: { + struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle; + + pce->time_start = 0; + } + break; + + default: + break; + } +} + + + void perf_reset(perf_counter_t handle) { diff --git a/src/modules/systemlib/perf_counter.h b/src/modules/systemlib/perf_counter.h index 5c2cb15b2f..4cd8b67a17 100644 --- a/src/modules/systemlib/perf_counter.h +++ b/src/modules/systemlib/perf_counter.h @@ -92,13 +92,25 @@ __EXPORT extern void perf_begin(perf_counter_t handle); * End a performance event. * * This call applies to counters that operate over ranges of time; PC_ELAPSED etc. + * If a call is made without a corresopnding perf_begin call, or if perf_cancel + * has been called subsequently, no change is made to the counter. * * @param handle The handle returned from perf_alloc. */ __EXPORT extern void perf_end(perf_counter_t handle); /** - * Reset a performance event. + * Cancel a performance event. + * + * This call applies to counters that operate over ranges of time; PC_ELAPSED etc. + * It reverts the effect of a previous perf_begin. + * + * @param handle The handle returned from perf_alloc. + */ +__EXPORT extern void perf_cancel(perf_counter_t handle); + +/** + * Reset a performance counter. * * This call resets performance counter to initial state * From 567f621754f1f68ed0aae560e9590805045fa3e0 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 4 Aug 2013 19:43:05 -0700 Subject: [PATCH 29/80] Fix an issue with the pwm_servo driver when using one of the STM32 advanced timers. --- src/drivers/stm32/drv_pwm_servo.c | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/drivers/stm32/drv_pwm_servo.c b/src/drivers/stm32/drv_pwm_servo.c index 7b060412cd..dbb45a1380 100644 --- a/src/drivers/stm32/drv_pwm_servo.c +++ b/src/drivers/stm32/drv_pwm_servo.c @@ -88,6 +88,7 @@ #define rCCR4(_tmr) REG(_tmr, STM32_GTIM_CCR4_OFFSET) #define rDCR(_tmr) REG(_tmr, STM32_GTIM_DCR_OFFSET) #define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET) +#define rBDTR(_tmr) REG(_tmr, STM32_ATIM_BDTR_OFFSET) static void pwm_timer_init(unsigned timer); static void pwm_timer_set_rate(unsigned timer, unsigned rate); @@ -110,6 +111,11 @@ pwm_timer_init(unsigned timer) rCCER(timer) = 0; rDCR(timer) = 0; + if ((pwm_timers[timer].base == STM32_TIM1_BASE) || (pwm_timers[timer].base == STM32_TIM8_BASE)) { + /* master output enable = on */ + rBDTR(timer) = ATIM_BDTR_MOE; + } + /* configure the timer to free-run at 1MHz */ rPSC(timer) = (pwm_timers[timer].clock_freq / 1000000) - 1; From 4b4f33e6a4fb18047a6ca73d3a4872a900519b5c Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 4 Aug 2013 19:48:20 -0700 Subject: [PATCH 30/80] Add direct-access methods to the base Device class, so that there's a common way of talking to drivers regardless of which of the specialised classes they derive from. Make the Device destructor public and virtual, so that arbitrary devices can be deleted. Likewise for classes that derive from it. Make Device::init public so that arbitrary devices can be initialised after being returned by factories. --- src/drivers/device/device.cpp | 19 +++++++++- src/drivers/device/device.h | 70 ++++++++++++++++++++++++++++------- src/drivers/device/i2c.h | 14 +++---- src/drivers/device/spi.h | 2 +- 4 files changed, 82 insertions(+), 23 deletions(-) diff --git a/src/drivers/device/device.cpp b/src/drivers/device/device.cpp index 04a5222c36..c3ee77b1ca 100644 --- a/src/drivers/device/device.cpp +++ b/src/drivers/device/device.cpp @@ -223,5 +223,22 @@ interrupt(int irq, void *context) return OK; } +int +Device::read(unsigned offset, void *data, unsigned count) +{ + return -ENODEV; +} -} // namespace device \ No newline at end of file +int +Device::write(unsigned offset, void *data, unsigned count) +{ + return -ENODEV; +} + +int +Device::ioctl(unsigned operation, unsigned &arg) +{ + return -ENODEV; +} + +} // namespace device diff --git a/src/drivers/device/device.h b/src/drivers/device/device.h index 7d375aab91..a9ed5d77c2 100644 --- a/src/drivers/device/device.h +++ b/src/drivers/device/device.h @@ -68,11 +68,62 @@ namespace device __EXPORT class __EXPORT Device { public: + /** + * Destructor. + * + * Public so that anonymous devices can be destroyed. + */ + virtual ~Device(); + /** * Interrupt handler. */ virtual void interrupt(void *ctx); /**< interrupt handler */ + /* + * Direct access methods. + */ + + /** + * Initialise the driver and make it ready for use. + * + * @return OK if the driver initialized OK, negative errno otherwise; + */ + virtual int init(); + + /** + * Read directly from the device. + * + * The actual size of each unit quantity is device-specific. + * + * @param offset The device address at which to start reading + * @param data The buffer into which the read values should be placed. + * @param count The number of items to read. + * @return The number of items read on success, negative errno otherwise. + */ + virtual int read(unsigned address, void *data, unsigned count); + + /** + * Write directly to the device. + * + * The actual size of each unit quantity is device-specific. + * + * @param address The device address at which to start writing. + * @param data The buffer from which values should be read. + * @param count The number of items to write. + * @return The number of items written on success, negative errno otherwise. + */ + virtual int write(unsigned address, void *data, unsigned count); + + /** + * Perform a device-specific operation. + * + * @param operation The operation to perform. + * @param arg An argument to the operation. + * @return Negative errno on error, OK or positive value on success. + */ + virtual int ioctl(unsigned operation, unsigned &arg); + protected: const char *_name; /**< driver name */ bool _debug_enabled; /**< if true, debug messages are printed */ @@ -85,14 +136,6 @@ protected: */ Device(const char *name, int irq = 0); - ~Device(); - - /** - * Initialise the driver and make it ready for use. - * - * @return OK if the driver initialised OK. - */ - virtual int init(); /** * Enable the device interrupt @@ -189,7 +232,7 @@ public: /** * Destructor */ - ~CDev(); + virtual ~CDev(); virtual int init(); @@ -282,6 +325,7 @@ public: * Test whether the device is currently open. * * This can be used to avoid tearing down a device that is still active. + * Note - not virtual, cannot be overridden by a subclass. * * @return True if the device is currently open. */ @@ -396,9 +440,9 @@ public: const char *devname, uint32_t base, int irq = 0); - ~PIO(); + virtual ~PIO(); - int init(); + virtual int init(); protected: @@ -407,7 +451,7 @@ protected: * * @param offset Register offset in bytes from the base address. */ - uint32_t reg(uint32_t offset) { + uint32_t reg(uint32_t offset) { return *(volatile uint32_t *)(_base + offset); } @@ -444,4 +488,4 @@ private: } // namespace device -#endif /* _DEVICE_DEVICE_H */ \ No newline at end of file +#endif /* _DEVICE_DEVICE_H */ diff --git a/src/drivers/device/i2c.h b/src/drivers/device/i2c.h index b4a9cdd536..5498793523 100644 --- a/src/drivers/device/i2c.h +++ b/src/drivers/device/i2c.h @@ -55,13 +55,11 @@ class __EXPORT I2C : public CDev public: - /** - * Get the address - */ - uint16_t get_address() { - return _address; - } - + /** + * Get the address + */ + int16_t get_address() { return _address; } + protected: /** * The number of times a read or write operation will be retried on @@ -90,7 +88,7 @@ protected: uint16_t address, uint32_t frequency, int irq = 0); - ~I2C(); + virtual ~I2C(); virtual int init(); diff --git a/src/drivers/device/spi.h b/src/drivers/device/spi.h index d2d01efb35..e0122372a0 100644 --- a/src/drivers/device/spi.h +++ b/src/drivers/device/spi.h @@ -71,7 +71,7 @@ protected: enum spi_mode_e mode, uint32_t frequency, int irq = 0); - ~SPI(); + virtual ~SPI(); virtual int init(); From 1fb4705ab7038fb4b135b49c58f14b48f0cfab48 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 4 Aug 2013 19:48:46 -0700 Subject: [PATCH 31/80] Add size and flush methods to the ringbuffer class. --- src/drivers/device/ringbuffer.h | 21 ++++++++++++++++----- 1 file changed, 16 insertions(+), 5 deletions(-) diff --git a/src/drivers/device/ringbuffer.h b/src/drivers/device/ringbuffer.h index 37686fdbe3..dc0c84052b 100644 --- a/src/drivers/device/ringbuffer.h +++ b/src/drivers/device/ringbuffer.h @@ -104,6 +104,17 @@ public: */ bool full() { return _next(_head) == _tail; } + /* + * Returns the capacity of the buffer, or zero if the buffer could + * not be allocated. + */ + unsigned size() { return (_buf != nullptr) ? _size : 0; } + + /* + * Empties the buffer. + */ + void flush() { _head = _tail = _size; } + private: T *const _buf; const unsigned _size; @@ -114,11 +125,11 @@ private: }; template -RingBuffer::RingBuffer(unsigned size) : - _buf(new T[size + 1]), - _size(size), - _head(size), - _tail(size) +RingBuffer::RingBuffer(unsigned with_size) : + _buf(new T[with_size + 1]), + _size(with_size), + _head(with_size), + _tail(with_size) {} template From 1acbbe46d178c7eb2d11a9ba3349d274a3dd1581 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 4 Aug 2013 19:49:19 -0700 Subject: [PATCH 32/80] Make it possible to create a cdev without automatically creating a device node. --- src/drivers/device/cdev.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/src/drivers/device/cdev.cpp b/src/drivers/device/cdev.cpp index 422321850a..47ebcd40a7 100644 --- a/src/drivers/device/cdev.cpp +++ b/src/drivers/device/cdev.cpp @@ -111,21 +111,21 @@ CDev::~CDev() int CDev::init() { - int ret = OK; - // base class init first - ret = Device::init(); + int ret = Device::init(); if (ret != OK) goto out; // now register the driver - ret = register_driver(_devname, &fops, 0666, (void *)this); + if (_devname != nullptr) { + ret = register_driver(_devname, &fops, 0666, (void *)this); - if (ret != OK) - goto out; + if (ret != OK) + goto out; - _registered = true; + _registered = true; + } out: return ret; @@ -395,4 +395,4 @@ cdev_poll(struct file *filp, struct pollfd *fds, bool setup) return cdev->poll(filp, fds, setup); } -} // namespace device \ No newline at end of file +} // namespace device From f8951759f8265fb57f25238d0bf6ee9dd81d6a49 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 4 Aug 2013 19:50:23 -0700 Subject: [PATCH 33/80] Add a top-level Makefile rule for building "everything" as a test. --- Makefile | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/Makefile b/Makefile index a2dcd97b8b..c02a986cdd 100644 --- a/Makefile +++ b/Makefile @@ -161,6 +161,12 @@ $(NUTTX_SRC): @$(ECHO) "NuttX sources missing - clone https://github.com/PX4/NuttX.git and try again." @$(ECHO) "" +# +# Testing targets +# +testbuild: + $(Q) (cd $(PX4_BASE) && make distclean && make archives && make -j8) + # # Cleanup targets. 'clean' should remove all built products and force # a complete re-compilation, 'distclean' should remove everything @@ -211,6 +217,9 @@ help: @$(ECHO) " firmware to the board when the build is complete. Not supported for" @$(ECHO) " all configurations." @$(ECHO) "" + @$(ECHO) " testbuild" + @$(ECHO) " Perform a complete clean build of the entire tree." + @$(ECHO) "" @$(ECHO) " Common options:" @$(ECHO) " ---------------" @$(ECHO) "" From 5ddbe24d8e5383a19f51957463211a4d8922d366 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 5 Aug 2013 12:26:31 +0200 Subject: [PATCH 34/80] Fixed code style for meas_airspeed.cpp --- src/drivers/meas_airspeed/meas_airspeed.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 7a2e22c018..15cae7d704 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -122,7 +122,7 @@ protected: extern "C" __EXPORT int meas_airspeed_main(int argc, char *argv[]); MEASAirspeed::MEASAirspeed(int bus, int address) : Airspeed(bus, address, - CONVERSION_INTERVAL) + CONVERSION_INTERVAL) { } @@ -171,6 +171,7 @@ MEASAirspeed::collect() if (status == 2) { log("err: stale data"); + } else if (status == 3) { log("err: fault"); } From 901a9c3e35456445465e7008d3c69b0bd3481e9e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 5 Aug 2013 12:44:20 +0200 Subject: [PATCH 35/80] Hotfix: MEAS Airspeed sensor fixes from Sarthak Kaingade --- src/drivers/meas_airspeed/meas_airspeed.cpp | 31 +++++++++++++-------- 1 file changed, 20 insertions(+), 11 deletions(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 15cae7d704..ebae21cf72 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -34,6 +34,7 @@ /** * @file meas_airspeed.cpp * @author Lorenz Meier + * @author Sarthak Kaingade * @author Simon Wilks * * Driver for the MEAS Spec series connected via I2C. @@ -92,9 +93,6 @@ /* Register address */ #define ADDR_READ_MR 0x00 /* write to this address to start conversion */ -#define ADDR_READ_DF2 0x00 /* read from this address to read pressure only */ -#define ADDR_READ_DF3 0x01 -#define ADDR_READ_DF4 0x02 /* read from this address to read pressure and temp */ /* Measurement rate is 100Hz */ #define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */ @@ -160,7 +158,7 @@ MEASAirspeed::collect() perf_begin(_sample_perf); - ret = transfer(nullptr, 0, &val[0], 2); + ret = transfer(nullptr, 0, &val[0], 4); if (ret < 0) { log("error reading from sensor: %d", ret); @@ -176,21 +174,32 @@ MEASAirspeed::collect() log("err: fault"); } - uint16_t diff_pres_pa = (val[1]) | ((val[0] & ~(0xC0)) << 8); + //uint16_t diff_pres_pa = (val[1]) | ((val[0] & ~(0xC0)) << 8); uint16_t temp = (val[3] & 0xE0) << 8 | val[2]; - diff_pres_pa = abs(diff_pres_pa - (16384 / 2.0f)); - diff_pres_pa -= _diff_pres_offset; + // XXX leaving this in until new calculation method has been cross-checked + //diff_pres_pa = abs(diff_pres_pa - (16384 / 2.0f)); + //diff_pres_pa -= _diff_pres_offset; + int16_t dp_raw = 0, dT_raw = 0; + dp_raw = (val[0] << 8) + val[1]; + dp_raw = 0x3FFF & dp_raw; + dT_raw = (val[2] << 8) + val[3]; + dT_raw = (0xFFE0 & dT_raw) >> 5; + float temperature = ((200 * dT_raw) / 2047) - 50; // XXX we may want to smooth out the readings to remove noise. + // Calculate differential pressure. As its centered around 8000 + // and can go positive or negative, enforce absolute value + uint16_t diff_press_pa = abs(dp_raw - (16384 / 2.0f)); + _reports[_next_report].timestamp = hrt_absolute_time(); - _reports[_next_report].temperature = temp; - _reports[_next_report].differential_pressure_pa = diff_pres_pa; + _reports[_next_report].temperature = temperature; + _reports[_next_report].differential_pressure_pa = diff_press_pa; // Track maximum differential pressure measured (so we can work out top speed). - if (diff_pres_pa > _reports[_next_report].max_differential_pressure_pa) { - _reports[_next_report].max_differential_pressure_pa = diff_pres_pa; + if (diff_press_pa > _reports[_next_report].max_differential_pressure_pa) { + _reports[_next_report].max_differential_pressure_pa = diff_press_pa; } /* announce the airspeed if needed, just publish else */ From b5d19d08ea02bd31e27f4259302b30946e1f673d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 5 Aug 2013 21:05:08 +0200 Subject: [PATCH 36/80] Equipped MPU6k driver with Butterworth for accel and gyro --- src/drivers/mpu6000/mpu6000.cpp | 74 +++++++++++++++++++++++++++------ 1 file changed, 62 insertions(+), 12 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index 9dcb4be9ed..be0a040284 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -70,6 +70,7 @@ #include #include #include +#include #define DIR_READ 0x80 #define DIR_WRITE 0x00 @@ -202,6 +203,13 @@ private: unsigned _sample_rate; perf_counter_t _sample_perf; + math::LowPassFilter2p _accel_filter_x; + math::LowPassFilter2p _accel_filter_y; + math::LowPassFilter2p _accel_filter_z; + math::LowPassFilter2p _gyro_filter_x; + math::LowPassFilter2p _gyro_filter_y; + math::LowPassFilter2p _gyro_filter_z; + /** * Start automatic measurement. */ @@ -332,8 +340,14 @@ MPU6000::MPU6000(int bus, spi_dev_e device) : _gyro_range_rad_s(0.0f), _gyro_topic(-1), _reads(0), - _sample_rate(500), - _sample_perf(perf_alloc(PC_ELAPSED, "mpu6000_read")) + _sample_rate(1000), + _sample_perf(perf_alloc(PC_ELAPSED, "mpu6000_read")), + _accel_filter_x(1000, 30), + _accel_filter_y(1000, 30), + _accel_filter_z(1000, 30), + _gyro_filter_x(1000, 30), + _gyro_filter_y(1000, 30), + _gyro_filter_z(1000, 30) { // disable debug() calls _debug_enabled = false; @@ -714,6 +728,19 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg) if (ticks < 1000) return -EINVAL; + // adjust filters + float cutoff_freq_hz = _accel_filter_x.get_cutoff_freq(); + float sample_rate = 1.0e6f/ticks; + _accel_filter_x.set_cutoff_frequency(sample_rate, cutoff_freq_hz); + _accel_filter_y.set_cutoff_frequency(sample_rate, cutoff_freq_hz); + _accel_filter_z.set_cutoff_frequency(sample_rate, cutoff_freq_hz); + + + float cutoff_freq_hz_gyro = _gyro_filter_x.get_cutoff_freq(); + _gyro_filter_x.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro); + _gyro_filter_y.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro); + _gyro_filter_z.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro); + /* update interval for next measurement */ /* XXX this is a bit shady, but no other way to adjust... */ _call.period = _call_interval = ticks; @@ -767,9 +794,17 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg) _set_sample_rate(arg); return OK; - case ACCELIOCSLOWPASS: case ACCELIOCGLOWPASS: - _set_dlpf_filter((uint16_t)arg); + return _accel_filter_x.get_cutoff_freq(); + + case ACCELIOCSLOWPASS: + + // XXX decide on relationship of both filters + // i.e. disable the on-chip filter + //_set_dlpf_filter((uint16_t)arg); + _accel_filter_x.set_cutoff_frequency(1.0e6f / _call_interval, arg); + _accel_filter_y.set_cutoff_frequency(1.0e6f / _call_interval, arg); + _accel_filter_z.set_cutoff_frequency(1.0e6f / _call_interval, arg); return OK; case ACCELIOCSSCALE: @@ -853,9 +888,14 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg) _set_sample_rate(arg); return OK; - case GYROIOCSLOWPASS: case GYROIOCGLOWPASS: - _set_dlpf_filter((uint16_t)arg); + return _gyro_filter_x.get_cutoff_freq(); + case GYROIOCSLOWPASS: + _gyro_filter_x.set_cutoff_frequency(1.0e6f / _call_interval, arg); + _gyro_filter_y.set_cutoff_frequency(1.0e6f / _call_interval, arg); + _gyro_filter_z.set_cutoff_frequency(1.0e6f / _call_interval, arg); + // XXX check relation to the internal lowpass + //_set_dlpf_filter((uint16_t)arg); return OK; case GYROIOCSSCALE: @@ -1112,9 +1152,14 @@ MPU6000::measure() arb.y_raw = report.accel_y; arb.z_raw = report.accel_z; - arb.x = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale; - arb.y = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale; - arb.z = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale; + float x_in_new = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale; + float y_in_new = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale; + float z_in_new = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale; + + arb.x = _accel_filter_x.apply(x_in_new); + arb.y = _accel_filter_y.apply(y_in_new); + arb.z = _accel_filter_z.apply(z_in_new); + arb.scaling = _accel_range_scale; arb.range_m_s2 = _accel_range_m_s2; @@ -1125,9 +1170,14 @@ MPU6000::measure() grb.y_raw = report.gyro_y; grb.z_raw = report.gyro_z; - grb.x = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale; - grb.y = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale; - grb.z = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale; + float x_gyro_in_new = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale; + float y_gyro_in_new = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale; + float z_gyro_in_new = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale; + + grb.x = _gyro_filter_x.apply(x_gyro_in_new); + grb.y = _gyro_filter_y.apply(y_gyro_in_new); + grb.z = _gyro_filter_z.apply(z_gyro_in_new); + grb.scaling = _gyro_range_scale; grb.range_rad_s = _gyro_range_rad_s; From a2f923b9a3bf403e3a9fcee39d87c7aecc28559d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 5 Aug 2013 21:05:34 +0200 Subject: [PATCH 37/80] Increased MPU6K poll and sampling rate to 1 KHz --- src/modules/sensors/sensors.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 0f1782fca6..5dc23f5c13 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -763,11 +763,11 @@ Sensors::accel_init() #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 - /* set the accel internal sampling rate up to at leat 500Hz */ - ioctl(fd, ACCELIOCSSAMPLERATE, 500); + /* set the accel internal sampling rate up to at leat 1000Hz */ + ioctl(fd, ACCELIOCSSAMPLERATE, 1000); - /* set the driver to poll at 500Hz */ - ioctl(fd, SENSORIOCSPOLLRATE, 500); + /* set the driver to poll at 1000Hz */ + ioctl(fd, SENSORIOCSPOLLRATE, 1000); #else From cfd737aa734f9b0cd97f79148d6b959978b2cad0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 5 Aug 2013 21:08:19 +0200 Subject: [PATCH 38/80] Made sensors startup routine more flexible --- src/modules/sensors/sensors.cpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 5dc23f5c13..f7b41b1207 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -801,11 +801,13 @@ Sensors::gyro_init() #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 - /* set the gyro internal sampling rate up to at leat 500Hz */ - ioctl(fd, GYROIOCSSAMPLERATE, 500); + /* set the gyro internal sampling rate up to at least 1000Hz */ + if (ioctl(fd, GYROIOCSSAMPLERATE, 1000) != OK) + ioctl(fd, GYROIOCSSAMPLERATE, 800); - /* set the driver to poll at 500Hz */ - ioctl(fd, SENSORIOCSPOLLRATE, 500); + /* set the driver to poll at 1000Hz */ + if (ioctl(fd, SENSORIOCSPOLLRATE, 1000) != OK) + ioctl(fd, SENSORIOCSPOLLRATE, 800); #else From 9ca5cf3108b21ce1d3a15d49bda53beeb7b5d1e0 Mon Sep 17 00:00:00 2001 From: px4dev Date: Mon, 5 Aug 2013 21:05:53 -0700 Subject: [PATCH 39/80] Fix CAN2 pinout selection thanks to heads-up from Joe van Niekerk --- nuttx-configs/px4fmu-v1/include/board.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/nuttx-configs/px4fmu-v1/include/board.h b/nuttx-configs/px4fmu-v1/include/board.h index 0fa93a1965..5529d50972 100644 --- a/nuttx-configs/px4fmu-v1/include/board.h +++ b/nuttx-configs/px4fmu-v1/include/board.h @@ -252,8 +252,8 @@ * CAN2 is routed to the expansion connector. */ -#define GPIO_CAN2_RX GPIO_CAN2_RX_2 -#define GPIO_CAN2_TX GPIO_CAN2_TX_2 +#define GPIO_CAN2_RX GPIO_CAN2_RX_1 +#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* * I2C From 338e506a28e4233bc8a16493530f3b82a0dd67e9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 6 Aug 2013 16:33:01 +1000 Subject: [PATCH 40/80] mpu6000: set the default DLFP filter to 42Hz this allows for apps to ask for slightly higher filters with the software filter and not have it completely ruined by the on-chip DLPF --- src/drivers/mpu6000/mpu6000.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index be0a040284..c4e331a30e 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -477,7 +477,7 @@ void MPU6000::reset() // FS & DLPF FS=2000 deg/s, DLPF = 20Hz (low pass filter) // was 90 Hz, but this ruins quality and does not improve the // system response - _set_dlpf_filter(20); + _set_dlpf_filter(42); usleep(1000); // Gyro scale 2000 deg/s () write_reg(MPUREG_GYRO_CONFIG, BITS_FS_2000DPS); From 28fa96e2db8fcf91fa8bb5cb0095b08306985402 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 6 Aug 2013 09:53:52 +0200 Subject: [PATCH 41/80] Made sure airspeed tests reset the sensors to default state --- src/drivers/ets_airspeed/ets_airspeed.cpp | 4 ++++ src/drivers/meas_airspeed/meas_airspeed.cpp | 4 ++++ 2 files changed, 8 insertions(+) diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index de8028b0f5..cd72d9d23d 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -383,6 +383,10 @@ test() warnx("diff pressure: %d pa", report.differential_pressure_pa); } + /* reset the sensor polling to its default rate */ + if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT)) + errx(1, "failed to set default rate"); + errx(0, "PASS"); } diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index ebae21cf72..68d2c5d655 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -415,6 +415,10 @@ test() warnx("temperature: %d C (0x%02x)", (int)report.temperature, (unsigned) report.temperature); } + /* reset the sensor polling to its default rate */ + if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT)) + errx(1, "failed to set default rate"); + errx(0, "PASS"); } From 53d69f9e919445d13fe1c98a0164d238b7ff4af6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 7 Aug 2013 10:24:38 +0200 Subject: [PATCH 42/80] Added highlighting of current line to make editing and double-clicking warnings/errors faster --- Firmware.sublime-project | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Firmware.sublime-project b/Firmware.sublime-project index 72bacee9fd..7292307d5b 100644 --- a/Firmware.sublime-project +++ b/Firmware.sublime-project @@ -32,7 +32,8 @@ "settings": { "tab_size": 8, - "translate_tabs_to_spaces": false + "translate_tabs_to_spaces": false, + "highlight_line": true }, "build_systems": [ From 2c24888d6d34183ec01a148a84add27e72e1637c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 7 Aug 2013 10:25:12 +0200 Subject: [PATCH 43/80] Fixed rc mode switch PDF --- Documentation/mixing_architecture.graffle | 4398 +++++++++++++++++++++ Documentation/rc_mode_switch.odg | Bin 14631 -> 14872 bytes Documentation/rc_mode_switch.pdf | Bin 15841 -> 16097 bytes 3 files changed, 4398 insertions(+) create mode 100644 Documentation/mixing_architecture.graffle diff --git a/Documentation/mixing_architecture.graffle b/Documentation/mixing_architecture.graffle new file mode 100644 index 0000000000..da8027bf77 --- /dev/null +++ b/Documentation/mixing_architecture.graffle @@ -0,0 +1,4398 @@ + + + + + ActiveLayerIndex + 0 + ApplicationVersion + + com.omnigroup.OmniGraffle + 139.17.0.185490 + + AutoAdjust + + BackgroundGraphic + + Bounds + {{0, 0}, {1118, 783}} + Class + SolidGraphic + ID + 2 + Style + + shadow + + Draws + NO + + stroke + + Draws + NO + + + + BaseZoom + 0 + CanvasOrigin + {0, 0} + ColumnAlign + 1 + ColumnSpacing + 36 + CreationDate + 2013-06-04 09:23:13 +0000 + Creator + Lorenz Meier + DisplayScale + 1 0/72 in = 1.0000 in + GraphDocumentVersion + 8 + GraphicsList + + + Class + LineGraphic + Head + + ID + 508 + + ID + 635 + Points + + {106.17826841821868, 273.42634001636537} + {213.16101457128596, 357.82365814026997} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 613 + + + + Class + LineGraphic + Head + + ID + 507 + + ID + 634 + Points + + {131.96398352136816, 273.42634001634866} + {238.946729674436, 357.82365813972365} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 612 + + + + Class + Group + Graphics + + + Bounds + {{482, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 617 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{456.21429061889648, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 618 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{430.42857551574707, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 619 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{404.64286041259766, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 620 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{378.85714530944824, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 621 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{353.07143020629883, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 622 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{327.28571510314941, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 623 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{301.5, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 624 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{482, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 625 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{456.21429061889648, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 626 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{430.42857551574707, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 627 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{404.64286041259766, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 628 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{378.85714530944824, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 629 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{353.07143020629883, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 630 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{327.28571510314941, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 631 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{301.5, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 632 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{291.5, 235.24999816050627}, {208, 36}} + Class + ShapedGraphic + ID + 633 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 Actuator Control Group 1} + + + + ID + 616 + + + Class + LineGraphic + Head + + ID + 587 + + ID + 592 + Points + + {605.82627753848249, 74.5} + {716.81658859616107, 159.07205874840687} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + + + Class + LineGraphic + Head + + ID + 581 + + ID + 591 + Points + + {576.14671565757703, 75.907219770052052} + {565.99614475502062, 157.66483897835485} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + + + Class + LineGraphic + ID + 590 + Points + + {565.49194626385997, 201.66102838314328} + {565.21582473837202, 338.8005880984627} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 573 + + + + Class + LineGraphic + ID + 589 + Points + + {720.20623661457341, 201.6610283823652} + {719.9301058948314, 338.80058788427203} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 579 + + + + Bounds + {{743, 158.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 588 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{717.21429061889648, 158.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 587 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{691.42857551574707, 158.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 586 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{665.64286041259766, 158.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 585 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{639.85714530944824, 158.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 584 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{614.07143020629883, 158.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 583 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{588.28571510314941, 158.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 582 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{562.5, 158.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 581 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{743, 194.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 580 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{717.21429061889648, 194.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 579 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{691.42857551574707, 194.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 578 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{665.64286041259766, 194.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 577 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{639.85714530944824, 194.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 576 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{614.07143020629883, 194.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 575 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{588.28571510314941, 194.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 574 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{562.5, 194.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 573 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{552.5, 162.16102937420345}, {208, 36}} + Class + ShapedGraphic + ID + 572 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 RC Scaling & Mapping} + + + + Class + LineGraphic + Head + + ID + 509 + + ID + 569 + Points + + {80.392553315069293, 273.42634001641937} + {187.37529946813521, 357.82365814202342} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 614 + + + + Class + LineGraphic + Head + + ID + 506 + + ID + 596 + Points + + {378.46463924118007, 273.4271429546975} + {271.51750416091619, 357.82285520170717} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 629 + + + + Class + Group + Graphics + + + Bounds + {{254.5, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 599 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{228.71429061889648, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 600 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{202.92857551574707, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 601 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{177.14286041259766, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 602 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{151.35714530944824, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 603 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{125.57143020629883, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 604 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{99.785715103149414, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 605 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{74, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 606 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{254.5, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 607 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{228.71429061889648, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 608 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{202.92857551574707, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 609 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{177.14286041259766, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 610 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{151.35714530944824, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 611 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{125.57143020629883, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 612 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{99.785715103149414, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 613 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{74, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 614 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{64, 235.24999816050627}, {208, 36}} + Class + ShapedGraphic + ID + 615 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 Actuator Control Group 0} + + + + ID + 598 + + + Class + LineGraphic + Head + + ID + 474 + + ID + 411 + Points + + {322.59687445702775, 444.84226761008853} + {379.20669915150745, 526.90773238985753} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 510 + + + + Class + LineGraphic + Head + + ID + 477 + + ID + 412 + Points + + {294.62113860994009, 444.9967148570675} + {304.03957452010235, 526.7532851429479} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 511 + + + + Class + LineGraphic + Head + + ID + 490 + + ID + 413 + Points + + {290.76782961936522, 443.67073351699491} + {183.53574398902853, 528.07926647675936} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 511 + + + + Class + LineGraphic + Head + + ID + 491 + + ID + 414 + Points + + {264.9821145162158, 443.67073351699491} + {157.75002888587912, 528.07926647675936} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 512 + + + + Class + LineGraphic + Head + + ID + 492 + + ID + 415 + Points + + {239.19639941306636, 443.67073351699491} + {131.9643137827297, 528.07926647675936} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 513 + + + + Class + LineGraphic + Head + + ID + 493 + + ID + 416 + Points + + {213.41068430991695, 443.67073351699491} + {106.1785986795803, 528.07926647675936} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 514 + + + + Class + LineGraphic + Head + + ID + 440 + + ID + 417 + Points + + {304.49194626386003, 570.74999900893988} + {304.21582473837134, 707.88955872425925} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 485 + + + + Class + LineGraphic + Head + + ID + 429 + + ID + 418 + Points + + {381.84909342488743, 570.74999900816329} + {381.57303538097813, 707.88955851048831} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 482 + + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{379.35432048604451, 719.00347978513389}, {5.0056232242123722, 4.9183513058348947}} + Class + ShapedGraphic + ID + 421 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{396.74606011338682, 726.18083608931011}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 422 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{391.6252245834844, 724.37750550833903}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 423 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{386.29980802056684, 722.50213058402392}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 424 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{375.67643661590967, 718.76105153253593}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 425 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{370.35101205342835, 716.88567379113056}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 426 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{365.23018452308935, 715.08234602724974}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 427 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{345.93778549185652, 717.4003115566619}, {71.838699340820256, 8.1246847180976189}} + Class + ShapedGraphic + ID + 428 + Rotation + 19.399997711181641 + Shape + Diamond + Style + + stroke + + CornerRadius + 5 + + + Text + + VerticalPad + 0 + + + + ID + 420 + Rotation + 19.399997711181641 + + + Bounds + {{371.98798359082144, 708.38955751823028}, {19.087577050122338, 39.91038694100309}} + Class + ShapedGraphic + ID + 429 + Shape + Rectangle + Style + + fill + + Color + + b + 0.153172 + g + 0.153172 + r + 0.153172 + + FillType + 2 + GradientAngle + 145 + GradientColor + + b + 0.416928 + g + 0.416928 + r + 0.416928 + + + stroke + + CornerRadius + 2 + + + + + ID + 419 + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{301.99718791759841, 719.00348000010274}, {5.0056232242123722, 4.9183513058348947}} + Class + ShapedGraphic + ID + 432 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{319.38892754494066, 726.18083630427896}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 433 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{314.26809201503823, 724.37750572330788}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 434 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{308.94267545212068, 722.50213079899277}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 435 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{298.3193040474635, 718.76105174750478}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 436 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{292.99387948498219, 716.88567400609941}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 437 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{287.87305195464319, 715.08234624221859}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 438 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{268.58065292341041, 717.40031177163075}, {71.838699340820256, 8.1246847180976189}} + Class + ShapedGraphic + ID + 439 + Rotation + 19.399997711181641 + Shape + Diamond + Style + + stroke + + CornerRadius + 5 + + + Text + + VerticalPad + 0 + + + + ID + 431 + Rotation + 19.399997711181641 + + + Bounds + {{294.63085102237534, 708.38955773319913}, {19.087577050122338, 39.91038694100309}} + Class + ShapedGraphic + ID + 440 + Shape + Rectangle + Style + + fill + + Color + + b + 0.153172 + g + 0.153172 + r + 0.153172 + + FillType + 2 + GradientAngle + 145 + GradientColor + + b + 0.416928 + g + 0.416928 + r + 0.416928 + + + stroke + + CornerRadius + 2 + + + + + ID + 430 + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{151.85433513439526, 676.40348606783687}, {5.0056232242123722, 4.9183513058348947}} + Class + ShapedGraphic + ID + 443 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{169.24607476173759, 683.58084237201308}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 444 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{164.12523923183511, 681.777511791042}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 445 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{158.79982266891756, 679.90213686672689}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 446 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{148.17645126426038, 676.16105781523891}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 447 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{142.85102670177906, 674.28568007383353}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 448 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{137.73019917144009, 672.48235230995272}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 449 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{118.43780014020726, 674.80031783936488}, {71.838699340820256, 8.1246847180976189}} + Class + ShapedGraphic + ID + 450 + Rotation + 19.399997711181641 + Shape + Diamond + Style + + stroke + + CornerRadius + 5 + + + Text + + VerticalPad + 0 + + + + ID + 442 + Rotation + 19.399997711181641 + + + Bounds + {{144.48799823917219, 665.78956380093325}, {19.087577050122338, 39.91038694100309}} + Class + ShapedGraphic + ID + 451 + Shape + Rectangle + Style + + fill + + Color + + b + 0.153172 + g + 0.153172 + r + 0.153172 + + FillType + 2 + GradientAngle + 145 + GradientColor + + b + 0.416928 + g + 0.416928 + r + 0.416928 + + + stroke + + CornerRadius + 2 + + + + + ID + 441 + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{126.06861430919994, 649.30352977035523}, {5.0056232242123722, 4.9183513058348947}} + Class + ShapedGraphic + ID + 454 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{143.46035393654228, 656.48088607453144}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 455 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{138.3395184066398, 654.67755549356036}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 456 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{133.01410184372224, 652.80218056924525}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 457 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{122.39073043906507, 649.06110151775727}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 458 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{117.06530587658375, 647.18572377635189}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 459 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{111.94447834624478, 645.38239601247108}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 460 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{92.652079315011946, 647.70036154188324}, {71.838699340820256, 8.1246847180976189}} + Class + ShapedGraphic + ID + 461 + Rotation + 19.399997711181641 + Shape + Diamond + Style + + stroke + + CornerRadius + 5 + + + Text + + VerticalPad + 0 + + + + ID + 453 + Rotation + 19.399997711181641 + + + Bounds + {{118.70227741397687, 638.68960750345161}, {19.087577050122338, 39.91038694100309}} + Class + ShapedGraphic + ID + 462 + Shape + Rectangle + Style + + fill + + Color + + b + 0.153172 + g + 0.153172 + r + 0.153172 + + FillType + 2 + GradientAngle + 145 + GradientColor + + b + 0.416928 + g + 0.416928 + r + 0.416928 + + + stroke + + CornerRadius + 2 + + + + + ID + 452 + + + Class + LineGraphic + Head + + ID + 494 + + ID + 463 + Points + + {187.62496920676753, 443.67073351699486} + {80.392883576430918, 528.07926647675936} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 515 + + + + Class + LineGraphic + Head + + ID + 451 + + ID + 464 + Points + + {154.34620841108131, 570.74999811167606} + {154.08771587848975, 665.2895656892573} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 499 + + + + Class + LineGraphic + Head + + ID + 462 + + ID + 465 + Points + + {128.55726775049197, 570.74999689176411} + {128.31848992771231, 638.1896106116875} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 500 + + + + Class + LineGraphic + Head + + ID + 538 + + ID + 466 + Points + + {102.76581371331335, 570.74999379087535} + {102.56212456317996, 611.68961371257615} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 501 + + + + Class + LineGraphic + Head + + ID + 549 + + ID + 467 + Points + + {76.966539516560758, 570.74998251647355} + {76.84574963416425, 585.18962498697681} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 502 + + + + Class + LineGraphic + Head + + ID + 550 + + ID + 468 + Points + + {180.14284120598458, 570.75} + {180.14284120598458, 685.34997558593727} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 498 + + + + Class + LineGraphic + Head + + ID + 527 + + ID + 469 + Points + + {205.92052173345891, 570.74999897014993} + {205.64439858308342, 707.8895785636937} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 497 + + + + Bounds + {{482, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 470 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{456.21429061889648, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 471 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{430.42857551574707, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 472 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{404.64286041259766, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 473 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{378.85714530944824, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 474 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{353.07143020629883, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 475 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{327.28571510314941, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 476 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{301.5, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 477 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{482, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 478 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{456.21429061889648, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 479 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{430.42857551574707, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 480 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{404.64286041259766, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 481 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{378.85714530944824, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 482 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{353.07143020629883, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 483 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{327.28571510314941, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 484 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{301.5, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 485 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{291.5, 531.25}, {208, 36}} + Class + ShapedGraphic + ID + 486 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 Actuator Output Group 1 (e.g. FMU)} + + + + Bounds + {{254.5, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 487 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{228.71429061889648, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 488 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{202.92857551574707, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 489 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{177.14286041259766, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 490 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{151.35714530944824, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 491 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{125.57143020629883, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 492 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{99.785715103149414, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 493 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{74, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 494 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{254.5, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 495 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{228.71429061889648, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 496 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{202.92857551574707, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 497 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{177.14286041259766, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 498 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{151.35714530944824, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 499 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{125.57143020629883, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 500 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{99.785715103149414, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 501 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{74, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 502 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{64, 531.25}, {208, 36}} + Class + ShapedGraphic + ID + 503 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 Actuator Output Group 0 (e.g. IO)} + + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{265.12499809265137, 357}, {6, 7}} + Class + ShapedGraphic + ID + 506 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{239.33928298950195, 357}, {6, 7}} + Class + ShapedGraphic + ID + 507 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{213.55356788635254, 357}, {6, 7}} + Class + ShapedGraphic + ID + 508 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{187.76785278320312, 357}, {6, 7}} + Class + ShapedGraphic + ID + 509 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{316.9464282989502, 437.5}, {6, 7}} + Class + ShapedGraphic + ID + 510 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{291.16071319580078, 437.5}, {6, 7}} + Class + ShapedGraphic + ID + 511 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{265.37499809265137, 437.5}, {6, 7}} + Class + ShapedGraphic + ID + 512 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{239.58928298950195, 437.5}, {6, 7}} + Class + ShapedGraphic + ID + 513 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{213.80356788635254, 437.5}, {6, 7}} + Class + ShapedGraphic + ID + 514 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{188.01785278320312, 437.5}, {6, 7}} + Class + ShapedGraphic + ID + 515 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + ID + 505 + + + Bounds + {{177.14285278320312, 359.75}, {208, 82}} + Class + ShapedGraphic + ID + 516 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 Vehicle Mixer} + + + + ID + 504 + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{203.42576152599673, 719.00349980074725}, {5.0056232242123722, 4.9183513058348947}} + Class + ShapedGraphic + ID + 519 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{220.81750115333907, 726.18085610492346}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 520 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{215.69666562343659, 724.37752552395239}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 521 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{210.37124906051903, 722.50215059963728}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 522 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{199.74787765586186, 718.76107154814929}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 523 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{194.42245309338054, 716.88569380674392}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 524 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{189.30162556304157, 715.0823660428631}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 525 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{170.00922653180874, 717.40033157227526}, {71.838699340820256, 8.1246847180976189}} + Class + ShapedGraphic + ID + 526 + Rotation + 19.399997711181641 + Shape + Diamond + Style + + stroke + + CornerRadius + 5 + + + Text + + VerticalPad + 0 + + + + ID + 518 + Rotation + 19.399997711181641 + + + Bounds + {{196.05942463077366, 708.38957753384364}, {19.087577050122338, 39.91038694100309}} + Class + ShapedGraphic + ID + 527 + Shape + Rectangle + Style + + fill + + Color + + b + 0.153172 + g + 0.153172 + r + 0.153172 + + FillType + 2 + GradientAngle + 145 + GradientColor + + b + 0.416928 + g + 0.416928 + r + 0.416928 + + + stroke + + CornerRadius + 2 + + + + + ID + 517 + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{100.28290111339905, 622.80352977035523}, {5.0056232242123722, 4.9183513058348947}} + Class + ShapedGraphic + ID + 530 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{117.67464074074138, 629.98088607453144}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 531 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{112.5538052108389, 628.17755549356036}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 532 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{107.22838864792135, 626.30218056924525}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 533 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{96.605017243264172, 622.56110151775727}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 534 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{91.279592680782855, 620.68572377635189}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 535 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{86.158765150443884, 618.88239601247108}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 536 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{66.866366119211051, 621.20036154188324}, {71.838699340820256, 8.1246847180976189}} + Class + ShapedGraphic + ID + 537 + Rotation + 19.399997711181641 + Shape + Diamond + Style + + stroke + + CornerRadius + 5 + + + Text + + VerticalPad + 0 + + + + ID + 529 + Rotation + 19.399997711181641 + + + Bounds + {{92.916564218175978, 612.18960750345161}, {19.087577050122338, 39.91038694100309}} + Class + ShapedGraphic + ID + 538 + Shape + Rectangle + Style + + fill + + Color + + b + 0.153172 + g + 0.153172 + r + 0.153172 + + FillType + 2 + GradientAngle + 145 + GradientColor + + b + 0.416928 + g + 0.416928 + r + 0.416928 + + + stroke + + CornerRadius + 2 + + + + + ID + 528 + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{74.49718852803673, 596.30352977035523}, {5.0056232242123722, 4.9183513058348947}} + Class + ShapedGraphic + ID + 541 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{91.888928155379034, 603.48088607453144}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 542 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{86.768092625476555, 601.67755549356036}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 543 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{81.442676062559002, 599.80218056924525}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 544 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{70.819304657901824, 596.06110151775727}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 545 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{65.493880095420508, 594.18572377635189}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 546 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{60.373052565081537, 592.38239601247108}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 547 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{41.080653533848704, 594.70036154188324}, {71.838699340820256, 8.1246847180976189}} + Class + ShapedGraphic + ID + 548 + Rotation + 19.399997711181641 + Shape + Diamond + Style + + stroke + + CornerRadius + 5 + + + Text + + VerticalPad + 0 + + + + ID + 540 + Rotation + 19.399997711181641 + + + Bounds + {{67.130851632813631, 585.68960750345161}, {19.087577050122338, 39.91038694100309}} + Class + ShapedGraphic + ID + 549 + Shape + Rectangle + Style + + fill + + Color + + b + 0.153172 + g + 0.153172 + r + 0.153172 + + FillType + 2 + GradientAngle + 145 + GradientColor + + b + 0.416928 + g + 0.416928 + r + 0.416928 + + + stroke + + CornerRadius + 2 + + + + + ID + 539 + + + Bounds + {{64, 104}, {54, 36}} + Class + ShapedGraphic + ID + 1 + Shape + Rectangle + + + Bounds + {{125.57142639160156, 24}, {36, 36}} + Class + ShapedGraphic + ID + 6 + Shape + Diamond + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{158.14285217276469, 695.84997558593727}, {44, 24}} + Class + ShapedGraphic + ID + 550 + Rotation + 90 + Shape + Rectangle + Style + + fill + + Color + + b + 0.243722 + g + 0.864482 + r + 1 + + + stroke + + Color + + b + 0.051159 + g + 0.160546 + r + 0.18663 + + CornerRadius + 5 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 ESC} + + + + GridInfo + + GuidesLocked + NO + GuidesVisible + YES + HPages + 2 + ImageCounter + 1 + KeepToScale + + Layers + + + Lock + NO + Name + Layer 1 + Print + YES + View + YES + + + LayoutInfo + + Animate + NO + circoMinDist + 18 + circoSeparation + 0.0 + layoutEngine + dot + neatoSeparation + 0.0 + twopiSeparation + 0.0 + + LinksVisible + NO + MagnetsVisible + NO + MasterSheets + + ModificationDate + 2013-06-04 16:51:32 +0000 + Modifier + Lorenz Meier + NotesVisible + NO + Orientation + 2 + OriginVisible + NO + PageBreaks + YES + PrintInfo + + NSBottomMargin + + float + 41 + + NSHorizonalPagination + + coded + BAtzdHJlYW10eXBlZIHoA4QBQISEhAhOU051bWJlcgCEhAdOU1ZhbHVlAISECE5TT2JqZWN0AIWEASqEhAFxlwCG + + NSLeftMargin + + float + 18 + + NSPaperSize + + size + {595, 842} + + NSPrintReverseOrientation + + int + 0 + + NSRightMargin + + float + 18 + + NSTopMargin + + float + 18 + + + PrintOnePage + + ReadOnly + NO + RowAlign + 1 + RowSpacing + 36 + SheetTitle + Canvas 1 + SmartAlignmentGuidesActive + YES + SmartDistanceGuidesActive + YES + UniqueID + 1 + UseEntirePage + + VPages + 1 + WindowInfo + + CurrentSheet + 0 + ExpandedCanvases + + + name + Canvas 1 + + + Frame + {{176, 63}, {1581, 1355}} + ListView + + OutlineWidth + 142 + RightSidebar + + ShowRuler + + Sidebar + + SidebarWidth + 120 + VisibleRegion + {{-164, -216}, {1446, 1216}} + Zoom + 1 + ZoomValues + + + Canvas 1 + 1 + 2 + + + + + diff --git a/Documentation/rc_mode_switch.odg b/Documentation/rc_mode_switch.odg index e35a83372b18cf42baf2e68dea03be681e2ef760..a8a6f93f31f90c26e4e6d2ae4914fcefd53301aa 100644 GIT binary patch delta 9974 zcmY+K1yEhP)`0gpxD|IVR@@HmQi>OMcP$k6gA|7XrMSDh`vF?qN(;rMIK|!hr@imL z^IpE0Op=wgviF{qok_AvTvFXIR21Og@c;lB0HkcM5-^mJrEISx&lh(;)|uq{R)NdwiV%_~_ zCLXFcL1x~VQ1%Y&O`d3LZ|}a|?K>>d&N1i&2vfg(O6q8=Ld$*O%6Tb2>pV5)*C?6< zZL@43_Q>7kVz>wzi2)dAu-@kttE(C;v*}WoybgmWcpU}x!+O1krwh1oSG9_?6D3qt zcj74KD9jp+;?;hISO0B!d@3+RMMYKyF-N9V#5!Zv)Ge$_T~(`~ zWrurUC1w^^3oROba`DRDrdp8;A#Kb=5>{lPx7D*^D<{_p;AXYT=LhwvMBRD0+A6Kn|4yTmpphqWnm>0(zybjWw7LA{KB*!Yz4u9FiFzLg3%_1`^g5ppTX(Zc@QsnN zi0$SH^eXj@c!&w5I&I$Q5SNR-zF|DR5@AZR3tzKo-@8cvYDlw97o}sP29FaVCCbft zdwI;7LPe&??PZ;Xm4ddVY-9j|{lb_x;J#*GodpFi*6t%=eeOM528DR7?dy6}^+F&?OwzS4-S{2-=O(S)n7tJi%Ezpw5x7 zXiS22S_rm;+>(*7TLQ{g3#&wdy)@4ydjLf@_;`alV#Z|L4&tH!$ zcv*fVwk3~j<1DcsLgB{4DYLofGLqjs_6P$=tyVPPt??Nm1Ive z%R^xI1XtQ5B;_5{oW$4)i$Q zZ7ipv&9>F;;ryK}IdQT3FT2Q6Z#BzZ z9Pj zE?whLtD#+bgY@2ZdI6nWn+Y>%zojfz-g4zk^9_qDPJHb$RT!QlC}QaqEJ0CEpW+RP@eI>v2T>7vO@K9^&q464RHl4s)JZL2e5e z*cYeoB8g8poRh#RB>j|ul<}N2c5BY$B3^})M~~*TzPn>Z(tf!NHg;IR20k$o|b$vTHnjxI)dCx%hl&d7rw zZ=EE4CBA2jwMCkdXf?e{pXR&migKDh;F)XlVOy%q`j+DGbHqTa)L!f$V8@_UcTwqJ z$B@}o*XoCrJNrV@nF5JoSA?!V_F~%V^e?)T{v0QUI9-C(F{{bR$z5FuRjwS<(RwRy z+p1di(XXSlLq!JGP#L%pr{oEaz6N;@32tBQ$5sdRBIh=*+~JAhI_{3|H8>B zgtp%i+Rb7={I>0G@Dv&M9Xk+S7@i17MvJb_Z|&%a`o;U3?ckuU#D9FAK`Zt7dT(Q- z=F`{e>tFT3Wtm^%JOjog+jYgF^7S;0^1S9<-6L5l8h*J--9fzzZd`v^Lu@02NWYQ` zIon0QiFTJUckvpaExw5C@O#90FI6alKUDduI#j*odRol??q=S*5Y3nFz=<&X&NO{~ zeS~YT57Xlv0{!AfqsQ*?0jfds`9AFuu@7tYI1b4hIW4~U79o_{j`#(cxcQg6;T%SK zkrTK-4Vg!Ns9HhMCx}uNbNuceen-NTGswT&30S?jTrA&|RAQUc0gZCAsrRF}&fveN zJ5Sf|vLSANErf?y$j+(cXJmoo-9);M3NE;Tl$sQGKevx^D3wHi_9pl3$iFF8)u%1B zIIUmYx*^4HGrEsrb$dUpF+9t&@)*Z$#Jlw{MpW9VUSJHBr1#WhCC9#Veae=j9)&@YL1`PSf<~u z{I0G_Q8?AM60{cO@-GbiCL$#JX1;mEz1fijp?mSBxI1NMuRZ@WovMRSzyJlw=$TW^ zcYIXV={Jj(Oc9eE;VGphr=KKS`iKpLER}Ap#R`oh9=3e1BHJHo*uOlSSuhw!Tw0!O zze9-ch3XjzwQ)xrv-1yy3Pc1TA~B+ORjCTaPX7WwIr+N2N4sp6OlIj&(h!tY9Z+mP z>2C+y!y%*;Z?9@kH0H#{*2J_}&TAN=cXm-aWf-TW_$_w{O)A*(`VT8u7M0vI)!e91 zHUNiwd5p0t;g`bmZ(C>aER!-H@?#AI~w=E(^i=c*EGx@nKNbY0&CemKpINM(!|sXx(1@Ob zrga;^pcE7+`Yku6T#O|o&`M2psK?qf6^}AHpV4^LL+ExD`mC;B_dX$v^<2p>xA|0~$2QtslHG-VQ%g^{CUtUzaHcutz8@7YeJ-VmGgsqx z{NjpP&+4_{G@6y8;ns)ldQAFqv2LstOwN5ZwWQ<#JXiBsrlbXd(a*ZJ>7om#daQCa z$%V$F)4H;!^`}l+dvaP;Y#UHzjh&Wmf=SIXJ;7p|r26n$`Pg9V8_9D_=i zxK=+s64A3Rasyt;7y^ib(Yf!r66zD)Dc)PTWaQbcv*$CAxsb0#T(%0YOAL+JSc3%T z+o(f)FMNcky_63Ndxx7LC9;&lNsl%MZ)#|b%&*WzTI+S zyQq6w9Ah?l_Zcb=En7-^@=ZIAobprX6r^F3Cm4loAG1N-@0r&;LRW{T`N}A}@7L|R)ow2m9Ic(2&KZF^MvOz7kS#mFW{FGEdN5hOB9 zGS97;7T2b+J_6my(|dZPb7dE?QL+372VB!SK{Av1cmx>!U)d@iO!>w_m>dQp?g zbNl5{kG?bm3gYMR`uKyA!%U-m%IR(Q${3YI>Y_BVI)n1RMs>)m&JGXSDX6Lw;=L}n zdJzLfVeGmq*B8L2QJ8J7v@=;+(`2d1*SnqiN;FV8vUzmAI$Rg&zRn=`8KQMDgO-%> zbtV{6=d4)BLb|k4ZfR2=<-TUIX0f(;>TctPMVL?H4`@0vwOXkdiZi(|Kv9}^Td@t`sAUyOjU@-7bF5A#c8R&sDw ztQPA*9128ZcYcmUfh>PHKnSe#u#3mIKk)lud zU+f}GEI9^bvahk`Q7oWvBj6G6h!O7y1vSg4suqFsthgX?>xhgcKWR3+RSlgX1{Dbv z3Dun$)q=vDRCT{q7h%R_)ttl2PPXVdS{b+;{6e$WW18Q`^GQ3~Po*x@@-An|ej$jx zri~_Al0m1(g{~HVf z7G3tBUe1A(H-ll&ig>thiB?Mi^@Am6;M5{-EAuS)Q8X|`MpIg zP>jM&pLV`RtM%<()lC&?b1UyvhfxmT$x42(1z*yYEjs-ila(J|h05 z+w0@N8Su$Uw$dRMA$;B7n$s1XU;h}7u0-gter7~Tw85TAwhTT*F)Pl!*5Pj2mDJKTyA zji3d|v#C&S4mc1p1~LY+KL)aYJ`Z<$+jBZ`2+HmoUG5EphvaER)H!W?wfPrsnHJ6O z9%&cb%e9#4-)Nzru)o$pGe2!b4%W~V^Houniee*k=?|cunK~tJvbBbYQ**14^`m5Yxv-IURWXw~F+3f(FI#oFznt9!AYlZI5VhxlJu;3yaOPl+Xrh}@Z3#eeAw=8mJD>#Uey;9g> z!U72f{|_`K!7XoDX@~k+dCT|~QIW7-H^Iijh99C->M zC^1x~yxp%vlrm3|2eVWA=G9P1pI<082rVZth=cyYJQsjte2K6tJtV@RYLD)ErE2;{ z%DW&8b$X~Yk!FmGFh8Hke>al8(k~kdCvt-KmmkPp`;L=o_5A_IR}BSFc* z^bge^N|igP+4uVFT?gM_pzH{(<*lKX2*F6a0V}`?*e(E{!>B}ZxpKLnf3n=O_Z_2% z!TnP}D(Ek({57FDQcVlUJ&KO1h%($>E(&A}35UXxFrq+$K!QLIcyZq-$7W9Ysz@mX z?5l3mn}yHR7-`?E+OSx54QShK;LI80cfoFe8{p>r)y;&u;WZNd%k$;x5Lk*Rfbi*CRb?6(*28 zvC)d_KgF~6ve7P+$?$`<(%ss@7jLqP&XCt~myWr%IFjinP|T7~WMJC8oG>@pY*Arh zen4w$Zyq05Q=|fFAy|M82{OQf0S_c2f&qnwWZ+#(#`D)KV=P?-fWse_Dh1?i9rbmR zz~rF(!2ZOD#MJFH zwu`<}puEMtUR%&1ftBjsY1Y?52(xTiz0<#Bma+?U-=fEiF;CtxM3p^e;|+Os*qev! z^+2pmQy~7$Qx3X5EU4nGUh67*?90{E8K0WvSR@Qs9ZOWAWD5m!^aBmCwcogndoPmvnBON^PkyNXCZN{oc;v&R}OZ??GIYJ5v>ig$)uL3!D zNE`~>(Aa!EC+Nr@r?HwL*%L25??DNurDE}Q@nCk19v_sYYeymUQqS(gyKO!{#%8xT zIjh9Kk82^r;IDY7mb^z-JmrteE#s>9w)OX37%}#Krhv7Q0~m`(c(IJ1O_hOBvsDxW z9DQ&gLSXM44(t~UB?bvxivZyuk^;j*kv2GK0jxk=A{2NNY#S3IE%?CSPz>eXC;)&{ zHbKV{_%aIOWS;H_26q}wRD8F zDzVh=7AJwCw;sN$C3TFJYW0x^9_xL+zcGuC5A~~uYb-onMPtd?JFBx}4RcK%6;T3` z%3rdy7@^%BqC= zkyrAuRFA^R2Fb`KDZ+u1w+k&ij7 zk!jFc;qNttHe7js=Y`~#l9;U6Q<5Q%2MEd*NYgdJHzKA0J&2nE5QKh-mZF!Tn1$;{nhMGbvxFe$|Q(&afBbl?VnpI<)Xv2qU*0bNwiShz7DfCCH9lH)@`H5kHk}`JW2h@fe1=ZSDkZ|`^%MGG%-g9$~l1+kD zW3Gb_XcSR&u!PZmB=P;Z%z*MH0i{Yb$YK z9TFYf#)L!k;UsjwvTVp`fNHS23>Lb(-YY=Z1PZY~; z6A5fGnzAyv+eo|A&5Z_q7mLQ&Ap^(T2euA!-A=L z{lh*md=jIZILnzCiB(ZnLF|=tg7M)p=RMDMZq5)q7w{6M&qH zS$62-YCTJ-RUwj(7XQM$^fHCO>@I=5BMkT$Ow#3=7W&zqKj_npm8JyY+{Y8Zbz`up z+qy>apr}s}jxdB=nqFRY--g;PPtrG`G%qu5r&1br z8L4zwf0{aA-rS?GXPMCtUsx1hM99}VN>Ny$qBTFRKtbDkTys#^An9?{@`+%2s!!K& zD%a_@B{v=1{bD}PVMwifZ=pZ^Py-c1G;#F%^Ap`Qrn4X&r&qonA5brkdt20&#HPsz z4e{Y$_>qii@)JRvRrH-H8rWg%Gn=}+d3~b<6FzO>F#Xhz5oDT~R%M`r4G=56T=t>M zvv0g*K^OH;|D|ZCs-Dz_Sk4JU%t0owkYUIrho5xUSYw&%DyTKNMR@_=2ZhzSU7);a zB{U?Iy*~0w=@g|5#38Y#n93_h3+xu^N$2kt?U9;+Wg@rS%$?(LD@CP<5+!shx5>4- zRAyh%DD)ay>dupG&Yc(pnT{4>+7zPAluls(K#1?AGQJ6r9@&=VSQIfNFl!$g z+mbK^XSXFHE=(@T5U($D{zKEy=`+vz(Pu0+ed+`#s=Q@4w`-fU~Qz_1013KoS~ zUj)i>%!OE1h|>}o5GYl|%5vzCBmtj~+dSip-7y3G_rbZxZ8c{b(Cdn$hG$gH8WBSl z-a~~~FG=TIViRe3hUMpZvq1je=Ia9y9SL9QiQ&TOW1!75Cd_N{c2;{V=*UXUsS3!c zsRyYMR^o-(R=5o$LrB)L_pK0PtgnEI;o z$VY|(l#tr+c3}E?so@1Coov3( zQUyhv*p8Dl;hXel51INa4Y-Ce<-&2esc+6cQi8sN>aGgAW z!_BYjH#2p407ytB0D#decS`JhCHOb!h?9{zF`5@0 z?Y}~y5;+-p{*{sP{jV&Kk?*ezn~6HHiVyXF^st$@|H|GlY5d!#hY9CTx#0&>C-UDy zBDV(UuXG>6{cproA{`GK#-H%3fA857O?X%-|Frz~-V5!|`}~`}C06o~Q2puicNg|| z69xc8|H}WQuVjhoWF((>(fnG#j`nEvV*^OJ&m{+J;6#Ds_e0^SlvkJw@dTL}g-b|Os0TNDsACAD@1KvTXd#Zwa}hJ>?k3Q#(0U{(i07DlY%Z%!VR7LK3 ze`)_dNglWS8d^WR0tHwbz=f}6WaU&!@;kZ=>ZDc2u+Z5@3E?QTqca>0C{rhm7pMF0 zWIuLYC`0|qwOv?9ES3$Qr@R?EVjJ=kF=9UOQ;-pRqmt&X^0mJO{UbXv9L%eRYRD%bAcK3~fdD?wb9E%;Ne(^-@0+2Q@Q zzVG?j9M_J72-q9@Z7JjXi5G5)^*QELl#8@D4A)nd!l4oBpSl_-C<(CE6S+HDgq*N6-%n#=$vZV+HsG<$pt>X+;LT#wuz^1)&d8?A6;=GU>Ay1$$@KK{H>6_i=QFLZq-`cRiUHoB7M&opE$n_c*Y=a>^3mSMJFiWd(Y;V)){b6W66d*JzMGvUjrV|rqYwAh zNBnAd3D&DH-x*sM>na#S0nINHfKqWtbK4qhk#Hs4_YM?0{Af%ScTictK;K$nqx-s| zsbIL3kw`YLB)9z0lKocNtg%;!e^`Iz1cS1@(}s5d2bXrz=~)$Lh$!o_#H>y^2eCOH zaZiRq{@7TgaI$S)Y;5Rxtxw_E`5jFj_r@d~JCK8)=>BDG8Cit}7bQ#CFa`URfyQcs z3*pWSEu+G!m^ZuW3H%AE6fWLjnNS(Jgh+SBZ-cU3&MtvZ^fJy_ZbWlAms2{{7qs5- zM^E2T7-ARUI3##OyYd4Jn-MS$$f{@Pj1=>G1jR z2+Y+KUkh{AMn-PmfgRgoC=J;|op_$I%(ac-NzB@-3M48n!BojM|98%;H%D0I_+@W} zxr!`4QGhQ&2@)8E&{Xi7YYE9ZG}->-DajE?PQjor zA*z(_2w!Aj4IRDqX}g%B)3YFyHT5LTN1)o)l%(oOhU~I6y?vUNbV`C6Cl8**XU*UA z_P7?jvp&xZ_qbU-xgunh8R9p)vVB)aIe(3JAM3-#v0s{$B*Bjbe8wgWa#}!i@YDL6 zvCb~yrOigQtE~4qM}9Rw9Zl+`e<04dWX|UIb$<{4fK~C+9K3S!DOxM@8&CT64d!zn zPoX+gwRhv!KIieS-+i{GnF-ik~6I4T{sQE*3Y{l?_8{t}f9EPfLk&_jMK-3mGiV7Yr958Z6s0SUxb5|D7Ji z$fh_3@9f&V;9zq&L$-}|a$ zqfcOTN@TS3P+#xavSz`{6i%XSs+!}8s1e2!kex{gWWU&cDfm{{>GyKVq)|$otAkT$ zr~hUv31b~TZaxSlFz;Ymku1~|pREh|+ZOf||bDpk%T6GpU6tqMM7DXgD1 zYrAQui!MpdulV}b9UjT;mWUF}gUWQt94G#0!&E!_5N5+iZi#yBr^B5mOmaLPu!E9P zwh_WN&+&G!B2sVFnLyA>Y#X(Z6E8+A+x$-FBgN(uaDnF>r%AE*L-jILW$!4YNqC{X zZ@)NMkFnJA_q(qro^cpd&0fQ(ZR`kHMGvjD-!+)o{CoGGN#UiQ8V>r>mL5B_jA&Wr z>ISs}HlOrP-(}Y+y!&A`!L<0O@sP#lC*ndc%J#g4|A?>VSYu-B@{{58V!p@`tD}X% zp!?N6$Jkf`)n%Ugjajx82F-(9%0WYlcv!~VwJ#hdp8H88F15}&)0;Pe^tyI$X!FeV z;aG_B!h*44>>94TCCp760WaZd7c)z)0;V&-l@+TK{*m9lx4QXR@mDXLutSh^^*7vl zBKy4Y-b6Rmx1RX0!7%OO+{Bo6!YV7D(9loJLbsax%ZJY1D0xC=6Oq1G^X9bK6o*VJ zM0C!7;}6vu%7;5ekVrFMW&NVlthn!^dh+s`{mZ=D3l@#OPlnzs zY`n=k@V1HKc)JAAr6-zF>}PmYvSKQ1BW`2l!P*utklr4LXq_2#1o$&tH0LaG9)5RP zkN9~q659>OJ6b+o%^>fA*kLb?P(XOYqHM5!kxkJHxEd9GWG(7Nxi^Bly~T7}kS2Fp z(t6DsFB+5PdV->b3PZzqt~_3o5_2F(L9tHeG*(|GOzL?jxW?bz0K4#uJJlD+JGg(U zl#~>^{iS-l`6CzRlt0Z9j+{4paNv)bGN!Y9O-45OXhN934CF9>`or798=Zh;D=DS> zFykflx2k!1E;%+SO26Mo#5lZhF1q=t`i5X+fEmNX06Y0GvI$eEu8i7dUqCiG)@gTm zU^}TYuA!Jxsy{qBzD z!(wb7eB0=eAwTeH{>g`XtD;fZyRLjtOy|=h^Y?JM|Z!HF<`el5wa`F46!ARq{OYE&*l=jMgfS6l9 z4sS%9;Z%8rJb}_;0M>Es9sPBAGwS?UH357o1YdPiAjHZLO)LL`ckB(c!VI~1N$9i+-2Nu1ffsfW+PY?}*ixH1qJAm>8@fRWF zPPmg0HiAbqEqYVl;k>Huafi%b!YSIeD%lLmXO}g}+~V{TS+ik~Ox}pY!`S95-QZH@JdFAtsS>{6$O)MOW^^&qg=8L1_hlYErY~H<$QAexC zAKj0di#6_ubfN}PU-yA#8ts>Sy}5fljPUTZ2RqwgBcm@kc}C>M2xnBx+wHC79NSA? zzJhXH@tu~MLiw+OShX_vi%RaAhhbbCG0uL(8gdP|a@(vNg|XIjm#iFxF_v^ea}|y8 z;_0D@6^(IR*?!f8CF9fVg@!DudJMYz!f(^#%H+8d+;t=kl%5YQMNM$@yy%nJ?|{Q3 zB0IZ0BrKzBZ)4Yey;Q{c_qyLU5uY^aULzdHpTkZVSz;Qh`d%ze&NT^$dsuUWsN<~H zX_tldtG?mE2!Cr7-`=oEK!g24GI)(Lu7h+8Qlg+ni#P;Y5=Ic3a8fN+7R@Mk!nbBH zR-z>i0rZ9$QLn~=EZq;P9E#1!FW_c$URK}Ue6(w-d}%P0RjRA@D?O#+b(3{!zE-5{ zf_||3FEJ&f<=&y2D5l=Q(Oo>EqM}{~3AJ96E|ZpGoBMRJj2x`*PIN|^EF<{6ZTj~{ zgwXm~dDvAdcMcauC#|0U`=6|Hs)29RX>+0?%d%D`#9Je;Mzj`lh90gow)o(t77;)B zAH9@Q%BU*KQA&@d&h_Jl*m?L>P*}ojO4}^U-Yu$?o4!~qqc!>(gAGeu|GLinB~jce zC;7@~@wy`*XVF7H`KEabf$3M>m7#c<%zjD@7oJhopCpI`Fu7$x3v z=IGO(OqTFp7MZw8@>ivC=wS<=O_mDq?ApD;`DAmK7>>#Mm45ha|pxJcpNX`3lv=u%?zvl zBeR#;`hixMGNU2FiBII-SYWwo+3wq#e-;CbMvf;`@rN4bKp`mqp^AYW7LLU3q66rI z{=y7Y7lc1gyN+E$dEncaH+3B`wieYqHA z8O;cemZH8vs~wyw-BG_F##X&dw-Oa}_**))#-_}Pj(SG^FuSweEF!AQDfmNJR9n9M z>A-OsW+9HOm79C>4ZeRVTZ=f*@CSl`Mfkau1NsM!B5`di@!+m&p87?-AofARup{!B zhVu*aJ?G`bfP^yL;JtV7&POa);4e^+u;&l;W}8S5p2dbO8UMa&X_mN}1WM{ZWC5SE zP3K~;4X_e2(gpVy@YIjY9H~ZR7`AOox)@?wP=u%A%W;fENA|M);IJY|w0|JT4Hi$G z7dCMZ85AS?{DJ(l?x#K^nbnY(HnA>sQc2>!+<+xN`ml@Oe~O$oBO2+KTEO|qW(qR@ z2Ts8JRhx1ap~#+6#5`{AsBtv5!4JAdvj`Gk6g&zZHRK*SKypmUgl8qD%(x-ivodg-zhW7k;YfWVXjB?mHM1`g%?ZvUKJT$0I zH21h&iPo#_Mdst{wMk)Ejxwl-x;-_P=K3qCgwdtj7K&z)82RTPhlJwCqE&rjn$Xes zk~5=g(a?~hdZ{UCxoGRgnCiss`CrAt$GJa*wklQ<6GGY!O?lD)$Rqv5NL1d;3sB@?gn63<64M9$2&oN2gI?j3Y_Y6#o|~}0(vTXUkC_Jz zk!Ei*8?*eSY|OH3y19_+bUH+4`IgM1FVBIv-WK1S?QOaY?b-w*HZ_+muPL3^zUBLw zRS@-mfK%ICM6h;XFo^`uS>r0Igv`lKcq_AfjJG8XDi`L~G9lqNQL}`cRhOBE)vl4j z6me(qzxgup%RA>7mmyD4Pf<^;h0dPx%93yzi{a>_OZk_W?{fs3&FGewQxd7T?))QX zQSFW}>dUC|wXdNhu=q+$7ZKvVHvgN5%rHVtPa*=%U`UPW)-XM5Uuy(Y-vT4ARu#1h zS!bCQoQyzX!+?l)kX2LJt~9dlcI#Qt>uZC`a?F~RKHYOLTW@8{&kt-W2O`lAqHXZ> zmpRqK+`LCCZTLaFtz-uap#qHrC@ksUV|o0Cy1i~vGEdazKjDb4mXyCYZ*_Xu=(Nhm zn?7WId7g%%FOQTOi5dqM#rXcLr-0PW1uNXL2zy-Yd1xrRCdHOU$P+e<80!s2{EC53 zyP--p?0$kfFj9+lBBlgV;h9u|T%ImC+l)%GUq935QeDBHnLnwMnb>*lKAD@{`#N{V zt-qS_#o{Md&!|FUa9b|CttKyaaFbQt4RO^rKI_Xeud{prg)j1T$YHy`!nqwI=Hk8tD&tM<7HGpH5oY8E4c_0H@ktQ z#BOu6I99M3dFrerpUd?LMaOMvh!oABMf1w=vm4O0nUpQavmnkJcui@Oe3tPg!jj|< zB;4l@W2G7wc_J(i3~RUhRn`dLw@0W!&cA)sYwna!!;We){qbbAaWoTNqIRi|Zw*;RG~i6Fx$B*7nV+Ii zBBN73@f6(HRPN~~lYqPr$!iP?f$&Q8(F(s3Q;Dz-31(H<0|YB#gJ4n`)-b3_{wZ#uw}iyD-E~vs3zIsknYUKf^S0^($N2Z=WoY-7g6w z_MPxAbI6{De(PBDA!$%KBryteY zQq`EqZ~*xa&N0YS5slxQUirvyXiNF+31mshThzo7b91s$@?KGerM}Vwlt6z`2`E~7 zQk|qTgo#3Cy+Ky1Tq1JEaz$zAFRAmFMfBX`kzgs*`Wuwsi)~DFR1<76Tx>8Z@E1Ye z8B_Xt33BtihMeA|xoP;mPS?OI)|Oi5_)uC}WLXqh6j`^YvTjSkyb2VCM`?{;vP3fW@%U*L-3$W=uOh!t-M{m3TNEU)sp?w{+T5LPk6J*jR-B+6VwF+~j@hRu zEA`ql^CZjY-O4lEp|tYO-czBi@LT0`x~=kY*wgS&nJoU!6LmhQHB2udGBUHY54>A< zVqeLzrK9I)cx@%&9i5$I0Bk328U-+B#09j;ApkozGLVc429%IM0Y!m8&x|BsY_p5o zv-7Sji3kkuv3LSX_3dBfm4V}wJ!5o!QjFI#;nB1lLr6YnqdQ>@>%skFz`#ogjH|D$ zUkL{L#uz7Tm|#N)IJg|h1Le8u0HG&)f7#lds3);_ktj_Oc;BT}3REZW+*{%jCituF zxqW3Xj(g&&m~t3Cfd(s(OEC1jv*ttR-gdv*xhlS`x91$z zpyE7ORiFSz3l=U={zyDf&05WmqZ=>+c|JtrYe!|6%>n|aW`FfDJ0CSi??ee8)`1xH zq8TON`#7;1OJe3`)i?L%C*y%ZrKs*J>DAzXM+UkZVjsaP4oS@1h|~i;H9z?4k{m$o zHxHu<4KJ9ZM`6VyAeLjKUJ@{qOsWY{1qVEu1s+s@IV71kPWF+()=$cP$FFdE>K|~F zjU=o=>A-AG=q|WabDYa(RhV(0E;{ZfX0b?-}a+!@Bjk5^x;nC51`ag1Mw zPHvy{`&?e@vAcZz?P`v>VF~};egOAZVf6EF5p8aIZ#$ctP3yHeGn<;~;`Jr1 z^_WzB?*nmw1W&N8*9^&McwN=%h5p^8W%ws~m4}JVUt9CPm*tP1v@RRM6$`sdSWj_0 z;FWy8{BSzB(KCTQ%SOHXYLLe=K^S9&^2(jAC^qZuiQ^Uw>2%m3c+`yDeW*ZD1srzG zyorok9U#%QEPA)DU4Wzec-fz=m?Sa{MN}F2bP7<(V;L@GQ2T2&R{01@j5))TQ~NfT z3DsuM;_pZa<|R=iMup*Y9Akq-0A)!nLFRIenCIlLIfushkq;hIlC`g!>cIrEK}qW$ zi^*|?C8ReP)V(3bi4{=3tH@38N8=!3V_NA9mpdHjY-<2;Xw0W(cT5m67p@9Uox>bu zb@?vzVc?`V_Q93J)^G|u7ZQudJs_12()GZp?B>ChbO}20B!>?#7|e!WdlcsYOxHo9 zwFRz0^W9P^HK>h%it~JSQyWLfG#MnIAcLdLHW1Z&Mhj3{U9D`g?}V9VRm=rdref&^ zgb`A_RYq#~977#@k9I@cqd&jglRtwwZ{v8iz5O8E2$XNebS)+BhXw+T{ddx?hNUVU zm00!u*8u1>`P3<$d2s|D?*or2xeErKu*$ zLZfF2`;kBaGQe4i(vr=zek6n0lc!R&=O3hlc?Fty&&pzJ87mHS&`w35{{nz#An=AH z5+9Yjdjj;g0;mTQJm0HL3vdSjf>V+z!^+R&14-b>wuttRfNnrqPY5Y`DxSM4luoXX z(kxJa1BEKQx|{o>C{nL>Zo0CGVlQ6=4Am?!8A)YdHSj?TB3VVkTmE{j;_P<7Rb4%c zqyY)VAr}J_K&oS>X;mb_)|$kEoJ*qZ0%}F%HT|)kBP&J<7q1Q(q3`XX_i_)!pjTXg zGtd^i1TZK9#Y0Crt!PJlpHBtRIu?N-0R`$&A*|gj1oA;d-coLX2hBs`tO1yX5KocS z9&K8K+|jei6^4VKVn+=s{fmM!F0zA5b8{@DgPs#-TFFfnoL-wqy3v z+$|BKr(pPXPsy-e`jJvTBh6Yy&3Xr1v>hdy>uJ5P3xpQpClb%{aj;}~^-AFGBZb7I zw1gpND^3PQpb#)T{VZV1B<_M)L26u^t(p7#M+b7P1xw7}Fa3nM>VTZ{Wk>VC^vQOh zhe!=)_Vpw0)lt-)7W~7BvOO!b(kMa$#K_XsyP04{>S1dT0pEN;3eVM4 z5IS-#laxX4UfC05=fp!heA@`<+zS_g0$lq3jl<*hG=t0}{ZQ@KO2$jY@dH~PP5r2# z{il{1hJ^27^M-`)1yq=H?Ayxteh`SZ5uyL@DlB~PcNLB$LNCm7Yp6gYw=II++0ZVm zW-qO<*nn2xm2iRIlQqrVr#BDNj*qvVUK2-VO)a^n23I!}y_A;=gB61h6gDF9M_sd` zs~Fj@Bt%R}J~dr9h%AubD-i2{iCK`VlM`+EBp>~imbF>fRq2CoX+C@*$u7%Grrhod z)FJHO?7vLjV)SCefj2dkn!-NAvcs$3MqH8%qpF5vJ)D_UXuBAMcb6qaS+)fbPr>+|ZCxAl2d6?AX=y zQ8sY1RZ#nFV>?M3*raasRv{a0(l8#itGil-70TncY7dCzv;LK(5`(>^PH_+VaV-%uTJKiBI5 z2cc__d@`67v@7!wZ<8|n=F8O)4|d6Q{!my5)Ip_>3%O!iQJgh*i2+E$YYZDui=A&q zxzg%zkO~twng(@U{T(6=+QhEeVLYlWD`dH&vscu5P08tOIs^W`&?-=0bjq=2U9!=9 zWd;MHUJboQ8lfMNC*!(nh{RL+jC>2v4P+=piEp3i#9NVQGEdTc72=pYR)K4fUjRJt*k-)XsLX+SiA~3 zghW)1Prcf6gbCPvYrpoITO_cHTh)+Cq6e`g{7`c8F`7=~4bRO(qe=4K)SHA?rZHdf zLSBp~)Qx>hU~dk&a$PIK>z@fWerf(GV7n`jWZ4uSc~(i5nu3AZl3z{?_0evhe+9c!1|9(92*@XTMz^Dzp97+${5)2 z|Jn<(z5d(BvGM%r8wS}rAb$rTystrjHOqWF{}vk|i20vm|EWCs_kJ0n&d)*fNAlmN z7tBB5|J&veS^VU*e{BBWIR*eo|JDC#{*;JKN^%@EB@mbp__xmKg8&7%<{5%Yfa7l@ zDgqSX<7bFGRsw{d0MWl9MivAYD>Y(D0OMbgJ`3WPz_Y(T|Jx1ae?I_;EQmZ-TI~Ph z5uqkT0iO6XAu)le$ve*fFQ7ka5Hey~kom8xJ3$JNFrrR?0KqE6@K^FjpYT^w%ZBmd zpQ-ttDkUKuLk>8O$fR}^q0AAJK-}*Vhk+a}6rR6(`C1sE9NH$h$->7%K--Wm3(4{ul z+@^!HMLwQ2`F+@LMVoOSy1-Lv6G(u_`(;lA~_QKujgku<3OliA&n4$VO zoE9VZ!ugq!N&}lGg~OGdWaF@2yK;HNj*N(KAj=MB+Z+5jDK?61-szApZ}HP+y)|>P zC_HA)f+pzb@;*5rL@I0x$pGUza+6P^G@*l8)#9VBzW7u3CLRuhE%VHy?(5ZQkjw-v zsPMu(;X8J@+LR`q??n{0T}rAsevxamtiRVw85UG*gt4wuZAy^L;-BB5SffkW-!=K8 zN}}Z<0(*g_c55xGU&E>jWJ6S6y@RU}vC=dw4H&F?|4G=Qgo@Y9<^d`JKiw*KzIIFj%Pih+iC1-cs%qnwn5vjOUb~wi-n2B_2A|~%1T7%{tZDci%W-pUqa@~xB{(7 z`JKY@G(!J1#QPF?)Y2gm6>&az23~y_rNle z#l$!7D3BTH$9O66kw7osQ2zTq8cD6Hz^qpTT)})B;Vvd-U-y&y7Bu zl47`ClUV#pjiGlZ?xjN2ub~g7&{+`$@dlmwvj`8!fnv7! zB|}3oX?qnWLG`x`0+EH1w{$~w<%|fCo?78U3g3e(^X$%Y087EsDs#%5!rA=MRuLnf!?y(fAh|rp!3W7_(R=`__sksR!Kj!@0nK>h-hRXv{n>j^DlQO<$!3QKn25BMa;iP%5)f@0>eX{8bP*i99&9!cxIjJl{odqtD~U##Vd1<^?`VvPBo5^{YKE5<}a%cER-vq2UcY=Tq$1u z2`&KQx%n%dhyD7(XeDX+*HkxM4Lff>tvWHz20x`UG= zhM?0WT<=0r#+Vkb>bEgE**{jxnWNc>jfMcx3JiAVaW46;s!}%0eAA?O)X$w1|KG<+ zdp4YBQJP2XniZ$hobxg}h57%R+S4C^~Ha6%v#NW>&q)B&4G;m(pc8k&g>xP?(=(V(|UQB%7T%Ni@EfPOur? zh5vlYT@e%wdlekT6KjSoL*k$q9JFU}%>lAN&Gk!)Mr)B6*9kPxy>M1t3DTAP4j3Yn znPVAUxEy=?wggvTUD>6trA3emZRG6HJPVa-Oc9WiL&?Aw^9y>bj-L_i;|QOxia|H+ zP{oTYrX9_s=K&DBT%k30$t&{ghjGuKp};=kUIwrmsgY30rvm1#pl~l(yB`t6^t4L4 z_BMeiu606O`YrY6aTl6>t9Q>EfzCO5_Xv^QO(~BMV=1N$1Is1WuUM3%tXs|D4LtqS zo>Bx3u9_mbM}~}_v z@|&)P4aC{(g6;X=q}jpwf0l?s*F5NC%{}GY6*aVKPg$$_;9xbtU9L>l&}c_eb$b6O z(St2L^wpI_+c0_MmGS;yOu(;7Tjk-&nh;64=i~>kLo^XN+}!fv!?BFGFDCO6EA+y)VFiH_j_`9VjPR9 z9C;mN80ICq)4=UlPI;Z=v}lF`rb&r;^zaw0jI1iwaW%Whubx>4Du6b}3D1Rho=Uo2 zOwvT|CO6X6p-~40ycTd*=f9Ac_6{_jKe__!8~GU$?UoD-G_xvlO`1-2i&p8Q5m#9} z;)otk&q1C}eW8zupPhG?mMH_$8CtJ!iw~FEV%^=1%r`~FqX-g9w!d@gyiEVYLE$c6 z^5Ui0;tC8q{+eY6|5emWV*S>u9IeI{+f){px3n)49Dm!30aOD%yjqirqmRX1Jb=bR zDEGn5uua}?-`taN@jyw&A^$tY@ei|PUlJFy9-?p%oSqA0e15-TZrI(^4s}bpJ#vMw zuV$rPmrTt_>FG42R^QT*UHpl`dFR`>T9%R;aFO}`tsivgQop>Z5$}%^heDqACmi@h z=vQITbD=1b0ic~QrJ`K4(f-DLq;SKcBSXrSI3&A;L<1wKNLP>{&vrH5DLVjCb`;3l z6zQQ-<}px5zD7fNl0=&Q{ytJHm!>Z$C;T|L(83GxaigUJOrM{$o&OTw(6*O9tIM$DHIRc2GHOLxIV&Gk}q3kDCrG;ye4O}Puy~d{u z-5I!%8cajOv#ag|BW8;F(IR6m8pgF3;IBX;3%jG;$;BntQh)SJ+ptWHgV zk^-U;OcC`vMrW1YcYhcK*;}HXDyGyPdwz$-M&7Htl&zMbHjoZetW&5Tr=xn!@S*ry z-$DL|dqAJ`+bD~`)k*8iOLUi7W1Emvj?9sxsroI)?w0o7fejjA7dukj<6Dg4Vh@S0 zXOCCITXo>K|ep(t0ZR$6*rUA9s& zp+{(9ZgmidOE87EoZ9M-_AW$VuTQBau}0~w;R`iqwZEQQCn z_vf(CN_KeStDHo1O)cT$Q6ZyxVM)x&I5ezxU8vcpYkjdFU!IdI|KS)U{fryF@U?}p z9w@d+!SKlQ@XMertX|l%B9cf-c+BXpBlC5fUDR14qjRiPg30jcs@?vNTQY5;k@M9b z97Up^!va^3jpbCU-|cfBRO7XtM7@!liIq|f^@FPk#r0_2wY|Pk+d*Ann~uKw`6Tx# z&yAXM@x!|wvgd2JCUb0w2 zd3&v*{1YTb9}JgH5aZ@MFCWA{<$%fP*~=$H8zC=+dOO(E6F2ZIb7hdHLhZ85J_gB8 z`T(9<)L!FCBPI_VoyZ{0-gd=wyCFdUM{Bl4o-F}y!_i&F_r#x!=;GxqdiL=906@GZ z;Nbkkln>5?3lpVYSqlB|M#EL#kFR9oTfzckj7_taSnK-<>Aumax&Z1<9Z-!J_4$bz zKb)8yCYoV)_-*?WuC|dMU+KoT<_lB7K47snAjkfO_r3+~PXBk*{;=05935qFUw5HJ zP=nHYuq$P&Md?kSxN$0@PvacU0T4~w1(UgA@#*J_(yS@}Jq2ZSBIha)HZ>VC)Nv%y z*n9z6oJ7eB@&u>|ddD?hFbU6~GPOKO@Os z?71xd-Z6sB?GlteX)G&{{072{KR3c>5#XvCw-rRBYg;uKaymQlzGnYlU`ImSNgn@@m z^IX(WHIvVJ7J;)4^>{&k9WUOSelZ-!TIA^tOx*C)U?nl<_Mn_Hf6J(S=lqqpyZ2=p zC6m|RR)6OKs&RRoW+}wf3NLab@f-ru+kyI10fk-L{BX0Xz7tU{}7S^_JWoQSZcJg-SJV z3mt_tLl4OkG~C+(`EAN_H!4>9nsl|6PG(j3>-LyV=EI-o%5VCPB*l8MSpWH8u3d&; z`aScO+{U}$5XM67kGJMn;+g2NxJ54Qx%d7$c1zB$%Qw^HYfixa{KKvMxCxw@dG7PV zzL(~?1zXPCtZj8lJL5=pqw(Qog?g&0u9D?~V}B^eCCJ|#4=ruet5-#rKlpOJP3{dDmo zHmI}~&!WjpVp`J}u|1T+*;|_y8*XFbJ0-Z8%W~CYWBPc^O*vdn5JSLQKGXRCc zmE`n#qKRsmcQT{=pd_1JWmxO!@g0TAhH;y!(Dkc<=chs|V{jfy2jj#39}TG3r$Fy zG>-J5{qO!(Z}gV)A$pO3SnSn+tJq=@_L+47;i@vk0<#x&crmJ1WrOZPwH=X-KL^6C zX~ciwnpRJtb9O84OYMdGT!qx1j<~CFrM>@bp{uTkOLlo&8e$eF4dH%FR8^lRrB>y9 zW{u~2hW&h^71K~h@I71>@oPGveSPUirxYTA1O7KhrXtJzvNV??ovK2m+P23#NfS5^3q)XMr)i8vzlP)9At5ouP#~b+mtg zrJQ=hzMFo1em1_q*d)RN=#xrjGF|%^n7;Plbks7f)r!!bwyQ1Y{B4VszR}rg6u>z} zUpdGQIFWk2zsSPwrRW z>o=D3OS?tB-uAHLx<6WN~+S+(&?mqq>+6ktxsGUP?T~$Z5J6)1LImQzv=1y?nUClU2_KS)^CiaS&9 z-?9R1El#gjU2tC6w(uo3)T`1{AqR~jmQ>CMfndigZc+n`c2ZK(>}I^7S0kQXn6!U< zWcyDE?krtd_#?qqT5Qjg7so1fc0|k`DKgYY2$_A{edVacP~S=&r)U@LDLuq$C2k74 zbwe#(!(Pl&oe^yoUY(4BGJ<9iK7X}L#f+|ft9!z}i zrz#xf_3j!Qn(d^fkLSO;_m)*OtT7Q#%#Fk-LLS9NeHA}A_GB$WAi^G#(z-aN(^YPf zIP-bZVy^R1RHc6zpVh3m{o8L{7LNEz&aH)8h~wqEJw<&1jt#R=uZpGea(OCCOOWiA z^7GsKWb)b|I;jbck?3C<63ZfOga-Dqe#Y)4BBQej?xmjG`<;ZN@K1aLLLm~Wv*r2C zgudO8w&^_kp0SOx&OQlq40tdMFWmD zScrYCU?+7Q&j=hUc-l{7cV8HikdvXtQynV|8GMiH5+96^ecqKDU;OvaS~9-e)`^=7 zm{Go39Nxr<_-VFlykRq~V6j^Cu52T|LO+CNvvogH*pl|}(E1J2bVd5WE>%Gn;#zopFNttDbw<=MVu zPg|Ao14DL+4()Z&Sm#RdM^rypu|qvfpAUt)*ImlX?}%pPPmJz_O1ifsJzmeiCIRL51a`zMxe_!AxD7&~*UztuUR zF;WxMuDG-+f}bG0*VUA30zy>Re<;?lD7D#C%X&XgEDq#w=m|V;f@yAd47cfGcRUs#SyeE+DWVRQO+v4=f-c^lv5z0Ym=9KoAf= z-@h22AVg5`UkoGw=KG%)_`ksdVE+FK1wsD~27y5!{(nCR27~{r0}FxvqZ8u)zh2pY zN(O<2p#L=s3;(+dAP7JIe=8Q?7fhxU69Z)VWrc-h!IHud2nY%W$w>-IOM(Psq@+P0 zAxRlNusDI}|5w6nOu#GSVkvEBZ3%zx>BP(n72pR8fk9A7J}F^g8A*^ZpP-zq6dzcM mPfk`^T2`1qT%6#&hq=3l4~e_A4FL!O78W32W0O^vBlv$eq5ez& delta 6568 zcmai!WmFX0yTw5P0ZEaPltvI{hDo|Rr8@=$NnuEdp*y8hDd`YI7#ivBZjclZN$I=( z_sjjS_x*6sr?Y-*@3qf<*0avK@49!qBHBt?7#WN=SSV_0yq`#syuv8qW(s{1>;2du`UJdoz?^$#=mO<4=ebmURckWRr=TWT%K1-rJT3^Y65o_l9?pHxii zwI5<$+3g1z(yCQws0F9n{<~YWx*Q?H#rf|EfLdC-||V3G}-9-u?$>B~N40+bpgj!-x0MEr_`CsJi|# z@%49GN}p0jzlYu{wNGXG6IXXTpG05W*owWlyzcM?cYS8^^t`*dAuam7+H~pR+k2|{ zN_(?Z$|4j0EyZH+{_5B|TPp=`*Q@bDB>n0D)2)7Q1=-E(-KvAS;x^q(o>a8B@B#~9 z8^e{gUN%=aHIBtkcg1wA2(kGulU?7BegE{Aa@~jpjyL^6R(?76mK5~qGR*q2w=$JO(ZfJDtgH~nM zry7_uW1o1=?;bB{OU(v|pwP*EAB;Ot9tb2^Ic7k>EtQ(O<t&tsZ4X;qEqJAO) zw|gSWVYu2#rZ3TDCdBahX0+~C$}N+;db|ih&xp;8e%_`vzlrEGx~@>lvMS4jDNDPQ zsw&q%X>V09V%$HPdWf}(9~rRCfhX&>r^G*!mziWu`_7UeOx9(K6448_C2{loZuGiv zI`s|p(xYRF(0=aw^>EY^1kA3$M?2+3a-o6H%&QW!tr?$(@s_*i`+!(CJ-A z*1?}=v!;Jyy}aW5uh40KiBY$LFnFgz20VI1q1D|%La9^2xf|!>&&{N zS1{-p1~+Hy2K*{S^2VJ=sWPM&G#mUn?OS@~Hv4~DGo1aC!p`coZb5Agr^Cz?>~C!7 zPANW3xgZiU_9pQSaqQ~I^4Gf7O2i>O#{H&xco|)WBVSiDqz53B(-Zf7KI|Ky^5z0B z45v@xEo-jwNB^I}qsn%TtOOE1o$SBDAst=!%^MIdi#y%uAFn3pzqTc3;%kICW7o@5 zl*?q8ZSb!9EwvLM5+{&w-Pqy2Q4Y7!ceD+N+pdMo zw6>xjTmY2sMQF*G?AJciL>=<*hEmh?IO@fN3eD-m2AJS+dwu@h5{D7+ViBZF;t7mK z#<=qhs?=(@80h^!BHwV*Kb;dX+Ky8(L)7WwGM#A60BKequa_wA>{dI`pchxbo z6Jgru+>1nP5d}OW9*qiqeIHZYs>(XAnniSvU%QY3-Uv%nsmZ3Om8CABFVcvf_H$J z*3GDWP&RevE7X;7?o^MWq>9d-e`bx^x)d5$kJr2we13GZYci5g#-SvlA8%2vRe`Rp z@a|{msVPk3`NA0$xfN&-aAiD_!Q1>}qct?*CeXq@wD^_~`BMg%em()b{FrR|GbsVr z1bQuu`fRu-Qf*BV{p!*!=nxK|+wG()(65o_V&c_aP3Gr0Q#^1oe4`xo>6z@f?k(4; zZ6ufPpSt3NWTEudzl2MJ&6YY*Rc2@d-hj4_$~FgF)CCJ^4HwLE${CxV&Y0x6m+?*j z1J?=jxm(a7g69Y5&%MLb>qvHoWIgnlA<(%kdXR5Ls!Om*o44nc%1?Tpc$vP(m0rP5 zHQKw@%YC}C)fvc-T@*zxI8#w4C1OfBop1h9_B1GU=KZ`6{mM2#dgW@_J}8ThlY>$l zYb}z9ZLD3j4EQXYq4>MCKCxP_{>5jk3251zGVTkT)-@elw2-;O$ZKXCss>7b`|>MF znV8MppXHpmdIKnXpie`-3}O~{PQB+_ncysUH**Wc72EclsTGA2@j{C+zP$H znqsO=-zUJ2n{eJJ>+ah%-i3_@qn_y$bE>}3p0KUHV~IdEP%FR=)ukHcRO&PBqs}Kv zl$pZWj}OCc6?vm`iHkx08S6ZrjzQyDd46wwXS-glgVd+exFd_>Io1juoJ(2gldZP8tL&2cLC72Oq z%k!>Xh~GH==unlj-;Xf>HMx?sgF1Xh`cKThVR0*$_nXv?(^SkfM3$M=inpb<4b~ECfONb(FkdIgF z%wN!#xTuRbAxCOzJudrc)2ZG$r#yiuATe?i$wnlla}P@#Y6S~wuj78n_l=tP(QY!R zY-rcmLMnQvl4*wmK%E8ItgLX%a1jz!#U3jRuAzbt+hBkOqG zFvx`BQy9E|CLfJ#=HULXZ=7_t<=eOr!{!@W=1aGr;Zw53e8)Gu%fZDcdVfpNSvcxv zbMvOq%dPjq`W{h+q)pWq$4USrCxujz&1i&+d*M(EVW^cu{Y$s-*?2rd`)@9Gxw#f*GzWtF1N03tAnkvy1z(ob+pNdBa2^iAjVqMI^@+b~u!r z9yp-YnR~&WN-im^-rcKHnt&S*a&Md~p->NczcV$R%JkZ3r>vg#04U0kK=U>#J#I0Eks-Jly8-3xLv9kmdW>eDpKDz26~j@IKKQUxUS?epw3)m?%hrXM3LYo zO#plpYd%FyOrk8@vmj=?;tKf6JhI!QHV5E3G!(VFbqNpzyz<>STK2$%n(?= zHWdvC;5l}xIJS~Ykfs3aEgp42hn{~*a&uVF9%yFiDYqvi9>#yanxaQ-2HRpt2pFm6JHlrBiywAc`%P+t;So!FqE6W5;c@j? z93FfuC%GYp+$Y$?UX2wfE`@aN7}$N_%RI`U%t-P==H}t<E(Na3TFiz(kBXU?1luBUhh9qmillhDg9oe>JQOC%R5$W z#~t9iq_53J*9*!otVq%1(e%&ok{(PPOS_nhhH4^=G)1$fULYuY3c8nj6QYy0Kp5pb z2ix>EdHISyk_u`1Sk>?F6)?@aIohjLTMEYNW{pRg0`Tg{WAq?_DNmn=#*(Yh=8R%t z;)BQn`J+J~_L?ARA5cIR>sz^{cf-E8PF1}K-EFwk(Zq48(IfQ1l1KX!)osV|xm8gI& zoKJhUwbeUbX`xvrJ65g->`y$cG=P!EfhpHmH8#IZ06X?ZTg3_NgGM1&n#mK|G~kiG zbE$x>o?eld${@5qauj9wV*Uq#(FcQtu{l-qEu~~{Ld+EVdp%lT71pBaM?2K8Lhd(v z!1B8Yp%xF1V?Q*L>}^-Rg;Vop03 zoeXEPo2E936rp!M8H;l}=51!%P!e}NKm!Ihh>42G+!5UoABroLV+hC~FZ>|2pA#CI zod0PN;9g;oVF=hZ@37pa>be`1l|nt`5aUhTSPJAOe)^^4u7>tv(A{xUxzlfc^e}a^ z+Ef*FvjsZP9a{1$jC*6_*tQ{;lmf3eRp{&~R6gttn;q`4T$=I=cGSpE?^oh*zj00w zu4PJ}I7G`8hjM^t+-?#IOJe#%9mQ&#ZILw?&7_h${QAh`9!$wypGG|s22lSgs?(2e z^l(QpP9u*S7h`Uohq*hJ(an!Q-Ry}-1`ICwUDwsNJ35N3w(NC+B?+Er#Bhu{91K>Q zR-9H?`R{pSdS-<4e%WHpD!co(MrT+zM_h_mkN;~+SFzT-?6VUALac% z*!ntU9?KL|q)UC|phY!uFl|;!l-@*Delz3yBv;lq@L93_AoV*{Fr;Ug)T))8o^tD& z>W8mgml}Uc^mqaOc?-LRI~~Y}FQ+Wj>-nr3#e0uv-f11^UuaREE_UGgDCW9Yk=@~s zJ=!Zha?YH_g!TCWTcf~&V)yy}6Fwu&4mq_@f!&*PoF~#gZ-c#wJY270W8b<`eF9YN z9Td@KZyI3=PXz>BJWf++8DjP8T^(hqhbnxgg9I9VcvhGA;BXN$>TejBD};~Jb$&(9 zN|1+dgMRG$(g3s;xURi4F>JY6$Fnrn!aBTbkC}F}O>AVLr;TY4T$-4tHU4b4XMe!I z5V!My9Ue5ppEy89ha-T1K@#`KB+%oPn@|$pQQg0o_5vz)eJG%z{acgaXD0{#v9LU~ z6^AI98u1%YTiZ`WQu&a|fwCdd`!G&&?uh~~E-T@%_07FYbNZDSYufGSBd77HF>U0)OYI?6EfQFV_&6@gs5KBq*IPr_-U-u11PCWEnZSBlDsXh4kB4s~W zjQ5&%_}Ov{0i=*ocf?Os{LWAK&YI4)olsTDDK*_WA7xP@DjH&}4Mbw!w)T}Gw&jgE zE{-RovxM;bH0lr1EfT@RURm)t8Wr6MY=ahz!}YHWKkCXU)Y@AaqZ4+wr_^c{DDF+w zG-MwRK+@#$8f0v)rS>yAa!Y#?@mFSzXVFyLRoM^TZknvc&W<)}gBL};v#PD84tXJ8 zs@jcQwJQ>TSRjF)=ehzu>rF(Z^oF$_KjK|DT`aFK*e4Vvc^$W)Y1u$BSTAJptM|+YF628tc8-;{8OG(l!6=tKRzDkAgV%7+&Utd0RVr4V$}xrtUh2%t8md zz53amqwfU1+SD%jUKcTIU0LcAcLO`N3k%vW4*6?a;2+sM2}>06Rx4sR=xM&?YjhU4 z^FCck44_a#7X@2Ovlqr6%X&{>G2?P4-n#+wACq(K$g>Ndz9!Nd9`WIzSy#Ew9oPLc z8Y2{Gr;W&cjQF9N8ajkK8*1%Hd9rYWmiL4Vk_5rf&dO?r&2)laIIn$L zBuGuxEC?btmtsI7G9f;xk%ARrT5L0GvBmOdxP&p0(i^O*@oQOFRAlDk@h_#D}+b;}Hi*lO~$jd8;Tlson$0xGI=UoblPg z&HR#uAUZ~WVCYMy0Lhb8@7F6r!lcx^&&51E>z7jwQ3D?rLsQI2hCSSgoE?+$NNM7- z7VQQ!zAZM6!sqQ#KP1-##EMwfrMT$O=~L#rOxE_a<^IkufT8vfMvC?hOfo zBqLs3`4BrH@rOa$!ks{Ij^li4aO(ye4AyLE3H)~=GHan4Qw5(Zg$7ljAs3-BISFn zFc?3Z>FK@~XfoR%^et2OGWk+hr12BGH={w`fa;*2z1lt)8B&HF2RWcbJ_ zW5s~qpLuor2*q(nBO|fE`F9Axhs{I^YF@Nj9{6bN1V?<9+DJ_*i&MB6PjZm_3q@%P zfklahiu$@&;3&1fgyeL0M6{`dJtmhzz0eLo;Cy%|Hljp~dfcneE&SHQjGyy``h6L< z!g!wPL3UkPmzhOmxMyzs_?+??BNi}FTP1f67i(DDNDVP3#oJ8NC$SGh=p{=`%b=kG zkL+Db+P@c-3Q7k>K?b*fuXF~l5^*zBxT)a;uLj(Zitg>kE|wmR7?wXtwKekf_;WHGN& zDW{2C8OzZ*R|Djq?fPjbzX1qeYC8+lUmBp@g-0l2i<(`AYO~ojKL|1I;8L&L7BY{1 zM_SBV-U1SF>ZV_NgBeks>~3^;>8r85U`iIJVEa^?9W2LulJHNp*KVWFzoIEk#skJ{ z5$S2vQKm(sg^^j^_`zat;nk=3l5z<&2l#ra2=5dm%gEAQk2_7+wzXUL#{>zX=Sl%=FABkA~%K> zZ}G|_8KU)^N*lt96jts(xrl%&&z@dq84r26Kqx>>6f%{WK6culg#eG84}Diuu%wD} zA=PF1LY?AE z@DBzQ0D}M5i~jFm0U+$(LIEh~UuHPupN|28frx+Uz#!1S%R!+3?UngYWgr*|`nMSd z{^t~cU Date: Fri, 2 Aug 2013 20:25:26 +1000 Subject: [PATCH 44/80] Merged commit disabling FIFO in L3GD20 --- src/drivers/l3gd20/l3gd20.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp index 98098c83bf..1ffca2f43a 100644 --- a/src/drivers/l3gd20/l3gd20.cpp +++ b/src/drivers/l3gd20/l3gd20.cpp @@ -333,8 +333,13 @@ L3GD20::init() write_reg(ADDR_CTRL_REG4, REG4_BDU); write_reg(ADDR_CTRL_REG5, 0); - write_reg(ADDR_CTRL_REG5, REG5_FIFO_ENABLE); /* disable wake-on-interrupt */ - write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_STREAM_MODE); /* Enable FIFO, old data is overwritten */ + + write_reg(ADDR_CTRL_REG5, REG5_FIFO_ENABLE); /* disable wake-on-interrupt */ + + /* disable FIFO. This makes things simpler and ensures we + * aren't getting stale data. It means we must run the hrt + * callback fast enough to not miss data. */ + write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_BYPASS_MODE); set_range(500); /* default to 500dps */ set_samplerate(0); /* max sample rate */ From 4b342c4a1f4adf47fd34144992a787107ecc539e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 8 Aug 2013 11:24:27 +0200 Subject: [PATCH 45/80] Hotfix: Give FMU its own interrupt stack to isolate the interrupt context from application stacks --- nuttx-configs/px4fmu-v1/nsh/defconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig index 49ccfd41bc..d338161296 100644 --- a/nuttx-configs/px4fmu-v1/nsh/defconfig +++ b/nuttx-configs/px4fmu-v1/nsh/defconfig @@ -328,7 +328,7 @@ CONFIG_BOARD_LOOPSPERMSEC=16717 CONFIG_DRAM_START=0x20000000 CONFIG_DRAM_SIZE=196608 CONFIG_ARCH_HAVE_INTERRUPTSTACK=y -CONFIG_ARCH_INTERRUPTSTACK=0 +CONFIG_ARCH_INTERRUPTSTACK=2048 # # Boot options From 7861caf482584afcc19ad235bcbedf26386c05dd Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 8 Aug 2013 11:24:57 +0200 Subject: [PATCH 46/80] Hotfix: Cleanup / revision of log conversion scripts --- Tools/logconv.m | 3 ++- Tools/logconv.py | 59 ------------------------------------------------ 2 files changed, 2 insertions(+), 60 deletions(-) delete mode 100644 Tools/logconv.py diff --git a/Tools/logconv.m b/Tools/logconv.m index f7c291b48c..f2ae6e5f37 100644 --- a/Tools/logconv.m +++ b/Tools/logconv.m @@ -16,7 +16,7 @@ close all % ************************************************************************ % Set the path to your sysvector.bin file here -filePath = 'log_second_flight.bin'; +filePath = 'log001.bin'; % Set the minimum and maximum times to plot here [in seconds] mintime=0; %The minimum time/timestamp to display, as set by the user [0 for first element / start] @@ -111,6 +111,7 @@ function ImportPX4LogData() time_us = sysvector.TIME_StartTime(end) - sysvector.TIME_StartTime(1); time_s = uint64(time_us*1e-6); time_m = uint64(time_s/60); + time_s = time_s - time_m * 60 disp([sprintf('Flight log duration: %d:%d (minutes:seconds)', time_m, time_s)]); diff --git a/Tools/logconv.py b/Tools/logconv.py deleted file mode 100644 index c47d22a451..0000000000 --- a/Tools/logconv.py +++ /dev/null @@ -1,59 +0,0 @@ -#!/usr/bin/env python - -"""Convert binary log generated by sdlog to CSV format - -Usage: python logconv.py """ - -__author__ = "Anton Babushkin" -__version__ = "0.1" - -import struct, sys - -def _unpack_packet(data): - s = "" - s += "Q" #.timestamp = buf.raw.timestamp, - s += "fff" #.gyro = {buf.raw.gyro_rad_s[0], buf.raw.gyro_rad_s[1], buf.raw.gyro_rad_s[2]}, - s += "fff" #.accel = {buf.raw.accelerometer_m_s2[0], buf.raw.accelerometer_m_s2[1], buf.raw.accelerometer_m_s2[2]}, - s += "fff" #.mag = {buf.raw.magnetometer_ga[0], buf.raw.magnetometer_ga[1], buf.raw.magnetometer_ga[2]}, - s += "f" #.baro = buf.raw.baro_pres_mbar, - s += "f" #.baro_alt = buf.raw.baro_alt_meter, - s += "f" #.baro_temp = buf.raw.baro_temp_celcius, - s += "ffff" #.control = {buf.act_controls.control[0], buf.act_controls.control[1], buf.act_controls.control[2], buf.act_controls.control[3]}, - s += "ffffffff" #.actuators = {buf.act_outputs.output[0], buf.act_outputs.output[1], buf.act_outputs.output[2], buf.act_outputs.output[3], buf.act_outputs.output[4], buf.act_outputs.output[5], buf.act_outputs.output[6], buf.act_outputs.output[7]}, - s += "f" #.vbat = buf.batt.voltage_v, - s += "f" #.bat_current = buf.batt.current_a, - s += "f" #.bat_discharged = buf.batt.discharged_mah, - s += "ffff" #.adc = {buf.raw.adc_voltage_v[0], buf.raw.adc_voltage_v[1], buf.raw.adc_voltage_v[2], buf.raw.adc_voltage_v[3]}, - s += "fff" #.local_position = {buf.local_pos.x, buf.local_pos.y, buf.local_pos.z}, - s += "iii" #.gps_raw_position = {buf.gps_pos.lat, buf.gps_pos.lon, buf.gps_pos.alt}, - s += "fff" #.attitude = {buf.att.pitch, buf.att.roll, buf.att.yaw}, - s += "fffffffff" #.rotMatrix = {buf.att.R[0][0], buf.att.R[0][1], buf.att.R[0][2], buf.att.R[1][0], buf.att.R[1][1], buf.att.R[1][2], buf.att.R[2][0], buf.att.R[2][1], buf.att.R[2][2]}, - s += "fff" #.vicon = {buf.vicon_pos.x, buf.vicon_pos.y, buf.vicon_pos.z, buf.vicon_pos.roll, buf.vicon_pos.pitch, buf.vicon_pos.yaw}, - s += "ffff" #.control_effective = {buf.act_controls_effective.control_effective[0], buf.act_controls_effective.control_effective[1], buf.act_controls_effective.control_effective[2], buf.act_controls_effective.control_effective[3]}, - s += "ffffff" #.flow = {buf.flow.flow_raw_x, buf.flow.flow_raw_y, buf.flow.flow_comp_x_m, buf.flow.flow_comp_y_m, buf.flow.ground_distance_m, buf.flow.quality}, - s += "f" #.diff_pressure = buf.diff_pres.differential_pressure_pa, - s += "f" #.ind_airspeed = buf.airspeed.indicated_airspeed_m_s, - s += "f" #.true_airspeed = buf.airspeed.true_airspeed_m_s - s += "iii" # to align to 280 - d = struct.unpack(s, data) - return d - -def _main(): - if len(sys.argv) < 2: - print "Usage:\npython logconv.py " - return - fn = sys.argv[1] - sysvector_size = 280 - f = open(fn, "r") - while True: - data = f.read(sysvector_size) - if len(data) < sysvector_size: - break - a = [] - for i in _unpack_packet(data): - a.append(str(i)) - print ";".join(a) - f.close() - -if __name__ == "__main__": - _main() From 36679fbb39a57139c03cce85d7d0fbd25383a98a Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Sat, 10 Aug 2013 11:22:08 -0400 Subject: [PATCH 47/80] Some DSM satellites are fussier about bind pulse timing These values work better --- src/drivers/px4io/px4io.cpp | 3 +-- src/modules/px4iofirmware/dsm.c | 4 ++-- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index ae56b70b36..5089ce3c7f 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1445,9 +1445,8 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg) io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down); usleep(500000); io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_set_rx_out); - usleep(1000); io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up); - usleep(100000); + usleep(50000); io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_send_pulses | (arg << 4)); break; diff --git a/src/modules/px4iofirmware/dsm.c b/src/modules/px4iofirmware/dsm.c index ab6e3fec43..b2c0db4254 100644 --- a/src/modules/px4iofirmware/dsm.c +++ b/src/modules/px4iofirmware/dsm.c @@ -125,9 +125,9 @@ dsm_bind(uint16_t cmd, int pulses) case dsm_bind_send_pulses: for (int i = 0; i < pulses; i++) { stm32_gpiowrite(usart1RxAsOutp, false); - up_udelay(50); + up_udelay(25); stm32_gpiowrite(usart1RxAsOutp, true); - up_udelay(50); + up_udelay(25); } break; case dsm_bind_reinit_uart: From 1d408b80ad70bd8ea873ce7215c8a92a62461b0f Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Sun, 11 Aug 2013 17:19:54 -0400 Subject: [PATCH 48/80] Support DSM bind via QGroundControl --- Documentation/dsm_bind.odt | Bin 27043 -> 27123 bytes Documentation/dsm_bind.pdf | Bin 34300 -> 323311 bytes src/drivers/px4io/px4io.cpp | 46 +++++++++++++++------------- src/modules/sensors/sensor_params.c | 1 + src/modules/sensors/sensors.cpp | 12 -------- 5 files changed, 26 insertions(+), 33 deletions(-) diff --git a/Documentation/dsm_bind.odt b/Documentation/dsm_bind.odt index 66ea1f1bee22eba9943f6077e7fcec6c6ef6e182..587a38883bff56f458ed0feed62a1731b69a4459 100644 GIT binary patch delta 5385 zcmZ9QRa6v!qD6;J=?+QhQo0n7ZWwat5~QV(7-%Nb7 z*Lvske4mefcF`=#)htS#78>|U@fvZA0sx?)0|3|n0Kmo0%Zks>#W@bBlCZ)^)?@e= zT-Ua;!Q&F@JXzh!rwi2o`=dX0U=9;6_h`76e~@jwIAd+YWDWPvtlGL=FU;RXLt`W~ z2|un$71F}CuE}tTHY|l(Byay}ZU;A4O4w~(?>2Crq^-f@7-qSK29DuD7tH0?(@?Z; zBR3Cll_$(C+VKIT@F2~{ZT@0peSE47m|qJ>s~X1mvXM$qbcA~Z`pFtWu*W6M8=IWm zJdvRZu@Jo%(ttPph`jWZni)!VKDlz0r=2N2-9OeKcXEJzBXuyl(owVTmfqeMV+Nh# zr6c;z<||^}8*#l62Rk0;SI9LVQfcCLd427xgGPMCKo4O6zYqHr(Pd`s=OW}dy*ndY zb!2Rg$i7d?zUoa!ps0b92<&!L8HH#KTs?2!+eeYEd}-N_dor@=rI<)Mql@a|(V`vn ztz@ZJBM1*Zko(6ok!wMh<8(RPVeS>tuowj&=ic_C?+0E>fXhRsyixMyI!niQ^?f!V z2+#yt7prPM&A`asQn0uS_2YwOdwnct_lgt}YwmUP*j5hKv>e}wLmeA!vH&}XJyMPN zmiukQ4ZCvyb}w&aBIRbdynFQWv2SOZr;n-w^?RE+NL|!nAu*ECR{1%hJJ2@=>*Kt=BI|Kd#Rt!Zv|&Qi*no6td6k@0)G}R z2_89={C*Pbc`v2jGV@TtE^q;J1y%{8Qw;))u)M+G4w??pH1nEbAXaCJf74A*js}~Z zU1NPcL?v5YuN15dbR|jHR?*|;YTiHG=#&X?Pe|+B4A><{UW>i9 zeyG>H*YPkd<0E`bc4fb&{4%ZKqc3Ug#2H~4X`$@_G1y!Era!-F1ZFQL6`4D;K1=!g zjX_434VN~<@uaY`Fi$a^!`V6I{Pc!rJo#T&%qU^yGfNaE2vf!@(unBCujhY#>L{XH zdhgPi`=B0{en>BpblUZ9!~@dSt8Xb!!>{?xxYxzSTzyEY0gFzjA^(b2kwVJQ!q9qA zv-%u|K3HXs!Vs3R^1B>$XC-xLf7&zaFzpY=D^ZBC25RitBe(jR39XA>L6xGbm*fdu z8o5Lwr|Jo5_|1=|Y<1EJUOTHC8u*n1*OuBB&Qhc&)5OIcbN1@wR4d6u47T6N zK?$IjT(>-|@N+t=qdEgi?Q785s;Arxr6X_U7(XqvSN^BN5N(0VuX&1>mrFi=8Whc; zM}1=-|9eZ;AfzR0(4{5o?rn;Dzac}}B=~il#&$~%_(t)^S(vniAvBr+-v~5#S5Q(r z_LC66AxxD{iwhO<7nAYyw`h0>0TDslDDLN#u3_(Q7zay*lqG2M;P#Y2v+t+_bKh4; zvjSI*faIK?$g@zAS{vM%-UhE#2)$a`|6zzos#foC3;5c<85%s!B{VZpH65XC0)|Ty zmlCZR;8qDLP-C|*l|S-bJI9`R%QjkGY$2RBiw%uSyGab*sLs-DI+BR22PtD?CGXTY zImWd8ODp<=$w6G; zu}Mr!I3F6`kjOFAByiFBiz3^dJI{@>gO)1e2OW&@O(Vk32hW?}Jm$rSd03Wd?Jyyd z;-kdcEMW}kR-aeqqYI~d9WB!`V$4U_a$Sz4o_9%} zGpCZzGV}7-Ndp5b`2stC#;NHO-XIYTBbZd}m1o|n9~%_$wbM`7wbb<}3^~`P#^xym zfiQ+gbUmYgR^@_VHE5j*3e`Q2F{_D<(vUh8x{7F_uW7k@W~+6ZXX#N08(YoEK2-A% zF$DjI9JXuh(N8_yo4yyzjf|2~4;@bm$XsPQo9=54T64z1YsQyQLJ+kIDdoCUgC>hi zOF)|c{H2}^+hMHPhG+wtvs6F*_Y$@DlKNLtoBUasc;&zWud}w&k~pyG8APxh9^;j2w*eiJqunUXtZ`gG6_6#U$3<`ajpt3)L@DjB$fc2wcA z=@RbYW4mCCZY?>?wJ*UxCJ(5S-$ntH#WlZF3L3*zj7mjG_+u>J;F8W}IDG@!s5Z5U zcrSW}3vos+20kJORtzt&updG^@cMA1vK`%kMNnMM5clzelm^AsA^Z*#8`p`l0*+8% zF_mpdBKz|*T2bzP0nsET>%#BpP&Y-`^=}?H+Aa7)GzEXczfCFid|67GTZM`O;F2 zH_n4%is7y^<}kYN)8mh5i|aYD8B;pqzSL3yfW+4O3*O7;Q>6ghgby9GjiYZZDjz?<}CFaKOMu3U!{ z+Y3uZoE0>6)H0Omii-NNLQ!wtHT7M;q}P{JBffQxUnoo@UUF32-|I)H4CCRG_&f=D_y3)+q64>sEa21=&Gg>?x|jmRH)@Pzm`~3!{aQ{a}J4z!BT6jRKK@325r0lc9)xoJL&pNeiMw=@_|J8w78+i}D!8SY5nHi#p8h=84a{xH1a)J%!LQEKbt2 z_=_0|rD`&+geVi)jYKEfVnljv&+D(e1V1Tgq(TIr9SzPady{}cSESZ9MLjs?3n8V7 z39f)JGtxz&y3{)g!|~RsW|8&m7ecU{(%1{I=^sA;0C;&p18A$Ep_2hH|MwCw0dNG{ zu8gn&fCzd302crNczXFe+j;(n4abbt+_uF?did*JWVLO+A;PRB6SCr`Phr*+jTxu1 zHf2}=rEiw^;!~b(9`!GnR1IeSo{qA~pf<+96K?n(5R+QJCBOlxrNEA*oytnP z+~Lx>G{;*AGGVfp!tJW6v9LnEnzns7&o1Ky`CJS3FY}euAMq|3oz)R(IXL#@?Zn^8 zcIBnp>OrRLDiykX~HwTHgWU^{6c$S=DQtL_OP} zW0|W4wQL|2J^pZ-+Ub z8^sh&lZh0Ue=zB_H`%Q~vz0ga#pi-p{`ub>M+)3A#lpU_^O&!5 zZ++z$^Tq87enj+vTQBEW)PLf+I-xM@+t=Y~v}GJ{hbG~YAGP#vN+t{Y52%M`KBGf! zJ#mZN!jJj4Sdt;W>Sy(F)4`BXmFjBrTv5y!-;s} z^Zp%pfUQ=;s@00S%PXNYQa-tpXLS=T6J^@+3$CQDN|1y|5qBH>n(Z`>l+Li#fF7en zcG)OLU!i0)I|UgmpqQtmT<3wajU7R<$v9lr1>z?z<%vr;zF@R7G3w5^l~K^nsd^4x zEvY&pb_b~@Z68!~Fx)EUWyhqJed!P`JOqKQwDH0acQ>8^98Ed}?4bo7}`z^c4 z2OKxMVSh!+9-%)RmK5jiW}?p8>GPwdZRxglw?+h`XO!qNsif!0`oNQHew&W8vo2YUe}IRk_U4f^^pZG z5eZiAA_%)AM!Az31#k{q%E>e|yw<_Hf9Q7xJ>a4$x_JX5)IO%BkN8@ts41!6YH#7b z@@3Cm=~@tEVZ)|oVBgYy2&UQh@~}NpU9oMuNIzvuoQC_?J3^F&S(h=kN_iw>9b1dO zKt(T;$gvZ-uqF|y6w!K|6BHF&Fvqbco@Cp&CSnXtl%++Zhtyk1L#b8^O$nUTx%qnJ zFtdP&hAMK32R;`bK4H#Mtx&+sA9bfy_%{*izUJ5-uGYTo*m@+J9qIe3PRwGOo{P?| zVwW&$g~q$)S#8U}1s_Xs-b(x+Ae$=fWGGQ|vXe74DZS*&19aYLazlTvl6y6qpDh6! z+)s0jPbKW}TjjW()r=>d0}VW%--z74s}nyD=O!rwmf919NAq56^~Z@S%$&VovqnbW z@OG+P_n>hlIEQ15i0|gq`-k)W0@I@7=qkik8LCg4I<*elh(}`#-Vf$SsJe@b{)N0A zB+7=W$-H<~uas#I21kTpy}{q~pWtcu#Od};ZQ~);*FP872WABcvw>@(qQpFIMFo)3 z?&#CqY)Av1d<^$9t&jAPkAu8LpkpV%jIiC|Zo*w_55SZxDqMt%;QP*f#S`<}&QZ_6 zV$SDKH?s4ES_~xXTZy}v;l#U>iA!VS+-Wg0f>)x9L1A#YRP9_VL|}@njZR+8zJ*;w zMp+F%^_cyw5g~3H6&U$lK)f*l2tJ-!WH7bv3Vw{KD2tw+i$^|{K4ZAmqg;izH>SRJ zp1|4I1wh9{nM{9Yxsb8eqs63nShQL+4=WSk{^Nd{d5OB=BN03NgmB=N>?>0`P1&56 zj14cWQi#e0mo>jp#2;vig6wVS%(3h7N?l6YS*ptjhQ+@!1J6139b#hBR7F$d9!skw zBFJ5wH9>kVsu9FPl*C(*Z?&l3?@D*LEM5t$G3^}*T$6fz@I_}(PoF8=L~CWxNh~?& zBnIB!MNvM4$eW6VDEJG8mv7c9r%g*B7jOBqx%HQByxBH_HRQzxW7YX}HUq+LH2+Yg zN}5%2O>U_=fF0LYUCvtnK+7B)Kl6SSSO|J28Y%MxFuWu=V4C8Mh$67<{4;Knar(9J z410aGCK!a6RS1|FEjy=rEHiKjNx+r9wWR&Cojf>kGTd`HMw;7TWbfB-$!{c-(f_D_ zIHD0as)|n`7xClbaNwPfC63llb5_&Re^_~~QqR-h`oNW6s&=eq?}1KaG?_b`XivE! znE_sRBh0!gr=3Ap9G*Cg)WaZI5#fBz<;8w1giJ8(ElAy%5{WM&6qDupEiP zCDuQ#LFW^ClYt~%&5`7K-|5S)d06;xHD~-VbG$|D2D-cW!OvuKqF@rxPi(O|wWAoN zNO&I0O7(dIh2aDII4fuCk<5c|WN9{Zz+*^$^H<7={V2}=Ny-$MgAxib1?Mvh?f(~6 c|4mnl(&yK-|DRd@8+gjM&-9oI4*zNX2a;lVrvLx| delta 5307 zcmZA5RaBG>pf%tT7`jVoVd(A->2es5P6v^0hOQToM!H)XM7p~}Mx?t#kQPbFv%df0 zKWm+Rxv%%dv-ZWzi=vqqwJ=m5M4P|Dd`3C-9E%#aT?9YI1qR`ev7pfV0&X-@v1eV-eAs zstQ#@-lX6}J=>Z2-4$fSL)1swFs;G{bUQb6SYGzc8M~jP9hQlq*fjv>J$s=@o}QgqE8`kScK?&A7z@I8*zv#y75Op4~8+WV@G*Mrna;zDY+Fo8||% z6jw}A(%imr*?5imtsr!$F*f9{i|FKNlEcY`odVT#@#+2{luW7--iy^({ja>FVV(9I zK~2PU14eRhdL8K~o&k)hNz_7~lRABl;^E0CJh`;I4%P)uL4=zl`8BUy>3PyK%&20G z+}qp<1G>fgeoGS9--RWJsBe zNux~dUSG<;oVIqoe%ReKNQTW{6>_8uNpm`xQH)#=<`pi`Qv#T#FG1{$_RA)DmKfbj z)t;xDC7LL6uk?f`u8~O8d*8CwgcxS26-j@LS=y!_+Zh;Ba@;32waipWyevj6;o1zI z9DHFXEDjwj)#Z{{EQ}%QvsMUi12OBe&@?OobG#W<$gS+C=7X6T?RETx$?rRF>wLgD zU5ViV0|a`0ZqNezXabfWQ*P6+K%iy_2!sOyfh?Sz+%28l|J%W?(VElBC|Nhpq}Qw3 zmn&d~?xVx(pCVyl@2w!iG?itc^y8Sir`@DO`qoHkm2{&#i4)k}(-|ooYS>>~+ze z{R$h^z;lOsswF=WQilo3#x9|%V|kvw)j7uL!-UkG{cTs#nrLNs{w|{gn)a1kcd=o0 z#x3SP{nYoF_j_Bj1zz<9=!SMXFW#!t=pwy}xweB$Kk^-%rxyw|#?_c=C?X zsI~$n%Gp^q5u6SlS>#>y%gwpXIAzuUmXzvmLTNj)y@foz%BjzoEaHCy{&t(_P2}hquBUw0DO-63qRdnE zv?tnmcW{8sywa81@{J#XSx%f%KH{4uLSnf})|UXsWeKIuA%`{2yBve#RLMTkCc^J* z6!ixi2=)9T^F97z7t+yZS^{*vFVM1_OkRKIa%cckt0X$w6pFmQu%SWm3BQ&4?#;kl zp@I!GbYB{r(m`+to7oa-3SV|6P;n(vI<+9<(8xFN^r`>B9qY+bCyDE(8mC{Wakzge zDldU<&bOGT^T*1x?4|O5Ag(DCi{V)WXLsZyntL}cY_54@M2IOOy2!cwiqy<<;aA$x zQt}imuGgGLr=O*UtPS%ToO=(z5?(nx(i4Ddna=e)Cxl&PujznK|?qwZL&EqOqka{^_|R zYpS(U-ECYw4HZR0orP);pv9U?7;}?SVnJ2tKY^xIn?9Mh!YFYVo6{AcIhh-~fe`@7 zYPx*s{?h$$axhU(oNxFPcq=kQXmz`tI5QL(5H&%EUAUo5 z2O*hRs8}N!C=I5hDACSR%7spBH(a!RGYE@v*!88(^Ix=^(_urW4MRzs>je0v;lT1~ zX!YsLX_ftvF#Foorx)*ti{2yA*IKnG+9?jlO)SE+!slW^M{$MMq18gavqS^~k7T|_ zqmLbTwA5s5>5+ythS(-zst!aVGdKL7=}l|E0;_&_N)#9)RC>b0^|5fOceoAFu2y!5 zDnF_+XJBkx;?M+5=TQf4Pk?ia%rUr_&Aw#(fUWZEXG4AF+@1-08rf`~0Hv3`E~y-B z={<*)SJPYXzR!)ZRPz+aDdDO+V!{nVFcT6+Xj}u8{N1Joqi)Zs4`8WjuT%fj z&0zh=#<4lhXM}ak1hA==Fd3SxZdr!DK!a68XDowSBFMenLd}(@urMt!#_^j5_$!d) zciDlo`wKBPYe)6^869YweXlqyJ6Uz?7d3OG5^TANGIg3^y)sVlc50F3!pH>%3H?~tWaB%`eVSO zSl$}FL)lW$5gbMMss!ZY`|~@$G{Uf!L}FqHkEBeTP>2sgO8Z0gK6=2@9%4zY!k=24)f z=raBhXU2;cEe^A3^a(g4o@3`p_lw9alggNb(@6_D5#A-m!EwX_jX~9>= ziML%1l*j$dudh@h88f|Qc*P(@|NGs$QcP44)_16Jgl(KfFW*J>R>jnuQ%K44dUAu_ z?U%LAl^43oW|Xy1J7>X}+(?8{?9s~kCJZ;qf1czW>mB}LJI>w+A69Nkv|Nb*VnHLK*urP zmgF5IBg=guWL|7=G}l)5w3xO)OvgfeNLwE*w2u!doKENUSoaKT+5wg`%vj zvL&Bzl^v3Fw_u~q_(7>uH#dJN88se?LVMMP3YFe{iC)o9u~-G09^45P_D|1g&>oB0 zolz)r&oF5*+7128OQ6!eg0*z`ua6bN0WoE^fl3+@>4w7k5M1al#OowJa{-;Tf)8?! zVYMjgw6oyW65YE25|;J}r|Q|_kjYn+`Rb(FYYNkl&9mC3H z*$wc#BGI){VN#8gOUGfj@~w%d#DOHTa;2$Uw@Ed=)XaYBE8uAwqtY<-={(I271gG&i9zQv6gF=2a@3gC2f(h-m- zrM`g!CGbig`niyske=E&D`Y`2Kj>Ug;@e8uBN!7CSR$@)Sl7*HBj_93Uov7`e_FSW z4)Poe-a22vQO57S_phD%=-#_TNB%bUTgg|tvO#gZ!qOYw)fD|ggk_C?#Wg;ZWYUF(un`t~$z zaztXwTxkMxr8_+lZX37yR3ocpU$BOfq5sEls8QArrvW|h16n9v6r-16>i`BXYGL0t zsb_K0UxT?Kj@F?k=qiP>XtmR~uV^K*%Ne;kvL(o@qK80UrFZ+%})izEfk&DqGWMs-XQRXyOdLGOM+i|y7SQGC5 zLXO^XhD_f}uq~1c_>r*qZ4BHQ+ULs=KKH}#(;QUoMuK9hHn#k%gkS?9@rJ~2RCEwI zlsdI$P{m?NU^wnEDBJbLdAI^QKo0ocYBjqoh*8eqze>qQ+fb!oC~M?d-@4bj&LqE` z4v$mv=xbE9zx>NtLlkCzCAOVo--r$Wr8oKR6~17tv%{bEw@*MH}402Pq73mzCMZW%i;U#AxX+h0*ehYm637t6KWlfkmo2>uKV}r8`8RQNL&UH4OZ?Z1tyA&5wox^t31)xGDNqP*K*9vL z1qS6&)Dy;UUYCiHjHl=`O56b{@OiS4?ri?T75`j9H(^lYbn(9pkVC#@}3buK_D z`m93>J~wj4&YU%xNubvhYM5@#`|}ynKVaEU3cyoFX_V_mlHBVuif|1+{rr2g(ZAPA zQmvAsk(nn($lN>_gCnp`s@n6&k?@LnzU7#C>K?ybvYworbw33$yhqed`0PQ*s6vKU zZzimWs9Ix={l!TBY9FBbME*4b*`~E{$s0a-oP&DTV!tLG#(#}NEy-$*Ie}nK6gs#- zZ$+zC_u1bU13%DDedTkNk{nD-278S4f8=)>V*3DW8gZQi(W2S3?bIcGi z*3FtrbpY=u7hrOk9&ex5YYu|NuPP5zc@bk7nnjaKJ!{yje|{BiOCU17l*}4mZsfh| zHP)LEWQ9&c)m}aqG=oPdXh6axx#XAjx??PL0vkqmQ}KlXK4HM2Md#=f6Slu|?Ro|AC$~y<-C|V}Ea*vg$H_o*>jf#4t4fhzuN}5G zOju60rDldAh1Op3XENBKrM=DTpc--)_hz`Vykw!<1V4vx?afqCARa(~)vO9c+(WTX)9-Uv##e^bBpEnT` zJ9K!Mos=VLw8FVELP`a}2U3<_HfGQf@p2^Lv5(SBKgt8grP5=`+W z@W*ErXgb-@0_VqukA~hSN3X=2Iu3xysJHf@%=i+0cj`}APCseL^4Ho(%G|Xcd>ps} zY(1|dMXK&^hZi6gCxul~1^q8Y1ly(xrcfUkR4KiCM__z@*Ba*m*lifUj&1wQ#Xc6g zY$r?EAhG`ct(Z(?tNa3*Y-kIi`oAyJ|E4)P-IkW>|C;50dROM`x8{a^DxQ*#jS diff --git a/Documentation/dsm_bind.pdf b/Documentation/dsm_bind.pdf index e62d1ed830316bd893f05c269a7f97384f94c502..76155569e396b715c00ff62f95dbd206f0f88b7e 100644 GIT binary patch literal 323311 zcmeFa2UJr_*DyRG6zS3hR3cp|p@Z}e0g>Jj3?V=$2_&H@5V4?wieN!OL=;7oq98>S zP(e^Z5s(g2Y=EesfYh9SC4lAL`#jHm-tYVV@Bi1jvsQ9u_UzfSXZFmTz4w_pN6OCB zTtQh;jgw8PtgNhzlT8_+gdq3^akA;^BAsHwut*a$8683hK-!@Luq1>ELJ8r3+=0di z$YSvd&W>9VNJla;0z-BpVzCYc0vVyAL`Shf6N6EBe}b+qJ&N^1kckmkeSM^D1UW2% zjKY(#crwXzt(IS*NJpfFlcSHFskxEzYK92`?}sDf2zZnq7Ei|chKNn=FTgos6x2}Es#r5%D6Y|!`! ze>8?1LBtZZQD!D|7{L!4qP zufRCjuy{Xu&(Zqmw=Sf29nyplfhQwWkk&Xqk|#oyRtll4NxSSq=>Jljmh-3LNINtU zODj&pM>=3hga{%AOVZUvniKG3+C>?mPR}z}LC}dJ%~cU}){y3E2xT=|p1wZP&DJ*v zi=h=jg`xwn${Gk|jnynWA_3!wC3_<6OwEx_*l6+!it)_)BiA= zNE()Gc*(CWj%epX^-RStcjo(l6VEL9R>InFw)=V2#T(iKf->3lV`EQe<{R0Ek?A87 zBVHElkY$LpUj%vrK!Q`5y=E*2Z}Tul&adp0nYimZ9ln9^ubs}oRk>_Xd_ ze8;;g;VyH^vCAjK7(5jxCz9pLNS~f{>jvM-xVtUF!}ZY4gksN$H)8TwxAjF|vwAsC z&u5rewFd8<_}+mZJ@pnkl1bSlwkyqb8p9|w@=lcYJeNRlEhnC zj?E9>3{RfXF=H<7#vU4d;OO$?(7kn8$gW4nv!sLBqj%phj|+Y*AgX_rI{vog zQ1|7?tK7rE@pl{IW!Wx7I_@45&Nk!fklaTkaH5-%1mvQ{NllUMqWf*lpTXl6lBW;O zl{CD6UC0;vK)bJA^x57{jikxo1P%w=$Z#)$wWj2e#DWs+neD7cwNw;z8c&3ilY9BZ zEG%LsHEBrV)DWx4uwW9995bBsLo`p_U?O9d_bRhLC&kw-JY=Y8lfJ2d%yWahYYTa z#&d%6(gzrJeiO8(^q!t)j&t|h$iKU3mfdmF^Un#d0q^1cny7dB#N;p6-sj0CxYi!J zE^pf(lBl7)b+RbleO+=(&_T111r}Q{aYeLOwzzx!bA^Wto2+0T{zgQ}n7Au}}_v5Ru0`+}rTJ0fSBCf;s~#xgLQN{>W;eV>m!MHYUE zj2mv!@)&m<{0=vGDHiMFGkY^l-~2-plYXAq*{!d2zP~%~oj9%B*~GNWHQnQ2C1Geq zxohWk&rNZ9YZF(Z&(}1pW%gq!|7;Bhc-C(2+_~{*HIIz9$bTj`aTkc5ZFTkVR}L9< z{%}HrnY#$(qj1$%tUK`#&;9h+rk z7}m*BRhSO9+N;0A7SLG4>CrY%X>GvpmF7Wm1x-{}EZT4aWa9YERTQw4$AZH0bvG zqR)h(hkhV>U=3S@UzO6qG{h%zQk?1<1?eXM(@5_QvjiK0PHoN2OI_7pUL-}`VOK|TF7cixic=Fy;n3bW5 z4ojT8x<^enIikF8HhM^&)j?24ZTf0?b>4UhF0!mMD7ElBUykkD(Dc5G(rU%0g!Dp0sSS^w#%r(kN-Ck}H2dO|&QK0&bKamWo* z3jZDm0R7@yE8Hm*jP9m8+-V1 zU+w1;d|GqDl}ho}`dq>zbpiuw?s|sT3+f+`U5liU=A3iH{+Uq5fR4j(lhpFKM{R`Z zEfYJlu9P+(oSPL3J;9Zzv|}tvH=|bQN!J!_e{(O}u!KPwZw<^I&&zu^pF^~@KXm%^ zkoB^RCQr`EAgf1d8}^^xspnH;;XVC2lT(1%+Yb#9zJC26D!KHPMUr7o>to;7ebJ8L z$GB$%GehOYC2OAE-De-*vM1U4?mg|Ycpxd@%d?mxbLgWwq@g^Y{V4*Kcr=cOz2GGsHKGr_X%XHBTz-S+~=ayiH- zz9`!3%Atpo=%%^%N9FtP8HtoiailavCaT*`$n5Ri)H^PSIlJr2NukmYSrIo2p4YPt zjOL5%Iu;ffSdlVNfn5|-byj&acKzPQ^Ik=}C!@^I=nCyK;6H;lIlhV2(-2?0H6ZXp zik@|F>6gcquAVB=W6yh%k^&1JJHi7>H!KFao~nK$Z+=Sh#W8!~Xteg3@LOh&zvZ6i z35@AIe!kFazuIBh-H+K5Yo%{F+V$;PCVoDcDL zV}}wuGT5-r>faP3w~N|dAAxm57tbF+YeBmBhixgC*w<+8d4 z=cQF2y0#!|;vVZ9yxkLY6{c_?zwN-;JQjHw4KD?K!0bs2}U+UOwfM%{Yb$s+3w#ICicHW2lwVmM_6_Wy>;r*e+kl zU2S3k$89brQggRy{H~}u>T&*e)BDaW(@8t1gO$Q^aZQFkoKcKddXn7dPVCF|zOVy( zKL?4bevsX+sXbjRVrce!E0=oE9`Ok!$qAozkgmRmU0*%Lo}aI{bxUQKDZi(^x1*WN z$2V7epe;AvTrmvl%sZ0YaHoiGX^Xl{sEpW`z;#WQUj4~F+7S@^LQVWzx+1)$v90OE zG~IMf-=muqG_@7!7~xB%*%(g52rL~+Q{s{4%1C202}{Q?GBzA^73&0Z3OI-Uv^^{YcXanPN#8A})+fAR_3xEz%rEB#})5(L{u*3UUW} zHLk3zg>=RFkpoExwN)MXrw&g8{E6S6gz5Frnf(_GnunkRNVMuuWON7)V}uU~!6KB9 zMkEYPi`P_FqFER8xPpqh64C@6W{IV>jGko_89-+Yp{}BYv_VI&B$PE(l<4)ku3)Mv zDIwifOVMaJlChyK2z3=Yjxk+3S5Q}0rdNPaR#DQT(cXoiXPe_fuqp^Ox}or^T22G} zsoDQZOe+6MOn+NEbaU!oiAP0cO+4zW*2_=v&@S4cpNv{M3Y`Z}gfh)Z;IIqvQyz548i)U4^8Vo01Z7IAmd3WqFN=W*%G8Nq zfiks0hyCCcY3hnlR#H-;Wje-?$kWVh-J`XN5LOK4@$ zMW`yPBiC*&D(XlRnm5fc42{7eO|g+U4A#NI7-@_nlkBiW6GCVh0Z*GLT5G->Qxm6E zPY%t|M+_s-d^-q#bO`CEZ%0KI>T02nSYtkHz&T!OE~!7x|}%rN*WU(CPq4&(jFJ51zP-WgzPG+^QkKWMXe ztkV09W2hVY1UTqi`a&fNb;#$wo#l^)>`{UwYDZ=x22tW@2&pJQ^m*6mQ zz`z58^T411zzEo&dYAzKFeVs1tTqr1U<`~*%q;6z+1O!!%!C03_*&+A0Aqx~85kLu zSeVx_!8uf6fPn|jxP@1l$;ckfCmx=l!pxtVbK6)#Qo!M%uc{hxf2#?LRGQ=D@Dzrm zE_k`*fVAl;CqJ`CSI8PdZO$XuucZg;+9Te4GnYA?d+5%Y`d4qKua-UTcsJwXADMXe zT6sg~`&ms3*MO+Q>3J26T_3*l00ssa10y4yCl+QVbvg@MlzADA?9t)kd`v0{sr)n! z9y+v6s!I9}6ZfZ?I0|4$YEx3oGzM6t)gQH)o^rY(2>k|12E&1hLYMU^*p6;)6QL}(Ro2XPLJT=YNd@IJ*_8Zddw~I%8Reg#!)Ns7eq#< zi>n@fT(&9G|1j;9bzC%~Q?TlhSL>L|cwBAnOhtQSi%XJ0_RKPOn`BB zl5qKl72(0x@9Z~?6Jk;AeSh~xuayHzGVOF4O7f~?8fq&_GR?{XCC^?p=yQFbB3JwC zpjTUOzfp8yi$9k|@6{-eF|B#U`X@~{GBe9PF$Wm$~^8 zva2X2dl({LT=shTzN}pR1jC#^{SvcPlxjBeU zDZ0C`GeVS-RnizbeSNy1cVXFJ(PS3czOb0C+vPaHU@hXs^1!OOF2Lhy-4)3XF6|K^ zx9(s@*)uj9E^B63nYeb`&j?PcDssKi@G1XGxB}C?YCeA*uVpN8ipx7QiAiF_HDUFN=&-lN?@b#sNltv3*`mcI5P$HM-m zsPwF#Yn;n{9-nI-!4V1&K>2@qU1ddfKuMm40Mt6;oZSV1x0zIV2;B62>Ap;%qH0H4 z7Rn{_j3m=gJN4$>qn8O16WzAWT#p<3-4=Sv<(rSrOcak%q!@Y!B4+*iX2>;*=YmSw zmV8GVHQV-T?itMX868|onJe?9=Ij*ndLrl=mpK*wWIC{XNW8fvH~eF1K-<#0?2fEM zuZpk_X5>AEJ#PrwAKn`Rdt5ZTYnI|rzDU{8K+#)1c)Df6>8pOhzNqr2Tn#KFqhQNr z&CfM0i;;uVNo%a0tNzOrfz+QuM2 z7=b{4?BMc&ClF}c8vp;9!txidcI?!?ptcS(CpH%mmHS}KEzEC^K=5+njTpVX z>)&|kw`4B$)qdJ+@i}`=fRuY=%nkD>sdii>Ei)+5VyWy91b9wC!1+k=4PmjbokC0I zw#zQ!R)pL%)K;kNKaC5|Ql+UquPvX}RIyKm&n9o~+~Iy+Cn|OES>vY@sSqIDhQOyz z%G)zh=n=n}``LF|cRfB=xfo}z-m2l>OkjEFzMR@t`&rOn`A*AHl9lIdqa_6Hc0*wH zqrq2HeD|2xcO5b6KmZkGFmd7x1j1CLLH6yYJ@=fc?hIB$vuADu+U=Hc&#dc zp=Y|gvt=xQ`2nxvog3JQ_%nwISJE@h^{(bnv&wIu=tTwl-2NO~zP))*d8u;kl-VnT z$s(C$?;tDmnVIBq2=o*|VCx7)wesAH#(jk^y z%2PL=Iq%|y#N2DWIjIm(KvU}dAkg6}H~!mjNXs0POtYdu?K94<`6E5&58(AoH5&K1 z?b5;K>J^gX1n&{rT+&cBVxEN%=-=V9e6$n-(GD|JgUj`gA<&&^@cocCN=hwk^!Xxo zJ|^VGmCy*MXXASd+A4hfzw6ClmXUXsIkV3d)9+uaH#GS?2#j3LUXmbC<8y)vbh)z5 zWHfshQLmhA&b;lx?$#W4TyP7tvcDXJa*U3`F(`d!U>ZSX8oMz#_nOm^4^T0et&~84+uEEPRmNaU5q*R z$z#Z9vsr*+n@Zrds^IbSzEv3;9#-&=wwBe-9u4dq8Sj15v`^-JZrTM1^xVy!4^F4z zk<_WJZ>GDPPxs#}`SPr!T)XP=|Jh^>FW9WO?p@%hv+mR9Fx63_`r?dx^cJxJ@8Ss>Y0ITcGR&rWv;x;Uc@VPG~ zi7rvgYz1-Zo>lK%7WMXYH&xqGzGb)gER9#v6rEo*AE17>p(KHNW9GO;zmc2p~OQiWhoy^>v003KnF(3j0 zAcH`F1w?=VmS6`^04hKQXaXf*3S0pKkmz|hfCVIg0Cs=~Z~za;bSPM9gAT0%Sjlf~ z;Qgfywqdm0AS3_)FP+mcGJcIMU=rd>{E=`7Aldv#m=N(MKNEQJ&%_Sj5YmsFodM*? z9|^P25YrzC6rTK(v@s?)z}7bivuZX1030lgO#q;qc)-CAf$$?l_!<(1Xj$}NLB#(F zW*qWoJY%AtlQW)dF5wVDlh%)59O8%gE4TwGgiMFqMTZzV{6J@m#A3(B+fE|r(umkJALgo+EIuXMDvRX$>$O_z!h%t0usg^bZ;h*U7^{e(N z&6cOz>-5nnP0!<6!KMX+eXBC(q$g=Mc{CkU_(ys(o$5Dwnw9=fCrE?Jtjqzn)o~60 z108pUj%5ju{{8?4Lj3({7B{`n3MA)z#t(=J9qs|Z4~RM)qVN+!r#VNb5C#DBmjOOX z%m2%)|D`-y-Hhw#b<^4k1AxJB<+s{zG|$HBl&0f~(2{V}5AIjOFaR*xtYQPs^vQ+; zWDo+dzz-+@N?agC)6y?4S*4*l+bP(eqZ< z3Kn_-W%>(kmH;9lBJ4L1Gl7T;z~NVC3Wu2^jk+xz1_0nhN012?SUi@9CS(2R+{c8i zEuU;F$TSEo2NfEC_LR=<6k6y14zVExtS!_lILzn}vJ*PsH!Lm;HY9|$ z{R>61bh6p8ws5Rl1OJB18b~1SF$%#2to0Q4O5-ipzyJUiKde7Gg1(TkMq-KNzd(0c z1OJZB?i)b&JO0wSJS+5#Eq-Ls`gkV+PrI^`31PMoWD@q*fx{Mp^{3tVeur}S63Api z=%3*1MA}ohKY;18N|rt_IcUS#V3HnRfzy16D?@k#9gl_q*r!%!)FqnN5dhc_038ni z&2zT_{Nt(n$5Z!@r|ut5-HMm=A5Yysp1S{=ZoYp!b!!g3e>`>nc?LU<=(Ep!q^zG!u&(7y&;(0KNcA_jCo)ePaYbqQ}Aj00RF30|88cBTxs5t42EA z##r%XumDCFj8+dc%*nNS@(E8;MALRKDPjnr$Y^vJQdv<633Lsj!_b&uEE(a84Zz{` z#J}9D6-VIw^u%4&ZIo=nOt67C%RNM_xt8;YvW1UG%!*eK}R76>xr*ymvFPOLzobVScJNwk^)9aLm8o=rl_o@v|Vkx zJVHfDSqZ7Ef>hE}P*$StnNU)upTt5S5aRlrY^=IOKYwipQ}fl@h<^Th;=i2eic+N= z=RzuP-@YBGq=HmYQ6T#HE0ALFWOTFwo+Lr1u|i~Ra}SPyN6?6(eF+g{J#q21c7%rg zp!}CTwub13`GFS}K@6eS?}tHRS9XSxkjje6KX9W%!)$DRp#LS=(9j>)B(hl~`QKxc z=-bQI&U%?eV)0~&HO9i$wx#?vi67Z?`O^x8X|JAtb0QEz)}-~*vHaWSmS6C(rf4!& zPn@>fML|hZK}pkTZMTbplA5-X(hBO@VYt7COz^|`$NWcBKa93Nff$M=>xtuNN7ax) zVb}nAbv8EIC_IUb#$&K3Q$6wM&@e?D&QDui#mv-LQ%gfj#Z1#oMOk_Kc6DPdHBB=u zBV!dMBU9zIvZe$~1Z`j6T3NsUqU?$X2p#f2qwzy3+H~&)?XaPqxT^RsaFmJ3>RCfQ zaoQyZ)>2Pj~%S;h*mM zufjjw^cX6*{J zS4jMl_jdvhCX7f10A>dOQ1!!-FaW>~0sumy$YC@%?U@q4Z!j&+Kzks{Pjqwl0Dxfw zEgrBEm#5>b#0_b2zfim%01Pyq!~8=1Xz_Xgz>&xZ+G9!h4gf%6Bn}$|0Q?mIKr$pE z6bAtPNj85d7EJ-1I~{<=#{jU>W_sZLlWzM<5B}TCzZqz< zT|xb3PnQ`?u=ywKXZQ&tTn0dE1_1cUpD^F^08|_TU_UD}pwvX|FwrARKMvymalv20 zFMP;5VEwT~EFObJxZto+w8JVt-qeD?;eWGUexdL`EcS=6GOhste7RJ>@1qFTx9|h_ zr)I#&#}43L7im72A9CBl>H=sp&sFTh%DAV8zu3OOkV1RHOTy6~+5-~@Cj=&f7`cK@ z->1L?*Z?=+2f|=8kN~pu%}ts>2N(h~U7A!qotR3FCta!^B`xFgchCObezD zGlT7bIl$auyI}z^JS+kh3p)TyhNZzWU^%dS*lpNd*hAP;SSzdtHVhkseT6MBz!^9g z_!%}aNHZWAv>1#StQnjbb}^$Z3?CV0-~i4J z7ldztE5NnjCU9H02izY{gvY~^;Ai2N;YIK&cq6lRtpvr4gQv)Z!yvBt2b zu;#K>v9_?jV_jt9VUuCgV{>8)VoP8<$5zDln601f8#_C@IQw>Xdv+ZAKK66$x7eSs z53|p6@N#V9FyZjxh~PNEk;n0Xqle=gCnu*gry-{YCzoYeiw-mP#w>S45?z7yb+%4P_>si-JuQyqbULU_cbN$`*UF&Cf_;{3g zYr4ZoqCx+EBcqW5a?lLfA|=SU6RLhHryPv`Sj+R&0}JGV)|k@vD0F; zV&ez_gb^YHaSlxtWf-nltg+UQ<05Gs*<`=h*GXnpE9qqmGXY&D&?;#+f*7X0(Z%ZK>b}tv*F)>&=nd&3^mprD(jPL|Vt_WdY%pRd zVd!Ug&G3WKR-+)J0;A8yO2$OvGUM+i+9q)(4@}{v7N$w2FU)w&oXs-KUYm=X2bkY9 zpR`c7*lY2?lF8EAGS#vRwF!km<)bF8G_B&S>a97f9j!C0M|N!6LEKSg!(d}&bIPWF zr_@gT&I(&#i?TgsJ76bc7jAdYp4r~cKGXiagR(=cL!%>~qmSba$5|(1rxd3?XIbY6 z=SMEwE?zGAF5g{EUDI5L+>mZ@ZcXkY?l|{K4;Bv>k82(?o@SnBJl}b#dnI~x?vmLR zz3ZvBhY79ySg8 z!C%im&3`mNFW^+bSfD}R*}w^$2`&RS6=WHd9rQieHaIUB3ULi74qX?zJM=D|7axqT zCu}A}6I#RM!V<%V!nMQCgijK!iPuOl(k@aZnV%d+ZjO+RI217)sUMjcITz&;RT|9` zjgM}Q*%os&=EENIJy-WK?#1kV6uTuhA$B; z=lhlRr|q9U;Ci6y;HHE74!${Lap-0uS0XX7>#)w@>?4dva7SJoRXuwCC^gA1=~=Q; z^4a92W0+&ljw>HOcN{w5f8s@oM#{yL%qQ_DJ5vo(ucz^(?MZuc%H~x0X~gNI)6-{s z&OAMm5tz}DX`ESnVdI6P7rtltWwl*2yjYaIDLXlP z;S%mrcaB9)`DN+LXRk0{iM;YY*Cn^{s@B!~Ya-W@uPx`{^Mxn~^)DVW|33yl}$ zEt)NrFSoy}YSnG6X)|bh*lyb1@Cx;+sbgnHYo~K(cb8Y!P`6+AXirGbRBvSOV&A@g zrv9XX^#f;LZ+v}uaO+_4kj7B;u<3B~h~r4#8_b)JZ%J>L-W`0;`Tpz&u@Cv9Dx>$u z%*S4idyc>R81`{-BJmT?rwgBDKi~Oc_@#N$ZSvg|aSHl+?3?hnylJ)RM>BRauV+JN z7r!UX3C~@h*P3r!a9#MY7`4Q*bZ&X;auwB@+7E?75Yz`u03!n&4rgG5!{LmKjEqdI z%uGy7Ozi8{F|%^Ab8>RBb8v92=jY+#=Huqz;N8H>Cm<*!B*eudEGjH0!Y?Q!NFxHH zm1JUKV`gR(w(yxPEZ2a&qI<>Jt$ib7+`ennV1+E0f5E9 z7~p`BhlzKKvJo?%J(@*4oL?m&HD{fK@$H8K4y}`ts=mbitZafp8-zuqq-A8cZc|g& z(A3(lZDML>ZefYCa&&TbadmU|!1!VP0|IeDByvP#RCLUq0|yT!9zJq3DecthGiTG! zozJ*@CHLyJyzBWlN=omPl~+{Wt$I{f|G1&?$7s!FR_(PP*QDJYKqo0ddvP^!}kA=TK1!1Kil=&fz8E*B-u+0 z|J#3C)4qJ|^B?G*k0Q5J1HaLD*~!kbf*_HdDI=TY>}uP*EUx!@csHtbhL8@O=RYN^ zrK@zas^JReYR_`9{r&x&+$vhlrIrFwItPtTHMpO5+FKS|H)4=T;UgD{zvyf-58kyc z&fyvJzTT|Io!Qqs zAKuh2L!M%PD0M8&dX_mM^%{4m>S5%8+B40^@4&~IGNda5;l&qjY`8XDxm6OLVsgOI z^+jqd+tjgS()Iq}F1z3^59zF{UgME9GOrj*?}#Kn4c7|oIo1?fw!gSP3M)1k5dCpz zu)e9c1z)@$)>~sN%_a10{9xi5SIYX8t;SG(+y0fxj4- zt9T%?YasimdQ+B_PM^+JP}Na{%uV`a-}Z)6RpXV`Vc1T+n;oOza+2(S{1trR3HC5J zJncSne6Mp!+nqk=f$*5Puv>NOp9sfnJmkG|yZRL`LZbnDkhj`gaK!L{^tXv9SD|u; zTKOs7v|O{?4aqpPaQFpaxkFHuVeSr&SZsS>mRFig^w$5z?|@z!M_lN z`OMkIzZw*X?t56X0rhqYnS4heUIlMwN5QAaAipercp(*4Vyj;B-wH{7?K z6mo&U!FH1lUF{6Z_9Y>C(%5X&ca^6yM{>_j4D8xuY*=ZRcF&sOP=tF8<#g;BN4q)B zDWM(rrv|90Bh|?IE^m#p_Rgrzx4}ZVq5F5wXT6ri&O2qmPkYA z)SqjbS5BQs5WG@oS~7OlA?W1M;?$Zqb;6--TPK`0cA0rg-H6>j)sS;NxYxNMbGUW_ z0z$!O_mtl(jH|J@U!Ej}$TU6jK=;u_^CwqdCpdqf;LxZje+e_=xBKm9|Kzc+{EZie zPn;WUZ?yCQ8p;86GRMF6PEjk!f|#7rV!+KIaY3XS$U%r>V+E7VD-CC~>TR zy3tyMyK0m14fnH)v&ZgCUd$PJBHby|QO3SQL`0k54Gf9dN_{6fG|7ibH9x<}q z1=O>eSH*dwm$=W|x49PUeXm14qWexY{{4b^iKa@jOW8M6TV7JsSLc>9>G9{El}4)P zzroc8a&ttJ?0vY$dtc;BeLtp{T8zJQ=U%4mEuK?+MvURSqhAu*0~<6gDk~RUl0dQV zS8EJ^X+!IiQQ#7LWSeFG(|b`YQB7Z$x{ETBz`SN16){&aoU%ST_)+}E+ph`>3HS)Pn>qn6v&7sI zw@x1%BndRPqp-ZoMbkpx_#!)WOjJG}SI_PZc5N$AzxRnNqU%mIKKQ77Z7D}s_k&I$ zlzf{&O>rdZuJ z+zb!Bx)c@~>`>aKODO28D~P^EDIFInPbP#_MWl^g^fUAA&9pCyl;C#K>V460_sfyZ z3d^~8La{=u0w&)L0)B-(ckdFoC0qMTP}lFsF;6YNY`u0-b#wgpeD&#Ne%O=P4e5`I zhn^y)?xg4!2HY6zi!1!pDOT=j5w)%F`EBNo0dQpMb=ATj7UH{+TODj+fG&LyZM<9 z>~|Gz6c|180Rm#R9dnx0Mg<)R7za(W0oh`yIS5Q0nS*8sZ*3cUK}?fahwldy0};m~>suV=+~ zEt(Gqzu%|l@$c@9l@K_xSxbN8lwkVsq8MB7YpD+PV9(4a1=Hzwj;FClCP=0Bjz>Gf ziY{&7aQi&AFZfom!IaEWmgWJ0+YAy?}C7-Od|y5HeG_i*B2>sZr+LzxXkwk0!v&kDf0m| zsfJNS=MLz7NGh1--2337^kj8sZiy&!2lmz(#T~(SJ8Z7LdS~e!zxztty`*mtI5POv zt7anvx@>GAfC_&3`z@x}VD2ddq=beImQO^9EucF-zLaaBs!*Pq&DlZ#lhsH)7qJIS zv&mlGNBikQ;LZ1iT4o4zzssYH+IS~;?^<*U?5sgdb{(1y9#h0r+@Fff-gum_J;{u* z)?C1oD*W-G&$Qr_CY6&L0(^#>QjXP#Me97yC@a4@vWZu8G1*SQ`pK}AS?I8o+3r#V z-q=#u=#yRaf#K|gh!$?o(LLFTpYUpn)_03?_LUYrl@7q&bzuoU@7I6u)9!8wfx3?n zVAK~4%-GR;v2-MkU~~KM=FpDUm0OOg7$1L82bWB6DTF`(1mIrAr4I|E(=6Y@(o8#u z8zLCj-+{gISdyKia3}dqiA3Xhu0Pl57Z$-;6%@ZG_#G>+@Ap4l-XRP>wahus zy311{Ov){++Gs;QW%%NK0SFio_$Wg!Auy!|`{?AF27x-gXgTWs*U}Jpm;-^4KnNu6 znRH!dx^Dx4111otf5}p4?`;hMj+vq21@`Dn2rwUpz|kvz?Apy`W--Vm)vo=uqY5L0 zB@r>Ibjn;nF%#vbXZ_%un!%C{*wZ2Kwsx|`n+*b&Dvs7p22$oS4E{gCR}2J>8oV95 zFA4!)!V$`Jg=vA$@67v0n+$(W9x~`XRd>LmszcG>j;?6Yd@cUoxAKYV)~Skwl$t0=KUG337=`$Zk$-ipAumJh_EAXs>vRXJ?t< zq5JNXpe<={9Qk^^1lisb%M&gK4!-*)DIb;A;$uY{w2urH4I%JyemHwc5CXIOls^Ji z2lpSr|KNRe{y>$4z^QAKgyo|(TOiOjzk3FLi>w^|zj0nmaVz7bC6u(cbe> zXR49Fld`>un+aKO=NH?F4gKaV-<2A#SI=FU9C;pLUN!Y1fqPc|BOyN~;}~WltyE>3 zfx%Y!6UyVqm)m{h&Qtk=n((isQ|gg>hv(mK-tbC3;Pwg6bv8Zs4)u5wQ`AEGxQ3>x zE~nkqb#KMT3yemcdL2!1pDIcxtDm~*X3L>1io)tBJX4Z?d%mmbeik@a)A~I=SLQH*^J-h)llbQtj>Br!7i$86t5s6I5O~xxRk6(D!$%o>2!VPRpM$ZUg>zSCuTFlLZQNgG z%ekEXuNE!0N{VRQ574^9fyEa({Rf&`4t4F&sHoB0)oFput@Q9)w?4Zy8KdJVs zH@ZJwzl!xDsaENAVvC&F%fd{1W@5NM2|+;0dN^e{v4whUfAyXfZ87R$?bn!#auB$s z4S`WX^$F)UHJlJQ)jZ|1oX`aU!`sEamuPI(XMZKX=7hj)&3c0c&&#ftT(jp+QFmrO zteusfI}8D9vej=&=!oW0I`Xi=OuHil+B~Ld&HoR2uIAi)6e0IxEw`@O^`~!f88S)l zDqks{M|nnPTfVyF5<)s4KPA)gc#qkNDt@mbx`7#9F=Eo{S;8qU=T2HzbyPl-B zQocIXY=A&_2n0r-$aP((d5++Xv7!)=IX_an2rs54V7woD>kJLf>$V6$pnDT#nq6de z8<0CZcXU{cH|U~9YpnaQ0ngZ;oq4%q-+RMFijGU?Fy0zK;Utz)`yV_TE_m~>-(0wI z)FPa2O3oTIKwv@E8$jR@?{^5CeMP}65g>5+&=B|179?dpbhTUlCgN=J&=-+`=sv3{ zvE#AsIYFU01rR_VFrS?6r99sjgU8|sikio(84i7@-oyC^$IKrcHGh@%qBMxD|F~JK zmHg^u{G;@R7sZ6D5A`Ov)ifF$EY7t`H2A^A$l7rxO_R1V(eB;SgA7JxKMm|0~2d+5vUQWI+Qyb#BqRDY=KouLrq2dL5Yk;Jdfg zbsmoEBG*WZXQ)VzvHN^Q(QREL|%L@Fk(ZA!;`FA)pt>6!S}ICpShlxhi7Pq?;KX31WiaVVt$3Y}lXFdvsN9{gqPQy`z2zz@ULmZj z?aa>#Cb)mmZ!5aF%_^BcQC(K|dH=-MtG%$kKh|Y1EI3yP0WS2;Zr8{gT2;; zo}(Vt(e|;fVu}3KACDWq9~xw54LG56l`*`ZFwfeLIXZZP3E=<8K*bP+IjEO#OlHdV zXsrG6-TbG%@>`-Oc-v$z4Zi2O?OyWu-urtVzqOfQ+R_UoCTvw=0z@a zRgumab~kVG7FNhj3DhB`VRSO}iXW#ijArxbO4o=^Z6uLG)O)o&v!EZ>Rh48G#dFfM{J6@M{TtNlt!h7MV{UXd z+|G?vY!z~vE5=bq545;x*s2#Qb+ zst0qzy{c<*u?8`DxL%jSw}mO$;W$Q4`4S86tfyrObA;0$@LGMN3$}I7HLd0pvpJ_f znNwdpCpWY|pO!yP?t67qTG}*1<(_J(pv(NZ3^2N+lW$TG9pC6$f#MZi4E*ftt|aXI zN{Ms7d01S~vfmuiZ1d*HYgsvpS7PEbLJJ~W`v>OZ$v2V&tmgxdUVwdfaw+?_^Znng z1^>76C{Pdm-Qa7l_Fel50R3}UzrBK(_GzsD{B5h%Pg?2g|8Mn#^7lcEnLRQL9 zNNg;556}M7;z!WB2Ks61hq4dK^BZk25#$$tj=ry}&o*?H8mFzl@P1dp@~M|M(GCl@ zE51q)60?c#WL_)i112i!ZPud9?e87wsZnMXl!WX(=IR;v8%Z1@K32BhMjDX1{c7kp z1!dJ=v4)Y+1Fw=^DEr;cW$Enx>;hMaHNK}_b?afoq+xKhNmZf$+{R~Trl5qWmPQLP zWqi_rndsHqPtpbgYj0b4Jl~DEgEaXvun)IUQe1A~+O1MSeedHS@>aS|_m`Y3K?lo< zr<)d*H#joB6Ok|}a9xLhajMp>*X62|eB;I+L#a5Rc!Mx+8P@NYD3rW zQSW#lVzM}YLN(MIPC*tDCq|Z%vs!y!|m_vy%15= z%UpBd=8a>|n~q+StdqQafnfD`K0(ZX{Ne+oKx~eB_PDy4@wx8aNunV-ElGZSUPZ(s zBT@WJ_0W6$YyCv**>X_te6Zzqnl18ZY_;oE6JvCqd1&25UCvaGT=67ob|yMCS$C}Xo%bctF1>P@*ZCg9 zngN$@aMD!0oN;uqVV_ekkck9BV3R#RNs^zP&dw>LL>=Tw5PN{(gk9@wR% zQ+yT(vkO;H4L*h^p1_6Zcy)(-G)C=B?Z%&_rrh5?=G(=7DL{y@#PM z6be=qYw8`G>>8|c+nE9q+WPQVdDv$*Pn(bQf zUxG7?cO2d*<*N&kM&|o)*&xQ%IMh`U3-YbiCcQ4$=i@hP2J-ayiyRbk@OefSl#0%tqU3I zvlFv4bQt_Vv+W20x6xQC7G@o!Op(tpvZXYwjH)WH1F2YMz|_b8rXlPIcJwP&9&7#9 zB-nY#0~=l;)h7{I5p#}Uq{&19T}m5ADWhrz=K?0clE+x{>(Sw~kz=i1=9*k&I44tI zsYQBln~OF@le=}(BoiB;Y+^2r_VzccA<|>2&(oZc?e=BP8T!kvN)3?#1CjENonx%F zVY6G}Z>|Ou$waJ;E>Iaua^dKRFOWAK`@JQhUgI*FI!IPvS?5P4eN&4rjkoC`e!G=o z_I90HZ!Z6x*8OBGv&Gy%G~zU2opWa}Iv3eY&8&4F&~t_n7X>~|G&(iuo5Ccc_K4{R za!8?x=p6!kQwpEw zZN7|vn8RPyEwB`p*%K|}h1fQK9v@_zY|m8n5q+9%P7@IjJe05%Ei~OSWUSJ7w-S?f zaV1N|N2#PH9{~7{c^&xW{R*i-DD~S`o1hh?@ApE;GGG=XV5+54JW2=2m1zKu0TbeA+)=izRz}0+9eQ1OdK$zt9@Q97GSq2BZ`O zA4Czv9K;Gl2LvC40fY{O9)$5%AwzSs=eJnN1lXTnkELU!r>AFOVxb36(=n0K(UFql z(@L1@{4Y7At;}_7fx7=)^}kP1FL0axG^PGC9w)7gxrwfXmIXe;3uwn5bL}%)CqBbZ z6b&&Ie1;d~2Q~cPu1e}U*of&m;xqhHWxu0?3YnYRn3>z?(n>xPK{K8INj!f(OxxUn zR#q2iLo1@IrK4;0lYcJrix)LBF*MVaHPEuq{dw_&nVGqb*0WpxNL$$$J_B_AOevaM z8Ec!H8`J)J_x43%ZJ?`b^K7;at%MfP%KW$VGvJTSZ)pL;XB^Yt1hOWEIxmY4o1b}q z)+1o3rEjHWN-JcjZ)>IdPpyCU*DqH~+L~HF!(TGI;4I+N<1@ZMru;LM=Zjx|m5}}g zjVk-o-j}z#f8H!X6J67n`|tvEgU|4?Fu`Yd(TLCZ0?vZZ_;Ua78DDN1KI6+B!)N?i zfbj+M0-y1xEsQU)KKP73wJ`lG&h)c5)6e2eKZ`T{EY9>&{9jCezVw^vKe0h%X{GS8(n-WU7)U^ovxKNIsUWbo^g%-w9;pfytG0E|DTNf&p!Se&VBLY?+`dI zjsMMIFRuL??Zf}s0{Xvd!S72@=|4v5U*3nmQu2HF``?s2s9J%Z`4 zl>8n+{x?gQ|4Pa41MxQ{KZoqUbtbWA#G=1a_1ucT+bEX5Qu5!76~JF9`IqtWAKlCP zS4#fT-#Iyd_spM;TDHGZ@;eIHZ|?n5CG>wa^j^Zx-}UStN`As2{~k47qUwtlmH&%? z_CEksFH!LCTJuL|`FCqxg6QAX^2cEO6D@zyegD+Ie~iXI(emH)+&_lnpJ@4Sy6zw2 z@lUk;H+}byQS>KT{?U0=@EKkr_w&^C|MFvg8B{EE&mH=of2=Pi|B^AiKwtez{p*3=smx+n)_le>Kb?;Xv z`t{`$e5RM#`afeWZXU$fW);eT$x1c4DuH-GL<^$$OcDg(0N<*ZSF3Z{=@APGh%v~6 z8KmeRWn13fTGl70Cb#D#e-B^4wIZXAVIeqCV{{&{e04q=*V0miv6sedtT$c!*?4Gw zE)0h-zRtZ|Iyi6bmej5!JFds&QyJQP(TqCU56#iB|AQ$iP92bw;ebQ>&^$`tiI6s{H z$hQ#l4G{@?9xvJ(H%aTK8x5B_e%BCD<;Xe?a?)GWNhG(7KzuH%bS?Zsl#w7cojF#d zzQ~Vmc}?g7xk1ENK${4Bl=oxU1OnY}<{ko?)&<&`wdSzcAw1t)1+$YK5wn1<-X)B# zTcwu1>(k-<>My(!KbjV!BeA_BWpZ~VWp?K*9@Nzu*0SiDe^5p*MI<<$C%R~Tet(DD z9h#mYH6az}Yp2d~*vwh}p4F8{Laop;Xc@y^=K(w-EjXFg6vubnD}DU#b% z0QO)HIqb&auh|E-5klhTlmwwrf+2*UFJQ84`Jk`hE;9Uf#^!Dx*&_gDQe?OFf-;8WQ8Lj{O-5I#jSJD{$ zk|LxHb08SNR))H+cG$a|iqG zo^~NiGJ(X7J`OEutMP*M^+ZlYE+D^usM^q}>)OtwzU!bK=(sCE-7UOz+c9=xBB*lb z?HvKzt1N@R_Oc`BoV$gB6gJ$s98})h6=<}z^-s3tWnCIq-rIu19$j8S3O<%$G&w|M zD{hfat`^z{f%m*^TbLX26Y1cytR|S`Aq$0N+uh4o=X)@5PszuR)m>VAAfixr0=5W< zxD}(vrsEb0_sYRZR!oi9AtCq=KJ@XwPV3;a|4RI0AN1@(sga9oQcS^>><%GexLr>t zOVd>G9ML|PQc*A8$1G~_LfRaZ-vFe1T8`Hncd@H*GK(374KmDoh#aWyuaaw=Y59q>Nfa^Elg_&eWDZ}X>$B5| z4%RP-CQ-*b>G%Yf=H8jDF=%eR3im+o&QuqF&6lsXUE@^Dr4T@%?+j4Gs%AbjH_ofJ zJ)1V$G$sGoKvNWWU>v_dL?K{A0D@%|-NCJUA*7&D%Az*5h;4?dCqF$s{F!2o0!HAK z37%3#`}F?f+I+&>*?0tts?S)93Lj{h1{~PD@wTGVskQ|DYzJ%H6i2eF3vw>;}Wb&D_&W8iJH1gjJU8@+47L% z|Ikt8tB(<-d{rVXiX;80;;~PP{muM{vTn$?U2jr4ZBF?F|FIRA_owGtxS*-xKiDwB zNsgu4$!5`p=bf|yZa3#s$L1b!8!97U?x8hUeM(}<1d3zN638<7FpKg?va6@1-B30Z z16?3CC}?kjJI&syDW<8PK9 zr_8v|3TN)46%Xm3_KF-gpDuPW&%&ihzi6;?8M&RD*ADTpH!owmVumM40m-JDEp|O_ z{PPf#+${7KD!$l5#e6miT5 zRW>x#tU;J99Lq*-E-fSXv-jyY*Y}9l25#N=DK}u7<|9{$c!>+TZWd-`H=gw!n|Ftz z^vljtUv3Va&6t-R{RdonR$rY_we;D7#T&Pz8Z+T-FCE?9S3H!CTpU`f*_)&dR3LF& z${!>x+Ap`nUs4~)?(d{n9&od)GmI=USTDl^yssKc50>^CHfPo2&1tzOokwlgE4*pW zzNsL7w~yfHy-_=uc$m<^3xvcNvN8GLdbhiz^gB=`WvH|$ zeLb$5CVo#TzNpf&vS@u)Z$?kh+fjC1Xhw*pqbZ|eYRay7YHED;hY|Pm52N?>o88@z zieSUcd3lC|(^cS%UPZ5cj({XoJ*3BxH>Jaii_^&cIbqWgh0OpTBwq%0a&~|@0y&~@ zgt4*t6=yf#3R}vHda^4FQlWKKOoNY^yd)!L_;B=roU0_`ftQuM0v!C~7eGd0s;TE< zcy1et4LXsC;o?=^7+5|S#AEh}Oq3KMH6Z*Q8R}u-R@|_<3p6+Bk9%0e3E8+; z*xsyqqRroBu5fz@bkAgWGJLo1WgGt{ws4}c#+AA<>FuGH^` zyZk>FDbzqNL)dK#Y~*8BXV54m!I=tkjM++?gF1m6_ zqAeBa+fm#qyd|HOkT5~Y9%Wyq?n0CI_PZb&JWcy8pU4W1i8iV9O}*o z7nLzqtmpa!t#%FRud%2gF9X*DWiax}bLaYY2cyQ<)-peSZRpgKSch4UjVUeo5fm%~ zgNC*#_g2CEgdZ?-vufVAHBrCpQw7af-mx}+2S5MwE{YQ+IWT}i^NkR1_ z(oAl1#>zSZJRoj*Ppg96%DruJfp*eF5S~1Fpg0W&in(|V$HYPz z3pzqFJ39r1LQY8N*ql*~dL0YZ2a27A`3VpnD6yPO)hg5y+uYe8wCYX$=qjNsRIa2v ziGEcwD!E+RZ9qH~S)=sSTwx`>Zdj#eQd%l=44Za;8;zi5EUUU+b@rSBR@+-trR>N= z(%AKn`<+J2(hHqI*$^U!TYZ8O%^a9C!#%Sm^s`la7UnJVc@(ujc5jOn6-)589ab+k zOE!ucz5*a>?_ZJ1o0$)Har8sZQ(8;(?R+KN>9d~+JJX9rBrRpuN z-)$Eg_Drk_{&;q)?$FRauk%4k1)d>GUXuIrb4*pfq|yq2l(x4kN3&;6ahT!YLp91g zC2avUoZaG68WI(~;04lSPYPD6G|O3Myqm@Dt^0gqDz@v&)$-!|!m5jJwJi;MUpkV8 zpYm@<#m+h4rD#)Rd$lfMCwB+OQQmcOU}HM-@r`RcY01Uty~&9;n6yjlVp}Ienc@z;u4($M{&@Szur=7F$c*+)>>( zl#gM{YF&gj5j-B88I>mZiF*16?47JJ6C9)#f;vzMNGDIllvG$0y)l=P3vq+G`*zl( zd=` zR!mh8O=*MBs7^K=yaVG^Dof(}zn=zCPZcRD+TF5L4clz)AP-d-amUSIWXY57khdqs z?FUga7b%t1(EqET^*!wk`3WSQZ`)YHg=9kKmi`Z{F za&ijN35_LXw6(N^lA!)kLp4s-d=)PH@5*T2NW8byp<;^3j1=z@%rRyS9!3X>jFz<8 z%C47&vc*2$L4^^;m=zRnn_C&Y!z9iVv9Y^EJ3m;CVL8*BP>Qy-FkWZAu*57;EuC^O zN@UoDny!_s(J`SqDiDDn?5*-618Qq4e-w9{Va7@mr!eYWo}F0~S_eY!Ye6~}3*qW7 zSq$3@f5SFo1+uSeLgr18?)Bl!n;QixBoz}Er8mOr;%bgeB% zjjLmNozdEK>3!JkxIlF>I+IIHW$kWTyh&)sa8S|SY4vN;#j$)P^`w|sOcmQ9pzO@k z*&#zm;kiHxw?h2ewA3WG-JOG46Z_eH7Tv1I?lwuKv#pKwUdWLw4E@Q(Vpe3MBpP-l zfm4EaxQrPH(vQQRwFIzo&k#2wshZ!ghY)F1(~pTv-U@JiGK?PByopK%$FRZ=Kv zbVbFWp|+M|PFa$3HdXeTmxaZdo`ee=h*P~g6J+Xn35E~aDi6FHg+8Z`x#tbJ2#%H? zL%r7Vl@U$$4LOceJlmq7FcYx?iCwf+XJ;2Q813>iE;jq-S)Hv79qbpu$0CA1j;2>S zH5_Xa%$fGo>hmN^w8ULVqkd9BE)g)5WI~=Qw^A0>22wlryjh(8sMAATbcP$zr@*#p zLJec>lIUcH0uE*Ze?l%eBz>-omqYNbrb2VOW5sm@SJ3NWWlvuI|x zuprAkDSqYQ<&DfIJI=gw?gq>>S?W|<@DD%VQ12L0*8q$gtOqb~)$c_#cE*^SO~{o_5y+$Nhnw9Rh&;04waQ`iRYmKxe!||`%}6_qH?Q+ zd{HXpr5>z4WUjJuhlQ${6az-X?~O|&6ryy7Dx$7q2H(jf&PIrY1Y&^f!ZQcLYygJQ z6mb;I5~bn<(JZ?9@3nQUzJ6uZ5CW)Pxkw7R+jvH)EHI!=vFS5imThcOBwG6<)>l(E zTep+!)T;|hsr1Y#8p3-X1g)3^`b%tBc+?KeB0ztwD!6S+t&d_WA&GX_pJzZR&l5j6 zDM+^LD$z$s7P7#}Boj)`>Ftc2jg!K2Vk_6xJ5H8cFAZHa@2hxc)?8!z;KN2!P=Ei> ze-h@^9(hMo*%k|(2N z>zDKvl&5O)C^bsN8?Ms`zn%9Z-bv%TK5W8yGb1EB$ww0MwB!uQ%<~dn6^U(GfO2ky z^m;|5uus@4Vr(&Q3ctM=GNEn3ZBbWs((~u1ic964B+-OVE*$Ne5KG}~D$yQ4J)=6W zya(Sj%Os_PYJ@{W&Hk);fNHVVLFZn$h;+7>#(Re83YLV*!EM(cE?G&Xrj8aDCQz`5 z@cN5j{`{9Alup#wv3*+BG3<5Y34Z8N$Q)^fDP>+^1-JG0amk(Mo1H8ymM94Lb=Bt| zB4WnK=B8`;5bVBFAmEJ+C@E8{F>SrW}VaIk3|Ybzyc^$v7?AQ-Yq?*{ofmUF zj`PfgUEH-oXXzR4q2>sN0Fl~4Hm4jT`k_96h+-inZdh44VMXto?*s1pDM6g_qt>QH zSw+L3_7qA%EP1Xr46BX5hI|ZLDv;w7jqVsT2p=ijX(%ir zfg30iPBa-i5w$D`Y+zNd@Bd0cQ$#_U$2p@tRIshQwQbrz(T#pFPX^Z1di+r~sxL;K z;)nc?oE+VF^IW(QRj2s#eq3LGY`k@eP}u}v!)V%2nK@Z9I+I}f{>CADVlO~azjs(@ z46-t#zq}7$7UOiQc!<2A{(7^WEyuy!A(Gu)W!YNrm|=aJl6$}m;rugs^x>Rg%`plE zHuxG4Y?#a2L4AyUM_wpz)@seDR-S0NcTbn1?f}e0{DC!LXOq&3G1#WI2<)pAR}T`ZtmTzvBe( zA&^o^s@-yN6Ce3SQ)3acSLc#~uLG4Gg{+cr*$UM;nop}kZvz@_O4T0=L-8UzQm|{% zR7u1A0Q=bnf*}mUQ3*PM@)SU7(ZD!X;zO8)l)JP~kR{@!Q^F}D8nIe3MG_cA3UeVw z)nh_Z&SpO11K#3!MEWr&mL(e}CXQcAJ}iSMxK=<qq=YVD8Pe9%%H`hbMNnYhBImjupya1qHIpnawCi)WQ$VNlOJ9-O%3}Y z^1mJK=OLZT7mv*82q^+qF=6o6+v5u!q@cB+Exs@tAgQWO2z&IP>?o|Q5S%cxh{dwP0sHi#2ws*BQX3u!is422PTv^w_?<5N5JKQ z2;j5`U$_|42Tu0T_9seS&^(y@NI@QNwiK0Z3i0^fjo zORX{{9F{3Z5~u*eBas_Nh1jk>_nm zhv}~M+o3EOQ*VL254FciU{OU(Z*e+o)?ddJ5NiZfZNo*Px)O|M(h4ZoWQPBiI`fIf3iAt(uOnh+Hm>fg7yif>k_1Uu;9~T3b-)^zBJ=gjb(*jw7ldYlnx#S5oFGE&E?g8eJ#iFDI6wZ69QXHhJ?7_ zLk)%HFwADkhs^_+KDSBlArr2SwhVeY2p1%*RsCf8Tw7`79{j2w^nL3gjNL>HT2t?N zI0snI-i4B-Wp996bk7xMiZ=|ez#?piaMz&H<93XZ?Mmt=g2O?VyNzYZQI5@fi@VdR zSX#_2XAX6K2G70osiGNE0W01j4pl4-P&Nf%k(N4*nsg$M5a*3h)P&!muOsm1-&z8aclo$k=dreDC07YA3qkZO2`a3G5iun2e4W z!vT_ls$JyZYB_RI*$Gk}Y84^T8AE(Y1EZqpqJI_53+(Jr*w(c!=Co{&D;1`hy_yDio~JmI--w@ zG*~TFsfEl^p$m?PHJC%i>EE)JkZ`}hnONA4IzKKT5V_;-J;!Y_d2+QmSY5KqQQuQg z@+cKh4R(O_O=EoAKsF6H*nz33T}rEy85=$vFrhdM5QXWI4?KSt+(gb|6>xymfI0FN zd)_+apn~T|#)y%IYLElegkS3RTAzV_%W1|^IJ6*yuV6dmQMx+=9UJyLBhrT!(N>P_ zl;m=_DIk!~-(H6a{WUu$Xt?`4qYm0GC+JbHkG=@{EMb)df?hq?TziDD!MT(qWc)@9 zT=gOSk;gJ+)z}G6YGeU@t$T0}9>_Po$mVihqY?ds)#2|RE2v&>R}uP)2g~H*h;ZLN zjldoV-ABuE_v0pGU)7T~rFuMk%~+4-$9?j7Z6O5?K03oe1>e}y40QIvFt?C{7DoW@ z;e6GbfPN|&0uC-s{Q5kkqc@P?^-dbd!#Mlj9$wK z#wX5Nb9AFzG#(k6m=Ub6l0EEcZIC3}y>fS=7TZG>cxZ+N5ja?PFTJ&KTV0vZ&to~T z85tQbPs*1LG|hx9!p*HZk1j(GE#V>kNlCpx3-)Fw(>dDEt29P_yvwf>PJngbWj=;A zeY2?fCft1y3qHt`Kep7qTAsfsO}5}x4FHKO zz2xdfYlH5io*J0020g;X2I@C-st1>P0?NJ}l^x5b6`G(y|DI{ok3^rOn`DWS6e49QGj|1A>5xbqf)(Xl0zzv`+!>0iY9wEO z(7wxyJCrtI6^B1n3jm(AgmZkL?v}@oHsapCywfoXW_Ew2zHnm7>yEIDc#d<8n|{<44)&mSk2u=ee)Jyk39}XI{O-Dz z*WJS%>7304cN^(MFg+f6P~vHuyj?)@9WNzJ6T}`@`@SL~@o zuTlh}Jk(RH27FC1%U#YqUS>^$Y0KzVZ0#QYFf1wT+`;xu&asGwOL{q_YA)* zoeydY=@k*_k3SL#5?>N>jn$de9in7=O7+r(-)|PQ;p45cn3;%$`w;i0cLj&caD{m z`xFoR6MN9_9sE9LS0`7XZYfXfD`59v9!RH1ueb+!;IE;PQa8d+dO%vc+~Mdt{XxRd zdO-2E@St40++Q7oyT7vV)BtfwbjLg zG<8!7>@neqer4c(z@zNA45X#M74{nWk<>%~n$e@|tPHGWs1@NF5veiCJ>DJd7;tY6 zvb?pd|3;7p^W69lr4!-sBs`<;O{+d>B91i_>FAP$d+ZF89dv%Wo@}1Scp`fZbiNh8 zaf(Nco!#W93cQyrf42_$>f`%qy7BkOUqzT-ZHaPzj5fj^&j7y#WPO(KbBGBT&q>4{ zP9usTctp_c{)ErX4%E%VD`4>944lKq5Ps$ioWhZvbc0$-9Tt@QPuIgIDLQehis-ny z*9d;kc`Q6v-*=#)w+tS`pK&}gzJBn3ryOdpI@ z(7n&S#wmwn7qP|XMP-K;TkEVvGlAA4MQ^<^#nDga2cQs>N;IO(7xdce41vda8bm3;)uR>A6!GMkb}`SL`NCu zT+;rsizc?0sic?sW`NUI2{qt0^6e-0ub1utx?MsQ#i$pASgqu7Da*(Mse7GY&Bdvp z1e!&8t2pWWCAi+$V&QSju3TE!Kd(EP^vCI!J8$;YEUpR!tJU0GtR5bS|0X9d8MOAN~1k4 zbEg#d_Vpv$^3pAChKT`GVV(dtPM0ajGZwdrWK)*qtNG`DM*j^86Ez( z_S-OUHJ>fI+I`{N>y95g+^hsnHay!omU`TQ>}I`2PulX-xggcBpN%Eiu=itw^l3!)@n-TU*=`UcDYbs@i@DNC z1qz_-`g|^@l2YHi`81ZKFB-SrWJO)gS;N(7*&r)I7z>EV@-253e!*W-t^;xQ4TqN0 z(zWg^ZT8qBD+tsY{$S5HR&evq3?&a=R(N55g>$TCgarG01jq)QyjX0uf5vr|KX9Yy2<&RI|o7=JJ`Hr(x<~ z!GhzEH;CiJ)&K=D*{}Yva8YW010=!vJ4sFu?5Vhl1O|KiZ0fSwKvtYFC%PUbVz00+ztqrUB)NuO}OT5ZnJn$E4BM4C50Nm!b7q zP0ZT0no+WSjPdrOlZH`>CT?+*%Z@i@XXR}j?G@_Q*r-65YsG}1&3D{e`rP5Peoe=^ z;jYX?zKx5mq=_01Z4YUyXxBMuH}VGXsQktjfS&qU9Do0UZ-gCkCu{ZLW}F_9xa^3++TZs^MKx3PMMY7O|3Sw4ln_75 zL=h9e5H^{wo5aTIPErOjEr`almv;jy>ue4*HE^M)m-)WgO<;C*&VcX{+lBA(8ta#! ztnY;Dp7gL`Fcj6-9>RKLs5)R+*$QJ*q;B3N`%PG)(zN;3%^K5qVp9%Oe0?UT)!!#> z;-*AzDkG$HZ{*^h$)o4i69P_e{wY#(PxvvgH~(u0#q#<|+S>PsIBU+8OYaE54Rr%} zG(K+5fcJjVd>9=GzHd77HQ!az`yrGQoX2Xp>N-doAeeheRA8|5pw7Nk`NoZ;vZb}h zX_De!a&~-Hj!@{pUDNf+!Pp>Vo0`yRAfSaoyIE+s4fdW+JoKJSyo-S&Zmxnkutd~E zLfiQ5!2b2Zb^K^RYcR_r$~1Y6Pz8KAqf-2}`XZF^TYLU2E7e}g%kr;8;_}0RmnD<@ z%JtAjO{b}&1;;t32#XNR3OBx4)!5X+)t{;v3+;peUL%Z7S|UOZ_xWjf&GW|GAakq~ zSo-E~F)IOGdKvVnzAh#pTYZ&z6D6`s>{CC<1W%<(*>s8G-gHr#RxR#K$zFr4T5ajx zwCz$usY>|X^m@ZZof%iDO866+{oW6$?P-Lih71*e&7Pmx(r5{(%^u8>6JKrWXbI_~ zd+lRo!-dh3lWHxldz2YhhKkhoG_us#v-b6o@|Sv^eE*>jrQyQok4!~rdbN@>wtG`A z7axTiYztNL_H6gg4Q=*LE*flaiI$wI&6<^K)k{>$+=5>0`DNl0MB_!LM!JgBy~h4e z>a0)RQLkV%~3-{t2rz^J1mcc*#WGPosODqJK4E&wg*4vf<*@l9MN5 zQ!rvvuvy}6Zh=|iZbUue+ysF$yN;Cq{!T>mHaw4QE{(3OOZDugL}$IVdvK&UOM$s9mt^JMK`QAeO(`pKw)W z)xRxGQ!be7&r#q>K@~}iV-n2~rI3&@jQSX+YV{*3ig;F3Z@@J#G! z`&zn6(Xl6A`8!OHko5rR8c}lanFT~?XQL$-i6!1)&&X)k$jR&CyI%4!7r$Ec??H+J z*6T0x1-8TT>|OVf&qL^exrsaQ4r^g~_ObgCP}5rRQ?x!{!Imtw@3LlD{7t?Nb7n=E zb>zCipp-&H{zK7MCQMlvI0|EI^ULd{Pu1hWg<1S#i(_wV+I~$Qi<0JHZ1*JFlw(hqQ|3^tauY{@nC-_=pTM@I`%viN%F~ zPRQ*wWDi?%7Y$_(tH|x=V>nFvQ&=`6ldO_*7jwyL4f{CFa`zySluL9T=Ypwvaqg~ zj)jx2mrnUIj>`6^C6mNbut8G2m>oAFZbUt@Oi1`h7b%g{n=7GH@+gq|ShU+(_*dkX zR8qPChJyJ+4oUtbcx+<246>Y&*GCEIdKe18hYgZE!-;QIJL&ai>~6CD=3LXO`hxO~O0oXG$kdH>3eU`q^_*g?tNb4Xhm1SR=X#I0 z1FzIQ?K1 zyBRqt5x+-U{`VLpX$lPYHwAPz@G`4`GbmDVuz_+S(~YGGsz(jlr>&nU#6S9q7SNHS zkmR&y%O%9XM$2f){4V^_Ah$j86dj(^?k?{0!;q*wTOc6@I$A0YdMsNYU(_e@&&d~z zO9saMoO$EI=3Fb;*rdWmH)cCIpcM1vA7o^ZXN%m)Rzh%EPDg@yT2AY>?y-p}F$>nX zusruvCU%CtXN10W1kifK>`;gMP|Nx@_*kLxVd1#b@v$^NSH_s4`Y(voc5T7OkMc75 zYT+dX35h`kJ2}n;5s9z`1p)I7ElNQ5&YG<=R0rji-NTq1#{0z; zmEFVh>$g+i#;_~z{y1u;XO)4*p(V^U)0zC4^80LfN9_<6wy&ow-_Udu*S#yc^Lw5U z-dFAKsu`>$U8A;yHjcRulhV3Dal4*48(i6A{}GUN-SaHDNbWfFP!v|El0#!zq15r5 zUGF7Xk7gZvhB@rMSDb~V*zY$1w{SRqidx{~*I}>KPFSZ`C{#m@+iGUnI%h5vv2z~f z-wM6X^7=G*DD_J7X!cV%BG9~oJ89$|XM4s1F4vOMOje^&i^eW|^W70|5JwhU&eh7E z%M#)OP~TzbSmmI(hjO`1?efmZ**-O~)i52E9gIU$c;6?b0#4lnOjkl1AG|Ef~22rL+p4uD*t8*o0mZ|6I#Y zt!uyyd8*Kbs#s!~U0vgdSn6-XAEG9DTUT%tN1lrjYbZAnG6j<#!VhI2@ar4=e1u8@ z29J`fL8aB6r;budaJVg1Y|KWBjC4;sAf^UCuZ5j15X;?l?-aj(rmcNG*SPCCE2i!_ zZpqc~bU?so1`xzZchl)Q(aBx1J6Rj0R`(LC zz>HtDQuU;y4`Z%_Rb0nZ#Zy384!&9?{l5N>2OGEeom$gd(e{dE%9(6DA8x3oJu516RJq zEjG+K>w9c))?p3ph@fORKg4Ff-Mm);axVFkw~Yo zpQ7SdByw#&un7T!n}zuD5CzW*s6yCr5%ZAq?iZpzJ|U6Jg{(i)Y53LVX(p`oTgNrE z8=4b@Yfd?ovqmxId0@NolABtBG;sliC>#{sBX61Wnu`T|*u}M_QV6lqZiOt)NDo9E z38(5PvRuEwYTTo3=9Yw+@8gr>5K_w8uiXL+R%A*G)Zy-r$=-Xq*Ul&0oE>ulzUOix zQoiSMy*`H3fb0gjJ|7BEf84mE(>k4}k6){aRKym1nurMHg_WcBh%wa1jpe(2`V*uv zkSTzfI!7P%+rP&SG80=%^r^~z72fEu@G-m);hb`@DcPD%i*#FgY|Zd?Kay(2ZNx*W zdsrF#v9LGtiBQpRxR-UBS3`lhpiuOQa*GmWPBxP3KaiqrLliDqUCI2xs;@Si%jO&? zcj}f0#q8F|)>6KgxGBqW`lam7Qp`OC@fnJ{y=Ejbb_ztNS`KK9MY9Fs_Gu zvFsjX1?pi>B^Pa~GH(^$^yzC+u4VD`Id3cn^>~ZWTN^AliZ< zZv7o=$2C)O7^8)rL!CCBkfOi8aLP>nSr7@-FrqP(!WwpR@Y%6sar=z}8cmyTzJIlE zbi2)}PQFqa`&GeNJKNhe)ntGBwR;2cjb){}-aXoGBh^Fw(ql#w>hkI~g`$aa_Rw$2 zN*s0kN-FnE+}_}6T|BGS*PJaL?%il7&w;gLejLh@ksGFr+)-l3Zqf6dyzp%nI@ceD6A!{J}suntGU`rg_ubvUbiU%)1rlS+ugQJ^X@oz%};WH~nCw zHcwXQGfO%|gcJu*)HU}N308Rjb?AF))!H86b|Q4zb`{N(wc6F~QB6JXF9>=p33Gp! z2@T>Znyn1t0vZmFcW*Om9c)*xz^Gt-vdqm>WtXMosvZx{eFS$$ek8dck~>sJv}au; zPu_W)Q`!L}uRG8TcW{h7m4r8#q$Zu*FsN$bHoaX}@-AX^tL|AoxU?;0f4o(h#+GF*v=uT;d>-LrR?e<(t3J91_u&3C zwncnFRLQ8PKRBF_LeHUZH$yc;rpgh$NbOe(d7%`yMKuC-1&uLbox3GI@+Fm#OW$eu zJb8!h?+Hq4WoH)17p!NB$k!V~M$pq3x%FM*PjI^J(U-Mc{Qo<~^=At(QW)9wZHBj# ze>Lep38EQE^u>o0lIhuiR^2~B`Y`@g@bEda>j!GIintkl{oiI{yTy&ROorzcrS_+{ zA!UVjk6?N#fmTaOxy86M!}zU#>Mt4t)G38u=c`sR_D zB-*qDb;5AsncXj)yQ0Oa+8b{v!C~aoUMtWD37@8LV5rsvpj}+$KzE?MHlsP}JN+=D8Ie z2+!%r;ojI7!|tOadc*!U1G(fLS*F2wslhjPY&tyWET`1*4#ss({Bp257fEFzwLU{5 zR&8(ofmZaeR#=56@jKyzIHkzghj;WoZ~M`^sY39DAhM2AFRP6;8vl~GQ++GB?@)Nu zx?8S(Qu}AJRJUvyChT7N*$>&`eR1o<(fm{CKa(DNn7d5jt#CUybsNXA&|N$3%Cj#i zBl|9TTZ|lOb2o#-`oD>i>{@P=gvx%%J!$aJoGx~4+ow&1#V0XIK*0B+j{cIq1%fDE|JRMYkJ>*$86#aZ2?%r zA6D*_qAG}hqTNv;#1G^&K;iDN5F88+20NYo-r2|sLZC3}70(DmvInx|Tgh&#y6?LG znnNW%9E0Bpz7IW$o(L$SaIIAJsW&r}9x6#w*2IsiV}4tAR?2Jt*HZ&L4Dto?rZiO> zAGV*omioW$VAjFMulJXeVgB*w32x->Ebv-C-7(WT9DDq(lxy}D&&JW`oyMwBM1at8 zPwN`gHNfV$XcV2y#}~|-O#AmeH!LilSTHPYLX!}-S@0xnMw2k=a$6N`5tn8F`DpAW$@?jPcscG#wjt@5SL&1OKs? zDDF7))XlRtaSi|01@*~iWcBR&RZ9Tv>VQ&k*-B9c^Kte6q2(=L<7&1&-`I)m#LNsa zGc(5=vmG-tGcz+YJ7$id&CG4)n3);d*yg8v-#Pc5J9F;Ln|XTD(qC);_O6n;dRO%V zspH|-0xi}eSA~BpDG7Jr!i0H*hyXrF1e=72#Y*sY5eylXpH5*^yZCJM(R9FJg|q?7 zrL#P@3v+T|t>AJIIWYx-raY#mL;}&fD1Kfzw(s+I6JcWV7<61+8Wh;a8O6eMyiZ+4 z0m`oOa$jB4HNY_s&pPSY(ZVcTN9yon(9#CpfU`Fy(~!Zf@aKD9dp4OiLRpV>Pf+di-fC z*7h>^XRWk4HyHBpPPo}^z;?rl!F7l*$1B0=wi^VF0-+{dNfSH-dlIaTf%e@)7B9}d zb&v0Vt!+@UMTP}8xH}x7GX_ZJxBO?47JnhesszIA5Tv8?{nJ5fK_Ti31EF}MCxNlw zAc&C0qB!#dsM0DKBP7z(!^Q(F1T*BHe6c+y#>h5WPet~gqd)aIU zY+8H{-rti9BY7Rv($%d0QQzoI*y-Nl1v7MoarmO9VqE^SW!Rfb;uop&g5TW}WUxHF zPK@{Da0LHqdr(uzTbz*59et7fw8{L}3p58vy0~NMSUx9pK*!wv4XATA`7T{uC4Kot z^7u7&L4&d~&DQz(@8+c;i%fE*!w7DgKx|g$MUp~&@l;FhR=t78ajrgr%e1FtXX>2Q zUvjKk(>ig}>~(=y)Pkn>@Z5dweR0p*wfi`Jdg0Q2dOrn%;|tdd-QRcoKK38oBoUpk z>eFc#f;Qa?KPQ>0&OX!M>>^V0DUb+4wTCeRmy#uoH!fBe#9l_hEZOF!}#RG zwi?V)ui%hea(-$Yw@hifxTU z$DeGvW7TNUqx+PA(jjTpQ${0>`jpv(zvN}z-ssV5+GzAIw26hg{|r({=X~j7V(z#c z?>3p2xE)5}cNF!*_s~)oaCH7IL+dgtW9j${SMk(#<4+Zz79AR@o^`3hB^#%rFm%omDQl`9KqAvWt=nbv_I<7GU zA5@OKQnX$==qiRulGN7sR5(56Y3s@gs%bWRbj&?-?K~%%?cK~(RyIzbZQbzw&a!<` z2WcPNr=CsUE^HKw581mN-xuAE!o5eobZB83jZ99XK$uU zG;HFzhmYp~uA;&PySb+rU5*<&PZu-;pIhjfcYSpZFV%F;e{?^X?9R5Pv3dV=^tt%R zjO^~g30$zAPfJ?%*5)w;e>L?*cuWUzb|06n0j@G}M7(&k4v3Qj9vi1WV?E!O9;e@j z7_L^}2u_)1qcbc9pI9eU6`5tkMX2(l4aWOE8!G2nNz~VxrE?6(Nl3Iw3BX28zvpf= z@7SonYvI0jKl74$Z%cNU*V2$ttN=x`(#_G(YzzxzWf~$PIGATB{)XyV6blEtU1)3X zlNZ$nbpTGncZ6uh^jOqcMMEAb8S#oT`j>`vG1%kNs-6saO_II6~oXs1B z_h(?f5w4W1P%AYRJ5(`6UL!?z=$BFhM~ifA+#rgUUd|A)ps*0Jfk%V77W~pJfsh>^ZL8P!M(E?C}ko4p%rHG_s~E{*jrau{ zS}Oqx?c-W$Wg!@TLnJtLn(kcGf)-^(D!2(%)}w%0p6!?$ssx1qs=x?$W*d#bgXC*m zn0$YK>Gt;Q)s=;NOI+Bq4j*4!7}nJWMDN9z)0DY&Z=~A?A9|u zm+|+h*dVQsYfe}7>Sd!ED!Lnzg>P3yU|56GKmg3%POoTD9J^skw3chenT&>b?T0wgbNjQ||!{Va5D(=LQBy zaLtC>s+GJ%r%i^-8tSf?sy{=-$T3sYl?`V!)Mxr51ypZq^WyIKDi00#kxn1gzdt*F ziE`hu6=z6G7&F;(#A((3H*Pc6)L4}Ftn?L22c!U9h{+WVT^NTug6g*~R*KRr6|K>h z44Ioo#!fRYgqfQnH(t@-8AyL5Bn(RwdYL;e6^kC=6 z%%S7PFAH$^*n+}LucqM%Ndv47;#+>2z|k??e0Mj8Mw-~l$Kex)NaNWooO~#|;b-ZV zK5!d(VaV7dziBu2O&h;VeAM~>0)JR}&8-kNHc3>SEB>c@?142rDX_du&f7khLg-Q~ zp>v#&;!{^AKXIhU>S=76Hhz|vp~F%yZR$EQ&Y&?*{;SPcC9U!#QAKAaT7o8js!wSRB@9{X_IZ&19nQuJ*V#mJ*V`FFXWJ# zPk#HKD7lrQ)sdi108e>a43_bSdt9Fvx^CgrCl&YbK9M=o#ZNWcjSmwz`BB3iQR9u> zr=%fiR2`z*`=(+`0sQ(^G_?h&nkEh(+4#6q+IF5Z__1yJv7RE$uTxCoH_e4jH226Hi#i z`cE55-TLbzB=kk0>lTeKbs%ia1iCeB5zxB}!F8?++oc`Z@T+1TCt!LOK}k33A7j$3 z2NvJmCDEVB!g(nf+eMy_T3O8^kze<<{LzcRPk!RP>n6)Tr^2btX75&|f_k-&UyjnQv( zO7tN|qbw_m`2-j%iuqU=7|P$FFbd!>c%<{|(f^Vanr{-+&PrdQXI5CM=x6_yx<;g` z)x`#Y4BS`)z*@8U7&eoIo^H19A3{4@$70D{#BQRgRKmW0vM_3DMGBZo+-NGB0`!Zc z;z?Sg8y2E+&}j6#`w&@X_~ctzA%2CGsOQ7yy<5oS4-eqe$ODe2SDg&vmo2%0=ab=MwU!8~+$}JDD66+@3b2VGv?CD8m_u5;ESPq`dOsG0JI~mT6t0&6K8FC}N!P*6VdddQk zOt~k>`vPxV@(K==`L31bg3CY6`6C=XqI(L=!<3c%Ks3(7Jjo-(&11}~QPP5#cYe~I z>2|^_!@%(g#_EuV@{P3uGOJyX~ zWqVrIYWo2`I`g!g>%=I9RG5U)JSLAFatw}+5zx_d-8oqdK0i=6!_}A-i`{RvC(K5| z>Ipe&jnao657scRlXcp*n4;bC2w}KcdsL~(sy=LeR=rtRC&aiKh1Atx+IZm6ZL(nC zI=7hxH3jCtUC7{s9lKvR<7q7|K_W3YXEDNeM!BK0$Qn0G z*E$AjA&glw(#7X~R(3Y-9I zCIc0}hM^A=L(N61QVGBgNaTa(ml^q#BjZ-C6!8Qs`z36^We7x#+l3t7bD{qQ@@t6& zto``fj9yW%0+#H+gxXOv`*jum2q^`WKlm^ZiwaUC@pXhAhn{1G1xf^fsgQ}Fc9KY8 zsgQ~Gw<)n8IfQ+{Wk^JK+jbnQpJ*apw#gMGC6!S!O%b;ar zzJv051PSU|B;Z9M+(b;cNDN^qJ{bMzS)gd5ljt|e$3_L1upVT|>6vdX9C+I4R&i=9&!l{qUzn{L{%F7@hiy}^j+-!Nb zd?@J;u}2yA&tQUM2wg1{zcwL#tYfateqY^USBIe8cFFUJ;M|(JqIiK?fyhFO;Vxj7 zsJ5x-g^L)axVA>~XiDH)Rae5aScUYSx`5H@MPA~!YL4xp&>m&P0>r;KvGRIY(XhDB#U~QJ5ophbF4s;Mo|$in!Kx?EGGet)~=S zLp`{NzH1c;A{_uHtRO=7-hbm&YG4)nBaN(QkfK(WR7?v+*b=`R=-1&ng$XxeaB)a+ z37#hMH}U@=27dVWL#^=PtYKVE|6UF`?FqDztfvgT5LcaS1G5Ym#y_6zuEE-ga@Q%v zo+Xp=?hniTd$(04=)2i{FtsAuuBH)m_tf+~yv@|w@QuVa+J+X^zU7ES<6hy4P(diD zI^k@8AtC8xSkh&$h{y2<0e5+9wkXF~!i1x7z4j}1LNyVs1Mv&H#M=uw+uq!!cE`o+Wxb-~gNf=5+HWXC(ETVL1(b3p0NCvyfLS}f_yyb# z|Du-2v4N=7M}u<}T!IblA!LFS?`=$ISmw-nt+VKseYRP#n{~}{U2Rx>lMWVR-&WZ;!>Sb=(0WAC&V3{@? z+hFfKZo$YRC$=kYGd}!}Ly*jS$Re=aS;6rWZ?<6UEvs4${gP+Pe#~f;=3(hfZIL$}|@YuDa%ePV!##BY?J@J*k zpb5~i*Ry@6p_eQsZ{|An7-CKytxcTPg&x($!KQEvk~Iqmk!+F=AuA6iQ;8|cOxRqe zTP+ncNHZczJQ4cA|Gff6^6qOnA=!LTk!QRz(!an7hd3xxic_W=8af!C!6_crQ@Qdc zzd7A@c6k4+iD>A=if=zKh9@&BAJ#!K^9$IEk%0Y!x>qfEA8DC8lB%%A}*^B zgNk_IeKc|AZ7Ll=c5lNjv&`r@-*SWR2d%6HAG`M&RO zTBG-=YMb>{NmsqOqSBSQ!m)Nf95fV&`&o3lckc7M7zE4m1~5DR?@}+EDn*Yq)*HOo zAsJ#>CW`4A=%$z<<(D3*`&xBW<8-jBQGMeDO!Z}DbTl+kB%_*?2JcC=?_}wt?{F6V ztcrM>E1?x51(tPXnRFEtQU9&WQ&$#CS3w$eGW@q2NgA~?T)Qc}ZQYcH8$EBs z(U9@QN^3)MneV;=JEYhzTJ~YE#7m3vW+YD;Db#6JXhB$Ud~W<;i6_rCin= zcKhBXa&18%bR4-U7TNSt$n2aa3~zDevolsAxMT3|bKOa=n(YZ% zbu$y?5+sS=VWeo*jI}5v%pE1U>G9d0lWytaJr5*ux)D&#ovulBwT6BiFJo-~$qBY> zz7la?LOc#@eB2{B6w&85tHREC6qOmSoUJGC`+z8erkr^v==5Y+{W)ApS<9EQ-&#q& ze9+#OYNiEIQ+1%VAS&kFzJo-*K&SEK%OSaNKIQpZ~i;e$>WdZ_VWEWlmZZbMJ2B>8FiAD^LFsx2b%X*5&kXx8AdI3vQ3BDZlA~XWE&i z8HUc(BAs90(4Mmd^ykP~&^GH9mOZidUy*EITwLHgghapL?vSh5M#k{48;uOP+0T!M zv!$%&{n`SYNQB|q$th|$hwgfIDpP{q0PLX4SV{bfsT~wFRJR^)=KK-}f#A4-PhM{6 zux5Q4Ob86W-4H(PFt9?oZ{8-ebTO5$TzYmpA6ORugj&%k^OSn8D7`K1BwoOdc#WPg z|0%p#6<1RD;3{z`+rW|cI7&zBX~*MfCwRNzaMXEs)Omc=xjy5ChUPQvZIO!6$w|=J zOyqglBKkfoXH7tmjQ!!GK~@=YE&bSeL4Je~U2_$!oD1U^{nqO6o5Z^7+SlA z;TnZV5`?*2A5t>Rm0^mDzOk1mJE zmgh59^uGH-&4&|=97Y-^dN%4rKXc*)kuj!ECP0E$FOo-3aB}+rq|ds%Q_Jz~=)!P*Sz!%6z{Nr>ql zZZI6Q4qeAx1#;s#D~;iew}$7~c3R+I;IwX#E_&^GPBl~(vMWt5wTUhE;e!!Yj38ID zu47`UY}<6%itI$5IQ|m!r`6b?-R)0YDAJ)9 z&T}@sU>4A@bpog>X!x%nAAdabH3Q7!%3yyfVz_EH_Gj|bYeZDoVpfXJQ_#A`RZP%@ z#?IbQ^2^f|PL?~8sl*obCG1dc?zKFa4*A?MZ^TCqo1)8~@)CR38>Otr9{UV{I^HLD z9U4h!TnP16GY;ENaPFJ!t*e@i%xhb6K)UZLJD)1)Yny;8s8-VX&;Dza&KIOehBgt6 z#py=XIH~GdfBZWX7o2w_R=ZZKI@5Ko#pB)dwA5@fA;>h&nHsQH4QfL{?;`w;CF>kK!;?6#h9s*c>-SKmxAcj4k$ccSveF4J3T%qq-`0>*#8}rp z{}r76GrGU}&+r<$rqA&kQRJdNRC3;F<5zRi01i~EEuZNps!z)4V7xpaa0q}&V^(?V zI^-a4{b7&{1m!Jxkb#}DTiTD4S3_^H!!CXeR(A6B;eJE$hR;>5AuZ3Y{UMjfgl4tn z1O6ZkMt*~?Ow#`e)CBVaYz+y#r7o$}k#ZqsvX?%XfFaH04M|0#GhPdXuZPRB@sTJ4 zyPAp|#iP=)``+F4QITYJ0wnpEB;_fbI(!-aRI%XG5!CwTJNyu))g+&2B=yLTf01d> zc+ieP0g#WP$b1rt7!z*?Oc(3(8WS%eXm}-a$&Qm4%zB*H3^ep&6w5XYmZfJ?Z=GAH zXn1d1MRIwqhYWZTR~?pOMRIv*1K=;?*9lnKZ!kL$E_=L?Kdd?me5havJLj^R;J#0> zGF(W|!7FgI(K~_>$#aC3X}!-W({5(Ras2>abh*2OYyd*uVIpL9_!QRyrbd!}VI=%g z8!i#!o*G6k#g}M^5vP2Xy~JH0f0nvLPeQOM*wt;nv%9k^N|6(FC~EW40rn_h@HKc5 zRwT;B$)(2KNgL9c;q;Y#!DVI=pcIg>M(bwq{kg>9tMo!qtK)6!U5$=2-=~^1fG?+k!QLnGm*!gC~u;P<^2e<=pEqShaYU3NeZaj5j+wezR;2S+IobH6B zHV7aOk%v--Mny!3%;X4;$&AXNmKx)-#u)xMXc)KHnH$f@s24RlI2&KyX&A2SqIJPhDu$g@hlkkk{`3%%6&rakEZ_nvf4-7sWHRNG-V(4TVR-&K&TKBc&P zH<7g|i2EcYMO6IBl9=W+ew3%E4zawlzowxO^T5VlTpasdSJf#(KcRM7~g>jVar zdAgD3kRtk2@E=b~mu#8%Xa=zt4ZV7DuK1VW?n8a_^{^pG4Fs2n5dA+IpyPjn=_h8w z9qh@!Vr0TZ{8In{3%q=Y4W@fR#_l$X-mE2pFmkuXj}9~1QtuHo1WTOx^~rCQ9(YIo zu*TGe|7#_*5xYZa^*OY^FlZZH(4h|c!g#bGOhYg`e}gALZb!QaY~LoN>glv6T0=tm z2FLdqska~SL310$9i1>}Xu>Yjrq*nE!wG=R2R6ENLl?3M1t})5NFWX3R*~-Rg7v0? z1rrWS`*FVQ50{;=Ry;*l2ozSZEt5Zz z5O(L*Kpro8KgAI4@CtlYUXVKO$*eQaDcBZ$x<4?^5N?(k;`qh5s9t%KE66jSNQ?X6 z=nc7fTl#h*?4EA3I=SfN)!fDUSyVqDmVdszlP8`xGEeZMGwi8|S*dC>w>eC~`{-`- z)!L{!NZk-2WSei3;MRlgxu=W&V!TdpGvBNPhv0ERUEm>zYPy>#Z%YK-J3J6c@roE$ zK(sfE3XBXzRPe9xC6#p{8PzSIi}#pc!QX3JpoNIgAJZL~FfhyjqM?uUii!_9t{?3R z#vL^hfc!>~6Ig11!uN5i@6XB|Ir4v2Nh>-@RMttXkpAH!S-~JVPhQ?e_Fo}QZpCP6 z#kJK_rkDNk=0p^`R{sa=&#OI63awi1`{63Bp1@IITGq*>XlB>n=I5g*l{`-9qz%n1 zZS9V1R#;9G-Yv_D^n(~qZdWKw6*mmqSwzPt=POS*-iI>jP-^}Hho-TuALY%Hu*TV0 z+|qCCr8sdpei`rh{m`W&c zl#=W+P7%m4YKurxm4S6*uj1tMHD}p1Tcllh?}e}nhsxk`cV!ukcz;{~@fYf&j~4b{ z|J2Rz{0F7)LVN)j3f)CzdOzkEsZY}8H~{q4e`-rT)zoL1eSc&H#}&exl^s14f}65Y zelCY+dOWK7(ztqR(fpKoOpbc}lhSr2RZ(J^@^zw=ZY~l=N!GTwzV_3*vG{SK6C0p= z@~;x+7km7dL$l;J#;kJGeKJM4|4H@=v%Qm(;vBCP5kQ@&#bBNcja+yhflneXSxdfahTVIh~+dRqNH-^0Z|*+;hfXbww9`x0~o@7>E>36rO1vAxL(DmPS^M z{(6SnE^cl1(A@lcvn}VlCPfvWsEGVZ8se!? z2J=tRp>fn9dZ^-BxEV=kOYN0FjO3x8UOFI&fj?T?nA<2y$zZp)^smPJ; z`k2Fm?Hc@3Uu_A2!^3q*M^`1WOZIoONnhK+u&H*% z`jM?a#vTozR@=%nwRih|QD(j>tnA#~3@Ry8msSRghS;5VYOpnE6w1cFPl*Pzp@7;V zU@ZzDYovEvBs&-)7Rj4Ajd}zllQ~F=t8l4xF2mN?e{{9~V(EJRt|6UVNiOAGU~Cgd zWkD)+yH+Wn_aGM=?4|-3Iw`>+FD58VTLobS>7-;ZlQjh8w z@DMc8h)*XIO>F9Pf~%ZZTRA)kEX zEQ~%U#ysQZ7+sptK9(29d1jQrUIk&1MiWfIy}f=mGQ(e8Ww~#P?xZ)e8(Ugsxo2T- zQX`(Ji0`B`VjNoK`hIkUj=%EW!>isq;1wUAdbYA+qUk`v1lzQ6zK z7sC?6yB>R#3q?zm!!$t%s$u@7WR241mB>G7{S6Yd}}= zu`7h<+sychTPUflVzwp226g($GrWS~X5HRUW&-ngK#%XoTFtXRG8RLsq@?v_0eY2 z2tw6_M&;YORE;swP!+=}~^4(SvIR2@aLCFvf70ar)yxATvrm~hT{Q`(*U$t z7ptDNGbT?IkisnDrfzA6&Pf;TlBam`)UdsNQiF2Cje{#|0A^CvEDH==zOcsHpOiba z0%g>1a({K@5#$aVAS_nKsMVWSb{RmK*Je*^vMkn=%(eWrBITDSxkY#UX%Zou_G7>) z_OLbb%Zq!k+E6ZC3K2G+k4(xB#|;`*+ND2Fte zsuIWu-8|aX>(iUNr_z?+CA(4PbwbQ?pz1u8=wVCS97E^$-2S@n=$6N;klLbQo2tEy z=n^)%xK?|?)%yGAiCjwY1)E!@_xgm>&7S3hNtb7Z?rwToK& z>0TCtVBProo^5KD2){_DF-bDoXu_&6t1#=HSN_X1T`T`@3de|-uZ|{rQmv#cY^X^@ zVuRv?qu0a1!(@*c@c|qg&3e@+tnZgE!#V{lD0Q&IAE0pZzJ5eE_7Ch3pO*gON$sFY z6S-qJIkW)g-3+_1_$|h`7WI4tbwL@HPl1Y4UYjQ*OZHSi!~**IWb}cMMT{ge06RF0 z8Cyg~8Ge8XUIPAof=hi&%t$e?o0CvA6^yU9)%{Fi*sJG_20}72OAsO-&ONI&-t6l4t&(i6W>q|e zZZLb3-Qc8@Cp@J+MKba+@qAxx3es&oTY7Iw@iMx?imK@L!SZc%Ti0pBF!QpiokZ6- zoe;JnU8QB^F25YnS~cJ7XP5!I?S`4Wa+KW4m-IYkMDHA}hyQRRp{d8P`G9dGB(mY2 zM1EUBep|Btx7~;AeW;SH^}#rgp|EvB7ivf2DU53E>q@$7|Ls~RtMl9@)$pjbxjIGJ z?+ssn#bsLfL4Hf}(lVp$(qbHf9lq0(yVLV=6Bp~;?=AH>!eN#s)46UvxVvuTItc+R zD1Oow*g5{bfd2T9VSe%i`HrG=!8s=kiHeEuNE))cNEn^Gi}f1+WhYQX+ddp_QY73{jS!t12o=_{g^Y!72&v%_Sjoq(YhIyC zONk~QA3-?`L^Iy`!UA&q%lM6V%HM5dRTjV0UCe=D_PgwCDugs-YESe7Eo}uiB~aBVextD_OZc zOtd&>W~g$|e)*Tkk+!iv>Pef#8yo`2)S?e=VrXQ*Ahyb3mk;)72HT>b=*@8oE8h}b z6QQ~gtb!txvPb1G6gMr7*w9P4>9a8l0-OSz0?e`TvBoiC0-<_63R=CIR)1*kA-Wmu zL=Gb)-~m+AP{?{7TfF~9F(r_2o!yKmK@KD#+TW) zOOKS0rEZnL{I8ZeY_@EaE;f11Wy-4KPkBX_(>I$QWX6Pb!$cHvHdOD9IAsKZ$?^`> zG2DbX($ zIt3CnH9`_k0KACSx7}$#AWWA?3}Po68&i& zgB<9>ID`CjS2=sI1G)j>ksu~rfWYhuEMt%OeG+1X`ztq$u@YN9Hy75#4CG-xx#l(z z7ZKK$uy%0N46e;IX4=*d?a(m?sA}M!|AfmUs2*@>Aj$n!uk06ohDC!;YKkz%e_Gs_EZ?C`vH@$W zhm#{%mEw8Hty#$kBsK!t#eBqWebvIe`#IlhtlqrCp=7xp8!J;fv+-w*7+Pk5mF?!2 z;%d$!Jg2Uu=K(o%mmyvmT}TgJn=tZk7tdSFzla{aC|cixj^ZHB4n@N27(WVinemVF z1j$CEgyhrhsslpntv@{rp#E8}48hDz)=*cvsSJIVs)%%8#|Yn~foJ4MF$Hx!p~M~`RprZj%@0rTb2x{}f^ezN9RZK8{6z(b#B(Bj3>{B`-M1}oi8 zuGmX`xF05HY9%0U>3*mocT4H=4OeWzjPKB?q`N0=DWc|^uCb47JDykihV(N+mkHi8 zAouw4Ti4Ed%-x5Y;|R?%;8VuyOUSDrkSDCu%OzPIC>RAkT=xnCn`r^ct-}49axHc? zL0;GH>`KU)k3hkbQWoCv>(4hd1*kNIuoanQItcT!sX8Co701w*8<*t>QWpoP%Oqk{ zh)O-(9O)bI@`$Ibf@d|};R$mi1}SE31MAZT@MLGkjh7D7*ODw-4F9%vj44X!mBacC zsFwJ1Jy9=a&3aqBm8O>9*Vbg8_UPj=jYFDL7e2=&x!p&%bm#V@a&tFvOS;TCE;gTW zcgwE1VM>^DMveEQ^u)tuJ+IB~xF??J4JiT)6VI>E+XnFBn4$hFKu-96l>W~$Yz`+w zTz5vY_nlTO-e0T-I6A`4x9~xoaY$FhZxICG;p8VS3GZxDfk_lSZh?=7;c-sDA?}@B z{CtL3MXaH+D5JRn=93+47l-IJE^!_F!v7H`wsA@7WEU~W{lKCuk4l;wkUZJh>(-`3 zW+{GSqRAj@boi||aCVhc|1_fUx>xDzsOl#>*XQaT%~+fD^cb(kS~@rt&9gTgyIG`2 zJ5-*cR7eCYPuZOtEoWvgl*0fJSRR0DtzZh~#vLpVxY(VtGr8F}Oe;*~VuF!f7(Tr6 zG&)&|26Ht!Wv_6{o#VS*>^?s1LMRAwcY=njU|6#8lg?#WL*xieGss+=65CprJTf1r znBsQFGt6AMZe&Z8hIh?C_&Gz6bZq2^LmB-J2Xv4_>Gi=bdg8UzPPzuXH7s$y;~JCK zsFhnFEApOS14filltsyls(+J1S5)M6Db2Y>KFQ6qwN_wS79yVPpeHHcDG-$gVwZ&n zR1o8CJ7>4ViD@Um&|H5T@T$qoG@Os#Kitx8*m~Uaj|7)$W~8@$sLJr8u4XDeu}mti zW)?f~Y;qwT<6*jV)qJv>Uv4)gDZen)ILVCgN?(M#ojQR?%4ae6s<$OtIF9li1_m8X zT|>AJ7nM_;!UMl9_@%otg);F+yK>pUlQJdV5%p4))HCB6F{R!O8t~1cF(sVK3nR`d zeTykB0d;7v99K$gR$eoqm7j7D8ZFbkO_rLMm(B@mo{-&r2Rsz)Nh}YjO3A2q@+F}6Z=`D8l)+yNK0)=E>=}kmV(}xSfKi2PRjBl zhauXAI1Yyq+`mA)o4+ok0=0z_XkU(h#tUxWfzkK#{)~wH&uLsi0=_Zp9h+W&Mf5Ve zj^~Wzav$roKV!-+JG~6ZF&clIc%t8t)?hsbkO(St2flp$ri%=a;nVMj5e(OXFjV{c zVMom$j4^GG0$EFkEF`83$?ofqE2uC}_HkZ;fL#Ht@tZDkSy05!f0-Jm((za1l&`wPRE#(KmSsAhADpyntSb?b1!^Iuhf^nY)cu} zC%R>w(J!HfPgH`2@pKE1g{o&lCzZ8`H)7$!oK4y=-Mp!rVuy(4>`t1^Ml5*C`4)iRGQ*yw?^~cVSK*_|;A4y{K zNVJWn_$vSVud)A_&e^G<$HP2A6$~@{=YcNdJ;_YmZ?mQ5mSVD1W#t&`jRhsDb90fI znut|-J$ApEo#6F&71#k~TX355KH9QFJ#kzS9>;F^{C3Mj<0*u@0P5t) z&)!;O3dqiu9{-8Zp8!@q|GhA$kOM-Y!QnxBhR5e{dMZ< zmyJyKGvPBwe{hgSYrds2HewspryDfjqtGXz2|$VTYHx3gJbSGUtd;#apPHF!Ak9Gy2lE3$rO=vjtChzaPo>!_=Q4C_tF-M!qIB!t4~Ev{ z_T~1CiX|VIOOjsKrn*Uv_^GzbENeHI?l9ls*JPU%R$0P}#GrP)y7iwMukcaY8$@Y5 z^Tl#54|TGZ$`4x8mo0mm7Y`fi6DAiBmy-^lT{l=~KLc)`*sk99;mFIA`TINW@B_)uj%Ps%Qn%k5A?>o_MYL_i1nUV; z@H@V~iys^CR}(glg1SnWek0xHCX`V}z!wt4VvFmO5i$=XC^jr($1r1$we6Y@89`Ez z4xz(JQ!$GIg8|j`w#dGlN?qI}TWk)QpU>f4LSZ?43h85p-oWcu9uV3Ha@C!=IC_T4z zjk8h>8%EHL%!e|qnJ4MccV(;7^6iyfi>`$9VT6pLT8Ok2jW&+D9$R^_a+&?HPpzggD7iGL$7p}b( z^=^YD?}}bZ8$|0KC0A%&!Ny!yBlqQe%SdgIqT$* z25~%jXRMLB1NvZCu77dBKyE_uYb}C5R{+I%;{l=k@SF_s>bQ&Hw9}7s<8C%jO|lqA z-s}c_D+A^9-CJG8er7u0j~8WMH@?M!KE$fM`}ZO{5^sT(e{DU&MBXWvb`-N6U1`T; zfk$lCZ&SvfDQfepcP&4ruq*11tphJbMcrY1s)tV-BhisEN@APqJ2Ff@ps|U$3Q4cb ztCwD~%&z1=D?rPyQ#aR(X3 zxAeo3X!Cvo20ZvM8bGb%oc_BaLy`bWeklh&)ZfM${)SADXamCmfC^zr?>tlg9Owqi zZiu4`ckQnoLFY#DUTLTWCuQ zytY|8b|W((Z%vVFoFp$9f*NJ8f2X?jG{|!<$v3OvN1Pg7>I+~k(XvlrthSMn$sIR8 ze#H=1Ei~=|IbuvSU6k_RZ_Fn9sZl3vjkRF(t~kAT9PR293RrlYzekQ!wLKTtiyu$W zNIDqxr?YG1Ka}%Zw9nL+bAY9K=YDx1QEfW%1^Y5#|oXS5J)BTAx~Hysaw8v+j+kBN&9sZ*v+mo|_ow z;~d4TpyV8lO3atTv{CytpWvAFjHAPx$`^)#sL2UBkUSKdFvKE#!Io^df zb>y5x051|~gO}RPbKSg%KP-!UOYVK#klSVxMMyslz+wf5IX||8&NPnUw9VaTiNLxM zQ+GC}JWZ@@oSe5GrkW#m2d{-oxujfV#{1-r(uCbcAWhGlIFS#9yEplOev6T{So4%^ z%asExBJR;vcjYQ&1@opxOua6ZS}!A{HCb|N=hIoP9X zf+Ep~>LElY&k2)US`rik{tP|UgEn8bqk@9IsRw=lMNPW>YJd+@&g#)m4N#w!54iko z@Zy_6m21Xzd<#OYA=y%=i=8fXsTUcF{n&-6I1d$I_e>=MjG+DUQ-RTE9lgNSbNT>5hKu^lo> zM#^>HJ4*U9txE3aCvgv0P44>)@2N4F3CE{dbMcnFjYL_qzxBI@Dn+#YLWG{LklO&h^LZ1Uw%fTupQk$W2vqdngjgrE-j~Dn=kz#_avtS+QZq zB3Ptxi8MtWbs@6NIyL_}l4UvIj}@{uNwao~_F5isf9u&+Nij6ve{QpdN0j!r5rR^R zt-yqYk3{Dte4sCc%l}NxqaA?FclZ&3KnbObPs&PJMd{bumTN2woXhub%vAm3eDXr< z3u#DwiStG{uJ>el_z(+GMmlEAEgV$1YsDj!x3dvP#iFmf_$R}9L05&mY$jxCZnQBj ziqqu>?v%^sb48d#O^e?dZ!9LS>uwJT3rpz>j!QJO42`JmjqswMOd1Nu{qOX5LOh$}$qz4dp(pC8WhiNuFch(*AFFQ@GVE^7~ZAAI&kGEgoUpl~CWHG8fBK+CvQ|}7d1_AU|-YY&;Q4_u$ z`&6a|c>^Yl{FT?BWi{4Q8+|+k^ak!xNBeACWG}0o-|nelFThI09&H*F?xaR$vWi9TxgSTO$gI17p*woXLeVW8N% zL(4(Ghx$gn{OLgM?CadPC$ud6D0AKY6JpTDHqutUbtOx5xU!n7t)9rYu~i!N8ar^k zrFFJV%&OivX1l(n0%#=;ROVcTzV&KRTmf|RZR@jbB|(ln<5pu88a9-V&R7@{9EjEs zS-2<`5)##n9TvN*K^aFM#s^t@9MZKqgqUUDU-8a;Q}4c;Jm@4-hj(yrWu4axz9@dA zXT7d}4>n7v0H8BSP=FOFosV#s;@yg zpY&-i@Kk(}D*Fh_ek3Rza^$Wji6luI4!yOcQ+dCm)dBQ};H zolQ^672zUaNbDQq*0mum4L1E{>i45^D56mkBgpYC0D3!&M+6;>Q;n)KQ>2!WC)dm$ zw6571E~JwP5Hy?H94-T(zT6#*IBw>9pA z;0(Nda;t&>*J}MFt zd^P1v2Koq*+S7o;P?YBLIX@-Xe~Lrbw`9Sa|M8Zk8>cy+cIm2MUUUc@-8Nt&0pzp6 zoe^B9yIbmUB)B|Yx0hPCO5q`Dl%n2$X#_>!DfUy4d+TY+wB~3Y%&uQkAg~cEAAdM| zA|WvSm0Wk*(_$`l^ia^1;B*BQXcq`li<2=w4dFWtK^63sPEZ>wCLJyW7n2T?>cCG1 z0jwo5EY1t0Gvdec=*~YOiWY)%NJTYiC_jcE6Re2`x+(tK@FbYdGpr}?;|W@_Acaon zcn_$Mql{^&2-PvGOZz1!(Yv9*Sg3!Z#cO+3ZDggx*j*0z>{7w$P7FKRA-`EWyotsZ zM<+D$ML3zdHZX=@BaICI#!e9V;+GsU2Pds5M=6Py5hzA*hL^>MV7yX99xqY&cbXLn)fy znD8U0nHWh%?RR)xnTj3Gq_1Rf7*X)0m|k)<@FfU4kSP1)HNI|02bz)_4J!NpkGLwW z0`%&u#+I88$plR4lrx{|CG%w)zQIQi^`n`h#J!#iu}glY_Ppa;h#j5jD>Nn67s-K= zd8k!1FPH))e|*Wu$Nly?`@@@$s7<9d-0w9L=~#zi2~FR=pHL3&!^S0f{aoUW@v~5L zC8>#60g2QRSpoQwfI(Rgh5PEp>nsJJ`~=$WuQtf*y=gZ;SXC9bXg7XD9_g%h|HTx^ z-1M_4QuTZx&G^cd$fMx=qLk6$p^k@@K_DsfgnCx#zV$#%bmca*MeopDZ68I=Wz^Sk zRb=I?DWQ{K%8+-8^qR9dippcT+Q|M;J+;;wO>YkDAFebNQEB>>H>a4yWca0}vB*+|iKYQOwBN@&Wj$`F1&B!vUPSnTIfB-k z)as&eM4ilg>#C;r6+0UYQk-5f4a)) zoR$wl%XIibd%naH2d}0NsDieK9)b!Z}TI z-EW8ya}3ZW=h*g49N6vU@wR#F<-_x*LrANFJt&+hDhX~2^n7(;7^hr!~L}^2$C(V=tmwT;Q z77t=hZf{O*FN5dG^Y1Wq)c(~7-?3)zR4GqTZV22(E(Zd4k;xTGIQFR@f!_S_plV`5*MW zK70Hc82?DbQhjGzJ$5SgDa(YV`c4n+&@^k)ry)?t(6vHwL1E+?r2c#_)hHDwyDrY2 zE4$3G(J^ReJ9Rykmd}2~l?^*Zs7$CV%y$HJTY|H%mWhnqb7)PG&DB+KEqcb0`Y}5T78W)Bm(A(d^})^{vs2yxM3%#eZbb+$7zTKtQFBZU}TRc z3UA){;gCI}B_A8tg)Jy2PjuVY;NUx>2B4?HyB!o8pfk+p`5EFLix-F2-QGVKmk{2w z@qOck{hQOp4ODycQ*Hu0nWBVAF8gB50@d(1(cK?XQ^IYxQT2Tu^B!8V?=Ifab$=^Z zD)3$_oTx3Z?w*)fENJSk!SE-m#h(75@HXSQX^8qFaY`r_f${^lPX!Ix#CsNuW&<(L zo`seZk}W$Wd}qt=aD8I(N`-si4N;(_ z#kq{kGsi)6OOIJanK11@bd zW<}|mx5E2)M@UVbl(i4}M}$~~8VtP+XNiUG__AfGkR3% z*B;t`pz#SCS&hCamzi}m->*~M7jl`fnlv7@wlsY6RTL|zq`}rB(;kx`{jB~h zz})U(=Pssxe6KnT5W0`YAKv0TxECKP?p!wA%*I#bQFo-nS#RUKXi?EHKPVT*y5M_6 zUGc3cttn?_PP9Lby4EqTVZ2MeAKVW%+}@bkP_KA@IIKA<6W8aYfnAA3GrZ;7E zk@`|@SaulyHayX_`r?EkeB1rzJvsP#8dxU$-TU2nfakHGyLT_o3Am-#O|Fb1n22_!4`BHmXovMXYghiveEQ>^$O9D74M*4S zISAbc#xo0w_v>;`ck3a;eN#>1HOI2F$(K~7j%m*8tBPmb_8fsH>tc4Ugg`qo&zAdd}ZWQrpfba8wY{npZe`-U&LWjM>$5%aA7#?v$IjK8AJzs&Ij zXXIUxYYMnY>f8pWd0*zffOa`@>*BC1D3q<0SlSCRRZ`*NCerD}kR7PdQ5L;@*}st9 zcBot*x%`f$R|by=7wmj>EdC5yh|t2+Zua&>0~cC^@W51o3kcdFdWKO1Ly-sLI7D|X`_@pG>*fcpu<}gO+N1KF zPuQaZt}imKY4P>94ULrBM);byv}Pf zI>hpBU^ub8bR_kNz|&IaHMU-xwL3?`;5k=&GK!eS`3KAx3AOF9$p&Xn-E*|H0`nh( z-Bw_|1%&n`LvuNNdj*~x*w#6rSX^MPcS_#G@C|=V~U4kRZaUc z*|@(Scy<_N$QYVW4sd>0S7t6?a<60Hgo=d>| zOjtSt$JV4viv*%74N@6036PK$F#dyzwx~=~1YX*F67k_@7Sf8`e#tl!5r0d2HZ{3` zN^g!XtRQGRwixjmvV^n>cVV*9WQ`Cn%`ZKo+|-ztwuof5T-EVM#4+>yGGb18W>G(+ z=>FA3vUjFYcL-FVf*)Y}@@Zi|b(E6Uu?D3r?oy%*p{l$!MZ3pn~;`|EBepG7S*s?AJ( z!F`}BM9i;%NsBnA>ZL#%Q~%rp$3vJ|0TYR6&O$w~EOGZf#0Le!PV+$5)f&KblhyFD&M?Yzu`N-j_gu*4Fza-L`@9WHaso`MXPv7p>Sp+gbF7Vo zlDST^(jF&|60#26XTgUKUTJK?TQ_qQY>xx`BskK-#??7EM^l>+Drbsf=S{RG=hg73 zFBUrI0yox%OFr8WpKZ>YSC4~Rm9({Z%H1rdp@N364a0BDzV56?IQN8kk06-&?Hqqi zjh*QNb^;}=_P(Z760h7X0u|7mRE3zkP34=$*^q>LI1SIbGH`uoUZ>NI;tKbpZ3G&c z0c$|g2Ta?2f`+cZCXmhn4Ns-C+GZGZ1|7J<+a=RDap{^C+IsgE9U3gvqxdlgNk*D4-ymJSrwqftBO zYgzsnu3E@~>KA*H`-$0Z}|UT;)zTuO!0Rl+eT%-%T_ zc1A7rrJ2b)Nk*j{CX3HVlo?x(=GWH@Y7oRM7Zmo^+|mcf9@Aax#&Uj(_>{oSCNwg? zt9{ia^Um}8o%!&!aHC6Y;1OZuL!6oJ-TFflS)D1_b>E)5b%-rGBr?s+q`0-t+I-rk zuExw{C%LuwvP9=`mgMo6cPV{zpRK2uUhY~&rSR?uOgBG4+F|5!D{N2h$DNS}sLYMZP35t(KhhF?i!jJS) znP>w&&I9HkukIUIdjV8%ZH(zQ{6y604rdOG+)ng*-|4$1 zA$iuV$6MCNWo0WLS zRy7V4gU4P{hWfrxqBNSB4}(^BbAp_#UG4F1?8+f|A>kP1j3i?)#Lu)sDc0v9cNDYB zC@$*|QMaS?u^O>XY|8LGptQ3{aD~syE0gSf$Vs3J^yR}hvNP1stTRmv+Bp7v6*6?Ux<9MJQl{U!f zC}?_AweScxPqa$+vSYAT%Vt)m!|1)Q`d&+q7wqj0HNWvKz!QdfMZ$a?5)C7^y|%4= zmr7Qm!uw_Vdlvt>ud{Gv%>V^VQ=IVZlGmo@Rn3PItN?Z_30HChADuJs2Y{dkj;KoY zG++AgAyuUhW-8i{77%b3a?2j{-r%{c-zN@=a)nT@>^#r&uhHqJVC9zPtrOK+tPZ1B z5w9e!&0kVsY+mJOJq+A}P)w+$-xvnGkbcvnhfDi{6E00f(u@GCLFc5}uUmJ;StnK@ zsJE*(MPS1}uGxw_-z=;CD0c~Qt&z7cd247Bo0#%qiC%&C+s3C_Nj^9z!@_@^~xS&_#1mp0`MaUTlt1jOn-1glM27x0ki{T-V@B} z=^*U*1U{%GwEcMHsnkW}+%Q=OxS5h!zS+^D^4ia_^*S$!Zn@y!x?!><8$Y6e(NI1g z;rDfg)rRG+7sX2?TasIdDm7`0-WJmzSn@x(#hw(~&-Wsn6zuGES4auFLSGRRxeHdS zb{=ZHJbUS0maK|Jp|ZaZ_G^h6fn}O1#S8ORuo5?`%dFD+Fr$Ln^xEup$BHWLaC+qP zQKK%{Z{$*WLxvIH8aA5t+~>`3l@~x$8BLb4TU#DSO}S1}R97;Z2)qt(UpRJ=8zIWA zG2rz?>8Z}e;yE-wjyKn#y@#KN<<;AV$4z7Y$j-K|Akdk%`g}`dTZDo9itEY&M*-_S z7M}C2|9E7F991&l<3t|Tdny|DP<4yi$?12VC3&rGrv8N{*0ME41-VMvXw&UHiJ08_ z^x9bbZIK*kHhkgTtS3fL6rT1+-$&p1RZR0B;Z-&$;{rzbirEQ_$TPql9HpOLN0~n7 z9Vumy%nBzILj+TyE$%7V&K)J{3D2(#4P$VlDJ+G6@WRpTy{i11e+msr%7BRP4q68; zd7<1O8)i9Y-F>CQ534zSUib~s&##m=ybol#1zp&FCEeh_Ve=m}z}5c5mA{E@A?U9; zk{QqaD^xC${VL9CrZ`A4;Xuz9H@)zzN}q25A$)cEghK=_`ZXn`|8m><34+Kc`gse0 z4)b*cPvpo;VrxQSBYl?J^%+XE-cFP+oEqDbwG8cU0wnY&Amy2K)Vwn&i5>mza_}B6 z6QFQLhTt}Tt@sdiOet$yrZz=gxeirS?POMfGT)F&_Xr04_ClX)V)uhcZCxU_RZUvdp3vmpeI(}k7KhC*$iw*fwsxeP@PXiuUn9nM zF0YEZQ2{;^cy3{3MczkS{YZUX^8C?o8x4vZp+O$)3y%^PIbEUhg)eTsIScDN(3^vp zFPK%|at5h3m_lDBPF%`tO}MHR?ErN-z-x8BoC-YhQFqu zPl7a3^%w9WJpAkxzOJ(B-{D30_(2pn9`f&5EX2a+Mzb%g{(ZP4Gklv5Y-KYcoaTMC ztZ9-^!`$ff(f+!SKwGG=u2`qWBr54(Bv^RWCeEIyvKjd(@OH)9E#%e*1&Z*|18Fkd zKEv?Q^~B?4Tlm5iF8-=XT+C0|_=_>L*vvM6e4Z0GQg;cewsg8nmfKGHaz=C*D^0_3 z2Q8?O6>?`Lm?fUpAfo@>U3fE+mB=2H=W-OrGgxGhXMknC3OIszp!Y1n?)HO?Lcri` zD=vMfiXCsX9=!5Q#;+kkF%F)5xc zHXB$*+P%An%^7ph!SHK?bG?ALm)b!|ORr-T2T5f(`m9vY!E*_h7@DTOFFMA3Y+M%j zy|z5s2BecO>YqO7&%?}Cx^l2Q$**%5{~5^`{O!YSB8q>_rf7WzX4(YK4;co=E1L`c zg(0lJqF)-?DrG&@>dE>3@prDGp5r;o{!1&z- zjZyK@RL$Wd5ihHvBgE~+n#nyrZh(|oGj4v!qnU!vmM+2u^uxxGmuL>*FSbypi+w(2 zmOTvK>o#3{#O*~rRRCk%z%MJFU?46lTA9A)BzDpFk(ohp3DQ}4!xfsNFF=mb+xBc_ zKJEu^%zs`=TozTDs(SyW+j0 zt=u2ywb|ctYODvWEEAbkOFv*%xctU&JMgz$dZ(tX%xJZe{7#&M8zDw9b0aWFg)f}> z!f9B2i1UX!Ij$ly+nfAg-7g4;l;1PkOS``sdS$Yo`#+SUSfT#$D1v-XUAZiTxvcxZ zykq7mMPtQp_%s>U#%f1acKtM3Xgjn+=IKncBf7&s3i@kav;3Jil2|bE%HRF~d^1tDYVee| zUPJ_`)wg#Q#qDRQ(S`Q(l}6ReOY-WrvlBQ_h;=i9lv|ROdq{!6ZA?2Q9L4lBl}U11 z4)B23Ls#l!Fu#IoMp=oyvo0+V^Gd2lY=j#v?F@JT*R(|NWfs}^5}d4-bkLG?&?4)i zN8iLQoX|-CGL6-_Ws2EM=sz7C;pITgottZ- zF3+xN+vs~h8;Nd+q;jC#78Zq7AZe{7B%GXzyt(ETEIXMU6v=C(jAtks6=u$I6g_xr zM&LPc>(#R_w%t%<-8{c@cjcMdu)Im`CN`29&Aok?te(tzmM+^WnXC7FoZVTA!KgIu zI-&3Gz3~Gb*CTF{Pv}sq(sB0*eOoF2ou%dVM*HZhj}hzfCpV<@!0k-L^kAYDsivvAmr4N%1`Yjj_uKssXU31f z%14n|pY#JUh06?v+tL3Z->IqZ?}K{kqD9xM)TfsNoKxCzIbe`FsNK4u&UCe9XCfcX z7MpSz3+0sRlC4L*=DmnKoIH}~`B5+qu#APD3EkH6H$0_fq?L4L8zVh>uoFn_@>*Xt zPJ|IHA-bGsqVPFbi_V!NW_y@O>-KV-89}z{?B-j@NR(pp{@IPGeb83QZV1oDxAF^1 zw$tPiL}Ydquta2bUgL8n_Z0_#A?uzclLMU|@3fjXJqsp7Iz0=lGd2B{^M+w;>!5Vr z0jVS0^eX&#`&)vCN8Hh}QkD2c)cGrF<3}$jjA~o(*tq+Tt&1YrB1xh*PQHJ^GoVYR zxGJ3_jX5m(i#dEK-xnxqXxWz;zb?WTLQ2_qn_F!H1FQzjP|_9Q7cCOm7%%2tWn)Yg zU^NwKyl~}~YIr)?A&nL~Gg7$AG!QZepCc;MQH|lj&KXQIVWh(S?}#20H?s>zz%(BA zzYU|%^xHGsw3pye+%)qtoz`!M{wKtlw=WtMvTt8B9%raCu=cffdSK7#i3;t#A+Xs0 z0WPBqbngwguz&OFZ*%v>59y7B?GC(G7S%cb=8c@b@>2p`?3ML>u;ay0vwKf*I%kpD z&>l(EO^E^73}FlAe7ntO-6Auqy;hV6aqGhx?IOLouad_M;G2GBx!Ka@^pRS}`oe?7SslBaF=mFj=NOksyAL2Y3OFf1|e zzrZC}RA1pK@t-Y>OVK6lT6%}~WZmcbyvz0btKcj<80@PFj$b#K1Q0L-kJ}9F1U!ja zkRQ!UT=9GDcp^BZcnSYZ05QNgN~b;h?Frf#?U+)L^3HV4U~W{ssJvm!VAl&qka|9* z!S674*B73x!s&ZXO1(QeJuJF_5Hwa_-ZK6xb+*)6Fv;;(^|0SfAcim zihkb1Xqft6poyX9$0?=o3Y|Pe0&cGj5#?V4*;k~soO8l3l|6O5UruO5Z0~ICB%Zw{i^E z$}g13wrinx5k}XqWif&n>gBW{Atup{z?(s|sTS z9xSU5KTepUo7*qtYLDlV6X~?Z;aHWl#@XC5X66Xdnn$gg2R|^`5ax!^6fDta?7@3k zD-<&*Kb`w+Q-v%)YB#+P7(7w)DUh{rYz9q!Cj9g&{CgnEIH$l^dhlFHyzU`sE5o?h z3UJ1WG)3NMe3vRImk0PNS%g~dD4yQ+eO%LzGS2Xy8#bRDe0dtQl0B(KBe!Fle)KQ? z+(7)~B%ORrN3O&W6b2t)hv|fgFTbeeY#UmybvzXw;1MAlD`SLFH>+ogi9cTG1Hl37 zEebRkDfnEtPA!vADf#3zN-W|m9(hW6N?w_{fHD%N?kAnsvwfN#Lxa0MD&zb$X_$!e z=SxI2MPeWm&93MtC&h#+I$3K#3r<@)4NrMXJR)jd;^|wKcvTv8z=|(?3 zRb2eslcn37vq%7wY<6o-ro5BD#eeF1c0Q;@CTSUO5hgWAnc6sAy3vVJ$|D`T@ItKx zV#Jf{_rv}(iYqqS%ppj3h!3c?uV;0SaW3twWj+TYshjJU9VWK%HL5mu@oil8PVR%( z-)ix{h?a^k@B2W6hF;zV^KZe7R$d9ijAo%qsBa>Em>dd&hE`qy2 zL@2){5h#6>baq&F`;46Fwjy3QlsQy-@bcx$Ow4C~{M1Z*{5<^C&tLY(tXG7=^@GC> zl`yO8z9YXxj3wU%bFUZ4_9c@4z#a)9Jqz8jFt4^pzM4&2%*!~A)6mdRnZ0iHZtV-X z`i8@7(lt<1{J!D?VewZ)W|Q`J8s%J?ENDoT`qcjn%Uv_(^D2UyS=4*0**R6-FNp9O z9A6OONjS!GRQo=+zg8$zUDKrh2_Hila{lT&@^ew_UEeoYlJ3-hNk!jkm}IJ6`)JVb z!7EXP-00K%TD#R0PQB_vehwH@R^4G_KL1MKK7cA}l9XO~kX3Xc_;`bQzpVJScO4-$ zgiZj(yUZL*(t~;q9!wc>`KlT@TNL}y_rEJmJfJ?ky3D9^x=k(|%8-*+0m#oquvdMb zVM#hsXT#%AgzUVMLgDa9P3ie0iNRBUlr zttj=*D{3l#H0FjpR1>>~+CqH7FCS3}Et^o1HRO*_$f&5Zk1xp-GVv}3^*MoL;ogJz zcfU6(X-$psFGF5o`%=S+BltZ-zuT-_3QX)Ky{WI5+84%bi_- zSBK#jDK~0`_8%+sH2CKm(H_I}3?rKCu|Prb(__iKWha&kdLvV2e#coZSEZxu1*O?3 zI_pf0CjBu2b4I-@2v<}sVK#h%MF6w!jea(K4KPG&&x;$~ZLUexMpewb+24a&L$CND z5A;iVaYjoUiTr|Fa#6rIqn1X}D6NdmDYJ%)*~c~JRnvwZjZ*t~%hXL$v%kWUk$RnV z)LIQT<9M{BO@VlO?8$EyRSTU5IXVTZdYeu0Md0kRfrqFAJ(gSHN*}#hpO6DFnM?L> z_a6NZQ3uC;4Z1Q>#gl?8npQ?H2Fhdo;yh?enIWtAQL7q5c-J}^dXaE5% z8|r~gEp9R;T0%^jIdK0LH%ysj{|8(^npJu)3%yc>p2`U^WmfgrgIZ8`rh6gsmrzE5 z@oBSFk*iTx4_LM?DX2%ZO7AJ)$c2OwkUOmg>qRi820OVVC5{;IeQ$S3i$L+>APRM- z=yS^xqEL78|L5?h(qA?If`x6EMTg7BS2Bp_DzEeq&n-v23g!m~TAmKbucPuCL&tr0 ze__HBc#(~DmOI@yuId!*^Y*LE8TjM5?Su800Lb30+F-r3M+Yn&xya>{1teHdkhIOd;CZZ0oU{KkjYq@wkHsmb84FV-TZppM6|v4UG>w zD%eT?XDHzYE8+&{9|(RE&8yu0c$qqot~~3=JpfJie zLU)eHisGE$4EiskAcc|qQz6l(Lg!8ql)Nq>rJQ+|L%XCBI!5_VYf+t?JWF)v$W_0% zybWT}sayfc2-+H>W_>g(3hLWWYl}(8>u z=h$@lpW|=ch2APK?C!o0P5Yh~ckcB6C89gWX329+ybTiSS7adBdm)i#ocNGz$V2cG zS+OKimvP!hq9$d=7DDYEyu6O}^7{4}o_S^{;meVTwIN(t-@T#yk%)hxSf^~4tFD~? zl>+jWDM1=66<4xcH(<`ROV|8T?nv$^vhw?z zFmw8QgPTrsrJMEhUL|3jq|%5fxktwPJoD!Byj_Kyi}8#fV&Qymj%AM{_+-y`qWRt( zzdH`&llMt_;F^2UEZi(S$J5N;%s|+r!Cs;o8yS@Z;Lk;_zoHxLov? z0%j)}nr@6;4T7P6#cCM`dvQ&>aZOUG(&q-+gH)hI0=pvlK)%unb+6z2@xWT1|lvH4(2QaKNx-r#8<}%cFUb>N{M^T)hi{OoR zR8`QX`){uS-2g7Hk=fhOAkPmXT08WNh(N^b?WIt%JN`RY5Ps9D&x$RC3q;;zgav{t z>q_5r^HWG(iKEwzY_5oY%+VEtkb(%yI<-W+1){o?1W0>V)X9-4_17dHm+1sh7}oJq z!^Z7|Mm|3XWwpw)AYyUY*DlLFDvUkioj)Sni$TPXkAXXDp4y+$>~Y+o<Oq zz4n{{UxhVX?XbbI-pzVAwKXP|&b*UP+L5FBf`IVR)iWrZX>&aL8kHSJX*a4Tie8V} ziHawNUN8TNoOUp5i%OXrIep9eWm7#R|B43`VADlz!{w@W`0-(+N8Z%I*=yY9;$5HA zx-G=vAWGEpn85Ukd0%juce`oJb2_ywO5cghw)m=pm_2os$A;V>sug){QlOEXC#t>%PVy_~TEzFALpc)PBty+$FXt5|X#)t3{lM-@4b zcgW9A&dRU%dX|j$-Y;}R5dd$Abl}b^OaQeve|`XH0>uYJ7C}f@dd(n$o|JlRET!!= z>b~r&gHY6#u(H*CC{j!4KF4QGb1yQBtRIA$zu@q%h<}oq(D_prTjb0SoF*Q_1nGmH zAv&ZL?`d8B5=)TpWPO)cmQRkMtdw2H1CWhI6V3)*9?=FGzK)(5gcL*WMD93OkCEm~ zaN&OX)J(TKL}FUlS|{j6Gw*O<4QHC4Vr$=Z#SVlgv-UEv0AkOfypFe!9zrJof6N{X z5!}@F)D?_k?+VV|Ro4p_TYKoHeEdHDeoqA>$bR|$cg{EUE!Pk=7TpTB?mmHT-a8mM38iFI=Hmt=nDY7w#y;Xz3vs7X!~a6Zu1daf$q)pE{wY%T1Gx zHt?dv%SuseF}>a!5AUKkFPKm|-3}fW>yfY40At&nUXbuuD`RT5Z#hC$?!*smGOpFVC zNC6cUUn1?FQs}f8@l)mu8ac&X0q+hf=V*(Co-b@NHr`1lWbBk)uw-Yf%ip1ye-Ds$ z-(ktRy^8|g6#}@xn~WVFX_M0}vIF0Cz2OLS=7_{6F)e>)U5w_;RRiGr?4I<2U3t&s zU9)UK0^RbJXIU@)|_@@H7>pUFy1anGH;IB?*&@VwH~jLLIi z4^~FLS!&;OyNSFTOxd=OsUTBAIi;SnaK@Tzw-kts6(fi+FD)sK{ zhXd0$<$~0An;+j@{czIz1q;>hrcxHF-<|Xt1#4d-@5axdMt8155JYgaB;^0zfhq5U z;J0M5f`*uZf{(xT-70SgSs>Slf5kS|zc#H;Kl47A)&!dfcOQM5WBuZ=TKT(xj7`wgssg6!GwB z;1WjO_5%!?XC6qTKXQ65OlP#w)laM^G)$Ip-wTcBRhdBX&v#^_M*v!7QX&JT7YhUz zVGm8F)yC5AP5*u@pOW8j-eL|74S|M+24!tW&bMT3M}9@#pSA3mZ8|Buw}LmdYkwY3 z%T#8>`?J(PvTugn9HcdQw&tr1l&X0Yjn0Jb>3m{tUEHi|y1TTwAQ91Mj^A78u&||V zX&QCBGQ+&MNbVT&9i!Y1CP`o#iM9SEkKwb%T$ETM% zOD*%>DXkEf)@^L^u+F_I&mL>9rjq08-L=b5b-y?}F8TI?%!K(oe_fl5z#l6{b0V_0 zsqWtzU${s5DAmM$;sHb5*Y}l-PKn}LLy{rlkai_z03CoXEKg0o?0hKnLN#qSPBNwR zy6ggJsbzHj3U~{!UEV&t1&Q+e|2ka`9T;s}dAO)(&p7`eM{cjErYFW5e^=%gz-adi z;pIiQ?7c@b@MUex?L^X^29h4qo(5e+(zp70iLPK+6C8>V{uOHS2>z*FoUk39vQ4K{ zUv7KCc*Ds&+V?qC5bsof$H8te@=3ecnV`Yw)dOWwH0{_Muna^D!kOQ`W0>FhCSA&c zvk^Z*bl@G(g6l&ZcoK>}Ve*|V=hp?=tu^E-d?$Y=`9|b30T}hfJH|b-<%1U{!V>%1 z{c}yG>>p2Xrq$%ncBXYE1FJ*>Ra)lnhbT7db<>W6ZF~^ssBhkSnGR@*?E+94&ZM{EK5*`}|gFhq5t2vi&>u(ZDwAjw<#m>M*0k2KPyp&oX1lT>xTc-16| zyuAhw&FmeKAlhDs(+&wA>nz^(#CiN|X~(L%@*c|7;#an233V6L+#mS7T&jjlF6&7& zy^iFGwR{DQOze~cT~tA>ylX1L=UWS0SxTZfS*$^*d#x3&_kuS+gKlg=xw`FqJm>tWsrZGYEKo>hQ&MIM_1u}-}?MOqBrpTCfqL00X!o&ixF8;i7vbRuoc zk|%A=cLi#K6&Wy`e=5>OdhCsgsh05MOOv)1UdiW=pgcnpw!tJ7G4ao{`d_S_byyqg z*0+&T9Ev-%P$j}?~uRu|GQOe(4J z@1U3fYpo9Z_BlrstU_=Q{;?y#yH-dfJ2`xq5&1X(io$Yn{$imo3d+%3eR%)N5$_4t zwCm6?ad!vZ@(XWmqo17$C#-% z!k5j5{Jh3kyvt_8wG*q=%dW+jSk*Mc4^eYpdhU{;ohFxuUBWd)mqwJ$ZN-kFlr8ps zyD{I$pZ^i`e9-;TRi}wPp}*?!y6l&O=OJB2GSJfzCO6O{`S9ip{L{1PQteYdQ7h0l za`F@^)VFks+*`UJ0noiGQRU-D{vExQOUpazoR)1Jz_$b0{&aE{Z5_#Px7z$! zCgrda0|&GAyEDAj93WwY$f7uCB&dX1^kU(Ki#O-?J4k(9kmw3PZ>qa?ST9 zW2?x8K*62-EVFX&4{2CEA&5fV0uOz%QNSfl@zi#LX(!k)ZHs{F)k7Afr6%B`Lia6)oEQXRCb`I2@ zPpD-kg!bLbVN(?j*HVgBh;Iq3|B(8Xij(*8Ay|HgSmmtpf!kd3UaI@L@AF(L7S?R3*?|5i- zRcM_$4!3Yx`8kK8Lyn2{=mq*>3D9QT8Wof6K{07OV314fU8PwpcA=@XM#=4K) z+9al-GtO-`m=1|<+?p)nL$aVeoz+*m5J;!V&G@c8%LXxTYcr1b`!q5n%1l4WjBlG}x3JX zv2g&OS|lD(QXf6x$BsIE!jFvu4Qdg6bpLFV%IPP(o*6)aTu12q&5@_S;0`QrcFv!J zt(Pr%!_v-P&o+q={x$mNaer8>KoL^t$7I%?D;TyPlJAFq<5p2*7l@V`Vw>4(DwuOB zdM7lt>g02P{lPm&Wcb$m$hkeaYhb${IAI zE`A|Iq|<)pX=42SMVbz0z2p0FhENM!c3e3l3OO37KoX`llPjhrR{s0u8X%hhuJp16 zx!XJ9y~2|7tx=dp^M*cmBTjkU>oyG zpd2_e%tGcAj^CaDk|%*pP91GTA_lvU+m82bUton`r2$MT%t1CcO37PSe|+Jymw$&T zD|^=sRnl{gW?aX5y4c5wP<;?attMZf?s#|PLlv;(*lACniiVPV(Vus9|J=^p`oNzr z&n?wG?&h#)Sf`)tFxM@Ogr%TEohzao7ZdL~L&>oZcwF0XGcm!|;fB9l6LcN`oB=+4~n`K`K`W|nNSep=dG zY5O;VEBw>nXEEt!dmH9+Q{y~irL5V1W=QX`nID2C9r-9=(cf=Z-_%ZuuBszAkrztEDx+_oWWW<)0?DGRaq&j9qHF*oRgW zBOL8CM2PJVkJY>RLjf;@W*rq8StoCdLEsB|3$WvDl#`^h+NM1Lm$XajyI0QmT+)@C z^69(?jmjxW>La8R2VB0BC>5{Mxe*GLx5GXTp?r9q&WVtMvlaGa*Y`tL{1EXN2@(ir zE0i6iJVJy7V$WjjI_r#YA|4|$xuzZ=@@+ynllnxJ<06&Lh@gkF6;cvQVfl`VjC>RY zDO_oPPouDm>+MCC*ZF~$kx|gds5bbD`2rdROGQ6Q4lXabj!&tLj7JZK0bMXSB6@g9 zcH|K6PGl5@D|7GDY!v8BCgrAfV_+NKu@}=G7b)(Q`aaKF4Yhnif(j`YN)^rNmu7<| z8WRjszFjC|K~vp@ugAJq09)*19s?DWoOjB%4M2zMA&;qeA=|$MqheFvKj^)Mq3`hf zt^QBE9nL-jzCHYYrvLWvyUu5+I@+qX)gyoqykf^BK#OGSs~9$t2mOeIFD2TUQhJbh zUG?T3EJXy%vqOwT_rO!DaOA&Z_Z4}s?xbVF1_FCO{Zx%VZy~$iEu z-~NQhYwg0cuf?V~bR%MT%yQzay=T!jXxB1XX{IkZ2E^=pXEm!uHgj^oG8FGb;v^6g)GQ^V|Nu(L}*nmLJ$e+d-jQky0Oe zs0B<%-yPkLG?~o0$=yWE2~Kr8hFttgcN|w;lP6fYB=HHn6yOda736je(T>5E6L})v zrIjq@*x=H@tp^luc%B$Smt|Ktad0sTpMPIjwqwv>YWwg`xanF8e7m@l2FB7{Ej9Sj zXQJ&c#|XAuXD<}W`qEu-690~J?6*kc7&^(E?`+%^B|^3TcC5K~A9gdcC+m?Kbw+++ zqL#%Zk$0rQcLS5lKHXj7Lv*(y%yY^9ayq)rhiJaS#MJ3|ERr04xk^65If}ev{eB~p z;GC4-yDnz0d@DA^Dn(t7Mrpf1%silr@;vYHX}E?FRe^S}Y15+2g$g98(*?@Yq~mQT z0;xf7F4Umaa!yHhJoWKN3*TutWvAfGGU@s-5FbG@#%>~DCf6Od9sgUD`!0hZk82UV zv$J$H`J{S9ES{6V-Az6!l%~Y0U2ArV;qXVd17b+i<>?2v2|av8ix zr`xD}Fo*9pd>rydF@RiV{SAY(3V(E8lv>0$r{`a2a(_uboR8swPxN(WVapxS3ia6% zcQzHn=J~hMRIVYcLQj<*tm0v3@?F{0y>Hi0fQy20&-cWs9280ZkYk0J$DK2o zuI=}4#*tDbrH;m=w+8{5x~iU5dEHw|eUc1qf)y38YEQVegDuERrjf%x4<*mIfFaKc zCGS~IU^?l?zcaut0VpI?rohN!qi3srVZ}uPIUK@0XHUo4cjSsR{52a%J9fTMJ~&Fc#;bbD=vRPIcGCRe!FYz)bTyAjDC>TluBYQjiO#FXget$hRKIpvS;Ks~ z7Q?!?YIK)wZA*{zqy)!ltL={=sjd6!%gSjRE3+) zc`Lcm8LFslE{dwEkC|sFo^$n=Fft&l1lF$*V#*BMQL}#xQO*p@QSQ={?m$wT7t{Kt zrA@;-%VLXf!VoO^l0ZsFNsO%sk02wnR4<~->E*b}(4D$GHd`hT<+2uXId7gyrLL#9 zpa&Xy01ZFb<|%ZRL;UHPoe?raI~{mkT)on6!6rMEg_VLN3WfuV8-JVjhdb8$v+*BQF30$eOL)j4j!U6X1>dRm z=kXY@|BNDKwQZeQo_4P%g+8@_j1SB%V732;?qLBXgR83jN-zvXh`x3#-YZB$Pu$p z(7B9LlR@aYx)bs;-(%@_8$z0|n6T&wk>_4~YTt)^ssLs1O;C1vAnv{>Z}J-QO9sK~ zTYcwS?5dw*4OI=6O4B_1M^IR429YmyTnc1nIp!Eq0HY-24;_-Ry0?`ed}#>W5vT4> zMGC;wAqJ~cfZ9=R?`l-*3kA>$mo#%zh&GU*vL=fVJX{%U{{19)0kB~rFHZ?37dfxV zqMRCEP4p0=lmYG>1G*T}Y9h=j_H(<`X0d>!Nzw$gRA20V5USHP0~#;9 zm<0XLz)D7*IX9PvNiz>q3`r-w2?NM6t65fqS>EUlQY07Z{B>klS6C@HW=3S${=x5)MG}&! zXoivQ$?j$^lXQ|$RHR~&A*dBV50SW{?7LKI3OW(~eE1cJz3%y2s#3ao|Jk639+LmZ zFm<>(U}_+a&b&y^ zxPYrf&S_NN&L3QjRT!sCzksW>KJhNNXz3!GhQ3mRRQT?YDS;4o^ed5eu$0_<>JY~% z(huNVkaGmZ7U2IPb#LlDCU}p$`x(T(yK2}Njrf^d?K64$8XPS$J%0|pmVNpfbiNIa z06B+GtkZS}Q^`Iu!g}JN8D{x-AdZuzFT$Na&fyhn^u4h=(a{uAwKx?(auY92`HF7S zec|gswCko?Y$w+U$)5ZSnw*W>W9@Z0)|!YWm)PIN(5`>YCsf{b&oh&e@@iu4@u^9UjaY{t<2?icgHA$m{CczC(jTH|C7t*XFKwi@az_vNlK$IQB1l`+pfi+^TH zUIh6enY>fuiyQb-9NddDp(gV6oIpJz@N%|Gzx}v^vf5RJT95w%`Uaa&4=^mq_k-|) zv_pTe_r`1Rgbey_eD3%mf9b}3{i*&;GVt;F6G+C4qf}!|FvM~nuh-FSl|mc*rbsZP zF*??BF5=;^;5;GLrF-*(jiOOyB~5oz@P+J!{A~E;_J}@km1ZD09q}<-=Y>+(E)x(jzaoZQFK38I^Q)N3`b#FuVRl~r**ig9UJKH;Y!5%PKG{o2;$DRi z4opwk(KQ_=1+b>N7jw+%bM!AhWRYAn*_$<1&727geXB0jI-4~c+2wOyB#n81a4;^` zC2aE~f3d?WAF(y9s!d%{Eq#r`STV`=E}-gJzlNYoMkpSm2jf-KxUn0o9?@P3Wm=Q? zUZ%ckaqzPp%=5r$gTiy9RTd#|90;izcV{E0=Re#rr9|7aDi|PyqU&)r`snNu8KR4sw}= zy4x1K@K+)mfJQ%+2iD|eTJ`OM;A^`B3aZt5VLL09iWicg3F@dK58Tv`xI&l^XOZK& zdOQXBAzP~h2RqeWid)zB!U=O$ey9Gcr%5Y)&HJQ3R;3I$#&R!Yn50X?81Dv~br!RR zL}zd7*KHjl9IQetWe#>GJ?`!M>jY~mn^kpWg9IxpZ5-mNs+^s)4}TCsz7(EE*f2vH zX>^&bNbUmtW`q?|f2Y~EHi&&^&A+IPHp;YjKf`KF&@^;9m# z*<hz1v!75X;(Ce!D zGvKCz;IZC^l~Ys2rwHQIPoMu2D!LNs`4JsBc6py)j$;(g^pb#P>u3{Fm?bNpS)nS+ ze$o~n$IXa+Qt6*VE6My{CFno_)TSVE5qo<*QXgx3CNdTC7lI>GQGUX*H_ zz#*vkhB2_h_`jmde89qm^p;Q|h|>^*t1ZESFd6gMGX;IK^~wQW7e(FyCoCY;h+G#T zj;_4L|LpY}`;PMB4$dO~3a|LDwj34Ve2(QhNs5(FwcU)j`QXEmlX5x3^%!fkdr0-Q z1zu%kLzx9U8F@}1zS3YWX-)taeR`ehxOpB{*$AqD1kn~6KsBIT9bhzp=poL!)wrE% zJ9S;2{^Q!1x{z{o2j@Q`iW`f?*IF*&9oXW$ClNt)*{r5hvH~dCFa7@wZqJsIZ|gML zA|n0F8L;jDBUC_!jMJpoZ9FB+Hpq8NL=Joox@U5d!;-)8?RASX>~DI_0b|P;#E3v5 zV^)>pOMbE;Se;%zsx53|R_Y7te}ji;#wCr1s1t+(=a}fL4+@fGhk@j+R7S)e!H<0S zM$!&vn;(hr5SFDmBw)RdJ<-uVLX%!gH9FMQmkd(hhHE$RId8kB6}^jo6(Rb-9@nFO3Z@nJ<|g<8$)n zI2|49KaK7_d=nte&Td2E&OqNzW>OVFZ0LTD<3E_%fo!0q)4PdV{Z z$ne~RWJ0E>jYsU@{6p4PF@$3%7kkq55SONH#=w@wkSXGq^$e=bz6 z`ejfIV`q_oxmO*N@3_&%>Dh*E1@MNWJ|GJ#XS{fOCK;ScKZ-}|ks+!0c`F$AFJf|O z7m4-XVZNjb^Y5@b*eFokPGC!0zc^4?51$4WoTwQCm`%F7dJ{*U0p|#8j|=kO&*v%} zV1vS5E-9h&jU!-HQo3nVJt#7vz5E)9`;Qn>Tb1MfE6!te8w1J0)z$KJecy>o(W|b|eE zQ69CkQ)4&I@uLT4QAUV)Zc@$f$p77iHl)P*3%8W$JyZSx8ISgXz z@OfxT>OOf0Y6R(daOy}o4AZ)-s+I9|7O4H^OIn&}{XN}eP!d5z0A{`Zp1GUf0iBp5 zdJ-2tkia`gn>-lEW7=sTuOF$G_*6zM zEin=F9&`9Brl)C0Yvn#b!pLESKSgMo(z8DF9`jcjLLx!1v5zhcx-E6s6caU{&kt4C z7;Qo)G!^hkZl6m1pj#_9ME^`2*^l6)CB}j-kmryxn~3{9V5MMi>yDY~YK4Db3Jly; zFKJ8|?%{1-sGRq#UMEvE?O^0sA&A+nTD7iP-5usxSWOcB*h!-?XHnUtp(C9;Nogx8 z-dHuNZ^O%={yK9B8T=X?fAxiO&fzR!c#G3}VXHh^SBZ}3b1%|+r&kI8WZt)mShO>8 zd*{3m_f)qiwt7U4B;9_gS6iDr``?%+*hjKS`!#~M(b+o1d9q%;p&+%|m9GA^6b|?7U>h~s69Pjk`w*2*|)3v`d)?=tvdHUHS|Q{R`VJW65ojAjHx z=g)Ymx#aE8`7iWF46AOvzr-zSOj%Gg-P7CGlbT!{T-5tec3F8zptpy(hbXCG9$c(TffgxtYcrGuX3_?w#U<{zpS|oZaP3bK+H(H(YSn7+F0MB_w;cMxCZ>m z_rT=9#2DEvxLy*YPd}kiWiLJ@K84=3Pd};g-5yh(fL`i&@yk)rUD}u|AKi<*XGpkK z>4ZPhTLLh~UlDDgosVGFNnrEAVfnYqmlHp3_NQ6WaCnXpgyVn@t8wy%4@)6qkrWB@ zNt&_-aFbLaV zrL<5LU!kT3c9uL!^)-)qAX%7qw>@1^w@8`dVb%AWTE^6TA7adXi?`@sosP7)0bTU< zZjGZ;bRCXaI5oW#ni2jFW~k{U^-SX%SJvqNW-idwdz!j|_w=9F6ZIZQm3c<}H*<|L zVV)+&)6@wpcc6YZ$)%oxNYtuXL)_I$>+n(+YgOLY#^C83QO^ZZ8R&1!fV|#@jn|8w zX#Kgca*y&hN$~vfsO5${1HM87=4s8X5=U%Ia8#7O(#!0cDByOyu3~K)r*Q>-t8DU0 z)ri@b()*vwU4sy#cZr-P6{D?*19fPY=wqrQ6z;Pq;=>Fq$;_8X2Cgi{b{|s_hGGikSwWMBw%;|xa+K1(Pa2g ztm!pah0^3}&!1Jv6yE#dGNI5oI4j0;u40HLsaiFw;$X47GOJTz6@8S8#yz#J(#K$6 zPHW86?c>l0Qk{4sNk|ZRpM`;G1uMra(Y`*kd$FMjd)OXHr=7=G(Ni$?&d_trr`x8* zMBf&B?HG&g)9^Hot1-xY8p(CN@v$?oewoe{yot-fzq3q!?trDJU220$yBdX_?3hEW%seN2}J`gnNj_)*tGPcH5+JMs4 z*2#v&;w!t%QA6I<{-_4Qj%{%0SNbv@i?&-6x6@ zblL@c85V}k5V0i> zDi=CkBK_|7zp}m&0qjrAx0jhhb2YS@x||4PXDQsYI`lkhWU<}0msy18zX#Pbt+0gF z^iv;{eX3`AYnf<@IWA6$UlZvopxWX>=#YY>YyK*l=(+o=NeSL9EaCL*V^dbchL|w7 z=wpRw?B`cvcG!1Da2Q-o^YB}EGHE?}K7j7V4aZ`4ca$59_g9>p23Y1Z0@616sfHW9 zs+y^f*If9!Fyg{{NhDH*($3KhZJZ{R=5CAK`6=mI2pnjK4Uq7(nn{a%tz*hVW;eVB z`+M04vRW}N25HSnE7K0o&8i@6r3+mr7i(de%h64-XO+OGwceY+|5nBAS5Y?$u?+ZN z>1e?7KM)F+_WW1|_urt`^S*>U)sLVAH&t=SXNPatT7Mlgr9B+1 z_ST2l>3`zt9IU#5}9Gtp(SgS?|y6{^vUte(J9BrY2i~b%~q;f$?aN)V+ z13zo)iBXOu)FFA9pP&sF9qs*rk<_+w#x4>m7L_p05XaZ-L-buFoqUvVS zYG0KDUK8l+|J;zO|K9&E2EaW)fj~fgOYN)b|IT2HE??r|4zkw&s#+b>Tf2r*jWfi_ zd~nqZa>=TTD>VhWlB6xjWX+^tgpD4Yt%(SzEej5{boUqg zo7ODdDCe=m8V}NPT!k;L%8&JCJ3u1^4x8-=`k~b>RP2~6i<6ymb?7rgZrN{#RB1PJ zqeBnIvesAvY4;v54%_*5Ifhh(iE>iW)rOJWzPr!U+Shx-YBViw(q6ce5O3z>2)hxa zl_z#HGm$9jb*aPw51P804wH!V8ZtsPK8U{E01nna1S&46id=GX4r98fv04Td!-2PO zGY_=&LwN^KIC&)+%#H#{<|<5c+&Cu80CY&>0wnL>nd+Vz2bS{2$PbC@iW1rE-g#(q z2+u5{U$?k67>LFqYNc8xa-2z-IXOX6vj%Kd%{Su3>98%_{P>N6roO-OMJLHY6e%vk z`w+-7La?(;rhm#@fMn9J_lhn~m^`qRbr}Up!1m5m8m>|zcJ`SkhLWHuiC|fC;A%{* z!RZX-xw#zHaO$H>pV?=g9LcSo;APN=_JtfD`Vf!2mQ@i`EyJ8?V);1M%rP5$kq_fC z!$ne0bRxAUrjmwfu?b{XO98>EfazR4_WG@6Th-giG4UGJdCRsw$^>DKR8-dymtI!f zh%FUSru+ONya-GDiAV%gZY6X}r6uvlJL&rh4SHd$b>hMw{0>GCvC?rxo?w}Sh;MNt zd<Rv#xom@HL}SZz z42L9UIe)A>YwibTHJt+l&3-ysX@BRK-S_N%GW885tg-kDetKx>Rs@n&Edi*y@qfB# z@T1Is_-IDCBrjuIod8(xTHXRE@3CN|JaHQ^YPgOWxXSObV{5ouQJ9E*I~i1;Y5f4~(qRLo`UREhx6^{f~jn3zOQyw%#`hyd0)V%6n2d{myJh))`2rA>6{;Yie>; zmq)f0uo$bwhZPzYlJj9)db}#g+lC*HHfAU=|A_M`EOc6uOXlw-*^o#UTxO{u3vs}{ zg+B{_esv=yt+$qCW}3wTIS%RZvQIRhh;~NtzHk->C|(0Cge6OHWXLmxgn-Y!&)lx zp6g%-+^~<2`4%K|eYvoJ`zgcHEe`bM8Ro-80aR-I%Dl=^Z5$5!T8^ z$k{H$OL6ot7ulytVRS0Dxpb%|QoH2`@-@GdX!aHa|1L?p!&$LSRp}$`-YHXe{pWR# zR0Ay7cN2BkS?J6>Eg2^*)zeH&NrvXIDZ*yk|E6TWis)V32Y!+~fM zfF4ahr~5tAg(w+u^IEL~W%BSTQA+?YsC3Vb{U+Q`R*MQ7Zwaj?8dUT#xWE8&s-@C_ z;zl1kMl%hA_b8ROO>Ht8UPOHb$24MH?ji{mZOji`=s+o}OFO`CPy9MO`$Q2IRqum0 zk5X|DUmpKEoZz88ho7Me!M_m-_jd=qWb#`-A}{dyawN1QOuMMM0z=aPPeXQxXP=p2 z^5?La6BpG;d$>P_Bm{5K7m;AYZyT~YtosxJm?r6_7@yNxNt*;sQcVY9!rY_TivvrG z%rrQ^nejT?VU}u_v+f2Z7;(4DJ#d{%C0d78TSb2!!JNBVGJtMX~SX--- z7kfya?IJCF`NZZEPYjdQk>gQ!#9(Frs9K*n(BBdVwka-UA93lMv;E>Ekr;}8JT_uPKqL(g;QdDoedUNh=nm4>&ic}QjwC+ z%aI}A&ds1xAO9ATsHPmlumdk8pGS;6&J~X}ju@h;F^(AGA*PH?zXLBNoSuV>e_Uke z3rWbxpi@6y`1Z$(*Wmv0PI)MoEmTYTHP|_-1hwK(jQF+U%GnG~0n{4we~%0W^)+;< zCZ+!i6z1iq6I_W$vEu(kWu6C84^as4s|ct3jx!WNTocitP2-4L@(2@%ZrvJBry)k5 zY3PR-c4de5d|ZtA+fQH6kLd$PxLvbpVCCye!&uA_3*e;?UfpK9CMB3tqdt!I^p3j@ z+R{f+m9!wU$4heLe-KXRkX=5^ym#YSGl=1g{xfTp^f>Mq^8VKCklR_W%M0dQW5>51 zq{$7P54^b?Hv4!(ljW5nk7p)n-{D<*$8P7}&=J5R=8`>=I2Xy6Y@w-e0aQK!y4s^H& z*_P6yUNmpUi2^pa8a)=ec1C?w zQWN=bO8S(Hus2ZZqJCxY_Rb(NQ~Nprq~jEce4-+YqwVwFa^?|i62|Xio0hY-40y(d z-}8o9r$xG9(**h`Y^J&*&5{+wNs?0B_<=sm|FGT2p(Z!>bvus3^DuS_S`H6X@0U@d zvfc68mQ2-ar$6}aCjs$rYo|X-9g;0Sd$sLLs=lm*{VeS)fcCl#7i46axXlz*D{C%+ z^z#wm*gJtV9VfSKgr{zCW~a0K^FsllODapJbAUC6)u{GxX)In!{#y+pr=I;TnjkVT zxt)+x&2i82|G^IQ;k?I4NVKsryD|I81@ncm5o$gpzgIn2i`{ge$}^AHaK~7czFiDf z&+<}Ef*g%z`Nn}b>|?tT7dgCi8!;c+5wBwdYA31#wXTtnBdsoyMmvHgisDgqnt%3^ zr9}(pku;PFKnMh2r3S(2b2b4e7JYcH=62KKc%M+U1Rdc3Z9Za>U$s{M{(zr6ZZ%^g z);5yp^4qiC>&BBeO~Dv5dYp{Kxt#6rIQh$f^+RV@Py>C!oJa-B`UOWk@~IIjYyr1l zc2n}ZS#Dmsgmrs(7`(Yjg-n%G1_=nkE0PXV8j)T!w?3n*Xigj0)~N;u;TdKe@4Mnn z#~5-XcbH@!)p5$3j`4UB>Y|j#u&;Y`eXZ~whIqnJuAGC9=BeZcy`mvxy_XlH7pL=0 zaIADDXH)yl?HsZ1ksi``^e*0Nei@iisTSo4|IGG^;k_w??as@%8?CLlFt=P4DLb8X z(~NPt5vs>6S-sV(Q(*!8pCP=zx*xduu(s|va=5MB4;`(WKBpF~WCZUMf|D#8#$l^L zCuBBgvl;Csv1oj%h63JTv-Ym$?lnh*MEo^jHF6@G@T}x^s5}h_7Jak|#bd{{6FB^F z6AXZok>2;yN#L?Qa4Xf4V@^BX(Q_drMKaa}A9KUp+-%6l=C-+~%M?(ul8CW_)ryao zh9pcu0H$-rmiVXT!Kj>j)d@uM!lzl5ri;sNlZ|88POw|!ISt?RsNKk1)vXC@wMLYZ zPK->B=c_YrGKNk0(DyFIF095j$svTAAwVy22CrkY=XgxZ_R>AG10z%5Ty#{52iU*N zOm`GQMx=Q%L^UzL!Q7}V?$9aO=3BAt1&+!++}`!{Zow=M3BYR})f zFStSP-l)2DlQ#1QIV>rxT#gyh4FvMT8YH0`KGSXAEn07MLvZom(|K_-+1uoDseV6c z@brb=PZQdJ@0qJ(T9+PS$?&vrnseJiuSxz6|7Y(I&M==R)c%dB_ULh+6`+C=d_&^CXR`otjOXx(C; z-7Gwa(X*y3h|z7i52uK{b9Hc~2j_rnsb1fRd`NTSAp?y@S1ov zHt`eLW2k`!$Kt*WUE3u!khSen2!@{)HIS9EzOVgXJO4J;cFA!;aX|rHY`g%qG2G@j ze0)P-hHr+F&6dw5Thr!br+`uNv}*gNyAB@jb9{QoBU(Co_E*8EZ*hi`*~ne}Qw+_a zl;mhMzE)t0w|h#)LAZjSr@wY!(Yn%?N(589Wv8@Gg0ppCD$zi__~v3ZhS|wwm)(xR zM`1?Cx&0bJ=Lt~dqvG2m8Bmvv^~q&gE(cf1ovI*%@I5h zh3b{irkqer7&}M8I#ddPw78dW%r|hmAgLMlf!yIM)ml2zV+lqZY(cmi#@BemKIBH+ zxcN~-t!!9b?T;+{s8o-)!;^zYu+EM^1JUFHoIZCW2?+xc$Cy!Z%LKstYn(Whtr@`91mueKC; zW`$7|0#yys#Su!1~JXi9bk<)%1l+Q1o7-EZDESX?Fn|xx7X>{Piv=aWU z?M4ldhIXjB3}R?d47kia5+PX3ZVOU_Mxs%vEK4u|-vnUi9z7!v`PL@O(C{D7Z~FTB zfFwOraqzXGsQCJMZiC2|DFf?^t4j~FWbE9mXA@jZ(H^0|F5&VaHx2o;ylq}avp1a> zp2KXAWC{_Q2%J@ahd@3Fso9yi86CbMa57%NZt`I=>q%Q5WxQG`dI9|8#w6BleG+#Y zX_S7V*7&KjbMXyGC|aMixt$aT;->Jytd0h7Z+4lvSllD9P`vFmG3%XK++Egg1a?W) ztJt7O^ZIZOIov%rSd*U4bzF%bF9q7Ua_nxEu0Yoo9S$%R5BA#{^*ZKaIimbC{h(26>1pE`$Y!z)!o)YP-t#|{*>)9JF=%MiBn4)qKj=)iz18QrW zes>DBq}d4AC1Ef2>{tdgbe0;cacrzSvRl;x91s=eB6m2P0Nzky_pUy37kUm3T04#u zqKxjA_*1;~X8)+47JTjT|g564A zh}3a~Len?x^kr;JBT_!I1?o$sM&ec;~gQ~X~69SLB+D!RS6?|W^5hw&$I+R+t z7_$U1E|b>a9DM9HeA$5H9iVf3S=gqmxgkGQ9NLrq@AQS*0BESf|+(gZ5=h;o~Nx|n(fl) z5<1tm9zGjBBMLI(8LSA2N>EQwU+Eb@ zPQdOU-qbda;_Is&t(76)pOHA6}8XJuOGAeCkXiUqy7cko`R+oZYSvO(QBvJoWt9@Vah4b z4C42d?a%p=AdC)J$*|whvZ1s1pd0ZF_|}S@KTnfAsr?hwX^bcCk|I-U&M5;b4IY6j z!D)S4XcEfAA#Fd~WA%l3eV2W0?8&g4bR2#8SXTp*O%bMQmK9)VDn`vNTX z0FuwB<$d-6JT{G+W5SQY$vfAkQMH$P;7y*Rct)8C9L({Fo@ed7;~=5+hM4Z1l<{-|tA z#^3nH_9B4)<$#Ql0-Cc*e9XV3TrL73c_c*>9x@J-Qvof}zR0-fhKDR=)4NXv#l6>w z1;stkkg(#O%MjpSQ1=1?UcEeKgP-*wmyQ7U9OLkdP@qQU(A-1QQJqd~o5Xk5kKUx^*N5jpBm-Pt(2rfZ4y0^X@>g07ev=YL^ z(z_DERMfMQ$6r^|wu28^%ULYfjp^og7oz0UH}XWAQ=Lw2yTGr?E)fpc&mB&R^6)!> zq6#MnQOE4I;oD`mCCG?qtT{`GXavZ*AHbs17@9o>lDiPwh87-uK)N}GX8?#{Pc;fc zd!-i*dGGt4xglmCz7Vayt{iAYaA@o z?k>UIEr9^Rg9i`p?k){9-nd(1jk`B;2JCEkWWVD(=X=kei@WYswN_VE_mWw~n8zs~ zQnO{#Wy-HQb-SIF>9y(DwX6e)6p8^A0TrY=Torbiy_m8z(rB^(ulv5D-z0v4?c^?TW{0hW*XHa0i8gg+2*I-asuC3NtGnF|yjdW50;nnvHshM}{&`9bA6m5$ihR`9OKZc+IV1^D1V z!q3VQQE2VpuVQb(ct4It^Zten4! zRp=H#tD6y`_MWBg<7TbP3lE{trS3VH*2m0LztvRab6~ebe5|Rs2=rblDrfXU7JbH_ zUqj;cvK8LgZCC5an(Ns;GRoJ(b|E_^!WYXhl|MgXSNHm1YmAU0Y8ne!M!^^F{zMQA z+6BYbquKcBwGSOhZGF~SQB_B(>)1b{yJBB>?)u^B)inO2WVZ;padUoSiz&d-Yquln z+b=+pr?^DYuyfy_)(ZY~6MKu6CP(riTPqA&yb`gmCH0aXd# z9LjcC44XayX>%#2jb1fh(laB39+kf?bEg-DyI{gGI?BIKReq2y^rf0i%fRnWUf|NZb1ldxPyF#xsh`_oLG^`5;sRc+-HtIB$5F<4(ehv5>&aP+gt1Eaw{nQ^ae$4 zHcI2cGER*EnW06r*1@~Q7}i(pdzq{aKKjNE$X|jCob+)WnZrVO6_5Zde6B1UcIYWc zdF_}#`W^E+%?;~$!>6T##tkS_U?3+8?o7#0#}&gRM|kZHqq98qkf0p5M<_3(AG>+c zcb+dSp&YZrUs6p|xT%K*)jYvTpPoov3T|o)9IdS#9SWr!v2B#Xh)E3X8+2aI4M$(v zIAny>94BH7-NhNIPxaU+eh)L)7zMVmW z6{bV_lF@$g-Nf5igG6IWEdD%d@iB3<0q+bkCHb_pQ>pXNt8@y}4FgqT)5$=Mnhg*p z;KZzBR{o3QXAlp_ELD&s-_d@HDcC{3Wxecc(TauoGej`H{^EKW z%nt6e>ktLs>ojphVB=UMsA@m+h|7O+z(emyMb;41lJ? z_n;S;88EO(2vaH@jkFYB3^bTzk?6vM;D000U=NJ z@IAn%k1vLnohi|PPTCr-2|slX*@L8QhBtAsERE;;Jae<@xqYa@x@YYv+q`?yhFn!@ z-t6$WU;yjN<4Z4r2q`hzfRXkO`0C3=_rnxfNEasO%LO>`|OYC23_z}PdB_N4fuH6EOXo}Iij;o5vQy8 zhzmkaeZlN8DOakj#ng8K5$!DU$4!w`VH*{bY6z9c4N73;pKbP_jSIf|7pruye0%oK z?Rc9Je80TW-Cg4ofbXWrU@JqJC@Mp7Qp3NKE3S_Yp)2@513`L5bYDd{-HK#A!WK?` zH8QO=nQ!jsb=8Vhemi%&Sq!AAFCF!)#QkQ9&)YJsm0fN*DbIFjyl!(_>+}!Xhj=h( z;0uV|_mBAR^s{v5d(D~ebST#;2xkoe9BVkTOsI+~1j>`5U)HsM814iVF!@7fh7rsh z(yfcyYgK-98zm^}F#5YQr9((+KZ}5E^Tfb903a5ej;{ygtH9Q8I zaMngPV#;TC7TfCIBJ0X+W9JOerDZpnia8_OCMuqZok7HAJZC+;9eoZ}QZ58Kk z;%N%0t}0_CC00`L~{tG<~i2B1l9|s3F3D0|PjPq?A zJJwrto)zqRENp14=`g56`-1?eG~cf4 z%EV_Adv)v}6FYTS23r}H-)AhpJNp_CR9#IMFMgMvJ7>(YS zmqp~<$sP%QY$KNnyKFVGO8+CwW*I7>?HP934n*2y(HIOd!YWs3UJKB+(A= z8Pt`$itSZE5ExCL2>S{N(JL@OG`e`|49rL&K_fuCNUdvxPfyYTJc7p^|5-M9R?~Qf zaR8j{#4bILJr8?>mpXdp^f8Z`Wf*xFxzql@`2ed_$#sWx_h9va_6DAg_5Jp9xL|M9 z2X(c}`|Go;+l!YSRHRoT;vz{R*%Bf=++;k+xxYuI%_M}!TF)XS^l&OZidsd5&?{C@h*|}Q&@+3;?L~!5)v+yjJ@llMczNdp7rPSVT(UJI=LJ8n+>1KzFS_C)WPEslL|H*x>r@ zqGz)0bih2!^6E5+XGQdeL7*!I!}x-b-+MoO2JKfkfXDxgfjyP}I2c4X=)Wpik5C#2 zQ~ri$hQRiVmI3nutg@}pIX3EO5;E6=35iYN#V6dCeb=$Ze6{a^DT+Bh1dVv7PB9nQ_f47}*JvKs zv}Y*-69*Ip{rYnIiM1v80Y;#t;fd4L^|Pwnqzf>&+hfo5#YCd*m9Jj{7&HPyV5bYX zi*O$y>Ptf-@lXF$*k^xPu#kq3ml(nu4#@>18SSx0d&Fhy?sNC}z+6uA*WR-dH^sMk z^Vih@QWx6NFH1eOy>kjK1eT<4N}_#=vX^PM>m>izCNwu&Ry(%7wMZLzVpOk0lEHG;FTUA;^* z8qSqWDv35N%ATb)ua!(HsYRmPuI+sD7N*V$MN7U6m`H10Es0+eEn1X4O4}l$+Dy6h z)>^ijDkQe0Q}^9i;`7Akq-(@$5m*t>LMVPu&4LaCLV!ttNv8OTQ}lfXb*=)TSsNeGEr<8w$6 zi#YAIC;q$X<&Z)NH2*hPM)hh;3t{=7Jf+24c-8hf8JsZkyso{Z9M{JGDehnY^5C!W zlDzLTG2RH-OOGKWb*h(BeV?6Keu}}KMccN-lqq>0&)mP!TjPDcigw@Xc3%|pu(RIA zb6qC;cX`_DOMDF?dvISDjJ$f8=lrE5cCcD)=@`<$ImQpD0udmV}0hsi+ZCn=P_;EEXK7}OD8 zjouCnRl7rDSGBzV8=Jb zG*y*LVMt+oY-B57(=e7)l2rPt#Z$xPFVG`Na>6ZEbOXjfNSD9*+DU~ekZ}YbAV=-> z;ZKWA08Os~AB=$}fc7Ucj^V@QK6!mu!@y4;x%%2e!N!nb4<9b|N&CYZI)1`P{l8dc zju(LMTSPiD`6P-<;* z0pXu^XaS*J%jgsJ-+Df>F=X1Kg+CUwqARSC9?$w;S%`#(e$p0s+;|lbN$o}6DTXP4 zu9t`lCc`Hgz53Q8#wIW}od_$FG?EQ3lQhyY%$C3TxGC=z)@j5>oaK0ocFP*xX@p6f zb%YxLq~;R^Gb2PQJeK~yw~kdJ@FPdv!g?NSKE@3Pe&VB)Q@UV=XMH042&P65Q{W2eRKSct*9*@V=L_k| zy5Vvl2Gb&_Db$B_s$iC8u989exK9|+R_O-zH)i?<4(N_ucg8nB2RdD1XAJLJq{I)= zL#}v$+)S4b-`t8B z)ZR*r!^^X(%LUBqSviC0V#0e#l36G_J))XGblGJ~s8| z2|u+iDT8joqVAvar%S^wk(It`cH}AQ1L{4LFlfZgm3jm(C~2MCqy3>|`XlNF?RYA0 zdZK(Hxn?SzjHJ1uWQ=0c*D>-~$_zI690_Wf59a8SG4lUkEybkRvFupN95$L937X%l z|DWo587EO7ozPDnOOf#&{`Y&Vh!8zoA|p#9E-8eL5H0`xs~HDfF5^KrFsTCGv1}5ZhMJCgnj7N>puK~)hde@ zj9&NjNayr1vKPkkhvfd0?d+rfGyz4ujYTxyD7j!;WqN?cHQ4D|hsmHZA#LQq&&aQ*yufI4ee zPy=g$Ri{<*{+9D{5{&!rh*cij{-=}kOskTQ`SZk0B!9mECXybB(Ym?W2{hX#v~rAE zfm*OaSCQadKPEmtJ{IcugoFgRjg#pCy*xA_<=26kEmC6Az(i5Mb-c#Lz}Vf{Php;0i~{8wIoRq=*KMZ`t7!$z}n}o&IL} zZ#lm4M#%&TopFB?fE$Ipy&)7ye>CsTO+Sa5q1BVcSE!Vh^|*n5gzyeOR=Ts+C{V^z5aqjHDcwss_n#htd`hc$E_?GHgxTXyh7 z3>g55vxct%2_uj`nb}VXiZr}CTp*mZtq zgQIHXhXCH~40itN+@PtmktAZxabZi3Pco<_f0%x!l}3J%;NYs?)a3Se3Uv5uit=3i z=_(WT(WhsYf3R11eAXU`LG*ACl4IEFgYnNoEzthn53{{68U(!D5j3sxaFGKYY|rxZ zH|3dK8vBcIh(F=%EGbQQeB829D7wr<$Kv68Gq6l!+~ZRknj(K&9^~@uR=2hEyw|GM zPB{(BA|Txi2NS*JVaY1@yJ^gBu^N$aPzU#L^;>Qna!5lKR#kWVR!i;aHV3in;D|wcffyH%F-{m}UII1yFK9M1ATc9!GgdCdZvBy@dqjY`TQ3z8<(pFn3 zW^UnlohAB2Xnjq5tkV5f9|`|;7L_kjgkAQD7_D#iiCE(>S_FGxHEnXZPbhTp^7CbT z%)q-~!sy`wl}OFW_3y@u>_0GzL@O-*w{XE(yt}7ROx(Tm3%Yz<)AIp`pAFBcRU;o! zb`ow?>maAgY5rYIac8oqI9E}KL!#S4xtIfeW3q;Kx1>c|DdVUkYN!IHcGy&m%Y}BD z2s|dn(03|zIO?2$ScTtRq|p2qh`V{U%UuzwRE$}Wr4d+%}=<` zk68ZBZtfNn$obE>LcnkJ3oQEyru+0LNw-Yt{5|a$ef*){4Y7Pep~ugNyGU{XA5>%b zEThe2PKqVcko!&z`>H72b>F&Ak%N-fHU21)N^|b3VsM|L05z^_B=GGz&s4Ks+IMkLL6P(#78WfI$t=Ui_NU%R|cfNctZ zgEI>{tmY?ov%F%McQvB}0Q^z`WY&@0_E&Es#IUGVvTvKUrIM^As_4yYDTZpZXXDxC zqfNEOto|^u(stQNjvss`Y6DM?DsHuPggdRp>#gDI-hnyD7XrV|f43ue08Lp}w7%Qy(t6=6145cz)(5?uNrkPMCSZlPDJNhN8T;_v_j?zu;m*k}hYNeo3+-Dh zq;2uXi+WCTkDJZ+Z19`R5U5P)5L=f!@whM`rt}3(6wY-B2{*iY91(T-tK4o3F1?zHzC~AF(5Jk%WwXqd#cEY28wblUWnD$(1iImi{Fm&t zP!lN5C4^{c)t0DTjPP3x z!ya9>hb6@?ydcgU-u8rBI|P*Vg>fbH3cVG{$anj3Ml-aNQ~nM21E zOlObP8hU5|Q`*B`k3DUGFbyqU2BIDbORvE$d`srYuXDFl-DoQGQj0q*Jke2UE$Vkw zxh|z$R{6`6X)Wq=Wxp<^T%KHSO7c>RIkY(WyZQdE<6#y6xFWm%Dwq{1RvCAVkH399 znv`-02SB{hAS(lE4C0#@X}Jq=Fxy%W%kbCYO-*er4BrPj^Q0fP;;cK)<8SDc7u{X& zI$!h$eQ11t+PeXOJzeqxpV(hF?0GcAvkySb=myg9Q^tLqyk+ukH7@m{)8|X$1k-E! zk)e9+IL8!Tcs_@f%T2c`S0w|>N6ogY^SV%?Iz|x4d%8cSer&&J<&qxiJuvOIr>Px8 zbK7p2Ywr(P+H&V~AC6@5Pd<%nNv*6Xvf86v1|Rc!n;NNKQ(c%@H|e^jd$;M#+Nxd5 z$KAP@wCP+6T?)RsYrXZneU55&PTj96`e#p4smd18J@bm~T_*e}`cr1ASpsxO?jz*H(6NDRbY7 z=RIR7;CH%s3124|EC(LHQoGdIV#k@~$k02zbiQxxTjurXme7;vqTw4EZt)bP~utJq|4=(+x||r`iik zST(ug9l85)04#g9ANfFG+3nfx8NU3D(?D)7pvB%$HBPVaL`ub{pr29YI)}DRc_X3l zR`LJF%)K3p)k`{&Qt~nHXOy|lp=o2I3#}5}fcZ%gw^o%HQjue5Rge-bQ>^y#qSNdA zME`E$XFs&Rzx#@COFSS#c}pxOctF4TyS*u`muLVm--|Q-P@zaWbeCzvUQ;jQ9IH`2 z0}-pSTvujxp3jB%;Dp%Mrl@T|RAn}whf}G928VqkGnbH!?B%2w%7AJ_3K5c^reiz~ z!F4Q9Ahkx6p*<%JdRqGy?~ZcWh1AsS(%7`V)uMa;m%DNO1R-ID)-n^DA{XH;qfoV zQ{msexyl@^vPZe_W;HkFMGSKAee#vmSw6WOK z?3v(tcygfgZ)Sf}Uh_ZWhEvUL@tyh`0aOqW@#sVIYu?qzGzOi+ZZx`qZGeFaMBOiH zt12^CP2kBZy&0mij^(wQE4W+RTQc1s-%i1`^DCUaFPtmkZWtF`x4Wf^4Ww~&PZ$f& zmrTB&tkPD41Ay6=05$a}O7+Bob`Pk`;RJSMHYc|v2C$rv)5EC}k$G=F$!c?-DT_S) z`g&H~5FwMfyUOX4EES*XMuYvKTdrvejRe8HlOUb@@&OW;YXF1q%m!-Ht-&8AR8S$c z_AE=kp3Oh`x|pKF4<^|N(JDAkzexXiTg(aXt&D&z@LACBEK>>mo0B9tCh zpBOEKG{NqgY+o9w*eiLYjIG5I=Vb|%>$7!b_}9StBcuy4H;YEXXA+$p8k;SD5FrB1 z+aU|t9~(Vv9wZ}4Y6z--W+6o~co&G4<%jmZv#HX^&%T*}q}SBn;zIvz6b!n?+b9^( zq4xaiI_0$3G-$MA+YxA%Ibd32l3|ciT*6Ta^(Hsq?orhMcT3$&|((EK)i|3t0m&i;!xLpccM zqM`l%XmMestiB_>pr?*&*HQAWUy(4LNQpZ|iigFs{G@d+r5_50uKo0g!`O$m*5~_d zAbG`N6oQ*?@wp+&0$_F=k0rBmTEQ31xgPh?#hjJgwY}2~LnyRcC2HKZb;W{>o);@y zmPeOv^!MCa!x?AXu>wJ35cwNINna<%Qe!)ESG!lIr1aj>QY7PJ!0I#R|04ZlsuJ~C z-*;@zywEaiMQ|rj!DF1E#|1VWf6-4~d6n`l#*QT(W`66Pk$YU_qV=hyNrz3qbdxWt z_D(C1HgX8F^mOKO(YMInvdl`_l6X7`SiQ+y;{M;IRaRlJ4yKjT&3guvT8(n98S9SJ z*+C<$x`o!|JJg@);Tvj1bf!ig?K90PwH(e5rs`VOmb}o&qG~Lwth%r`Z-~d>4`No; zrOEqdl{&x0ez6sC!T_U|3$Ck(>7p(tAC6qJux&gekDi&MMdAmQ@^Dpw+_=cTm#lFB zzeU=hCeURLd!)5`-?!-{Q)?B{5=Ut%!f|w9br&;ojp97L&f=CtM3m5aBf%_S$bKUo?fTWS6^#NF&Fuz@upzy~d? zFjy(S?jM)ZpVjt5!nqNT7|IBMO~>n-lJA)d-_PbZptDic!#Pp?GrO{EGd zFbQDYM>~h1wsA=UFY`jMmzxyCNH|T?VCs}JArv+R z>!%4}MHGik#@h7!EV!QaU1DYNM!t5+HbUj=5;`gLR1YKAQ=%R` zZ^z5ymWem1bGSyl5W2h~kgXoD>?bysXLi0l+kiJs=fAv$x&;Q`S}inBSJCecLHGUd znBpf9rL31tcq4>4^M5*jg~BG;#ok>WhaQRnPp1d73dg_PEa1gDmEuq7$BXcnRX<$Z zT6M4Ru=pGQh_x9qm7=pJumKX)W8CX*Gu*xs>;^G~dR8{J>P}DZ-gxNfmF@02d$*L9 zO`o6ti&=GZQ`{<0R0i7lOO|Ra(h7z&ZoanQ=do)+kgvKi(|Jgl6f`>rY1}!gKBR;% zMP?n(L`^jMXr}W<^AMy4R_&!D?@Rioh7SkTW`m~AXB!2y(u>I1d0p9@IV@HyvI?BN z>q}9m&%rm%RW*kfw|d~|5!JKZS!YwLvaqq+EsG`4>5kG|xAsPX#?$8vg0s|=8#G;e z>>%Y}q5kv!Z%khUa7DuqM9W`i6_uf28;x5<&qFlJxog|w-E5{-3pDvuLh~$+ zl}lDsG}ve2WcLjoklo0ZzVcV#T=YDJEPQ52;0$%-oL|Ux{WQGnQ;!FgzBY$mRP$%= zGv@3|nL{njp#+~i#pi|Rh{rCNxNOf&I)F#VR!PH=-aw%x3VbU>BQBd$`+Keg#N?%i=bAvdB0{)xdS$x14A_Xxa#MFExPgqq>_T zht3QRbar|9f}ZP*ZMQmyu3Pf{{4omQ*PJxh@_pV@%a+K~w`&2e^S-E*w>r92?P90z z)&ejnT$ZiDNGZXNRl%J>3V@s?CElWbdisVOibc82*$q`F(L+$J&PXldoQu#r!{92; z73wXz>zdjXdt*J^<&9@sMGI=t(R_1j4;P44*KOop__}5l=$@{cVf%nqEE+F^BaA8E z-xG>xW%LQ!J!+L(kDIKoWCgq5lHY<;bGbTYBZw>q}$PRXjYsP zId*qz_3mrE>TI@{6R`(cY1mUidDn8Tc$*2ER^r^STmVHCO^~)8m$p5u?w59NDO;9{ zDpf}>)o+(}nnKjfhE~~U`&VmbjgK4m!VIH{l$z(E*DCRtzN!1_%~ZU3SIJiH$E{YC z)zdpFIo_3tW6ZU{RW7eLz^o7qJ5t%sKJ`GQBXBVVTz^iL`AV z5TsWnwF3@UJ=MPy*&~;BJOAiB7ihaz9!rv$(f zcmntb#QUVlBvj8vb7+m3O2OY_%-KlH)0;O@SSQ#LLz02loA#~lDgPuHM~}uVj86{5 zIa>75U>n?67ZPRqf%Mn)aga4Q*eW&EvgjDCjny3$lckJi{qxBa2Ps{fz5#mo1`5Wy z{$vj;R=)0g)tTY@D(m!@0zxh}ap_bfg3EV|y_5sIvj=`U`wua|r3lxRx9_`Q6C1q@ z1sqK>rC;_#%vd+%HYP7j`_rAF(aoz%V<$Ojr|xwGHonjGx)P2yn$efXDmfJHX{&=O zYvre~`}d30?rZm5e^VP!bMr!<6Vl+N_MKk7C9d|bbdhiEaeTar{dDItgQ>`xnysVv zGFND(cC0qXDf3pgK%#n9Ee=z;DM-;x&z%G@vKPYVa` zR8x$e{uYyovtFfPIwd%;&YXnV@?Hyn-%n?;u4%q(DA%OIUc-uXZvMXYBAg(~o|~u3 zg|O#k!}~BwE7a2~=srm}YH_PHcJlXb%FH#s3!zA&NQ}Mo_0|~c1TbdG&UGHx32L?? z%!Og*em~0vyl=<{^Q9a%3|LZ1r87ci2yAhU8uj};Vzkzc_bm8mcx^@lw$g6U_{yjH?RD@VvQzRtR ztu_DUnxV0FEVCAisZ@_u-w%4cDy+pr$NOO;{`nwp0V8eWu+aNx8C1OGz%Wi>M&RyA zNEn8r8jTI|=^>yQdh~9#>*y5rVQ8gtZqYH+fRR%bkAuPmvl3BMz}HSzF5<@A`Gi(xH4hF z?&;~AQO9k2Q8rj4D%<7R4vnm7yONo~xHTFS><4Ce5&mz%;MR85>Aim!i})Xy)A~a_ zdB|Q*Uuu)yw-qjUmI)OucmwbLP*0oxhX1+r-*$f7q&bZoxLsp;s2>z$_)8K$?YX?+ z`aolPjChOw5G>@mwW_-Sx28~>+Jg!Ui0dv=Q_=k#Y{eodYF?awgoh=N<2Fx!qTCI$Gt&Prmsjco6p&^Fd+t9Z%^!q)|YTX47mKbK{vdI zL#CosE39F}5oB+D!^dJ3-1X0l-vem4*voo(SUq^wzmB2`sp9ezK=kcuC3^7VD*Wv1 zK8~yk331&fJ5MKJwi3lwYW{1CWV9IVeGi5nkyUFA<$%9Vh5fE{^kWzKQ}@{Gafd}h+CVfw;W^4535*bU{n8Lzfec+1)COZW}syiw0~@6r}U1K{gAIRC;FJf4)F;|!Z;fNCr0Y0;^;g^hjA^xS6Jl=eqM4K$ZNS2@#o8)Pj(xIyO%y_*-E2?>&@?DISMQ^$I zSk!LM4CI6wFbgt6`sbM2{g?_Qv&}e;Xm&^B(;7_whQM)jb5d_vsr2zNNcDQ6c$$O& z=sPr;BQIx2WKKGJP^4e_gga0>P9#x0Hux6?OM=yT+nA!LdB==dIP2^*lcdx1Z45|d zD94O{$2&@N!`}h#Lf#QUJ`?qdH+p4-)`F;@jO^SwyH&Q;Md%?>tBi>rEMsd&Q8Ucr z9EtC!rs#Q#cXa8w_o-N;j0qGs!RLZc+!Q^RRJBTyKn`+!SS!or$Pb-RcVuUur%cSZ=T!h0GoLQ{Py?wMYc$cDlHEvP(q*pWqzwEzvze=3oLJKuC^RzLLv zsSpLaa^=z_Xc%PiG-gyKVaA9v2md?9zZ>E!N(+aWi!&qB%l;Age`DSU7G?8a zYf6V!&G}ZiQt3xeoOb|=n#>x53ewEK!djt5_fnRwM3fU3HxgSp#WB4e*g*RNGrIMe znu*ZC$dTsqGod{uNFuY9MFGQ^y(f#G!@?cu!}C(f=ZD`g4av?j-=6z4n!31}M&eTT zL7PF)^;rm1S&x-hN2P7~0lIrXeWTmIHKR7Hf)QP?yQ4a_6fG zRn_vD^_ClNM;l~Ixw(8P}l!uIj!X+ zN@vF#v-ci;ALYuo;Ia8TGO0{An@Pw&tgVaRFEO#(#a&?YPd2q1N3u!kkZ~=eHMK+Y z55?8)S|NqSVXlwu$U$N-vD29spB3%rP^^s_z9^RFyeLlDMyZIm7YQRXBpkI`?x#L1 zAo3JQ9B(=?DBCwy>OOZP*P3qmQ2mLV7N$YL399PSBvdWwJyY(XRyUA>#5r%y!0wPM zIy}*vh|jG=W@fQ29iCDU#rlWIP;P5tY#bIA78PZ0y;SCqI}XsCbxE}%=&Rkf0`)7K z%5Yv3@J;WZmS>1j&_xN2mz))Z8IRbg1u0)h*Nr7Rlpr;z25Qp@m&PGa_XX}61I%ab zJl0fnQQNNN}6^c`z09rjy4b0rE~Z@ z%?Vw+K=fsiHfNrm2`wO-Mfw+i5Qa(s(b-28HcJY@a9ZeK;_!Wl|64s_+&u=#bxQN%hHbdP>mp2k06%`Wj}qKqbc5sEuyn({4YC<<3lK$j{GuB5 zpCp{AB|?$i8}ckjOZ+>}Zl|)4>bj0r z&a?I82HJx8NZZ2Oij^O;Dp|S8h)RV41t-R}ro)8_B`1)@hfLt~=h;GhO-I#miy7vrZPcQ+h*{Im)m z$qT=UU`6GVMpN0DjKzi+T5R@{=f2mwIRA-bqC66`KN9&y1?e~T@w}vMrJ=I|(;Jue zh?xl>V^RxC!TBq-m?Xm(B`b#zncB@VO7_G4?5Vvt2?Euaq~&SG-e}F|w$7fL{n-u% z_6GKEFfXY0&@d55-g_}oV+$x;iOAFHDYTMq(YQ9M`N9OW9$Np{pL1MInJwjo8`7^^ z@zVZ`XphFw<9Vd3?I&fA$AGE|tF}T5%Mn;)kGvFQd73Dr^hF$AMDnfTizsw2W_A4H zjt{0q%W*O+tr9()c(^qFdYzx}ZV`qn-v%hK>LY!LVwD$!5tVb{>OcX`g1LAJ&4SkU z>{9R|m;ubDTs=s@A7FKRm2$1)w}c_hbU*h4H4bbCDDhTsUlJO9HeyYE&hKkm?le4j zQL|?oeJ-| zIfj%YC)RiDBduqn?1~*)fVM}j3!k783$ea0d1|`%&h@UK2O=*Z;d8u-o?;e<;`>Ae zEo8Oa9UN3Mn_TmRW{F0F4$&GBtOFJOH~MwgL`eRNoxcawjxK}l?~fMW@Mg@wcgs?{ ze5k+(NtNIGYDk6oyXD4R+8%eL3t-j`w>%Qi4&7b33*=mhbY&tmiZd#92vdou=x0{t z?x6*$Z{QaF-E`j36y@%t2EuyyFT(cczoO&ZHRkHZrs8mBMRFn76Z=LB%k(X^lDU?v z2ODS+1lKef(H`|iuqMlI@t&&cmeV9&A<;zH6fZ`D^yzP$Mvrm)mM_b|gK_-BGON^m z-$dIhJp)#~^D^~oRg)4igcP6MbZP$jb`%H^mZ@04tb&1y@{j+Jss^sCi$6v~mvWj$Q_i*>`+F+_G6xHLp?8w2o8N%9;F|R4{i|)+CBk z70dYtx$W#yn9W05;BpOH_rUS6l*2#2*v#sCxA?O(dM7`-k@bFV1Ju-3FyO95F{vuy ztgJ{Br|elf;I4%=sqoQRS%FAJSqx@URj5Wqe(^kUjyCVYD(Ez#zo5jyq9|pKHm~;I zWx_O^vx<_~u=OvF8faXmL| z7a*~G2X?&vuhB0fn*KkBzmSCg82ygbW>5h$BxN1XxkjLR0seMOD6>5aegWtC*SeigUTb=*~+tFr0=WpI}?GzKvjtF~OZ(?&)B>31GNE{nmLC_^bT#tsTA+9 z?D?U=%8GcMjw3p#pyTvAW!k8qnEueJ>@wW5%eWDL-B<-7l3HQG56aA+g(k}R31eD` z%E|6`r)K6STp{9@>28Oq=I;Da(-`jj*K!w2+htfxb(h0xAFbuD5uuIp8oC-wH7!Ra z$)ytSm(b7hJ3JIbVZ3Kh?p`Z&KZC9Kp6GPgAN{jHmG9S2^O(39Ct*cV8`i8WiA^Df z(qc?RCMjP6gWWunQf4AM_%CyC_p@MC^d&aGH^&2U)e$yfWQ_ge3fv7x7MSQ>>tjgw zx!*28>RlsZ!dggklda~Ph5(STDormfj7H8|55&y6w?&x7aemYcUWm!QJ#A(jx?Z{$ z;8_j5wd>+Cu$Rekw%c#5Nz=xUV^HFuQOv4EU1Wtf>rzOf&0X>hcFUsCqDpVm;>~g} z#@kSAIX`a&zR3%=GW)#{vwB-S%y9LOWU8azRM-r$!qqE1G}#QX7*pEjJ{>z~gKe9~ zKzad>UGweIWe1*i^YGoSy|4h(%4=<~>abprb8_`7AIJ6ic>756ev!iI0SbI?j*(C5?m5IIREsOv-dgQ-sk`1%&fWQ&b1!N zlbNjNUiVsJltTqw(%kdT>!9prjJ?qPZ6j;CWjhc+OnZC zhy3V;4X*ZH`EvZr6%_cqnTx5Is=v8?#B{c{`7-3VT%%9b>_wvS5whC0M@;WS)nhip zLuoE3BE5|X9_!m`WOo9i%s2-IjD6PIYsvkHacZR5G=Og3cBI3 zahaF6{!U{?_gg($`<%PknVfajMxt8u<3;NAu;2lS(DKp!A)!FzOW=BAP1O?0CH?A5 z0Hb_Zp?Ru>TC2Kb@Qg7_?#5N|?(+p*$j@c|T^USWE5waO0}VnwS|Z+#DQmEURzi!qpBY@!lT`j|O>G zl~%nXT$LM0bY4o6mS3sydmk;fYJm5K}rQ+(W|L_0`IS{4d>O>q8w~(=~yh#szpB|&RLPtb@{EMGN z4QA7&5^e+MPLFk4xhBehtTuPxy;dc44gNwFn*L<%0TVl}*sK0O)q$%~5Z9_7NuP@l zxZ}!&2OQ!i-E!ZLX^r5=v9$YA1oY~cH{(&*0R?w>(*l^lScy;69cW8m4L7 zM)`iB*NuGSTtCwF)@iiC?|E`U8BTHtz4JL?TI(srlA4J&#Yf88nMDFSc04E>5flG# z#XyqzPJ*c#7l^ai$iwG&Z&_nzBW2C?@BWK%BBZ`1nOX4gV;Yr_+=_fwsQ$Xq0PeL{7%Up&wavobZK^Qtzcv-rfPq(aWYQ(LWhus3p)$L;yRl@;9&cr zwDoXKsoHbjN?*fQ?5qQSZ}afO9%y>yUg;ow?v*H2#L9s~mFI)F2WrLiSOHoH1tC;! zFUZarN2GMXN(iZ`Sv#$@FGQ?`cqw$NiIDjdlRhI?<=%Hfh=4K)wQ^GO=yK|Y=g+=D zDn8H;WM-pz(r!IaoBOY(+z!5l6wpbouW;a~iFplnXcA|-{-IiYtp;;D;`L&4U0y7G zLqlSMMG!oq9J>cdRTpt+dx|K54RE?Kb3e#4d3rI{_XuSzT&mU@CgL`xx;lSOJOy7q zFm|f9LFU>XPWm~SqR~ScHOzBCp$jYQ19I(J!bWqnXWRowTrpA^j-P$?!%mX)RC- zc-M_1OXyjDNwQ32licjtfREC zOIM8@F9L|~LnL-jmJ?uIhHv?xT1$#03uTwqbZK&vh^jccsiHQ)wBpQrec3+YWj8zp zdD{Hity&BkvRad*lU$O(+UY=U-x?oH>1NTQfKkUy(Anz2kdLR7s=8~O!QQq=>dL$fKYwecHJ&;>M`)=9AS2kicrT?>>ssOFnyThcg zjBO~~$!5kf%?7zpokT4vOJ?&CPN*WBo|2aJiWY_;%p-_1Xec48xAnn2XD$vT zeg6$w^mWG)ThWLhvqJ~=u^AK4{^{Sak%;a+^K*dpts{aH*Xt2pEtu>$(L)8<^HL|p z+;wORUzs{ILX2M4LgB}}rpvlR{jZr!5DqUs#r$|>E6se#Uzp42G2sYkIX`^zY)Pwy z{W^Z(q5_jhvai0a<>^r^ryd) zc+d~aH|1cpbv&W*LQK|d?0&b*095*-4vYY%~BhNYWVlZ zeWjw-J^Wm8I6!<)`UUFd2h9RA-#dB?2Lt>A2l^C|X-#&1Xc$CIm$?>nDwzabs zW|ZhhdDlXVUU}sp_19t5x;4Tg#-oFHn+oPiPlY#)GcGHpB_B;R>*hsu=f8FMx8U8{ z8N7(s%L>%ayo#`3dz5ye?ae-u8ChoPKTZC5BvyCXc>Rn*cVRt#CcPC7=6IAg-vUQc z-l8Pp+uJBVd&KKy#dcphJQdzFxncX)-}&D@%zxhzcx_jQC1<;^SiidZQ%9$rF+e45~OR+Y7(YvVS4?T$|Pv@FD&V7YTTHnVrrk;3G1I5 z)a4&|_+j$+ku9H{11l)*!clPFSAnZn{Sr^HZ+fKS18J?(fO;?;O7w^hIl7AzL?0@9 z4BovS@yvyIFTNEvkfiAQvFprue7&H$XSz$%HtkPvQLmnvw%yy-aR`TZW%@pCZrJt8 zYpog>(~zVTbek3#)@S6%_?}@bK7bH#-R62#c2eu$v5hmEItGeS)a(GWZklg{9dg`B zOw);zl8^*DQaIQ*Qn{kkf9$~muDYiO{aG&3>laa-UiCR>$b|G<{V>_RxF`KRaHle7 zQ}+CMTb9b%oAdhtdv|G_Bj%`0-(Jm$niFIs=Dg&`l3{uLVa-cBCUBNw{-oUWmcJv zX8E6ucc|X#qKFKh2m^T~43`h1m9GXS}GRXyOBX$*8)G`NG2ECP)N>0ut5 zEsoNC`+QXcgMyW!hML|Knfqs7vmpYZn`Y%L)9tBIZp}wnyh)t-}qHJt-nxV-Bo&mfA2vX{T;z3$GJb4XO*+bxucSK zdey)Pr;oGceqc@hpnR7^1+h$DMgsxbj0O#tULfgv=3tXMxgT=7!$7qikP}}9W=Jk8 z^l{ckIaW_Tf)`U2-r~y00~14+eQsoDx9*Y9u6#(FG(T*Yo81xf$7aKkPBm^R5+=CB zX`FkaOS@(lV&wRxgb4X9mKYghTs3Nt&A?^m{mXRz@A3(q!pd8!G&_aW76$>;*VCr4 zT`|P?hN#8(zPL@PTkqcx%==+QeY#V9~9$lIm}|gKz-c*U7`1HwI;yeO$CySQDEq0Awk4PV1Z_EAVc8|Yoy6^ z@UOB)u8}3DuC*rMsi8@qMgu-wdq6G4{}X6e?O2Q)LrY>^Y9E4yJ16BE=5YU#mRw++ zEPeJtVN-Ta!`?{>K&@QQO*4I22)3#HK`pjv^tnMuxtt#l+`h}tF|wTKu$HNf;xPy< z$avf={cys|u=O0P5ObqcB=Ml$sz*my|C+6B{j9#a5)Qmx05S%aHe)|7uqO|s;9mDo z@-pt;&CxHX<)z_@-aXFL8H$3S1q1uTy-lc{hOkkmw8JVU&3Q<#F@( zWga*%`h1Z&K%^5Tf4+zdu|H_W{`ZJJH||C;2T&e1M=r}<^TL4-|C9O`*C#q`W(pAL zMkO6KQ$T1p0C*rJ>#2jIbIfy1p_% zVDWPbg~c8;K9m-zN`cj$FW_d;rXbw#vZBuyo@W{MZib&5g}~(ecsJbmv!XAIhBwWn zr&ru!2j6vQs3yBKg^tUm^TOTn3hZ5)unVF^jk~waRVm&6j+s>{0ZmM*)89RsunX*m z#f>}vRFUIy=}zCriQJk#sEQ2#dCK?ko^;*~_aV_m0aYMXfkde*1buEVxpL>-59_a9 zaEhE464j4RsQo`d?66_|NZX3#L-uG<{fvZ3u|F`&tXdbDAS9|E@;`^}0cKSSKviUd zTsk-WkNeG%veUvXWz!uZ6Nms+Osc}&1L6NginEuvRfQ(-AS|PcT|G`SKr%W~_g#%n z2@Snt3noi8A1G~>X#+WAnhBE;_~nRile8_!n}B5;N9P@|?tUd~_Li&-qq2QpzG3mL z$KVY$gmwccJE`Chm`p_S?HBEf1`~_yN8Iba50|6QOyD-((Lz>r@ z$@%6htQm0VRzD4inswi2A)Z7y02FsLKub5|3t3mi!4b#+5!5*t+BM=PS0r=pgT7tGln`l2LG~x{_`LI5^!MJ;$`M3I* z543Yx=>)rZ}6&>1W> zc}%qq&BGUasVd~R4+5iPx&$j|DOO>JlwNGa-JEoxApl(B)8oHZnkGAf!g7Ph@fC1< zDVNAgx#v!XbgaLE>0m2?n+3lnc=PeV6ql@+V6aE0nIU2d?2mP-tN-1}8= zaIH<9ou}|s@$BPAAP(eE&si5Iu_r09T)=w$elHiK)v4P)t_R@d8^E)k3ikz2OK+fW zG==$Xw0kU~mhqEdP&UTQebc5@{KLZYicLnmq)pvOm^&=x*?us)1)whfgqwTSQ}%+B zfh?_Th2P{-@$BoE@vByMU{ca8(32l#pNRCxB1mk?=pi1~IgNq;nU^nxjRUZu-TI=m zn`TT|>x)#}+ZUwLG3-l0HaVMY%5cU*YCnps5dYcZFb5SFWhJ(0XYwK6IsWZq)1K)+ zGUjVhT4c&!nWYQiKQha;VsF6Iv1paqJJeYRf2)KU!p6@@hLjt16T8VUqB8=OH`PvJ zA8PfpFUi{Wc2aOi&1kb5f*l33{>~OD&w6!ax(MPpAoP6*dQmYw6KO10vx^!()>zhc zrRu{Yt8>z(j0ow>vf0wzUvDl18Lqf*XYHj?xA|aMvUR?$HokfEy0dRUKH}G#3twa) z(b-VwpSi_Y(i94B^Fd-I(hyk9qh zWke7y;(}d$qj?_$ET1w!I(D6FZk{^1UMbDw5ClP1RiAzt=R#ll283NTe3(0xh3qnc zhISL<=69=Cr2)%m3_=@w;oZmLqcZSH#Pb5KS9jX8#kc%Mv4917?rjLW-lJRXI<^Ip z0JVnSTasL!=&Z&#h)Vwc7o}sOWKM2>=Z;jFBnXR-euR9TJzgYB1b@V_pw;yT4Bbv? zf`3$KZzz^N$;^$kF9-gfpEr;Je_XZY{|F#Pb=_2uba__%Z1S%wZo-KpiYpo%)ov`~ ztk;IEhNcAyqivzWkmm6>lVV05#JU+>lk=_x(Z!I{W(NEu!V}jT0Zu=M0AMImyl+S( zzzOJBXT2isH(^05!DiVN^49{9W`(7T&0cU{)nSLs3czyK%h9{8xQ_A9tyV5x!bTDp z3Z3U#68O&RT*flHCV8e?z6d&*dH#>mw@>?QV4Uw*E>+j2i$7!o8;xJf@jVRP6#OI*V3~-><0q&6Ty*@sFy%Z841o8nMu+~Fj0y}gM z%Fj95;+(U?oZ*J&!fhe77u@k5ZiR*+;TO}-?`SqmyRPlO2NE5Z|1DiyqO%%>vUmjO z7OZ_GknL*6nP)aQGF`Akf`!iyfPmI!013m|7sIQ}vv>!`1BpL}ulpch|D@Q*801a# z9~lBGyhw?m20gMah4T@!Z4~9l*Sn6(_dMJVW9xpG`DZhV;I#^~46zoHch)UE`;YTJV&d*o z5DsNE>8$!@^~{Po=?7ug^KSx#N*rCqgiN8NuOnIKtGI{ixCg4ZhpM=*=mx5uCTI>m z3a<$L!JGHZLw}HzZ^)`Bd{sl|1Fn*BuzpSj-RqVI5~bi|(&j8T%QQx&w52Px-ebwj zOTDjoZcCf~S>-1;_XBVlJ~17*FgvdJQ+t_WFC{Y(1Q2=!VlQO{p>0-fRtbjBF$CM% zWB8sU{#}R-&ig>8tn4RQZOJTEt#!3m2y5_WRxuXPOdjs#v(0rK?k%_5wL()v_?c)) zl>Hn^SJ0g89s*M_AR79GDOZU6oYP9);sd|AkMx44gARlrSv-e(g`H%xjp@gbnvn?K^#Wz~S=c?v4k^H!goXAtvYnRn8Ekz56!p5ekVfj}7eQ5f`}? zaT+Z@gkZiHWar?}Xy znaKYPFS2WA7lLb|{!gfo`ME+CL62$WMIlY#NH1iaN?bU{0`cTYTP(Wv6e8P;bB~^O zwDKW6EhB(F;6c?rdfLEFF>mbrwyY~0XqVf8;6X5gjRoDtmy5Uf=BGtQNU@o{iAQRqvFl}kJ$877SW#n+TifCP^s zgQ>Q#0WXmh{fiilhHryRTu5D{u&A#UTyU@1U8t@(R($Z6u@x@v)?9;(c)tu`xi-G! zrEKWMXf%3~Oz@WslRhwQw>>cJpnl0q8Hp97M;eK>3cFwVgp>f|U*ii5%ly?7iU!+<$T7S z;S0O+8ZOyI$D1X=c(n4G(d(8V_aXGvIG}D8X;W3`r!#WL>L&g!x@e+CT$0 z>SF?vQ# zeVDd5tsleieF)}8FrTuYkpXr95RT9{#b|C%?r=It{CvV~H^hB3TH3m@YX)huJ2>Ae z#av1IlqxV3ETb;fD`KtZjumz>*=;knJW=xLPQ&JV|CV*|YqJM(D{k3Txa|)VUvjjM z?7AE`ooY=4VlHLKOq3t167HmaB3XfYG#DFyLXtV>*N5&F884{$GDLa+%C6zT2zMx62z_w&{V` zn^`I8o8zEk*vhq_=v~luJWO7TJY(z5BR3teu(Oax7$*^efUYzMiXw+`6eJ5iONRAp zM*d5zPeXam9ZI&j&XuvUiomHdZ@W3)l)mofOek698ZTL${sk=$ka@eti7NFgAE8{) zi~M7asZ)I`_Zd?3%!W-@sEuW`X$vVce+cf4(Pa->Lk{f0Av zYmVzp-qBRl8Gd|`a{0$Qo;g&xbzrE)g%}3@`;w1t4+1>oe8W=9)sG+BwFyWO+_3Je zv3*196zN7fg!SwE&mdr&^K@?5z@x|8vGgu9r|gA{+iNCxB1x%$jL{L6I`%|LwX;r= zu6k%NGdcN>Y+Nk4XAl8jk1XL3?N>zjcIxUO!8G6Wb`m0H`HvEs7;j<-P~ek1-^-#Y>x-#wg~BZst&@kGm$;ApL!+dbvq-+eaAd}f zK2@Tpo)3UdQCSSTS<7X1Z)?8d6=ool$MbR2qEuSv`&n*UgYdE z@ylvz(6IVT=6+`w(q$X8*;}2_?J$`$#k_JC+^&YDuV$Wi*ysr&G+|^fKQP+5VI0{@ z{#-UdFv;BBjnI&2THIX)TJ1ra>bmN^GmB2?Z`04NEN<^Um_HDTEwmSD5dq)Ti}BrM zF;3qde~vkLbj{Kqq}EP#&VGQe?iMz^l59q&tZwR_eQ)dj>C77`;ng5zuP0;-{h>Gl z|1})vc7#Me{B|`uA^niG>GSP?KXd*@6C{P@Kw?fLY$qKZ|5awiS*hclN{^-+wzOn{ z|I(ZMlV~&PbE%4Z*KKvW-MBjpuNGMfeb;2&#^2YPKnx+Y+IQ+Qp?6%*_I!@FH9COO zlY3(_uX3#q7~6@np~v%h{Q}}uF>&0vEJIrdCgScnSE>2iFage;k%c3YJr2!JG92w$ zp)4%a?RNbh!1vLt(UB9H|Ke4V+-)NPx z5l9eYQG)jG9BTWJe9Rey+n##ywPtPF-FKu*sBuofK0SZp|JpFmNgaeUhCY(SxuD1S z(f4W#K+ft1i>vp-^e_4OGqY~3Zko5>Ob@~OGOfNMp=7N))jX5bv|#! z^geV{qB`c#KkU5iwV&yS#=7DyGp5P91HOBxA79YwUVpy15ex_Mz4~Ut=PkkpV!0!q zb_YM_Q`{cQ4=3L;O zjxw?ddqKKonukY7LfcoMz`!VG2Ll*jwf0lIbdjKAwv_}dzp77a6kdTCD7BRv zycU@c#83F}+&U;4u998uzCMM1 zl~jMtSQbjB{W>nSRQn>H+j(FAjsKuVR@FoS_bG?cAK@JLHOX+p^px-gS}?Gf>v?H_ zuiA1j^TN-Vv~Pd}0Vj=KmB9prnB_mjR36)FiZwlyG8-^l7Li$UB@Vy@46p@~?ru4)8iT19yc-#z=& z@Le7rHJTG)Vs&E@04r~2S1WHNd%N{Z$CyxzHpS$u9dk^ETKXn zV=p}x8Ar~;omOL&sKJW5o*R*5wNMpfm;@LSaMJJne~?FaeVjUC0tRt0Ni4bR{U5~y z3{=&19p2x&3H&GN2z&wN(3joM9TYWc>=qqGFGZ=QT(`LM7%G=dJw-TJrI*E2Cj#mO zpgL^PYyHe(Rd12Hp3+ynp)qNRfNB9Jo!*hbIsB8m6vm8EhZno}F_^vgJ$m@xUvy3;ds z9U*bqKH7))QMw0VI|Wi*&x~KS+D@d&{~MG92b`2l-_cet5B7OHQS!ei zKLg@*&ffB%a(jEMqO7yRWlxSmkyxKe=LT}}lI*D$cG{3u4fPU%BAwGTPOMtaLhV;& z_;%XrCE}D)u^N-kA>`!6+3HwfoL+@=44e@WgR4I#P9wtKBc9u7Exl)n|4cKf_Gv7^ zPD?#kqci~H=b359pR_YZGnSb>C>qrYStFE3KO!Ii6Fk2o= zh_mqht62QsclmErAb&7~s>3v9g-`x~lI1-5;VWa>!^h`XUPJ+Sy&VtywdtST^LdU* z)vm0L8*WOCKJfp1&5RVxuKYAPOJA?y?MdG5bVC_-z8w zm}N-K1`Ca%YR(<4^Y-0E!2-!?^@&>bmQ3{RWX7(7^v^rsnb@Rt{zu<*)l;Er)V5@< zzx;YC)$2{!Ifeq~%fKDv7K1qU~3jl;W{} z&h_n26gv7F`i$Kl0{SMmtbdXrw>-NI%hK|POn6%82uWRgnr_v%ptqcN`1~lONPcWG zok)geM*KP^^LSR=>A&U@T8x?t^2fZ#y*32 zhRIbC;2>%pUYBxI){r28y1C!@Ti1^#sD7&b3u8gO~lmP{~3*qjAdcpFF< zg4oTxj?SOKJig5HKL?NN4@6IyKd1c`gk=V}JvB%UN;D(VBM}ZNYbW#!YL%S+K!l|d zK$_!EnEs%kL(Jv=N=J@vhldNn!u^mHCNILwAj&5=Cc7v6QqM5*%)n>Y;=A|N@#xyI z{GRkLZ-&Ty+BIV(F6IA%5z+qMB^Xk6uf!G|RJ|hE@BsYjMW7*$a4^p&`wy*nPR9XF zFVig~YOl6R(e0RDu+%!-4j#3PZF4^3dmPsO!dn7o7?YsmQ3YKohJ8o)z?F06wLk65 zea{g8Y`U4F>7Si=ktO&tPuMt{US4N4uFvVXv~kAW2g}CHl!y{FQ1F9od$6A01FOO> zpE|WhNF;o}^mlng!hY!W2zJC@-h)%V&#Jld{A zT%#JS)5TvmOW*wNa&2BE8A3H|x=U3v97&Fy zVG|1PICdYS9JbXjvVBdaqmLqxVa8(ibB6hc!P{plC^$I%Qg{2~g$4R6czSAn$;!C= zc>i6%h6(RZ8M=i_$OKd7*PMRY%|tUp0CMpGI8`q%Vs08DoP1_h< zg2zQ)ae;+-CcFmRuYAT`&vnK*&sE0_yee!luPbb;rV^0K51WLHir z955bd8!%NP>!W>`V_W~Reh@adggaRw0;ZrovVFT-G8%t)fS{S-Bq7!E& zcUAH5n~&thFmp3bkKieLCvgMco?=@C9YBWsY8Mvn&pDm-Ywp##pD2bYe%}h$DtS6F zW3Y2LDC%Y>_iN+j{3_YNbP|GSs3-aq-RTdP8{$A)999i-w64corFfOyzB(`U8gXUw zlWsJU`pTK(|Cz;Nm8(cY333(Y)#W;xK_+-Q>*AA|74DovA6Kw3C4=Tx9H}?*gixTS zAcV_P=M2}1jv`x~BrBaR6vAOyoo=15Rqxg0gU*AJiJWj&`lbnuAt8`S%W_3au6m1e z<0{7^Mty-yjl*|c#l&PSI##D|?ZVciLRR|HaV ztdTtAmgDHkd<^%JEwotnU6_2&8)qmlRl*u#HC(OA=@bc^dEu#APvY5-XFk+mll!81 z)g>Y@732~6b5?-O7@1z&FX0oYQ zB7Z=mZErnq(_qsQ*_Yu&pg-;ERU6OO*`@)qBtlMw zX#@YZ{jad5NfyAJLR-cG*>dI<_9-q*aBrS*(MW8k`e@i%?e(11;(ENdqlL7DB-k~v zqpw68q)@N@_^M@;{-VyKd^579-mZ=>8{m~X2@+J)uS#%GPiXO{x+>*qGgar}U}0VP9j`o5-Up@0{Y8;epwT>f1ZT_X6+eijul z5n`M)q81>-(AB9o7{C^iNvl!8Ic7xIw*=QZcHsCJ>m{I3DYVhZC09%=lx*8#mI@N) zOJbh-w%JBrB0kzeh#Wt6I9B9H0&Ug@7DGkKKZk3TKiV&DnrLBI4z`KxEdjqkuojPv zczrHT8`;?E@Uzk_aXfLE+}|*UHx>Ji_~!Oa;6IkqKh3`Q)Bxd}H=>p*o66p5EG`%! z9yL5|nPv46!ZI%OncYhpo3ObW)q1XeS}gXgtY$lv#pQ#W1E=}q$Im9UDXE%cCiCeV zvZK2f)plvqep+*uhBJQ5K1x!~qY`zjBmNrQbuAaA~&GNWv%o`lDl1pi_i1l70<}eJKfFAP|Ux(3!m|vx4pA28uo-jc#kl!agCn0>+^~UJrz8%N<>$>mLo_#2Cbi0$+FBB!;Jj11I<){5h z2p2`2)N!B1*Zr_NGwu&V7bJa_^Y(X@Gx05IV7)CFYKcs=^`y__g%;(7no>lu(#@uM zLGk7#UpG_>h9+4d)NOFAyxozzEvdX!Y`yc@Ge6b1E1Oy0d3-BTX+K$V6Jq}URQygB z;BhK{hnR_Np)Fm42Tq-q`ZV8RwP>EUPWoPpy*I6#x-&>OY=y{?7#c>Mqt22v8rrPD z4XtzY0*t02GgXn(WFPhMBMf!ka+TyIO`6+!W}`4G>^5>l?fgy&T1zpj#wOOrql&>4i)zq{QTbP)57{t!a}5` z-@IsNtXX$1+AvPJR>;I6YtgmEx3yJSBEf49sp6bo=ibwny{@%nyxHhm;tv=~ajN#$ zR|>4x_n2F3-s3Xl-SGD~aal4hS!kVZ%U`c*7;S4?r)eo#mtVpIGXAPj z1T@oox(zKlCHw0R`Rhp`D^QN!C%t%TfO@qNs>N5aEZ%jDAH9PiJ?ox*dx<<<4f-uk zz(M3k>c_kLys`c~7CF-l4%B_+aEoS=B06Jx&;!C82M|_Np30e)nP=%lz%z9=>D7LW zI65NkIA~=SE_bwa9U4o=ld(37s5IX1>^SIjk$o>2BdzIbPZz_m88$b5-wl1?mshb& zxc4YxzaG=KnQs<_MeJ@`DTAx!S+GC*DfcS>#*5*358CNqjTIZ>E_~CODkWM-s+)2s zH0ZV0qi!hB>21d}8Q6HKQ(QVr;iWi9fSsu}nVm`>l)PAO=ZRx7x-?xJy=ymUNPq|v zs?*V2&_Xz5uq3XxD#SK>Fu)Mb#?R#JUY9As-RznSlKVDio$J9-e5If3!LfWrVlz!l zZ7mxvyBp`lsTO7PaC>{zI%K4Cq1a-RL|fyA(Qey$T`EB)&mp}KX4(4TqL8lCyaj?& zp?=cHx%S=Ai)nW`t70a);}3V=HeX9hW2}qK~d*HNoKO&n&g7hS`pqyU;ni!+=d?bs3@G0J_OHA7L53C;?uPo*T>PUw0y{YJFGo% z$gGXx-0#n80XNc@Yu=x}j+B1v$rDAM_jG#ftu5!O!NZh!|IS)*0U6fjDLD!`(*|Mr zr2IHNUU{9TQ9Q{kB|Xhxo_LQU1b9C_7OpW3?N6HEn9l4!o1mV)?T5Y@w2Iw}k1{@s zV=W5M^|uV%$r*}nZQR3uv-dgKyB>wFu%kI`q|u$$w5s?9qbNoxE>sg}tiY_X)3)pN zG~Q=T{BgXdnvo5&f<_nkw*PQqaUcLW+t1k2K|ZW$W| z=2YuRj(^-rUu-U|Y^W{;S|RqJSgrOnL*kU1i%LfTL@?9}zS!H7!IcN^waT#fnHB-> z87(�aP~gm&#&yCF;*oX+=CzeSt;L0-!Tu3Tm7)@zK+CODY>+g#bfaa~2w={cERx zR4Q3y&AFk7itqA7asZ{$Q{FHA#=NoQfYz`m zJ^tba;h*#-m!9xuUQSTS)M-R3B1WOo@X#guBQwNjXf@o$!gSO7+`)!X0SYup-5F?G zU8>pH^%~(^9(F_ILAfRbe2T`7d$}^Um*(wEYtbeaO~?6`A6sUR1xA<{FSc&CsRS=hnUqgoZFXxxKY&GVS#ziVLF-o-K!j>5W%tYEQqJI7 z)Kwgh)G<9Mcr{Zlj{Q}UO_7D@_bvTZDxyKD5_*dc7O7p%h>$*CVe#IO0-w4GnqZrs z#++yen9Wd8n_&gS#>NqFU=GWio9!4n?3}Awsm;8pB?uPrDXonTNn!BauUc6|a@BH$ zpjU-D6r@h=Huetf=n9P){l>_`BP?=j(}HuQH1?-f^oC2UCo};uA|dSe^FSLYdU^##W=LZ_&u) zap9R_TKVQX$0nW`K_lO4p4Svo;}m2fQ%g=tho;C{`W@;r|6iUpHl@Pzo;fxxXSRl> zo!KVMZvgwpb=99|Yx(A(eLME1wZ@9y#5^2z9}%R7Ic|5G7ZmMVo2R&`&hK|CZno6< zeinj;Ig&iu%}|=F`m6$7cT^)Y%qW@5WFLmsI-cOB)6SW&dWwlexJ#*}&%X})+zO>< z(u99<1AbJ^8EfQwp~mT!6hR@sDdzZtbxfc@utsv#rAfBr5pRJ^jqs{l_-oonuWXXt z44L6E5yI@|(2yUFpT8Zud{lscIoA6KREs~h{Ada3~iRJ7dPh(JEgoZ`VJV#}Q7 zA(B#VS<3`9Zbtp8-a2iX{6Pu7Y4Z4CTh|Z9{#Q|j&CvO_rYmdXY=2|dcg79=7OvhI6K$-G z#k`|!QjK-0PRl6^>cF4=YOd9}%QU+wroa~eKv%=XB2Rl)g~b%l=I=$j&gE)I9T`eR zyns>t{?!dapV76=Rt~+pG3IP`>6^rwW#+mZ+|-zN56`5Smir?lT}^o$@Iq;h*v; zt7Wh&tz-bL8`zbt>y=07@zqYz>{L!D5jLXGQ0^nX&*&w$tW9Z{nD?>orrSoEbDInV zeY14a28c<&x%{<%H|WVWW?CA`isnZQXW@Og?NlaBO0isGp*y}mM2cBrL$pSGrYan? zFu+y?Opx1ab--_oRsn)&8s=p~S1nsZRFLCk6H-bVr|Xxngcq%bd|%yf z)J|nsso6-6@HF$cy}#NP3y8hV+h!ftja)oQ-R2py6?bZS9bndEm-@seTevoq1uvA8 ztTB4w6_Sm@mA&$-^$~_GQ~4vD3-Q^PQ(qa5xW?oHRF;_7`%&NJ)eU;qqle~TYMmwEH&PK~{9%j#q!LDLBC==Z7%oC6W0OY6PQ*S-+*R=*bpJ)VV7i5= zPz;Uy>}mKiEpN4{h!KBGbvgCzh)c$z<@e{xm1&5#3(RK{fOi0N)iS7=5BcE?(!1X6 zpDIO%wp>Wqb6FS%?CU6TFSAa`;O2x^(fxiV=AhW9r^f?us<=P$kN|p|OSE?gJZams z8qGPLeXiso;Qe{gm0MBQJHF5l(q__6xSwYr`>WSpc}g^Ake(5p5p`BLS2=gqO6`$E z#@*muk>%Kcs$?)}FR-o%%q;^4ZXa>4>+ab;g2h#^JPo?hJu~evS^BWd#CFDfCDU%V zWVMV{l45qJ_|-ioj%h&r9JEj}zDxKt>?r={j)ptOT7YpeZ{p8whF^IJIPTUNDUxr! z6$RW`n;v~F;+jnS8sTo$RPc@>=7RRA#Hs||GE-LQCHwPtGj3XBhfndM*n7s|`T#9D zvhv93Zd&-a?stb8Ip3J`l=Q#q4<;wQ?a@fl;?;gT`Bla4o54@vcV8?yo_Q!Pj$s$+ z&M`YCdcJM`**bQA`-{7lI1`bQ%}=*6tnIJv+D*JFK9POTm3$=eGM}myvs)NcNi}9- zsErbG9C9C*o@jOI4-w9;ZDSgvY>#Su=A@9e?!s)SaO5MPk6U3d84EjFhYhvoZRbsEGaZ&xcR(AXHu?`b1xq-!RAfeg>Tn z_&>#PmAMdjOLJZ{-H*AJ_Jrgs1ZUvM-Am6eYF|WNGB7v4s_F;5Vqm+&{i+gxarEv; zSPcJE;=Va{mRC488_SyMTiy%Q6Yn+P6Hxqe$XbH^+Hy8hr2p;3ztPFC#p}C;l(6*MU6qHgX zu{EoEZupkvd=_(!b>oTK7r%J1;p=ZT&-=ayGM5d@2;M2{2+G)m_y2zYKS030%gEnX zz&n^pyD`_8OL$|xF`o#=$Bl)=Wn5xhLPTS+v6x84Qe!Fc7@syiO=M$*@p=Vpv=&t`mF2O=6$8P24H&7Wat<#lzw;aY#HRj)>>Qi{fQ*T$~VZ zN-T&`GD*o&nv^N!NO@ABv{WjUmP@OoD#Lp1hRLzP)Ci1afuH|g{C*zfE@XKk zvixpj`8~+;WMuih$nq3qc`C9z4O#vGvOFDGo`Ed?1hPC6S)PR~e;8SwjV%8pvOEV_ z{s^*sF&P5MMXo=JT+c(U=OfoYgOR z;Pel{9w?hDk5OA2DB31*ThrOT@Cka`##PdH1OQqSSs1_-A*p*gfXIEGZui%o7flxv%)g z5!d_^?i>D_(pnWX?Vbv-(z;uqe-^obQR)d8=@AhhFiD#}9yFhr7)TaV0%=m;Y>4TB zOff5vBW;@v(HzK=cHV-RA1J&XD61n|#3g~HVsW5!K|udec-`Uc6k>T`)or07P({aR z9&7;zg|9K%BQ^$_ZwJ1X=q9lxuo}@8a3X|&G!wqIXrE7rZWHBzf1&5f>7jLEFcAGX z_~htLUog5`>Pr14_gBLv#>R={kB25u_G`r7icf1RW8qjxGS({ z7WM}A-wveR!E*6HU{E|1IIW4@z-GQ!h>0(e2F9oh(edj>B9F#GAHE`{AAdLru zv&y(0xG@WpfvLHWCW4*P&0x1gf}Dp9Zos24*t<}DJ`9o}7%wFR6Xzi*m@=#V8l==< z`b>CC!7VZ0KFb$tzB1k6I=^_92Z!l-+BVOs;2BR<@Eo-bk2QF~;|QMcGzTwvRtK-rIl$u#UZ=jDw%H>E zCq4cU@kB!gPgf{``ee`gP!hE_&&E)yXLBgS(;v$AY!Bt)`~;x(?HLFac=m*fJo`f> zp25&E&ymnd&+$+t&XIHuqVodn!;`@*&*_lGb2e1(8HHz$g_=B9LQS;qJ=fGS=p5&{ z5o+~Jh1zlMiOsb$#%Q`s3T;k_%>^31Rp-sq#*nCarahR{^ygdtAo8^4yOK1aqPHZlwM+$jKsE@X7?i?E%JGt0@o`TM? zv3WHHxy(OKF+E4pIa8Y(yAZK0iVV`#VB651!Xg$~L>=&&q@j!}-v!O)Q089F6*heqTLq4UUP@ZHpADdgVJ zMR`l;vb;4kF7F6UP+uhP3f)Azh}nVW7pX6m_l8;O=i~#xf6YeZLt!KJTlD^z51eOP zbL?u`zi7549}SzR-;_^;ljY%X8nyB1`)PjKmNVf@`CK?hz7WonFNF&cSHnx?>)}#) zGQ8YN!mGT7aFw_>Z2edtq}9utp!#w8?3nMK&ZE^C+d9V|Pq&Bq;TS&bSqu16Z;}d3 zr>bKS!#qDZ(^rCjjQPl!{*dOyav%@Z6Z+1Z5$vWM@$HBn^zDisrm+p>2aRcbd!xsE z2ckoC?0ko!r@V*5*L+8#Bfb;S^VCQBhNBmKXQG#B+~GSH9mkl0`m_tt3E!pYP2bfH z)_1+b=$q^?`AJ7Io&WuYjx>KlN2WiiBZtn>{?v{vJNZ8WSYOEev-y!{*@gLd>)N?v={};(#oLM{FNQeeoMz{%omI8VsTjG zEgy`C#V}gz;jiy-(s<0@)FIKf`dd5v)AvJuYUBR)j;P<=(dAb<*89U98~tlLHe((d zH^!jFiL)>_7Sv+DS)g@`#dHhAb^di7{V~jo>tZq509RN;HNh`?1;rtv+OE2-0Up~Z9^1=S9?psPVcg?G=1O7u-{u5j#6&V zDi87?Ea5J1eR#dMDZJ6!8s6+}5BFm%KG)vBH_-FcXLyzHfHxf8<6RrxKQE2}c-Mso z5k27}bpAtIq&5sOws%wbxVJBSlG>klTllnhXZWmlcX*Wko}zW6^QSYe;hxSL?JQ9ibo{uDYFGkR2y_X~Dv|R6aBnvSSF?(-D z@)b6+L@`E+6;q^4Nsg2&X^{#VJ1993o01o4R0<<4%F;+1`ULRN)Q+e>R+dL(S`TGa zB&bwHIu&cA8~dF07xbaxh-^@rBfZqF6lY|sB1Lv!et%?_5{>Ltx*`W?45+M+9HKE5 zg|abnG{#M3bL5259~nkFqQ5iX81qNU_Q)A!AaYLG6S<)5k6cm)BUkA)nxB@T9En`V z-)`F2D#s&}%E>5EPDc&O*=PdgmNFVmqI0-17EM*IL^G%_ru{-~NVyixrd&{NM02q( zrlJKtE?Pv(^2J9>XbkR4j4tz~L|6LKqm{m_sKsZF)=&Ff7++t0w29Wqw|r_#Z_ z&V83z%kAd&Fki!+mG!u@(t|rIui?&0FYc^-6L(g=g*z*KxU;eqcUHcGJ1g69XXSgi zv$7L+R!-BM73MnKSz-P{cUGA9=*|lB0q(4DxU*uwofQ-Atfb@4N+#~CJcc_fPvXwX zXK`m`68%aCAf$!zF@LTyE{4Rbke}F&4ALUQ*!~7Zk9DjjtM7hLY z<*)OT0^wU!5e!0tkR+rE8A7&@D-;MtLW!_USSeHr7NK5f5?Y0J!7V6!5TsKG3u}dS zLXWVC?^Z?V6SfIEh26qF;h=C>I3^4Ur-TvVyl_#tEQ|{i!c7;;x5dO|beUYqt~6IB zFR0?mapk!RT}xf1ybMC?M03(>^oj5Uy3W670J#0^zsox4^I#ht6dJnFH z-izy?DP%QiBlnSZkThHkeE?TOAH>zrPvB~3Ca#7)gsY(s<7#L&u7-XRS3@7c)lf68 zhAzg{&|F*%eH2$i^T6hYNIp3U@;I)B7UF8?6Sx}sXu8CGK zAtpj9nGU9dyohU})wm{FgKMI-xEe}#Qh!A1m>)AgCiS=`YR5Iv23!+;iCf3LN}9mZ zHI}s59Nvhxe^CVSpgiPYvy+VJL-W$lpl8@ zKN4`Ad=a$k6<`u&Ln3hDHQ*EFK@zZF2k?n9AesCC8KaBam z0K@30KY*j2j%(l#!pL7H892t7Od^c&LpZuwIIa)lh-Nb{F-_!?IHHfhhzi8a$S|V0 zxXS$~vmQn<4@dDa9L0QG)BY6mBjx}pAdIodSaNGT*4*IkUUOrfOgTAcyfblHQk?0| zEEMxR$#*Vs7CXyO%AFM;)o{i(M;e`pYocqS&K8h15Wy*f4mvxX-P5wc**j0RIJY`? zfb4Sa)#QLChnz=2P5_1%kTcG6&I{9W$$52Ju4^(mS9ro3_yj&_T2lE8O|s`nE?>YG zX;Q*316j#e&Jzn?&o_azg0zFUd4&)2Yx#A2&$Mjf`{v0uekZ>hWFLP}l{I6k@Q3+h zAVYvt3&;q6p1(LPm-+E&nb73sToG8o$e$8S(~>Nt37O6^A!mO1LY`14ES;88kmbUv zIZ_3%3J#QJkktYVwjc?9Au4nU>+vpCHVT`C{<*RyP1r6B2z!M6!XU~K;kYIzh10@W zVN@6su7ECGK&}ZlgsGUgI9Gg3peIpWiIm^26v|vzx+}|NcJ{jRT}zz9u3}di<%g?` zzv(J>Rk$hyr>oj!6Z&0^pi5mXt~M%^DJ}syQ0bCgLB7w`>FVZ_TpL`yw5MHLTw7f` zT)SL*T?d?5u0yV)t`n|dzTS1lbZE=>ld)%9x-Ly?; zi#E*Ji*^E5;O=u)xVO1?x_7U+;ob-5ufp-5`>^|%dkF4`cb{^PIJ4a6-51@L-Q(^F z_sunf@PrCgL{>CXdlgM$GDw=33D(-FTCA8O=Am7}lf**j0dc8V3bNdJR9q!iiPowX z(IGZF&$+ra`=b_kU0f|XMM?CFQRe}7k=P}!7dHyc;%2d5+%67?d&K?XpfD;P5s$~- zYXE*affc2(_ZuMhl=_Z?c$zYhGFTle%-4^M0VYU^0DK36zbTnv4BHld6GHU6Y?1(s zPt)FrXru2$(30txLmBk#h%G|1_J#z$BLN(yQYsyi1nDSnbwC)T?@S2Cr8AVLphwlW zC&V1-s(V7XAzc@yq)Ff-=W65k(YGn!nWMnaHvZ=Hn-tleTs{Nep@_XXp}i-;w|d&a zPxQs!l5lm3`#tMCJ@j1)eq#2!5^lF=2s~LO_>d&t;5h}}sns(AvW@28i|AVvd=Gj% zWH9FJLmvYk&vThyroLg}oRnEOKhCd|jh+(OBqzfi3F0a_jn9xXc z__f}6Z=yFvDD|dG8@yR-#=K^4zITbY*jwf;_f~kT;fl@M=xy<~c?GZR4T5wE1Kw_7 z(7VCg>)qnr>fPbp<=yK&;63C$>OBEDhrMUK=e!rZm%LZK*Q+;rCl#U?lmsP7NmVkG zY$aDIP>Q^rN{O&vS?0N{tW+u$3%^pSSDKVorCo6=^#8E3R#~U?D4Uc%xM!QPQ`xQT zQw}PJg=XcLG6XqJd76|F<-BrHxvY#U6Ut3tm5=oqeI{SBFU^wKC92+YxY(7R{NYj$>;Y)eO3agT5oa zLVF0iKbFzi0^lqG9p3j1FU74u8w& z@mGuiW8OIY6=TF-F?ZlEmpk#7O9IBcCX9LS!k9M^f3w_;zgF%cOkzu-6WfIE9r9{@FOAZ#U1b)3i^S=>uXmtl5^8-mh`qmNc8wHT{6?fC0_tz&ulPQo#A8 zX1{hG+Eg|nkm)ZEF1v(%L31_ zq}=K=YTp*{?-nTE0&|lE<|PaCp`}>s-&lV_AJTc!0(IxlsL!_8RM2u_WzhM}0`r4K z(CRgJoaT(t^n9X?lZDP3v<@^)=Y%aY?zgF9XX#e`o26H4TP)84bM`FEn3u5)`SW4f zA>5i@7noylZjE8?92=W27nmn&x2gEpd9qWOJr`~eZq0!+<~!Pc%1aB(Ef(N~1=?eQ zIl%&Rg5{FRQ44U;0zTaWKE0M`TsEjSOHm8yTJYVqz|GoJ)fd&q{AGRV z=Pb8uq_#lyTlD^EA2`>x=GfJ=f6;8Kwn#gIU#(rH*?H{#CiQu>aDOd*4o%lQeAbN%E@U%7UMkDTcfbG3WJ z+O=%eM^ld2U|ei4rZl#p{Gc(74X)dA)v>bytc7rd{;-v(JhMTc*r0th?yy0hV@v^D zvO(E4XsZqS-3INkLH%v?xxgVC)YAsfx6%5+^K4KrTMqzyhOG|(+_&z5BltJlZoodx ze`@}c`bZj^38~ui&fW5(Se8}>y=H^B*>+6JH`fo(@xjwEOw11t2^f#rPHAl&nQ{MB z)y8e-0nkqZZ3o1`wh1lIjv3gy0OrPmClW-kYlVy{+?Ys}{yK7DvsrtJ=O>{;n3ryB5Z~cHfNq4gwBq+@4w9J`FIo zwJ=V#Fh;d7KDFmn-p;ePCM`|}zSdp_z*zC;g!yp{^$|B!SXp)cL))Vq2ft}G0!*q6 zS(5=UhgxauIHJ~(mP_r*3bCR!Pqi1c9pE>AL4~zc&1+q*_7iP04}RDRF`Lz@-S1G# z<*%x+LM&wkJGDX_WrY~Z3UQ4UVixOqHFmH<%)!HWTOm%c4ybLWKAPGQ^~cuzYCWtF zBUm9uupZa?{Jh$SR)`g>r&YVMLY!b7)AG~yL5#ppsxhE-N{y)~>bP6ntb;kVE>W|K zOPW1t{-_T6uny+ZI^a$n%=vZs>NT35mQlAvows6RTLKtAN z^LkyQ>Wi(-stwh(s9dOPQ~RP0=FK`;D=Vn_?mCz!>tK$ogXh%Ia<&yg5efdr#T9I6%tfF)3Fkg)G?;~pl@R=Ij4`9n*se=zU_bkz#hPU4TFFq zfa8FZfYX4p+Hn*xrX8;Ut^sZUrU)@|fOz%1F%gggNC#vA%z%8r5qAfOY_4cGwa1#AIq1?&Lq0_+7G02~4w1)Km31I_@>0WJV80j>hB z111TW55NEbd%7bDkP65EWCL=wV*#KDPy$#6SP7^ESOE1}{wD3ut$=ob8=wHffVFD7 z?^p-u0c-;F0k#2le#CJ%U?1Qh;4t7AUH0)UJ0z{PmrVmxp$9=I3}T#N@U#se4Qp}ctDVmxp$el_{Nz0khY zUTR-%UuCZXSnUpbvwgMQX_xGNd(_@#UvJ-N-)!%5eRi*^%#9;wW~MIm#Us_RWrJht1K5XmPYT z1c&ShIyxQQjt!1p#}>y{#}3CX$6m()$05g2#|g)<tgQcOqp{b#@p}oP~pfrRV);6qb=xNxrAo?1% zHSBEI-LOxSgCH~0hc!6{GSqOYVFc3WHM!Vu88Hqr0dljEZ8SET8j~B-8Z#Sn8uMUI zxPQSfF%a!b3`YDCLp*+oApyU{V8SmkB;uDClJH9m$@nFP6#NpyefSNA`%Rgq$H@bx zCrr!9W2P^fR+G<}+D$I9!X%k|Gk8)ncv3TX(#7CO7lS8VoT#2#44!l`c+$mLnG}O*59*2!4Bm#cyxuOogUG!kJc>%8B0etm%0Yhu`5y zFui1IhH-e=^a^><TUguWB&O!br8GEBQbKgxX;bROpX zGnWr~RIR5zfVH*Jwx}i0t5D7tXnw3`p8jt^m*DvlOh3*&jrnQGh1jcwdI8VhgXhbs z)}6=mcfqs%K%f5pU-cEB-{HzYU(kEt>MOK$Q?KZsz|pCrTK@v*#n{7(^9==8Exr8`iA|>(h!gp?VpfS%&EvOxIxg3B0Qi?|Mp2 zqkazaJcoInW`=2+c^A*WiX|+?d%G~rVrlQ7 z{w?PJ9rtt4*SVj;)k5wx=p346{)qZdc>X2sH+U6tl0RYo&!WDBdLPy7pD|}KrdQJZ z%&+jwvzY!hmi9WPx8wOzy!TzIb@yWWH>lr4{RZa0!10iCh5l`3PPk zKSA5et%38&G!MC;@1XBnQ_cKFI|Evmi{&JvPQiP>fO2B0lsg6s9CqAZ*GUoiMfqt>39@Ay0Q&5{wXJ82? zEWv~&q+Mg1<8@T#WwqaHxr zjhdG8D)v$r&7=D-sJmz$<{d2I9Zdfg)4!!{VJ_&0C?`>0(0?1XfchoW$QJz-D93_If-RX;$5S7brjExYG)3DCfLUN z^+%CuL#PGRFQNV=)ySWdDl=&s_=!2;w zm{m0s#&b?`&Ru#DmL{;QfD}QR1(1~{F1;y;1*9n`3MwB8%1059rXVPwND&n2@PU9d zMVd6JOOf8BiGUO-y61kGU+zEe^FEWwB$-Sm<=(sNCnHHll1%nUmR2lo0#^~k^Q{N| z>mr;!kET|RK-SbNte0G}7khbJ%ws1XcJg5-pZL(CSX)Eg9SIcAY{ce9_;~n~1lrO0 z+vsPVSh_@VtTypXe8Q*N`?cqf3|2GyBKfb&MWW-K5{aF`OnmNe3O>wabRzlNtzsmB zTbo3}Mvv+0G-RUcpJPR7|xK$2?vSy%v#Yg&BTY{bm3u6 z{P{lXVjHVwGozTtin!PPh0IHv6I9kNozJ+YRx+0V≪-44MnFS`%+a!2l`nDU~ z8=Ea_FgBm;B&F#Rb-EASPoT>`!ZmhEC)T6Q4}Jmmp#5el*<%|qCXzd>wGHqb;Eu3} z^pjZql+tNnOjexNlAJT2=$$NkiuaXZu$)!4Q7i<>%)XB#A{VWbJeKFS zX6G_3R$_E7391?J7r`1P)k-4vg8ONu5VfXaXFZZ1+_^|@Qr<{Phk<>;USL(MO$O_M zC-K-!a^q?98kWymERHpU2Y#e)Bak$p)+|A@U3?g17c>Kjy~WZ)Jw{6PAHogXt`0ff z)x~3tgHKqeWAVQ|rF)$Gy`79=z4TKTVWv)VmNWE9!Lu5Bcks3_mObWm*^%khli)h= zTkK3nKLuXI^sw@^*r_gU`H$*9E%r4}Nw0{Uqo#|+$UJG~p|hg7;7qU^>u7PJhcd=KfsEpNlf_yX80KfiNh>w6Qv?1EV_8F{`i}F=DQ2e(I=Qjj z1-yMZUUHz8>OrXx=mYZlj1nhHu(Gz#v=x0{%EvAiG4$G~ae zMDQDMrjheQ8kW^P4ezCieVt!4b$-0D01FG?^WgIs(V4KB#g$ zm3Z3^4x?A)k)Jf1Eq+Z;&JcU)_rx|kG+ zjj=|=LnB(Txlw(l_bD%G7Gx6)Ybr1EguDS}o(SwYM}NrKdzG9LO)c5e4JS#x1mxsz zX2?0&Oyd0MPQuBYt`&9DIbF9!bE({U%}Uv!G^cm78omQ->GFzYcwI5Gu`og~mPO?H z2G%&+>lx@*C+fP2Z}l?qyxt104HDJnKABCEn>p%>{#0gvn_w^)or1)b7ERp)NdSM7 zSvv-Q4tXIg+#&V~!>56Rz(;7eGUvC?<&L8pOJ3E7*iQ$Ob(gUtte1?fCvXoMKn5Ns zs5>I*!-@0+c9w!$K~6q;Cw7j4o59!Fso8Ti89tZ}e;I`PH`t4N${E|_;tc;&f-eW> zg2TZpQYvo+!7=8dDVn*#T46hj1F+B^T$RAN;BZhZEJ5>aYAqCrMUgZVN$?`k;$C$+ zgVn)7yj{G++eHWNBh{p?_l4XMOg5rx0WGG31Lbu^rx7j4Ey{>~qm}##Tn^3!hlAE; zP(a>Q!WG2QiXhqIZETJM+km^U$sN-;@6Ai#a&Rs}*O$Xy zU14yF8XU(%if#ZgR+1Rf*m;FXX6h30B;usxZ?~U#-1gH2gs@0 ze;CUX;T`3!Vek94hu*uKi@I|@*^ACzv1y7kqJ7-Tb0u&J*bD3c%IYg3Jv6!Gy(L`a zR)nk<|0veDyV+658RoUbNmZh#E30E1r8^Ti1?&ZO05_pyJ#6wzE5Y=jA1FFqsWm-; zBFTeKZs51W(u!R##U%0_^15;`CjI|SB*7rg*z@2U$pFW>3m-@Sjetl?puDcE4Qt^O ziL`gkKzbrK)GSrM_D+_Ia})>vzqnD>#jLW{@E@( zX@b~{-84hVJo55$4x8^Y-t(;1T=ME-=PQG=tGvd%EZk;~D_{mW;R=|+O1}bTkl~kF z&TFc9S8Uq-ai#1pjOash-AY#XaeBK=US`ZZLEV6!yw2;*8scG9I863d^vA(hQ)?1- z+&k?Uyf>6LsAnX%gl#EZO064-d?kDbm<~<|{}zlrFMBKcBP8}>SrWAb4}c@Fa79+A z3FQUGMx%`obAM3S@?Vi`lHLZ_iJV=m!H%r!+epR+Tf~~k4SSY<9(;w{?i81!$QaxK zH88j8mn!6y-2^T3gK{$?=R_W2%lSJ18p=LIR~C~q}Ey1AcxD7(X}SbLTC z3TJtSwC-1-54@=8x=0K9cdXHiGFubaq63toi(ri<};&uA}HtWv4ihM}~mZG1#^%_CyW)lpF z;jk00nzseb6|=zN@2u92!h_#~_pIavJhlg&H^?WvIoo+`Ywy54g?<=o2-atGsnX#Xh9tOoJ<+aTeF@-E|C8IM<^i_-XwT(BkLSL5` zbR{Hh~>!U91g~x0)bB&@_}68+-1xo(ZPnpIhjsfVqPcO6~&k zmVN|DH{xvrd^mo17R$4da7wXzgv53Yd|MO`@ad=R6&VjK&lUi2$GJIn<8IhZ?xD6cmC{DUfaJ+_XnqJT3x>*^ z!naTwgV%G2oqE`*hn?E!pXUBvOeCfllFdkl85@(Hdm+gMzQH@m6TFi=!M*qa?&c%p zCacGYzTX_pZM3N5{O@n&PWKb{xV%`-D|XC7@NN!~FjB)v4I{N^A(o3^xd>xF!PrlT56#nJKP(*V1wWK|#LiHMc&r)x z5j;~UY=ZX$pXT*uOE{IWG?5dI*+aXQ2Q|$REZo4F=>JLI)`1_GQWo2r!JITC|KAq5 zX-8=21bsPV&$>N8k%6N4xH}sx-LiYqWZuf~vL*8?;GlM0$-50}q zbEx$Y{%V^TL(J4bcoBGhZu&mf4Eo>6TaYeGKdZ|e z8O=-$r4L1dauy#D^!L-sKXL}px$#L?G`E6fsauR%x#2#uABrRxAQ5733PT0my9BjH zFuES_HwFD;@CU<3!OtW!Be^S)U}H@9G;j&_v8nH4M80_5>fE9KcUbT8&6x+{bL1O1 zppI{a+w()__4rHjeWAGRVdmcWM9b^MH_3O*;>#?ygtv@WmhVc%TY$E$%%zl;iGPdc zw^*1%=?M9LRD1>!iC&ww{6Z3UJ_@(1`Q zk`7=MdWA%}RxW_wQ~DQJ158K058hDv=Iuu^4g3aq8okPotDcb=g;u^~~$iPjuQNX#j5n7GqxCj8Y^X1pO4S zAEo^=@5nbLkW@&-q2;;>qj(mbPbjTI>2Aq*-eUM(mmeq{h2|)DI&s(soj8~wWAR+f z>~Oh=(S3ou2G|jKHTYySzruT)k++vom^F;$ipx$>vc)OrFN);bK}8~a1NGgC9*=wg zl7WKWY(dQ$*Q{kfKR%ooow3*-EWwJ{<3^WxSbX9#MpT$}A)_;R@*cbZYv(kQOVs*_ zv6q8)07rv^!ExY7>K3Hd2K=@j`AmBL9h{Zo%|NnL`eyqeBf5*^BDfyRg@u5gXELr7 zmzVHxK5FGck~=QnX{in`50Y&>a;zd_*i2QI{?}zaidQS*0k^V#07qi8ub?^$Pjwt? zhrk|@*j$Exjxv_g@RjI~jb=zs;LFix5Awc@hTs92i(Zr#NA4`QrS&BG#(ME7Raep6 z364Pikc%tUBiX>L5{V%a^kQNl3o~^_+A?F{4UpHxLSrz$vkb@Enil=6^k)mWC*i$E zEV|iQ2Y!p@bg&4LwQjY7kAi)X9|g(qp4(@i2CsqX(N&3aNNV_MYpEhUck!o8Ke3W`QMDf z?NHx?o2Xj@&6;4NNZt}%M%|AN`?B{9rEkE`$o}OWLGmbA5B&x3QrLVK$wD|M1dnxL zcXNr%PKlljmd}@&ix5pWzsKV8U5M}C+tF_gzXUD={|C+|`>|_;oGA1OBAMMYcmbQ+ z!RP4P%k+Oq{44pq82OWKJw~HwSGYU5l}B>YwFSS;&eDc_xElFNIJ=2=Mlzx2{Cv~x z(O@1V%%ESIxmyeVn%FN=m>rSqL-UtJ{0Qzq=P&BkK<8*;E<~Qj9>jj3vmu`+7**wa z@|D1{X0)tOz5!U2PuxcH=Kl@v;U(aO!lf47x0fH4_jdgj-%G5>_bLzbI+2x6g(}JK z0=x}^{-?ZIEvA$gLhq1~Z*^wynfMNF_k4P5Z*$pXTzo$JlW>0?e5*NR+w%D={<_ps zt^9RLzPF#%%8Q!ryasGk@(HQs{?$NP+#_fLULALerrIy)b);7PAST~w5gvSjl(moc?dxY;GB-vmF=AKTIc*c<~tgw4n0-OOKs z&CY1n6AWI$+9_~5_&zvG%WG!|L4O^*fV@!oH;}~mbf&1bcQmam3V4*13U&}6;fu{2A@jIqF@IM6o0Df0)tbVBE zcU6B`%XNIomL+|As`P*I$5(7OkkUo36#DaGf%~7=bICY1?vE!ZcOUqiL4`=-QB!~C~ zBy0JSbL#oIB`5gu9gkTu3crT0C42ZKBzvG=2W)`knsEOwsbw{Vr~8F$=?#CEExK8-06_(%JAmv~?PtvB+n^zku%oYk^NA|A4XNL-H)R z5qTN-tDy4$E$Vf&i;i~?$wydlqkafYJfjQ3zlIN`R}ch9U-1@?PZf0jD zyeFtZW=g+>9T)%jCu|76icQw0o`g<)dYFo2K3ENWoZdF0G>+sa7uB@;K72YBC^d}T z$7bNeS-+uMFXKVC3hsffKS^!{VY497`!ypyiKGXXx1c!_-T}-*t>VauYW*&fQeYd9 zIr3Re-X?0br*B^OPwGq%k7-tuZUnl0fjvl* z8?{^YuID2`EW~CACb1p^cCnDm6La}$7?PLZuFuXhtODH$WY;hu{lr(g4@fQzPQl4h zO34k;436Zp<8<(dpuPw$6bu67Hw8V=ABZFiI?oG+>(ML%K0#@2_%rajXifu|KFW|etTHw>j zKVU5RkUR@+L|z8|D(E~wi+UaHqT?Mz@(~u?s2@TT&**~iui-=K)kJtZur#%DQtJw( zX~^F|a)(m<5LQ6qm)XIPtqVy!Ci$UgB|4WO^WAGK4&bRc| zI{;q}RtND+&>DUX3u}>N#U@eYV<9{Q8Z=$Z6h(h2_z$&+4f8S*`lj(@(h!gs3(yZL z6D^E1ypE(Km=|OoWAx29-`;>916zQM+BBy0Ir_=yyjw_SQi_N5TW}Xkj4^Boze+9Q zTu(x$KCP!BnGaS2AE!UfD2*fe349-%PF>`NQTSL3d^oEhbWt}Rbg^^~bUjG|M}s}E zvjyw`=0USKrNobZ7fC6w4TwK|V$a(|t@iYxE6Cb3#I`>i3wY1l0PaNYy!04Y1s&GD zcDy<0RtjDXT!vwcrY3eSV~6ko;r1 zgKh?yBb@_e*1~Pnb+Pdu@Equ}!6k44emji*Ym^fC{)?1SOOwM*KX4`bN8wLWis#J; zI2prt>uw2hRzX0_2d;1X!5x&6@$_CeSx(o36V*Oh&Lf|Mj5;7k=}ZuxXjX)71iCy) zPS)fo?bfF2+ei=#u^EC%tf_#k9+C%QE_)0^@)F$j*^Qkz*PTG}stM^Q-q3wOa$0ao zP$?ZM`IgsCt67+D%3af+Sjm&T!2Bk1oyMzIFTKm+XS_$%3bI=q9|W@Y15Z|^nPpLn z#J_}mw274bibUS={uPNg4tYH|n!!3jlZyNhztk(brpyx?8t1+NzJ<4A7tg7-Hsa-V~( zwS4>QDU(O`NAZK-Kwj;<$=LrHohH29^}^02a0l28{0e_+J;d@M@}i|11nx0Cl1e}`}{Cp?|fy6|Q2U1;_c?p=Tfl&+=LX(ai;Zdvj z-*z6eio|4%3|@ntJd0!olI4v368v}S4rkP_!3WUK z)3j1RH2pzH+~{2VbO4`6rz5@n07)DAiT89DBzI}ujdU_zDvq@?NL-7hu=6P%K*y_x z%^v9Nl0JC!(=P&xWnzFXoVS-3v|bp9U# z|BYIQ;03`k=pTb;2Op!AqG&e8{`XiuO=%tQBWzZIe~IP-;a)-3PH`geTW}TF9$bLs zBFsw>Ec^oQrVsBi(waz0NAi1ZeC6fApK$Ycw8TojY78AFF#Uk|VT!5-g15K0Mhhl24Jkz^B1=)K53f6vgTIr1hFNG7Z`M!AD>=X1K!v1=ffAC>U^QVIP<`1T}xmgpNYs{ay}Yha-|rIXRz0iTIHO}=g7kHlIUE&hPce(H9N z+mpHXEn~-%9+thOV4wISO5PKsZh2bF4jM|C3%@0vnUh!r65A)}Kj#zuD0NpL;iTlb z-8MJKuIGJ@&NqTVNBqy89>m0&Nn#y!r7dRMe2(S4i5)~N?}1N%PXoySnlq2zk=Uyl z?X~@E&CWYMl22gS?^Fx)N5}2i+uK50uhXmVl$`v@+9y_?tYV!A}|HxZ`lHUl-kIP^Cp)LIGN;&m;YtVPQInm-j=-c_SX9MfWfXMMq zfOyOwht6F5+>6<43SJ|;tV;AIM~f|fB&ZKEJ9Fsm z^UUw6#2UAA=hY_~mqhmFWrm_t4awfPz1wD9mK%rGs+E${eivKn&KMs>@_RRCO)ZG_ zlXdG`$y1Ts?=n>lC1+9j1#vp#-H6{@_V};J72lQ81;nObOYAGfUt(ACS2u&Kylm$M z74O~=Z{Y6pT;ygRrS3DSPmu8Wm(ORKhEF2QRwR51qq1T@tJqiAj9!pm8bn*2`0 z+L^~+M!luvZ`iI8{P=3)+EjB|&%_u5|*Qk4mKHsFYB=X#X z^4Iz7=qiF&8SfBEzXxN;ACp#Mh2^iR#xBd>$PKs2U#Ug^g|LcXtcLv6R{3p9R75mw z4<}=Pq{V#5OUClzu>tgf?}^DTL+yxOkZ+5@E5WOTTae#@m&cBim!>~$;AP?MuyYXo zO!y(>H^CQ>jG%O-#mBJl7#1qSD+|xO6E+u&?Xi*+;ZX{_s=f6J=EuTQ^uG%I@5H=M zq14WP=9K^p4-hAgzYXsIZUS#&r-1yTB(?~?7z;nbM_cSHzxa+?2jc~qg?aLu9g8+L zqWA5MK~Uo4y!=K!^J+L&>dH6qA}=!zuOq*Ck#F`!l`}6|ekoI8xQ_6s9oRDJA@k@^ zzL%c4I&-b~UnEiGh&d9QRwo6C@ISzd(U(Z-P*?Qt!+xcRzmuG~htetZr?>n~=1k%+ z%5Je?R7(7oxdF|S7RO~u+ztk3f|WCW1Fxfb-s1R#ocpelKg8cV=N+Xx_kFvE%J=Hq zU0?S)_2}69O>dI=K?QZ6Zk3{*soT7Dib_py)h0y^YudPein`RgRoxWNp8Mi)m8|lq ztm+~4n9W}eR7=&)=B~HZN9t2+yT6*OzEz9VO0_}#YH!k~5;gMMeXxRhToqSO+Z^}2 z>Z;zcJK8wgpZ}__)GW1Ftx_A+PIX9L9;lJ5va5=A?@LkXsj8>v21S`AcF)oisytx=oRZhPB4 zo2XGxORq*e2#DXPmets19T4~dCVpQuUpMq5`6Q8UzhwOp-J+f;_V16-h17FA6>sYOs|9J*PUUH&ie6z8a&xP)T+d8>(ii1!{%*S#4MQ)d_hqq8CNg zedeFOWW2{YMA;)EwqueUhPl^)JgS+y4<X5b*->u194MlM*9{`I@(D(@K>fmL*nd-l1cARfAZYSdZ9< z*qqpw*ohcN>`i=+IHYBlCe73c;yB_A;sWAw;(FpX;$Gr0;sxSOJdh^pk;fn>28p^| zhi>hI$%)~_2x25L53vxj7%_%efmn@Lvt7q#?SgfQjfgFY9f+~S-o$~#Vfdjg!I8wV z#7V>%#JR+U#HGYl#P!5@;`WZ-_wFVhARZ&0AzmV0C*CDK@)+X8AW?Vh(!4_`IWe3V z(aC#1l9-2Bh**pmL##loMyyG!OKd=F+7-uMs5P+@F^<@mIFLA;IEFZZIE^^BYnu)& zLko#ZiK~d~iSfkk#NEUL#AC!WUE4S76uLyb>(S&yO$;YS5(^Pyh}DR7yLK&5&}>R< zOYB1IMSPDqj5vxofjEOW4_U}uLR>}MK-@;$O*}+AMZ843Nqm4TY;mGVOiBzVW+vt$ z79y4)mM2z2Mp?Cq^@xp#&53P^orrP7-o*EaLy*zd2;vyx1mZN}Y~ljq65=<+wZx5G zyEW}gt;EC2gdzbn3uSe&F znf!&B=`T$7g7kVyvslFEw-Ubl+d4?_UXp*C2G)mZuue_)KlD1>f6cKXj{HY$cC2py zNt+WZ?SIZP$o&GOyC|r~{&@ZO`R|Vn2I*gbNneOXQQ7oIjWP|D=6ckCC*V2;gfJGt z3b3-QCTq+(vHol%o5mKg^=ubA!LDQA2;&jF058jH^0s^&kLUaNIeu3JL`o4UqD3W9 zSF{vy;sY^O%ofW_J&05UlO&i{%_V}q?1|y)D8dy zI)P$;YFoP#wsqNrpAQ?8aQ`XpCv2yj@~1Y&hIDfiu21(M;rFN4iP{kfw@+U_QM+!U z_6LdDdlR-ZWKPtsmZ;q&VgIroNVq=R?S$>TjS{sRCu%oM*#CTy3D@WAL2ZuJL(*qG zE>P*2Eojmj19M+WtY0GicjJA#%eO~-d+B*w7cSx33cjuB+eAlQcy_{GN7YW)E@md& zzF3EZ?GlOhSF%o`cA~RX@@ArTBCnRxiP~X_+EEGHr4yayn6`f!wfLf3yF~2~3AZmd zGEqD6`WcDZGZVFECu~=khi6oy=bEukp(UF{nX)M^z{apKz+{+ALe)f42-sD1yj?|a z)a&&Id?&!Juq(LTb#~pm>&|WhXLr~g5W1W$2Znx0zl1fNH(t1?D5`j)iYMhM@SPw% zQ{z2b=U}S`6nD$GFS!-mYHoG+Rkx;F%YEIg>o#y3x=r0CZZo%y+sTb{ySwkY1KeS5 zS+}BF$*t^Gam%|^-5PE=_ht7Lx2@aR?c#QIW8HRcH@AoTj@!!Z>GpGbxwYLl+HT-W}BCd?g;=CcX&*{1iV0il60YA;>TBUm(Qq z@q1tkQ<&fgSGb@>8j%KEkx68QFi}Vpg5;vCC<`g<#&%;!X*ac7Kq@=V?g44-_wDx~ zgFW6J4;k$#_7sS)XWBC%lRex10y5hx?bQ%zZ?-o>PJ5rd4|3T@?W2&}K4G7LJoYL3 z6y&up*cTw5eaXH8`RylIh!u7$$AV}llamRGI+0E!cz5*kpKS=D|G>BW*TtRx~ZPZxk_9L5(w@Gv~L7s;->dEVdhx8to& z$6JGr_hmZX-`2cBYhI-_HUGRuZ=)mJPDl779pP_lcF~&Mv}P}@;dp+P_cR{2xOcBI zjECXbPl2OT*p=+cIC|IX^$@^g^0JlyFPk!vgRUG5h4}gRu~+Y5(`7F7W8o}4^k+F( z4j9Plvj#ATwPWpJ2Ou$Fh{-C;fN z#e2bbybtdS8~8vz5H|9`d@yX{WB3?|=b!P?!;!r@7OX-*Wmn!}$Zvbx;I#CY?#RI*ZOC!gMyB zO(fCTb#{?d=hQhxGM!uJ7Rhy9omZsL`E`DgQWw+(MJgSoqeN;Qt)oR6T}&4f;ktw_ zA=2tnx|B$#V|0v2ugmJPB7-ik%ZrSOp#t$ft+s zAtJvXriY0F`Xl|3D5yWyAB#eIlpZAt>oIzah|**ASW!fe)8j<6o}ed)qI!~^B#P-N zdWtBnr|D^;gr1>ih?07yo+(P{*?P7pt>@~wB1X^C^F$fFKraww^+LT+l+%m#Vo_dy zt-ls8>1BGEsGwKq6{4bEsaJ|hdbM6HD(kg+t*D~E)8C1z`g{GosHQjRO`^KqtT&4q zdaK?lUe-V8AH*wqhu$Gx)jRc0QB(h>b5jp~r>C8GaUg=qNR!E^EbtI(JIdl$4rE}?AkXq-_ zc_59>r}II$E}#q0FWVM|bh?Nxf`wdBT@*6t;<`9w)FpLEh|r~VX~?9@=rS0yylj?* zvRPJLSyzT^x}k0ek-C{~2HABB-2!sxR=O4B)a`UT$fY~z4v<@S(w!iWj@7Y{SI6l% z$ftYg9*|%6)qSCW?yvhpK|N3pghG0-9t?%`P(2i)^l&{Kis%t~1Vrmk^e0eMkJh81 znEq6M3dQwj`ZFk@$LsM>Qcu(qF=|iNlcBVps;5GXp01}u8U4Bb9LnlhdKQ$^bMzc2 zufNb=z)O0*o(~oDm-CQF(%uhItpW%d6cMR)PrUq_Zeo28EWqqg4-lcQq1aGQvfV3A>Pt2@)Q@bp zP=B&*H`jBk5&~UPGp^wOR z4}FZbJ8n0UY;5QgvfVEjQ2e=!S~EW-y@TJk4*MGGS&CUG~XlBeUHrWJ@UElky*Y+X8RtQ<9lST?~yNj zkIeTyvcUJqm%c|9`X2ep_sAIRf7j3y^2ki`$h;Ty$YS3kOMH)f?R#XY?~!G`M^^YA z`NkhBD}B$b@;$TK_sqAxXV&5vK^` z!1`hsY+%>e4R)K|WxukA>7j+JAftQ;@L zLpeE7PK5Guikt#3$!T&LRFI#`&!M86C1*h;IY-Wc%JK{O1yqsq<$S0rzm#7>HTjkN z3aZP+axv79U(2uIWw}f)gIDAVxdL95E9FY4DObzYP)n|nYoNAVC)dGi()(5CI&zcT z1h31@ax>JGTjf@GL;fItfO>L=+yQUOU2+%Hmv`k|cuU@w_o0D&ARj=(fD>?_k(tfR z25+0$&Fs+F%xUI?CT4CkH#9Z#nt7p_ncvJ0&CP;lL1bvxr#)TA4-7qR`qb zZWf0&W=XRov^7hcrQsd3j9CWSnJ<|yL3^{7SqnPY_3V1k(dp`Rg-%X4ryF#3x;x#W zi__ET30+A;#FB>SMj9fHG(>mO5Ismk^dt?@i!{W$q#=5fhUh~YqAzKPexxD#lZF^T z8sa_D5bu+Q7)Tmo5NU`HNJ9)J4Kai?#8A=@!$?DXNE%`|X^4+VLyRB|@iA$Lk)$C$ zAq_E#G{k7q5MxL~d`cQ(ENO_(NJESx4KbcH#01h16G=l%A`LN_G{h9r5K~D*Od}03 zoixM@(h#4MhL}kjViswL*`y)nkcOB`8sZDm5c5bw%qI=8fHcIHq#+iPhWLs!#3IrV zi%CN)Ar0|0X^5qyA(oMbSWX&Z1!;(HNJFe74Y7(e#A?zI-;#z{LmFZ&X^3^CA=ZwFSRlR<8^tCOFE)!UVyoCDeh}Nmj^|~2&vRmyn1y?sL;ttud@&z$ z{X&5?JZA0h@%v7R%fIh^7H%~k*RB$)#kXROSS!|v_2N6RL45zb`hxa8Tg=A2&lPiV z?+e5N-1}Dol>r{%4&1xf4{z`JAo+9m`ka1{&rbP1^FH@CD;xTpSBZH4A?XCZ4c>== zFbF9Jy*Uvk0bY496{f*-tUf=7 znJ^1x!yK3kUtldd9~Quuun@k2MX(qv)30GEEQ95+0=|KjSf{RrZ($9rg>|qVNBai& z9yY=zh=MqU_TsygIM1lh9htkj=^y_0VlEA zJq>5zES!V$Z~-o2?Ry!1fh%wouEBM+ zSc})@ukkwkbzYah!Rzrid42vCZ@?S!M*MBwm^a}~c{ARex8N;#E8d#7;cfXlyd7`P zJMfOY6YtEY@dNxIKg197Bm5{o#*gz8{3JicPxCYUEI-H3^9%eUzr-)|Uxdl8@TgTx17uox}Ii%DXUSS-F4OT{;0rT9_o6uZPvVz<~M_KKgyKCxdM z5C_E}aabG?N5wI5T$~Um|L%51Nu!jp+t_35HGVes8T*X`#zEtdao9Lw95s#^$Bh%l zN#m4p+BjpJHO?95jSI#_-SI>Lpb{RaBK!WmQF0Rn=5=RYSe3UQw^AnyQwntzJ`g)a$CQdPCJy zZ>sw0E!99ZRE^Zzs^^R(%+N%z#qw1tOt1hamidEfIoa(N6 zsGh19F1=MB)mQaX{nY^Vo_b#mRD;w9YOorjhN@xeLp5A|q(-QZ)kyV;8l^_7G3rw_ zR(+<%sqt!pny4nJ$!dz4s-~&wYKHn;%~bQ%0`;X@sJ>E*)MB+neXW+NWoo%vp}tWo z)he}GeXG`}wQ8MOuf9_o)c0zm+N9#uX0=6aRom1LYP;H@epEZvF7=bzt@fzB>Swi2 z?NZ-b?uB#jBrn;|w zRS(od^+-KdPt?;O1euzpW~(`BuKGgFQ@7M@bw}M*_skwDCPEb8DtG%bIP?vF2J|So5s;)|b{o>nm%Kwb)u>eQhnZmRakp z_11UR2J3rkqqWJ3x3*b7SUapAt)12`>nCfswa40P{cP>C4p=9x)7Dw*ymisKY+bW% zShuX()*b7vbV?FaTl`;qO!u|PFJ{6|Z-QF3Z8miHK z;$>8$2Sk1G790|d#M^L$^6xRxNpynam?HA7zbxbhn}NMcb+oc1U<|_KZOYTbs0r+^nqxYg}3rMr)EJ zSd*I8q@gw8w1%TfEWit3!Y#(V|HGjqFA1Di;*~(~s=O)~{8j!cNOQC~8Up4Da|I~# zx_KS<$K_Hy+y9vioiIQD|CpVhpP&E8(0|R*|1(+I%fo-Oiu;e|)1<1oYN=YQcQHG8 zS+yeO(;AfNYGKwIK{>P@=1(tkKFgaeo|7@FJ~wCf{y${PzvjyEm?i(nkAKcR|F7lB z-*X{m&2gCB|C}?+VQu17CeP{;uPUjDb;+-ORq_yPk~gs)nL-uGRIEoH;OMQ3Blc}? zbpDoEdHaM})ef_h*h%eVc5*v~ozhNar?%7B;dWX(ot@s!U}v-=>`ZoMJByvw&Spp2 z+3g&5PCM6gbMc_(XJZ}Grndf8PG0cWtgKxfrjz_7H*dDKSX(JWZ+~u%-j7-Opmo?f zY90SATkDiM6=m!z|1xJk{%h9OsdXA1ZrA^}vUh^qZ9o1`XK#%5)fs0gFn5Qu9FUyV zWOX15JwKL%HDWCwH*3XOL1EU0wSg%14r>oZSVz_iim~48Q>efuu*uMfEyKLuly~8= z(3i*YJ}`jyAD9|g$_fXT2jW@Pz?Q%+RzI*Wu#Yth91I+0%>zdR$5|_^3Ldkzfu|~p z4OY>rBwM3Ot1|5SV9sDJ79Y$L%+Iz23kD0a?ZN0^G}{p@9xTp&^q%%$JA-9|W!bJ^ z`CxhWQ?OF765AcD8m!9p1ZxCqu)V=L!8+{c;2Xg=*uG%>V12ef_;#=vI}mIWY{QO* zjF7>OnN7`R?6}#&Y|T!ZZOvGA){Hab*mcaU6WI;St?SqW%&qr126yW%Zd(nlUc99@ z%f<)VQ|(iHkn@o@gQS#5GUGQ}gsZ zf=9Z!L?t(`Tfi;m=5dR<`Q3bO5x0~MBKdgqvP3^F(;oD-1IIpv&!2N6}OefRJ3^JpPkeOs=nMG!m*<_^5E_2A7GMCIP^T@n1pUf`{$bzzv zEX?+>z3gYUkL_m%*g#ZZzeA(G{+?ww8kYlbcI+*0X?A?q=J69 zr15^L1;Uxj!XPb1nQ%zYGO!Ggfu2>(h!LkIL}0|J51Hucs>~E?vaoin9b~1aSF^Eh zEDj=BAJzw>(oi-Oa!)#>fFbJB%&5>Z4v&}gWW`1EVfTZR=b3dds51L0HwRzk;jmn_6 z)fX~h1{?@kz3c`#F}qEN++Hq%{FsaOK|#zwN1+I2q2myZdFV70#awh2ilKTu55+Mb zU4#;tlP*I^%u84B9C=T*m*fq8@5?s7FW%LVAwge?^WwOz*CWAeqDnKUN0NFJz*@CF zUZ-Baf>?ugh7k43q<%TnucXwkkUQhE; zPYY5{qp7FGFo(}VwKE4bQyJ=YMe22B%&m8!I%d|#sI$BtRpo8{r=V)$_1S@XR0QAQ ztO4`>Z`~Nbmqq-oa^aO5$EvU@f7-G!D+Is&)t~nshy2g+M=4$k{o#4Vpz|!rHv#gE zBHskbHzBO!8)Dq@JY>X_??SR%W^2 zJl0qiT*F!^3EaerB^>V16X^x8Kj7(OC~x+#7}T=fwJXA5&2@SfrLn8H)bn3}J*Qi_0Hd*2Z`LI78ljY~f`;JO<2uI07;I;h4r~ zO|uHmjx3Y+j5ieUp5=!5cue4WAto$LJOQ@5EpHWD1H_K+%d(v=S7p42o8g zqE&#Rm7-`Bq-YhQXk}8gvM5^F6s~G7)7h36s?j`v`S9VDg{NWR1~ee{|jur zm%I5ZP!4tUaMa3^P!BIa)%z{RsO_j;$BJ=>AJN_K)w4pU>c+LZ}3=cokF=B~T+^Rh9r# zoq%1<1=0rtS@wZB%LDVYAM*L=0mv7im5}?Q2O(dGRzdEMRzn_u)+)=PE~;X1XU68k5nbdKT(w-AEl~rIgncw@)>9$)Z%Wazapr= zVyM3osJ~LExiYA^a;VFnp#Jti{Z&By?d58PDgx(S6wbRCoOf|J?-Fp{CE>hF!FiX4 z^De`kcNlF0%LUwxd$tmw+hl-)c3<|}P%&s-;?OE2xZlIw$3rE@UxjjQ2foS~Z_9U?wo8i;(8Mrxafm`Bi+zPj5;0%5S zgCWEaW{5D}GTt%XGo%?Z4DRzm~c@86@Ji|Q0Ag<&3DRJnh6lmSFK12h0D;7N+ z`1PsuO5oAi^jpBAJ3x=_2tB$J^ytpeqq{(l?g~A+8}#Vz(4%`mk3JiEbWiBfy`V>* zL;nPPxi>BV{I@^!-z%a2PGX1x|Gfstc@mlbS2X(H)8OBtC#WGX=99E{VEpty`hGZ@ z(r`9ap!_;eej_NqE0o^@#xGtl2ADf`=S!hcxc{RNL+lam-LWMiH*qa|Yteshn`3qa zdJu$GgFvexL2dIu-7=tVnNYU^P`83mw?a_2!cey&P`9E`w_;GY;!w8|P`8p$w^Bfd z;)wL;(bFl638QC#xb*Yt<(?*hHj6-;MWM}N&}K=WKZ{eC6Fw^eVv})1__FG`y^O60 zXw?*G)x6NEfhPg}!TAT-uz}1VW+*d^8NrNXMvZ62u3)ZYu3{!LQUilg2YP7v|=Q6k~$(q z(j;jj(j+~S9wGztYGp}ABx6L5G=*e_D8L+BRgx9S3Q>cZw(2m`b`s3A)rOh2dN9+L zfSI-|m}#pIGi?p-iBX5Oz{r<1~MIH-CDq`TT7UA%Z6FERxs<< z8fM+jgju%^FzeP4X5BiCWiMj~!C2Pd@nAlF2IC391Mwg{0XvK};7h@13b7+#c6#uB zemedM%*~VW-N;ey69j$)^r%LnVZ$UQeuE?l#(WMxLgMBJ@4+kZz4%d*5=j|v1S9Mr zso?j(teA7}7J!umAPCS^2%-wCVKJfxY+*T~2{gAFF#?v5j2Hv`uSZPA_EFH6Al4iK z0Sym^V}h6%CXFd$8l;)yr$6Dz&;R4+FaMKY_@C^X|B37y3`B<%G?*gH7y*&wjK7p! zNaIHJJikuJ1*39Lu6;h^_AgJYjh|`*ePCwTg7ICWv6flDuYK8d!O%CzTX4T^2<`!= zVQkRmjJaZ-m^bEw1p*Hk4SeZJ?la==5%;<9L;}5hO(uUN?o;H6#C_)cU1EPjHryxD zUy<`4iTiYVA^}_ab zL|>ESH>C76eU@-+#IT3|?2Y|kZ_E^t1`+1BWcCM|{w@8u6FOz(rsy zA{9=gNCoroX{Onw4fCVCSW$|U7ied{1}?9Dh2&KR#NN0>+gHhe?`E z<`KqbyR(D|L2iXAO!M-K2@Q)3iH(Y62@ni!Bd;*8TToy`RAeAaj*#KD(1b-D!vZ)_ zF;T&>3hXFObQH%gHVk}1nNZ|jCkabUydD^&;2std33^pqQn6BHC*RipdY?+j+s@rREXC#`BZ+}dvR6sNVu4K>u+^_4{lwOX3D+p zz34D`@pN0kN0^qc$TBkTZ#T_0+zDCfHQn%OL>6kECABW6hne7zanz(>WFxlajuNx) ziqYN%W9uuLA9Avq7cMac!@u=Z$p@#Kev`FmQUKGY{)r;mt1;z!$#^?bh z149I62rST-Fwrq!>F5(ILKnP=nEPeSC`xuB90>a_bplJ9{`o5s5)!`m6+xVT*>~(W z%Z|jg9A>xq%=9f+S;nPSCSkSVS{++PLQ@aUX_Uh^dA{Fyvn^NMp+9wFVwiUC@thfb z(ZRXdM36@1*|r0}F%v67n!;W)b05%{O@le{8nsGS49<>jm|1zS_G6RkljrI#C!b2b zl?n_mx-afs_44vSaz#de%{3982jLO1Zh^ORwrl!?Es}pm*(vpFf6%^kY0+${>t(Jv zA7^L34anLpg4YzTwkMCa1Xt3k4wiKXynpeerLOkrx;tk~Du0f-wlwg`fa1JG({5NP zy-s#3*J5jIz>77Pq*z|qFTJXxd{5zG&=8?jUgLEnK5V=8GLTbLsDDhK;qtT<@}5Og%`uiW;`lokNVpd*B`Zd zf7iS@)niqE(H?EKa=x3qzTxXnd7ito0uq)Jg*1ayj&z%SYrE>jJM#r~&sAr>+{CuC zr5swOK<|6?y!q(sy3UIxn?@A(nb9Ir#jmtIN+X>#SaV4Abo<$hnQy&maYt8k?|!|A2% zpk4FOS74<)`Ry$?n`qiI^O5+GI<4v!!#XD6F$Puust5p8Mb>HTe+#U}E_1aAl?bd7 zLe-oJPz8XBu$ur?rhg5pzT0!`_Yj==J@kqhU8%e4Vph7=ij@x*h%R{?>i>fJGu!jD zkG)Q4=Q}&WEw2O%QU`=OJc{D>niPAljvGAt+vHAKRoVY9W~eCxff8|zkZA_UaW%<7CPsSv7* zFjNkCuYE^V=g9mTIm#pUr0E5e_=K0L-4t8Ni0+xG#kcKeQEe0rE8>hC4%bol-94;z z>x5?b$Ge8&?KALmT|AeawyOjv&~;S~`m(KrmicrU-zl@M+cH(iYvlvmv%%Ld7ua~d zcHphKhwuC4%`c`U_YQTum03leEwD)9^_GjSd$PeYq8tP0RrUqF4Ai6`da=GmFJA}? zG`_8B8QX@m15rsa63_)pk`Vu@k#Ag8EFD5?Y#poozK-3Zq5wz$-Gv2*1^C4VDOkkC zhDLG1ViO@s5rl~WOJAQg#XujRl>X)+^E<80|h~>7@J%2f1VDMayVAs4(;Oi_im(v$D#M zC(c@uZ_9i8qw3vVap{-$#aOMrnSAHf@gbwK^FG$UR#lqan-rQWwWpjDdVLH68z#)@F|mP?0w_ z#f4YrWvaRNFWYB7WOLcr)TFRJ!KYljFzbTgCQsAm1AM-u>tCQ|0hp1w1e3e;gt>tb zg&+Yo0eik12hm~R#EqKJG(w1n@AK`1C`zWlj)6NEZ^O8~e7wqXx~{f9`~HrF(<)d| zKbaou)FC9t-z0*OaXA{|j>Lgm5H@1*6}T}Dq%1V|RL|{G75<=kpXQ$J-CIVujDg!s z!j`ZuVi#GY&G_r!Hh!4{Oq+{J5ZF8>0Gl0QLs(4!Hj{q`*tiRZJ=W_Vqc03ayr)cG zt!7j8G|Ie2|4{f-hF)aF%;BfLanBs4>D*+4d+iI4by%g!?JHb%Bq`26V5aAAw4}nb z;6Zd_L;c&tLo+$U)1O$ZZo7|*hg~QyP|$f#cRB5OQRjjEwPVqbD)>uC<(~H%*3a@9 z%C;>L+9po6=8}kf zskbsO+;4=mD~+^ zd$hMi`$Vgj03&GQ&O5)AycbgA3o_aMa+$n+mv)@v8%$+nI!7>soy=Bf*cEWDzFOSYJP=*#wbg6o_N*dlJJQ_Y z%cUW-*m9$1I(p)*4>`s{ucK;ALsH(k)n*xp1<5hicL{U{zK*(N({Ww=apGxm{q+&; zyYlM`570)0)y*q=-`(H4+NP0rp>5DYbEj&{0jFnm@rj+Z$$SwqNi6vuhDTRl@kpPo zKxN>LQ5P}Y6-^YyWj)yz>R~P0Hf5jB>daR>$nR6|qU2y&=o&m+r!jsJBAZh=B)0sG z*cz21>6gPRY*~7Fzdl%Eb`x3UZ+rDp`uPTl_Y6)}bE#PsW*$BomY>rjP$5un>_WZK zVn(F!@B;jP{sq6qLMKD~miZ^}n=l4pB|vOL17Zpnzge(qKya)7T=@GV^xj>(xaRI1 zyRDil7U@dfKi>1;%uZKjm&!|B5>6`2!K-_&I#k9I3W860fAPo`ow;4wa_hkzK7`tB zWKsX};{zGI%wYz3$BT@1`3nXr>vj#j4w2FRu>4WF?2|`MrNzz4?rmA`tuOOkSx|MQ z+LB!I?x)4uLT*m_)yBO#?MmMy8(sASY0k6V@LrPkNciT>MC7_x-o&o=t8V1h^(*GC zdV5Xy74@)tgj>D!=G}IPy=}0dx<+tCZtr!TWc!kLYxfA+itwfEUi)nJ(oblftP3?2 z5g=@y9qv}PX*{jtvAarcsRb*cJ^${sHQS2)utT!^H6MoaYtc(evph!MQCdzZ(7&Mf zelR0@{uO$EH!%DPy#*$sH)uhKT9=%IVYj^eR-xa-m@qsB0 z9d8nw_DL-B*LYr%uQ8b?LCXKUnOuZ?$_x5A?Z(UOy1sVmh)G^>03ToZ1VQ5^4AA6YE?Q`0`%7eY}V z*Xu8?{dCv0HBx2R^Go32$O%1(@eTS;s0_vA~P&zDhT@GxoE?>I8t|%u? z>ekkE!f{G^`W4j3qIsFBO-0YwwkhnjWl$x+k|v7NcmoI5#t-f;jk_J(-QBIRrg3ZB zp*gs_ySux)d*lA%-n}zB6K{53OvJ|fwHe=!tgouR%&4r$-1MY9`XT7xc-UdYPD2~i zS<6v=Z?vBv(2}BwpBKe;`-7LLAd+wE3~O>ai=pwj-SI?H9kJz?)HfVs8kvBDhpB16xf1J8hFUtkN8;wq*VG?2XH|Kf>P#?N)g!BEzS*ce9xWx z(;{%MD@6XlfoQSqU$NWtioJPKY*rY%VZXjXet{4FNietm$yOBLNg6K2UK||YE_6)` zkfv9c1wGFV;Ah|xVfEfbqROj24VL^?fmk1Dxu38YVrw^OFv|g{j(Z1=%G!@~(<1vU z8Thv=h<7dmBUKaF?d-<1Hl$*#r7T)%R{-~rtO6buHE$e z*SmAF&N?pG;2g9y3rJM0)QHk`t*cJHM~q-3KK~AG1DfgcGSr_o$4hOQ+*=GeJi}7H zO3&UGS01ofa7;|NE$$;{PjYhKum>OBF8bb;U&2-)i6sAxG#Gyf%azw&wsiTB({MRE zm|&Psn7~%f;PM#sNH_Oew_Q~r7BJq|pfUaZyU_7C^|VuTSl%Ym=WaFxy@&Qa>~Ew) zOgY*T;rlWT6V+_ixwlnoVB{hP%DE;XpQ3yPH*5kmi1}p8t-nvE$8lOLSUv3}Rvgm6 zZd{&u;Q3d-m~8&%$5$BGEgrw%UgKVQc1-A>X2#s&Tb`FB$TI?qD$+h*^nw7=)D#g; z>AbVg9i4$zmErx?GLEQ(FDgH~&_f)n~fESYe6m-ODADPa4VHx|Op^P_X9JwB>2ULx8XT z;Xw;x3j;=C>u>QDk%%vU4b~-@lTi@O>`h%dxTcaSdbCWWY{?p^jDBqs5%OU|a| z0%Vr1u8zD+OdcK{j2>)^4$c-#EId3sOw6oItgH;qrsfPTUiPj=o(%Rb82_0VqltqZlc$j*6AL3V(?5im{&Dj^ zDE%wD|G@mOv_V!DmaZ=U`v}heJoC>$o_7Db!7Fd%Y-46BsOs!y#?SQsqW_DGNdJGZ z{~P4LW&iiN{#*8cpX^^3I5lUfagC<0tqWy zS2JfO30osqGchw02UD|u8v$(W?Ei5BcxL*>kJ$$?e-(fH5u9>D)*FJ0f$;4BSaU2| z@DA}a6i|XY_8ZpUz$YZ%8oL2z(dckemksrCAb0v=xR+~fi889(s-c$oPD2NpudiSs zFf7gb%!%s9lAhVm>F_Zt+*~@>Ie4wXUJo2X3BH;E^?M6X#9ocE?#7p1?3~wGCohge z0^VuzJ>hIN*l4;t-L#ZaXl$^p77dQWkktu$7amChB=$EXR+UFYIF$uMI^RIjJ^KTC zzLq5TKMSI|j`3L;FJ-l<#BHvVzE3Q}b#@%&^X%L&`)AhO>u)Zo-*jEXR+6e$WX z(%y8k70ipU;+)sxiOI_TiMyG)at;_3K{@iv;2OZ7@Y4vHE*G>ANK_}UaTt!==G^Gi*wA%cKo*F9NI^P zgo0$+5&z2)aWMaf68+npCgoruWhMpvZ%W3)%FW61ulli&vhZ+lvvB_B8lL}v_e@k< zec-v8mm3+UV6#dvrNWz)BK@r-5{I0xL`G>wiU5Owkq#1-{CvjPFb8F%pL)Y zHMWX$T50Fx=COix-b$Cc-!{d6g^*h=^m=js`FinrK=HW#=%wH_b(_g*F;2P{#e$<> zZ!6<;@KobadBznD^w;ds?2U+L8BpVj^0fz=7{K5~@~E;Nj)N5?uEI^v_fqiK2nls` zK`%!~{)TeTcOrxA2GLopEzZJoVYhgE-fVkZI)mzPgO==CLTm>wuefyYj?QNGn^PqI z*9<0aO`g`id*G0QP_!RhX*J`|xZiUI)#%!LG9EhmH0AkBTKijMj~HG~io&r6of$3Y z$&B>-{ua>3JzxJwWP5E7wmJIyEJ=Wy(UMaG);XH8vgEz9+Jw9lf<6#E>@)P8{vG?K zzW+LIP;V^1)Z5R;vJEvj3!f=akT;g>NmFlweLm@PqeW ztUUklsxInENR@HkQaVgfCsAX@enNK*^DnB$JGH^JR?D=M;T_zSEs?@Mck$vroXRo353sD_v%1nB*ZZl~06Ri9ob4RbfG$5K1lKDZhR*pB$ z`MGua>2K3}bnnzH`kjp#4fpzrSmoceH|I0F|LeskQ@n&Y**oRWM{!gc%)a`}PPId` zRY!R`Su-u$uLP5Wb@-f-42EaRs1JXZE~BqbK{lRRaAU&JEak`?_{%HS(cJUfdP1eK za)@2612!6Ye|wMWgh=u}h$zqn?jVoCuUc!g-PNb!tf?$3mu%;3=QGO?EYmp_(u31Q z)BDn^*bQttjZm=%cBcge__JSd6V8HYQi>AvQVjDQ=JO zCn)YTw8t>*%Rb3;MmTJz+)TVV`(bs(T^;&7*S(2ab^NfJz%gN z&caD<^VUkLg^b*46^C?l+(i_ry~q4Ewul9UbIt{9KdC=IEvP4eat-MToerMqB_0Ql zsa~JUg<5Q9=5kdPC8(-u>WPYJ{8qbZW|)Jq1UlLvU3T;OF2{L1a!F(ob!OM$?e&j$ zXV$s7mnV>blS1f*IY$Or6kLZwnKJhn@Fr=|C+Or}*sj%Kz1ffK$|fK;H#Ar9IJo5Q ziC5Ucw>kasDcx^A(?>*JXyMLdY2W=yinG=rrm6o3rBna>w()lLuk|s*KqtP#wWFpY zvW=ZLw~06vB`iZbrPFO>hp_$?1443T`W6Ue5cRP-UPxvzL#Wb4xM^Z04P7~>vQpHS$Zu~brB#%6(9X(Txx@;BZy44)D#sQ0YL8?!JvNXz=NpeWrP&{g?m9(WL0670KOjSe9wkq@Fr z0ekcFQ|eW@CQ!UjH{>;QTsjsm6aRF8_?cc?>jdYUk;$3}Zy zMAK(LAmM>97_x4?)D9sTQFsU0lrXsfy9h z!{-Gn%N=oRBAnfD=ayrFW5j;N+0b?t14Uuf8C+!)ES0nX{|Q%u4$GZ3m3D^;C#$V0JI%;aQHg zK(Kz+p9j{&V=BX+V}iGsO64T!s&Ai|VyY;w@LP}ZsFN)#6-CsDI31d=zZcfJ-_sv_ zGb$r1@1H^+(=nGq?#xzLUq~r}-AH5fk7+ zr1mU$BOtiPg!?D?WPY+Y$s~}z*!u9W9>4*Xb@0*9P;(nSyX@ltYFe`etezT*aZdW_ zt-{O`&?%waE^ikO!m*%Y7h~I@SnUzmRNI<`7PAWC1`?Ca6D#GhuS?KNvRn7B8$$J6 zaDBsESH&zJ!A7glSHjevd>|z_B8agn5_CJ+6>i~RQ0{EM-t1RrF3=;Rfif{kS}=7Y zj|^Q<`i+bo)jksn9`t4cSC~a7X`Z?!r>~o)1(7Rf2vQ>_=rEY}GRUW|SR+c@NrpaQ zt*#r`O6#TP7KXr)OzMHvyX!85*(4G-$rG)i#o)#F1~jjI5JG561?gIW4i;FQ9Nb#{ zfBFRQlnCn!qaC_;6fY*KpAbz=^0>*ztw~;ot-ogLeD#pmR`Xfv=xhKAfVv2CJYBvb zCA5$X^_p`qP~-oct9w1bRjk+UJ50vTyPrp)(U-8{Ldt7`xx$YMCS%`pKj@Vt+kJuw zL(1nih`7yPrWj}e*(MqX0nQ4zB_rHGSvBgc*oF$v7MkS)fTV zAOf6B-lYd(OR*S4c!9=~jAH=uAa)rRod`JKX+bLGfE@5NKlR&yE6}>2I1a2GVFi*) zA|n+~0wjS{rIZ;506;2P7U_s^P$p134S<=C%QV0Z9F$R}6%PjtfB@1g5)m_?rvjQp z<3xak6bmQ<9fX`>oC<&iAtxD!0fGu}Da1PgULfQ|;{ZSl=q?4E1K3q;?X>)FJ@Dc93VjR5F=#gcxugL?MOFB%TSV0rgAm#PjBCj?)++5 zqXaS#Vi^D%I1Wn95BuFq6D*9_0pJDJgDmrv^0z_EYS)ZF-h$)byEwoY87HxboPwt| zfPca+HPA0{7arJ|vdahTOxh&?b|&xA0a0b0q#~FKp2`6Jal3y2{>i(Fpf}|Rru-+} z2qCGPGyr`5QwJbN<|Z6KB6|}DAd$J@1NzYoz=PVE27Ey0DZ6^W&A44V;AZ@;JaF^( zt{YH4VOI^PAGgZ|YNsEN1+~)*Ac4*kcD;bv3As>)%R&`e{l4=*!ln1;FA4z zC8WFQ-`xJ`==Hht_oMINJ#_39E#;Af@&Dk)|IBD@=Wk=*fnDg>8fr=t5u*d2?xuTl z`-P*|+KzbJukH$-ME=nrJ{Ou5Sl%4xqu}_^AWr2=U2t@+DUv1h!6IgsXnl;O9gP*c zr94f^m-=)|tQi?v9pRP(u?bUMY#DrLZJGLCmMm&oV)eg|&y|c3j_JX$Vz=Rk=o2WE z*g=O%mEpy4mYmAa$^tX=;I#S57-zPyLd*q>g|BLu^5p3<0Mb&jQi@ViTIzHW_B2b3 z88I+h_-Gi_uk}6Qz3{={bwM?Gi z>(}QnP{|p9jH%)FDB0ktgT_0rcqQ8WX?)yS;G>8 zQe<>-!K341RNybPY#4Z9cezhMQazeZ!hFiv-^#g!)W$};dSY2SwCzF8U0;bPc}2{G zR4%W?{K;R!kB5|Wv5rHPbSaO0Mtvpk7-qOsA2<#=$#~^l!$vzPUg+>XMO=R$Pl@@1 zY5nupaS~rMo&8B)qK+Yw-m{NYSp7uqSY{-}NI*$j%9l-IB)^P{0yohH6kt0f>vN*6 zFgirmsSMr_i~V|mH~{!5lAC(+hZ9UX(W((EA?AU;A?*r3b0NkTW}i1{U!ZUQtu<}bo~$*_l5YlOe%pK0j=VL- zk}gS4wnJCcl_N<{+?8?$OH3z>u_!$QxFq6=H&Y;%@>P$}nInJ^vBf-yk)oA!KOKoT z=eYeh9mFcYd58J%C`4EEJ3%<7((V2HB_Y`Dn+B#O1BZd=|M-qzEU~eYGjr?CC`+s1 zg)iD7Sqz2gkzv>vS@N#fGf>uCIhMrHwu~G(qVr-L1mWhG9A6hOC&<#J6_#d(&A-Z1 z7ul4Y;d?7_%&_BMs(LF0c$fT-ABo2E{s;K2$g_93ta){!PV zpOgNWN4@{mOvS=CytcSb4vY+T1=s%;6)QoDi+zzR5L78x4q>^ZW9IVdgLX!PG6hJ=L8S0d(CqVzs07}kfisaQKbzJgy=|i7rizv9rU0%$E~O7%+bS&_Fa2OY*cYy8CY`Cj z?WTI$UNgK~w?EyoEl5@cV?VN?vti%#d~RNlui38?&C-sfW$P?r&03BS#t^6WzVlt< zp2tG9DL;G}b??E3S`8q*uJ)=p`gY4Z6?Ax?opp$kt$r&p1>ODL?c3eaEzrGj=$GBr z?E&TSXX0X;=&(+pNq7s<7s-+BPX72z;;wR4&I`xW|xM zlp|Zqjq4dW|HRFD!D>cFg|pV~)$Y^o^u>ih>cq$u-2<}E;qKDKB*+Vyqfsn64x#e> z3OcVF89_rzjb)ivnJbxSGx0w>)$I*D-RVW_4%VogHj*$IXzX<5X&I|+50}>N)G0sT z&oU|=X3YXA0}Co-p(2kM5i^4!8EH~+Qnz@Sn4A6pnTr~L)0)hD(@IJtscK3%sVmwz zsme+Oshipa#lT`zInnnLShc|KHfn!r|L`l#XcMREG6R_r9>QVG0@-xNpfC{!VF#OH zkfIo9P!hYnk}VbQsI1S8ArdfHFb)q*;F{krp)VcQwGUBSA6q$;8(|cG#+yYRi6`tm z$3MC3RYff=?`}q^yg6y{6f`b#nfQ~ux|MUTl4LA&B@Qf`w6ox+Tr-#(t68NYMTWzp zqQ3I745sK?yEtWx?SW+Y87B$h3Aeb}D=p3)RY|=uCQX`2PFd zxdohML#1IUjAc}V4#DDgsYYoaHETAXahX5U{43>86T#vIelA^*1#*2InQZp(R#C=) z^#kBQ=O$L48{yTFom$e$irIyPx-vGqLK^XY3fvs+Kv`EiXK@$%FjT`_*&25jxGDbkMHe80^Ysrs(}R*rn6^-x7s3YXqMXcf#}`E;-TIfwb_fwnCq)WC8>88o9e z8eA^j0>MqfjkXMviDV1I32_$a65!UYZHQ8huL)ZYqYg0^Xx0rfM5xBqgrSF-gqwuI zhPVy%>ee+xorYnDstbhsL!1gb4s#lS*X{ZTyBM-G(5hRN6haj;={u|vsvIO0bV5LQ zciMM6W=LGLDCj|`g6{}Q$N)%_fSCXi8W;&k3kdQ+^lnE(TqOu(*bs=IK;iF#zu}Q# z;2>JQ`~M;N4Q&eT8%R%zISery$o>ay8yXY{=tlAkFeOEhf?59#^%bojvgSMTHdN+! z_OGzq5PXKvWRP@*kmCUeVGvOPkkin--}zdRs_?%ZtCXhUh3B9HroDrO?j=c{jVkzAOvLqkpt}yAqb5M(FHFED+nnF zCkQ17;|KqS{RH7j;)%A5){fK;-Hy@@+m6r<*^b%{*N)f@^#osXLrX?&f#3lSC^d;;i z(8tm8C*f<3$*0Tzn#_RAge0_p7{cpz zf^+;o>i&C7!J*BgpH_iCTzclzOMvo0f&H?FPc$6FIGYv-6_blX}3 z&rYk&1Y{P2Z*2mi&vnPgz0TjNc(mV?j9##brNLGCM6hm2?H47O}-gttFn+y0WA zG7KG5_D(IF!lM~C5yiw&CDbBD;H2i;#^|0E_ae5$yNS(JEU{9&Ukpa=c>ETCNu+M}`74@jR! zng}{J>qCfZMil%lc!+*biS+6}zRE`1WuA1?+#+dek9hQpcjhJbj?*2(-;TZFwU#(x*>`RqHaaGi4*R;~m1rjPJ%p?oqWLtp>i24ad}u zzTdq@k~tx^c1Y7_`NPJnsP+nUk!wG;caG2qPq%N?h(kT$@)Va`WauN&aEY`=^GWDK z?4=y(%v77=DALiZZ&p>qwSqLtqHgy>Fa+hO&7&1`?J0Sa-vXk}@ZN{Z0jJ#xMMxGUE<$;f)7So?)z$#I(Vyp|qQ)p~DVA7|Yk zTj;>OqE+yPwoCm6x(T}&4}IDI8!w|fWrQGx9^+}53E6I=%G(}=7;~Cg9n?duP!FcX z5vG89hG)$#<>XJCDm0Z!^{z4qP@}GGB4f9sY_UfkS1#L-a7TWvD^`wbwrNqI=G)dzpC@k1~) zwffiuG$sI>K#&rB^@E0!jxM>VYI!vkCqba~Y8#I-EsF>NwgFS*HG(#zUr~m@$NiZ= zQbHA{;P${`ybO0?>0o3!J7;I4M4PL|e_{D2&D?gx0OFK@i=(kcmP7x3jADpJ?42t% z1!{$1CWotUUc+&G4ank3#+1Bvq1d!c8IlA;8PcB;9A6P$t~>rg|{fGuv} z`eKpA=C@a-p-{g5@X!Klv5?#v%^SUF$tiItug~dqnp~J0L{OD3=;ZZGn$eTL#BUxO z8R2Sf)?9Y^@{qjd@8uaXwzfosm-Y2PE-Getc!H+oY32Ti-|h1FZr!zm94|w$yq2zJ z6r37b@j#7Lcx_qZ3?3K_ckewqrr{f3E1{s>d-XFFP`It$6ab0;lBcu$et z=J8I8+2)lk>giDZ#l-5lRwH|;>s|7;T7g+t@<$E@w|B0-?N8*t8u+2-3$OI=-Nw>) z)a~c1japjV-R?t=w0NuvUO|M^QWM@4Bi855>Yl~p9NN*mMEbn<{HFC1mJR6B2>|>0 z^m>!Lb!Caai?|2w5-mi7lXYb0;WNqz?xIKE^ZJM$+RnlX5&bNx@$5n@7q0#jo;udj z`{NUk9qlw+UE4deEG}gjV$rI5MegS(HjZ!?FNlOj@Vvk>9vo_pImeu&KyzQ1G82VHQv4tMK1$ue6wIc4JLO_-o zY-)AOOwC-UUE4@DtzSQJoQxmJ&(n}EC$25#Ei74WOFuam{4-h;>`oOLOFq{6x&FAo z-v~QhtlvplpH{Cc`!pk5nNVe8;j5q69`V?FUdkt`@t_7-vx~ zEZ$)==R#R`Kb|acdnDoXHD{J#(t$^?tYNGCj`boU4*s*?E;XMa8Uaoi3snUBaRaH59pC$yM=4cf7KFm z#58$L6~CJxdof4%tqbea%0x52Ax0m2V{ET^${UE>2%Nh0ORUqpAvshgeNs*wc&O+m zkc!!ATEg_@*gBe-D+@6byjvR)Idma^C}?_J5u%b`~-U6N(& zTG&tNnKc-rr*va{fR|O`bOTh#V`XW_&c*oZOV1OjjJI%;IlqclaLNrnE>M5Osgiip zwH-AHu1PQk4sl70jb=6{3oysU~5Q-M~qxnR(nhhRf~98 zlD~KsI29IIT&w)bnS&iWm?z+l4WD`2*p_p9bv8!M@>R%${)pHl&WQiL9nGnk$4mE2 zfGP^+hPZc6aF!lgz0BKQ*5xk)NN6H!6Cp4DT8^oVA;1JL)O8|nQdc|0vf=QYfwJ66 zCRl)d=I zT=v)6l1!HITArU{-u4#3v69xmMz=fnCOy#;HM5xx`3OmT8)r_!W97p+X|ta3>*z*K zWZct}CTj@!7z9xhGWW8th^DC-e^xEtL{1=N-#v+Qdek2*$7g%Emi3rUTRJ86zM zy=Qm&(j%l@8WdVxN?#H<#Dpn0mr$=rWCdmQFs>#U)$uGChOGQ!$Zdrg@-7(i_Vvhd z-e2WV|4hTNz+@^;wP^YhOzQ=X$fCqiO?_Eot-smzRVx4O_#}3%5TR$^*=kAyS|;dB z#a#mKCY6UzC|=c+))Q1z!kkV2Le805;MwBiRaOR=)KfD~Vw#Oh7fX#^Q}8@p=YR8p z-s7%>oXLK|bx3q7$IQVUm-fON4KyNK6oW>w}n{yrAR(v z?U=BTlwRH$M^)yK|Buzae@Lbnr1Pj6Evv4`PB55kgP z>wWqoCywIs%gG|$qXTdyi{(9}K-M8ODM{bQ_qLY6!kl)^{<*+zvEIjTwdQ@eudZMXO+L?^sm5e`lEferrSZnZb)Rp4dr>4Sn|MP{ryZ?%(0r}-D&b%nT|pgFBnIb zbTN*iH-Vxz!L&*9IZb+(O*Q@rMC+2jQ&}xr)zmG2%c#*(Fr*fa9rpgT7Jt=G7vDG} zu5lahe;;I186Bn&j#DJF1#@}I=hOpct85w^Q9ojV5^?^-<6=ubac#LlnYx3_`BQI4k+nd~43UX77$?m*o^61_B0_rd7quVe zEfuQNdSbEkxJpn$5gfH*)&aj;^6mWgez-pmc9L=JgUyjvY`=P;RcJ&>V?@d3XX}^V zYLnXyUp{lBD-+e`0c~p|*oZz#fa`&5rZkcG1q1wtkPJPBU70FEIxE zjB{4!>t4HH%b0uaJ791Fd4fyf=4}%Z*9X1&phr`pLx-bPSDbiBqh*e>;Y~sYwVJ(` zvEMCQib)#(fMu5DgeJA9CQI9Dj_uXe6VpQ{zhKPnWK&t&QD^H>C)z~8jHN5dqEU(2 zSfi*P_Suq({lSr3IFP$an(Sa#koaba{^D)AtpGX2U)v3k;y;qI(&6r zhmhYST2L%nP${}FO+>3k6uRsT)FJ1|%x{vwkTw8QDVv~r-fTiJ`alYQ572?)CJZcE zw$^>kMpn`}8%_|sKUR%_x3vsQr^}|YDnyriNi@aCi_TYOO_Qz)dzFpSv;h!^d(b@z zz4Ae&kJEAuHC#E zYA7TSI~IWuvZJBVe{a@{90`+yuBziEJ*k0VY12p9{ZG|G?tzwq&1@PipJY10%h?-8 zS!LTzt6IbU3x~hIcr>5(uDrzhx3CYD#Kb0&oAk$=j1Z0M@BO zADNd>W*hmU!lC!25zDrR{`L=`m0l9eZIj0xnMcE`T%QW2;dsJRkj^}*3dm=%Z|M7v zxGd6ywDY>NcFapL4UoiDp$kq5v}(y!h$@AznBZkbL2-6`I!K$eY83}c74)=k` z8m@*&cd#7H`8PIJ5eW&2TJjYN4q`9%aD068)F=-7CiNlW{fbW4VWQgzbD|WISxg@* zX=Zb-YtyLTHar5wl~TRECw)|9+2n?g8Fz1(mjOvfci4MFQ`Z-s`X(sNHLU#`n4PU#Z+sYF2@F&s+1+26jJku|g&E^UwYdPjOgf zCwmsp<_ReEjhp5#PduFiU)-V>u7pEM4GaCh`+m{_6H6%45aa*GCx+&4)`~!M9NC(`P)koML(QOAi!!%`xhMmz#(M$>o$Ex?jpvu&>>e5N#z;tvEYo*>7xHoj0u@1WAsEXkRyN{QK zrq;3)j)|`Jw$*ZYNeLWH#~U@b6#ql;ywJv6i@mUEahFNokE#{qz+kEJcpG#UsP}e&PEz6u&cDE5zYm_oOkB0e3^wN-uF{l9MlY= zrAH~fW-tD+bCp;XBDyaM+#UtPWVa0qnCwP5LwORu+Z5E}O2 zBuZiqsx1NnpsS{^`_7N@Rq7+W3bNAVcEIHlM>ZFD&Sj&xb@TR{0GlyAS1fqF)WLe8B@L$SVbQiZNUF<6@E9OgGv@`aZlEbkRgVOt)it zY{>|g_(YERbm7|h^IHO?S>(qVfwP+;a)DHtS@M>4?70oAzh-BC_0Hb0_c+{@s%n<0 zj+Fib7PbX4>Xe9yGw3?D)-v#(Hh6x;J#BzO-p~97#koj0Y^HDARHE!q3MOj1T-*A|Mf8(X6fPp;||Os-YIXlZLk+eSm^p#4-IV|5!R z2Wgp!`t*gsO$OGDpbt<4ldH!x`tsBkCKmPhHhC>NSqR`j#kz*0ocMokim{s}@ruR?YLrmvT((m4{r`NIWPH_SFmZ zyc*n?Qj6jhQ+=hCHEY>RLDqjIh+c?(29%mhwx5L*+`uBREjx0C4wbT`B5$r@P1v}B zx8lP5{t~c1GOvuZfDu9s=A)xNHU{t_C(gfYf5O)betOwcKME8^YYpm-5~k=rtYc)F z$=*#LP%8Hbd#B7d24RH(>dS7CVjPINg&NM1Mb&DT&+|RJ0-DsE8hD9hV!uE0l4<>k zFI#|xYF#CaC6slO`b*kr%uL&D7i14l5($8vg zohX|*u#T_RlP1VgQuS|i#~8T}=!v4L`$8Q&LjRV+08xud*tRhW`YmH4oYNvuT4eCM zMM6{m44;OUjZZ!3(%*?^z|@;ItI_$?VO=5gV(!LpV%TmBzv|1f01--;mgn4PMC(~s z<4p+sQZiD_sim8lJZpS$+x}cf8YMben6aS$fz(30%v6$1X&bFT8Kd5fJ^LQVdP~94 zXd^@u53w||Dr1|On%A&h)t4bUO>%+^q4`<&xzp2pc2yjk42`qf`{b!E`XoZFX)Y(_ z$v?3NTW$NN$L*K1xn*S0dMbGn7v-BNV~MT2*de8>N}VJyZI@%!tV_%~j}1$4wI}Qa zw99ONQ>+Cslg$)0r6p$S0TWWn4Mx3PcuD-K&EwSF5zfp_>@~|vvJ2EG?Z0I>Q1a*p zHtM(Va46M4_ssT(Za{}!ZT!(bSY&K^E7jnpz z*{f>YY%cE?C)xfBlVi#%o0Okv<Yk|j_73^h&O=wd0} zTe*{Cn(E@n1QjQ?1{6XMez_#+L1VqVMc7Ep!7QpPca|= zu1KQKGLS*jY0oKIe+Q@C$D|A1H=L6T!E0O@UARbwPe99zF}R1*(G_|Bz5U=v&(l8j zHi0HGAw4-C z?-7^0UGO1y`RV&O5NJ5mPQJkr5B_jZ=UwBfpopB>^7_*cVR5d+t(G~nQ%&H4yn|0U zCC;YLz9LTDh^}52^p4wb;=t!m9{P9rmh%U{ydX>i+1Cq90ok7Qd70#x0=r0;+g6v3 zPP{!KHnW+03FCo6kxJ})==U#6{sk0_`5d~XXeEe|hs|JqLT?K%3-P&SGF=J*me5JP z&T6ogi*kzPg>Wn%#j&^0l7K^Toy>5>u~t0p@+?u>BJE9~Oa17xMKhlf@Q^!5+W+?S z;A1pq_H>dJzBps^=VCB=xzS~c?dTV>V#KF)<<@RN4A#EUoA06;gnoKiO(Z>!!Irt z1}Q%;@Icnoc<6Z+KsMr?TP7-8{-tJ_Vz{Rkciy+Rz zD=J(n5u{yx{dyqpme-WWmDQEw zgU~GO@WOdlXo6CA&Zbm9br%Ay+o%^oF0W^ezo+rzR7>E*-sl-t;ADmHM9Xx)H|EYa zuON#EWE@h>tq0l0IJeeB*7Q(!EVTrZ^mb}>F*aIL%FAhQJJ9ieQx~8xW5IP zw!<9L&`{2>ciM3~b0eOkzjQiGUp{%I$FbacseZ}=rGr*tyTJe(P#Fe{#H6xe$N7n< zI$}1XLvLb@Rg+euc$?U&SXb>|SFMQIF0N6##x6v#6O4F={Vscy+eC9`m25Dq!yj4a ztsHKKy+5GhZ{#o&Fh{>TZZY&_{0q4u zXe?GYOrJKtZHbt@WbZdWo=&%E$^Id6j>ClMfWbql_P{otz~I)ECpTyuFDD-tZ8&Qp z5n;RP{idU0dXChP*ThtYuc>;#`8O46tkHnKs=SWsck+uy)$iG~q&0P_)^s*TBKXBP zWg8l+<4XDj)=H4o!KoT3T@$Aw^yc9yGd!%1=@@DzKw$H?+(MFsOsySG)1twqo_%8* zOx*-Sn4s{{LkrPOsbOm;yEbUi8$Cu`?nA%_`m;)o&1Iw$nS9WN_K3%g-uYB>e;y%C zrGPb5#PUJYxoA)C+nAN22FLiokXyuRwpdM>+8#&36m1W^pL@!S?a-Rum+#eF$HA6` zy>*^hfS1IH7_Zt3SkVg#3E7LrglJj*@INY5ES66kxfngx(^Ni#$u;T&MS{x9gw7&2 zt+#`5vM3TkgQo+2Td{ErmpX=+>(t`i7|aFAKWAx#t;UH9O5$aZ=J&}+h?LB=#mp$d zwNOK7C+q#A39e(UyjtX?Q9s9S;!GX)Tj!{vs|b+UCR{yj4&my-QWN-_ywq8X)7(VI z-clB5E&Sh<*B)V8@6Ix1XnIvv)D{};;wJF|(`>i^3_mk8m~1+{kF*=}nfZ!7n%`!F zM|u{{J$ItgHTD`Ig$~A<(Ab>t)Y;fw$=TNuqkdO|5HOoo6;r%j6*9W+ESWAbet(Ku z_cOp5s)bQ7{05-_fx(!!vQpq*{ne|)DXzW3?%B)KkuAH^tVz#qv;?BuWKs3!*h4?SCd*b*K~5EoJ$y!u z7&pHREycL=+Ly7KXX(vdCX`TFUvaA{e;;JV67Rb7d?m(4cDBQv~bGBETAg!qyZ_HXfG{M2F?gz5NiN0|RCB@rZn_K4f zgfvO~o78gB5?pC+i(B6n$}r*t4^8+Rph{UBG_v7nlX3!8}tKCoJ$a zOiy9PpBnM1O zD@R>T7Hf6rTffRMw$`SGO6;iZb7i>lEzna9O~enlau?R6BHhQhQV@EiJ!$A4%2&o4 z(f~1_Zw{x9!^w$I2C^jl{&G72$ODyTC-MK1BDqj(q$Y)?LEJSETlfW-LiNjLSuja!5tQ4met&DG z;Cc;rAjUW%kF(F2nXx9^N54BMCa-m8B(xbh(zy%P_7LylF-N5r7siZy8YM4}wG0SS>>$|=xU z7~M?XqGNB;9yxQ)szH5>8YvI=9>x?ShAVrtzM@LEHo)Y8yB|${{h;Bst3?MHn4Pyb z!}x-epT!Vt+{x>0QoKjx(gwvwqp|L6gA{Wv2mnoY@Ix@d^LF_scmjW(`W@6x4a)|5zh3F=!pCn(ctn&40lmSPC2 z82eZTf%P}$ne5I%x7=>}g7^|OCV5WEF}+stt0Ez-(NkRb(V0BNi^Xm=UiLZx3En+> z#{rZnPeYu8wWIt=l_ z7wkAV>Nl=c6d^zRR2IGW{~$?)y^ypqQp; z*XENMWm(1A!~)~v&DL&@T|3#UE(P1~JuU%l5=~XfSgDRz&uZFt*bPtG`?XO&iit~k z1x#Qk4Lnjh@sICf3EM?D2K_Cq4IOaM?dI}U3mnLZ?Zxr<@5CR5VSFRF22UTmaW_JB z^83|u*Hp>R_yTdot-hGgU4YgvDRAdFc5vbn3>t_qqW&^7_j8;k3m0no&SebUO)Q<{ ziJsp<$EE(1({yACU84!}XlEhrukEF7bQlEU?MmJ<2$da+P=&utAYf?f>l+`b7d6P^ zdz+rH&3>CAY`Zh?iRuy@X6L;1n+YVyD_qqlBe>*GoPkmEF#!4}{u1wuD41I#`YSGP zD?G!~&89uWJc`GEW>njp_^d7h`PMX?^ygdZ!ro_Q{FQ`|m|v7f5_3GQ*)5!%Z%MOY z_SE&HJIaG&VkwB#PrI(ftw9uvcUe)Al;9?sjfSeAiS?(VnfXcR7iB{R*fDGba&ReZyt0*J@}fIBj5_~0h~aLkB)G4; z?sK{g*{2~;lzdJWpBxIlg4X+Rw{J{0{AFo7JwE4dz?9UA8U4{a~j= z2*#Z_y}D!dRJ<*~6;~n{wiRkG{m$Qc-Aa~=Lo{O7j2n!_;4bT^Q@!sa zw;Y~Sdy`gu9tOA}Ut%$1Ie60jj7aO^lud*wqwyW~?rQutTPDS4)X0jm~8Z~JBhThmUsmqrJ9O^l6g#jLea(Er;Y-<>Rs+1uHRQ) z0z=&lJuUW5EBhp4D9nkjlt{2Nhx*y*KAL|=PLusM3jb-30i~$-ghi&OtBg%s?ylgo zFTVLV1NyR;7UInLr1L-4TGBkVEm=d(w=2zruD3t1RcJQmCgo2Fi=u23&c)M+Pg1K% z%fbV?52k2v$RB0O-+qH9licD?Gt>^2+SODR7~$TPEtq?o6Y+AbTNerL;v59+{p32R($=^Fl&=Jm?j^4oVHCKl>Jlk{y>9l5`8?>Iee3?VEPMl2gH#=FB6 z0DafqO2Y$>U};@Z0%e=bR>VhcMEAVuFDHt4!oGj#6oB2t3RmvpdQ!?#hW{P&g+6L0 zHmW_~n@)VUdcwBWWl!1Cq_roKL;BYo`pmzTRcqu)U#KUde#W3!p6vHm+O?xZHSJ3_ z7#g-H+6l`lqMRx}mMkpgq^lm%|iBJ#iXZAn*nLJw@D#+p5Nz1y9PW3rO8y$kUlZ53ar6X^d@`)-%H>sZ_ia%{?kg}) zosdq--twK=aO!O8DKBrAb;as)av3^T936PbR%UhBeC$yWDBxVP&;RQ%kMaZ?8Y%0U zLyR~X@p+xIW(A&US@5Qg$#wac;RAK22{*f8ra|X4nn`1ni3=+Gmy$cWq4kVWefWS9 z?A20V#8R)jNSanyvk(by#?utK{9PSw-iF$CLw6tv%+AMfnZK!tr+21uD_l{bhn{vENTD~_||66V|#*o0}bS_Orrl_y>4}OAP zgIVyWh(A{C<<8zJ2gO=&iz7#%buYSwua@?{GM`LHR@dNM@)X*I&GK2;Nldw+8~7^p zI=Z`|Vy7Wn!7rMe)H-%=RW)vkoc_X>MRd#1K^Eo4$v;clqg`lM>HrB?9xids~VCu~i?YPL+|eaJwf&@D<< zhl%zS-w4rNgOJ>E_Aq5lLKUd}h_JX1-Dm(a5UN%ge0X{qlwdrp2hzDt~`%~F`-ke-2V)5zN}LF2|KARJS$2I4>1 zQ&#g=i?qdm40JzsKX&t6H8GEQ&afWoLPf^<{5$ujUV1E^`=KM!DCpCfJ-1MMf4dcK z;vDqeh~%%0nD1SKdMVS4gQ9&=ejWGG@2|UBg=l%uBBnXnPT6fP%L@fh>&EHK9&X*^ zNuykr|3?AUFL|~a=3Eg&H*XT)NeUk*z{&N#bq8=ge*)S(lLH!V6T@(Cx#T}p+`7U( zX^2YS2tA7dEcH%wrUv225Zig|pMAr`@M0MoEt8VS8-?Hnr*mLeIc1UvcfjmGqW&o~ z*C0x_I*2C#^6rOQ9%T|DFpOK$ zz73E8BN&R19;5U25yaR}haozM<%d3-tw~`};;aT!c{BkNc*p^ZsZJJ6(8;|D7-#^s z3*_od%CoeC@FfQ!*I~cpS(@EHx{>)g(it+kRGs)Pys!rxxftw5&V6V!f!|V_BTE}Z z_S1St1#&$X4x!Z2S#)coytQT=IJM_AT>0e7^czW1Kwda%-eh!Eb!bK zpwW*89{Oj*SRhWx$A!BI>^);vpxL`6z+O7#Dj#cXk(Z65LJU+xuz|ZzkyZ|)xNj(5ZQ6p z2NC82-*+*F1A#a4^c#`)5Jp#vm7zE-7|dU|VUZqUK+XfiQFnc$gIgFNz1k+*fQ5C!aiftDiIz$58?ngP*N%cd!8c{o|E+&;Ub$7jx5_0W=q;# zq}>@kApF7jesa70Cz62(;sD@<>l=W}?v8evsQtq@){O(G7n;b$;3RBLz0_0+d|}>+>WkcpMFuoTxHI|P?S8B;T5Hu zB8tlYmBP9k_%_q+}t-W(vg_ZTm!~3?Z#QL8wB&EbLPqPP+h_VLZ zyNyFg+z7?mkgkle<{&U`gAm773WN7g#8uZM|0Oo0o3{RIV1|mp`)R#ngM^5pFF~sk zu;_1N2q0w8AnEwhhd9gLSBdyn5^!~b=XI`FURx20k}Nu9GzL{nYD^e% ze-I*i0xWeYV~j)Fq2Xg`PfbC?yq7mu~~F;GzN{p1bMk&_Y|AlquH;aVx5*RodxMA$znO zqZm$@x@wu-pOW3iP;_%-9_@*NTA8L<8qu)#)e_wkEAjwu0~du*ajDZiH!25bh0s|V zBebdYl*0M+%NGR?kqr-OBYGEkqWQnp$lhwy<-OFx?$l(%<{uSf{A8(5pW*gKApMv| z(aoA7I5APA=3=o(f=;8;F`UAb!xb+YQMqu1F$C_DQi%#yVg?ZO5~PjuKl?&aGJ?tx zGpl8C37Uxyc4_fE)Q~OR+osR06KQTNYwndZ`4vnHY90#3c$6 z3D_(Q!_+T^$g9J?Bz7~hdPsjABw3h;SLeGB?Yb$!GnV3M=Y~=mpMNdb0?bf**P88Zpk!jCo37YO|z7Y_l?lEYZ>% za@{?zHB*2ex_QiLDt4XN@V9s7;ecR{VR$lE**>K|E9g;E^XU~t4`rwYqpFO#TRQYz z(L6bNG0n=#Qbe+B`9q^bbhr>Q>C-<&a)Mu>@zPbTgxEHx94ub^uYAL?&;A7=vcErU zdSbIL+eRk(-CGfF1mN!lVO}3|D%?xy(OG0#&kw?tC~!y%e&vu8j2b~Fw?+0(ZKh>i z-IeN280j$bz@4Bx{%$B}QY8@v;!BCWUqt>ZUKSDI+Q8I}jX_({QQu^S z|Lktf=e4B1F}uH7JQR-p3nc8g3<*oB0oliM9}L5ZvxjXqUB=mlZ6qAW@o`+C3rU7$ zlcUI8GF%4^OP+Z-$ETL#m-`NeHN?KiskGZkBG&Td{YpvhRzKXkx;Ji$iBmJt$o9D1 zExzBO2hcQNrrXlGfSg7#3X{8s+Hkt$Gr9cu_Z^lzBmXyDz>j|)aZY{A zd%&}DXWGb~UvK4?Sfq20{B+_zMjOo{;mPP?X0u7vqR%M`&Q+VnQTV}9PU1_;&}r1+ zpp~+5K({xK;s{IXvtNx;HiRI)-go*+H8p&3AIEI+w1yM8vOMy7AWxq5tX&|zJJ9Gv z=qewe40PL-s_^BKJz0;ff1=pjkHNm4lXk~)CD$!hJ5HGR4H}e1T|}i;mUXUxCy!L)IzlU@d2bIlOg$9Qa&m{7PH#+asBnL+aV6 zvjBlHjqQ8RqB>*x$cxKyZ$-TX@{J|g0acy;_w}mYu52dmk2~KW4V) zHm9NI*vF*6PJIFFOiQpDrsu*DZr#k_M`O2KpJd+5nQ`(Cq(y6^53B%9U8OG24 z<#d(S#JwIupVZETTqXrXxluaoDu0n=DHxnL=+b4|{q#ubZI9KJYwBr4=-FN0UddLP zpfFJhcyu(tgXjHd$vVzVy2AjMhA$GkTL00cFDRS5W~i-+v?^vI`$q{EGp)&NmhLQ{ z=Ni@>f?e8M6K~kJjyo=Z& zRf2zC2;ef+ zbDPSi6CuN*u7yqA&D9Hiy_|YLHWpI~*2xD%#VI8ZRHfUg{t8BtX*T(p?_{n%_QjtB zzGhtv(4EdqJs?cM_gL>pHa7h-B$6dvx3(Ox9uvQ(+B{Lnuf@wIL_mA{s;^;^Pb&Gl zb&HCH@$Ln_;#9z!bR#iAQ8y56-rd!_WjCAro*>IFk{9zHUAtc{n$E6{cdoCWvk0FQ z1HqFeqS~mNMqu3$^RAcMwWX*xw4=c+;vd-?a__c#+@tR$t-7Gr@VZLQc@^*gI^m znT*Q^b3_mLvFIT)mlR)rI$y`D?+9&aq`(iy3{_h>@yiI&>j>)JH^zG3jkO9RYt2}z znx{>p5aU=vi?I<})tS3KHN85=~zD>IWF&9IrMX7*}jMxi}z(6Xym#@REWA)>Zn z1je_k+I(E$OBVU26{lm?dWZ|leUZPgOea_I^HlziZP6c1WziV46ebOd`)nks*V^F= zBWBHShKJW&#VomKh4Jn}J^tcEp{-5Rra1ntrJEA`2|MB+>D+D!bW!pe6U7A&NL@*# z>0wO{1cnCh&g$BGwm(|4-Zi!dIk9HyqBgb%6^U!@7z9=viBT|9-a#_6t~awM>yVn- zA=+9@GN&28= z7C-$Ix1yi2`^G5Jm>v@Y$8hR@QkE{A=y{6BejT5OG7xIt3frgQT2l%s1suW&echpp z{Y94hNy$3Kh?eJw-amDVKJicuWYxu*J(yW{DAl9$Gcq6RXyn$jN6zP$a3W2Y;r^jx zRyem+kIssrhE=3>r>L1e6)Br9%UKqgb-ZVH(Oq&b=E{C&6E$FnZJ5X z>xIsW{v+dGwn5!a{T~?&tPB}CQxlVfSsa<3S&5VWV-@X8C^?&seRpL^FRq}w4`6>x z2m}t&4;w-lMr2*$6gm44qxIvmQA(MbPL{J+F z#0f!Sb7)Q#bVmbz<^!XI7a@Y~D8NGSA+zB{K1XPB>a$D~pgVF94@r>n)okhy{4q5$ zFflqYMo48?Q66B99B3;9zKJaI2HK*5pHaZi2;gUO@H6c{E!gL;?Mo#CPM;V+p73CO zm=NwEHCQl8L=h5Tt_*lW{I5gtJ+LB*o`&Y^L7q}sBdR+3FH;>^<{s&E`r=NxuptCt zMHN5>B*+KAoG_@37$S-hVge)46j}5JJRt{p!a;&iLuMn3Fe^T%DN6Pz)@UFy{>>Cj+!41^XiixrP-z4Pm|gWEvX)(kWmfNc;xcB7%ExAsG=x-oO(i;7Kg-1OaqM z0)7?)3&Dk`MilY;r^@}J0jt(nBZI#nO0*5lH2_as{u#DT_Q!ybeUMNA zp3s6kDIlkl#tFvywfCCbnNpM7)*ryn?Ek#eaYWIx*`5ig?IT1h{GZ(iz!QB?8z}^W z2_ZY5RlA@p1>b~Ga)7_UO4I-u;34(JeXoEyeoz}4hI{clW=K|e(JNr??VtDb zCxG;$hlId~>>x_a08cbQcO5}0EtB6CbXQnptRg)IM2pKO<>_R;=w5~MWrP(i1Cjow z-g1K1Q9}w5CHjWODL`$65Hdsw%E%%P02XAbmieUqE%R1k(!>mDe%CAfAi)t)Gypuo{^zc{zd96?w#tp@ zD0Sq2u}xyMs`jY6=(@m5+;7S-f!C2kfTojkLvvF9xc?as5>&z3fl9aNpqZur$}G1c zr3erZ|P!v;U|T;4qr*>`m;Eq5%h ztaPeNKdd@{mtHPw+c!5I96?ek_(IM=cZR*_h(Ecs4G4?0v5`pEQF)z%n|`p-|5`=j~o=GzMk|u;vhIcXst*v)oa& zDB^5wo%ObZPC?fB!;u<-?&=j?VYCxz7#e4 zb<^d1J8GZyS_4y!bIrXJwRS^w-P8gE@oB#Ol}ekd8kgRimqvy5%4f-&R=Y!Kx#t8c z546XhG-=}r{wkoA_eZD@ZrSGkmy0fbje#LL+iBF{OZM zpNqAj^ob}=y3baZW{Ibqp7RL;eBVKvmo_aK8A(aKm}?3G4B^Dll+->qWy~E#wVGWj^e4V%B*9%#~B!KcB^MLZFA-hdX^T zVn#7y!X3Uv>d=(AYGd)T$9vsK(XBXD;cafh7kn|Bg34X)L@w}3 zXC9=VdbeUchg~c`DR)WHT<~LR3tz}uBPCVCJ9dtU2V)9|+X`2Zk@Hz)EdMI|eKC*j zdZy@YH*Rq4_H{s^wr(as>x>3r`y^|#jtf%N8Pi_9SC1L1DZE7;RHzcn|KOg*h7FDx z(T85Nr8;li10%8A9A5GZ?a|!in0an% z>;cni<<}Qwn6YkxpYNRd-@a+zN3KPW(2=(sn&hb)Qjzqsq~J&AxIO-C zPFzt%Y57cNOr^0*c!G;Cmn{AEJ>Lv5ZNXtI{iP~XfiX|%I@!W;h&JzSfHiWLV=d}a z$++EE&`+rMg3_0^y3_U-sSPue;U)7eG6 zjl^1*(GTcsvxLuWlERke!LZTO9}LpzUM;ng4Y7-G?d7PhZW6@}n%n}_Y_IW{R%v~` zU?0)rV07{3b)}yG#osCz644yO#yorc21~a5{b|dK&FDqmLV;`oN^xJKV7i@ERQOWk zA)lsXtc0A0?Nh-G4BYgV=5E4KZG>|jXy>6u$pZaCKK@O({xMIjudOd}uK~&&&5hy9 zy;^59ringgd1rup+so}pW1T%3td#C%4FA8sn%eo6mmPcSF3(09iO%-zISbb4Dp(vA z-edc7_>cQ6ZkD=h$;P3($(Q@3#;Ka+ER)H_uBcn|RhrRUVIifw*WdfjPA+i%y?9__wjrvW{G0IS1|9gC7$?pbemyJS zyYuzWSOoMKL8Zl2E+^IrAxLPF<;^WHZr1?L@mvdr1Y`ca1OqrxF~pq;mr6IG8%ppH zZQ0km8E zXUEGY4{u)I)}R4hgdb-+fIJWMlLPj(&*xH!A3Q9hL~ImSnbXco3D16Us}EGh-kv*H zzNLUpbSm;z(?IpT6nS$wzaoBGE=edH0<1_H~crYCulS(J5@ZvYw{9c6`u<| zOPLXIhiM9JV5x{|uNYgTA!3(`gy^H*pO(@{G!oJ$SD|L>qQIg&Qb&}IXw29YDH3Xo zZvrx}(ht;KO1+k`37Mxv1xmx;@ePRK5D?9$@dfZseg@gAw8!Duv}^Ll1+!vA?911h zSf*5-L`$>bM;>T(vp$7#oWFQ@&5Gkg>#6eh&**W24lhEK|KQ=46LmrL82MaPScgr8)nuHrz3 z(?1ZkjaTR0?6m8R$AxRq7-lcZ=5lez15GHNSX_lqSis6tClHAJ{r6~deqO-GEVWc^ z>v~}^7M42NDM&X{sMvI~xr!aRL;c_N(VxLB1jLRQ(aj055-t41e~UlE*B4*vSz1Qw z)1M!>DJc};vK5u{df|qgC06sBz}^WK3T%^S`W{D_J7U^eF%l6_wx)JO1?0rrA`Sc70BLc`=(WYg>s+#j_<4LqO+p2x_PBk z!4R5I6)QjO$IRH=Ck}YeE(HGX5E1`X~Sb`dZG@3TX4^Nivl7uUtob(_X zfs~7VZIyoCsrKAQ#!(to{GRty1Gl_$I;Q)d5=ROa`UO9iUJo4|REfi!=MqTHujx^< z+sov8b6j3~ES_s0)fzzp{@?=2dV83oQ>2)c2g!oQeftp-pGLtohtPR0jl=jnph0gX zYG&x5JL$s_ogkNc09EAr6q0+0**+$x<77F|t8fK7v zhY%Oh7PG;t$e0(jqpYMPe~Zz5xvl`YN%F*#KzAz6$$8gv3U`buy!Ls4QgU1Gd@RHq zri`@0V^oaHEY)b?Z(Zu@&4J+nY)=9fztjHgUE`enB9sHX|ay zG^K+jyc1z)j2d`%-)xynPo+5n}6@6`i!Y)=%Uc2C{v${@SHPgVBK;asN_tWt0MckG` zz0yU((pzn6*TNmK0W+ST1+6i$gvdANZ^M_ny{ExYs{C-nC(vdY|dM}sY& zB|kS5bgSJ zE6QDovmZ0+t(iwNCPyH?-59zO(_uhddG7a}I;-X_`w(Bk8T1+>cqL8Qqzy{?b_^mh zDq8>#d?CYGO)y|;Aig9R@E2Y+*P}$KIumx+!;oZ81T97_`B%hVBJFp}$zW_}aPa+! zjzYOfUXb$!=oOpZ^!4~x6d{r0 z3%$Q<-7Rn9?<5NuqPXAF@`bLLG6iCtU0X7hRP=rkXvPi0>!a-H)X@~m^MbDtOLTWV6vuL=r8eVGnN z^3ZISh%0WkZ8CbT=`;JRrCyrvGwyTG=H@7Wf9HaVXC*w7o=8MDTf7^7%R^P9Pyt#=fmleL*0EL{yj_D6-8ueuZ%VE9y|LaZQd`pNyN z<4iV=O~XeMHw!m^P|dB#l;hMc<6yI*F`v(}N}Y*;w~hD4xho5z?v_@XHcqu)?fy}M zW#$O;pl(mqt=>_W_Eqh>wr1_I){)j_t*{UD^mXxS@adi5I`rlp_o=Jti?L>h&9#BI z^Z5o~W80B*#ix<9yU}dB(YxVqRb!JLv^C2;x5Ghg?xFhCp{(Kjqk#e#8lPiPPnCT$ za9>EVx~+z;G~Kpmy{qT? zYGW20%qmTR@Mi4E*X=bicQv1e0z@Uffr_qg zYysk^9kCWlOS;{7k_r7y^LrQ4pQ&wLmzcJJ7pV5?uac{(&FL?}zt5rjbajJ^Mt1^t z0dsYtf2A(Fc}I)To1$`3PiCHnH>~O<#$Rk^X;)A?20oESapVpL#zm@GTqlkgokm()N<_dn@-QSDUY0 z5eE8;>gRvsvfm$;d21LKAKzVTYkYn@C(zRl@_RzLX1e#M&IXBncOGl0Ib~Y~FB2Q*nSt`mu-Le-yT4~NS;tB8-o}uST`}W6G zWbWyXS3uoF%o{L8Dfxowz@OdIY@l?47o+XcIoC!HZkAg zvk%(>L7`sxACwr)zG=@CoZV>6d8Pnq29nyYc|7r(56@0ft@(Y4!>}A>_w2$d<{d;m zpbtfT%*wxk476uUV>L<940guccT|Es6~KCV2Hx7PG)rvps^@3X*w!G8#QfD`+v!$L z+JezBXQ{||V&+sNG5!EyDBFq(o3oX1eODiYiE!B;AGhs5dBtk(a!Os7QMgpS(*k?*buZS%&aL5tZ+5Tk3n*9X;Hy2kI~Eqd&P@K&9l zGlWW;jD`e~Rmua~!SAfUpRDxNSCU(U|AFd?FG7mu-p1%g z+1}p?*Nq;3W;DH4Gg=Yf^y;8UFCyB{pF^de^~xEm#y%Y3a>+j{OO)o1ZL-@-Og|~= zpY1U8KEz-7?;92}%TlJXivqN`6qVsmSE`Jtu!{SNPLHcR%yOkDjAV;h3WwaJ@uy2vp(dTq-+=tcWg1S1_n! zG`;o-SGgKjc#CJ1Oh>PhY1I{d`WYC*b)r-;dZG1{9ak`g2q_8bE52d$Kx3d7Fc?S# zf^{RaLsW$cB`C8HeM!q9c(a>6875y$024~)g=i(?oSicUnR3Y2q=SshDb*9hKNjOL zu1cuu!UE+H1em+k>tNiVb*_ulcXz#C53Ub zs)MJ14?!1YIbI7%x#kG-lq3bwf$%{XFqoI?l9=DnG7?KLsVjwE;!B+RY{4t63BluC zrp6d`!T36_%=ONn>Ye%P8%S1sMCzS|>MsfO44Joe<+?POe9u$o2eiCc@V8~;y1p{G zp7v#=n%P!Gm*$6KgwSWT6a-H{X*?wRjSW~BWxV^(52C)DNJFi9#ZY^@7T(mo0`ay< z zn<<8+>`F~s7t?+TF@^HoCq))s%go81_K*kI{FZ)Go99y%uNhSBqW`n~dA=*bMWM7W z?Ns$sFU}XC3RB7J9S!m5t`Pd4b@_Z^ogD2cF)Pw`1?UZ)CEg!+>7_PBybh2>uXU0< z;@xstrbEr?N-~dP_hARLmte5qNW){p49swwiHi-NJ7HYU$oHL#alo{0$Y5MIB0)GZ zgdNx)VZPy(fFf_>AY=%F9jq!`RaokM*VqKW9>_AF55W%!fd!M;A^n6EZti`qqLxB7+x)Nr9gM zpaACpRROUNJU~{E&^&4oY(D%fyfYvhpbIb!M}v8>7(hOK+2p!;+3eIB7~v=UjC2f- z_MqnE3k*d077wuo3;>=UbPNfa$@IeeGr^cJQlq-?_>y!Bj-ZCUK=@{yn^>6X$V>I0 z)xB3PU?}ZRe6R$7ABb`a!gXXT!tVM*J^X{!Goxp1ipoQ_ld2wE;eB1y<>A7=FjF#fCZ8Wpj>?p0dbB*=FL8 z%s|v^xzj=PZ@aXS_?GQ#I$S@i!es+!?+71pcRe4DYOb%rIPE4 zz(gEeo(KKZO9{4INt9>2zb+oDEqQKUR7p38XZ8tV#6fs@{>n*uNqf)n5T zP~;pj$3JANHf%c>GZ%tU^hP57$`|zLcu{o&T3`HMp+DV~lN#(v1G)bMx#s{arh^s- z8K=fR)8$<~;_7vGywY8$>fFQr$d+PCYgibO9O-LBkk`V8fhJN)(OIXzAGTU%-<_U*3B zJFneF)YkSqFVc^lh)O(mC~Og~#9_0spfx3zmJOVoB-d9|aCoL93^H6^%i>eT=H)59 zNbf|7OXES?A58b;TT=H(jnroex){sVpX61eeivKt?uulMK?#|AJoiA>!eDk6KnTVB zU-dGH*^Ci8HH9}CcQl`7<=)IMTcul5RZWJnWC8rhVx&=p7}9fyCAN|CZBnP}RQFEU z|0e%<``Y$_@3q7RWi=_&i^l}#D|!Z8h#4I=Oa#Cti9Y?hh&=TNt-7b^s#jShDc^SW znY@aCL$CT`@(-6Kud>R`dZ9n{LO8Vg^zyX)KZHUu=a6^joxQy%aok9oiMq+VWdz-Q zJohh-N7rZK+wvBr1{V#^8ijf>W<>2TPK1P+epr1EQA~l8hqnxC0r-YnnUQ^iOG2WD zS%t?9Ck^`ourfmh4TjYKc+G@4;d4-?;WWb60c1dVDvTVotq)u1)9@~^3*pZIIG~Oh zbu;oBCIs0J)ejNO)eP@Pu!aKp;D-rjYDNPSgG51aAR3S-kPf&TmL0AewhiD2Glgq{ zgJSl_EE*v1KD@X;(>G(SVL>SD0C(^&eYaE~Bp@5mIn1Twl@=80-}eNrKKI-`VBw)g z`8~=KvC6#TT(=TfH?V%CVaU?3ZP?Y(#~Je z#Paz~pzeF9vFJv{3?J!y3>`kr0B@Nhn6?Log8LFg=n8jy!N(H*h9kd+Md;#c%Kosasud?f@ePeNfnER7Mv` zOdaPEB$(I(&uaz2siHfNF-WoFO+{P$BrI})qF)yfb`pkeJm#6(eqnWDi!Z~r{2FDE zVaBSc9`j+c1?zDv1l#pDtRVJ2JC1LBx6-IF&DBTuY_fzAH^HRAQLxg#K)-KC7HR2D zmLgEOIP& zIMI#m{OkKy&`%$l0C=!S`{XYu*6iX3hRv; zRQhlE^yxLrRVut2)%YG&(!>X{B$;negmK6<2St1tCyv4a5n1Aao2cq9D1CL+MLI}5 z2%U1`w;)2*KCU1})d6~be488p>=45ZQ-0zd$UX?MXzT>!pP$MBOavnZp`?SXjl!CM zb=}yeiMP9BB?IdKM>JsqBv=SY{{_9>*YqP91n~F~430K|$d30{{U~ez5&wEcjF7}< zJ(z(`$tE_i7(oeQ=r1Uu&AR~O4gJnAH|rd9hgQb||Gb$bbXSfY1^NS;JPmP`I1X)C z5N&R{DuP~Kk4uv`eVt%gx>{t5AnA{cVN`FQ9T3~Z_wQtJ@TsRmPxYDPx4aY8T{>zj)K6G2F*GLBHzvG{ zvdyBIW0fn^Pw+8ECbk;mC+oz&#tle(8VgyYM2g+pmvLjn9N813VP<{!@x{k`&Hu=#o)H3!@zIN5%>9HNsc(P_i(1 zE_P-%A>;!tSfm5&e{*`^NC{V>-kQ&f1EwA9wr5Iw!j) zJLjS8juPe~Q{J`*Cw{0L-6nkR8)KmdL|97P;(ZM0sma5gEeI=$bkt(}P~XFf&R3BT zvkaok3!CZ|Trv@&SV;+rK)?6E-$51E#=0s~(AtYrlFJ#a6etx`q_J$b>~PgE_)pFn z!k+0qVRTo$s?y!AvwxGoi{Aw$tl>7JGiA}J*c)VuF-t!(HQ<-&VJ8Tg+MfON5C;goaE#-I zMKrdDIuoq-StLv0VqT_be9Ml-aKc(}N|JhgiJYh~NW z{xnfyu8nPD8)v`3>nzIuaU zMAjK6HZtNVjTXC;lKeuXlM>?TSH4y^W=#I-qlex1adq!!a|YtGsh|sPV8>eBmbyJyBy$*Es{mlpLuy{^1IiK~V3LOJjcL+5f)4{F@TcUjbYLpf5EcG#8v5|1S*cLuU3}2}0Yzd1JdyWHaM`{twja zFpr>xu3pEKrdtyJbcdX)lMXUWz9mbw2WO|*Wo$o;8T$&vNH(kmW<3dY5|+X68@;m0Hrwc49< z614?3Xnsh)?`rLK`G(4Wpv5*x%<_WRa*il)e2r(kkn1t&zb~Bxu2`GHckEVzNGb2@ zgJduNoYByj`}<`i)t|ARKS4vK5t)3$dE5;O$& z1cC=`Ttlz~cc%$1jYA`ih2YRY2ri8~jk`1icMI;WjXRBfwf8q_~dmMs(P8;-1>1v8=*6aI6WEH*9h$|?P z)SxS3R?!G8l2zCE|52&-Bt%S|Fi4#YFFlS}{ZtXNo(Rw4I++Tu1Hv!X1V788du%(N zOoZnHg)i0$iIu$72~zr}Q#uZ3SdBdQ?L1Dt?u3h^J?1TrMb9k0BPYCGUL5-}+}mvz zhgY|HI7-mOz#O`W9LEhfoWZ|YhT?b{S9PRuA?LY}^Ody6cocunCbHZ5fyE~xUVlzR zAP3gc4%}l2{iw%Z*!6gPM$C5Ito4L-tC!^#+-Z2U2T%n}1LIjD&ky@hkKf^JQHyWq z?K{sh!v^Gwiu0-Cb@jjsX%E0Tsi8C^Q5x@p}Bs@hrBJaaz~EwP3F7jxYV zHTud&XoomS)GL0H;1y*GB9!HfOou4h^!wvpj%LuTf_uoqc+o5hKM7uEJU z<~7a36T|lRUZlh;EcL1sTC3JxxXUthc`Ic4;mG4>cdw_{#T=g5bt)u=r8r{Rb=lU7 zG`}J2PaRU%m+4}yU}*oQ-zbFDAG5kcuHWnUuE!4#X9HjpPRao4?h~Yy+oXtdHcy0; z(u0Efl8q|=Qn`DI3+IUu6)~CrsmK(FeY(fni&FLtK+#T6XFi1Juz}(Sk~b^O8{q%c z4`AnsAr(HEMT&o2^0(~b7jJY^rN@QLt`^5cCk}HiHLZ`JrTLDm5g;>29YE`MW6Tt+ zV*Wr0Q$&=9@obz+jP=hL3ck8g9thSI#p?7S(k%E!L^zuDR9F3DxGqG`{u&UK>^{+% ztxGj|S`aT&BV4qp!Ww1mp+4}xtS0)h6{*0d1u-%(;k^wNhA2Ue&$@v*|3Y}^53K7_ zO`q1s_tXfNZaT6?fjkyE*XgPFPU=H@6ol>89Py)4-2d;DntET`d-NEJg{~vMhWZ$1 z+tm5C2GQXQ$I>Wg?>nVqU%ac|3vxY&Zu{bjBUonwGed25IIhm+DgFowiXRMe^)tg= zu55V?iCf0W;Z}dk&+sp7^bLs{|3i`U*56xKrA|QAPxR!9vRyb9M*UZn6voFH|z=E2{Bwvt!nG_QXN;9KQme;Ft>h@UQ zULf>w@yQ;JGN0Vy2XNKIkm~%-vwpTUV=oC}VUU@H-M zq>(P}I3#hZqnax3zp5P0y>;Ej8|OpDrBgLuFlqcy{WHiWAIk_oUOh6Mm8_WD*z-PI z%`Oc^+4;DfWv5Ut-tBD3@QF3vjQwksLL2vsaRPZYj(?XDGS#AYx&QaL@KwQP!pY^2 zT~iK|_?LwYwtg$~XxLlj5x1qGTlWRY`(-ZQDt($?VVyf-oLh1Hex=<_5ysku| z|6bSzw%gSgpn7kYI}_Ok9zCJAyIo1GC8SBNkCwR>7ZdxBh0^dv`&#J>)1tXIMJ1nW zY*nn#3#)%yo}yEl70tSn9iHp^)Ojuvqs&}etDLQ?miL7>)bf@2ORD&C|@g4m#GXHIIGtTUDLfE{6=MLGV`_+*Ly_&{is}&qk!IS1P-J};|3uw%)sGy2VuIL`peT8lE9;-8Z6pvl{ z70$`Iuk{WzoyfIIsfU!G#dLi;up~6>hoU~=9{%*lsLyw!m#A{i6Y5d?H*PbERS5j4 z(NN|@PJG-?8uaFnN0pxQmd=<V#t%iqBcWnEzcU0jN#TAcXC5dmaBYBKj zb@%Ixv!_!=SDTkcqh|tFM^!}G&f};9PL5r)4|mJ&w0rUcP);C}(>il2A6A?giEEr# z5zu{C+Rle%rDHM@pqA&N?)PNgQUh*f=2YLcj^Rv92SByNqP>h$BMe=J4L znjN!wL1LzH(02rZP4-vJ7kZ2{(rrW-wW{TD-)#wO?uA~=GtS7h0WmKB(PV#Rf8ohA z^9cdmyHI79Kwxb`nBp_FgN#XK%^2e{)!B2=n0P)HipyfFTK`b>k0r~Qc$wt{ ztvcNwIdRt}V#g2*XK2SY^;GlHPb3lJY83R*um7?|O({m_cX32Y=Z?bk3>@=y z1(jI6yYW}UDLiSpQR*$gC90C>!yQ^t#1wOU+(f$S|c<} zV{Dyg=!I(gB5k=$QU+&e0JXhgtd+(I@EJN5*S?TcXz!mfLxb$-q3#3K3*_uf?KHBM&c89(Dh0qq3>3hT<^$9n+-~Vx zG0$R2GCM<9TvTb4jV8Kvs#?`kauCH*3?%6UetR2EyJMOPikJy-s}NWq2h}Zx zDNZk#r$`bvW|LOt(#M}d(0_B4P1oWIbwpJ7V7ZHg7-Xv2TaPyAfe$qay$Y#n=xcjC zk5=!?-(M2Xe6G#2)gzJ+_rC*_!O6@X;2Yy8y!wK3)4U43a z8dCj~wi?pPdz$;xw(Hqp0rYe%u`u8MOZ`;h!!X~uOTe|wb!1Wf+Xs)b5nR3ksNB^< z*S;5_lic0u&dN1m0oKt@S*wD2P*5j7H5i{vw@1ze?OZl)Za*$5=taE^tKH19VwOZ zJ@^qEYIh!x`^qEnM{p?j##dto6lcaWEE*)3?ZcP-?vUvtiD9~p)KU(F{!-jP)2X|* zD$r7hUVf4;Z|{xTfZTr6q=@W0^Z|S$D-VIo6Nusd_Vok*ALxRjY}LuTdPC{7S72{t;Vw8P-Mo@sAMh|3Mmhl#mZQ**Gp?wx z>k95j1t;IbtbZ!TmedNQjsGyk09YF;`WF!NrN>sgSD${z*$Q6 z*^Lt{L#}H?eRf%8HeBQ2lSWg2YKlrlS@Ddb#%uu@QhoJ}M!n*s_ZKsR%%4O>iRc=G zPK4vRvQ%1hNOkd&{l}X9$Hsj_=G(K!-1b?n2iVT?d9jD|sUBczZst?fgt5qKR3zd% z-;lGthrN#Flt{{uzT5>I2$(i@{#rJ6nTQ}tK@cGgog=&&L?=x)K<8Oz(u+mQHk0^Y~QQZ3N*QtIcoeW14|A1$XQQ@|JIHM1aIJrJ*6aR(pr zc*xp0ZPun@E;T=XYvA_g)T<@+kTV_5mkv*;6WNNraH^3>V~a^}-rUsp5YS?~?5!zr zvMtu1XRd>6Xht>9F_+c$7n^NmT{u}Mk=j+HCR+sQfwnB;shu}vqV8s_Uo=QkO{`(F zR1>a7#V(n=Sisur_3RW@tC zWpPR-40w@jDc~PNja~GM#xcX?Uo2*F05)st&+^ImCo@=Vrk?OR7Wt`RGyCG_YZl!} z6D}95k!yHmhuN#2L@>7iYo?1Yc_)|h=H}Hs5!Uu<2PyS48U1{PrwT=0G0e*wN%ix4 z{H>*;fM#M?ZvW|s&U8V64zqQ97$jz7Tw}8b%s2sE$9axa4B@xwem<*p*B+uVxc7dP2PH9qXKkpk>P-VHnK!>JWJQa6x8 z9h%!fz1}lcG%L=XQc_*4M(1u=%wej__Ip;eMUnMGQa7bW&)W5;i-L)z$DrMbYqPQ4?0&GjMU0!E^wsHz ztEV)WqUuV`|MGX~@;>UBW=F|XwG~EGNLB0`yl(9nqD&I}1L`P&%w-;W#{J$Yv!ECdb0!XHU{C()^{kuwtGp1@ zs%OdG!IjKA%JG1^6xLla&hJXrp?F2*aP;Jg%3+!Eu&Kk_t$rEjYJL?cv}o~5#8tAV z5e3S6tm@VBDHtftKl5_yk93{hI%k(w;yWA~_DTX> zq+upUJc5~7@08K|MzBg^lRJ=i%}p>}=K>xX;j*T^`_kHP;TKbOLj0bTZ%X$`4j625T9DiS{Dnk6#$EE#+jQhakHD8rI~Y|wuc-%i{i>j@Gt_BB{Y zY0wv&6T!(wNf+5u-1E|8hwtOqlY-ed`N$m0@U~k!c5^SKt?jw{fwcR%r_#*!Isc4f zX}7)HW9dD+oWs9EBW?^VGw4$(6J*woR2lrhZ=72#6s8veFX#JO#*%DVHUf|zM&*p4 zaz^9@Z1O00)o_mPBRR~5e%n)~1J-i~U6=ri3jdo2d=k*yLVIVeYzYzTF<+nMf z+iJ$C5J8p=iVRg1fp$_d?J>ReMDI)wm#o~r{N`Q9`QrB3=a{?2@|?W&y)B^HHq&;? zK5bNQzb?`TlOL6%I8WrJ^t*PmLkX$k*9#b{IB_cL4zz&Bqy7fEOJ@QJ)g@)gqhiUs zs{RBFuRZ+OP=3CV|!7CjP#wiX-{nhsp+CJ$=`1-qN{cBagrW9_1x?N3HIv6CT*PA6C}DjtZ#?4q1WE2y4& z6n0|3*}~EdGuCJC1{>=$bb~dEZs2+hX<*GbrsDos?WLN^L5mf^3ON3NAWL5?|5T_6 zjDLx+qsdsCAqZ@&&4)5np~8Q(bCKs}Y2+G=EN!2x=M*Miq@s#E{N-y*b|`6)NN6kZ z#(#L0k}6EP9Q|nZ{#dy!G&6JMy%zy>M~@?yVq4+$bH$Eb{%00zA5#C?sm0h{`)`-G zubJ68rycO<*O3KKdV&wwWyH;RKsI-Ldn3|#6De)g@;AlG!IMT`RspN4?G`6;6Z3}t zZf~dBTi*r*ckdIMM+v+gBr}N<>1OtXYFsA%xyqhFD=bWZkP18x4h~mrpRMN|WNX9` z`-RKNBdq5F*a30_xCwXy=%muz!=iBI!jyi6u5PZyI0z1xKU(QinG^bwYXt;{rFZJP z%q)K|S&fPovEgugw$>m164u@loKitz`!HcKr{E z5T!smy6v?lprNhM;^m9^ywtwJ(FZ&tu&CDZ#F#6wQZH; zoIlu5^|@JUElzxrPHYf_FG4|W|pHf?SCXoQ^dF} z$G<1}^;Woo0O#FfL+jgsz&%@)3ZOFlGJFzJq06qh-4)YOwB}ohc%C4%Jzr1r;X_OJ zgF<4Mo&(DR{?!Vwpw5_#aJ(QiK!Thk$s=d$=Lrm&voNV|I{S<@#2u{{izsdsJDY1 zx2PblR*=xfHKo%Xj)15}q*C;{+Qv13fT&cYQmCDC;Cu)8^iI&j2PWLAm}W?*JNjjk)S*Bri+Wggo%6YCq-gh;b)=?qb#nG3MM>mo>sy47{Q4eusp4P3 za_wQs?2e(dPVA00vX*d7nAV|xNA{0r-D!WUH`w#^L+8=4=Z8<&53iGr(?c#JU_=p7 zFsoYu{nv*f-gFBjO|OaP%dh~(YV9=@AP3v}spNz9>$(nwDO=+1R*!Hr?A-o>&BqmF6`nXVV5?oYV9BfN+ z>8%D;fsTEi;56q}c|sSK_4ezpw=a9y=D!Is_7{E2$oO9W^+yPKc>QbrH!u9ql7qxu zgUkz_1dx6W61^%h9-Isr+t~78J8K@F%pca&*uHzbQZVK#LzmP5l@}Oe`(-+?WBIRg zJe6)|>Fn+eoUq{AEPg>@pZ|a}^9nBDIvlf~$}lUyUgZqbM3+*(QI@~YPPMqN@ITck zEZ8tbVk?4s{m7K@t;KB%o`L-u1P3RLN^zXQWa1{4PZcsrUGmGQ92hpve7K=wmV_SXxXkv||0%;Y3dh0Up1$Z> zFpA$)Tm$y$NsjU#Oavb>Ui|n!l*W*U#*ioWBN^Qf=~p=_Pp$q74gD$dH(dsE#E1;O z1#IsO_H%#F3^A;4ejJ~#XtFLD{v*j-cnW7Bc^;DE!dX^SV-s}Ajgo2!mV0j$46+L4 zxWS=$Y=4y-izWXjG}oRz1IHN67;=)VH1@2gWl9eheXXK5(+rQO4a4+1WQ?!(e<~%B zPyWW38d&@KQi2TUBOb+b>af+<6hX8Q!Dw&M|A>k=|9>P|G&D~sYd6Lc_5T08<~aKI za?W*7uSnOwGT(ci#3)WL`y=#?Y1aQ<{SvgH3EGkW8R%c--)ZB;roWD(InniPBqu6K@A{`P`rbf4$XK2PaHwE%(Wv9sPCs?v9aeaAr1GSSy> zuTclMa+j1fQrd+B!UP9H^L5WiYm*+yBy738jB0h2I)q#&)ehqShSF-)E@ zYMwD_!sy_1g{=2)7()X@gzhBsC_M3+Nqv~rA`xNJ>=(xB((PM1Yo0N#g}vgA@0BTD z5y(94ivESk-u)LnnCvos?~gkMPCCLT%L2n0fKc}1lNX{bzj}zTufLZR#NJ##r8Zp2 z){Je-`aPDyDSB7#JOjEsIq1wTHw&VQP!N5JZ#2uabXl0$!iy$(*-SOnL zC{?>wl!~v{b>Vl>qMk0L>+4t4Vyo*6Uh1O`>OaCUiUP}yRX%m7d}3Q_@6o$<$E3Dj zU1#-b4vhLl_U+%ua2>y*n!)UZNWo=z6#imJhG$5I6N4s4hJ9&XBa(Y?VKpNV*UV?d4Vi@YmV0v{E&7@B{V)`u z+Nkz@dmjQ)`C%fx_dY99e!UK7=grth`Cd2y=DFaB79w(qz3iHMCVc0f0wNZ?RK@|> zedC0rl5QJX?HAmcf;y3AV?_^KaNSVBdkOk*&-FIy6;5dpvZWLFB=_&6McJ-)yrE0U zV+>r4rsuQJ7FB+ynly%1Q$>D{21U07v;rn9R$wiIyN?6cOuTZr9*(73GLY?TzUf#PkR>SZjI;Y)qI{`h2G0aw>Z-bA~U{ zu|V%*MMX<%5iWZwe4nMyCR};$q2FdmvWtIL5Q{ucCO=Ox-F=C$sLy(y1TmG$iziG| zcQU)(@F`_hxOw6|S}&yy2@Uy%jX@Fe9h39;Esl=z7k2!(%$g+{A8gz`skL|RBvgJC z95_^gJzs@|aq#Pd<<500)XR9}5nVsNia)neUinC%A0ke{EJ0X+G5MCfNCIc#Te33d zp2RcDmk}A9+w%N6Il#b1^2IuACsg&B+~C^VjY16R(%lZL-%a@bPf?#gA{;<#@c} zZ+ImzYJX`mj)v2iK|)#mE-865p470G-S2mMk2DJ zfhy(CxCQqUwUL*TEcwyJvIm-#QzSMGEgZBu-nm_;uCssTf%`?2f3dGsOPxnYU*Vwe zD_dox@K-g+sLXhy9>lDyX0KV3!8_sC=#aUT#TN7g5>58?|6q0}EaDS=dt!_Guj6y0M_Nn^$S90Wgn<3b29yNFj~l-ZJZw z@9nYLxxt(~C8&4M?~ORhmklnP27KIRkJxS(&03q3emzfo8T0L?QSB?U@GGS@?nE5G zidEvPsufaqBJ*d{JEG_#9he-%Tf0&fATYBlWwl@JC{AfGd4>pd;;36%Tof9_`R9C$ z`^*3MwJ=uHFKrU^sCE+$Dym?HuTSLzzWnnY;dqudbp+Yok9B@7R_ zvuY5(ORd*uOM63m{(|aIYWQ=}4ZJr{8dsl_?yv%Nimvr81)%4dz>oKZtBK+K)8rZz@}?@6q(@WF)8%gNM}G4_ zLKgtOX>4a!U5E9tD)T>Z%ZzaH<#eN2<(LpZZ5p69NjPHJ*B_5-(hN7nG~cRMzmD%E#48u~d#2*>4vnhwT{xal$lfV0H;{OzgNIcD-RIlzopM9>?D=D<=&xdwRIVNLSVN+L-gnPJ{cY{+%1!k`Qq#jNIo@iURBz z8;wyPhB)<3Gd;GYr{1emsY9>7Y+H!Q9Yl&)JJ#rX>Z|j#5GX)v*1Qhoi4QyMH*F{O z-V64zty&C%e|nz>x8=X-%Y@{o(zE>>@9KiCpXH=vniA0ZqoG9Tr_07W*dEx?T00-69X!>)j-77RQSp&Nbs4Y0urERN*@(j3Uyz2M%2t zu~j32%4A-^uNJXhd?dX|ZCOOD*@H8AX0KQWtVk``l2%H`Dxn4ya(9aRK_U*{eMI|ou1;W6b3U^@_4oq%$a?&=GqA6h1 ztV4CcQg7No_hu?wo0eGn+}7-4I8k)bn%f@l&T|7vOdiUuHrJ)2Z?Ip&8k}Y_9;`-o zZQEi*fGT|bvsdO*KarwsgSt+OH4TSvjrsM<25JstQY1GWCRy{lWU6Nr!sq^uYr+~9 zz&2vFUoU?k@yb#65J!)${fMqU;zY3GXVdXq-1IxiE?5>PURff^`WsRZ9%=FGqxj(E z0({|Cf|~bqUBbaQ6kx0?>0>K*0jJl+d%)90;Fdve$ZZXEY288fyn;}|5+#IJAm&Yt zB(Asi!YkkJ;==bh!XxvETEryn{aDsV#&P?bibp1jwQlkAQVz=0 zwYMJ)chIkXy(W=u)gfGd6`Qk7AdcHL_5qqmxQbK9U@lcZa1g4)?wG&4qS)Facpm_U zU?Zy|yfl=yk{=X>Twi&zht!GeM#b}&Yq6FK$ z4~xe+RL+~rla$V1PNaV@Y~vMhfTSih&ZE&xAluv_Una>hdh>XXE1YCA-;;S8BeG%- zwE~h06ld=`|CvdwfE&0vQ_Ep#Adkc<;bFyO*>Z4oNau=4>`>I@%e)}cP3Vo;pZR*Z z313%(*JBBaBh?1Y7!W*}b*$%_#!_IK<|2}jS^PN1ek+J*SLy?Wsfz9Ib;m80w}AGX zNyl!s@->R|T=Ew@T%dxAsFUwPaarA>D6B)(Fi{*wx5r(NlXI3d{1V@dn*eaf_NPT^ z4=Vlj#}k3qN{>UgO0hTW%WkD7=!b6ZThJ>VQ=M5FYYht@o?j@&z&mKGeA=Mmtql3iDAC) z-LZVRih%xP=LMQ;O(zJ`*U~n^WKGsBT|G%=$SYl9j>i=Yh2mG+$xeqZpcv#(&>kE? zv85m519D~syQ9FQ#XtvxRQq2yL8t4>obt|ZPj5Gx>YACZBZDN8vNg}AJ zYP@Km3f{vrov-+8k9)(5)>0luKVc;c+nTTvH^)qiAzqqJrb+R5?zYc=)@x41xwRU2 zRm*vl66AKw@7!ySQ?XL`k`(B95O(VYxolgESp}!tspxZp)YMT*)6bixwjb`t8^6}2 zGps!x&SgyAe7YY+t=Irm4q9uZcMdG{FMR72ExqFlPJInn&YiwENIk+X+GDQut|=a~ zdGNP_u3MYz+6#Q*KlJT0{B)&Vo1iPIiDLkCN!ApbdeAGJ?~1E~KC6RlrMPZG3l>A9 z!J*c+C6;-K1+H;~1397cA|ck;q1GiO`|_{cHuMjBXBVQYN|Kw)a(%lg`;0Y9>RE;w zScc%JSiTIP#2)we?q>T>h`b4qG-7K4)K(O_wjeC5Rf^RzZIN3LG&dx@%PXaEhfz|F zQKQ9lXP22PO?(2%PN|=(mw@s;^n%<{J<;!>&7|y3;lQv{clx`$#;QlD5)Gr06`>!z zfw{}gdgoDY^ol-#Cw@Qzsu#<4burnp^&8HCuS-sHSi9`61q}5W>?WG0` zm=E7Xg@d}DpA^;0d>~|Tzj`7T)3w|w%_;T%CW#iqfng-n`}{ggrKf;)iu5AFxeJmV zF{ZiCRmx}g#uGXZ9bWr3Ho3#>wT_b=%*cx(x$m6rer*!O$Z3A6Ht!ykF4%43vqx4& zQbu+G#f9=nKRfd}d%7-s_UX)c{b^Or>|A|s^THqx8?P^Di!>ooD@BXEmDkrEXrXUi z%QH`=m3S~j9eA%*q14+9VM7heKhNHFq@?GC+EEzRNzA4Z?08kKE?p zp9h4KEGT~1ZeB=7H-B;E4%@V?Y;sh;jP{OzQZOFz1X9q+B-K)|%B09D#*8b-u*G63 zXtgjcbDNw}-bC*9(K+RkCKPYdSLH1*;U-3yg-&dZz(eB9fTm`87D-y#2|5W$l<>AG z?K5*ECz7?Q?xM7&J=NUXsDv}UW=h9%a2x(fF2!DYAq3<@bwZPNBbDQnQ`8_>DOx$J zPd-aFYe!GpMAJ0*y?3b>=&YB+QMr7_?DW>DcL7h}jezlCI7N7Da$q!mH2#*~XPunE z4`Hd5v|HkOvpVLX2D7C$=KDpiV6}Ok1C;7q#J=I@>4)5VIh~P~nFko$-q7Cd$M$U9 zJZ^9Je(=7Gsl}~|XY;g5%Y8J3iLZ?>4Ry6x6<=@gfr6{5VuhNktf-ZJRqIcs+1vf< zR6FY0fz1zeu}p@lvOKY6MO%BHZnVImjq;^hS_Leos`r}rigudQMXpXM)@5@827C12 zn1vEMO}+tE%;LybiZT%8<9A@H}BTd`54c7$^FCKEWlahYq9)*5bB*fZfipou?; zHJ}2RlrJuVNQ;k`oxv$;KC)I>7sTxWkRNI^ZL5dX^d|6-33~;CRy7)% zvU+?1L$EDPne7kxx!~e6=WXHQD(6h+%*n2XPAgk5m<`NUb?8v)P+Hz7)aq7R1L3z# z<<(TmhdCp_3C`K$ZF>g`dkfYV;6@>l5}#p_;Xgn>0PUnk*x*x`7ZSKFy8Q%{2$=Gi zAlrqyQPoKc;lo0wyoU)a!oaP7p(HbrmFA6Rn+RtjeoS~zYT)oEP_uLA%^YMwV2h%P zp1%jSKGn(SH8IZFGX3V@rMvVp{j`5D6V|&wlROjME0=a^ zE&Xr^TQ?wNIu?YuNkw|PdEOrs@Qsq&Xq^T@I`)f}UfKs3ERt`E*lfG6H@|X~u>Z-| zXSb?wl2$!(n&&YxyY0^I&OSrzan?M&AC8zt@Ex!;yEU6#PA+*ad0v8-ZkKLd$&VzC z)S61J8tR4*SLm7p7H8*o=nm!)u~%`6L-VVYm5&?V2b6We5C(*kXKX?!rlwFK}|Zjypfn z)zg(;ZU|M1RH`BFOb=74BJNI)6tiUy8wne!e0<}}`_OzZ?PYgIcMJOfU>N|WY48*W z-Ro$=;E>B?_-}a3rJzycj@!Ftmg0rC!*8&=e0S4X?~V=%>=Slj z(%dBOmNmp2iNP{VyvN<@rrykQ1H4_a(WTzp_8ln%K+kxDZ?exQUmbbpo08LRJkP#c z5lbb$;6-vpig0;Y;BDWR9u1$Q6bp1DrXvsLrVU3s6iZ!~qlQix?wohPx>83?;Amj( zm3p(#DPj!wqu+yU*>ulE4NX4+#6;$e^xEn{8}D&eVItF~jUD78RFwN~_e_$Y-ngg2xI6M>XufZ)Z&&_}qlA2Q04}FXq8MHcNyT zs>>dHD?&%2_g3D=Wg6P8#<{x+!eTP^sOV_9)|xuKP{aGr2h-;RZIM&dj~fEsb@xkO z!OuaLo))}!0aN-(KJSGgx9L|^59>;nBV=RtL5?83~>9z5JbU z0WN-9ZLlY^_GC}TY2oTF3iS-}iQzl+;n~4JD_9sfLG!RoQ;O^QSxVfxegD0S&hz7;hc3JV^xA$~)S0>8Tu5}SEQ*D`v3 zF%fghz&z|*B)0nSShBWwwSLuSPbnsi)Xge+8LMn3HR}m^C31Iz-m~nzb&93*Atb61 zVVCc@gJiKDxdGmyhZwW(i6Pm+YkFOI^#;O>RNI!{6G`s)0Bby&ho4Sx_8gM5-?6=X zEOLm}X5tMC?=r8D(Py|M4cf7E0W^k+^P|K<+WZoTC7uzpAM$vncy~G6xvOrZ=nWbe zSL;|3g;ki(3BT=rv7|3-9-o-I=2$iO0U!UVJsUmRlD>R*N>8Wy>_^_$08Bi!`<9X^Q(;!Z1cGVc2K%G)0P+!Z3b3cfshk@d&=>c6OCU#f8>Ec-X=) z6{ces>CIo`q#6_YJR=1}?t3C6RdvTA zQjyd>MeOW+wfREOx$B+~c0`LJety!}a>GI&58CS7A$QQqa5rg(gT;CTp5G&vG+J6O z386a;tr#yCZ(qHbgJ8EyS*6yv_7-9bVSYC`ze&lZ`2yIXP3?|t;=IBGE%BS?Xu)U> zst`FQ>n{BTBDsB5W<-I}9OTGN? z)gmVyjdYa}i`O}&z}&~|@HNjM zY)esPe4z_cLS8y8xC$vDEuG$5g_Ka1PFv^k))df3KhmUVfKF3KT%txK*bfMIKn(3am#V|8b~5`La}Mr1j%-g5w%xwfC$qB?9gpSm~w< zk&IT^b1!q}ifY?c4rUk>W*GQJYekyq$PVMRkBML7Y1NfmRL%fklC+aLi)_q=Y(?Rg zd5x9fMFC9(vi0Fuu49YUd)X*8i*IC~``+?=PP8s3YiE?0RED%9z=%xpBXTAgdBRS; z;*{>k_7U#&SJ0IsrU}w~Dzk;23HM<|b$q6z9QrZq%4B(1p*0!Z_@s+Dm&8y;z&+E# zSKr?wHasbs&Jz^<+eHoM0HvYqt*15Leojw(nrkTqZi{|UwRf^uQk6^GR;`KktdwUp z(PWuqHovVvK}DyTHS^{&v}3GeWXI--F5)Z;YKsjPVit>jR9qHUTf%V)Xbv~TH^cLa zvYP>g?M@*5HvmW z+Xw45nOcn2kXyukR%yZ|j?=!U=tVffc#q-~M`asy1d5D;^hny4b+TkC7P_ShG9Y47 zSQ}uWh?nePq^Z3uFnLB_rIq55x9Ow1uS=*r|xYp`b~|zR2y6 zIdK|^Gk-bzZr z>Cw@kDSeE~@A%q}hUx{v7!$g(Oxn87B_$mQ@uH=2t%@@O^Q(UD`#?ie*?Tu~mBL;7{gdD1y^`3~#?~;x&F*KC^N1T& zektip|5<60CC>m4rpSonkW{*_>%A2BdtL&Jip&stUV^c&@YcW?2d)PKa|uEle(W2I zHh+w>3^XFI7dJP?uZ|V`5ZE^LPjBK@K1ww|qf-CnPwmgi=Wj?T>RSfDWghg$PC_T= z#1%|JCkNnm190g%aOt^l$y8$r==6WTwR-JPua5B{#_Jc}@0Tl*R#^^yboK;XRXNW- zc%c8#=K8MlyX^yMUn&U$bu4Ze+Mqw@pnt__)M*q=7%7Kt1rsmcv%~RdH)h4LkEA(R zZ~FR6ycozG4e_^H=W#Z5&D)nRe|uxh*X0v)Pyf~T zcBtSBg@uVLsB?eI)K%_zQ$wH;dnNIc@Pn=b-~4;U73Evyx16wH`E4xD#h14)V;3;< z#uL|FJOdF=ZSP&h_NF-u{HNuPLcA`;tLZ{9upKOb>ujk~fD)kK@WTr{rJ zGS}^L^kcBM$d7s@^ebDbH0`o?RX|#E5r!(Di8;dE9P!*7A!#ns@lbNFS50#W>Rccm zSx6vRYl&Im4-^<4r89UV`=cb47Dm{SCSNRzftyWa^!$O{>%t*aI z`;2w=nS$g!nuqZZZ7mZmlZkhSA{=dcJ-J|h=bn^jYu!@#l!%*$%sd)*#* z%x8uj{e%k>7^KzJV9(d)CL-#_SsT7fJX(K5ikheWU5=Zl|FNvKCFj+a=9=2p1b}TN z$hjrRebu>Z1XT1 zg>JnE5d#fzCIvgE=a*z4=)Skev<7o}xz{|~=2}Kc7)OmckHevqm zXmKUJPJ6k6IAAM&{lXn6Ib-2ZzGyt_7t>2WVHULU^?Bvj%GQeDdv`DX1mV%Qj4|Qr zSxJ739tXRXdkIqrh7urp+Mr*N_9Sa}6t!w+=jHnF@E zT!eCoZukJ7Q^eSj(=zhg4VR7u{krk(DZL686XhH+OTLS}Vfe9}v60`_g=)*LC=+TO@<fH6%JwK9=^*S-UcE$8$Bc_AH3bSyqoX3iLKte(Cw zkVE!5L(gW^g;gS`O|*MDAA2Hz-iDS--4=(f`e(+&heDY>qAzlfIC)+l%g*&nah9hB z!=kSj>yIhHc`fC?VlLdOsdvc6!FvkcZATgSqQ+nW`zD?lzvvrs^Wc1G?}^_> zg$2g1Gy1=qUI$tRMXWwUEZYl2MO*L9=s-_cy{Dq*5oXh*uglegb0iV7C7;0E)i-mS z&HBM#UbQ&z_WOgww=d90#R}CvL`QG3@a!W!%bKV3SuBHe?6weFyb!;J+=Y9RKGOS)N&YIN zp7)g-^`i$>=7um{K=e2&Fq3N7r372EL-&Pkfqk>`*?^q@LfxETcv4x~d+ZbB+dt16 z+N5!%tOF)1FIM7z4h3&pzfSorb}aiLwaZpJ_BY&Yu5{vyZu>c1+g`kMy?bZWjflAI zdFud9jUQs#;g>0IA9}xmjec|C*>uW2>1+TF$gH|2j_-Q~KUkObvDp;ZkDJ6%jq2Q* z$vO$B1txhV6cIiB`;QOV7iv9Pssk{rUQ9&Q*|uSq-EWHmxj68@#mBgIeT1)4&)7Ks zzFfy~AoOb}KI$41?3t;%)FJkl@WfvV?(DsD6P*>$T^VIJMt@4<4QK((;381(?Gol) zHJcvS4vz*n@qJH4sea!$yg$B9&1lX)j?V|sRtnI2*VG&RZu|Rg@Me@DbG%Xat^vc!5{QHDMF5 zU(O?TD5WzeCOimiyi=N0yQs0#OF7_r?UbbD**KrtcwTS&+3kN-CTc$-F>9a4%jCyY zNorIokYB!)?bL0`iY|tTH<3hzl(+c$O*r1GEbigYvvaNT%T1fc7_d)=b{n(z*#B1n zU$cA9f;WZ=`GN9xRUl4v&@B)pg2Sy=3sV^Y1q>F_>C;QQE?Gfn7o;#S0<9ZhKYXOl+YsAb$62 zi~fAaVasLfyZN-~&aW#G5p8mNGZBB|yA1|wq62p4Q9;kYl@tBU(PGRmN9Q`OGv0gt zmJ(AAq#*!)*ubV?;4==69-^AeYOIhR+~b@58XT`ds{v%rAM6N5w&%&?IQC3fJ@xlj z^6i%K2-Er*SML|G?TX>Qt2)zbI$a;IhWS^rnss>U2M?Y>twD@LBX3@wGY#ic_Klo9 ze+B|XHW$X|jpU6Cl>DU!wS1N{brg|x z)9U(`>n&`Lp`a)MJ8y;{N9F~eBZtZ6pttjptWloHY`6f%*C57WH_ywe6Y_~orspVS zs+d4?{i|$X{+930u&=IX{s6`dy}_zgTZ~3UFw8{ZYLq80aTlV)ns2Okn^yR&$%wND zD4fe#w2$jf_L21=A4OFD<8x=|63gqf{=@HQ{s;m{?8f{4xu>$ddm;phBCpRM2QpoG zwLMZ9XR<7`#H0W+yKPwW!6WbdPD$QbzppQ!P82P)mghv%xu|67-4V4waq7jP*J03M zAl%>Mp`!4hfHTZ(mwcO=sdDLI&e*;f)jF1^%tGxgcpbd3Q;Ipf;r4e^xhkdckfa{4 zc{(KXr0}FrAGLWpGzx8YBfpM1Pk~?=945K_S))@)C&w28wL=Z-W#40jO#;~1(|5j@ zj5|*_N7o)&LET*CjA?tRdy;lic5rqkK2lesilKf_)UJx#49>Wthtp8&>o9W$Hdl!# zZSx^{w@e&7p($jqOpUZ71^4k840plK326oag?Ny;PP?2}T8y<$JHdTQjMityRt47y z(^B!DQnM5C*Pv%Q+GKD}s+s>_iy@Izjk7wIK)1Yi@?s9RRGc=koa8b;&-ad;*XL*<@D{6pBz6>^2-t4F1Z6<0DVqz+`Ln0-MmvAL6>xupi8=q@hzp5<}4tIKyttq zhyd!DVllp|q)cbR_oNQ>Ofj&7*cpIUKqqu2-{YO!YFbQQ6lSPp`PzvEI>v)3Wck|J z1vN^3CUr;oMsL z{d@f)P%|D(HOk|QEl@L_aCUL)1+@Tm(y37H@I1LfjZ*TLI?uL1WnPTpi@vM zotSKoJ@f|DNjJL^aUyvr0P3Xs&?7HQNHn2&;CZ5TGf6p4ddYrmcu#y!6gJ5(QAsvg zCSRtXL>&uMGM2lvhuVXB=z8TZ?V$$G_Rns9Ae8N$|9Cl6c-maE=(msPHLJwZe4Cw7f3}&yHh7gx=9056-UWQ_!#u!4M^b9 zFfbAZ%RD@IJ$ZGYV_Qn6GM7#h&7hUPw{)$%!#|uH6%g8+87;=Dm3$eBf~D%AoFdI- zUD8gD6JltcSfy38`Mie~2iga0hu@x>7|X`Wrmd;-d2{jtfDXz~yGH3mm7HqIr>6Df z@v`Za-vK}erT@%IrhS*g5Bhvw1Ky{mb+_@dX)oHRruB|wm7Hqgr>6B9+I(IE6R2I| zmYk?#%ln9vMS|m(_NsL!>I|NZ3s8eKGgSu9h7qX2nplR-zGXp9K)uzMDsD_}qdSQs z$+aa3RAo*4^(heaz{{l|CExNZu~fvgTTUuKjY?mx2<9CZE6jI|ZlA-uGIQCWpo{kX zyy&a-ccYRpTGHLYnSoE_3m?8G10OJ91YF64Tqv;upQ@euP2jGME>2wQ81RgSNq6U* zc2&t!2SpyiY%-BaMTO;kCe(ZQbS)&G21mlo(32?IOXQNqRFLT9=XW@q&W)6~N4?fM87{VU z%sAD=eWv5Twt@Rp$Lz>v5yu=#H^!^{I^_Jdf_>F)KFclWp1Tj_2rj#`AG&5Dg z(O0v%F4$P@VrjnS5TJNd@w&97nb$fE?w!S*#k}TLl@p%Y8T}dkz+Wddv9C4DFa4(W zh9#1}V2M@9n62b7uc`DE+nT?#&$94zpj3dnEOLRW38~OF+&a={y0l%Y2d_f92*djO zbM2)*3vk2^eV*6&hxnTmtNf7dxIWHpZc!oO1}C%vXLM(%=>74FTX#wfleOP|iqzN}d?kA)T0al`)N&v!1imSr_? zBve_S?Wfm@U~z1Un%^=-yl+wTSj7Ik{{e!ib$;_kIAiCd5{Ybxf!$)_#QD$M5q65M{% zCXOK^n|=mX;H7%DxUFi6mEe4O6{0voARa%z-DTSYW-kaJ6?@$^72G0$@-Cwo>GR=dnZ_v(&4yyT81%XpEM z&AoQPlC!AIt94%WEd-7`bKBxi*p7@pdrDa)r(2u9>b`h8mX3uC=*B_4o4ut!dyM#( zfArjoDu~XBicdEKBg)&24HB*cN*u-W;(#)-E-CjMBVBqMENqLS^P*U!&8$GYrav;@ zD@lPEw_O?=QQ9xfZzmVO?rG10O9THr@7V4X&Tw21^u$4$|2qhve3H1JOjAU>DF2Q~kduCiYLYWS3-c$WQZJV$)exCb91Dw7F~0uE*7E!M zOjw-oJ*Y|)?@(2f02BA?nbSP46r!lqxU`hD!T&O>R>SZ_!z(CT;A=a4h(tdfqzR*#tXhjhuv zO44LWY~+$YDQw(K(sCh>`Th`TOTk%|iDuzTBP8LnUoV1>57V9_? z=YkZS6kWQfIH{Op0*3^dY9r}H4mU#}nM8h!UMRUfjV_)}H)mh&J8}~#bk2(axry`( z5Ch2(@plWH#0E^^#jiOpaa$pZ{~y!mmRt;_&3W-f+1do#1Q!Z8du_+QemedHa(3Mg zeHA~Zz>=N7q{S3GMp=KdIc6S{{Gh~qix8X(F29ldO#?y_pi(oGW>WP)@#9NG!R4$F zr_iLh(mv3hA8MO!Q{v`v;&Z}BkL@2Zb&XOp#f|)d-nxfZAycTvfLlD)hVw)@@@0wq zCz^C#XKbgcO(qB0)1FL)t&c;*-OBUDv^gSu2e0%xKhYS8p+JcR=9kh#vj zUSeix)C2MnrX}A|T~>V}2oa>{h{yuHrD5gq3oSSf{RHPH!J9KLFPs=hOTmox0aw+Q zwS%PCMjYuFgxf3Hp&Ybz;+Rk`+eB5(qF#_T8g01>SK~^xtaUNa3cn@%y`+=OZLiZ! z$xR76qm9ffkRxg2F0l7&^|=j_iBse-4_7HB23vZ%QWzT;J08^o%c)S4`oDE8}} zj&)mco5ETAX>@L9dab!U>b0VaG&-QH3r7w^=Jfn*MP{4%1C{pW@J$@*^~21j_z1cR zr38)dl$XB71;G2d2`Hp|Q0Gely5iZARL0Zg%tnhfrPVD#;}7MfMNCXkP*Cc`rR;PX z5-lvPn(7B()k~x9gH7Wlq>P4foPqu>zt9lnF1URG`%ElsIr#5_j9pkjM>2*(Srh&R z7P5y_Ps)P4;a|fLABwPp5HAI?{SdT6g+ql~m22_Ovao#aG~a$vhvW!g6ZCP2tCW9K zP+@ljhew(Xlg~zrMSTsX-!Nx*pHY3Slsr>j>5G^BJ!fdS$yhzW;Fj4XYomB^ixvR`$g6J!E*PRartZDSx{=?<*M#A zpY`xg&evcx=64_MSL8FbJBCE=K$VqSua#Sls#E`lzZpE}+1oQew`YEehG_Y#tbo0= z&p4`r*rj`CJUBsOM!8SzjE{(sezbpmgZlxZ~ zL!F6TFLq#Zu`aHERK+=<+W zdeL(#yh%3mz;$VsB%>khb!kPb|K0P#`ft3Z|34W=miYAyURXaY|7TXTCaqX~_+PLt zZf9i0|0YEJ&rkmW+7&k}jdf|3XrrO$hM3HWce9_YAK%j61`W^2@rK{cm|i08st?Kk zHU#V9zC={~U-PDKV-^wvEg2vdKna)-HQ0kR5_ zl`kdhD=Xlq&#=g$@p78lL!ws+mI{WKbDdcxIR>4ooS7oWySwoZjIZXe=F5(g1Y)!( z&nsibdpXUUEF2ep9Tt9iHo5C9nyGw--L;Plpt>b}KJE*qJc`=QJSK|w?EuT(6`y38 z0}S89o`bJW8UANL7w_BQI+ZdyuZ$rp)J}2%;x~+RfqvQJ{$eCBaN3VGqeZf37>87b zRa7t%@3W*R{(CXXB8Mj4rh^(__ouq)yD(0O4;^vl!5G33b$HY+0Ua#I6uNk{F%`dG z)b7b4krexzBo^v06C73q+J59A@3A8TqZeKb+YGi1vP+vg|J=dtr*36-m*4L2iCrf| zb@)bb_eJ(&#vbVFF*Pv$^E|s_vU_VsBatPMny%7PkVs*CH{Y<#m2wJ>`I1 z3`3}SW(&z+6Yr%I+Tv8(21AH?Sz9TgEQ=#neJUk{X97!L(`GXQJ6em4M~1LiRoxE$ zOQ~wWLg+zC3rT*HOaLbqZLmb@LUwVg_DJzaak^W_^&8Uf2WBd%ln7HBcr@z;96O5wmo4VnTG=sWMETcfJNJUNoy78mTlKktQYnYW9o|VE} zs+9W?84K#4>WayZ0Y4q2pKK!Kfz)*C@!MV$obr2PG>dCi=L24hqT~CIAh!c|IHH6t zn8o#krnu`;*Dtgn+{~XOoEX$9K_RT`?BCMfU>Eu@J_eR|jD#dZ5ST7UGv^{b}tI{%oz+K;=|(F$SwZ8$J>*NLi>;y#e8LZGVWAc-;y zb`d%8`+^08moj1HfBre^sv|aJq(UXO%%f!KcDuZN7Yil?jknj)3gPpb9S?YTu_;;{ z52T+P+Ty4$B!QSBO(e4zyioSYeuHF)Lb*xCBe*$VnS77;mZgXyxUuXw7c@&w6mFVsO2cj8TsTfoQEt4@f$mF2|W^`zEGiycd+V``K491xF&a@ zCgM@|(i`F_A|_(|f#xK|hePQ@?P8H=(Z|K3zemd|Ag_=v=7M7es7g9RcQgv=U-J;b zEqi`NF7V0Z6)1KACtQjsPR@$fCymPAv%|Tmn}VEd1C<#L3(DoOs%oZ(ZwyRgl#zCEci`sd*$6-cQql zdW$qmn%slZMm;`GTZ?A3Q?Z__!8zDqy6s;2&#i+mTIO|R&aGY(G81p7Je#t0CccX7 zsov6Ogusuwnv;%v%Iyr#=cXl>5#@r zpk_^(cF4vid%D%<=+6-53xjswtNsO;w2jT1NjHL1E|OWqZKV!KF0$)a6L3pRyD-~-UMtj9 z4k;hDImxdk8eAxNh0jE_c`|-xfn~R z{-3BPt>F$PjN$3hrxAHs4K#g2^%4G|7^JiEl;KNdXlFfIPikit6{wy1Xi%fYvdgjM zSrYxxv#Jcqn^?*IoCZ&aFe#a-FE|{_D94;=*-YjXjjOcI zdmUq>yRRpgT=kyzs-hG+1)c4p0lDH za5}4*>g_2&jI3)zLrU$Zz^I=yY7RJj2xNcX*mniRg5npHtUm@kxBq=}g2wZ`;HRcK z@gQz>7ZpXj3Lntyo<%eEHGf_FMa*RVsa10d;j%o_2BS!O`MvW&o29&l=_>t_a|_`i z?UE~E^UZ45e0ML}DmGP2yMBR0!oG48KbB3z_NRA#m9E84TDQ~wGx_f<1O|RXB*sNL zRTi7@v7i8&;{&D^SR7_Am>lhMxRxq@TZ}U8WsP5>N%^XN6Srw4IwUaGS|o^G|HP5g zbX1sqhAg;b(><{Zz|EuOWXI zYU+z*a!r$?fr{s+K7C4i@b)&qKQ8uV6l0SKCbYAv&`Jy`c#yg7X;?!uQz}!t|Nw?A!cN4a*$kuss~YgFr7#dz9g{cby#(le=xz zXFDPjJHDNEWTsE7d%Pn2kTtrQ?Tt=(7^B_|hD~xBp4+vcAm4`1vKk)!qPL@0nX+5YvU=I)sLAXd|JwX*5BcU&cajAS38B6unMExZYYh12H^$f-_Jy`H^pJAu zrVHEl?DA4Cvc6l@7&hRKt64k#4q6&HyS{o5xwXnnr@wDHygnW)JNYy}Z*1iR{ihxF zVEDG4SLEFzsLij92^-jl)ZQ=rS{?if17Xb`c%Rh7 zA71S*{ws(L(aNdpwK1B;f9je8vV~JjDOp)c!8{I{Olv) z(UUo>$foFQp}6yd-0Zyg&i>^#`{2OokT*iaC*Y^8o~eJ9 z3p834!;%34bM$kcwd{rm1AWsFqXT;``;vN$`w6?4!jAg?otrOucW0>!&#dk!7G{+* zwfYn}f06_nyJ<(;NJn^sZ$Vh^wP+T8 z<{=LC(n9O)dV8`>b}?{8>kNR;7UBz;(Z#F`<6iHs2qbo@5OH0tg6*Kta|yj;z#w7Avs`;k8u zjJ;|TJA3!UKjeZoYJ)aQuzyouGf7FZ|E!ykU||?fDU7j4IPe@h+6C#>ii=bp5$XK6 z06?AsDyupI!S9bjVmpv-ZM!wAoV(aRS{u1GT{r2D{ao|Dqb=uI7>I>aXsLR4Q{mJt z5rB3VOi6#dfxy`DMiSAfOp(gGAO0+Wh{6lSjtmTPtA?(>S5YFJ-AAe-DPSec{B4bs zX_Wl+#^D^|2{V)~1S6d+b7xnd-;8(Z;q10gpEWL7F-^?>b!p{k@E0SQnEmTs-m_QC zYsHuiZKcFo&-(0)GtXL(Q{bqf7}Lrc5N3CSvS$#x>lqIDrd*2+u)&4&TwyoP5@Xcb z3S7K2@nPuYrpqR={6Y4|l(l;`2A8YzwkO;KC@@W!%NZSl&mC8X=rt2kk^&`5LKN?T*^Xl*1^ zK({#b6#B!LDrxW!TA?^@aMvW_Bsez`gmMP}N{Sffg0P+XpfDXF~~7~9P7ofYv? zv|Slf;_tuT&~+mP_*hQH32lDn!&FbZkm(&gBxVv zOSSX6Eeojx`)sW=oWvLj8K6l2=d{H{UkPKN$h1rQK&|?mmEOddFpbSz6kq z)qO0qz(0-jy6`gM93h`W0=%ibwgEi<5tX_2qleq{;1@fW`ATMD_x@y5N#kn3Qxc2U zgb~iTmGfgX6@os-9Nn`51zsY<;PyaQ^|0-Id@YOm)XWPLb?G^Fe9L*XvyhaCX|HV^|mFw6l!T7=f)Xu~`Ba7>~ia+DZwNQXb! z*Tfvb_WWVP!5>&hno%66Hk@j$%9HGZL+=gM{X#fUMNGKw7g(upj3rQMe}v2|{;;W7zO6BLQk{kssXF?JMSccD z+CG-2f!f4C-aZxgZ`i1GGgBXhsAe$Dwb?KRnp6qCrHR)_0!xuoKGX3PYJWcuMvKdPrJVJZ~3qBX->DWSvD`cJTv zs4e0jcJ_gtrwOQM$YW`Q?}xc;V3o0(CwHi}P`2codfgz=eu*3+KBs~RshjZE37=gj z6IluXCFvzn|5h<+y-$lrQ86EYKJW4*VtFnqK18+FdR}UcN367ei9PATwc~>3s8pAX0qJ@B3I{1snv=)W5bHv9AoaD; zLSFp(qmx~a1;&c&4JoR<@1y#tTbGvpsqUW}L{iLRYEF~|R~g>VO0H_k$k_*M0<4*2 zI)_uH+QJOS@a_j#jtERE2&kshrPUr|*%C9Dc%%MJS^z_M9bq^5I@}e*FW`f~{R&gx zE)^y;?P1JGtNyb`wRTQjeEeZ^LpK$ZI!fHcR>Yir`XCkTI(*U?9U!aUsE5u{vKNN$IKO{)Ez;`!ulr*KN)|F zWPtW|wcY~$oFMX>2>!ZF`n?Q>DXuBhLR1I2_m9Id0tM#npte_jw&G-{+rO8YtIRMh zCl2~IfYEp2GlF^S#^~FBuyT;tLIER0wH$+;Jgl?u5IgV$oHW$oD(ECv7(W31zgzsH z9M&=-tlFTQvBz>LPCLKB!^-aM6rM(1MUJ^NQJGg!r~F$B6yo<}W+P(@{O)ZX#_M_X z$C~75X26FTkO3Db#RoYBZ(^Icm3TX$#|btFGE3mZZ_YTXHWW0{EluStxqz_rgc5zE z+E7ZmViw zbN%v~Q;a2gt`c{D_GM;z)ryq!mSHX@cV`ks_y_HySvNZI zA|K@r)%Pq(7x)bPE%6bj`?qd5m^q!=;ch4D5cTW(lWtPobT2M5*3Vbwdd~j+;4hW9 zUI?lVopnN{vCAmcA*s6Eeeet7F(FgB*)>KXxpTP%pP?3U65mvDOTQ?bmjOR(TB_jvcxT_bjC0~9ivji*jJh42<=Jy zia|%pfOTtAX~Vu6ibr0Bg_+X`Q9UnlfeR93*hIONS*UJ?(KSQ%hJ`CQh8r~>98ll2 zJkPDeCV+qIGr=NmF79)AsM;dn$L9oUz!ukY`0Jap@H)++#YR~AE1OdBn$2P=j{d!n z4#`@J?H&?XHnL+!oswZbPYY>ZV@WmqmAnBrSub$Gcn|FR>CkUX?n3}*;JYlfnA9#- zCD3o?gYXP%SEu<;8?}3Zw{O=ZgB$$ANA5MU5hLtv+HPH~$}< z+2@7bhcAm4_1#)8jpyC|l@G_jmxq-L_T3*3ydLZp-MzX7cN>WJycg`vLBwzqogdH_}@_b;pHH26v6=zqJKbN&qF})b7)=oS~X(N5y_@3@3xA3>%v?8W$V%;i|!k=d%m zz$k)S)}_#Q>N81>rG%jP{S(MM`y9`0!jkoEZ#nK6?XCZr)frE8(G{OE-Rm~Zo#3+K zwI;7s*}f*$vLxx>pB2|K01_lU@2gsDdU|_>BIsc*VDb2=bpA47VGct#Br` zMsKa?<=o_XjTW?iY~EX4LLPKR|B!mKdBr33{JB_}V_f>)FY;Ij<=A_U)PShgu zz3DnIjJS0k4tIV;J3;x6d5rXG4P1EZn@?q z<$hmi6ZhVKs6TN!aE@j6*lhb5AoV~~49YmcOkPYjDeldA^@AGRn$Y9Z1Or5KUP~>r z$bQ_@kr&~od~iOor>H0Q<^`~vmVzL(nDpJzA12Est0}>m0hEkFzT8h`@&b>61tp=N zUKM~mFgt+j$w}Q8TATdAcuJ}fVn?Wz~Itddxhw@Jy0UAB5JIxL) zpm9Xje*q_X9p3OykpYIHw3y>ItiBM4B8y`I1pm zQ07O+bj$?g)8x|_G6LZ4truEK*b9ZBT8g5+HU~I!@3>5Hu_P;U9igEMUr)2SX}1!c zbLnibL1RyDNli2vV^(gZT}Cx&;6s^qy_ShwmPs-JiU?5V zCiBB29F*gUroTX#B|k;>ki*vykXUw@b+>PuY;!2!``y?$MeC_B%qw#xYCY+4%ndZK z97j0|DrbUXu9gyp}J;bwaL+^}Itd zd_w+RG%g6a0bxtBH>71p_5(8zPXzXfL|S9qmbsa*tv0kv?0vK^u%bM+wyGM3BHTJB+>mTVwNkD2e zQMocxs27a)$h?#3taFiAS&uZSlu6lhMbIre)YFFf+bKd*1W~C>QXElnP&C2M+-Kq; zwcsCbtk~tf#dL{zYqjt!s*#o&Nfk)VDXlk#e`m85l5)C|j(M~)nG((aacWVLKPAi2 zLUx{%v=?7&Ysak{3NbP_I&IU|f(YL;XouW?sr3<uxJ#e2)*XNr$H*#FJX zIuqHrpW8;k7E@V3uFzx&%kkq>Jw28AtK6`9g(jPp{IYu95(SSut9lNNoU(kFR3|E}42L;5PS^KyJyg;BP;Y2rhe8{mR3#jt`!pJrc8twDORfEm zR}T#^Kg_4lHWsgXbu>TBm%^ct9$FETcIeJrd&V;d=To*AOE|nW4y}mEI=tPOg1MQf z@81y2cRoU%3DV%a5?DKvb?@`POx95C$Oa_o-td}Fn^3KE<>}sJ^k)n8BX*RtUBSGj z4e3PktYX{O6u*Z)qh298EaE`}hx~`K!BISXsyL>jo#paBu>+THc@|eyi!0WbVtcF` za?T(9FP2<>vQKHC#J!qLF6DC{+mUlbx@YbcZ-5tkO{;+ndmfuOs zMALE0SewB5ZN&G9Oc8JCdDh8OCq0jL5%_;X6gDt!BFb*YyLzcHA`e3aLNqd)9PPIp zWBHRJ55r{MwT5?C<@dtL;I7a0vs)@IYa$e6p5!US+`I0ZeC?+kawaNmDif@iDUWh4 zKoN%4KyDX->sWtX64(5cKlGHwE(vsJMwr*h{)%3r;XcD6@4_z4|73^lFOgj*MBWrP zU1m+&2=3s+eI`X-4BHL>ILBM4DrV!|v3uCvf&0<^cfPxB6=lPSmk|Wm&^dUS1mwZe ze>PY3Tc^ayRRCVbVT<$y;Zx#0lz-Iff9b)+yV2$Na-;$P!_WYg5KRzc5G*ZVp-lCN zF&H)t@b7rUOQl&8T;Y#$2l!kuzj%wAEyAku>ET6yf_Zxy`xuL6{UCsD7tl4E!xYg? zSdu$hEQ}8e2vi@#2|{V>;omLbGl=%xpM`r$&{(%MAh=p;{0& zx7^#yAZ>q9++*S6QnlIPvTsN2EOGudqJNNQL4ISa-POoWCbPrHHHHUmImXs;VNU+T zcft+U^x$J24)!RH4zOo++(nU&(GJ}Jtw}7S)EZ(IK>9G9bS82(b_M8rJsZ0Rj0m5O z-2hy1{bXIxTpX^A`!19Lv&jhlEq0nJ;FS@`mA=vd>;J z;a&pb>EHR5~{1nev8cE{J zKpStMK-iA)y4O~$DR`825l>sXQeU)`0$z)7W$6z>4f_2yel2e2K~+lVp0rr58)ZWC zDt;_&ZlH>JBw&N$l5$CH+4HOQ3W7uOnCk3!Rml@1-$Z`a*LA9>!7qF~qbP0sBEp9G zel(>fJQG0sYvY1NU1A2CR)(MC0r7d4MZ+&IO+oBwOZGZpo9);uZxlzA%tS}Vnd=n% zS=1Ped9(*Fdag%4P&T9grV9~>d1(rd6K)4EbBNLLyNS?C=&56}g+clW_=&smRwMm} zJ->H{hqx09@6gn?mnbLM_vy{p<*$26cPEXR7_KfE%w%%P_@F^CR#W{VK)8K&GiFx( zgz7Rl0wLgVK^1=V(coM@)0)mwwmpK2j^diOqh-Vyj>AIx@dQKWpki={*l^sdol~*c zV&48Nr9jq92B?*vZ}EmM`G&>~*D%8vvFBL%=GdZV=t6(;0^4_O!UBU%4)o3MG6X#E zlqs}m^81F=JHD6Z+FzaQS@Iq2K>8K_`Do@LBgvlMSy6lzC%QarmxlPEIRiT-)DWtmlrJ6ac&irzVU(*OhbRj%=$Wi! zf0$up-yCAs=v{r~&j=iz(K2C-7eU^A-{--*7CULYDXi_vyVpwU2oVD+_555==?>^z z*I5Nz+S|@Td76)(^}pda<39p{F@X~P6|?Kcml`gw)Er-Ka6s@ET0Mam%RS$Y4(M7s#lsS-PrwGG(f~PO z?_Ert`D)%uwbjhu#ZlYdu;SlvTH&ReRb}VuIij0OZg3lPNn59IqOGNzs=da&#=i2* zO{<(KOY90~m6zw_pBgn=46xCU#|QQby;IelkZuhfxaW=JSr&dJSr&e zJe)VA?BmND;T`pvY8dXkAJ2W(%2$bP-6SW3ds)-zXCa7AJ4H z;HEf^Xt>7EaK>$-GqL~1R?sx$o#_81^Ppaw(yce`EEGfVy0P1GS{S>jAD;Ur>l}7x zYQWL=m=XG4$2O4v{KFT~0SS`T`)Oq!jraG(fwVa}qhl{n3o3XAQX>0C$prqbB{aEb($5cH<*TDc>8gAU!W@Fp78{4*Rn@wZewsD#? zww;qkC)SBIYra|Y&)n>*efg~Q4j^-!iASa(aOg>Tb&E(5N9ZzAw?5ml$Lo(5JX%+g zs^O}@mnd3ROnTm{TKN3cYE#V$R9x3GV^H|6Zc@8!`6g}puR~A2pL$wMzqCGu4_cf1 zyL$wmlRa#6n2S!9`XTL>AiQamLuh3rpMu@@b@84NPSe>fKga%Qsre6OME4DD6M+tD z8dqIISWo<2+DFqjzAe5j8}Tm7tt{pP!oR|Hxw3*&!dAJkeDK=b-+Na&>~bLhbGd)X zvDmG6XH$&POfw4_cDR|Be-VsgQrPRyj|e;IcQ9?ii8Tr{J;H;ZCnM=g5MsfJe-oX|wrr%%;?}INH`6skqhSw;Hiyrf(9#<;pHE-nP&=^CuxB zuoZj6%YMVr0l9;1HB2UKC-O3U2idy5tn)A9a9o)b`Dv{dW=EPWy8`AT{u^U+6d(I5 zqD2|5F7C4ue1dUy{claja0fK$jcMtkKp_Xx^_FxYq(>5yWOhz}NQdsh`e>nAUmq7(r{&mI7d1?yyCE147fg>R%aQ#V;Fz@K0GK(a z>DBRBiMPz6IR=-0+{yINwTBi|U|odc(Xaa79By<51ep^@E-xdQgk1Y^T^JXQ2Kd_W zE%~)D&gopqM`zvAcbq;LYYy?QS{JEA%Scp~v%@f5Xt=G&F8w`Url>@RuYC9pGl~~X zh*v1Ao{D_l2^0U6+`_k6m;U63zeH}By>+QNB@jlZFj&GYi#W%y0`g>(+t6iOV*} zUPnrvEec!~u1RltKvXy5T8?~4(qW~mZbs5!UFKq1-GCi|-D+C5AhfojciW3}{rL!7R|xN5FVeV?J%bx85B++P<~n;T#OPyA!O%!u^#vw7sFcjd2tc zOxi#KxA+(cQlZ3JM7|Dirai_rty8{z%A)@i{uw`eo8@1?dF zMk;{p)$M?Z5G+<%CwIW6k8o5ZzIo(`<>zs%qXKlnBL4E?EM@^ zSi1u3ilU!ZHdDy^87?wexET@HHV4qljx9_Q6L4M@Jez)(bVJ;>K!pbrp6r`kv!--6 zf0Xs>5}`eAMy$K|ck->Vy^a~TrAKoASRvBU(2mRvhRdyPc>ntT-CY~!4*ko#{*3DI z(&_q5p~r7&DDZ*rWkOchmRSCSfkQ#lL295@)E1n@PBloU_sQO6$k!M0>4Q3v-*8Mpy;-%(PHHrS*K+rr9q#1Mj1$cO{~{RK4}+f4nyRPZ&WShSno@+yaKpI zGC7oR5tA^CkJ?n2i)9G0pBqYx;)hA%DM0l!<=tI$l^N@c^0sa_-$5U8J()r$(M`&&cZa4AJmagdR~fHz^%QV1H^Bj*_acK7nb zX1NjM2|maBMzj@@IyVG_Mf&1!L1BGGN`M$G42?z33KCx4i9AS1e;(t2csj#@cmlh* z&&9$F-Epv%uDyIus-24_hUFCwNZ@~ETb(RB8$%N1-sTVrTJ^gaUn+F|w7H;#cJRG> z@;oK{^?(H2bBZ))CSm{|bXa$u46A5=qYZ+Uhd7!OT}fS6ZA}_nyLSv@@g&(YZEm=o zN-|ufd7&_+IX}@Py>4gQ?00g|FLYQUsH{5)i9kIch%}e}bL?&9)O4zO`H2Ec25CSb z1AK0ws4^T2+(d@}+q~QTy@wI(K41k_;Xrxi&A)tvT3rj6C}O<#L78nPq1O)zFoO=h zd72H3cwzwkOohF_v0Q~TZ$UV&ho0xJjcJoAzw2YrV6t7z_P9p*G0N6L?X`;bHI;!b zH+hu_k8PMLD37aU;uAAC>m4(uJqLq}9wOg;C6fbhtQC@iE~ohod|Ed_Ev2^Ekb$CZ*2@L;6XvfZ(?D%&5rwitaIo=^3Sr#qx#QJ_C#F^o!rlw zVaBTgwKC4ZiiP*PV}mqDfIUXETt+CpUM93uMqb#Nv%HA6Z*1f2bzfJdyfzfcBDIPo zGjqU$cK?d8XO)IGTH%>M4CUKHzXnFbv6S=YUuiQdQ)%|*A$)!`>vOZ@$h@6^`$YGg ze5zNjru3(peWLrUg29W3?eUhHd%WpWB?o=B#JSyJ^W-swIe4$tGlQsuuaH^y^-nVC z>xfq`@xW^_fA6rJi-=dRu>8vr&#=Txq|^6o;FPHlkHX>4f-yn)v&C~V#{}B|xy|;J zXdagvJ(N_S>9(=~?f@Kj`~6p|_tk}-Sy{|Tm=so78o9Knl%$hb`F7cO{r5Oo^)gwAaB)fbiQK*2Lf^VP zk~z{r&sE*?I?vh39A|F-$BT_t>$!sLlfZk{gOW$};oG*B&wtZY=DkOMf301WEMC$~ z1{c7Sc-w7u)f46k9$l=o=|p>^VAZRB^x)Q47p&(`N{dDXaF@+TtieC--d&6q z85&qQe54oAIg*2WVab<>D;6=s~fy4{jAMmlUj5F;=z~cZbQ467&7&R7&P?(;*Uuqd~|gF zu*>gX5>85!B){q`;?K+rQ`VKV+JlrQ@j0_C4;Zt}KdSDt>PT0);62;gx&`U1N6PY0 zQ*-J>gOi(Yf2FmmsLhJXZBYDP3Qi!M+3_Qh zoz$hJvo1b-|3!MdU6u#;TcIweaktHyDmW(lF>`hJ}?s zS%L~P+?W~Z3)!i6THnF)YBfm5sUegpX0oeK64Bk4GyZO&eD8lR*%KLW z{M{n_E+pd6`C0OssMaC3L1kH(7OsZ!^{oGq8l)(H8hr4CIzZbR^nQ(V4E(n^jI%Nq zkRH)8_F0~VaqvRR^;qWPfN+05D;_n(rW z5J{r-2nXH9t>1fZ%KPD{zJe|3HP&4GQ_LPtF8Vd8J`pJvDGsR|J~1g_AzC3uAx`iQ zVF6*50ahcdV1>_q_5tRB9|K$i6azd#WJVYw1S0q%#3H!LRDF`=k}HxAl3L_6sv--N z3+xNruI42Q@;BY=S9;c&T`qS(0?JiptaP6YMl>BF(hib^Q^w}3{aSCj1FDG@xc(EszhL;X2MuTEN5*6+q z9$;6@_@rcETR&+UnL_SPX~a_dpM^HA9{t&9I|M?e)VGh3QeU|GII$Y>hxdW$T(5%@ zCx=l|>(}Yk zS=BjR(C>4j1?}jx>eTiPH+wZFwNUG(`&zazr#6SOYiHh8AP)<06YVzdOS_kLkH&i? zd9ekx`E!~s`s_&`fkHrJ+0kz$Pr3XHsteISy*wPiYt%ISbgyaExQ4if)@L$%$pg*} zi3JG-oXDT3_Q_>eU?-dlngw(@Lj*(k9zG9u5RMTKAmh{KIUM+f;+JF6@Wt)HW3$!4 z=YhJ(jqLzASk8kXw8@S8@zIYH_nH5?Llay#k8dO+^@R>N8t<$5$dJgyH6NyYev;@6 zae~-c)Fb?-bMwPO()wkuFDi^`KZZcfpGJ#Ktr7X42X!i%?lK4=U#Y%$<=lm&$PsDQ za-P`cjdqiH_%}*XvLb^;6asg+6Kwu@d!z_a4>kcXoT+N2{L$|kR_ZH=(Kfzpk!gEr zTt`GvVvE1+)PVB=XSj2n;39Gw&7(oG(r5UzT8KaKBQ#9;t)(ZQZJu~Y`9n4AK$H4k zNb9dLr7_wbiIlt}R2+kd*+M#+7UR=#d^^OH>xB3Fd3+lIs0^~;-M7{oV&_y77U#yt z5|2ZyyyD#;fET^_EWPyIP;l7axQ2KOZ!lQ(WjxbH2dO`8vteADZ13AEZ5KoU?hEE_ zI63~)7bTc4QJ>~!50}6EeVi;f7ig+X4w%rucmGpJ`I zuc_jnJTHKqA3lFRWC&zz9Gq2kfi!@}357AKHq-lgT3enkMp=jgCZ-QB5(v>0XM{u) zb<~HNNL(I(IZ@|5*q`paZ)gL`H+^UPrXZGnopi{nhadl`K!82p+7y5eCU8+5r-MWs zQfo?0ID#4sp(Uu0y?z65v@s#MQt3eBgwzzHISV$jUpd_PItW8$6je$(Cgt69B4&ir zymy-j^M0emcuy@UhQ0ShnZUU5iNTBwMJ6D0QL~XP{t+34rRtisIqZTGoyQf%Y~H=N zCp+x`cMpI7I!TcikBnw5V%XL=@_^y_mTHmzxNb(#n!9$`r19&zv;Zxdds;PGfz&R@ zDczEzysM)$Io2VOruv4ssF?R$;NX851IJ-6z;7;?J{TJLaJK$v&KKfa%pl$Q#;B^@ zt*CsVB@KP-c<#j_TwU-Qd+W<|>1si!F#5Zikb`PHyUU?cZ5DhmE=MootlO%r5Nj^u za^Cx+hl=ry+_P~?{A7{wJTc{+x0@bzE~+NG+Qe5n@W`Td!UVam87W)3E>gM3KP-Nj zi1tkZ`a>zltV!Qmh9b5%b|Q%_*~ z_+FI5T0%-U*I!rNUstAwzafgb?D2XZk94%4xGfOsh3AF?e^jL6Q#H+?-sYs%mF%sQ z1NMb}o-l=!)GC?$PBioir4CShV;w32)mV}FVIrl+lRwi&1+Hz+_sp<7qR&S!IqPGd zp16-_kW;*hN<}95Zg>9v+u4|^z?sImah~z)`Ukalb(wMDx`KAnbpEJI)baheS8v== z1ET=seT$3`qpt}vTSt_ptt;laC306Rv820aMF)29fO2hYT~X{v@#9^L-jUauUT5zN zeLwOVeyDv`xQW-;H8_a^{5hk|o53X+O0;m^gPXYR!=` z?5F1D=Tj3Ljf*W;;A{~1eNYV2nxTOtq`M0F)(P;dkt@mRK>T_}RVZ7*Uz0`o@P zzHd6M+b9}~>#6VPvybgvFdk4M;`&VBLYSve1)DA03-K+@n?cAjI zLg%nC6GQ$$nCifl`p2!NFv&B`o$7;~%1Dn>QhRS~DhmLAU&vCVwKY3yd#>(sjANv- zf&ErgD4%XH3dpb>OGJ52-c9Jo-rw1JJ8IC^K(uCAVeq_@@`dqEVu0jyOgYHQE6*}n zJ@1?HqWNkQGtC92C*+$dLA1ZJl$ zazDhbNk0)^8

L0`~qG*PXCkYqpTzxpA+$FU;8z9vFCt{3bmMT-qwp-8}jPJubYp zXs2&_+dRnpZQH!5E!~Igf_@1dnefR+d@_8f_y69*ur9tZwaRzr7Ly2hxJOeWtPaK{ zUka-l*N}VCwR*G%?JpZCIQ}dt$0WEg^n_ne9N>4M_em#iiuarT_)T0EvfY(pXx>_& zy#10VTiFW71PtIsnO(}WlV4~h*+vY442mkC0HWNeK32@FTWiz3l8Pt8X{Q>_wZI9L zp71pOsO*{(_xmp;<$AR|EML5z*GU$ZO+Q_ti~3VsB|NmF|I5t2BPD6+O7A4Ph7#)0 zvo|L82j96c!st+dQdB8#u-CrQB>ZZv%zIrq3*`>vOgRaW81Y{=PGjPK|D{bTH@JRR zF8nDrn<>cC){}1YI6PeJs?rG7JebJOGKK*_-V~xoymoNL(5Q3T#t%?1F z%^4T&VPCDeo~zs*af-oXMnl|ps%Kj3DTgaDN8VoUe;R`MF@9+=`3)zcm54cep+R|D z=LimOke|3UWAUb6KaPCbCGrrD!=XeCjn}F)cjq2Z2>YzejkF`&p&c{B?)iQwnh;yM z1o^}~2S;wsiU0Q<`Z*pW($CP2`y~1p_&T zFQ{Wn4*u@`9+sjPh&HYWqv|K)?tME);os+2OYvNPmXJH^_lmQvscpHpzOuJ|LNI`N z89;_wW1eK4=H7G!MiRNV1sPiB^Y;at$G3Tt2hxo0#r~lF?MPBBJkq7SdiDX6-L*y*BpmfyeIXkxhXs* z&!VEls@N*#BJz%!!UFLYav$CrXZzt%DRG=kz-QZDTpP|b?*;Lay>1}q4cC|>TzQxC znmv-dn6!CZxV-UH)9f|6@kV{yG_qIYS`u(Qb)!_T%oyKw&}M4ry&^NrB(lXlTkLPG$VOTKq zr}fQS=_R6HGf$)IMS?$IWwX(^gaW~bq8q~J+23KcZ&~_! zQw&=xkgnFhzr@E)z_)@fgZ8TEQEgT#^K3%q&XmvIlo?;bek>fu^l@J6ZG!OnykFnq zc&IS^lto_{iJ951+m)E^|9`Lw%JU1AQo7k25Q$8~WS7 zrRi^Jx!qwt|A_Z>p686#fTzSev+g*O^64_48jpWHE68POgVJm>_*Zg>7 zpqw0@m8sqRfNCl^=Q6xA6?X#^tn74a{Nc45`_2Q7(fqUkx%%;VlSXu~qZSoo`(zem z9&T6Fy0vRdJi#!&$MJS{p613xG$iy__bQF9C_g}#0-ED?1Dxry)wM@vB;Gf}Z3IoX5+3g-{CD;ElV~a(AJnX|3&APDQIAzhKbZV-mzE}Xl+G;irttFaVyu=` zgzi(UvwC^EBkF&~!?CYWl!cIc4~5jE^u#dcI16YJ5=h8~DU3%AYbtz361;Ew)3+9* z6m6ajkd-dR1L<#f_1k|oT?YN-uH`Y{$*++l?l}DFW?x#_HVN$Y8!^F>@h;Rg+yJv@ zJ`-XuuiJ#d+y&&PLoLui*eo}wv(z3{xY%2{xlpyJ^#?y8`=Xk(Ud_OrllF`lO)%I9T6XCcB!4se zYhkV*so}ra*y*1vyN&HHTTO8C9(OH@?}ggy*@*7ywWGVA3Es69b}B&EDqw97k*DR^})y_ zyHOT2Apdlwt&+{fR6q7x^=-HfnSX~NflA>yjfC-&^f&X`07 zPh9upGthSVyk_wjh5L60#abfP@Qu0##}63(gHQ2ire6Vxx@}} zQwRAx!JjA^+mW+W^V;U_u)+c2FXX-`_H)hRFJ%M&JTcjv{>scNJhVEncK+i6*#jUy z(gf=Qi48*Db!_6f0OHRbm+T-*8-2(ih!aGRativuQmc4j3^!~c>{tl#kTT#l4qav; z4KM+dSR#Pshtu`_U03$J686p3A6DtddbZY_gtdx3WI?n9ixLZOWl{a77dQy#Jz+CA z?5~Y`$|=fY=$EBzEpq%mW8@NcPnZ^RQF0jJkT(ERcC>g-3~rvTiQ0#EMN~OzJ-qKl ziLc>75htrU?|W&|Hp*2*Fq$867b5<7e?fJwq=bS1uDk&8kS{Pm0CB#%2*NrvUd@mH zW9ZeGFNFudu^g0eyy4|B&sBGlBKO0+oER|=qmCb;Uw~-pX99!aW>Wbj?-AZRrZ2|C zw#IMOX}}$yjsV;i7UF&$gz`|g+JX*0;xu&fytxo7p#w^glrcA?amc4YR`wa~I^nCE zl~+rm+>yXk5n(y_@dMsN|5-9JwE_>#7El_uYsZ;Z3l|2L_Sng`7GGygZ?vjRnDUjF zh}_m6g1kp@uN<(Vu3cVNoij4{4@qF^sM7N<+alW!ev=Lp!aQ|b$#jD^QL)eAAE{GUnx*t(s-w}+y%wa zWUY`am(3dzfk&5r&AmRXM6LI;k;k27cdC@ji^hsh&_UgC%(d&6O3($v&XLRPxhecN z%2lWoxJ`UR{@Dq%#4P1lR1J*v<|EoEdm-E?*YIq)9ryF4cLEFD(VJ^x@3sS`%VU6U z;23r$Vg|>kyvuG>162M@-9yN3=+RhJeR-Qj!rwpLDVxy%zUA3rD9PR}qRj@d;zO1@ zQ$R1dFr=~ceZNf??#!Dw3!Nj!me=ZowAQ)yG^8%ozx@}&d2^0^lp9iPrsdT6Ee8}y zH~Qa$O?l|R(=DfMP-bGlvSkR0vY~Lc5LP*MJsNbZ+MsII_^lVTcwNcTguvyYS9e#17I&S zd59Ew2c1X>S{UW)!G&esrvPj545HT?EK@-A52?i;p%owam1FXw3)2AZ_Z)>YhcWiN zJ>b4=$MOV`Kv`Nz3>7BT=akU{+b+JiH#|_ydPV%%xWpZ{3(Ekb!FVfE`V)uzi;UV zYCiyDSt@r%Hn8b&Cr%s8LCvXA7BuVwLy-%(KioI6_+1X%ku9J>)wW{vDxCa&Z^zwS zpIuCx=jGE#tb4@xPXAoYD>>88{Ch`213A9hkid-lZT5RWR$_imW=r)B%7DTaiJ&>- z0e%pUGC^yYw`7ak^CiKDm%RNzs`_l}k^O^yQc8ZD5_;j6)4!_;%$o5%p%1HBxb5-h zw!f!X1~m-%$}V2CmjT}cH{a5F=?i^NU$(*SXQzE2O!&@F@50Bc53xBsd4clXPJ+a^ zD_iH3g%bsGTNHZfsD+x`65|n$#BUD&5|`Rzqy84;`R{z%bQQIWIqN+@>fe1txSRB3 zR&!hl7n8X2)FdpFMT=w2mnBaea&W zn!C=?1rB;#?hkMN58E63ZG`XzI1w(Ud?h?N7AZ|An2lx>psZ-25+l2#m`1_NVW zg~(Z!J4E{<92wG+(oB-iC9yu(1J9A$4tOVH>ngPdL$}G@vYe;SIye1z)nN$F)p4!! z@B6F_Pw?BfUrHP7%k$}Gu>iM8K|PmM0cB_x<)Gcm4{OM1~H(@>7x|(9mG7V9PNDg0J}!#3?XznRevlB9=?_IgSy3hhCA;acK~Bk zY>5pfr?L3lw^}KbAHK5M{9wSi&d$&IZjKfe7pp_}o#bVVdu)OMb%i{{QBdc6zcW@i z5@=9Ndw=URQ`{K!>nCr?*jpeOe}9k(%}rT}KaxQWNINQ6Y~gn31h_17%>36xGM-XC;w74=aa)4!`2qho@`s*pxZAmXfN}j87_$EF14fFAzq~gWL%7zILh1n zae2Q_%WUm<4cMexStAn^LRVhY{TRd&ly^)r(=+6~HrH3DtPCBl4+ec$F}@GIO7gYP z&^ro6752lJ2>6X`r8rmrO`YZEMDzSqbm6$W2MC!!S}YeNwso)bk-XF{gv@==a-)eT z37K7E943?9!+O9`Iwp8Rm&Tns+iZaunwF$07zlQuIDl(b%MZ8H+=texQv|n$%ed#`TxgEs%^JJb6h`|XNV;J@Bhx??(O4_T+baBD>`WE#eLI$ji?nA=e1Tibd< zX77b@i{BIoOiHtV7{xYb&`A$O-m?d8@b;nfL0rgf8O}4!|3VCc`NaIhdL=*#Wbnhw zRK5;kpsXyl=H@K$9!K33cR^Z*!{0hE7A5>)U)@h?VYICWekO}KSpxc4gIpN{a+h?% z3k-Ma48GWTS47#v6*RhR+#M>&YkBv`l=YoCpZUA+24)iHuatQ8i%=H?T#s73@|N1j z&jNaLE@I+Rsw3VRTrT<=qxTS}p_@0TtYKk5ZCdEqyC-D!lN8+KIwXQ}wKTs(P-o=9 zqoIX=td$Jkub-lolkUd#NN$0@R{D#91cy^G+3+LDGul#Q-Q(88-O7OG?AEjnFQshn z%xr`hswbsi?Z>mi|PcW%pD%eaeQfQ(Ptw3We@xlae%^QbzhIkKIOFHp6)^}V2 z)q#OP8rhBrD}$>+(CrUU;(9BpAj%1<4WW4Ls;pCZFcp{`)ctIM4K4-N0^8f_e{LaI zI7I}7ZU%sQ_bWpasCZ$x%e@GAiTbj&Navk#aP+3|8#})_$mmNGzhvl1AJ&yJwO-Fb z^H7M8ZbMOv+85`$3N+jTS8Pl!g0S+ZOVyL{x}aYu#`_?4Amjwrh{g2E)pLVjyn4nx zq=x-XVB1@ZVilcP*tLuC=epLf2P7Ohz(D*H>SqQZX8%B9sHsgWx|8{X`SUpM+#f!% zOJ^~wF#zfn?TuyIhVTDjcF7FFX`6%@g#3aJM&O5&*oz}!d^-K>9C_#go{k#TMq!xJ z|DFW#MrQ8+j%ah@!PNc~?z31gm5dtZ!-AaT9Yr$sr*k6&^l;HbcKk5~)PT}eXTArO z%rx8QJ%9qj1s(erfagH7XYN|jUV(jwP+`ey$uNZofl6Dcyl3v?%l}a}-SB^vZ9)HU zWo*~GCuFrl=8qKrPub?}|EFy3>@fy9S`mZ{vqmPN;m@6#Ccc$z#%=gciuU6wpN#E# z_FHU!8}W#U`(^4}pc&Utv~2=y(W=BQl}MK(*38MQwRB%9+w{1Ymype z!fhBqIgrw&;K!B@kN#lc@$9i~Tq)5B=}jer@t}z*xREJs$#`L}6vP#3EWH(AmrMs+ zS`;0&Gp}Vwb=v9t%y~dxI!6n3;zgZZ+Q&?$es|0lmYO(tneZ)$wzzSyfPatNT-|`N zrfp{t7qFp)84HQW_qUX?h9m*iE6e812)5h6?<@u?Z`CAJ1AYG#^S@8H(%ceu|1&d zpg_iABIb@N{CC;yp_^lAN)I)>3@Iw8vu^4NH{Za5X;hBw>gN7 zc86ASPQN`X2lv_$SM}39gmfA5XdtG;^2whHj!QhpN|kSirs;Rd;d;Ywm8z zUJBQzH=kc-K1ZP8yFQoDXP>x zgDfO7PzerG$3EgL*MX!#%r2c@!P?1fuAyq}$Q~e(xL09hR7DaD(BG4ml_E{#Pj{`M zli3@j!2hjzthv$*&6Ofj)3yhbJ?Zkg!8@|03s%FQ(@;;As$e}EpbO*{fJDTV(3an6 zV9Qvn%+Cy$^V>_{;g>*Fn~=q?&k-w>a^oPd5>*Z#M0IwEHb$Mrw?o_~64n2ahay{` zmX$!q>X$eo4;&;8r_tm+8ILof)ry${oz4xqiVuMP1=&PRUn1bO}sve`RFw(0j-XOFysLm~BV z&0{AQ*u1Tj>9R&eO7D3)4tDn;&1LH0hg=48_$FT%^LM-;oM+)jq}JaF-ett?^72@> z%Q-O!;*HE?HMdcI)a*zzEWhDa5BiZ!jcaH!vum6!Sx6MnjE#c`ID@Px)o+!u1JG`*H+f|7+hX_G-nI$LVhv1d1%=A$!Z=a*R3 zHAK^m8?%Bqau0JXe(L`0DBcyn5>{GTFf6;ZVVIDoK6z26u1FELxNf;^E{g)OaWKt8 z5bXy08AjxjLsW%d!Q<6IC7+8v+#6%(mLkh6s&=#&Ap$w!G|%>o*c?C##&|YV^9KZI z?b!;Y+Ot$|U`J;+8ujR9FF_wnHoxheDF+w@N9x5NrQ#`Y|L#}I^R>yfJd2y1cCm_N zHm=D@+!t~lT^d}1FXW`pk-uS}+rv95yIOYEt$aP@*;juTlC8n;a0eaFGlBg#t215= z{q|3WS;9z)_DGkUj}iOfd$3;17GJdm7rhb(j$nfnKDdiOzTw`j0b_5Dt8{03=y;{U zCk2!9gU7O#puO<23^)of6OS$C0~3#YCN4vM4whh}bGO`^^aGp>){>G~aKr0TlGqpG z<|G(epUfAPS8~t4v?D!JCpUcW$Kbck4*sMW%bUh9V@b;PP;lV<` ziBHcd-yK2IkxMvpILQca9Cjgq$4{A!nMJ=jaF`n>Qcga64#18OEpz zPT>PMuPERPZAInqBzLvIOfxW*z)Ylqpt z$70iW2GXy@?dv#F^vQFb)wfr$==bo*>BNJO*w3XtbTsJFM#5A8i=BMz&Kl;;XKCX>jDKSZls<{0NzPWK-N-T(4k7PPM+?DS72*-7P+1p+TEMJW$bwk(H3k zvB!kO#KacS%EDq}rx2y*xhEO_yo|Y+e9PW_68L&auACEI5js^8*-?M+n7c@Lh%vzg z;DlX53&49}UM$qOFCA-<0>r{7plJ}4aPz3TLQuDt_2{1SfqHHH_-dnnDZuUQED+WlrVH(UH#zGi4EPf!7d8=w4b6b4bq*q}>@W!gNQWtZ@4#?i zS?@MK!BO6r`~HY=u{B{Vtm4uH{0?XiONFk4pS}3wXfcP8N7JR_QV#SEJMV1^tV!?J zbg2Xe0ZPLvVOYFQ=lj&ZLlXmh0C{0BFbbZhzctu3#F}bMm;kR~$?zQ}jM#Q8S>)>y zO^rY@fN4T!oM){j!+iZh3OVA-oJv8y+Sj5nlcY2ljq8n1d$;@D+iiUJ?HKPVT2(HdR=CFa_XdfG z@H71_s(F-10$)&gb1AB?$sPfuDmr*V0PJuBj_lYJqQ7!8HjvKjYUcvmikI%P>iy4??m$#Vz zmeLW+wg&Wi?#xdoPtQ`D_#FAv0Uk#^r;~GKLSGk{OAT|kQk!m{C8v{rooVkMGDYZi zUWL`PE=d2W+56bk2ub77el4>;)T(?TU6+v*gxD zz*HXDmX#TC^POb>GU>ooR4|rCY#(0`D(9-A7f?d45qVItN18Su^LAOTktYwN`V2-( z2^Qv`^v5}Iqb5o8h-z*k3JQzIn>#@}ZjE~)`F5mvf5xWuL}CH9$DI=9!%fEd?K7<& z`WUX&9H0a@!c0SATMf-jiqV_58vbuldi1C*+m&i<<+?cbS9H)ncf)b}V4U7OuNK4U zBSW*yy{4lplPMuUhJQHI6O8_++W^;5fc?bFF3ZW=RL*8gMN(b0{{g|P-mFV{-oCe6 z)L@-1ll|&=PJ4@VsA}FbyLhlCkWx3-F*+Ad@$5o@lLNnrpV zNaZ0k!FX#^TBAP-tkc&7tOk)9-=%4leQzozi`a)`)8#C~ROxdkVM{fQ(s4(t#B0zJ zH05fT6V&Ny7#LM{G`)4kcfa^_%KU1KnsgpC15K;X8efOmxfGGZkIsHRP}ixXuE6S4 zmu}lLpD*@s8my#yYIarBo}X2Ld4*8g)6M!LGj_I}lFBbKycGIooE$qx7rpd*nRcDL zn|n=Kc2=(9yw`UwuXIK~**L#V@uTwpyv-SV;-7nLBdlqgJZzJGIzbU{k zYe*?&N?fs>raz`)G+Ap-Cvvog57O$<98>*4U&f(^PG53RjfcGiuMs8>Qq=e@e>Sa= zBY)1ArZ~aRkY3ErpE9Y+m!C+l0+XLluO^irepS-zp;V)o{=lS>UUO!kkyvxOy&RDP z68xlz^fa=Qs`n7KlW_D1Iuj-KfH;#Sey9g?3e_X3X`j^~s(PO_ATG6n>zKv+t2>$H zS>_RY@E%HodU%nGAbOyY%R>2Mjmot><^1xE*2-^cCJj}RHIq4 zA*jDDYUb3+EWYJ5$}ErNRLv}v=|f$!U;Xvh8V*SHHj-H}P)m6(c$-G5D2or$RC?dao)hTLh``ja^lY{(E*cD|Qs4Mp~S> z7QNEnA1S|S<#yGB2`wtOPQAv(yyuC3rB15pc12FA`;JR_FXsQsrB|hT)EfAjVff@B z-H~|`3$jy8EdIt-dF;Z_UY4QqOHbXNR`Rl12&x59iWV+I-8Xv85{`Pa!I=rODmCr)0WDA4i04h*zsV4?Y{+gD)89xV9Vvd5p9F)zY%TAf34NHX>`W$yJ0U4gkkVGr34Nrj z>>MVC;UOue24Bo6w|~YhOf6pbEDlRUQj(#hh2inCv02##Oe~y+#w*2)Ul>iSjE1I9 zAUKSnr>9Y~bkSJvEQiKRLQ?)hP$)o3XTT;fBI4h{CrP;F@ZC?tgefO&#A5JaXl{Fn-rkwo%6q5b%XI$0vu#MGi;hOH#o8aRQ#3~9d(}NJoFV?NOo|t6qxUqxm*7P>h~+$ZA1lyzy1=gO9qv`W(hYa zgHm79gzM)dQ$Mb0_w5X3L|Avft_=*;*PzSo&o_%a5qB^ccceQbe_hoHNa$38uwpO(D+qA^3^d`R)9gejJWXD=&SarT&*?T@!XQ(Nw!2gIx-?`Cq-y zfXu(1=QA{?*QIp=^>IL5Z+&m5+a8PYlFBn%zo<`9mX#^6TfcbYvhiu-1CL+&=c84^ zTdSpCT)`iifU&PZtB-=9| zU$c>0D|bez@{0NkXbH^u6{{!|p8OeVbv~5>9@Y=wFd@P*#YKPexxX#XL?eEVH4hj5FS&?gn#xy zNC}aytR&P!l0NZ5LtCu)6+;?6a20^w3)J0k{2Srv2vnfNb4>p*4J)G6Fi{p_;UDV@ z2H|KH6Jf>>7SkV$W^>KZ8GqPyP#8?80{#Xa66(P0{qepLs*56BuYLb+Z%SMjjogIJ z-JHAusc%Z?5KVl8`94izje8L#)P(y82;v?3JV7IhqHw`V0=V)5c0pKqQ5-HfvjE?& zZ@Bvy22l(y*bS~c(hngul_VMuD-vg>E22Ur1U1rUst;LqbvadIE0{Iab`?3bI5p*V z<$AT;HT8Ct1sa!{a1Uu`Rs7YJE0XQ1j%v9pIPIE_>RT%)52>%Zmm0mxPVF+6ns3WN zo}$DW(aWZnRTO7cUMp;#2Kg#9D|DWE`Ks0{e4a*zD!40Dp1Ovr+ACaMVxLQoditBI zKO8-DWWZ281wkrnYssghukbq>-t)@m13iU7a!+d#541vB!BrxQh5w7)whoG`dAmiE z5C{?=c<{l3+rZ!!+%>obcXtmS+})kv1b265aCdiiZcTpg`+d3Ro_ng!Key^uojo;G z-Mt@K&w5tx?mg89h3BLfX|HnSL&7VZ=Nzr#+5Kx*-<3kv{SnuYm7==+W7ohJu~+lB zI;y)>i<%j=!;lH(bqL-Io-vx1tT1&ia#8@0!h=b5*MnGXFN z=J=K2YJDY}GjNBw4uc#PX_cdDyCs)1(1+O$1C8dIm1SzPM}_!CCoFMN7z)!%dMBXU zB-8xHUpl7AYCE0^i&KmaBT)J2F5^?I$Vq`xP?tYVjB%1gM)dM4O>_xZWfJrAlT1c` zkrm9OE+jkdh=Et^8Dx^e^J82V>{&D=gZE7vlTLQ9FH2m)6_CN;D`3mWi^sy!w%WKE-sSREw!RrDF$?srw_SYuK8pv)M#ASZ!u;#v_gpoJ7#xPCQiX}13FlOGoHnG$&W!};;F=Kel zuwdT6F@@W(eBS6L1!^agT^}ihWT%kbFgyiqCzsudE-_>$y1~3Gv3N)AbEk2B;;$Wi zrjcf|{1kLem%?&z-godHz@@19#UWMoU#E?6=Ks9W8rW zw)9QP%Vq@5dz3P6@kVY$Rta^Bi<`&SH!hDYP%B?gBc0|rH}J2+UHV$kR>V$YofbGZ z)2>Hdc3TiugifQK=9@M&ugippg5@x#<)}?X1mw^VMM&hx4}@EcnZ+j(jm?<_nCX%k zaR{Y;8U`DN8wMGMeG#q_suHmiv=g=p+6mqX-wE0Y+X>l;!2B5=6do2H5*{J_Q#!O2 zBMseylY^auj05x_ZJ)g45#QjEq<32Sh2ka?X!jCd)^YBU)|#>T2(v883!h?-_RMA; zW!xy`G@16DQ=}Q|dmuq}U^^YRe1zXJ>in(f(gL-OSw?s1Gin{u9=j_YUM#H59F|bo)R)oEd8w462~<^=aduj9(W7J{KH8^n!+hQ4McJDlR`Kf9H~X3bd)PP5 zi^KYw!pJmQ%}^?ddr2S8=egA!sAotUWQc67?<%#iMS@52yqAcBtNzkaIJfDvv2K;K zP7&_gCftsjGxTaUapqdRS#%t#fW@ zUeY3k7%yoPu6Z|-Cbt9`a4u%hHgYVe{s7`?Mt%KIFg_pvRgm3k@eL>bjr zd6^mBYK^UVV0pvR&gls?f)dRjKGA(^Rd}1aEo>;(|F`^xcJQc)Zk5yaD}ZBG*dLB7 zR;t_QQ-nh$&sLn<33Me~tsn6mj(V5H9Ofdwi90H1`|%t~hA(gqDo{WXFKjatZnXC_ zE9sy_KC|E;-?j6ysLu5*Od*z{m$OhyiI#uIfdlA$z|iugoT;C#6}{fm`2yI6;cMTa zb7B$Ge&<;@U6DjPR%31%JObH9dEC!7X<@6wQn8s^>+#X=M(s2=s*f~=HDimrj1#TK z+TG?v`3O~kT1YLy?EK|{0lMkqXXB#HAZ89`q!7O^e))Pqq4muI8u<=nFm(fwlgQ-)*b7vP8G^GwX~9OxcWBuU)ULXYB0qT-su`OWrgr$OFUFaU7?jKMm~f*mnuw z8TGB{gjZ>AV24-jo);A_iNx99HjVwtUwLm;aDeXt;!vX%^Jw)K$zj?Km(VlEph>dp zLiMx#1Ya%kc7{36|^}8-b&!D zjrFe}P)BDJn|%6jRXC|*LC%!4>iq1GwBZ`9)7oGmmipU871{7R>lr9t6Z$YW9y%gBakD`v#Sm-m1=;q z*LV|@d=wH@Y5O=T-;sZyvbD{kT7n{&+7cZ9q41H}Pq+j*#X8s*GZn~>D}6o=Ef08` z?!OCQy4s12E0=~2`s`a78CE_a*ze8GNWK+Ypl7*$SVOn9aae=072nk8vL!wea$L#1 z6|-w_p{INV16@IWvt{;R;EoNyPR#}jzxf^SqtHD(0bnej{9EKjEqA!LX zw_*f_9@O+3^BHbhqVC{bF{MzbRPRrYFzmh^4*49Xd?lAR8RcMbd6hU54e7f{7x3<*=qy%Lp?dV9_`ie@*gSIa$gm{)42=NnCPiH!@c!#l}=3PFre7IoG;Lzp=Ms$aN z725T)BT)Mtu!oGVLi;gbR|S9g2M^w(QI~c2b;|eD>gR&Vn+%)xuh=_c$afm9?O2mg zI}*q$0PZ!3{kI70zX^SX@RnuTb;Hk;zr*!iesb@_Ax9`N(u~2at%|4o=%yN1Zyh@= z1jE+B$P*><<_ONk?~3^cuaDp03k?+48gCsma^vg8iT9~<1|FMuy6se3Ei5ydR!r{f zbW4^{w5J71Au>iey@GYZ5_d#fYudZxP=_y<^z`;hwpLAR56=k+gKV7F?zTfoq|j|; zcgm=*!A9HMXx+%(cSPvCxjo3L8-eEM0z~Hm!cVd)PqKnfktCk|7`$6Sgv93pj2nTv zJ;*&lgo6~G6k1QRK6hEe8-Y)+)LO%!vu_~oh@`ugM+SKO(9No0U;j$<_^v?}sKfJl zP?zHzTvMgvzAw}n2(Pz|1EpZ&}fgHOc zk7DAyRBxxoqtCDqV`UiI!+kAdJjUYtp&$>up%9OE)ITkPoq{a_FnU<}#C6rr;&vC~ zo$Kb5R20qCo0ZMo!V6oEe>!xB*D^iMBDao1vC7Twm2bFm%1nONt%~Y-w^22PvBl1us z`W%j?XAa#;&pe=nq~5ZQskU9eH{SV!9(BnP@1wWk=ZtQ*&x=)BvKqyvp=lKyn_v~+ zN~RfIys%rQ@ScTGy(4E?jn((P4Yj%ajf%gkYC%ZN> zgPk7SgtvL5lD+UtDMdOKH<4lWE2Z_A;H1)t;c+)z+|7@bQfD5O5u1{gGHV}nQ`Q4@ zQ#M6(Q#Sf^)z`>%)i-D=OFP-!ha86Y)yuYNb$0{pf;2yk(%y)(Ma&hiH|v)BU*5-? zrD~g#;n5$nepR!~u3l1~w2jH#UWsQ(p|M~QQnM+lUgDgz1?O(BTrZN~(T9@5ZYKGi z4|h6a>Tne^q*H_%q4icFY{Dvi>{nP;bBFGa3uk<3GrqIBD5V{n!t#^H3-L{&7$)_g zt-6Y$d9ivF=_r}Cvv^A1depihC&?{`eQ@e$i04NC{w~5qmMaSNb)&DE<_yT=hgdKX-AO{wnCI4QAF@8eNU>PJZt0nr`l*s#(hMh$j@?WP-celOasS_jq(EbE+DJNZ54 zb57!KkJ{`uW;A9rTrQ0*(=XkhymP8*nqEG6**dXzYI0kCKKXiE;Wov6l71D6bwixK z*^s^~#C@ULOspkWo~XP;y-wyr)*`=Rp=EOFNI&1yMZFn!J?OIC0>6@`B~%{ml;BjS zJYT$_czr??ku8WWf=!t|3WjbJou}ZuzXc%l7b5HD8dcdA4ltIcnU2YE`it179}JK* z7IHmH0zE^b)GV%yBk;PE$nJNi%2}S@fukyz=pD(DF5zBQI&? zqfXE=BB>+qhSqlB@_5L$=&~fSgG|uWn8G`e1FVMh%ghNvlZmz&pVv6Yhdh5g9W=j@ zpJ$)RxeU<=F2zPd#71KBc92C!4nu@ZA~`Oqwk5n$%iq2@{btu`vDHi9u3V>1~GolHNUOoy9HPs-(Hl5jJOx*4WAPU=67 z$Nmj%bh=>QHIH^UvKD+@?y_G1ct+35pxQ6sn47KAvz%i^D2_hVT1%kTHxWMQxg%t&s;9$K=L-9FPpD&{z`8vl?nw1?2@c-yG?a8nYKAN8!e9#QK&4vxMi8zA4k!d#0w)w_?nZCEUIL%*9tfzbZ zV#6gGQ$K2=(3L_KPH2K!70UvOx-x4JYMe?|X!45TSf*)E27d`xGf|kar<7ShpQ68Z z--dl1mU>EQfb%=X#OrV!t+Z9bK<~ehD*h#_)A!0 zM05R@=q;_&j2@sD+~E^O^Zt{_!O_n?LqFaV@22OYEU9=Vn{^R&N`aG20hBt;j@|pv#1Fs@-zRR|HaV)uml? zjE!cw7j*^Ao=q!^xKo#IDgwP?HjJ_R_i;g&NzbQt)*2(d_eWH$yO$IM4Zqx95_s8q zF*n?G6caCnzM+g_DGGJGW{WY7Vky5QIQJGZrVfzIpdGtCvEnY=de;`uOFiG(FIup#j=oYc^c|d}di8qg#V(JX^xY>M`LB7cJEQDk z1yL31DClH9*@CjMu)(Nb<%lW7-wOq0{{M8bt(kD^VUZs-r6MdLFY?Y>KBL<;OLRS< zsKuTxSXk;PM#UdXQT`{{a;|7U9lsjcLgWGoSX+w%BjqjPhpG((ts&>tyW}{Lw)C89%Q}(1NpN=QjPy~A zEX}V75aX{10tPwiZ-XYu4%4#i$4X)ohvY#l8KYIUjt@lCv2xs3-v>g)u%GzZa=@7; z2`m;FrfHMszoIL}w&vFeoX5KRf;2ty}p9v;8fQEj5+w^WdAgQ=(6(4|PkpB<*~^jQBbc zLqnxlQWTz3cHY2IRXYq*SVa(f*S{S?VL(NPPpWnO+)WI`lfLXV(JZhR!7$I&$F+>F z=N0A1?u&FMSI4h9N({j7)&U{7nhK7>-H0Znb5>E!`tKe$I7O}&PVc`6&a=!V`#E?@ zcgyF<4pf1*X`!@OMnniDr{=pt5y6)wv8R4g0& zLea+k_#w|UJaOx?LM^i-U_G(jQTOulHy-=U89ESZL$i50PZ2zo>_UfIV?1-{K3Hj> z+b>Ip7i9G!Bv`km*%RtkEzC_^m!E?bqFqvU#5hQhLd|9V`%D}J-Nj#VO6cWr=o<(~ z#im!VnJu*ZXdj;Nq4U1- zi-84#FTd5X!LZxUh3zu>nyYRt+&%k=sU30FL2ElJ-wfrrnM@|m+F}>WBNw@qa+2pF z)uyFmP)3^}aRZ+(qGm0ZMdD#E$xb_}?{zqyJsufH(rCfL{C)=YZ;tY{#9czKUGkUV zPJq?h4fh|wi-c{Bq}^(YoO}n2B=omqhFQZ&N##T+$7nOmv?mlR#E1k z3Mc8@x^0cTFW*OGVM@ux`tg0SlZ+pBST`b+sPS2mTqN%~I4&6NK)1mpY?UhvZW9z4 z35_?OlgJsPP7C2S-idUoVW(#lBL*_E=sqoQN6I1d2^*LLgOd*jVI*8U4PswcJKuI7 zW_hD!T#B^(Dh?#UIn_J-diRxrkAOT7O5bLV8=ZfhkH;c_PxSm1I;;Cfnzn$ajDxaI z2nkA__pG4F2IB3>M65C&^-;W{02I)Txq|cUdbv#Z<05${C+f4tG5%|;v8L4H8TKp) zD6_)C!08=v)ka3>1=Hwt%tC{f(X?VCQiz25xH4;(Y{%>er#fqf;6f33QinVWTkc!1 z>#o!Xj$A)`{AeS_!0Df4i9NHeDPCZB0UGI|%PG5^8_HiW(R5Wg+Ywqw&s!2Ovp9WT z9Uw9)5h-@q2&}V68q(BXwbMs3gqMYl@82%WJOtijA@5UAcy28v3oU z#G|<{56hy1mWyma(kLjH*g(pG)U?+hG&>lG#PB7p?6C3n3-&55U)`OOO5_aP(&R{- zSy+Wn0;1|l&^CNT{oUU9bdCCh?U9+1UIMP=W(=u$?r#_;OQ*sVYShbRQXFnJ;wkkt z42q}p;k&cQScC#U{DJ%Xr!`CHp^WcjG>_;0L6~nD^DYKX70%1D)fzUAf9xx(co)9o z`<7=GQ2eS~@t`I(upx~4RnanYP#2+yPxdW`x@_LvtnBq-x`(HTb>r%U#ABuQPmJ2t zVhKir&oL3x=YorFa^TL2M3Zb+=o>` z1g?1p8Qtbkdy+D%s+5xav3FbzpkNkH)GM<7$kZnd$>x$wr!{HG!tuPB`}VO~bAoBK zk=mSyu$=%+m7b)y;XaWD_g zdNSQK={KtctyilrEP5!DF2knz`xZ)XJ3>B@i4g?PyM>iG^0BKN5i36PISFaPO&<1s zY0(#KVBPb7j?-enRpA@&3)1?T5o7zq)<)L5q22Z^rzchJYdRGT&fK*FLC8~L-xn<{ z0BQSD14qNc;saauHxCbu=AUIe-ng;v-aup1Ao)dqM9M`!QU96a_nO=D$TYP?Mo_!+ z4zK9Gj6fi3D*E~C zR~59XLgqvjp4meExj*)7e)kL#=t5^(XeliuWJ?h=T6XAZ-qO88-6dh%3S>Msf2rqnNAqZz^lT~mLAimF*H;4KAom65?7Pgp1G>&rqte*aBE1Jda zSA~5K0(^b3kklC+46b)=VpP71+xmp&k!1Nc1t}BS*!*ourxz5e zM?Y^E44@HEE)lvIosXrZ_|KHys{yl%x=&yhQcU#m%vG_6su>PtyiH8Mn`3HW+Q(R@ zXIN4TF6M$EhS zT9emerhEV(E%G@WWqvg8Z(yREQnAlXV(lg)Mi+67Sl2JzwstK)nwAe%3`*aB4phI= z-h!3{ILeHxZOPoz+2zE?}9jZnZk!7c9ul$~)Rtv5yU z_Su*Qk$l^Fxo4@vv!K~IC|*Ys=Z<7@T);2g#T{fHz^HSWjinYCW*;WI z=(Qg+i+h8LNZWs!B;{#W-*0)Aa+|Tn3PA3E2dLcEe-k|PUg`^3>|2U;UL&v9(3RPN z6DODl`wdbV!h{{15*(Z|2_6db)YXMC6N=v+jU-J1ysIDhDkaBxm|BL*QrdGcl_T{L zf42JJ5ppYnT)Z70foOP3gDeQl13v{dQq-+?;vU=&o?TkcZv&FHaCF@Du8ItCJsu}I zZ-_z8y@OJ>&btKX%4&DnXE${lYLmJy>%xJOwPCVi9=0K2&|D-t$WXINV_Y&c1Q?QB zmz8MjGRgtB43rb0EoD&bnaAD4U)Ez|*d~S0Yyo=P8Z03!xZL{>4Zj55YG*3nhwgU* zhJVa_n>W)b4JJ1RANoJNEmC>iiS_o#I@ecMp(NZ)8yli@$|~h|%|E1`s)>;Mm~z#M z7%qC_m3?a!wk~sJxFT*f=vL?*nOlB_7zE9q?G>T@`x$YuO*5Tzr`;Xt!uzVk-NPyb zS}nJF^A-2tm5dr89Au}fUkZxrJ$b2&c7JW1Y4?R0=bYprFX5^svZ~|Z!cd@F9!W;o z)={=ZG6M<{g~dF|6n#umMpx6=#^3S{*j0Q#tZAOH^dXJF^|NngS;P!>a!=JQ?s7P; z3*qq%P5q8$Cm!OLP}3u1F%+WCg1j-3w*!-*L)8L);?iAa3E?C^6NU!d|;5i{yNr1!WAyArjzLOqYtm_5eBk8u@eJHCcFv#@X{E^b#%3Ga%n zY|^V^5(h-1BJ<97Yt3XgZa)D=fLw7!#tQVFO+f5#9PT82B4tYzCw>gYg@nG@VpDJu zv<|g{8ymz>yAOw^haKKN9VSOVz=b%6awiYWL>-RTm701O2pl8w%PsZaJ>-+cBZFnLc7YSk zo?J=^!VR{SAHy15(Q83(;0Ta?`Mo25dX3Y++RHv}CbDvG!S&>M#L#kMI4;gG>7O<7 z62s7-Rn)|%ZMhgyqsA0m zYg`d3PqAib+*S)4r_sb^fG$_g>lyUT==Mbfq@QACYs7KVHe^Xnsh0w@=j+h-ICXY` zT-zta#h))xPo0t<5qdQh;;G#3>fiqE_bRv$TD1?OS<(Ux?(diIjgZ&ak@(MiS?nWF z<=KaQ^yTW-E|27T{2pXHbN&V;o$yvw!oOgmG+(8*XUX z;bGS?MvQ^y$NR--4ICP{fHxt=EZv`PB4}TD)A}YnV{{)-e%KWwVS7HUzlAQpYYD(< zO0)e2)33AL!M$&ZJ>LC9)n!1FA*m$z?jVY(TKCEEXRU9}ZjyLxMnzkrH6}wU(F0_P-#LBF4JeCL`zWalmZ?$UyUSNwDK5;N_k_%3-++v9!#d1 z5{{G!_9m}CaEM*3t%l)Q--L^rwy0V-mE3K=)LoUsx8CK-GwyU}T;#kIvdULn>7I|o zIjo-FQj7imPD-nWK#Qzj5W8)c2LC$yX|1XDywlONT?t%MAJG z25hMcwYMYTcAM_>d2_YPb}h#Gg|qBKh+Lo`uGSIJjnvS0y*e-l-toDm58um&Yjs3t zM0f*BeLH(w109P$Ln~cVM0gM*fC2Dl#KlGb&BfY)Udq5;M_(Pw(X9MCZgrXJuaA&ye~T?|Vq|P@_rK0y`^V-_B4>+# zJUFCuY|RYxdA`{?7;w@5KbHR|hyec|JpU)j|JL(===$G!{tsRMThBkAC3!(%9xnR- z`o{A7_cz+WQlFdHiI|t?e|{1G|2+xR0SxK@5Cf|w0KlXU00LPw0RTo;bpVK&831Bp z(gXm2%<2FZMi6AgrVe0cV}qDNMj&&J52*CUYC6EpHXZoik z7IgqKJESHcJBvDii2<_8!~|Joh1ABx%<``-6EnLy0LTPM#l-Rl+8<}L|5Tt=12s}0rNF4xVVf&{SY!D`ZAclY6vO)@FgY0fzqanTE# znA;oJ(hHmG*c%8M=vnC-{CmS-Vf*`j;hc*0U3BmJj{e#P%6G{P<4Do(d{FSAh~gg+ z0ZP8`P~^A>0)oEppr8=Cbdc=h{N5bGz#u^zz`%U*`{V@$^~Q7k!`lB`?9Bh7`6F-u z!(Trjkn!J2|Exk-Vq#!{5C@^?e=PIQ{J;Gn6#w@OGWuuRKsF3ytNgo3Alu_lOa{oN zfNY0Ug#QTbUxocgT7NYb^cR&7sr~f|LhQen%YW~c z01yPU{Qp7&%#1(==6?ji2w-GoWn>5b-&Jvx2Ir10w9vbHaKLUW349wZiTd3Thz-l$ z|LNq@$krBYKO&qDsUHbIG*Yies6!DQ3ci>o`0yP8Aeb&D$oP$NPE#W>6##aRD)7g< zgF)BK;>efuviHoZ^zNujpKo$rq`0RY>~9xApfP)7CNy0^bU3+RG)Bg&D??~n+){&G zGC8(dr>RTL=QConpBC*tMEx$h&GZ)NoBGDhXReJm5u<%Wz`^ekl;dp_u8M!aG0EGKubt`It=1&{XtRDZ2wf9;uwFkAQF4| zh4J)Z60T28^Xf$r$^m;S3x-bk7mjGzr zi?me3t}TEThdG={A#5p&2(OGR=c6RWY7h+DUh#Gw=_0yo4@C28Krc;7x^`MZ63lGg zvXsdijU*q&t$MfsHJewkM=_S=f2Hm73$ce~x>ZrKU1AOIu zd?HDszxX}7CrIp3-D9r-NAP_F|AZEc=?Y@PhuW3wxQ-Y(QLASEj52iV)YYRh0P20?J?Qvb1Fh z4EWq)uogs&wFjqO#GWY-l4a({Ut*!~`5G2>?Gd-Xevr4?17!LBinzf>%<>%1;t!PL zv1hxU<;g=~e#0Se{1(v1)g9*xr|B6(be>{SwBU73dHvguW0O3##xPHZjdYrb~CLeFURW&;U8EmW*jGw7TzsW z+GAPxw+hf3bDFTWz%G-Z%kkaH*VOvnObm@b^RMQ#@vj!NnOK2&{XF@~`FV3^Ge7K| zE~wi_Y6TKxTa0&I!Ca9nl(mS7_z~o>X7%k^?Dg^UX5lY5a!7M#ksD)O<&Mjk)ZM^% z2)kuwfSbm>;GcbN_+=(|_S%ejuOwWNA23?VEpp2D3CFGc(({osS0~>dJ3NFV@xRhu zxpBOI_C_-EDq!Ltn?x~2#P>I~mvobIeZV-`&w!VC{pS22w!Tm9Uyy;G?kVs50JpwR z?pKiUDczI*f0)>;@Avr^5Mrf!YB)cTcY=9Q(qDqku4McQylA+d_158a}GQ3n=&xL1KIi27LSQ%bouIHa;S0tTaUexrLsI#jGzXC5( zuIGxgtFBHkGJ*^*4cBwz*_A*i7#U86mz3){^X$sE6O0Tm!%OjJ0@VpdhLzzR4^4mh zo>tK2B$nQ)?fl@mzW?Z7aEkT!1TDQ)#`%F~egDy~05VZ_e$ZOqck?ee#YlfCJGV|WL9apJnGJ_ocs#fNVuNy*Y{6hWmd_!JQB{XG&{koDCw;d z&JT3!`%QiYr>N-(Jk1*hogtpd&uNbCEYeg&tW(qC%NuIl^?+Gx3+E!Ov~ z5M;b0oFCLX!K-$!)GF}4C z54fG+)lccIQqB)7>-&p-1y*S3FAo@7`$3c7yaH{;^wtY3mxtCb7gu4EU@vGHtXB^U zYJz2J}t$mf1d#9@3ZQC4XxSu`|Xxjp}_Y#O>%jiTXw zZ2WOD=f9=pf8pv_=yxl|L{y$_tBY>aqWwd{Kc>#k{C@?W0)MneuF(aMV2B)K9DUYRmcswQ^D~ z9Vy$S$)Dx#YE2>5-vaCY0+FgZ5!PI13bwAP(Gpux7o$_av9WUSF2@w7dpn&py+riS zQO^uI@wA`-018o77n~rJ?LuvrD@)KR;G8p2W8Il%ZJ{#MKZ5?dV^Wkcp=nsJ!YY|Ey!N7oGl7qOC1cE5R$ynwMBXzp7bL9cD z??-HZOGv)2jy$Ai;iuIxIYw7O@R#$y$cl=pbdTL~ z1s1FyJY-~;cE9?Hk+yvayGx3j%MaNI?wYbN{i~I^BjWkv;}!iOtJxA=)7QMbWUs); zEnprBZuIQgu4bMCM zrD~~{U}n?#$(fstx_-<0M$H!aZ(V7m(L24a=bGG77+n~md@sR&Wx#Hvi|Opr)4*!$ zfqs#c;%|{Z)czDLIO)f{VWiZ^0%6r#VD_&jjO-QhpkvS1E<-kDWI!?J4E4O%S5Z_k zG>9H<{^-F+MEP%zyV>%rLJFg&9xJ&yYX{So=u0d=(kN!4b>7u&yp=Bq8-rcIm+Sum zwWa)HHgBd|(1lA}MNdIAk0;mbepM14n=&3I^H^9-@5&Ts-|Kmo+~8PrS>Co+xh^B4 zJ=DH6ni5{e>$Mn)UltLIu&QAFVC7o8i{8^K%tw2{@U?Q{$`FxoXQck2=t|3k+s*!T zrbc3SN;*9@d_XJ+4u4~@&aSUPHx0>ck)>2GJI6c#;lvXoa%}}z+~hCi=_?EAE0^3! z(^1m<17hJC30=2J;X`sg!iaS358Ui!{DG%-l{|bU^k|2eC7fw2Ys*--8OdaQLKbD&nn%c>iSqq*Wj7YTIpsfN8=&e z+fMB6W-wS!)ziPsbck-&6_#9twq4lHP(SLt$bJaVqoJWWtMq5f6yQaEPBk5~^r2QR zr%c{BgRcLrk+-c7eAX_Q@MzqxQNYWw(4@*KIMEP(p#x11HL`;N(N@R35(r79q6 ze!0rLh$h&Bfyb`B2HqZV3#OdMU#T7Qo)-|Lx zT!1%Fte?y7z|g8S-YfJOQA)hY)`9l)r<@m3^~bO=rk*?c!5g9`R6b38?IS=h%hOfW zS)M5LnmD4B4V|rsfsw5t-y=GeG&aph^-JFLuw?fDed^r2 z<0faW4VjoKIiI`v5ddLI4?x^k?0o}x73>pd1anKZ9zAzcP!0(2Pqbp>YehH zU2T`Uzo6&u?c5bKhw=v_E4~e;4xDyWC<-_c^_?K2R1@b1{Xh)o{);@cM3)b8Uft!IG*mvG%TVd1>8j>r|CtTt#8 zCj{XWO!*1sQ;iIl8jt9EuB)U#p389~0^y!6qYY=KYcq~Qi~;X%#uFyS6W11GwXkZ1 zsnxfd0oB6v=d0iGH~~dX_vl{D_%Y`41~OKry-GYN0>|5E)Hw^ebkCLOp9*CJw}>2E z3Rj$bjMHSXKb6c%7lv9Yq~y$AClNLKd4}Z5QXAvRW98zJ#wFZs${(rUftW`mS3W(u z8}MY5kFpk~Ie((IQ`K|A}kKlXv z)>u1EnRRS;0O1g#qFT*r>0_!N3fv`6WI_=`{+GnR%zb=<7L76wHv3n}-jsKyjN z|D+YnXsXraR1Fppw$LNx#I8n)@~RU1CatCRviChl1qgrcH_~uQdQ{Run18kLgl>sh ziJSS;T+M;~to`lP-M-nhcbWHz_c_#T5q8-}Ct>$qHBe97hIEjOYVm@mV;%QOtCHq| zm)>i_!|7gm_%UzG>(fg!CqbjQS2nrgR;4BP>Q+Rs^f5v5yu|!ZFgAi_nEj`q82n_P zSZ`*0F+~>s<3XlE515*jmQvtEDbgfLWrz(w!%kW}Ve zvykCi)Qtni*{no)hxR?=u^v@Vj*LtqFv!w@6BQbTVBA;}7Zxy(0X#_r_GuA{j-e5+ zm(3|VQplQxmAa_4ReL$EcHgdk8Zx<$0Ry{C8U}w^&Ekw{hD?eZN0yoUk9+bjy7(T& z&mP4`IZ8M+k%2pv81d46`_*FLuX=dvj7FJc%@;>D+#lxd0p}~#5X z7_rbMwOW+H=F!FfTzn*=)qWqwcTO@h+t$%)R>h;?`52x{wc|PZQfpTHJY7%4(rHyL zT?EWo&&#FqxA?96J0@tVbTMLECd}F4h%; zG0v#-`(%Wevf5jj)$e0=%8blzU>gRjOzshfoEGvTw{MlLakxim8%0;LTyuQ^yGL+r zx||8H2F|y%;>y6v`4v(y4VVoK3;wP^uVAF`dqBrj&(y-yz*46+Szx$hhp%ehoVnPr zM{-9=ae>Gx`{hQ2I!AFVw5Y5|rH-oc;54@V8pBZOZ0Wpa>t6h2oMy)?O6I=nxBD{M zWwGSKC+&!C_Y9Zu8fc8rW%ZxYGOB*m13J)&nXc2FpPygsm>A=KpQV51&Zs*}@8pj^ zEvCzQvO!wi&ti+<(-6VcP-O{DjL{h~wsBAyYfgp9EtE#{>W;rtFt>20z6iv;OE*>6 zlbBYnX7RsoU3o}5G&BeRa$sSL#ND-42CWdxpFtL7o54X1}hGZhfQ8fo+^n| zy0Qiv#AT~{O(24qSy&5*S!!#+)FtIBaNu2x2^0C_)(vaeBeTf#tdz<4jqcWs*jiWC z;lPD7{}+3sj&A;*QGQ>sqmr7HU!BLo38Zx^dD%_4_*6^FLYD!ADViq>*6;(g;hTp3 z8*HJ^bL6eH$cA4v3420$f?mbG=!3GEifLZHy9d3ze2t=ZdM6)cb)G7pV%5PGn4|mj z!NH2Ani@x0zG$}x&7H9R%hp|QlPw-b4;dnJ!rn+vSt>l$0KSr}+(ugD=KsaDI0k0| zFh=;|OD?$Bwr$%N+qR82w(Y#JZQHhO+wOdA|FknZyED)3(m$h}v`09>P_InQOxL(o zcFf>Yd-;HIXV%=%Xz?$%e?n$FJRQ5d*WEuE9bJrQp6HOrB=eI*9wAVbGAOAM+6sv3 zmVra;zsaK<&`d_urs&WDak{dawTzlegHo#qHanp@>b=oOx+poBIhE}C8IFGWr(*Vq);|Hx^c%zEnqefTr4 zrDvWzA{}AUzwIZhi933&0F(gnb|zkc&-?u2(i!#wT!R^Ue*2Jg9k*d}UEPAw$p~Gv z4sHkIaw&Tho%?iVH`jBdIv;jJ_!MXx=YCp4{6UUx7OPh={N69-cuRy-4sON{0_GGc z`=$wd6QB%jytYJkd6b(-p~^WcPdfR@I@!soIE~Dr?8vYZ zHLs46mogzeP(2d?S0(dAS1Gf^tav@{gP9A;G-SU&a}MnkTjGW|TjU*YtXIjSeD&>e zT|bs4c$(hN3;w})Emspxz zX2+&AGn2>O8v*x1^hD0BXyp(pwr)^ZATeU~Zea$yl2~CH;Tm>I!VPcyk*X8q&sc4AMaNT8lfS-3N@}rvjH4uDXxy_iaevHuk=k_ zN+t4(BHi#Ce6pDu)B3iAN1Ws#ChhR&c-!*s5f-YCyh4 zk^n@QJ!@B#k@pnOX&~{fI-j&n#WYhPuuHZR;fLX>P$%r**YFqidkm>QXXR%3hAYu#9TMRNe583$c84X$!LtDplkKJab9|??>?0cd-C5!BvK@)?pd)h#hMh5 zNm3)sq^(|Qtpewy$^-hk2VGxdDCgj&uSi9OxzO;;NZs1KzjX`6?%W8=%;#b9#0+^F z4ah4m%sR)qvRql}(RPe%6U2so*Fl-iMKs^>_eg58uSp%)FXJ7fTflCS6ZRxs%m8NE z8QsQ!op4)fQoG%{csc=D+ov94ggGW=KxulQPMPv%4f288k-gP-ZQ%QNB9Nn{=~D6; zC*@=fjpn94@Y2XN0Z^uoM2*w1R@JDcm;~flur6w0lE(}%Nnpa2PIoL|f{L9*mMW^( zSewvtWZ!H~o7ts)%Xy>rM)+wdFO{^6$f%ByCogNM;9k@@_j!T}+={cJV69~8G>l?& zWrSz{$H-^CY0hKIW5kpJx##Etw1|~t?$}fH9r3U$f7y|x9LBXS&P(=8bo@K>2b-RG zb11}UFlwBEFL`HThf&73q&2W>X8g_Ar|TJGMydN?VeR)3DcZzU2n%0)O589TMQCzO zvfQFQn+#{){?bmvN%9#FwwrT%&9&;l(gxg!Ls3WUe3F)W(>+yB_D=Oz@H}kAs^9>X z2|DMZu#_}cnAwxgIN0i`jY)ld8q6YH2);Sf@R#I(EXGYmvM7!Jje^=7#$a34pxbF$)hp$ZmXGw)_c}eF4HsAeSOuXuxhZ?{?jM)vL5ts!I2V8B{yBi&i=pV zP^e{}+@vO@{xyQ5B&Mt${mrqC{bn=rE@5`&X`VFhlhQowTUhn##?X?Zep%NB<@!0W z+m9M6-C5j?+MQaAhf74Di14VeQPNdX$jLAx4TLj!(LCB@pXi|iUZKZ2C>vfk|F7?| zzt9OrJgKkU2jZ~T_)iff6S-?e&~jo zfWx_u3|nTK#;dYm8YJ=Or5eE+-yk}nD_O)GJ}gDV-3pIk89}AE_Q#m3`+FIDheM9! zHfAte0ckbE58iR>P}3bknE}jMQ7fh2?y{R=iA_)x*s)uGuUu^yqnGgJ#18(sls4mi zbBjMHvA0jimqsy=lZA+5+5JU8>u}%4YA~F?I9c=k>3kr=~&6lrv#Y0RGDvu(v>n z#pPNwC$~B-g*$?6c$7XxdG7VvjK|E%<+Sjsr^^LTIj6KrAP2<9=Yld!r~ z@-&D06K0LSPj6K9@UwVR!6mCUC%6$X$yNoJPXRMq-UYJd=}cI|-Vmwbi(jXrWtQ4| zdLu;ULTo3rLMJ!-5Y`g$0@ya(N3)wCsC0YM3x^va(aK6aGLfjr7bYX2be8N&)ukKCDPDm)*o@HciAV$g@ zL~a)|d%Vf9ljb=XlUc4vWPbV?(hD?Elco1bW7GED9iw$r5 z99n1d^STUe&(JQRDl3a=YL@Jgvi|7bv6Fi&c)D2n z+D&=AU+B=p-$`qOd9JeE+{t7AA#^g9NFwEH6gCeyXKZSX&`DM_&zzRBSx`J)$J0kB zvTo_J((9@gmoFO%13k% zf47_>?6*igms`fvWQ5KP-(tYp5J@JcU(D=%}8@}wyQSZa5HX>5q7E(c1W>J z&cOrbL7|OHo8dY~c)PVYAjSq`gKZc?xa%g%tD-cm@Mn2a>!vE$4RCVlG|l&M+3>>m zv2BIQYPnq6IjFIzd^hw^jM{coOHPJ9qan#rA;e~-A%)DzEx7%v43k2Z13?*kKBy1V+Y3f5D_?d`X@2oz4a`t`W>%g*3g1-izb-i%;@S7AsJrWwUb8vuiuQW)&iX3!!cDX|h$!f}kWET!ZCOB0V5NrR>)TWWSTnNkVjlY6v%k`>)Qj567K zvM(CRl$1u=aJl!bBvPq&4AldeTkj5S zPWIIaJth~;>3lRVUkmFN76TC+lSHH2mLAk_EHvh{->YVJJVL!p<}&$p8OUr6KTcM@ zzmpyAkhy(^bSN!ynpSVG*AU`p9n|)H2|qB$4t?l`oJ>_2;p9!$OJ89*;ijSvS?F{{ z2Uvkk2gz7)<18Z1_%?y=o8qB@uqY!79RH*XPrY#lLz+_mbBwGdX(UuSHhG zA(0#4x?$PVakw#zlVf!@Ie38azt<^0 zWN8*vUDM)i?u-q)mkh)T2?ud&{$+IfaPRaHDyq{MPvT9G%u%M^~}E z&p}F;z#Ym7j7%U9h{De31HICEqIF=nu;Jhahcoc719FW7>`(Z?yb$k0GrW&OQ-d+6l$z=MiUUwS-@R1$L_M;?eoEmB z(@FVo!Kl2J)4_K*i{l=DWPgzJaYuT-DN*{fruEgscTBVg{Z2OZ^J>rP6{|a>X77T& zwfZYnI|p8GVCBavl}MLSh0*tas{dX5|9Jm-A_|&3mW$hsHL5f%iUP2+BsWn^C1TL| zgZnxR%GgRY@IQ@OE7$z>7aMY7{Dsf+*ubp4e zCK`c1uO}ZrQJW&>kv#`9>o5)?My>HfP(W<%D}qv>5`{N#Dlry9M7u6uD2g4?Xf7O| z5_%WLhGH@Ie;}HT#91lB*OE*NjhI#c`tE!I1>G&7?xkE&0@&zr)lYxf_m6<9FwZo&ItpkyOc&8#bTg9x=)RcomlM190mlax=oT#8{=+q|~Z zsswj~BC@K5F;etoiq)ECG)0e(PMxd=cAXyfhA8rZjquvw@J4z`mW(tqwvE~IUs4vS z`oXOQchv6s2R2h#@&}49)5=~VI~DV)nuUo+)HUDklM}`Wh^Zhv^?z=)lzdS8wO~x$XNpQDLC2oWylAtJlUVA`+)3*oK%H8 ztL7$_G&8lcNi+r+X2*M76ee^`>?xZRwk{W#11RnT-TU?Y@with&7?H!Wh~jLe#5Tq z)l%eQ=o$@d8Cov#Mh0wJn_}y{@l|sh=07HI$7I=KRGkdezVG*JnX~J=DAs7%`mFls z?`%;l>OrpAZA<1&=NUmN|DsNV-lQjv4HqY|u8y0@vV}qs z%9h#k#>_43`at1|$tIZs@({Jv`NaPQM7E@BW(gHLMC4lOh?>ETF+sHTsFDtEi@aDb zYgC$E!khll!dnoo*EPg4#;S`@S&_;%U^84QZf+`0X%4v+&2tVcEuW^*@3B#bDVkch zZGe&G;%23Dhiy-JK5-3#-5j1a1k0ZeDzz&hkB<~9tP=a!(LjTbfqJk^Ortm9t#2{@ zq4~(^r8gNd4(&Hqur(_E(jwD(DQa@oOBg;JQ#zs_)l2Rn`av7lxTGJryxa_T0|j#n z`tafzpR;B_|1`}aLQW+7I@Q$Yaqs!giTbM7md6|8+72?`@>Fj;Pr|(>pSv;d#dwE zH_LzQ7WfVQ^Xu{EjXak>Q4mZc0CvW_9Pyghtl&(u zmw%9-7*6Bq?2P)w?KzgigE>P(v##1$ZY+0M0m@yj+^1S@iRxNduCU~9E6!NH1{rtx z_!jsV+0uzaB~DqjO@KfW2`ZL7L_IvkfF)+IW-eWJuvZG1x~kH7ZUg?V-VvF)rOpwG z8lnCkl-jPj+CoPdufZ`cB`YDBu~Np+go-eaz5PU5_q{4eU-pMAzPpI>bmvB3hvHH< z5P(=tD@j1CpBle9N0A^SmdI#KgDI}Ks;36C!*Fx)9;cgD6mqUU`cs_2hq^-K+eA>{ zA;G>T)SReejL#|ZKI-6@kwtuySaFE<)gf^omFR?J3!6HI>PV`MsW!IcXle`9lDRR1 zd;H#pyoq@Y>V}!15_G_Z{Ejy^ z$Du=gMvr{C$g|GJBu_mRpTP0G0wuBpnRIfxDhZhsG_1l7am6l8rb+Ni*}5i!W@$)q zi+)+Q12ac^r-r|xr`ngIIiqQ6`B-+UV=#qqJkB!BmI75vEZHH8aYmhJTCXbUJk+r3 z80SE->C%pK*|F~E-$cW5(DLLmXC?b`l5K_s6|;q`>H^sU-2&o*#RBTW7u$TwYRZ}_ ziRI?B)FNm8;ImNObr`ahQ<=I}Ot^P5P8pps;>emzP$cJYWg)5A9xu?NI$^;H?;2L_ zb*(e-<$-&xDV4t$f50UkKW@wfnj+HJZq#*rdbD~x@fE}a*r}{b){{%2N~5ffdV!*b zvXXo@4r6@LHSRQ?*?KK@DAFj7qa3XytA<*pTG3oOU0Pj^Ck7K=J=$GbS-PO`vPk6; zz@@<}s8g|BdaabB!apywqHKB2vX#-5;l?Uga5NV@w={Q=|B;VBY;Jfwm^7F)(l}@x zy%xOs525p)F08kRDM*8Vz5xEqNAJa^S?`JeiU)ictoNWe#QW>&udlU!k)(K$;p3t> zjX*hu8ng$g(R)At#oTI$cSbVeI*f3rc}66EPC%McK$8^1h#%+ME&#W4al@GftzqBa z`H`Zx1EjO*KddJ3g<-k@R&&_U6~}#Fp#9KOAzax8ykY zvem_5puhgA==q0Mzs;241#0`)x>uBAguhq}dHLZ|ALZz$dbFrhVpv(MhZk||<2(R_B zm(W&o_ixQFA}|Z@#od}$bplHLJp(m9UVTF1zNWw01+7^Ee5u%_`?|lQj_w70+1$Y^ z{#JT{Bca{T3E(u!2!O}@O7LgwT@}F10sW0JA>ak$+N;nNS7AbvG5<{?i;{$mgYQ2O z@b*xf=s^PMM4M*i?*o{vL3n=>?BTQ5>}|v6db%s{n-jodz)XXwp(4ClaXvaxGuf63 z1T5$`C|)Z3k>2-+FPNhW8geQ_nd$h8*gjZu-7u}ptDM+SS~BPh;41q2}Q z9n9oYJL?mo_Nzhwb3M}UUI4v*q~_HGqXK&KSPk6u{wWu(bS2jo#Ex1Y<}rc8hmGSH z-1E&aYSL^TPiS3Oq65xCobamU)9}$3otdhyg~vXtMp!HKPSqS43|hwk$+IY()u6#A zNQ2i}m3nyH4}KCSG?5jHk(bNcEshOuzLq%w!NRi}W%JMM57qgR`HEll5S2^r1(@t7 z)hySn=i-zfh?AOdf$A*VqHC}JQub&N44Dfe<`liKPHemXY*@}8OP^gf1?lI)itG`- zY6JWq$gi6Q6*U1VUTcY~)d-&40N_R4#YS2OewK5~B43x_M=zV8MkFYHZ^B2P1GZJH zsZSY{8JH#5VT8|Fur_ZG8Z+u{F|a@zq0a%hrg>Rq=A@2rx%#KdOt>FM;PF>J2sI7N zrysp|7Y624$EhBkd9ZGagOCvzxGK5(G~Ga=D<{(*6!V&N0gN@y9R;`YNYY4^Cp_N~>hL-{#8)>{)8H4*l zBVcw!^$3P36lIZDVo`n@>OV*g)fgbWlRgy!?2J|~1fb?o7aqj#YG77ryk39pcsqkd zh2_*)9uvkmbhx3cJs7*jPO zol9`vXzL<(nzL}dRJn+svZXG&a|O1Lu({DRd=t4kC@d2v8-kf2e|CRmaUjIcr&IlT z%Zt)zgkHYvKUcOy2#?EmAt$OtZ%=02f~9%B>+G{O^&8>rPM(!>eP7#za~H~AyzB+3 zti{5+3CPl|bjC>G!$JG?jIPWde7NgwdDLvbV+6*!T-~iFg1b zSI26XefE;DmG9RIE6-OCwALcQN435e7yVI$K70xJ=?+66FrS#l>~_~@bUG1|x^v)P zrt0{j=Vn!D@jj2GAlJ=G5;pgz+F|{!kI40oRF*aW{`6XPU`eb0)w}CzHNQT!IP&`- zrrblLF){4{-qdHP`JtLLXKr%#m-n&%>g=1GAT??(r^RTAjv|Wu%q4=yFo}marD%2< zqHL{+_^z5vwOGO&wkdxG`gXiwUg|bj-xgTp3lp}ZvYL8*@DqDqqKiMSdKdoGF?5zyc|C^*@`3xVa1hSsJ&H!!iT?Xt`hXwY{2&T@aXxK075O)Dgq9ur++~& z^leE2A6!3`=JZ*x=zYly)>7wBS5#p}aYh zR@+B51PnZOekL9(A4_*@g18N{Mkb2rPC+AO#%`g4mADn}bU|o7+1K|ebj*8!8;Ar_ z@HZtvu=ere2^3+^^RS@YZ5cUXL~}?fus>1EnB$}<^SmIUNJvqnu%5Sy;2X5LT0&RB zgl|dkR_wg*2MjcRbe{S;3o63wyT5E8*#e7Kmz)y~=%2;vrdxvuSFZ!3x*0yCKj7C6 zqUH$lE&TSf=#mM|dtOST{lO+znnI{=;erqO7qJ!WVBZ9z!bJu^CV2_YksobFM+A2u z0hmdcj{tdBE@KcbTIVI7X!@MkKK`Q*J0O3^p2yA%*pz_9d5!#Kq15l;e{2Kn_t+)O z%0xa?Mec^??Gy5pgcwGDqMR@SK4*j@TNgrx^!IWE;_QIVWPyy9!`qZXjIf&c%f)v> z@qVvTv#9Vxx2YR>>Q#ff6aF@74Pd{A$%a65n1m^G1#jT2@I&}1gg%FU>_NajnIVg4KZh%Fx(V_p4pOe23_NN;y~{-tEmn350cQGCI*fX z?jqkvOJ8!VvDFk#siIX-I0Cm|Jy=@moRY`m==QQ4*aJ~6hS{CVPz)Gp7-l;q5P3#W z`W~J?+y3NB^gn#DB85!*FtA5*!Ds6+l7nAdte&{&fNs!N^&siBPr)X@MQa6c!he)- z7_sbm(=m3k8=o9!hIm0jO@oRubU*Aa@SMqn?qC->?f5jk5e?0{f5?W&Z~w|h--ch~ z8}&`yd*gZV-u?~z@TldVjo*$JHBg_8ANk9ZI}V6!R3u<#q(tIX|Zm(n^vFk|tu!M>jlLalD5hZq$i0u-qrt;{`quwJfA zoMIxmCZ2Je>WGP`cBX{9b|##>PR_&W^abkeXBS^UD#IFd&jhocCqL!x?WPDuvNq-_ceN-eUoGeYCN@dY@BmEwe5!5DtT%XAz7>_{-e$@x;}WLiiMhX z6VIiPD`BI;M|x}I%gv?d9eq=dHEVdVOOoRnM33Wfu;dDotwF9a%oV#9%$bdFifp!H z6=Uui;#Rqc7xock#4oWIa~J2eq`(KEm1wVBc_+ah!JWW=K9h#Ez)HG zM+nOunu-9jx4}~w`kc{^VA`PZcXb=TNG!>kyDmN9QDH_U5$)i=PGjb^f3AsOg{e5? zW}~9_gl%$=oT%{@>=wN1Rhm7nAL9iz!OmTe$K8 zu8ulNTfa(4t~joOG8%GO*1>HYx8USERg0p_xCLL|$)5r>J+?3(oR^?vpujN)!*vJ~h^JNZAkWOX~Cew^wsj%5NT z8LS5%&+=s8PL8|nA;z>AX!-6n^Yfy*FTq&Hq<6BrmA1GqTm4Mu$KI;hS*Ajqy0~v+ zL%O|;H6^0bP-{9?&n~aJq)gkf)0*g$GV|mA1I7ZFBu1w&rT*J74r2llPxzdI+~x>D zB%k*!{=|<|^#11won*fzV}KMkDt8BZ#hyIwPZ&gZ3xO?G4fAa~Me#emgX0@DmB5p_C=ucVu=zZ`BQ;Vyo%It4FWRxzn@<8Es@WjkfNCAW>OU9qOAakG2L z9=o2f)u4WH&+46Q9=Xsiald$WnRYz*xfQG(@LX;gK68I`+NH5`#(KDAv~bCJx&=01 ze_l;9Tidp{;UDIJow%NOZ3pJo=vU#LxZGYkY~SNC-neZ)JO@7buLR$7jSEkYY#$u! zo-p4~J}98y0Nl>#Qpdgey!%lP06X66$){hl-e?z|Q|LNIo$QmTIsq>+Z{=3?FWqm& z)EghO-YcwIA0p?N_EUpYvD!|vPKZYkNu+5mb4`Dblva>#a)VpTy&WUxRW2d}K7-?Y z=bFa7M)DmnJ3DBh=@RLu6E5rD6KKllQth%xw~n4v!%3U8E>NY>n$k#Tnh-yOt7*4Y zQixWtDW8Bt`Y^n|ok6zYO>e@-Ct4CRe6-FC`j-&3iRaTN!vR3@J ze_Cj*u12v()+PHf)2$_0f0P)m) z+T6^h%eLE4X~VstLZz-7)T zI)g_cOUw%-OH9vkZ&@0k+JIDMXVWs(i>h8yQ;OzNd&H2ypGY}0R8=q%wOK(O!^&9yNQ#J`<_`9pRZL?=zi7Pw6 ze)r{u9j>$96Rx3|akBfh^*sZZ<>)sHezR^~`pAk^q|?sh^G3p^TfAfl(OaoamRGNv zVO2y-b#z{V6*4Ao$Q)<^dFYJh$qQ-v#im@m1-<9*#;ZFVFu=MK5;alCid`XNr%$Bw zyoM`MftyV;wZj*-RY}Kl)ehwm(Vd7Ja}E=CO*Uqu(*=lWSG3g$N5{%dF{kSn-h(Y@v_}ruh^P!vge4O_P2h{?j|M+5xM^bk~ z^8|3jr{Ty?{D8XF#1qLI-G-Ao(L2=!0%-hr=&lGzEt*>cI`3F()sauQEvcT5J!~zi zdckx-YNeNqx}j%1tX4woR^BFkKsKT-HZ)tx72U)i6_yOYEUKQ&y@ywg6}(W}RPfUJ zM8B1fTz1)6y>NU&&zk7~lBcfEs&@<@+}S=7ZG2|fe9LVT%|iKcts0R@FLE8-D#qxDf?;j;bMrp(w)9R=aJ{OMZ!c-t-Yof zxS4#!u2j|j!tL08-;Tfu(+<<&h1<{((H_ec(Q)jOW1r+od&+l3aY1#%cTsv;e%XCm zD)wU{uA?UVqH>3KWqv;Iy5n4VJ%2Dw#3x$&(NwUdvkq8c^w0jPbouDg!g+QHwRam{ z=zkA1{M;?H7PP)}+0y8l*>m7~&e7JqcC1q4{Cq^=W^-wBM&M|6P0w3;rW1c5rb-+J zOFlbw*nZG)zC6=h`9fjD886-M8mr40N^s9Xx*4Sr=Y*f*fcoi^pA0=pyiId^gg5cK zoxJ3bYN$H^pBSc*=KiOoIo@cRV$m@051^jnnss%)Er5gG!Dc5Pa>6@uRBeOJ5>uhW z%|^0%sng*NvFL`KPaJ|fh~C#Y>*1VZ?s)5Y&rv=v3hymWjD1_OolQU3H1?!Z{OFc$p7a>5xZyqOwX`_n-R%gi-Smjg zr2YW6Ha#|f1gLPcOFm;sJ#|hxzK!RsR#$?5gtu2lL|t?uuOAroyn}Zoev1l0V}>7L z?IPibTed<@Pi7&)Fb9%`5Ht;ITK!f4-5)X_(ywCWn_x}RJYY?+qOD6gDbl@YT2{1b zj&6X~7fLO<yA-I{|;<~$*_w;)X5N*%|l;C=7)H* zITJBM;%%s-wr5#gTgBzTyR^6@d?%Q9m$IC&;;A3rJ~qEBNCdswb0|^J3VGgC4Rg*6 za=!RA_khZ+=R#@Eq~2pGzAIz@_Z|FfOM)FOFUR6ioIkK5em%Pt+u{LfOV-)s;H;N( zGaa0+fBLU$r_GZ2o{cmX6sU0D_3$5m#MQb{5d@;>w~cZ}{zJ${K{|aIjyRL zXm+v}26rlJtKkPVo3-*!G)N=Qj-lTV5_uz9hU?4zW&^y!^w*fGk%`>uk8w8G_C8HE zWS-RXsI11&8*1WBB%O#$X`2b)Up;}(7>zKMF?N!G1M`pY=Z3423{#fDMmu4g&N@rG z3ENwpDO#_UH@%(B`k(0jC1KjGD`u==P`D~9tTzECEBhyjiM{8`r4`MXrjwe-<}7o1 zbwIyk=|=J0Nkpd%Jiz-N11aba#7fO2Zh zz=X`O>xz1Df#ovVUpOTyqp?Q$%SIycdC3z&lKe=Jhqwg_B_{;0pi7ohkJ<4v#<4;HX?Yp93<;9w+RsH$t}nZDf=c%z2QdPf-DQsXI#s8 zL>KVyOZFka;>s&iTM&D(bdyuQhq47`oUg&cqPFy__FJTEejEUiWVy4Wj5XWVnf73u;EBKsq$@&a}Z4!NnmZ@*W z3C!&49=ADUtHZO!e&PEtyXJ4DzC_q}yhDACUnTWPl?@Xg%yA5Gm-3En2qWIVX%!#R zg7nX{9A)4c;yrx}XQKDKg zd2cKW-Y~MLt2}{AsnOtiRi9v|-FO?JvD13K%c=kDbxin)I^vyx*tU2>n4tZ3N{P*{ z{7k*$r}VaR)_x@R)^ZklH2Qo$m7c@D%{0`F_Q>2pb7D?8@Wso-$(-y#&qT_cMi}J7 z{b2dYT&-NC`6fEZ)k|5BwV?7bD>e>?nZR_iH60^eB9)d(NnK24Nn%N@q+XM+Z!@+U zdrr_H^^$r{#-ZR;c5FO!9~(vb-|ln&=KSU)yM1^)NtejMWV$EyhGxD)^@d=6$T>l0`qLApH)!}a^og#4 z1JI-Z`Ud+3^N#mS_rNn@zp+}w08CFAPj6sTj6aL+QZF6M7d%|UHBg$RsgGjNkBhf++_~14A=&Y0fqoetcTs#-A8y%(W9Lgg>+d81Dved zu)&0+qoymYoYO8!&7iAC#+qwPNe%0Lq=D8MF)>GAOS(Wqm4r6|$1CAzh{}^K!#TnWbXOGjjrPNJ=pTh^q7^DqZ;mgKau zS%_1}!ci7fC+57XSu^vFhTjepbC0P{cJ~uH>av#X-}}`bVfPfBkT|&;@5~`Ff>l|Q zVkWi?WrK2k_ywc|B(_iohRD+usa050!%7)Q3ZtwU$U9I!s$tY>aCO4N6x6rTj#H}cP=kjkuq}de z<;Z4FpStViGaxhQH2J`jYUU`Mka_GBUHUzn%)n)Q)n^~)E}m+0pAgS;?;btP&oaJ8 zFXUZ@F!GSs%b@@syt%fk|DxRbG4y|&OTVg?>LjBbq8?{fbN(zcl~SjiDH_SL%f>9X zY;{8z7_H|;vg&wxtDxXN(!wvHVjA(P_n=v|TiFPDh`E>*yYqTSMI3kxvsa6 z6`HAuXk8aoEaP=q1AO65feQSKl9AlRK-SE~jr?W!XtzFe8tlg^1Z=mcqmRZPU9Pj7 zrnjQIyePMj{>Z3-arh6mgVQvAFW-|AhDSFNdC7EU&cD+;ayE0T?9Rz4b;fh_=TVT*%qy2fP3 zxs|Gyl_Q02;Jy2f;5oA_eQ5{JoLeE!&`L>5&%LvruSfBX^P9|$z$ky|cW&n_yUc^y zjb1I^7`v3o$%k#wCC(%D%eyVHd{6TGOp@CBaQO4bj0gHVeSVjx)u-@w(Kq4^%n$30 z)Q_w;89%~N*F!J4rPXZLFq5OTs<2LZ&NC$0#qXk)w;OkM)!L5XeV^tvOvV=c!y2N6 zCBA#xG6v5Ul|ge)qa9B-Ws=hmszTv4z~|p*vnD-}-&Ix_+2&``p9)74Uw7ax--Gv% zz7amWw06%Wp;ayIF3sNA{LGF3>Yd#jNuxY}GP4H$*!?OW@i$jrgEzV!k*7_l@t4;V z;yC&R_m9u*Ssc}s`FpVM@q6KK%Pu);{&PJc8}4g8pB)!Wo14NO_>D*#8vX;j-(x%{ zcFQknZ=yf#_k=$o_lQ5o_g3FkN9RXP+7U=D*n2zO*&?PllgsSBDi}SB% z{P=^i=_+}^=|XOg9`E=0SjTg-`p$I(iCy_mEBk=&d`An>Qb!LFvGq)tBVz3oMMaCD zm^r+W@7c@9`sczkVL9LS0P0%nKlfOb!_Z^idpTv4-Oq*87hriB`aHcN+vpRp%3fjZ zq5ZAsK`w(H<|jdyue()oZ{@S&#d4@$zNd`Kt43`x=qhy4=kX4edSDpiN>~fI zZnG+)XuB=~)jfi}$Ku;AO7vuw{&%!kEYs(Z%!b~J&k#W^bi25Q$P0xY10M5t)P@v0 zMYeNbeWtDa^gP_S-5KOjeG%#S_)LLU{DU+7y;VE<8{AgpXUesxPv{Gg5Yu+#?{s&1 zBA)0MA|bZz$lsjy`B#Qpi7ikupvR7{xPNe2V~S!>W0GT*o(;r%=Z;rTSNB(sSNACF zFCkYiR&P#ST5&>gM=l5A4uTGn4k`~i4-yU{4$2SO4^oV*;rT~+$Zca>{?!|8XEky* zb80v_o~+^)IUP?^W)RO%W&$=DV}&S#Kw;=$URh#)S^VmRX6W(D$%*3FsP;$Hn9$r+ z?!fQ2<~re8rC-zF7=sshrFpU2lw?!mA?_Z5x$B0Ja;!{Hk!xoEAd_Cvgt^j&xl_!o z?HcW4GpcYCj&!T23SkrWaube}6ZkDqy%e)mcz`r}$M{Z%4R%onLXQlJU}o`&yFl}s zD02*G0GTr2xaa*v)4=@aRC&-a9h@+xjew`$`1hSPUy!&4Q|i|n@PA<8j_BUMrV{`ZCN+H&7A)_7}o9=oSU-1R&{n zLlZC6VLwq{L2U@x<5HnCgmSf7NTLRy1A;UH@i0gQ$nKck1$xcL81H+4mWoI5)+a}L z=2CH=(PEo3At^;_pw{LRr2%l1(vY*yd4hDi3+}~to^YOW zo(3DuMkIUwpyskn-GxZpl4Ar_k+{9PUbYHH0P34EJ&fb%j_krU(?X}O#vr^*>}hWnfhW8ywkJT7O;`Er3gPjsF&R9=xiF0YhV%Yp1+@I7d4{V;lC&a*DwWp>3qa|~yo%j!yYrMYabELXC# z*OjaFm&@*&>nd`|*!paHP9^m_%^ueRZ5FwzT#H@HT(#7%Feb&Lu6oxRSJ1WIwTYm^ z)#=*lOaL$94FQdf^Qx=M)$QtW9gMV8@EVl}%J?`hA-ImX`p|Y<{jSp(Yc%=-*MRGS zYtS|98g<=3{av?R z>7H4WhThg=^JIB)J$AWG-sqX@DFV$;=f;4aiucH#GS31DJYG(vrwV$t5_DC(@j9u{ zv)HrDQwtL6q)Jb{%sgv6LC<>N2R)lS9iC3$?(}qdx;;IfgJ9oDo+F+Boj#P$_9sAY1VrlcageOjL8oU(kK{?c^?elT zD_(7@4)o>2WaX;)bJa1hPWHFH4${LM@f^hm`$NYO{rs@wb-*Z~gKRCrU)|F$p)S_|ZtD2Zx3lhq_f@10cge!EQ5Cdj z%}%uE8vwUe7>7DUd)Rt9D@vDFzc!(c@%Fpcw^@nmSZJWhNm1i;fJ}gy_Pf?5Jpt;4#_GQI`LI6Dd~bXDQ`e-A)gy8a>*Hi~yd&a2%hzhY zL>J#Rf9|*bKPY}cdp@zgAGc;c%(!NS*RT1e%EWNH*J3*ZyW0nF0B9pXj9TxQt{z@( zGsv;KLPqNcGVNbPB&U@r%DDzKW-abR8U!-i1YtPp4wE3v_ zPns{XP3mCJpG>zGO!{~GJYB!3I@?_lcB1y9eMQ6=n<8!tI1F$M-~?l-{Scp0;jGGse5pq! z;qi4!KFWJu$%}m3C4eg`|0=+BfLosc#uPakX!54>ivH8hs%(Jiap8F*$`#rYY)Q6M zTZV0hE!&oFE3nOj;Ifs%vmZjKZ6WY#C@i(Du&uPMwgrGLwYAwc+P2uXJvH>ykZlKI zj1|hZoABOG)jpp2c&2SX$XjT0eX8Ep3*oTsm@e$c&wAedNnd)ygGldom`d+(NThc- zJWg+KNTK&OOry{ErqO47|AyYxkV9{2$fNf&JWKCq$fq|m*y+s-v+11-&;8ZwWs$}f36AC<44X^}Y`6Tat@KhZ@!$ah21_1keYJ>8eVU9@O{9qX>d?sT! zV>BY%czk(?zOCnHjBB(m$2|kS?TtRk&FBpt%DX!Z^hxe0`XqNOy}Kic-q(>rZ|ayv z@90RQcX6cCTR3d==8a5x+s4!Mo{bs*-{f*^KkJ?RAJ7w9SxI`{)Nv)GdjTAwr^0ke zr6`Azl0IKc*Gd4cOs@=a@-T#_Yw|Q%C`pr}N&rrxLo27%j5mk;Hs}i@zl;Adxb>g% zKWC}@FZf~hq_NT1$eu^<$%>+X6n%^p)0;z*020)9a(p^eUWD@C2l+kxVP@cufUIOH zlL9#s39J2Ky~#N1H7fTuVtlI%v$MIn9A{a=)YDUQt>>rarX^U{D{<~23_xbMw=Lh@`7|$Qz4={oMA^$_r>|a3}1GK51nW;5V zpxKXEbo5U^zj&B&8@PVDyYsR~p>{uGX&C@BJ_fSyo5ooSSjp5BC0OIEaT+~!!_*D* z96vSQnq|$xXEoO-;wP>@aot*Pt$*Uy6SpuQK8MQc1C*yyxz^mN>#Sw^fMp}|V?KR| zOi$y}c)gBk<}|ZLE7~dgS?jSqX`q)<|NZotY?oR;>NWPnm{qpQQ`bQb8S^Q@Iv02i zQyUSYD+a(z!xoF1PfShsbz7N*DSBGDfIR! zYxEzY|G*xL{xJGOmPGHDdi+oFag_jN0JY@h(&;-U3+b~A1*+$xcdxQF^oawGNxFQw zY$?7gC6tc?Z}e@jXde6#)laphQf>IYQ!`mQBTE;_(v4*4CbD!3S$Y&%dNf#i1B)d| z*ak*zFi;zwqPp>YL#Vk@_miaKYSNlxbs-+ls#MMO`4p`==2Cf|M6(CA_1=1OY@6EO z`>5^=;;mElKBnWHR{L9@@35+Ooyx;s{rYok2CXIOzAZ44Bu0`rlEjlFfh3tp2EM`9 zaJLRrOEk%k`sLt>>xWu zy8?V)GK))PEanJ7NzD0JYg}UN5rmjiafukiQ%cPKxI{=hqNK;A$EC;i#HB!L55(!1 z2XbW+o*6e2xfo*3V+fb1$x~B6QkWcTTuQ7Jb7O5#6V;58uq~D^SiS&luCsteT3)x{ zYE!JS!}8Q zq%DjZCMdx-0Yq-pB8Ql0AG6^vxmu5HmsF{FIsbmr%{|4bV34iM@`WrgBLq~7b(Qm0Vw4L*F3t{h7yEGT+kGrO;mqvjBz0_NLP( zMDa|jv^aAzH?&SU&mukmIEooy=NJ{@hWRdI8)K$iR$}ac&`G$+SY-@Ckbz!c+zAx& zx{TdGcN=>Ex`ESeJP0XAC=^k-oe&PHp+gONiJH6)kQG!VVd_E3foVM;>!7iZBm|B9 zK%F+Cx6$@v59^(WxI}6pem0gFpoNBw09ydIsq_wj-D` z1Rz7c)Jb^cG?gt86CtFCBH(5*Uc|pB;R1vK;;j=i#dI-UxFF_<8^oCao5ii7`X}@& zIU%n@4T)+L`_~I$Vvnmc>tKlff67W$`;{C61O7{VoBU3N`JAv=O^lW0oJ|P zu1OFA02$$ceEu5HE)_}v{3;;55THh(W4k9Iu9EmA_^xQsZ3Dj@+{#vbs|dfDuZB=b zJR_`*dmvQvhlCjZfDj`j2uYL+!+bSoC4W>6+tsiOu_|#h(3opG$lAakfHn4jXovVH zNx-y2Kpo{z3aP|92~-Au@~_?Z^nTSly4?ic5t_&A#$(3k5>WUPRu(+ZaWtCfllv#^ zAs@}e9Wd61CJ+x3uEtbu3)1Y45za|mpTUY)<=ctVjd&b)Kf?-Vd;rTDE&@&^Ia%X% zD04iGI7Tc>oSTH%cnp>`Zo#r*fase*%amGej6>Z>J~QB3^q6ra%E4L~{(*hs2^Z>S zgqI*^9M87fC{@{m&<+Fa81WXu%6>)JJ!~g@miSYMrdJ3<>nYN=*_iW0piuPp_ zJ%no%ITHh@Ct~g<(UnAZ5zay^@If=_=%7sAX7m%ryM|!{Sq}1HrZB=pleJeHmXL)LjWU7nCw!Aq z8Kqi?zD_izHdCo)N^K^7Gv#k4O^PrTW{{uiC0db8rTU1jR`QE>(wXvzG;_%V^dZf9 z!4^3FOB25b&i5vEVtc87dI?_~$Nv%Z5+24LgWl^Qx(a6;&D=hk`+W*c{A$Ikkbg)T z-%Ycad;-!?b}sn`J8`hoAkl+FXHk9{DZmPi`LopC-a@6&OI)YXoG{=#iW5J=(I+1j zhrWybOdJCIA@Q%1H=82fq8>obhggc8HBLutz`8^`X>o5Lap#jIx)m3KmCu3AxEe)W|95xpfM#HM^LE4 zJ~5|ZKNz^JiW@{L>2mc${l8OHA< z{2j#HIikpBe-J$emKDap=W+aPZX3==4y*-^WB&~F3GP3M{s?K_Nj0Li z+~i-yUKMAcXXbF+3%S>kBY^%~3jYg`nZo^w$|_iqvy<>;%!zz%GqxR0grmeikN%ub zz*cknk>*aKm*AhkHX;oP}%Q+%*Xi?=%c`Mb3&egHosDU6-rox zw6Ij@L=P-{4e)NvDeNQ869!n9#Wwoy_&*q)gHijO2m-|t!+gMx6aE$PbCBk(gtr-B z78n%zF$0{MjXy)$P;HPPf120?bf#DW^lTApdB;!+bSLHcI?{$_1L$cgH9#K2D+cIW z!*;_0$g>9X2;b!Y1@IKX2lz$9TENW)1K{JZbK`{13NJzHz9YbHL0B$)8|W_?T0p{U zfrRG1?-b=3$p-!RlxrLl&~52KNQeDzbCwdbqQ|+E*Id;Dvn?&!xyRdz9jqr z_!+`7z%L0u2E12*Im`c%@HND+TSGk`6&?f52?4A~cm^@oAbgiJM49hkKZ}nDUxz%8 z2tR>5RRVf5D|$t7Nc=Y%FR&lOD#Mq7ew{|`2?LJEQW300JO(E>P8=2wQvbjyS0CKoC;R@ib!XWXFV%rV>3X&UyRg`BHjY2k# zqdFGrXe?kpa+Tr-G!{QWO@tmA3plq6zZQOk^LOGj&RJX?_}6Ity-X`b1<~(P>TKdv z)4F_uaxz*4=yrf-l!qaojZ&V?l>bXa?<_bBWk`a6gX-$yKbm+-UbSA{*}VB6d}MIWl`JGf^MHjvCH{GW~(k64(h$VdM8 zh@l_+^Y6tTY_IW;fZsReV5^OIfAN}O2x$eI5{QqU>U~TV))K!9IbsU&-$f30LaZbV zHo#|~zv44!l$rPi!jQ`MkRSUO;{0F4+^>{UhC<9^!2c{wh@*&U&HB)^0{t+xtB-bQ z8MvQ>brjk-5s&ovL6w6znf9EUU~dbpgH;Gu8QQmCFTt9Qd-WvRDcv!pAdRVjX?KBj z0ZyUyZaU%rgLvXa+Rp@Otyk84BXLqlj)PWqBhCfP1AB-}+NGmz1GIys+ud>6<+5&S z#c_3?kMw!MrwNngjGt6XDH4?b8ltr*pQT78Y*q90)7b|(29mIc=tl`BQZ3Vn|1RYp zF@VjC&qfTRZ$ykU4%YDu;($M7kEj?qr|~^DkUA503kr?-Cq|WB0oo7bBw9)3srSTW z;>QzRL-;WE4EFH&Y!i5}@pq7(aGL&}WYP}7u$B6}g6MA%ZX^5~!apMXE6OvE=&MA( zNBBv?U#9)Ag;G0-vx#UrTNz1?aW!!+5~lyg;#>fHneb7{BN9$z+!&pSCO)A4e4Owj zv?pf_R-%bpl=^$J##<`iN*v&i(Y_9L;Pih|uv5ee2Tug0xO3wdiybhpe_?|4!mt3b zc$x4j#C$hmVH#qSg5M+#VUbau*@%sV4Ox_0Nc>|&e}(w(QhuVv_lfg1rG7}9IV8bK zbSKg6l=^ex@WgqVWSWToTjFdWeU_3mq78pb{Aa0@(w4o%zd`)xh*L%qYKVS@Qbpoa z5vP~vuM^%yHBKk~KN9B-<&PpqHBF^6v zeuK(V---j&-mg);O6@a=UrhXM#Q8LF<`X_aWnU)TMws#&{wLv`#GyPQ(Gx>xZxhGS z-Wcg7RFLGwct^ok!nqSM%yiy?^V;wWydg0xKrCJ+yb3YjjaZn5*reb$i9=XqlxH?# zBVn-Z6=c;b$eve_ZLc6}N1R1v3#rsGqQ63=-X&>7i|;FvDgWD)=R@Mmp<1j&cM{!B zsXr$UPn@SovWfV=CC&!Yc`4OGwBc`w|16bK+PjzdH;Dfnamq+S4bjg~sz{tF;`9>z zb;7%-#_7cWN8-?3lOc+55%FIk{s)BD{y+A!sZ*y;ovL%Xs=8^xi3YtF_#F5ah*3~OK_|f;_=H1}pFyeK>m2C!1-}*e z@Y*j^T8PbOhfA!3pEe^nFu>|Ykk0P3jQ2$%7YUQ%thT8&@T&}m$Mxl)MCegS>QlY z)#;8n-)kfDFgqac+N_gA^)@g?qOw9FEhEva<5X~fDpq$&kVFn--Y9JZ{%+9y!Cwh^ z(CS%m7NPVtICY`H1@t`7<50RE90eRt=rn_W6PyXKCl=a3Gk@@FqL$v5<>0>nzacnn zp`jP(8Yor4=?2b5(364LXt4_Ti^2H-c{^YT_yfSd3mgSbG-#ZD(C5InKzLXU1)T(Y z;0+E*eg>s_uXCW^7yMS>j|UD1Vif2_&;`K9;7pNdhw&;DA<=@-F}pz~8Js)d%m-%# zFb#F#TQv{;orrez)_uTl3jQ2$%7YUQ%thT8U=-Z$9LT6T-4XOHoFBFaUc)MV z8t9KWnRJpI6>C2gD+g7s7fc){w{!{QGYZ7&OWlC=UM~1p#WAcsD4x-)o}dFDvm7`} zKU2lY)iazg^+hebD`4`KD-hZqJB3=1$4)YDmam7YpX={R{n5l74V}(B@1{GYvzIQj}NS3a_waLQI?7owUoaG`*lBH=cT~6 zrdm=nT>_cnkPpNDXbD=^z1RtogZOIabO2X#>3mCfcj3k2<$PVZa3%&1HT*a9dIyk8D{JS zj7S1${h@QnV=l&O=}nv?0%!_Cs3? z`c=!gzexHa`0XG$QMVI%{4fKNZh54eDUr-ukv<07o9tP|RT!&g2 z`o0n}yP*Nkao7e#v=uVDAn$=b`av`NMz5o-vgq$YSk)4e*+$gQ7P%MCZY*mNDbIkD zq5mxOU?!OH1czfbsvlrU2XOH8N31oa&h?1sLMW{zV~zJTGL>jWnT$De9i!h1xeL!| z6bIPZAEi?3(FcBZ)DtM7}@cle5$frulz8}gMg zY6l>r$KWP#vQawT7+=|XQxKGU%A4^+Zkg2 zj?%(FqF6wGgiN@MCb>IS1_Pe}cK{~=Bk?5k0q9)ddWkd^sDR@Px;Rh+=7FDuy65DM zLumLQPfmcZum>3|X~h||Gx)ARZ}2S=sfJPuG~@tB0>k7JE~fy+(5`F^FdEkOL@!nV zB~5rmfh%>}z^Q}MAbEO5ufa2}YE!|XXk{`=BhhX(-4gkpj_{b|p9JSJ=v>e_pr?aA z0IN=cb~T5<9(l5=fb#&7gVEnQ;6&(lg8mtG!{l>ns)6%Lo{A`0@Ixd#b3@v%PJrbB zypq7)@?2MW$9KwXkKXNp{*#d33(h22syOrVXiGi^A?%`T9km{yEpLnk!TI4G@blr@ zd{}6O%t+7!*<5-0$}~AT(0m8JT84I?=+E&nbB*x}qV97upGah~Zfzr&}LSA}os zbev?~!YG(fIz*Pz`sk^P96?h@T?6-!t%LJS_K1e)d|8)nz&YwZ=$Q|G1T>e_Yq76T z*8_G+&D|gq%ccnQ!c53jn*pVU5|S1+%Tg2gIg)Ss3Ai8F5htrpAYU1DF3=4gRw3gi zIh3$zGFPMY6a0K#73(o&3F?NRNBTMKTD`xhTN3yZ{Q2mGr_mSr4&+VLC9w0hVeK76 zA}oRAZM5Yr{cH-9bH=n)a@0di-1ixmNIlh0^1duj`REd67Nv3Qw4l9E>LF2ageM=t zW24dTCir}~9>199d6)@`L0dq}S@ZzWw_J}4%(OdtuEX43uID<;*xATDm^sQN@b6<> z4(ORmo+T>XfzH5}XuYPK)goSGt@W6_uJU;$oe6tFVNWdV(LfiM+C)@Z5WmP6uq0lO zJDg6B1cqUEd>wV?K|WtTs}gOELTn;-c&5C^A+kQ9MKi3Th?maNeoH^eF|U^#c2y$J zlb+;`h~j1v&0E2_EotT;QSE^ES}850rJ>V;RzlFOqwKF`f_#rfXm$~`9!V4tC;e7m z#)4@9;&Cf1xdaWJQ8xPOr;*L2KkuEuYkSQgR=Yz8XcdmQjJAuvveG8>i zfawy=twATCbf2zMp0ralyxl<3Du)Jl@b3XbWvRFaN%_hs&A=E9MQM9r25^Z)We4!2 zM3LuRq_vV}A0YD)tptKz1v*vUDcA~N1K>xAd?W1il(c#md=2-MCKAP+LUKw1&x0Q% zPaTCN68q!H)N*yMj53LI5%}wX+kuZIs>o)n6D%1EP70n~67`+1;RZZ*06lW1V*aS* z&{k=ja25vr7IYl!^hdj|c?rR3jM9nFc^vbzJ7jLdhmFv?u8=W9<`(+(5|M=`VrmU` zNuCJ7SKmUWrF?gS-9)XKkQ^!RVia$MDFfvRt%`de^O1ZdNZo^zG)MSf_Buw+dC}|s zIH8sH)WztGWbSgMDtpZiF%x9uNkS{>4Q4M(d5XN3sVkTRNo9>_Y`FXI3pRnjre*Z`Lw0_TAumnI^}b1ep1S?`tbif zJagY9-%;U5VE^|RyYA@kAoOEtji~Xz9H{`YDM@zn8pBwwe$}C6Da+& zNzMlq&xzCukSPM0Gr&d?l@(&IW1=0UZNfrHPnD>)lqh=9MBo)^tr8?TVujX3o{~vB zIXLtKaFf)=?C4!l`W}Askp2;#k^bq4x+|dPHE;!<@-L(<1m4w4rJc$`^g2k5gHCD5 z8t5M)YteqPcg$C!=ob~7=eo^!J|3*2^rz^BlpiVetF`2PRt+_JB+oIDz{h)Hyg&M~ z7g!(uABS0*1Hb*DdI`QFb*kf0Ivm&+GpZuqtO%2Bu|SMzAm(2(qgiB05>3*U`mCZmNo(|8?WWOO!e?u)F_6dViaheqpCKFrV{HP^vu=U)8` z7Bczz&Ru^~0-9F>@qCtEGi;Ms4gA*F?@z*c)L>`}gJd2`vtYv?##yD5T#uc;0@{Mo zJ5rK71ZN;@aMSw*opoT3Bl!N1zm3-Ipfen_KiVn}dO9R;LDB?09bwN9l-39BqVtWm zBtC-&LLf5)^ag0y2b_<#g5(E zDx4U5CsPU z3tB%(_J(9d%$7^wZ^c>hA-qw;angH8)}o$}p9z~`n;Hk&3-)`UR3EQLphv?en}Dlv z614#M0OPwHGIzkq2j__)BjuMH^C}PW67lAbvI8fa79gxu?!)E>peKPoV9-g3jwQe( z=nuv0%EN4w{8`4ksX8YVwCqtV&aa9?#sXR~&VHqgBi>SYh+1`E^S6ezOArNlXa%tV z&MQ5ZLGOiRXVi5DcE;%7l+V&nN}7=$*j0(Vzbs|Hp+}D-nj1+DUxslx1?+%%TUzoh z6HpiaH>IOiBiKAkpU=R481aFyM?Zhw3mfz(a0Qltz1OY^5hd^ZEA^m z5{BOSK|>GpTEqN&h<5XV=YToD3qWsZn2Wl5fG5x*W~R~x+Ez%uu&=7%^iuCg#H<^v zwidVtPc!%6Y;X^r<9iW;H&6(%BUz>ug!NAD9ZB4yh9$?7h(5_N{Yj6$F_FonUwrS> z1Ts|qHCo5^A@1^xp@IVWZw8V=#GVu(MTvv_C3s>VDWo(~m^c#`;wXO0H{)dqu~8=Z z%@%`J2q#qP4UY(Qm)~|lxoVU#;zWu?MGZ(IV}O~!DZn|vEa39!__#h~eQaDpZ?YBm zYg|HHD%l4-9G8+9Pfh~Q3Blgv3h-8ZVpKf22YfOhCOVG10)9vq#U=v8vn=u#Qc&{6 zIN1mGpE!R}CW1Gygm?ZzyD!l41v-3zI6F4<*nfeVfkj9~;!OfbJrY8~Nd)OeqDeeS zB_r|mg;``F`H^t>S~8gc51UNR`W62&ggj}N--s3~bW24d-?1_kI;{V;vl9H(i(NMC zHQ8-5t_St2lcrybW(#?7E#anLU4!-dt_wt4Lci+@D{G5><=TJtt>T`j2XxUM$uz%|Fb z6W2B7UvXV)-bEB~-7S9Q2wfQ)%Ip!0%t}&m)b*=f7kY4+D9+6);>Bai$e7B}5LmNJHa${PMDXZWR(?5V}w z@Jo5aFCKQQUR^hJ@(wcPEPK!+6#L`Zkp`9_PnOYvG z_JViTpk`|41l1IB=M8G6b^(->yJ%1|@x7Lc#D@fm@dziKNH3AqQ^_}Ef_BN)(q&sq zS8Od^wY7B3*3xxbOE+vS-Td5=_CQe0ElmXPp+U{m9)W5qc#jS0zq9C;&7#{ji|*Jg z`rT&HA2y5b+AO+fv*^Cfq9-Nq!@uxXImA%@km2Uo)2JC?>|=Ma+2* zQdJT6XJwISOWdE8EO9*`Bo-+L1!gHXZS`&${WdGplyAitWh+aC{BmU#u~TxC98y?W ztE?kV$_8a4aaJ}f+k}3K)u;=RYq&;OYdINTMf_eAtW;JCog0NbRdy;n#rjN)wlWKU zp)J38C&yl7daPyb6FHq|xYP^EG4nM8RZY7l%ikMi+6Q;|CZO3`g< zNA2YPiE8MFkf8T@87gPFiI?N$Wj#}8@-uxv-Dy?oO?{{ztwqym2F;`s=p;IgeoJT3 zIdlQdqD$yfx`M8vIdm;uPdC$T^jEr<=F-FTI6Y0z(M$9iy+!{Jx*pLd^cj7@sxog@ zpEYESSrgWjHD@hYOV);UU|+GWtS5_NeOP~%$Wqu4HiC_2X>2ST$HudXY%-h5rnB$Z zOg5X%W%JqJ*dn%=eb0VkKeN?r9oxjVux)Gy+s*c|gX}0f$xgF8cAi~fH`pC^k3C|~ z*emvqedL6z+`={P#GSbdcjcvcSzdux;#IgO_u|!g4erbRc}*U~>+*)YF>k`V^WHp$ zr`WHz-)O&CQ#7vGX^xt+R$MEkmDN17%34*;TeE5bTA)@>Yovu}p<1}sR*TR&Yu&V7 zTC~!-CeQ4uB0nTF}j+rCdKI*x`vdX>*zY-N;lC>q$K@?{z6L8opdKDP500} z#EtH!`$-vkh#n$k=`nhYl%uEUDdJAg(zB#Iy+|(-4|=0$k?O1gYe0NhBi4x2V8JYy zSXl@QA-=2`YexK7C<`V2ER2Pb0M?qdCN)`m)}GX2omeMQn{{DbNFeLMdXOL%$s$P| z7RzEuUDi+RT>KtCM1+iW79|r_AUFCgs~ZH25HG=u~{UX&0%v$EBQqe(wZ$` z3rHKbkS!!_Sr*G8?N~O;Chg@HO-Ki}oGm92Y!zEYIm-`pX17TUyUXs9SoV-TBz@RZ_LTHxFWE~H$KJBHq#yf}{Ym<>0#-ocIpvfL;AUnwk)?e!{_J8s# zPARlJ^`teZKYd9j)9>h9`Zv0m{y>+}4Rj0LPIrlD+fR?s6Z8x{PcPH!^ftXK0NvftT#_Lx0qui1O{iJLg%g}4K~%ffjvTAr8Y{dp}GA*dcalE<=}_M5~F z!mQbAg|(tu39YnNPOG3**L<~_T98&>YpgZZT4=4bc3Ma6YpuK1TZ_>Kh`uHxvk_!A z6LOk@oJNt;ROBv(ti_S9%*a<3b@{$Ack|Xj`VdNzzrJdtgxA=`K%+jt|}R7W20K^~}qJYYp0@I@Z*Lmu!)9tc1l zsEIsK8+jlQc_0XRpbqjtUF3m!$OH9}2O1y`G(;X~ggnp~c_0{hpb7Fo2=YKv{KLXihrAP7%6RlgJO&^hYat$MBOU`0k3opXI*7-* zh{t+}$NGrJ28hRoh{r~V$Hs`qV8mk+#A68Ju_@xQ8RD@y;xQEQ*aGnwhInj=cnn88 zwn99%Mm)AbJhnwVwnHSgM}^?2Z`h zff($G80>`@?2Qi2n`dVVHh-wfQC`fAogJV8z}*5w2c~L zqta|tx{VrZqcUvNxX+aQ*C!3?B`C3L7kB*|gs@L6pD5z~EOw*f9xXO2;y!IhEaLte zi!U37;cTcf3BXR@$^NK_Us01j_)LlUAkPnuiC-_pUhOL69O-Bg?V?P-(g)ZN$~^?Z zZonjJUY9#SJbkcWUwv2XCRfSR4JBLOCz7-Fh3y^x%QFdSlYHvrLA-^38yP1MN3df) zYCB1|Bfo73>USIU$7hNUk<$O|4qSicX2R1p4bPQ?vy^AFwAx4QtHv2moFMC{K6aprG3Bt>U7R6H^jnQ{9^+CMWs$mbJR+!o~h`Nn&#E)VRb1 z-}2USvYZxm{j0ovVq&U$<3Xu?6O-dohgr*(aIn_42KtHr`TJV^x|DG6^%Fm93a0p9 z7wa(iN+{t)m5v>Ji&~4wAC{taU-eGu8<)^0RW##db(BnVQFHs4=mCid(Vq>o`)7t# zu$I>iEA?f0bc}n4xIPI&t9#ofjjib>537T108J)FXu7E|5qvu(-DDzLhK)MceM8fr zP5G^Vc>Bm#^OfIPU1$+sqhf=YUB@eIu@Buc zdeGITJ6BA1Y`edb*Ng1C4i(CsYFzO{BWR>rM%B z3c9+}^Hpr!>L$N}{3@YKH^rOAFZ^@c`l!+A@4IEEWsIA)_Qlp&Kb#0$+IC!tD&t#U zwZ0+sU**29pZ06!IKAzJ1h%f`o)HyywvVkpzx7eCZ~PN7n)6dxC&Mz8 zgiP||?(x?I|}!IAHi|L^BpdSSAMOs-dNLXlGq-b6jR-pE>5+E~jt?eDUDrInw6FDob|F4LghV~F+RNg?sw%=L^NY}-az>0;ne$Cp^j(Ledl&EQl=v(v-?p%t35|OeY`Yf)%0sY)9TObwPd^_^Jld}(d=s9O*aQ~_Uw**eVVRkswz3;J|V;c95UA}$G_Gtl!Ur?u!!(X4i z5qy0_{>_`K^50xP>#!l|+>G08HU};lSv{}*DrQ>lQ(#8`TnOPD=)ck-eoO0&fUeK+K%?G8sF$)y*;C9-1t37w_Yw= zd3;Q8@?b}iV}^?y6KUj_-lh``kP8cc8AnXynSWzc%Y+joa!hSMzW}RWkW4tfR)5=1 zYuecVC$>3Y;)toMwrbP1{bzCdPsIPn+_Td<@z18o%RBVXn%IU^*!^o>nfmL#ZWQ=3 z<-7FCf6Q?v9WJ`1JJvg1X8X>!!BgkveGDvh=a=`lAD!tg#&WZn1ek^9>o_E%?*Z(;8 z{1wH4Ls`nf(tdyIIU}>K`Y$HIkAOqX$K$rqpQCK}sjkq13&+^Dw*Df!XZP3{3C@i$zNzn{kwod_Nhw8t}N>CJika{@Zbwg zR&LD={!lR{AZO6pf!1krHjn*~d?)`{?Yni7=CyNo+%|CIp;u?`OuAP!Ddp_rn|nt* zdEP0Y%b4_sPUn;91LxL{t~yK^5zbg4jHq5N>+!?Yi^ z@7&WbqONbxJKhOLp0}#z_M+_I5t(ap$DdnQ?eVIkj=S$H9)0h`y^Q3Dbk~Gx2eW2x zELC<-;>^pDOZT+wzxvSQ`ZI2?ud#CYkf1*O$cXes)ahE(>=u=Sug&(@Gv5BB%MU%T zr1&M*DqC>SbAQG5ZDKnjdZCfvUw3o;GB$s|({?dSop<~jDH5$42Xlh_s z8)6i!b)4sUUH_SBd}Px%^h$c-V0T*O!`hH$zvzNF``Z$H(5&9zY^%ic zr!YFTJ@bx*0ft>}^@m<azdsd6Q~sTKIpo^5oXt;*EHF!@!^-1LXm z+>rrmI3%j`iRbf2&CLr(Lzd5f?%AC@^Ip&_ahKMkkP~hTLGi^4hjS23p3Fi+6Q}@* zaS$nqrJyG3<5x15P<6YqOq(Ci5-~NAM^w1XZ$31aw3G2tu~xn8x3@E!o46T{pAWYjV1mI!7JtgATU{SgQ`>c{xSj3MhqNa309xyUMSArI?$vRkb;kTLsE~W&^y! zp#IZY%@@>{B{zJ=d@spwc~U%i8#C8wpY?IMZ#Q4J#7ryw-CPB>d)_t2@Qm3~vBj6_ z@dKOoCC;EAqgfHW$MTD7JA#bkpO%f&nZu^b?qenv+sxXEkKc5NRv2lFuySv+Bw8HIUdnhk3n5@k#o3-fBF zeQJ02pk#-vcqQC)+X^%@szFaIF_>9X$r(6pbqwSH^Qm@rc+~9U9$Ck4q=JaAO{2Y1 zLqXM%hBMA}uZ!aYFT9^Rcj->tgDt@tivl_EO}>tD4l?^~3Z00<#k}O9VzawRwW#d- za-#JgjRKiR25B!gTJ6iYd~dV$!Axlg8`589>l2sj=eRG|h;x`*SMgkc@eAC$S|g6% z-o{-Hx9ryN9||nEB5_?ZY&gm=AkZkGf6rJ-zrYxYi2aC5wYD+;m}>oTV9es7RUGG3 zFlS0E(c)8cVL(RizJYpZt)shRRg(8HKXRhdkac?Q zN7+f6n)tAb$HGU1dPQup#S{Ko9i((vuAG8`zZBW!T-Bjb{P4JwTsQZjfEmWfY?-%u z?Ysxsy?sIPz1Qbg+M{TMREcA>OT(px(7v4K=M}mw7`P3(HN&Kp#AbHX)k38RH2iUx z3u2$N=kwNw@7iYt!JdiDBWfkouPY&Kxh00@Gs3=nPCKBIs`~7xj7_AIezFv4k&KP+ z?8Q5bme2YvCya;o^b35&j{|!?4>4-1rNSQUmpF_}=H60zd!(=A`Q(>{<1=;yufBPH z6MZMr=>4a6GeY_9KE11ciz8_7qeh*p5qejPGgQbcnL;nl8%=eFz0!W#k=x9urkrox z|0P3vk|ceiuHo_XFRAWtTXOEvzZ9ldAji{Omh6X)N*nk;6Dfo`pgR(e-nisykS;A# zJzbk0Iqo6Ux3@dwaf`B$%+Ta8oIozX7Wk2NmJLqm@AFa3b(E=l1})s1spOv1l2&Y! zDZ)fdEeeihk1XGX&8T*EJ&q;95PUsoVpaZdu8vpan{;M{`WyJ-T|N)*aguRc-bqGS zwYDGHC0(@jMzq<19+;RZYuace!gfW(0GfbI8y0i@f%o%RT$% z2Nw>^V2=54TuN`>ALY{v=yv{8gTp*3KGv3Gl9JVS%aLQ~DT=w&gbsSEL9%^tC=XQu z3HAwWh|6?mE3^?8QY$~(cC~VET;~n}O4MsFxvKY;C*5|-Q8DOE1jBRYk2bVb;kIjh zv@Vv2JviDoC>BxvWVt`0P6Myyle?Aww2?DsJg3P15AYA5>mUMT0FnUVfr^6`HjK~# zLgfLwc+L>2Hf724t6xqPj7u4~VZ|jO(`2PaJmukf4tGi=aidX3dE;gccmB>%&%B=c z$*&oHaF;tGg>8oln~-<%OhHzV!SKqe*^$OZ=dxKrlCrzhiU-3QxO4#0_pYMt1hDnU zGJ3(|{I}Mkg%06eq?y-C)V@O11-<(T6xF6M_?4RFup!fomJ7>O&lk=WDxGjlEgR)V?px z7^mQb-5XqVYHu)1B&MA+GTiyHq98*%;6sS0dQ0t2%>WJ@muP_QVI=ND*lx?C7rj~n zgfAou@Ldpy;4=!p7h$A?6|Ll#?CtDr(D~9ypN-kIcq^3Sm@%*RDardM)e_9Fj1QHU z4Qn|)SuUCV=3gfGc%gTtdyJ8^;_3f7c86;G`6sy(5w6ci8+_E5WZcK4kWU)u=}


^yU}j^Z4oiwrxy82D7!5$ zO7~qP(`seN`B6iBP(hj7zTPy2Zyn?3u0%zjx*UBnwx#6rCX?7R4!6$>$-F3h7Do0~ zne~dB?&8nPXDhQqEpf3EsRVllortBZ4QV(lE_OH)00OLyR7T zt^7>0nN(Om3*Mv+r+w#DMDi3|XaNFr0^MJ5ZMivY+3c@YD+ zCP>p3L$oBHcBK<_UA6S^uGV-IK|}#9=Pc_?v850hSb#IdhH5YCEH8p3&~QXqs=e&0 z8Ylu-GhtZEi$JBpQb-V31kEl-Cs@epD5?D6L?>9ti&!!kwz5E=larIQ6I7Z;Cjr4I z6bcA}03i@5I>AE9-i6A*I!jUQ5C0iKiD-|flWiGf8Wpe_5sRZaFyuu<0Dl%kvHcO3 zYA?N3m^7Y70Xk!CfnaG6a5WHc)$^xFe^mFA=HJEEA(Jc__WwBpea&Vqku&8F4_Qqt z-I_>1>(L#EazGaK-&6$nKak%^eo21A^-J;_u3wTrwj~`U6|@}i#~zFR*B(uz668gk zL=@0}e-g<2bP{L*pgy9TR8c+lyS;D92?GUa65VR z@}6twY#tI+TGcPPxJ(WX&cBlH>m*Iu&v&@>J(Fe=1u94bg+ez1{Eqf-b1SGn9RFaX z-GgnD+zU2)w(!(c&J}L|vw)!7LP_~E1DltX)4ex{n$q~)wlt3PuLQ#+uL0TE*mAfiE#-oh|dDPU;&5T2_F(EGrb{{G|55DshTxfIQ+hV^*=F(1W zp54;-Akx5d&D4XDlKn|DA1?NKTD?=?TnyenY$U4w?dVBA_y(O#dY6~Fx1Hq?If>hO z%Q3ERamahuwkr?diWIutgaXIcdEK|Tsl&G;7f^L@nY(p+rn7nH%VWh(ZrT{ISuc)F z@5+(-O_eV;wzIkQZ|=UbYdhP00DJ1j;{lr+*@Oo!&zf^oZM$KPY~LnvitFJvzqlDl9YN30H~Y}faZy=A338%Mog zc{cl@wk5=fpK>z?;}(Co!RLb@16{z`bD4@UQ`~j`Xni`EkCQ9@cIHcG>;q7BxI?(e z>kS%`Lvj|}&^r-jxJ>p7nAA-OHfA|{#+P>XG4L2_Oml4WoYbA0x@Cs_a<&aJ2c>xp zysS&3D|*T`-wjRaI8%y*&}?ri(_iwwADuE;*s!$OBL<*ZFDApSxTE^I)OETd$J;$` zH@p=KJlzcF+;i>b#dj7s)RfE=yPfaC9Z?JfkROCQt=K5txVzD%(WLPVBq9~#D54s? zWx!-WWmij$p*C?-LQ}%+gvf++b?s_%B7@LPY=^i&you5^zPjAEj#Pw{ zKCnq_)|EbY*bW7wt4XFeV%y@ELO-+?ijTiGtXj+i`;S=f@OIaArNFpuV@hU>Y z4VWx4eEd~l*ReJcC*29ZqM)K+In|PrCHfwxmy0)=yfitajP+OaF2yL{eQ*UAfV=bV zRK=NFP<1^qH?dHiD~&r6-D)zjuFx~4We3Y@+-vM5QY2y|_$Bs9@akLWkyEr%s#6kE zNczbw;#SP&JgY>j;pUh|;z-?RJy%q*H~R6D)QLoCy>$IagV?tEmhDYdEtW0L57p`k zmPaf@tsJfEtR9iSSf{mFwH74%wOLpmB~P|Zw0OkFKi+#k+awu7Qa3PdGj>X&W>0LA z&x(mRO)`z{rMUZ|F$&5nmzTLVwZEtVRL9krzu-nZMGOcW1PQ_v4|E7j`F`|O@l~s= ztL&((t;8RJ?NtcA7`!uhILRofA<0d{O;aJlFe33@OJol+3_K5h1D}Mfw3NQMN<2rj zbKBwK^D0R5jBHp@2JGp;g@aFv@XDFfxt-J&%4|btKuhBw8~K%e zC37r|dAl@ok|}*1hFv?xwA#PnXg0C9K7ztCJ*Q(N^0!92ZCu-uFll8UAYZfch~A-o zvMDDZLZgDhC&;py(E?FNqGzLnqy13|PGI}Dg-`Q~?4H^8^t<+Q+08H{ZAYEL>~`6w zGdu_GzYYA*Fa{na59Zg+6!CU4+pPWDZsy)XG7B5rT3=O?u4(%NtC8iojq{nYSA_f0 znZk4PQ+=Z==J|8<-swAR-2Fls$bM`b)!d?g{#1C}i@21yqc4YEj$U)ah#$&4qC*jZ%aiRKx#aOirelAiR!YBWGKPakYEkSjffTr6Xd1!P7O0R!UaZ z0@6~_<2>44VWp#L2AXEk=x}U!U@Z6^IV>M&A3DjTRb9a{Fu!JU)g7=xDjs-`bfh(Q z-_0fCvWJJ_jkg=?gqngu2OYgYS`Ld_s zxqWrrt>{?x_APDfwd_oG1)j`XPuz*i`d5RAUGep*XS%ZbN* zg66_`F7+ekXZ+MPv9*hsZj6(aymi+o<73TE{7#avhmNpm-y;0|Xyw)luTn36RcBQd z|EX4@FqFcx&5{{*K5yNMJX;(BVtY{P-w_>Alsv%xluO z+}F1k+ZRy~={jFgJmxktk5o9RAnq(an=uwR9bX_k>$&>RJ9+33qIF(oVCtJ)>q2&H zmd966;QaNa1REVnmR$|*JbE7_mlw7i*(@tnWi1a!|1%-#!J z0PgpYa((n^x=NC1&|`na-rqF2IL1@=)A_gK4NksJ#gm77wd;m2z3>oUdAO1}8a$c2 zjf2d=@qEMl^_j)Lf8a#@^uYOFsRt+o0{MSVJ=p$4Y5awHuq9Xk!P3w*M!=R}A$yii zBRJrRbhIWJPp8?_EEuIv00uNV0RRDkp>nJC|FZcTYG92@`EO(e0sn)guyvr@tg$Nu zJdkKZq!6hLdmvaEyjBnaFN>!Wu?!j=y%txOX!m_!Lq=QSUFhHQ+mQb#WbHEWXQzKo zru-=IFKGQt)HqXYWij8Y)1%RB{vBZJ&Hm*_RKhZd=v7#yKr&KbupSs83q#0)ky0R- zEC{ql#eC23-Ez%SlSUw0xcqNCf3p0?IACoxHUBdb6v}rpY1L9ziH3Jry@P5>Xa@%} zK^7zfhbk$96{VC8tSy$#K!exT$d8Y!i)!@) zo<_Bx(J8C*L7)0z^0W4D>ing5^nWP7ll+qWhU=H)H(b9Yzv22N`3=`E$#1xRN&au( z`hM*HQ)b*eQeQpoeY#EFC4^D zGX#lT{RU%Ie&7c|qM)$#Ius1NJ_iJafUd_BfQ0r@ff12|0tJI$EP26T z)_H)zGAwz)5SCtpf}xQ0m_or&6srz~V3`{j&T=oIU<8QO4uNFVAz`dKnZKEbj0}q% z1iZdqz(_b8vd#{SM1qj()+!i@gvqR1TM#4&hFI4x5F`WyUWWk$2|<8ad?850x_*Hm zp`i8nL6A`JdS56Q#?ot0FdT(kw=SVz83g>Nc`)c$vJH{WwfgfAU9u|?fB*q?Xfy@@ z3;+RifNE3=8elco>R8EG4y>r83}0KNwm;k=hJXkv8`^E`{ QfKhNb7rU64vbM_q0N1E{^Z)<= literal 34300 zcmcG#1yogC_wY+8DcyMll;(8M-3`)*jzf0|(y53b0wPE%jnW~~D2Q|kh|+?9bSP4H zz$5s)_x*q4es_H1JA3?gt+nP}vDchyuer`GO<8#Xuppf1R@aaCTp~CC1aP%Cvhe@_<((|NY-DY$T&-=y#fdz>nPse zW_<&vsOFm*{yg-Vfy-yu5!0pSgY5S4Afm(rc~n#&`MB`GkAnfnOME`=wmx}Z zELpy+&QW*&_S-N1FjVrjoX!JTFR?Ng{dB6VdE_nIS=D}-@5~8Yyz$ii$iea8#nC`Z z>oS|^#;KQMi=B`5CSA?jlVzU?U@S%WK~`)=ib&1FqwXIrW-cw81Fs{$06VJpB;L~c z13UB1-UOsZ$?b107K}x!w76?{(5jrZip34@ZT^l{(g^ew=sd}eSY>MgrG%u8+T`m2`$^uz z12bcu^(EiB;Hl}L?WT-=;(>x{n%yiu)_r2iI>JSli2T1MYcDz_DPQ<7> z(_LBpK=Zmy@$x12ourC*z~&c;2Scy-a~tI-f6$j7UNV^TcvpM4lp%b%yb}Asago~j*GG{>*&-{*y5h41x16h37!1*M* z-ZFyhd4JSUgMd1VH-C-y8L8e4VIH$;dAC!pn%c(;t@8(Lhy?eBf^6m%)uRnVx2lRl zWO4h7%aFt9nEDgvXWo=%TWr~M-gG~FfnSv$)^emd_&4k%%E)}cX=M}Nqf#mhf{W=D8o3SqksLw zY?mIvVaMPG0?ALOQ&E0$&L46R5}x9;o%4{TRqZIA4qyIt4G-rY zTUAOP@gsbLG7n)jrJg9g(HDKzzp==yy-NqkBj&^%K?z%Th!n)Z)z zF%Rl`1&Ss%3JNE>y17grXuj9Rrc}=6bhtTOP;x4wAVw!_HXmPY2cbc;T=Z@5Ewl*1KL-X>7UgLMo+wRiyEnIG4~*uTOK+)hU`!P5RTB+|k;<@o z9Ho)I|FOB=((B4`Xk}pTAN2;D$p}!sm7nm|8o~|LlA~=>cJHUfdG7fQ{{}FGSTRg; z3ou!UP6tSHG)c3J0w%la@Ah~G>$Kw*{h)bt#*g=Q_|tn2ux64!GEvpi$s}QHDw2Xg zj{M_|WU+6uNjN!avQtYR}a4&JG(q4o+zd6VbQh`0wi(VqeQY z5iN|saqKy=4&3;5c|P*qdFFwrR}byD$1bHP1&gJF&t8T)m{f zQ>Jtpz3O?MF!FsvM&e7FDx?1UC6b6_9}}BJf>+ve_sw|Hi`0B64!){?P@aDEhwne!uBK@{P0w@!bw2 zs@6*a?w`^Ux?$EwF#ZLA@k{$esQyb0*bK@|k}$v@Ie9`;_{RS^&%NrLeX%gQkvrqt z?_P8(JR2-4%4Ms}&k4$mKfXOCX^1_7DI0;eCARPBRfF3M&b*woD86f%J=LlhE>3}N;n9rq zQ$h3nbfpK8bxzXp#C^hYXWY9TMsw#`iSkPQ=2O%|KwgbY8%34UHv@l^YKBwuGv%|0 z5+T3dd()^IS%<>}C(zBC-Tl$VMVY}A**t5QqzUmdoM$f`I|-!bAL&UIw#U`5 z#O6V)yY{MK-`P4Cw;jKR{_Go8C`m5Gd1mbyft?SWH{JDC=c%;=hTf>}YCL1vY&MSq zrs4(w%|AZvebtR>h>oWExmq&)(`h^IzNE0Sg#&R{o>TQi@wy-PS@ZL=*LnwMIZt8`;i|wSdUrDkC)p=}qR)n^Um)mBG#&-LN>is19^4Mt2 zQVSYT{w*-MYgoCRwZof7S{KP=q;=b8i~m3=3I2BJk*x7eAO4Vd1eM0@>6)#iIn$xQ z`W>!r)V}?A-Y`;Pe~16%Q*EurMttPga@VrJd|-@-czS0o}!U-JcvaG5!!uu|TlA6UZF2Q5*{!)Ol}p<{U8sQ*Z~Tgyn* zw_)WZawPru{>d3NlZM$1_0NT)+!W)ocax@TKh+-wgikYQ71rcz%g3#g` z$B?cGmfIa&ZEW=nQfmBy@<;`KystNC-)QGK!VJ`feff6z4Qj-V0#+aY!1DiAwwsYE z@pRH(Y3rw3cXek=_Nv|#u6l%Lk22p6_BsOX+_1e$hL3`6*QY*jjf)EB7YoB1v@vhq zO?p^5<-EvJ?ch)GcjVtwPUKB7r0NtV=f+mE4$n$M&vrVooE*MP??Xm2O%^MiLKlLW zrF|>1VuT_E%Lf}XdpeUzE9+@0*tkn@191aiC>p6#4=?xG+7XWk60te4pla0j4;?w5 zwz`!k%xwnW)`Q9%ua*N1Gboz`J;v+OIO2*2;&Wet4v=xXL?7?l4X{UfR^8N2$aY`) z@?Dn`GLlR@71v`M*ZC!bmw`XJ)rWA!c0^dk;&~g{-RZ9ts>Nd252^#O85X|s(5qVz z>bntk96kh{7ATZ-RPLLw^&K4E^NcGRZB+2$LZKJD$`|e%->B}jX`y<=AEzG{$Yk`* z17f*B7v8(ScJFpHdG*WTDmg_@CWpgevKmU#y(Po%E+O{zuK+eEf9IU-qgN5z0;!x5 zGjpr!YWT8abaderyTES>@_n`6+DdesRKQZD+Vm`0z9pIB^?YJcjumfTQVESs5|K)L zL(k!S?9*;}xdHU4NCjXus)|-VCB~RHP)#6RUrhclOQaX#HSJomVKDZJtSNa}@OBW!&7B25*e}&*k7Ltr?dy zV#xOaY8w~pKc6!;F4pItK<6Jm=SL_6A#`~UEc9RBM-b5e&IeMTfr={)l3I^j=k`bv2}}ib-z-7WwDUc)hm+yeU|r`HQ+d-7xgAD{dO#hRia-= ze8yM&Xe4bPU26ENFOKYK$y3+9-wQJ(6HP%!Dh}vCbfD3sX;juk=sMZcwXE78c8p_x zK>nvG3H?&veu(2dRx`rVId!eZ#1*K&DcnS8OjKavTQ9WS8*E-2K<`gOg}ZrxSZ;QX zbkBWTzjG1>&A;QjO?MB)d(u@$Ce-8TVbK7zn&Ku6h&&Y;VsvELY@WcwNH2e#uzyMZ z6=~Ddr1srf&*#Q#A7E{UPOta6IDg!FcjwkXQ+dLHNNs>h6M1$6{v@?!@WYC|-HoUv z^EXv5aC;R?b{({Dq#0y9YIDy(QUs}x*iapKT7KW?T7Qn{SkyKWWYEaPCgzGgISdwy zJS=x|BTsJ!DV2(feQBIIZJ;#T7gxDw>3p`;?WMW2-Z5(>T0E@wgHyaBQ)wfW(v6)y z%PPy}8+T(yveI8?4(s()yyI#Nzk> z6iovYs<*3+Y_m#rDd0t(scW#YvsvR>5J^{I&45_18iCBUE;1`sPN>O|Ef=#Jr> zz@sZ>*H$9$*H0_8@pXSuhKLh+AgKn;K50=p z2#|&m7dF=RNsl$Ct6=J_N16>(_h@fF9MThasmOkZB_wv26I}WYDl{m%lf5{dnxRM1 zsX^I(fLnKeyz_0X1vp8Ah;(|WogZ(@{^fSiER++W=>ENClHft@5Ms0xovtzx=SuS} zC9N)s(~wfvg3hWo5(_VQcpCDTi?ZEu|dwOWB&bawFh?bSHe>hrw4O11LcE2sW(0< zQosS;czK>1H>gZYyJ`;i*c00y0oi*R(g8J6 zLV#d(Plsv6qBl=~h>71!c_E-C#WEVxU3G9ny_ssa*NilvpUZ2&%)9BeCY26(dH<+9 zH~KV9{|4rhD#f#LR&R{%J!*Sw27&u>lzu6M>Y1uc#YmsR)V#*#2R?_5ST`rfcg%k-xVe=`gL|C8a13_>9P zoxuwOul=tap4Zzy6QY2NS_fQIyC(psVsGsUFurIM?SIOlO=JQ9%D8&FcmW{)l5qaW zeMBHc) z2y_J$iToEZH1rB68hQl+4ZQ+{hF$?jL$83Kp;v&>&`S_V^j{EY=oL^j^a?l{dIby( zy#$OvUjc`s|6pZh#l^*ihC;xXC@CqSp&-x|5G3*nC=B@*I1>E_V`F192nxFbf&~2q z0!RPB!NI}R)z!?*3=IW?ui!r43=Iv@AQ0pdQ&Uqk6b`;bPEHOD0wb@0fFM^uALT82Az~F)=h02D*fwpC1i@fUbZdz<&Wj(O1Bs=u037$Q4i!_%Cn}`VW$ll4uYF zc8QFPjD>{-+VWz9LLh%ZfY5(9e|Nx0Ug1n3eyJv|HtqoJXJ_Bh`l5C|FqgI^*p zE{+C4A(sdX3!|Z6&=n8_;tCK1@)s}^eFX%Jz5;|qUjhLmE>TfYK|{dsD?m`hUqE2= zB@ozo=KcVJp|1dg&{u$<=quoG^dIisyN8B?VOKzq;7jc6?3|sQ-QC@NeSOgoDC80e z2?;a^0=h&*L_|SB0S$qG|AK&_|A08}grF-F6&2AC80-=x5-B7kgoc8VS3p3ZO9BD{ zjEs!X5E$|bC>(MH1P=KN7>53Xva<5syLZu082l1>d3jDwPBa7w{TDDa zHa6zw=4cQUdIb~#`3newz5)zI|G~-02@Qq9{{n-cuYe%YSHNNDDY^b?$R$2LK74$9IyyS&i=UsL zpQWWG8iGLn1&%;p!gH}fK!_`#Q0NsPDCi0(2>us10)2_s`6ehRh=#ynSGZhkP$=XI z2o!#awY4=G0ta8>?d^?*K*3i)LC8x`DAcW6x6n{1=n4n|dIb~&yX4NDJ7^FHafyL} z0U82_UIB$7FVWJ{QdLz&L!hv~Kw#)U*xTEqK_J)_5Gdjj7Z(>a1O~mt%gYN51w$@z zbaX_6Ac(&}k?6m`(V#y-!SE|U5a?f^VDu$W24}Cy;Fs{2T#jG@jv;00;z5 z1eCV-^3=5Pka2Z(b9Ff%aHEL+IL-gtvMDCG*?Tk%#q>WH^1Lo7{a-(J zYe~sGEYj@O5RiO`g#KZbCaxB?ai8QuJVUS)RT)kYdoe}u{jrB^X@G}`Sf^gw5$*wNm;SX?9GfjqXyg5fo zyc}UXH;&d_mZR$&GkE67(ZYDS!XGU6yz|IJEIY`1~WV?nqVg{=ekLBnoSSBQ5X4AM> zLEqo$G7BH6BuIoVIMAas+Xi13F?PHju{=B;julqmkys0RaSeHcSBNVu6uN|#u&+0p zoBcdilkQ>qleI#4eUf~C(mpL<2zA2;#pa@_^L%K}%Ja7#V+^2piL zj!cHnDkFmUw|9cDPOf{YHL!OVSe{%DYk~_kY$o&Dm=EiQ+pUffNg4@9W|_T+>M~oC zQ7UYIct$U3Z8z%8(D6F{?R?bY9ES_@U7e-EbcJ|^lH&oJh0YmDwqVCk5mUDzt4OOk zC@6Q^RCwiJ?tA9~8#%wX-nlD#eCNl7MGQ|C>FkZcntiAd4O08Hz@2{Nf8eWM4e}L%a}W%A zyv+z<8!ZrTo)Vgqwbz_vAo1YF&d+sg?aq#o-aevdz&W7_$IJ&uVc%XbwF2N44hYo5 z^lt(8$6u>`*_3A|{C=GLp|9mGKV6VOKE_g5z{P;T%kT%7@y?syU~tjm&*KJWw`fhT zp&l>Ls1|;#vf}$6);*p=FFvuWI34dMqeVksjTz7DJ9&;eDO6almPUp+hWW^i%&zX( zM@G$Ak;Y{9^z~N(K{@ehyzMf))x8sHGGp6nUfv2mzCr0kPdtO(?#`RIIp1@ZRsa1% z2>7Vi@AwgpAI~?N?EZw=N7^p0RyJ;es~AWQb*Y<lEE>`I)2L+FnI65wv8mE&6 zn4!sk?nHWjX*XtryT!2VN$*5RynOZhMK0zG$ZlxujUm%Pp2C2@2UBD5a`BZ%?GiV% zzpmQ*x^=YE^d(n1(Qs3l6+U1S{W*qw-P~+>w%%RxBW4c1DlYQxpMG~->E-Mgs^`C!?ixAgozt4JMGG>j-DS8&M06Wi zqVn}cV^jL=jgYUzvl*#5)f%0+1DxTNk8AmFr9OS=J3wqBt^EGf|ET5q`HB!I| zt1`M-FTw&yNn~NgJV+W?4=7_LCG#GNK213rYOt(#>LH+Ge%2nh-=@SiQ*(EaYxO`7 zHEXo3^VpBslYqvRV>IJIrqcU~zCiW@Fg2kLCip2m3E2aYV%avX1~(0s`E*NBeX0%O zG$FXGxJF25v&pLy790^A{W2=)_V7BkJL;^2O*TBnAyN_5*0$!qSW=E_vv?mqjQ#0RcOHmiYvPybatnhH7)|Ud0l5x83iAQ`t zN4qWwrNOr8yRhhy*teYdWe0Vvq#VT?k116bE4d#~&D*qU#8gW7j^1o2<7;=~hSsWxP4t(7}Zw*0K>da={O^03MKASciN1YNW7M;TL`LzSC^_ z_a!&=qIm)Y?h}!0E%^C<-3d=gA$iB!;#(P_clK16BzoS1oS@7En#c(Dlzi{b6(dgK zI$`a)xVu(dV9a={S9|%?Sp5#3Hto#~vwB|E2e-D&+fGLb3t}45xlf5@2CkWPGH7n) zvm6wV!uqv!;)BQ^Jv%6l^6z>c^6bMNd`q-qm+6NFi;Fz{@ghd%q5S-OqJj8O$D8&h zmfoV*Cq)a>zkWSKFCa)CIucAJ?Fh*}7Gujxj#K{PHX?Yf{S~a6Q9498WZb`@^Hy+< zs%SH2Zewnr=;a%i#$T~an|-IRD0@MnCq)ZEipPmzsf4>vEIN{;*E?k+ml`_7>7Vq@ zI2wRDJ|7f361i2gGQ=iM69|+X>#s|pIq~qk`+1^SX#VQt{=(oQ~xZ-nsH26+%xfC{^(aNjcUGN~n)`!z0PFNvqCa z72}!rxtjnzP5x5h^s1!Ts}Glo(ms@tEu4A%%*Xirekv7uQpBNN!GX3et!X5K`m7~p zF9m&$7ry!OcYeM+(ze%N_zu)cM@d)Bs(Uz3Wdm*GS-monh6|6AlGp7EeG%O>bl9pD zT|xe8x&1*eZIVLrxD6ty%eK>&)$z5Xoj9$rai(u60{Y=YtONZIT`nT?==VS9#tTI> zfREuW#SUoUl9!8i-9xOpa4`qlK2*cYijNB)(`MYO@w58;q?7>8ECntBEAc6Ty2&-N z!bRKi=0a3$TyEBrvBK234G%OV=+ejN**Fp;9>iwd@pf${67=(=wk)xbcGIr?SYh!GGm0%3u)jiT*7EcdRj0tPe@Bk4QJXlQ^ETlRjSOzN z?15(s{w}H~$Zmas<;|SHbjTd@pFl02+2AsP?>)1MGyQXJ5hZi;x!!u8=cyuaymM>A zTz(w9Gbj*TeQ#(Vt3i%4djA9HlM(g2+)ERVHcWrisFteX>uILF$uKTZ5RxYS{o2-% zwf|PZ&rFND5BCAU^&#B0M>qk}O5MY}WtC(&OhQUAMiW1HM#LsidaUq1+Z^@M16&&* ze};wUD1T8}j-Bb9D#FrFLI>Z3!^BAZaD3yLT?3vTv!RT;%1RGxk~Jl;U%Zv-!7Xv?CCR+0DDYj}rOf~*^rzmzZ+(D_esWxvoaU{}J^x%Y0GdwFFmbXR*p zk~t$6M_6zy3r=KQN5}G1SX|ofM~)UXQM}Z6#Yfw@2EV}==wy@{ta(g)87p7^EYxymV!QV_K zUu)dR5H1;ObhHO(k!}qBG3j4Oz6GHSZtq3ibI}N7s1jy?w22 z$x7v0sLh;MN+J&XJOzW>6nY!Ta+^78FQn8h4S+vLg`hvv|FshmgqyMr!h(XH&Po&4UQ z5FILLEoDjXHqv9Yob3j)4PJcVa5iODh5<)^Y5U#OLPJjz6I5hv0DokEo=Uu4#xwcP z3nLoN`QEu9C+|#d=y?V*<&TYh`U(Z{mI;-O&+a@JfTX|pxM|NF|H|(5t8cER`tBNa zOFK*TpLZHvo>gRJzy>}_CMo?iRKF&GDSVp5Z|{Kq*pi~h zg7SCPjaQRkE_6s6yHmLm&8lL%S6EzpcjbFcl`>+#kms;*HMUEkdS!yb$ZzI#T4FwQ zrbXdJUlie}u=nX}j}k|G$JI2xv^7S^?#CC`5&G6CPseQ$Fy@jEv1xj&#`;egYV!4+ zzhZEEcFVsE;NqHK?1$Q(lvSH%sf*=({wPE-{`=jn1Ik}R2e!|@h0O;B7#oL`=cte* zHbAGPv@w)7RalZoYj{+(F|?H(X;ClxVVvIiH;bS*lrroUS5;+%xh}3IE!1SRF^mTV zq@WjS*zt~}(t4A8DY7+HCQF65Xo_8jZ|TWub=7mM1JCw&l^@=Z(5W>_7*$Wr6C{br z4eu1i+8r(~tMGSVw`mgN6V&c1F2H}yAEvZ=M|09*Rfs9cOzX`(Fq&LazK_-#nn|UF{*KF-?2rD*QLl7T&y;5m2A<`S;)~0RvW?|f z3BS&>x(^;R%qR)~s}@Qs_msvsu&MeOoZ1&63%KSab5~O8J7kq>^hdBY-kK{r6sIk< z9J|fdjz43$9pnBxNkNzVkXKLTGdb$<_bN!sxT}s!|o0~LQ;11`PZ_2Tfk+GmRM^zo6 zvzZMv6$Mc|AInRUI-EPdCh^N@Rr>RFB~Mx6OJOa4LR=rO`taOK3m3rN;F(TAo?}a4 z0Ln_HRbC=zC-vHyDSk^WnJ)iuc4gU8Qw!>GQ`IASc2w62U=|J1T6pzpkZ*%r#@kbG z^Op8{YhhxU`W!1$0~2O)O-@Sy&J6g_9gJTdh){T&@{!OQ&&}fN#-DQk=PRO(VLY#d zf2!pFM-WjeN~$=vsb!k*=t1A8!)8e9{M=NTeHU9oyE6n#5z0j%%zF3Gr!3yB*eK|S z#WPckv_ecj`oL*BF6sXL>-4BC0Cibe7oMmt(lbaa8rS*f zHnYb=J8V7rf@xnV-G}@sh+JP(p>)>PBD*bh()I1Qu{7_;i-JSf3sHa`i#=1`VG-Tv zS@o{RQrf<>pdU4zLO!EXanQ;yA8qH~Wn@tjP}Z~v*JYkW?bdLPVf((CHv9g$mhC|b zrtwy{2ot@#vf!Dmv3yKWFZ8sT6a|Hmrbg39zK?nXOs4+AkiZWEZ&z;TY4#SOLn{xp{a8JQ;rC>AP=s=_We%Qqb-7RsjBgTnY0s))XE*-bSdWGVuxY4%eCG> zAO4Mpa%Y0f;XLZ#K8)o6OPhlQM17oB*84V#n57hXPNx@10bOo28*36xeVSVip1k+< zj5nQfxnr?@Y;K!;H}Ra&VZU&CB3p&I2Ol)K?{3+fM6R+ZyVEmO3k9IR^~aT%0)3o% z)XrXEk=>mZgL#`nBrWOSw^{dm$J>Kp6Cb**B&=ytg?)c=VRs5Ji^1p)_^RjoxWwa? zNM{b$-_M*l_MC2tgF-rrbjN3jP5x!LVnaAXv;v;*ypOwX1 zA=*X&A`fNbaiVgGN|^x`oixizR>9BZA}tLJ{VT*hNqv$T)DKkN5Z)1Sn3QoO|2=wQ z<$QqTI`!YD8nM)FPERP~SL&O_w%{#Pi%!lb7<}#_Kg387J7`Wm$dL_fc!zx!N^$?G zLVE)J!qYE<6!ME{>Lui-b(17h|Tqkgm94gljR{q^bC3LkQ2acrJEp21Nk1WopIKm`@KK4iV#<~b{4-Pu~CM}}LRyq)g!M}I+J=A*gfB&rft?~H|TAO>%AnW~;w3XVI>SVn9 zK}R({zu)$l1P6H^u8BM;zCrzd=1a!!cnb%lk?k?#_s1Cp^TTlsR9Kmo?;dIY(jV5l zy;NW4KyA)kz8Zp)%CUxh4fIYp7t7WadHaP3)c&|?J@Cg>vP*lo)x75E@TS!}Y+MKU~0N&Bp)R)rZyK@I5?+OB4 ztc;Mg@wD==ck^=f09-6N0N!!cb+JGH&lljL5w!nVe{!Due3IM4(@VzA!UF&Xs#;v0 zBLA5u_cR8;p-=z>EChf%GKK51p|Qm^MACbR@ z_E*=k_O`Y*9yTskHlD^rU?2vJ1Y)2tAs_~dgaI)S6ad=6o`SqfEXbd5Q9Jg zF)$Dah=IV*&%ozrsPia@^Rz+;AO?bj5CJhT7|P^d`TN(BjsNvK42K~8{SJ>xxlDn` zuMIY7%W&`DWDqH3heU`tNR&f`q_EfbZU+#?|1d<{lVJZ;CPQ!KJ~Tb61{-Lf(OHn8jK1l zS^>k<{9T`)bV7TI4qoOKyg7L3#ILfhB$wr1D8{3~&*rG{k+|p0!OP(rR{EsRiN8P3#$Cpt zRi6p<#O6A9s81a;3Uw2F?8sp!9r5^B^5|y!2X}me9ENM@ct&kHq}K{cW{Z^Vq;t)g zu+{A3Ii?8gq;qHI@L)NQ)r^SM6k+c26KZWnIJjxw*#jBUzO%DBNm4UTzUv^Im2Q39 z3ee<Wh_H|DT;20lVtd5Qq=}0R{nJ za1;Oq2LYf$5C9A*1b{-305}MI5q=&ADFg?=A<%zAba@SfzyVMY8~}x#D+lO>EF@S6 z0D~d`a4-Y_MS%e@1PTCwgD!x7%CiKtq&*Pov=Q94qa}Wps918pA zIUqOy0fQ1D5b%pM5F`Wuhrupnoy$8Tq+23 zE*1oWpO@p}>|Fnz%Rb*BAm=CNLeHNKInNppbN*x@@V~Y0zZUIZw86RI`fKAZF4ZlZ zZT=@yC@t;kXAA-efRQKw5)K6*P#}}@VF$(&03!lQd0L&jdJ!lP5m3g$?TUh~W>jA)E2odnya_ZQ4asN}^bL(U1gGx<=8yz)*> zRQxz!(|7=Q+S63_X8Fk0clq-xw zF7?Y4^#zA@EuTkwPfwxbLEDxZ#7+UnWUOYJUt3Nyx;|yij8~f#OvSBF{@llH+27j~ zJqj2&nR~nte4IG z=2MQndjw)FA=AQ9K_~C6qB^?BkZ}0=Oxe`F;;u^|@j-H#c*C+|0Nd2~ODnI^M797uGoX_q#BI&Sk2qd~AE$Aa=`|oc()UOtvykF@)f?-K73*zJ-&RV?IFr+L%(CloF7Iv+UsEu8zLiTM?a>M3ia8D#+>Rc#*l%=8?5cgsy7xMM#Wh5(h_S3I zw#Z5RiAGYAQ8i;xo4wcBjKr@xy?WKY08AtFQROX(G&bdf&flX|^XcDxHp2&h%bh?{ zsq)9{^Ah=&9!xs%XlabTjCE5g>FX@oSDDmPlu5BcrC8awmQw?;+SXx6f^PCQ9Z?7V zfv7j2RXcj3iBBT}pofh2jTlH@$VbVJ65fxOPL2=dP6{QF6$}#&_5TpX5aS;zcCX>q z*H8Ce(U1-yf&t{I*$*2DC*FrJ#%SL~;jUSl>RLIdm+rt5@^ts2%)>e2Xs5sUD-%&N}guIzs%B}!!%FNa9Xt(CuSkYJ!)3)wuU^ye&gI}%J zKsj6|yoj|%Wt~!^oz0x=b+sLjM5uPYIR`g2?Z@Xh)RHfvrHOJYIBIeh7@QTW%Qek4 z-+jum6Y~A-G+^B6vp~4Xv=y)=TUs?LG=_9E0t-xix>pxi*B!9MwPp1!XvcKb)ZKXr zg7Ca+f8amoKi4#YfBe>bEcm^@x08)|9`2OEbaw@~Od8ex0udebs_%JWABvawL74O6 zM6Gv;&CyVwYjx%u&kcuVudcnxMTR@;nXL)V69|VikSe|CS3mvo*o}ycauXC+hK}&O zE9QnlzUxPrb2_UT33@p;o4#M=T2Xe&?bs)IPDLi+&sR{gm7*qY0 zDUdMCjscccm*J7+6PR^O`mUKcm^<@+Mx1v+)NaS&c4FO9QR0XjEp7YVn_RZv9zIYP z%}~Cj^UO;y{6>DK$42g3#Uu+F!EVp)6>Bja0aYR8Opk2Z!XeKs2wL|w=Tq(2$Vnrb zl9Xi+mF{ode8apF*EAz1aMG$^&!#6gRh1jcpKYAvI)EFo2?q7lJ7oa z!{SJKFR@zpCWGoVVHQmtIqhe>xUI3?mB{AEXa#=f)2BhqL3Uq4Dm!rQKI<0Z%uDc4Jc(#LAuv zyRW`;q-%EmopN}0vzFAo@>s&%L#d^i`1r}P)k0S%ncx@EH$EP7HANE7e)}BLALr{m zoOx+9rx6}J_p4%8q0=|u^-ojhtRsuV8+)fn3YUJd#<$ZsXSaSSHl??uzZH7xXS1Sw z;&TwR5wy3wmBqB^X}3$acJ`U*jKnqTd)jx{{z2RxSyo;1Hy7UwfNAvCa^x_OVe#hV z%d|1@Sk7nNEa?yQJUWn)N-aUsCw7+9??|;3M?fZ3zABXdrWPeb4*YPD!qGysPbWc|j+9Vsg$XaB6l({Ig#A{^HJCf$0R!Mf0^XD6iA=wb87_8k} zT6J)R`V@SRsRMFzEX!docqRs`Z^(!@B!V%EQgdPWdU`G~p<;}T-nY=ISB7F(pKBHN z%^cznFcRbVGr?tK&VA#-EO`<`Ty30m7^{cMaz)%c3)-4Q53t)>wud`@VQaN)FQu@n zD-#+9YU|motK5mO<7U*mo7{D(3}pA^aHr&g;BaVD@T$tjXp&zquU&s?eBjdWa=PN5 zOOwgv|1~@lyQCZD!p!7my5)N$T;zkoQM*}XPAmW3ee(7sP5ck7A=n~ZR*>x`eo{YT_uog2yoekMYbs?B_Fxrk zV_H@A5l5Pp^gS()oFD6b^-H8eWImo^?PO!-`y38bWi+O^Y_V6kYT-$KA&)ROdNx2( zLhNBYULSVJ%xWDzxdc8gtlR1XYMZ}Ih;mUaL03M3G6avNPdYj&f&W8g?uREsjcGb6 z4nhxflhQ;5#v-3>!Gg(3A3qg)`n8J6rYDI9ntkxD;XUcZBe4m)$?2+X?X`p0-=4EL zm6O-ozgIPMJr|4){^FV^|9J4Zx=AXypTumpali~;-%=&-{rtz{F}PD8xy8@H&a$A- zL}Gwe3jY2?n3|5_7{hZykhq?R>Fl@0LE?c9aSKiaGn3ksO6rU6MGL#XaGG#jEt!04 zvmDy68FHwNY^}1wpUvDvSHl4y4sPN?H;tPbCwXN<34#b(!fz52;{-<5FtZM1A1Nq*k zk1Ibwr9(#s`blm)(UYd70~j9p;USDqHZydp;<5)if!4qy#65;)Rw$E}GFcPitBqrK*T!}znu)y@!Z)M}x^3a{=@~Mn;Vtn$tO6?H*3Q;g@|=JA z8lQSTJ&V01x8Pr09kgWX3P5Fk7H!;DEV<1S5{5TeinOGBv{3zC#){JPg{ded0e;76 z4Dbh8fFD`BP-v_-rC|G++I%TdW_YpG{Jb5!>m)~~H!!Q|<%QAZvg zccq1g2XR2C>BFhav5wIE$r=Txj`X^VzioU!^TYQu79`%0Pg6Q4la1)m-uY(A_Uj|&m3WA@9X_E=&{+(QeaFl@SIKya60nNOEg{XV#La(!ZT+@& z?*F=Q|1a>ayM;Rk^pBN0KQ9=-2jTnY%AF6w_wOtByVL*4%AHH#KUVHY!~+6GLKA;L z6@SAPe?S;W;NlMP_!mZk1S{?U4*owN-cX7`MIA5@kz}KNbyG86psT_(W;go;|)JW_tRBd zSbvh85}maxm9@pqyOAhPrs&7d-<0S!&pMe2LGEEl;>0@Roz&;C&%RKdT}#_{$fWB{ ziWgZFbC%4S-T%BH@QVg(vGw-r)$O_O!Flt+t$vN!8uqhIS3$G>qzS%Mhh{4Ome;Hc zRfixv9{5$Fpz9j>W?$l@pH-LQdj1f=bt{#vUww^sxf@sPru}S68~AA(hkG z1bx}Xc!AijI*`xhjxC?hO6p>>`&giM%-)ott(~CB=NTG@l(jrH_Bc^~VNns6lkoV0 zjN6;yvfIM~G5=pWEq)vBEqtZ=H6yiNflhn%`q8$0AEBkwwO?vq?0K!|t)#ep(VwK6 zL~xfjTw1K8=zrg_xu_?;ne@6i)t`JgX{T#GhjZ(@_tOpR%HiW*>@+_^a7d1Y&?RVb ziFDfgGVx`icxk7^HoBOPda|`V+Htaa=WtR#YR93jtCmi-t%L7-=HYR4F{0U%X>Rqw z$`^v2Bcj9NnpQsBZ{O*^*YLI;bVMJiK8)Hyd@-J+;%oO_#8s_5wV=d054mmhYH|{Z zdR|5C*V%#rGBv2VStnBilg zy0isSf=0kiX+v?~7R*qMVl>!|I6WtF+e}bwq&~M)HF-48jmogaK|FbacAQ|_ zxt?LZ+(DYJ=;2uO4zp`~J?lKf{HOi${V)evzT(s|+6mgRft`$D+R5}`kq_RA?i%Nx z_NnGs=d0?+>NlRvVN!isMrT|2mVPUK7O~l9-K3(LWGuHTda=7W=l}S0=}_C3{<3F+ zoZj$yB%a>;Y~|eNsyn1Av+xF1xcs%~qTsV3lXk|{iI{=V;k!-C;!=IjYl2MM>#HWd zk1Z9uUus$$SMx!B6*rOS#$5iF6(F(O#JDnEpX*4z#oC`M#kM*v6=!3%x0Ce~HCl^5 z&VK6f`B|;(miX81ooGk$aT+z%ehcsklfgIR7xOu*@*@;=@e5(i5V(DcxnkP%X;Iai zif_Zz06$!Q@b$++(o?`2AZEmQn8OHg^o`i}cquPp{$O`^yu`A zedXKPdc6{CI|3NfbJe}$J@GiRgRZI0W5+Dd*m`heg-a#oGhrPcNaU6!5#p7s7`y?PIn$B7C6rW?#R187FwaTaak3&Dr<}eMx3*k z42hMB^*!yYvwGUw8SmSx#ZKB6T=kNM`qh!xbFbL|!V&X9V#`vY**J#-p{#wKsJQvj z2QOK^aqjg*{$$z>;wGcRwVb$VR%V>0@0Y<|Q|Atz%vZ}4OXdN9l&aWQ&Y|2Z=8b9b zdHlLqFeyUmqlE8E);JtNk6Lj)M!o7>2KIxnG;rl}*h4&IwA7+h#UE+mz!L6B(!iL% zQ&6>mzRMe2z&wrD`Z}<*cID|R(5JX13tVd`UOaljbD<`-qXfjvo=i`7=eT; zV$BZwaRe1Sm~1)cvHsGbewgz5youRQ9m^=bqwM)6NDlaxYN*irE%ol!!PY@ks<}lM znccE&?Mw!>rpj?flTdNkF+KaOZE^rnm>B@j!59>LpZ=x6YrLYQC}Me8T{JPHS8FhK zzrw3ds4ATRnu9F~DoF6JOoOnWyJRCL+#G%h9cA6j%^t6#}>N z;2>;Ciga@#d$lY@=6sYfn&A1ivQc>LDzwktZeIP@TkF&h5pz+^k)JzXz>2GWeIcX~ z0o(dU_zWJUonxMG{dBsRxQGnjs8Wrgd;G9ScSxQ_mC7Ptx)Sf!F7Wns#H{8qkPRe|*$&$}=nNw2h^0{7|X z0{cLb=jQ-wiLs^dPF3DjqFlHJ4MJtLiQopCouaWs%Osft5qgCDxv zffqFHv9u;wQ&D9@s;k(ixD+{X#T@B}m1er?5eca26$5-vxnJ9>iUPQ+N}6Bj2u)0w z?`&^5>xt~qRh1FE8(D8oHz!yjIQ|S3hI}Ew{+akvK9l-D=~1F9%R}n>RROQ$Z`Usk zvAE~sZTq+j&ZOzdBVU^YSI=4m3hp}z2on-12vNRacn-{6FI65>?@wF9+y-u9q}+>= z`O*`X1N8Izgvb0O`RXWH{R-ugRx z`5>W4Hq?0RTc~ozp$2NqkZj53nZVV@k9CVQQUFj_pYDk(tk=t$3N|;7mqM zIwXBgtj7Pd*K(ZQM62NlPe7cz@!@*Qd;dspjvvbFu8UWj+0$F^=Ei(2H7%vYWLw5t zH(m!z-YgPqqHe1zRp-@vBJ4E{R|t>ae=hkP+L$^*_ep1teu3T&pH@woSe_{lZ(*F4 zu~EXfvy2NjUYsg-`B_(J5cm_vJ#kGO91_qGG3T}tKdIIiflYw(Y9XofAY?~qP}Rl! zB{BR_f+qBXGS@rQiy_4hE8J*rSvzd|=|NP@6stYkedw2+l`pjrYvo;4-rSvEDMTqD z$^!j`_A{beq9GZwK&E5gst@nxIy>(}-lg__J*U&j#1-oxa*_HP>mN2a@?7;B^t)o+ zPnHR$F$qL#H@ex8-%Dl>y{x#0p0RkQQ`x!~uU(*`gOS-JqPlvAl?gCSFUj|x2X+gn*eYC<#g4vKGAO0JXIo-$4f%gzH5A)IlD_)?+)wrnc@F3v8kG?A6bS&V#5tcl@a+l{lCBuL`qY*rhZ6ffn zB)_Ni@p6lfBSnOl^!sy>(cbS1CUQ^r;v773RRb1KVqiy1Y&z?GBW;d~(Py%x&XNGX zvY~QcyEKL2B2_20eH?PxDb(|7CFrLZk4xA#41jx<1AK0ximQYEI7l`e$6bTo9OkJrK>+74@9Q z=oJ>lGMV0KVQDVg9^TZt4 zmlmkpL{Fk(;n-7t%t{5;o56gw6@a$J`qvAMTSslA1To5rPqaXloJgb(mk(MQ3p?l|qk1+E?PNJPAO71^`7XkqC!NbyX|{F>d^b=U}DuvBt5{ zz8)h_*O$g7ngq;PS`=)taY2HS6C6$giUDQ5Xipp!39$;0lh-HKN~Y=2Np2f|$xS%w z&n`-zAhbhCv-@EQ_y;5==rmR|54r;b@XwBn+6dHk#<>)pUwJW@iI=!iC2RA>Qep9Nr zM^lKeZT?HYORYuq-4^BHats zmpzaEMz9-&*qNvHArq10PNryangcY>pZ-`Nt?s7(x-fXK7L{R9+4b$)wDsrD(}ZdS zT1mP~g zm4;W}oO)adc9$oAi=pEEo&HUwpiugQzFl6;l7$Dxc=PStOlG8BER`Hh9EQ+QkK85s z+3@`h`vSwV?93cv7O`!yR8L~AwVrGymkywY>S=mJ+IlzxXE*-Ommwa|j3~Cfr~L7Q zZ`oD}JYi*<-IbE9jNOrQjY*9dTor1L+-paH7|Sg0v}hs>x3n5^>>=MxaIxADj;X1( zbRVbfo(D#Fp^31FmF}v)cpPP|nSW`rfg@m+d196>5R&M|U7YXzYvK_%L|Z*KOI*HI zkZK?h7zu<6i6N^k%ZY){6q@*&&a^;irzVLEtMV6zh>dPi_%7X94>Lf4-3&v$EB^D)m z9cGDGnB>Q=OB(AHLg?^*@lLjgI(1l5XfIwcYx;(=YFBWw!wy z|JC~*Jm+n7J_i{}cxw|h#qRT=qfH`?2;6-Yn{zC`E6aoH+ZkVeCz#)1_%7+T)6#vR zb^0^>2CSE2u-y-(3xm?wu{_6zj+}h_vHh_4=ZQT<(>>zl#?(0YI0e%yFsKykBGDc={?w6oE!+11v zfQ~izQzsXMo&%6?Sk%&GMIFs^d+F+)$CF=*=8B^;qdJ&qkR8VSjRIOBf|8oKP(cf?{g@9 z@w7!qe+9Wn&}SJN4Iba%qvFg%u87H+&gvm! z1bwY8Ny>3>KS4_D1OAQ5d z6$L%!>*n^M+o5Opdx{86`e*bBeD77J)GwYDpwhzE8|9jyuebIgv%1|TO7+!G5yUWRYv#MHc5@KMisZ#kySK^HEVL5}ltCokgEUf614G zW;2Zvb9+PFA`uT`iE=tCMcLs#0NwNeONtTv6g;8`G|m>34*|*IjJP~&_RKB~b+dC5 z3+69A3(YoJ)OT1~=#N|%KKTr7IF5-DUp53fUTse8E>!>t>4tr{%pNWmlO|0ogDUW_8r*D$R4>I={idv4U|TXEfD zgS(Ia4Z~gT{4sU7^osuknQ--#(I!`xkjS~4!@gJRiSB%9y`c~_9j};K^U$TcxCx(3 z5tsg`klgtYwWTt!-gr}V&kOT9NW4tW=xNi`xzGOUNyS#(W%$_i7&=JKpXDk{L`lS4 z050&2`#DrQ-dp(6#Mxz2)HV5mUthrbb@!Z{h@4k`$;vnNF$wb`(K@!u#Iki816h6F zb5s|(s=VIMnMK(z#)Qg)D^yAeCxYD1_m%ka9=fdemiCqkOvbl6y}-0uw{9DFTUZPvQ>eWb6A?ZU$j^Oy9iE*|`k zndn!~>zka{T!U5NWMs0Y#FET`gz8>O`U z481gnJIu$6CAFF}!_Xw5Oj{l^pm`5M*IgwV22{SxcAm?@`xrh*qNLyNv@Uh@>q>9kyZUR(I8k*Ia|wNO z>SZFEKl*c4d6XVWl*%7wQd$=*FnAQ6#4|H~PI#VLU*B@#T3uV)jh$esAkM(P$*u_u zEX=Zo#?*d3t@)JY=9?6OR72>C0(wn)b^0WFT~5EAN`du4cS4F5->B?9)sa#M(lNsQdCs_{QMZCf*-2hpNkB8{yUtePT~l zJ!R*m_K7znHc$k_zkDbMuD)q{MPCL!kp+FiAUb$*bRhrv7L@1o2qcTz1uVW7oR41c=sKqtQSVBKX}LQ=x_3VV)#*Vf$p1H z851)Rbs#XujSzA03=!-gRdtffliGH*<9-2-(}dcfx%@DZj)l-}d@_>j!0d0=Omrj2)Gx(U?frn+?0l`Pxl^$jkuP{x+sOGH043);so$7GM3!-`jKb{fJ4Xo7U zEem!yt>Gf*k)KOg{1ATq#`#MSu@cIW*!^EZLqt1^YiSGTj!y?@G4`<%!)><>jcUOL z+zAcI1GutKwyY+(i`e^Q3@(r7T0HECNIg5sPB(+UkM%*|oB}-H@yv$`Dn**xc89gY zLuXJb@y%T0Be|_uP%8$vgHnPd^LO_=#U0HB> zMh2s+IjbY6dDqTs@-p92k7$fX4;0Y_IeC?u*cTky-Q-M;0M%yrZ~<a`dqzEk*T{l9 zb%kZn=I24#g^>vKs-t|k9MA(HVf%&l7HnFraO+=xeLh(keYw(IuwK=T{aSA0cKl|M z+043>CbXmg>>%!bap3AZ>q2q4H;8caZCDY?_nv7UbB#F?-IYg)4ov14VFDmnBu4W>qx*ST$b!DdTcLXB-+$SY$aqZx?%y+`sk^ zMDD7!qbos7orFP)_aHempD7ozHkrW4&G+nwH6|{r>T2TguYPG?BVDV61aURofUk}G z>>MW*!^O2Mq*zX@QtT2G;`e?QF2{hb?7OrR;hALyTf&y&B5555M-5hG$!D)}CkF*v zXGpZYbagVw6h?@1$)2pLeZU|Gj=>zZ*zjn{zbWhx_s6|{SIU$gdhh8Fg5vXg`x$MO zv{3d&JM@>$c0-c!uL1q0GT>6f=9gf-*Og1T)H~WF8j^s8@s)ehR1;+vWQcLve8xc> zs;y^&#~=>h7Do84?XImdZ|6hOfqNHWHIGufm!NGsBk^-%n*y#8zF7QSlG*~VW=J3V zpuA7`q+aoe-AgG4^UawdbL+4Bcyso)0_?-ReOzLqk0fnN83qE_LCncSAr}&(rklq$ zA$+~lvE**q4tpkHq$xZOlYRoUe0(3lA$Y^)M%hg>5WA2Xck6C=BT!i`VAr#I%R z3BPfZ$wu-}ywx}sz1+Ryk$zZGd$7{ImPYDEu|?PB0!i28;QnJ3ycekG0gZ~oCz*{t zDKdt1&B{S_=KvIDH#iZx{_~3*R6{x6uEvqZ1&{Ny&>FE?&yDl}_v(*Ti$TpnyoK&W ziy{}p2B%P=%u@e}A1?hvG%XUIv@iWAez~2M?54(Vyq03~_uI#QFGh3O-6?b>G&j^c zsk}ibtOLE>^qClMdN<2e^Tb#xbCOr=WpVSq_dDSokG7x6{XWMPP4Tl>HE_PJeX@Ns zdPiZ4nHO0W#$$s?+pjrZ53DjDTyKh^%@a2Q>sddu8uB!{~3wYlX z{21?qsIfcb_$3SP21Ud`7iOy=%A$7EV!_^E9p$D`Kx=xe+_1b1_5q3S@OS=u62o0t zxvM~2A}z9CxQkg*_$a+kFz#{mSKfbMo)fXG_Tzw#byWB+$AR?HjFx zPUVedQKkhv;zK`qU5&8zn_!7X4o;=wfO=cU7}emm`@>XJoLybh7^ExhG$>?q8u^|B z+CGo{%>^*t5^6{kOhpSiw%__On46p`)ub;PJ*)LKZMZ3FhX(IFcug4_ywjPg&^j+n zm)x(!mAg2oCs96&!6hD1ngv|GH-bCXU!;tisU{z(kgcP&rprQuEBDGqoSamWTJS!% zhxl?B-zs6l;9OyB>F(aXeic#uQE5;y|^VdKghQ_@(Fl7(7}M75pA& z7P2?yam`kWyT-;Q`k5rC9&Z-R=<;2JHV|z>-9RuiJ7G^wD%CYujz28zF z7#%ERi0lc?xQ`>|uZK%R=^GCQg(7*nLL%Dnyuv#Sai7f*(O}Dme}6Flcq^!e09R*K zhjN$@5kIgnHnuz;X`^mCyfFLTOLl~GQ`f4NFK%-n*z%&oU~pdP%U+wsC#B-2MTZtI zq3qR($-FzR*nM<1vHoV>35K;2l$^<3_5Z z^u9s8k6jqaMfs>B<%q6zO?l(M@TZAP``fAHDf%*{R++G$3%v_c;aiP2L8A#~# zrXCgwJFeM=ge1KvVjy>7l=*HntVg^sPLNDE@*O*w_XYfA&pC*9D^l_(k}#(KK%!U} zKl-u^#}$h&K!Z>gK>W%_Emo!kv7(clcNKrhLC!dgV}%*Zz(o{Ar6+-7nx)vvT`uy9 z&)AW^d&BII_&GpEV?mwM_E(#8xW37Q?FWvvhW!oF2aV^S`qqxN+w{CHH+z1)T~zIl z%T0H|2+QqTWH9A^Goz(bdDEvyBpnNvB>XuY&1U zb6ndKbGZi7;(G*S)8qH0#_>hE>DLH*&HHM(##4J?8otlr^1TX7Rx~Oj?^nU^c6w5{ zq;2aN)QfkuU-ZRD&9>+rtXy4noeg|vYY)jL^x}EX_$VaXNhxo63^xS$1O8LMK`%p% zIdN&>MwvJL>lfK^22UDVNo?N>pXV)1^XZjc97PJ&k=*^V8HFp`TUbTCPAF<~_$&_Z z?Fjoe)=;rO&4kt`Gek)MMr+SVF>occUom!KCty4mYD4vrAnXfR{$Q2Kb-yDtw;QF4 z2$M(&DtsjDKI)qwY#|1t<&A#J6>VeK$XScMC(Y9=Sd_ta#;rdqsA8d{lJXq)1^>7NwuZg?~iq`EOpa}&&8|?guQwBB0>4%5C zu2vuHmr^2*C$HSKzt#O{-)|Ra4Ez|!Vn4gdrM$0CN4diKof;`sK=PECuQHY|HCky1!;?PiHX};qgMf8w!EaJkC!!kP~c1C3=S&2i6ZLs8S=nWyO|nTK>Ps^0mu=BwrA<+fRD z!9(3OAp_ayFPWPoW)-LhPMPCJ>f<+yn2YC9n^LdNvl~W|R|%F5WcR}nz2mU6)s*gr zFM^hH$5#vv%6(nVioEao?r$mkfO(4u<(MVMvZa1R@dLl&b`OWchjz6jzyQ**J(rP$ zepS@Sg)Hpxd&3c+Wpu?DtlZk%o~3fK;J(GI?gwy`6bz$DlFhJErIOpYtKH=S&ivPz zU04rHlCbNjD4cOyKg8*u04PIMi8=MpTl0i)t8r%Du$1UIVC8(n7dIs(Lf%3?tCnJN&&f<`L~AvbOq(&Y=RZ?YqR{%_+X9t3RlmnI5?|g`zx=G) zkf+#w1ifPY3Oh3N38Tdaeb)|e51tA`Es8R}td()%{sg#>@!3d_$}XX<3>$)E+f>P{;2>ZrK~x{nBS2sdi~;Q?3&Zgw{^qnFZI{6DnxFg zW=)g659gNi^RE2|QlgT+J<3noO}{D^?Ov~C=j*{ABVD*R1RH{FB*3TA><2&RM%kq6 zk`J6U^Y{M zkaeX3;z^a7av2<~K_Qh7K^ClM#NTP1nTK$(6aewtyJPf%Pb0Vs0Qiqt%;0vS<$DW z%S~ml_O<;%5pI27n~ky4GTnvB#t-itlf4}~*O=!JwR}9J`^p1X?^U%_7K9x2Z|$do zr1Yn{H}_6>ZGd&50QXtjk6#7_T>?LxdJNbdC%{L!>>g%SYK@ls)DlEfqB_AeKubD! zF&@lzQ-k+I2Jhff%yj8p5=Y~cZi^q@3kNygN)Hy$li7t=GAj;^5{zWal40v+$Mnax zt<_3bKhY_E{1kgE;mt`(c@UQsd6`GP_9=g0NveIDhO5?qanP~aoKem~~f1HL{JkP0Et;dwaQ%3`v|ydVnNpF4{sEGj8!ILl2_IaV`_` z+LURoYvmrh`dT5WzB;#phT;CxzFnJqy+R9}_XWLU;(S~LH?pOu^FiNE7DS!94}D$q zpOVI86nUPu4k?T6T|WLv`*ZT5Om2bN(`A3|1GM023)lJiiWu#+%yP}uz5Ta{Z!Y6J zYjo};=7S7!V$%om{2dvwz|B`t&f-tqY%nYxvM+f!h69>8&vM3k3^DS7r!#S<uJ+unGP3vR3C1m<;2Ucp1l)<&0hUg0V+ z+Gf<|3MhM6YIpvM;LQ0zbJ#cFsY?`zN&VupuxRqo+9|v5i!Di+CEi#!>h33($<1pV z)9@($isf4rO}&nUf4(4oR}tmUoy>PTyZ@?{@~=(Ix+=2nZgie za1IYsM-Gd-lGrW)xQn?6qm+iSEF)6EL(s$C(H`z<3h=PEb8r##5CPtq2s*e3BE=ve z;7-NWRs^W4q6Tn9Ana_dT>)I20-O*I2$UUQ;cRLTcSkte0wA2cKv7&_XPAYchP3RT z9Xi7-M1WSVu8x8rkh{A(r#qAr;cN+l2nYy(z+50ME)Hjy1&52LgR7|rhl2|f@J~By z-M`HoTsZGy;xtFtgRFHy5Kb`YFGqjvi$~U>K{_@yL%6w$0KqUGGhR~|9|v3j4(5PB z;9MNYsvjIM2uuJh0EhE%nf>L+@!tac4^NIT3lM}83IYNgVHSdF&Ip*BIow$UDCuTr z=Vk2(K$am=bGCN4D>M#3UYpq;Eyy?lAb_kh9PV!F3;qT7qPaRj&6$~?5FutJ2(Qrp z;!TE`{~fubo3q{BV*@h>!R_G4AYDKZP6!AHfSC(gAe`+@T}6PV|4K4)@B&4JVdjFa z)~hhwYf9G1!3U|&_OuE02~0A zi@mX#wF8V30dxK1F4U`R^mR(=$ivA&|r#Nq+13E~-11ch2v~og-7E^1mAH%w&)<7?Rut zei!o{ch|iGD=z46rm#jhAg3Z0X+h*X2Id3vgTWB4yD1C^1_N1fK`IE?|3gCy`6T>D z##R3Idv`^5q22j)K{niR7D(9I=D-YF|y$dJ}>l5lgiLj32TutA#NMdyj+oLT=alIGzIx4;DhpkQ3&KieM%fR~2{ z$^)dun|HD=QSt#%~zdXGE=nu>%02TOMkB^`GcfVjhem=f` z=m~&-mqDOVzJK(`!^O?}yDb#@k355Uz{oN%|B)*Qlp9$o@pl=|KV&@oJiq(p0z>|h z0|=Cx|M$E=xWUkW^v4Ym_=k)KBJjHpD1;mN&BMRqb9FYgwu3w43JU{3n$})$02B-W zX&?};fV(ep0YC~476`zfb!HT#0s6vRT(aC?KCpz8G`}=AFAq027dMv-R7P5s3(PCU i!zC;F|JE=>mLhaioctl(nullptr, DSM_BIND_START, pulses); - for (;;) { - usleep(500000L); - /* Check if user wants to quit */ - char c; - if (read(console, &c, 1) == 1) { - if (c == 0x03 || c == 0x63) { - warnx("Done\n"); - g_dev->ioctl(nullptr, DSM_BIND_STOP, 0); - g_dev->ioctl(nullptr, DSM_BIND_POWER_UP, 0); - close(console); - exit(0); - } - } - } + exit(0); + } void diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index 133cda8d65..bd431c9ebd 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -156,6 +156,7 @@ PARAM_DEFINE_FLOAT(RC14_DZ, 0.0f); PARAM_DEFINE_INT32(RC_TYPE, 1); /** 1 = FUTABA, 2 = Spektrum, 3 = Graupner HoTT, 4 = Turnigy 9x */ PARAM_DEFINE_INT32(RC_RL1_DSM_VCC, 0); /* Relay 1 controls DSM VCC */ +PARAM_DEFINE_INT32(RC_DSM_BIND, 0); /* 0 = Idle, 1 = Start DSM2 bind, 2 = Start DSMX bind */ /* default is conversion factor for the PX4IO / PX4IOAR board, the factor for PX4FMU standalone is different */ PARAM_DEFINE_FLOAT(BAT_V_SCALING, (3.3f * 52.0f / 5.0f / 4095.0f)); diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index f7b41b1207..42268b9715 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -257,8 +257,6 @@ private: float battery_voltage_scaling; - int rc_rl1_DSM_VCC_control; - } _parameters; /**< local copies of interesting parameters */ struct { @@ -308,8 +306,6 @@ private: param_t battery_voltage_scaling; - param_t rc_rl1_DSM_VCC_control; - } _parameter_handles; /**< handles for interesting parameters */ @@ -544,9 +540,6 @@ Sensors::Sensors() : _parameter_handles.battery_voltage_scaling = param_find("BAT_V_SCALING"); - /* DSM VCC relay control */ - _parameter_handles.rc_rl1_DSM_VCC_control = param_find("RC_RL1_DSM_VCC"); - /* fetch initial parameter values */ parameters_update(); } @@ -738,11 +731,6 @@ Sensors::parameters_update() warnx("Failed updating voltage scaling param"); } - /* relay 1 DSM VCC control */ - if (param_get(_parameter_handles.rc_rl1_DSM_VCC_control, &(_parameters.rc_rl1_DSM_VCC_control)) != OK) { - warnx("Failed updating relay 1 DSM VCC control"); - } - return OK; } From 35ec651cee89081ceaca63a1641541d8ed0a1467 Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Sun, 11 Aug 2013 18:07:25 -0400 Subject: [PATCH 49/80] Remove unused IOCTLs --- src/drivers/drv_pwm_output.h | 5 +---- src/drivers/px4io/px4io.cpp | 6 ------ 2 files changed, 1 insertion(+), 10 deletions(-) diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h index 52a6674031..ec9d4ca098 100644 --- a/src/drivers/drv_pwm_output.h +++ b/src/drivers/drv_pwm_output.h @@ -118,11 +118,8 @@ ORB_DECLARE(output_pwm); /** start DSM bind */ #define DSM_BIND_START _IOC(_PWM_SERVO_BASE, 7) -/** stop DSM bind */ -#define DSM_BIND_STOP _IOC(_PWM_SERVO_BASE, 8) - /** Power up DSM receiver */ -#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 9) +#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 8) /** set a single servo to a specific value */ #define PWM_SERVO_SET(_servo) _IOC(_PWM_SERVO_BASE, 0x20 + _servo) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index cb61d4aae6..10ab10ef31 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1472,12 +1472,6 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg) io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart); break; - case DSM_BIND_STOP: - io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down); - io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart); - usleep(500000); - break; - case DSM_BIND_POWER_UP: io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up); break; From 0b935550439a17856f5218fdcd6be8b864cfd346 Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Sun, 11 Aug 2013 21:16:55 -0400 Subject: [PATCH 50/80] Tell mavlink about bind results --- src/drivers/px4io/px4io.cpp | 24 +++++++++++++++++------- 1 file changed, 17 insertions(+), 7 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 10ab10ef31..960ac06ff4 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -577,9 +577,11 @@ void PX4IO::task_main() { hrt_abstime last_poll_time = 0; + int mavlink_fd = ::open(MAVLINK_LOG_DEVICE, 0); log("starting"); + /* * Subscribe to the appropriate PWM output topic based on whether we are the * primary PWM output or not. @@ -679,16 +681,24 @@ PX4IO::task_main() */ if (fds[3].revents & POLLIN) { parameter_update_s pupdate; - int32_t dsm_bind_param; + int32_t dsm_bind_val; + param_t dsm_bind_param; // See if bind parameter has been set, and reset it to 0 - param_get(param_find("RC_DSM_BIND"), &dsm_bind_param); - if (dsm_bind_param) { - if (((dsm_bind_param == 1) || (dsm_bind_param == 2)) && !_system_armed) { - ioctl(nullptr, DSM_BIND_START, dsm_bind_param == 1 ? 3 : 7); + param_get(dsm_bind_param = param_find("RC_DSM_BIND"), &dsm_bind_val); + if (dsm_bind_val) { + if (!_system_armed) { + if ((dsm_bind_val == 1) || (dsm_bind_val == 2)) { + mavlink_log_info(mavlink_fd, "[IO] binding dsm%c rx", dsm_bind_val == 1 ? '2' : 'x'); + ioctl(nullptr, DSM_BIND_START, dsm_bind_val == 1 ? 3 : 7); + } else { + mavlink_log_info(mavlink_fd, "[IO] invalid bind type, bind request rejected"); + } + } else { + mavlink_log_info(mavlink_fd, "[IO] system armed, bind request rejected"); } - dsm_bind_param = 0; - param_set(param_find("RC_DSM_BIND"), &dsm_bind_param); + dsm_bind_val = 0; + param_set(dsm_bind_param, &dsm_bind_val); } /* copy to reset the notification */ From 518e95ce44ca586a930609fabf551f12001a7b52 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 12 Aug 2013 21:49:49 +0200 Subject: [PATCH 51/80] Hotfix: Fixed Windows execution of sdlog2 dump script --- Tools/sdlog2_dump.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index ebc04f4d03..838da9c489 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -105,7 +105,7 @@ class SDLog2Parser: for msg_name, show_fields in self.__msg_filter: self.__msg_filter_map[msg_name] = show_fields first_data_msg = True - f = open(fn, "r") + f = open(fn, "rb") bytes_read = 0 while True: chunk = f.read(self.BLOCK_SIZE) From d3d9d059c0c0780541d9dfd9c44b1f521298f5b6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 12 Aug 2013 22:03:57 +0200 Subject: [PATCH 52/80] First stab at Python 2 and 3 compatibilty --- Tools/sdlog2_dump.py | 72 +++++++++++++++++++++++++++++++++++++++++++- 1 file changed, 71 insertions(+), 1 deletion(-) diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index 838da9c489..0ffb381766 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -21,6 +21,17 @@ __version__ = "1.2" import struct, sys +from pypreprocessor import pypreprocessor + +#exclude +if sys.version[:3].split('.')[0] == '2': + pypreprocessor.defines.append('python2') +if sys.version[:3].split('.')[0] == '3': + pypreprocessor.defines.append('python3') + +pypreprocessor.parse() +#endexclude + class SDLog2Parser: BLOCK_SIZE = 8192 MSG_HEADER_LEN = 3 @@ -65,7 +76,11 @@ class SDLog2Parser: self.__msg_descrs = {} # message descriptions by message type map self.__msg_labels = {} # message labels by message name map self.__msg_names = [] # message names in the same order as FORMAT messages - self.__buffer = "" # buffer for input binary data + #ifdef python2 + self.__buffer = "" # buffer, python2 + #else + self.__buffer = bytearray() # buffer for input binary data + #endif self.__ptr = 0 # read pointer in buffer self.__csv_columns = [] # CSV file columns in correct order in format "MSG.label" self.__csv_data = {} # current values for all columns @@ -114,15 +129,24 @@ class SDLog2Parser: self.__buffer = self.__buffer[self.__ptr:] + chunk self.__ptr = 0 while self.__bytesLeft() >= self.MSG_HEADER_LEN: + #ifdef python2 head1 = ord(self.__buffer[self.__ptr]) head2 = ord(self.__buffer[self.__ptr+1]) + #else + head1 = self.__buffer[self.__ptr] + head2 = self.__buffer[self.__ptr+1] + #endif if (head1 != self.MSG_HEAD1 or head2 != self.MSG_HEAD2): if self.__correct_errors: self.__ptr += 1 continue else: raise Exception("Invalid header at %i (0x%X): %02X %02X, must be %02X %02X" % (bytes_read + self.__ptr, bytes_read + self.__ptr, head1, head2, self.MSG_HEAD1, self.MSG_HEAD2)) + #ifdef python2 msg_type = ord(self.__buffer[self.__ptr+2]) + #else + msg_type = self.__buffer[self.__ptr+2] + #endif if msg_type == self.MSG_TYPE_FORMAT: # parse FORMAT message if self.__bytesLeft() < self.MSG_FORMAT_PACKET_LEN: @@ -170,7 +194,11 @@ class SDLog2Parser: if self.__file != None: print >> self.__file, self.__csv_delim.join(self.__csv_columns) else: + #ifdef python2 print self.__csv_delim.join(self.__csv_columns) + #else + print(self.__csv_delim.join(self.__csv_columns)) + #endif def __printCSVRow(self): s = [] @@ -185,16 +213,26 @@ class SDLog2Parser: if self.__file != None: print >> self.__file, self.__csv_delim.join(s) else: + #ifdef python2 print self.__csv_delim.join(s) + #else + print(self.__csv_delim.join(s)) + #endif def __parseMsgDescr(self): data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) msg_type = data[0] if msg_type != self.MSG_TYPE_FORMAT: msg_length = data[1] + #ifdef python2 msg_name = data[2].strip("\0") msg_format = data[3].strip("\0") msg_labels = data[4].strip("\0").split(",") + #else + msg_name = str(data[2], 'ascii').strip("\0") + msg_format = str(data[3], 'ascii').strip("\0") + msg_labels = str(data[4], 'ascii').strip("\0").split(",") + #endif # Convert msg_format to struct.unpack format string msg_struct = "" msg_mults = [] @@ -211,8 +249,13 @@ class SDLog2Parser: self.__msg_names.append(msg_name) if self.__debug_out: if self.__filterMsg(msg_name) != None: + #ifdef python2 print "MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % ( msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults) + #else + print("MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % ( + msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults)) + #endif self.__ptr += self.MSG_FORMAT_PACKET_LEN def __parseMsg(self, msg_descr): @@ -223,7 +266,11 @@ class SDLog2Parser: show_fields = self.__filterMsg(msg_name) if (show_fields != None): data = list(struct.unpack(msg_struct, self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])) + #ifdef python2 for i in xrange(len(data)): + #else + for i in range(len(data)): + #endif if type(data[i]) is str: data[i] = data[i].strip("\0") m = msg_mults[i] @@ -231,14 +278,26 @@ class SDLog2Parser: data[i] = data[i] * m if self.__debug_out: s = [] + #ifdef python2 for i in xrange(len(data)): + #else + for i in range(len(data)): + #endif label = msg_labels[i] if show_fields == "*" or label in show_fields: s.append(label + "=" + str(data[i])) + #ifdef python2 print "MSG %s: %s" % (msg_name, ", ".join(s)) + #else + print("MSG %s: %s" % (msg_name, ", ".join(s))) + #endif else: # update CSV data buffer + #ifdef python2 for i in xrange(len(data)): + #else + for i in range(len(data)): + #endif label = msg_labels[i] if label in show_fields: self.__csv_data[msg_name + "_" + label] = data[i] @@ -250,6 +309,7 @@ class SDLog2Parser: def _main(): if len(sys.argv) < 2: + #ifdef python2 print "Usage: python sdlog2_dump.py [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] [-t TIME_MSG_NAME]\n" print "\t-v\tUse plain debug output instead of CSV.\n" print "\t-e\tRecover from errors.\n" @@ -258,6 +318,16 @@ def _main(): print "\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed." print "\t-t\tSpecify TIME message name to group data messages by time and significantly reduce duplicate output.\n" print "\t-fPrint to file instead of stdout" + #else + print("Usage: python sdlog2_dump.py [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] [-t TIME_MSG_NAME]\n") + print("\t-v\tUse plain debug output instead of CSV.\n") + print("\t-e\tRecover from errors.\n") + print("\t-d\tUse \"delimiter\" in CSV. Default is \",\".\n") + print("\t-n\tUse \"null\" as placeholder for empty values in CSV. Default is empty.\n") + print("\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed.") + print("\t-t\tSpecify TIME message name to group data messages by time and significantly reduce duplicate output.\n") + print("\t-fPrint to file instead of stdout") + #endif return fn = sys.argv[1] debug_out = False From 487497d66eab5846f133ed2da1a1f72356c24668 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 12 Aug 2013 23:50:29 +0200 Subject: [PATCH 53/80] Added Python 2 / 3 Windows / Linux / Mac OS converter script. So much for cross-platform / version agnostic --- Tools/README.txt | 13 +++++++ Tools/sdlog2_dump.py | 86 +++++--------------------------------------- 2 files changed, 22 insertions(+), 77 deletions(-) create mode 100644 Tools/README.txt diff --git a/Tools/README.txt b/Tools/README.txt new file mode 100644 index 0000000000..abeb9a4c71 --- /dev/null +++ b/Tools/README.txt @@ -0,0 +1,13 @@ +====== PX4 LOG CONVERSION ====== + +On each log session (commonly started and stopped by arming and disarming the vehicle) a new file logxxx.bin is created. In many cases there will be only one logfile named log001.bin (only one flight). + +There are two conversion scripts in this ZIP file: + +logconv.m: This is a MATLAB script which will automatically convert and display the flight data with a GUI. If running this script, the second script can be ignored. + +sdlog2_dump.py: This is a Python script (compatible with v2 and v3) which converts the self-describing binary log format to a CSV file. To export a CSV file from within a shell (Windows CMD or BASH on Linux / Mac OS), run: + +python sdlog2_dump.py log001.bin -f "export.csv" -t "TIME" -d "," -n "" + +Python can be downloaded from http://python.org, but is available as default on Mac OS and Linux. \ No newline at end of file diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index 0ffb381766..bb109d6f3f 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -1,6 +1,8 @@ #!/usr/bin/env python -"""Dump binary log generated by sdlog2 or APM as CSV +from __future__ import print_function + +"""Dump binary log generated by PX4's sdlog2 or APM as CSV Usage: python sdlog2_dump.py [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] @@ -21,17 +23,6 @@ __version__ = "1.2" import struct, sys -from pypreprocessor import pypreprocessor - -#exclude -if sys.version[:3].split('.')[0] == '2': - pypreprocessor.defines.append('python2') -if sys.version[:3].split('.')[0] == '3': - pypreprocessor.defines.append('python3') - -pypreprocessor.parse() -#endexclude - class SDLog2Parser: BLOCK_SIZE = 8192 MSG_HEADER_LEN = 3 @@ -76,11 +67,7 @@ class SDLog2Parser: self.__msg_descrs = {} # message descriptions by message type map self.__msg_labels = {} # message labels by message name map self.__msg_names = [] # message names in the same order as FORMAT messages - #ifdef python2 - self.__buffer = "" # buffer, python2 - #else - self.__buffer = bytearray() # buffer for input binary data - #endif + self.__buffer = "" # buffer for input binary data self.__ptr = 0 # read pointer in buffer self.__csv_columns = [] # CSV file columns in correct order in format "MSG.label" self.__csv_data = {} # current values for all columns @@ -129,24 +116,15 @@ class SDLog2Parser: self.__buffer = self.__buffer[self.__ptr:] + chunk self.__ptr = 0 while self.__bytesLeft() >= self.MSG_HEADER_LEN: - #ifdef python2 head1 = ord(self.__buffer[self.__ptr]) head2 = ord(self.__buffer[self.__ptr+1]) - #else - head1 = self.__buffer[self.__ptr] - head2 = self.__buffer[self.__ptr+1] - #endif if (head1 != self.MSG_HEAD1 or head2 != self.MSG_HEAD2): if self.__correct_errors: self.__ptr += 1 continue else: raise Exception("Invalid header at %i (0x%X): %02X %02X, must be %02X %02X" % (bytes_read + self.__ptr, bytes_read + self.__ptr, head1, head2, self.MSG_HEAD1, self.MSG_HEAD2)) - #ifdef python2 msg_type = ord(self.__buffer[self.__ptr+2]) - #else - msg_type = self.__buffer[self.__ptr+2] - #endif if msg_type == self.MSG_TYPE_FORMAT: # parse FORMAT message if self.__bytesLeft() < self.MSG_FORMAT_PACKET_LEN: @@ -192,13 +170,9 @@ class SDLog2Parser: self.__csv_columns.append(full_label) self.__csv_data[full_label] = None if self.__file != None: - print >> self.__file, self.__csv_delim.join(self.__csv_columns) + print(self.__csv_delim.join(self.__csv_columns), file=self.__file) else: - #ifdef python2 - print self.__csv_delim.join(self.__csv_columns) - #else print(self.__csv_delim.join(self.__csv_columns)) - #endif def __printCSVRow(self): s = [] @@ -211,28 +185,18 @@ class SDLog2Parser: s.append(v) if self.__file != None: - print >> self.__file, self.__csv_delim.join(s) + print(self.__csv_delim.join(s), file=self.__file) else: - #ifdef python2 - print self.__csv_delim.join(s) - #else print(self.__csv_delim.join(s)) - #endif def __parseMsgDescr(self): data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) msg_type = data[0] if msg_type != self.MSG_TYPE_FORMAT: msg_length = data[1] - #ifdef python2 - msg_name = data[2].strip("\0") - msg_format = data[3].strip("\0") - msg_labels = data[4].strip("\0").split(",") - #else - msg_name = str(data[2], 'ascii').strip("\0") - msg_format = str(data[3], 'ascii').strip("\0") - msg_labels = str(data[4], 'ascii').strip("\0").split(",") - #endif + msg_name = str(data[2]).strip("\0") + msg_format = str(data[3]).strip("\0") + msg_labels = str(data[4]).strip("\0").split(",") # Convert msg_format to struct.unpack format string msg_struct = "" msg_mults = [] @@ -249,13 +213,8 @@ class SDLog2Parser: self.__msg_names.append(msg_name) if self.__debug_out: if self.__filterMsg(msg_name) != None: - #ifdef python2 - print "MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % ( - msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults) - #else print("MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % ( msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults)) - #endif self.__ptr += self.MSG_FORMAT_PACKET_LEN def __parseMsg(self, msg_descr): @@ -266,11 +225,7 @@ class SDLog2Parser: show_fields = self.__filterMsg(msg_name) if (show_fields != None): data = list(struct.unpack(msg_struct, self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])) - #ifdef python2 - for i in xrange(len(data)): - #else for i in range(len(data)): - #endif if type(data[i]) is str: data[i] = data[i].strip("\0") m = msg_mults[i] @@ -278,26 +233,14 @@ class SDLog2Parser: data[i] = data[i] * m if self.__debug_out: s = [] - #ifdef python2 - for i in xrange(len(data)): - #else for i in range(len(data)): - #endif label = msg_labels[i] if show_fields == "*" or label in show_fields: s.append(label + "=" + str(data[i])) - #ifdef python2 - print "MSG %s: %s" % (msg_name, ", ".join(s)) - #else print("MSG %s: %s" % (msg_name, ", ".join(s))) - #endif else: # update CSV data buffer - #ifdef python2 - for i in xrange(len(data)): - #else for i in range(len(data)): - #endif label = msg_labels[i] if label in show_fields: self.__csv_data[msg_name + "_" + label] = data[i] @@ -309,16 +252,6 @@ class SDLog2Parser: def _main(): if len(sys.argv) < 2: - #ifdef python2 - print "Usage: python sdlog2_dump.py [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] [-t TIME_MSG_NAME]\n" - print "\t-v\tUse plain debug output instead of CSV.\n" - print "\t-e\tRecover from errors.\n" - print "\t-d\tUse \"delimiter\" in CSV. Default is \",\".\n" - print "\t-n\tUse \"null\" as placeholder for empty values in CSV. Default is empty.\n" - print "\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed." - print "\t-t\tSpecify TIME message name to group data messages by time and significantly reduce duplicate output.\n" - print "\t-fPrint to file instead of stdout" - #else print("Usage: python sdlog2_dump.py [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] [-t TIME_MSG_NAME]\n") print("\t-v\tUse plain debug output instead of CSV.\n") print("\t-e\tRecover from errors.\n") @@ -327,7 +260,6 @@ def _main(): print("\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed.") print("\t-t\tSpecify TIME message name to group data messages by time and significantly reduce duplicate output.\n") print("\t-fPrint to file instead of stdout") - #endif return fn = sys.argv[1] debug_out = False From c4498ce9a3525bafd2d1c70f7e16812d14d51206 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sat, 10 Aug 2013 12:39:58 -0700 Subject: [PATCH 54/80] Add a 'menuconfig' target that makes it possible to use the NuttX menuconfig tool on the PX4 config files. --- Makefile | 28 +++++++++++++++++++++++++++- 1 file changed, 27 insertions(+), 1 deletion(-) diff --git a/Makefile b/Makefile index c02a986cdd..dc69b0ae8b 100644 --- a/Makefile +++ b/Makefile @@ -148,7 +148,7 @@ $(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC) @$(ECHO) %% Configuring NuttX for $(board) $(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export) $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean - $(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)/nuttx-configs/$(board) .) + $(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(board) .) $(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration)) @$(ECHO) %% Exporting NuttX for $(board) $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) export @@ -156,6 +156,32 @@ $(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC) $(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@ $(Q) (cd $(NUTTX_SRC)/configs && $(RMDIR) $(board)) +# +# The user can run the NuttX 'menuconfig' tool for a single board configuration with +# make BOARDS= menuconfig +# +ifeq ($(MAKECMDGOALS),menuconfig) +ifneq ($(words $(BOARDS)),1) +$(error BOARDS must specify exactly one board for the menuconfig goal) +endif +BOARD = $(BOARDS) +menuconfig: $(NUTTX_SRC) + @$(ECHO) %% Configuring NuttX for $(BOARD) + $(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export) + $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean + $(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(BOARD) .) + $(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(BOARD)/nsh) + @$(ECHO) %% Running menuconfig for $(BOARD) + $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) menuconfig + @$(ECHO) %% Saving configuration file + $(Q)$(COPY) $(NUTTX_SRC).config $(PX4_BASE)nuttx-configs/$(BOARD)/nsh/defconfig +else +menuconfig: + @$(ECHO) "" + @$(ECHO) "The menuconfig goal must be invoked without any other goal being specified" + @$(ECHO) "" +endif + $(NUTTX_SRC): @$(ECHO) "" @$(ECHO) "NuttX sources missing - clone https://github.com/PX4/NuttX.git and try again." From 5e2d67617369474406d86d4eae5ba9a24d5cbb9f Mon Sep 17 00:00:00 2001 From: px4dev Date: Mon, 12 Aug 2013 21:57:11 -0700 Subject: [PATCH 55/80] Remove our depdenency on CONFIG_ARCH_BOARD_* coming from --- makefiles/board_px4fmu-v1.mk | 1 + makefiles/board_px4io-v1.mk | 1 + makefiles/firmware.mk | 4 ++++ 3 files changed, 6 insertions(+) diff --git a/makefiles/board_px4fmu-v1.mk b/makefiles/board_px4fmu-v1.mk index 8370696446..4d692e31ab 100644 --- a/makefiles/board_px4fmu-v1.mk +++ b/makefiles/board_px4fmu-v1.mk @@ -6,5 +6,6 @@ # Configure the toolchain # CONFIG_ARCH = CORTEXM4F +CONFIG_BOARD = PX4FMU_V1 include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk diff --git a/makefiles/board_px4io-v1.mk b/makefiles/board_px4io-v1.mk index b0eb2dae79..1872a4124f 100644 --- a/makefiles/board_px4io-v1.mk +++ b/makefiles/board_px4io-v1.mk @@ -6,5 +6,6 @@ # Configure the toolchain # CONFIG_ARCH = CORTEXM3 +CONFIG_BOARD = PX4IO_V1 include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk index 3ad13088b0..0d742c37dc 100644 --- a/makefiles/firmware.mk +++ b/makefiles/firmware.mk @@ -154,6 +154,10 @@ $(error Config $(CONFIG) references board $(BOARD), but no board definition file endif export BOARD include $(BOARD_FILE) +ifeq ($(CONFIG_BOARD),) +$(error Board config for $(BOARD) does not define CONFIG_BOARD) +endif +EXTRADEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) $(info % BOARD = $(BOARD)) # From 60275e1ae65633dfc03f6353b7796ed540975803 Mon Sep 17 00:00:00 2001 From: px4dev Date: Mon, 12 Aug 2013 21:59:10 -0700 Subject: [PATCH 56/80] Clean the FMUv1 config through menuconfig. --- nuttx-configs/px4fmu-v1/nsh/defconfig | 32 ++++++++++++++++----------- 1 file changed, 19 insertions(+), 13 deletions(-) diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig index d338161296..a7a6725c65 100644 --- a/nuttx-configs/px4fmu-v1/nsh/defconfig +++ b/nuttx-configs/px4fmu-v1/nsh/defconfig @@ -73,17 +73,16 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set # CONFIG_ARCH_CHIP_NUC1XX is not set -# CONFIG_ARCH_CHIP_SAM3U is not set +# CONFIG_ARCH_CHIP_SAM34 is not set CONFIG_ARCH_CHIP_STM32=y # CONFIG_ARCH_CHIP_STR71X is not set CONFIG_ARCH_CORTEXM4=y -CONFIG_ARCH_HAVE_FPU=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y -CONFIG_ARMV7M_STACKCHECK=y +CONFIG_ARCH_HAVE_FPU=y CONFIG_ARCH_FPU=y CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARMV7M_MPU is not set @@ -93,10 +92,8 @@ CONFIG_ARCH_HAVE_MPU=y # # CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y +CONFIG_ARMV7M_STACKCHECK=y CONFIG_SERIAL_TERMIOS=y -CONFIG_SERIAL_DISABLE_REORDERING=y -CONFIG_SERIAL_IFLOWCONTROL=y -CONFIG_SERIAL_OFLOWCONTROL=y # # STM32 Configuration Options @@ -248,6 +245,7 @@ CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y # CONFIG_STM32_FORCEPOWER is not set # CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set # CONFIG_STM32_CCMEXCLUDE is not set +CONFIG_STM32_DMACAPABLE=y # CONFIG_STM32_TIM4_PWM is not set # CONFIG_STM32_TIM5_PWM is not set # CONFIG_STM32_TIM9_PWM is not set @@ -275,6 +273,7 @@ CONFIG_UART5_RXDMA=y CONFIG_USART6_RXDMA=y # CONFIG_USART7_RXDMA is not set # CONFIG_USART8_RXDMA is not set +CONFIG_SERIAL_DISABLE_REORDERING=y CONFIG_STM32_USART_SINGLEWIRE=y # @@ -342,15 +341,12 @@ CONFIG_BOOT_RUNFROMFLASH=y # # Board Selection # -CONFIG_ARCH_BOARD_PX4FMU_V1=y -# CONFIG_ARCH_BOARD_CUSTOM is not set -CONFIG_ARCH_BOARD="px4fmu-v1" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD="" # # Common Board Options # -CONFIG_ARCH_HAVE_LEDS=y -# CONFIG_ARCH_LEDS is not set CONFIG_NSH_MMCSDMINOR=0 CONFIG_NSH_MMCSDSLOTNO=0 CONFIG_NSH_MMCSDSPIPORTNO=3 @@ -358,8 +354,6 @@ CONFIG_NSH_MMCSDSPIPORTNO=3 # # Board-Specific Options # -CONFIG_HRT_TIMER=y -CONFIG_HRT_PPM=y # # RTOS Features @@ -497,6 +491,8 @@ CONFIG_USART1_BAUD=57600 CONFIG_USART1_BITS=8 CONFIG_USART1_PARITY=0 CONFIG_USART1_2STOP=0 +# CONFIG_USART1_IFLOWCONTROL is not set +# CONFIG_USART1_OFLOWCONTROL is not set # # USART2 Configuration @@ -507,6 +503,8 @@ CONFIG_USART2_BAUD=57600 CONFIG_USART2_BITS=8 CONFIG_USART2_PARITY=0 CONFIG_USART2_2STOP=0 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y # # UART5 Configuration @@ -517,6 +515,8 @@ CONFIG_UART5_BAUD=57600 CONFIG_UART5_BITS=8 CONFIG_UART5_PARITY=0 CONFIG_UART5_2STOP=0 +# CONFIG_UART5_IFLOWCONTROL is not set +# CONFIG_UART5_OFLOWCONTROL is not set # # USART6 Configuration @@ -527,6 +527,10 @@ CONFIG_USART6_BAUD=57600 CONFIG_USART6_BITS=8 CONFIG_USART6_PARITY=0 CONFIG_USART6_2STOP=0 +# CONFIG_USART6_IFLOWCONTROL is not set +# CONFIG_USART6_OFLOWCONTROL is not set +CONFIG_SERIAL_IFLOWCONTROL=y +CONFIG_SERIAL_OFLOWCONTROL=y CONFIG_USBDEV=y # @@ -559,6 +563,7 @@ CONFIG_CDCACM_EPBULKIN_FSSIZE=64 CONFIG_CDCACM_EPBULKIN_HSSIZE=512 CONFIG_CDCACM_NWRREQS=4 CONFIG_CDCACM_NRDREQS=4 +CONFIG_CDCACM_BULKIN_REQLEN=96 CONFIG_CDCACM_RXBUFSIZE=256 CONFIG_CDCACM_TXBUFSIZE=256 CONFIG_CDCACM_VENDORID=0x26ac @@ -747,6 +752,7 @@ CONFIG_EXAMPLES_CDCACM=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set CONFIG_EXAMPLES_MOUNT=y +# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set From b3d2efc90af671f13f8f473230e3af6e8d91153c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 13 Aug 2013 07:26:05 +0200 Subject: [PATCH 57/80] WIP --- Tools/sdlog2_dump.py | 21 +++++++++++++++------ 1 file changed, 15 insertions(+), 6 deletions(-) diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index bb109d6f3f..8746a99479 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -23,6 +23,11 @@ __version__ = "1.2" import struct, sys +if sys.hexversion >= 0x030000F0: + runningPython3 = True +else: + runningPython3 = False + class SDLog2Parser: BLOCK_SIZE = 8192 MSG_HEADER_LEN = 3 @@ -67,7 +72,7 @@ class SDLog2Parser: self.__msg_descrs = {} # message descriptions by message type map self.__msg_labels = {} # message labels by message name map self.__msg_names = [] # message names in the same order as FORMAT messages - self.__buffer = "" # buffer for input binary data + self.__buffer = bytearray() # buffer for input binary data self.__ptr = 0 # read pointer in buffer self.__csv_columns = [] # CSV file columns in correct order in format "MSG.label" self.__csv_data = {} # current values for all columns @@ -116,15 +121,15 @@ class SDLog2Parser: self.__buffer = self.__buffer[self.__ptr:] + chunk self.__ptr = 0 while self.__bytesLeft() >= self.MSG_HEADER_LEN: - head1 = ord(self.__buffer[self.__ptr]) - head2 = ord(self.__buffer[self.__ptr+1]) + head1 = self.__buffer[self.__ptr] + head2 = self.__buffer[self.__ptr+1] if (head1 != self.MSG_HEAD1 or head2 != self.MSG_HEAD2): if self.__correct_errors: self.__ptr += 1 continue else: raise Exception("Invalid header at %i (0x%X): %02X %02X, must be %02X %02X" % (bytes_read + self.__ptr, bytes_read + self.__ptr, head1, head2, self.MSG_HEAD1, self.MSG_HEAD2)) - msg_type = ord(self.__buffer[self.__ptr+2]) + msg_type = self.__buffer[self.__ptr+2] if msg_type == self.MSG_TYPE_FORMAT: # parse FORMAT message if self.__bytesLeft() < self.MSG_FORMAT_PACKET_LEN: @@ -190,8 +195,12 @@ class SDLog2Parser: print(self.__csv_delim.join(s)) def __parseMsgDescr(self): - data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) + if runningPython3: + data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) + else: + data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) msg_type = data[0] + print(msg_type) if msg_type != self.MSG_TYPE_FORMAT: msg_length = data[1] msg_name = str(data[2]).strip("\0") @@ -224,7 +233,7 @@ class SDLog2Parser: self.__csv_updated = False show_fields = self.__filterMsg(msg_name) if (show_fields != None): - data = list(struct.unpack(msg_struct, self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])) + data = list(struct.unpack(msg_struct, str(bytearray(self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])))) for i in range(len(data)): if type(data[i]) is str: data[i] = data[i].strip("\0") From da9d9781f999361009b2c7b8e9b18d0d500c072c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 13 Aug 2013 07:33:32 +0200 Subject: [PATCH 58/80] Final version of log conversion script, runs with Python 2 or 3 on Windows, Linux and MacOS. Tested on Mac with 2 and 3 --- Tools/sdlog2_dump.py | 18 +++++++++++++----- 1 file changed, 13 insertions(+), 5 deletions(-) diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index 8746a99479..a376e03d39 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -198,14 +198,19 @@ class SDLog2Parser: if runningPython3: data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) else: - data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) + data = struct.unpack(self.MSG_FORMAT_STRUCT, str(self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN])) msg_type = data[0] print(msg_type) if msg_type != self.MSG_TYPE_FORMAT: msg_length = data[1] - msg_name = str(data[2]).strip("\0") - msg_format = str(data[3]).strip("\0") - msg_labels = str(data[4]).strip("\0").split(",") + if runningPython3: + msg_name = str(data[2], 'ascii').strip("\0") + msg_format = str(data[3], 'ascii').strip("\0") + msg_labels = str(data[4], 'ascii').strip("\0").split(",") + else: + msg_name = str(data[2]).strip("\0") + msg_format = str(data[3]).strip("\0") + msg_labels = str(data[4]).strip("\0").split(",") # Convert msg_format to struct.unpack format string msg_struct = "" msg_mults = [] @@ -233,7 +238,10 @@ class SDLog2Parser: self.__csv_updated = False show_fields = self.__filterMsg(msg_name) if (show_fields != None): - data = list(struct.unpack(msg_struct, str(bytearray(self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])))) + if runningPython3: + data = list(struct.unpack(msg_struct, self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])) + else: + data = list(struct.unpack(msg_struct, str(self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length]))) for i in range(len(data)): if type(data[i]) is str: data[i] = data[i].strip("\0") From 0025e9ca909d4e1c8bc63841cd0e61265a328e30 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 13 Aug 2013 07:57:39 +0200 Subject: [PATCH 59/80] Hotfix: Copy a current version of the log conversion tools to each log directory --- ROMFS/px4fmu_common/logging/log_converter.zip | Bin 0 -> 10090 bytes ROMFS/px4fmu_common/logging/logconv.m | 586 ------------------ src/modules/sdlog2/sdlog2.c | 9 + 3 files changed, 9 insertions(+), 586 deletions(-) create mode 100644 ROMFS/px4fmu_common/logging/log_converter.zip delete mode 100644 ROMFS/px4fmu_common/logging/logconv.m diff --git a/ROMFS/px4fmu_common/logging/log_converter.zip b/ROMFS/px4fmu_common/logging/log_converter.zip new file mode 100644 index 0000000000000000000000000000000000000000..2641e671068b1ea6867fc6b9fef17ba3889e5262 GIT binary patch literal 10090 zcmaKSV~i&3w&hzkx@_CFZQHhuF1xy1UGB1NTV1wo`z?F&ok?cS+%xw+$xfahd#_|C z>(AP2DanF?qX7T_Xuu{ff@mT8c8nK103gi*03ZVJ0Ip_sj+QKjX72V*3{KwaYA^t> z_#qgTx4$qd?p|;J5b#G30N`Kq-8i3)8!f<-w^}1~@Mg_n+07nfxKyYj`3`j3^(tw? zCk)(R64e$1bD4z*Rnyh)uWPC3A}SgAWfPIzRle=JYp*Uw=bO7$ckQ3PS#^%o8%aMk zt64d4hQ(Wmg^^d(^=FBQ#wcc@qYuRgXt2zcQ+C;A?x)Y?6#)En9%NG*X5!fN1JMj) zS8;k@Pao3K*}m^JX;u))w~nx4Z*l z3*1ZIOFfxvCPh|J0mPSC=#q8x4#(mCd1;pQpIJBW!}|c%0G@0H3={efu2mFZei51C zU?@obhL3nd$M{7wSyh!)8<}>@r98xRA=uj~e{2IiJ+vkaeRLI7Ddcc*-YInrAJMRM z0xM30J8Y5c{%cOu5E%;aI$t6%KeDFLEebBE;FO})!wk2ConHTeYqMyTmLKY1kdwyr zEY8j<%7;;TnWa=2bRn&1{b-SrST|Z4r!Pu6jO(-!oG%@4TX+VaP!yJ;t}L0NIIa(4%KVjE zb4D2@^yMdlD2Ok>8+x*|$81?%hAq2#p0qK`O5~-#=q9$1^weh<2EdIiV55_Daesoe zyJn%2(TRLz-0t#ym34Z2dv;BK|C~c&6@Xnw@D~u|=M5n2;tqgIu&mxA4UWlffwKI0 z8xc_6uX(d=_{RV$t&}l4PCFX{AjaXZ#HHH5a?UormSP)BAnu-1Z zHmV$vvxa(iq6XbkWIlxbcFzd1VfzPvFHfwaQuheFeSQQl4j6r7<)M^%L+wyKW`AS|2%{Hwna>UhC*-09UBGOCWY=fDRt;DS{s zHNey`w%Y|?IZKhK85tm@Geb~@4QiYtTvaM1meiCu*HJ)M%{hr|k0gq|m$lUw7|4c2 zjROzx%&H3xae7?%T{-WnESZXMMfz9|DJE?dFw4UCmMEyWWd51)z|@*0{is&dMVOto)>D1@l~!;THgX_Q;W zy3uTY&sBNDkm+b_9fC*T!O4CGnOTdkgL!n0j;XD(VB?(2b|mr;k2q!PL?fiBVy7pU zmb3TspBBs0=6&Gtn{B?#}{@DVg=px5GGTHfY zVws9~GU)~7iW?INl#3rgEid^fI}J zI#yk6gC=^uYeaC&qLH4>$=2CeiP<>!UoNVEr zBjA7HTkiK58f}qZtpba~P)#`k?;gs2f!W~xN+HnwiErFaEw!GvRy0vVcFcEqy_O1^ zo0Cwu?XCQ`A{1M~Lf|dEBZovTPl@jvO*yASsAY`kfn1gWw*&@#O>y+)cHzr0*|Z^m z>peCg5UiG%U`vJnFwu{NL++)#zemvrM6Y{)XR_7paw9t1?XYifRJAH7Hk+GM!xZP; zQcchy`zjI7mYde|ZPGsr@~hCGO10+EQT5r5Ly?ry1)~2Jeqq*GQ}I({R%$3YpV(Us zw938Obw5iYTVG#RAM4bj&zT>;@S{(l;WCaGAx9~MoWja+szBcxH@yF%ny8p(Zej=T zso`{!LH_8*4k^CLg71_vxZFL7!8>^4uw|8D&spIz4t-}*5*U{p6gUW)S&EvoZe1B- zVXA9dJjmgGZpTfSJ?rBCS!SG#e&OhERpJW3D3034xYbb=^4Ix$0pO5H2$Ly zZ*k+I3feo*?llR9yRMjJG-^`lBwyag$bw7a7^E1;nNyB!+U`*R(m#v1U@xLjbp{Kh z8V;e)%C6N?XVHl({w;v0uN|7q(FrAH~;LeyKI%n|+nO3Af_Q6i?Krsr_>vpXEP0e0yDYk~a zxn`xV;s}@D)7V27=L*NX??8ZYCjMfTEN1ECAwYZJuRaB3K_54>lr6)S@>LL=oWx&h zCcmgHsCfkXW?dh`rbq0ijV}9U_Vx$stn(H@C7s`D!~9j4aq8#?)#i1v_;$qnR}98&?Y|>)hFsFRCn;&CIAXtt_F`HHK(`U`%cW zRsekto2mrG6#ar!@=%FeGCk`r|DU;Z9Vv-->Tx_4f=%`a2y071;!ZS;VTw7S=D*1l zDO9oKf%Tk%51U89mk2ngGX%jknJuuN-bimvlM6*SzCGe&_OA}@UpZU>iqXEzy^;nN zcCx?5^}5E_OEw-16A5(P<%A}e91-MJOB84)7WPB7IYcNcHLoh_XgsbTcpN^8KXEQ7 zTrj~P(-P+Y`mu+YXoaaTSxMdv(_#bRw(fF>p0<4}2qlkHm$`e|hcJsp%IA3K@&NlV ziVH^(h6kT!1GcxLoG4`OR+M0!x1<&be~}%PEXBoO(uGpy!I0@;v<)*&H3NlQsuVk> zViN{9t7bWupPChX7ifZ(WXd0$2vHP;vh2@~M_zumoUG;)p$3T82rBH8Zc_CmCtQV? zlHgza@1q`J-bJ{9zvtn)_uNJBw7iJg6Mb1tPx+6<=CyvX(hGGZeSc`=$Is&AJY1zM zTXZ@v5e8i1h^c3G{6={!(Kyv)qHDyx9cHia*r3ezHq;x$L4`DAZ->Q*@Xj2FlP9B| zEmCFhW5Al|f-qEw-5C2-{<=N=r*g?Q@X>&g;u$9Y`Ot#M&j(pDSs_$rmJ*X#ca9lj zYIJ634gqp_e-71|Q(Nx#FM`w26OM~YG86f)y;X+TEL&O^)-)mlnPs-$5mPBtd+VEzsz3{ueic_G_W1NrUL6<2RARO>a_{>sQy>cxch)u=Lf--xfyT54Q*Au^`O`yX_pms2L9fX>cr+TDejFb&ahTPJ=mlJ&^`XY_x;!|G z6s1C|(Ug!Z7s9E*Nc$RydZPFtZS`UAql>FV$H$GIUiXjE_o2ad3ysitQHgHV#69ZV z=Xd+n?sc3?E8zVjchjI*7S*088da@wV$hBe0Y+$7kSWe}?pA|MUkbPT9crhG&7V)q zukZ+IpD^5gY*4p)C6sro$T<@LvTY0K8S@&HTAYDK`K7*J-O8vbv8YgiubX<+N1Vql z%m!lxoy?4Z6GcLOB~R7-eulNYzjg*yIdAFOdUP$javG1>JdYOXx#4QAf1hobEyKHu zD(u8IzS?d1Hac`=xMoclF=yS%zJM4aJ6?o9g5~^x2wJS0jFupRE?4}vjvG=*J5cH0vyD(;Dk5V( zs|q9${WfOYb2aqXNq^)tY_ZtHr8kv|;*bPge810}`o4NA&!N_eq@olK@esL;N#-uE z&nwO=&VAUp$yu~@1lni8bbHB72OF0`nB5{aGszyNuwnE}s+Vgp6O62rbSLJzB~3bi zK{Rchd04#-Wt(o)_Wm9{B8;%a)Esg#T9iX_Ypa#qU2eezXOi)}&22 z2f8Q{#tpsR4o)4tIQ?fe9#$zImq)B{ZsFefFCb+cD} zj`X(liSM6x!RY-mS%vi9v)^jDn}3w|Xg6GxG26_NdkaB2_#7xskf%Vl<<}~R;p@nk z{E+;fW&>TR+#>0v-yoA+02}L@ki9Jb0by2Z;An(&L^drwpQfhV;Nwr$J=Q z1R{eJCQ$;|;6zx-cwOoJ0u8B)*AOKBP|cL8tGfyWg?U)Q0hyu;u)m0>nezjnCTvLZ za6@-WmbkNc^7n1tgPE)!kGp}o2pLsj?&`gX9_yjhDCSHoqpD_1UuL=-EyBwol`)Nd z&aaC@A=SXR$^tU3(^*HH}!Ka07)9!jy zgv*eQ+jPr44p2G=p}$Kim)NJ-^z~({IkccxwCf0NpJPjRcB=GuMD}`N@M(=gERIQV zFz!TbA1X$ekd1W0PokF!!S;(cTOXcHJ0ZrSBqnxl(Ck1dQ+XR${4vC&Bu0tf{O2*rdoQv z@ezr1B$TTD5>=y*yKMG=aJ zZ~3-92lKV$9XKI@Uz66%ZA;C$u3Q_fQJW7zlNc2R8i~t7=Vo-)@+e>G`{Q!djz~NB zAqab!Uon78{gCmReRemrQn#*zm5CIw%m_=%(@5G$<}+v}!Ygv@1=b-O1( z?B#-bsM7JJCbd1f2}F;5w?ojIh=Bz6)0-ljlPd>sdkrm8`=_IRU%tbvv!oylv4okJU16HBJ~=KsZ1Ir_T?XkRyEnZ_8&756PhMl9k}8$@S}aZuspoPVC42xWqfm*>gBx z`ARmt4us4xqz1aLxi830;G|`aZV45Hs@TsZ1x_YHR}2WwYSpu7i7Fj z#eKwq1iEI~R|gCxiCMpYS5~C$%T|W9E-hYlwErShrfv!U;Ku1<6vo4eqg5n0!i(h8 z?Tr|z-ZmF;0;v5y!F$W`kaI}GtI?}4cW^!mM8I#Eu*ZRTq>%nx_(}DQ7h5EbF>h^c zQDj(>-I>6i<0(45YTFA*U}@4frAqewPT=R{YJ7-bv<$UI6q~7B<~Xz_X%lVHKq91| z3N)rsPDJymh-M%p56%Ek&JW`mgNWLGKruY7-!A8}jO2T58NKtz*SvXR-)4zS=<3MT z@6-fWx&^RO0_GRi_A3NzL0F{zu)e2*L6(T`24jtQ&bMln&ySD;9||UaW%NOVqywK# z`ksNZM!wkPj~HcmS_O;zQdV2_%w}0u706N^c)8xGkh5h1mS=3#E5*?)s?Nvz%j*vWC7KuzkOqQ4WElLzjyd z#>ET;;*y?6ggT~^MeYdxb8L!Cem)T+F&SDWVGXvy;_GyetUOc)@SLg6^*8#_%w?

A{m!XO)hr8(xGBB;%}2kAZgk#{>7 zxQr$=%zt8~Q9CWqPJ`7Et%#oBcZ>Vl3hE~sTp(CZL#_;Uk@{r1c45H9vj>2vAClZ7 z*iO|nV7IV&rku}uOgDO#!q%2n2pm{!=^&!@;$5=C2^$(uEa{My(94y0E`6Y{C7gWeO58d%oM z5A*;U4gf8OVNGg_Nl>ca9o3^nWUJ*gg!(gYkggXVP%SQ&;=a@^+(=}`M;@k_9aXq` zp?4%jY+*WhL44$)gK^a5OE&e7N_|mEYKb|j8a#kQZXWe~a+30;S^IYl&K{ccTw~rs zf$+AJ2@qkjwgy{!W5^=}8}%bli)yud91vlUp_%IeaAWv!2s*39b0{us?tRP^=G=1a z?P2rF--kA`$2Mk1*uK=G@XTZR;q^^PI-xs3A#h0d_4+Fw&S5uc80z0Q=H4>mUYYF0 z_#fAZS6Y;-`w}z0w(sSA9CQ2*BlJVsA!E0y)6dZDT$`~|# zINHR7U3@pp)LpdxVY3XyFVTh%{-ILwb(aRQ%q_o6sn)h!4Y4wMO3|`M$p*>%ZG{2V zFrSb%{%H5Ve{V%iy0d`;Cf&j=!u=Kt-)jAFn|Rl1Msi+4e!Zb1qT`tPu@Gn@RV2(y zy3hGZW(Fkhy&+)(QLcK9Vd_M#sfV`J+hi}b2EM*>y)|nBRUE4p)g0$Z3bUKkko9za zHivBuFb)pycB+^e8Cm}B^J-!eAYAP!w3{?`aKcGn-^8wF_kN-+!4Gx_w~(aCCWn~h z{6Dsa)C5f(AS%lQN$ZnFgT>T4%z$Y}23qw=6xvFRKXocciqR^2=eui5B0THZusict zvk*!i=TN@%bCzMmTyFi`;)6L z?I>8@ycJ_)Op*ue91RFvZ4--z@k!cr?wypD%%O~EE9>WocL&+=X-aYaXI}QSjwWw2 zR|Nd`#B2xApIXu;3J<(npeJJ-g+RkKB+aAPWCy0>V?Ctt{Xk7!yxR&jnwtxB;64Pk zY$A}$<(iSfYx}FR!JqkRWa;ncsnvP*rFMssdXFHoOQY6u0Nr@sUnIuc_Y45QuObtPJ<8Z(hqg;0Wr!b~BrVP}Nj&EABO`~)!|H}v{g#y^=u z?x4SWsI|>nVUxF*V@S+ITmPwjvsNV-crX$V#sXjW-EU8Vwd!m$LJW%c!NL=aeB5_* zV!U_s(huY-l$cutPlV2k#RW^K_Da9D-Tg0+-FJ446*Q1DbDQ&O(^0D< zE*^!&wuRO_(%0e;Og_=&wZ(SbLO)D8L$l3BCr|G1r$r!OAlHC&q_84oDdz7Y`x;MY zvHF21lKcokPwzCp#H+a!7JN0#f z>gi^0e);DXZx=l^+?5#cS}oy3#1^(@tRqU%29w>^gviB{l;3j=fq_~%ARvo9uH2-g ztMgHynOg)TtJlIcR_G>ZZWT>cxz4cB zs8^%kKLX+%AN|r(uWsjJfaG2RBV%F)vj|>Tt$9DZp9kLPKj7Z z%fHmZq-h`!zF`e<*$1uf>-=Z=cu2|(c_vs(&N?&;l^vNt)^6f>EK%i@pZs;GDZjDF zdtzMSh87ZJ@?JuVUx}8ZCMv_XPMI&BGr5!&`gDR%pc=qB7(X&b(*0QCXTvD>d@#H{ ze6uw!AQ!RsB*T)%vU0YFAETg5`Z0oBJM^YWr|FG zLv=yYhIeBAM#W(?R#G4iDAQ-z_`8*LFR%NURhko2gg_@b%tpFm+e@3UsY8T;!U1u<-za2di2ISi8 z>SO`ExL&)J!hx%C`~nYlU-|6o5!iVpK*P1sC@t(2gDHtJWVHSsLhwPY#}FYgw46}Y z=&n|JWLAu$sW@@$=vlae`jCKEZQFYauzj^J+7J|Kv+3iJ|Y}48n(cra0P3bc*t+8e5Q!Ega#?h5qb|Q|S82-nqG~B!v{mghV^{ z4c#f?*R7T+>YI>z#st^qOgJ(s-v*WLWN?IPX!WUC-%cr%3XiI6X#ZBkAg%Jwfa1L= z9PJd5@w(ho2O}hOs}HV44G2@dv2RP)MLNTwA@H5;DeU-qm~Z`{Rx$|)he;Yviv@kB zKONw%J76U^RJ*-Ijv9Es>_XC4{_*E;ZF4`zNLT5Rwf$RBI&B22;(7K_i2eu(n2pTE zy)#5NP{B56GriLNwyk(Jjxu(=I+{W%d0eU})Ul=jAXKtqyNl%#*gX_>7&vGthw4=p zJ5C#E!)X~gi9c>hR&psX!RH)aiibM80g#v9vUb?)SD~$WP0xLH*BdFCBg%mZ{-yIE z>Da<#J(rMke9So_1S%!NZ=D$`FC7UbkC&1`(*Pf2DlprM7D-U2l87ADDB&gMZt)fl z8NLLdR@zNHRBVXB%2YS3G1K|VcF<+@h;E`I^i0_y6M7sP(u^hV{F8vvDX+ACVA|ML zriX9{*7Wk&G$az|H#UZ1_uK?$8%U#-F=;@V^B&!b=Pz2*EilpII)+;N;l@ai67h-} zaa6v0>*>s1$;$29u4x8T$!`aWxg)OXNy{c$aYeCX3dXlI17Ab@l`T@1;Zex1$&h35 z`;RY#UvAiyS@(8Hdkfm)eKNh;!SNFSIbLRg!f%4P^WCRN3_Jn5x^z;luKr)XrSB`b zo-Bd~*l9o)uXm)SE-;Qkf_um770=K9rI!!CCi(41P5xs(mwV~78S7b)55HJ$q}*XJ zF>0aQthz>Q*@c($*0rgPoD*wT{3nJzHO_Ui@f*{%`(?5lse%}gOr=z0e@0m3!`yE& zbC`P10s$3iS;HOx2oHm=TdaxEDPoRF_poLo14c=NqnJ~ z3LnfX-;;TZgSp{;v55J4ignpg+7yRJ`@|ISv0odnwez z*fNZ#K>mzv`)Wu}N_aQ-2$I`vY|;(<@uXP_XK)UFK4SwAj_W5k+HE)4gk_AF(Fkeb zh7ffB>K#`zc<_Rk1$W*7vfb7}r_c?RrjRlJXU|_&tO3U&M@92mfn$e=J zGTdAgw)u5B3cP({ZpK_Q(NkFgddur1%usG~|3lQP9oln)*snCbf`?A*mUq!HAJ2iu zKIhC9;=&|nv=+}!I@wMEfiB`ciU$!;nG`~kDT<*#N5dHC6{A@YyT8D8qC`m<4U~jP z6xGMJ+3J3Ev6A7TjuUj8_^oif4kN&9n$-4`wrqji6*|iY@AM|h&U7_y&RV{MT!SNP zVz}4rZ_%Bp7b7!9y6JeeMIEk6Cwe2Bsz|RTj%`0rDvT*rV;~uD%OtR< zvlVq4c6fa3E-M_|**Pz02RMzJP_~_V`X1z3l9Vi8f}n{G6MpVxT9J+5O$7NA%HLah zGcu^*qHE*6u9c6!kJgggsZ8+@x8{@w@Jn->?C>W$&E2}c#gN#qyvU<*)E)Qa1hygA z?m;y4{~jNO`7tVP|2D`vt`_i7?z%1bxr+TK=h;7p@6HV&XH=HL;S@=io@w^7Ioq@2 zCHz2XY{t?C+buL+_5^T3I1N1bH-N7 zA9t+T@Nl|QplmF2?ZlTMV;;f7H>T*$x_93V*%v0Q+s8NH|K8fyy5U6&Xkj<+KmY(0 zFaQ7+fCo?!7Z#HjXK?d!``593O!NPn6H-^vbzEmc^Pj1G`AwNXkg}F2B$*W!c1~;;^Q^(t7 z`FD!aF(~DqWC_!xj0zSVcc+{xOm3+YJ`VS(gC?*wnR8jKsbXBq9yBX)YF6?RA}eQc z;*`@w$5!1W8HBS0ZQ+=7qe|t(>x3T*Ps19!G$|r9$ZfHR%^;$x!;^fzUN0yK6wjn# zNon(n$y7X0@cSc%2rPxV#vz1h+S6e-81menKEX`a9GUD@H}Qn1Q4Mu=)ZdGP&W3bsZo zqP-d3_M6g%85{IpFkwyCsJo2grq1{eQ+Dl$9GcJMcQlo?R3SK~({^S0rRDvlv$HA( zExz&p?pyo4^f@~(MqD+X(eOQnu@oI3B$7+UE zMEMVCKtKt>{=0}77T});0ssJtg8upa*T5OX{|=n}m$2EtWB#Y@^Y55_@PL0efgk|? tGJ*aFxc_AKzr)dy0sbGJLjeB8^Z&qufc$3}FaQ|f9smFsQ~a~#{{rgbAVmNG literal 0 HcmV?d00001 diff --git a/ROMFS/px4fmu_common/logging/logconv.m b/ROMFS/px4fmu_common/logging/logconv.m deleted file mode 100644 index 3750ddae2a..0000000000 --- a/ROMFS/px4fmu_common/logging/logconv.m +++ /dev/null @@ -1,586 +0,0 @@ -% This Matlab Script can be used to import the binary logged values of the -% PX4FMU into data that can be plotted and analyzed. - -%% ************************************************************************ -% PX4LOG_PLOTSCRIPT: Main function -% ************************************************************************ -function PX4Log_Plotscript - -% Clear everything -clc -clear all -close all - -% ************************************************************************ -% SETTINGS -% ************************************************************************ - -% Set the path to your sysvector.bin file here -filePath = 'sysvector.bin'; - -% Set the minimum and maximum times to plot here [in seconds] -mintime=0; %The minimum time/timestamp to display, as set by the user [0 for first element / start] -maxtime=0; %The maximum time/timestamp to display, as set by the user [0 for last element / end] - -%Determine which data to plot. Not completely implemented yet. -bDisplayGPS=true; - -%conversion factors -fconv_gpsalt=1E-3; %[mm] to [m] -fconv_gpslatlong=1E-7; %[gps_raw_position_unit] to [deg] -fconv_timestamp=1E-6; % [microseconds] to [seconds] - -% ************************************************************************ -% Import the PX4 logs -% ************************************************************************ -ImportPX4LogData(); - -%Translate min and max plot times to indices -time=double(sysvector.timestamp) .*fconv_timestamp; -mintime_log=time(1); %The minimum time/timestamp found in the log -maxtime_log=time(end); %The maximum time/timestamp found in the log -CurTime=mintime_log; %The current time at which to draw the aircraft position - -[imintime,imaxtime]=FindMinMaxTimeIndices(); - -% ************************************************************************ -% PLOT & GUI SETUP -% ************************************************************************ -NrFigures=5; -NrAxes=10; -h.figures(1:NrFigures)=0.0; % Temporary initialization of figure handle array - these are numbered consecutively -h.axes(1:NrAxes)=0.0; % Temporary initialization of axes handle array - these are numbered consecutively -h.pathpoints=[]; % Temporary initiliazation of path points - -% Setup the GUI to control the plots -InitControlGUI(); -% Setup the plotting-GUI (figures, axes) itself. -InitPlotGUI(); - -% ************************************************************************ -% DRAW EVERYTHING -% ************************************************************************ -DrawRawData(); -DrawCurrentAircraftState(); - -%% ************************************************************************ -% *** END OF MAIN SCRIPT *** -% NESTED FUNCTION DEFINTIONS FROM HERE ON -% ************************************************************************ - - -%% ************************************************************************ -% IMPORTPX4LOGDATA (nested function) -% ************************************************************************ -% Attention: This is the import routine for firmware from ca. 03/2013. -% Other firmware versions might require different import -% routines. - -function ImportPX4LogData() - % Work around a Matlab bug (not related to PX4) - % where timestamps from 1.1.1970 do not allow to - % read the file's size - if ismac - system('touch -t 201212121212.12 sysvector.bin'); - end - - % ************************************************************************ - % RETRIEVE SYSTEM VECTOR - % ************************************************************************* - % //All measurements in NED frame - % - % uint64_t timestamp; //[us] - % float gyro[3]; //[rad/s] - % float accel[3]; //[m/s^2] - % float mag[3]; //[gauss] - % float baro; //pressure [millibar] - % float baro_alt; //altitude above MSL [meter] - % float baro_temp; //[degree celcius] - % float control[4]; //roll, pitch, yaw [-1..1], thrust [0..1] - % float actuators[8]; //motor 1-8, in motor units (PWM: 1000-2000,AR.Drone: 0-512) - % float vbat; //battery voltage in [volt] - % float bat_current - current drawn from battery at this time instant - % float bat_discharged - discharged energy in mAh - % float adc[4]; //remaining auxiliary ADC ports [volt] - % float local_position[3]; //tangent plane mapping into x,y,z [m] - % int32_t gps_raw_position[3]; //latitude [degrees] north, longitude [degrees] east, altitude above MSL [millimeter] - % float attitude[3]; //pitch, roll, yaw [rad] - % float rotMatrix[9]; //unitvectors - % float actuator_control[4]; //unitvector - % float optical_flow[4]; //roll, pitch, yaw [-1..1], thrust [0..1] - % float diff_pressure; - pressure difference in millibar - % float ind_airspeed; - % float true_airspeed; - - % Definition of the logged values - logFormat{1} = struct('name', 'timestamp', 'bytes', 8, 'array', 1, 'precision', 'uint64', 'machineformat', 'ieee-le.l64'); - logFormat{2} = struct('name', 'gyro', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{3} = struct('name', 'accel', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{4} = struct('name', 'mag', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{5} = struct('name', 'baro', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{6} = struct('name', 'baro_alt', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{7} = struct('name', 'baro_temp', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{8} = struct('name', 'control', 'bytes', 4, 'array', 4, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{9} = struct('name', 'actuators', 'bytes', 4, 'array', 8, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{10} = struct('name', 'vbat', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{11} = struct('name', 'bat_current', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{12} = struct('name', 'bat_discharged', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{13} = struct('name', 'adc', 'bytes', 4, 'array', 4, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{14} = struct('name', 'local_position', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{15} = struct('name', 'gps_raw_position', 'bytes', 4, 'array', 3, 'precision', 'uint32', 'machineformat', 'ieee-le'); - logFormat{16} = struct('name', 'attitude', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{17} = struct('name', 'rot_matrix', 'bytes', 4, 'array', 9, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{18} = struct('name', 'vicon_position', 'bytes', 4, 'array', 6, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{19} = struct('name', 'actuator_control', 'bytes', 4, 'array', 4, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{20} = struct('name', 'optical_flow', 'bytes', 4, 'array', 6, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{21} = struct('name', 'diff_pressure', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{22} = struct('name', 'ind_airspeed', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{23} = struct('name', 'true_airspeed', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le'); - - % First get length of one line - columns = length(logFormat); - lineLength = 0; - - for i=1:columns - lineLength = lineLength + logFormat{i}.bytes * logFormat{i}.array; - end - - - if exist(filePath, 'file') - - fileInfo = dir(filePath); - fileSize = fileInfo.bytes; - - elements = int64(fileSize./(lineLength)); - - fid = fopen(filePath, 'r'); - offset = 0; - for i=1:columns - % using fread with a skip speeds up the import drastically, do not - % import the values one after the other - sysvector.(genvarname(logFormat{i}.name)) = transpose(fread(... - fid, ... - [logFormat{i}.array, elements], [num2str(logFormat{i}.array),'*',logFormat{i}.precision,'=>',logFormat{i}.precision], ... - lineLength - logFormat{i}.bytes*logFormat{i}.array, ... - logFormat{i}.machineformat) ... - ); - offset = offset + logFormat{i}.bytes*logFormat{i}.array; - fseek(fid, offset,'bof'); - end - - % shot the flight time - time_us = sysvector.timestamp(end) - sysvector.timestamp(1); - time_s = time_us*1e-6; - time_m = time_s/60; - - % close the logfile - fclose(fid); - - disp(['end log2matlab conversion' char(10)]); - else - disp(['file: ' filePath ' does not exist' char(10)]); - end -end - -%% ************************************************************************ -% INITCONTROLGUI (nested function) -% ************************************************************************ -%Setup central control GUI components to control current time where data is shown -function InitControlGUI() - %********************************************************************** - % GUI size definitions - %********************************************************************** - dxy=5; %margins - %Panel: Plotctrl - dlabels=120; - dsliders=200; - dedits=80; - hslider=20; - - hpanel1=40; %panel1 - hpanel2=220;%panel2 - hpanel3=3*hslider+4*dxy+3*dxy;%panel3. - - width=dlabels+dsliders+dedits+4*dxy+2*dxy; %figure width - height=hpanel1+hpanel2+hpanel3+4*dxy; %figure height - - %********************************************************************** - % Create GUI - %********************************************************************** - h.figures(1)=figure('Units','pixels','position',[200 200 width height],'Name','Control GUI'); - h.guistatepanel=uipanel('Title','Current GUI state','Units','pixels','Position',[dxy dxy width-2*dxy hpanel1],'parent',h.figures(1)); - h.aircraftstatepanel=uipanel('Title','Current aircraft state','Units','pixels','Position',[dxy hpanel1+2*dxy width-2*dxy hpanel2],'parent',h.figures(1)); - h.plotctrlpanel=uipanel('Title','Plot Control','Units','pixels','Position',[dxy hpanel1+hpanel2+3*dxy width-2*dxy hpanel3],'parent',h.figures(1)); - - %%Control GUI-elements - %Slider: Current time - h.labels.CurTime=uicontrol(gcf,'style','text','Position',[dxy dxy dlabels hslider],'String','Current time t[s]:','parent',h.plotctrlpanel,'HorizontalAlignment','left'); - h.sliders.CurTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels dxy dsliders hslider],... - 'min',mintime,'max',maxtime,'value',mintime,'callback',@curtime_callback,'parent',h.plotctrlpanel); - temp=get(h.sliders.CurTime,'Max')-get(h.sliders.CurTime,'Min'); - set(h.sliders.CurTime,'SliderStep',[1.0/temp 5.0/temp]); - h.edits.CurTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders dxy dedits hslider],'String',get(h.sliders.CurTime,'value'),... - 'BackgroundColor','white','callback',@curtime_callback,'parent',h.plotctrlpanel); - - %Slider: MaxTime - h.labels.MaxTime=uicontrol(gcf,'style','text','position',[dxy 2*dxy+hslider dlabels hslider],'String','Max. time t[s] to display:','parent',h.plotctrlpanel,'HorizontalAlignment','left'); - h.sliders.MaxTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 2*dxy+hslider dsliders hslider],... - 'min',mintime_log,'max',maxtime_log,'value',maxtime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - h.edits.MaxTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 2*dxy+hslider dedits hslider],'String',get(h.sliders.MaxTime,'value'),... - 'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - - %Slider: MinTime - h.labels.MinTime=uicontrol(gcf,'style','text','position',[dxy 3*dxy+2*hslider dlabels hslider],'String','Min. time t[s] to dispay :','parent',h.plotctrlpanel,'HorizontalAlignment','left'); - h.sliders.MinTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 3*dxy+2*hslider dsliders hslider],... - 'min',mintime_log,'max',maxtime_log,'value',mintime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - h.edits.MinTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 3*dxy+2*hslider dedits hslider],'String',get(h.sliders.MinTime,'value'),... - 'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - - %%Current data/state GUI-elements (Multiline-edit-box) - h.edits.AircraftState=uicontrol(gcf,'style','edit','Units','normalized','position',[.02 .02 0.96 0.96],'Min',1,'Max',10,'String','This shows the current aircraft state',... - 'HorizontalAlignment','left','parent',h.aircraftstatepanel); - - h.labels.GUIState=uicontrol(gcf,'style','text','Units','pixels','position',[dxy dxy width-4*dxy hslider],'String','Current state of this GUI',... - 'HorizontalAlignment','left','parent',h.guistatepanel); - -end - -%% ************************************************************************ -% INITPLOTGUI (nested function) -% ************************************************************************ -function InitPlotGUI() - - % Setup handles to lines and text - h.markertext=[]; - templinehandle=0.0;%line([0 1],[0 5]); % Just a temporary handle to init array - h.markerline(1:NrAxes)=templinehandle; % the actual handle-array to the lines - these are numbered consecutively - h.markerline(1:NrAxes)=0.0; - - % Setup all other figures and axes for plotting - % PLOT WINDOW 1: GPS POSITION - h.figures(2)=figure('units','normalized','Toolbar','figure', 'Name', 'GPS Position'); - h.axes(1)=axes(); - set(h.axes(1),'Parent',h.figures(2)); - - % PLOT WINDOW 2: IMU, baro altitude - h.figures(3)=figure('Name', 'IMU / Baro Altitude'); - h.axes(2)=subplot(4,1,1); - h.axes(3)=subplot(4,1,2); - h.axes(4)=subplot(4,1,3); - h.axes(5)=subplot(4,1,4); - set(h.axes(2:5),'Parent',h.figures(3)); - - % PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,... - h.figures(4)=figure('Name', 'Attitude Estimate / Actuators / Airspeeds'); - h.axes(6)=subplot(4,1,1); - h.axes(7)=subplot(4,1,2); - h.axes(8)=subplot(4,1,3); - h.axes(9)=subplot(4,1,4); - set(h.axes(6:9),'Parent',h.figures(4)); - - % PLOT WINDOW 4: LOG STATS - h.figures(5) = figure('Name', 'Log Statistics'); - h.axes(10)=subplot(1,1,1); - set(h.axes(10:10),'Parent',h.figures(5)); - -end - -%% ************************************************************************ -% DRAWRAWDATA (nested function) -% ************************************************************************ -%Draws the raw data from the sysvector, but does not add any -%marker-lines or so -function DrawRawData() - % ************************************************************************ - % PLOT WINDOW 1: GPS POSITION & GUI - % ************************************************************************ - figure(h.figures(2)); - % Only plot GPS data if available - if (sum(double(sysvector.gps_raw_position(imintime:imaxtime,1)))>0) && (bDisplayGPS) - %Draw data - plot3(h.axes(1),double(sysvector.gps_raw_position(imintime:imaxtime,1))*fconv_gpslatlong, ... - double(sysvector.gps_raw_position(imintime:imaxtime,2))*fconv_gpslatlong, ... - double(sysvector.gps_raw_position(imintime:imaxtime,3))*fconv_gpsalt,'r.'); - title(h.axes(1),'GPS Position Data(if available)'); - xlabel(h.axes(1),'Latitude [deg]'); - ylabel(h.axes(1),'Longitude [deg]'); - zlabel(h.axes(1),'Altitude above MSL [m]'); - grid on - - %Reset path - h.pathpoints=0; - end - - % ************************************************************************ - % PLOT WINDOW 2: IMU, baro altitude - % ************************************************************************ - figure(h.figures(3)); - plot(h.axes(2),time(imintime:imaxtime),sysvector.mag(imintime:imaxtime,:)); - title(h.axes(2),'Magnetometers [Gauss]'); - legend(h.axes(2),'x','y','z'); - plot(h.axes(3),time(imintime:imaxtime),sysvector.accel(imintime:imaxtime,:)); - title(h.axes(3),'Accelerometers [m/s²]'); - legend(h.axes(3),'x','y','z'); - plot(h.axes(4),time(imintime:imaxtime),sysvector.gyro(imintime:imaxtime,:)); - title(h.axes(4),'Gyroscopes [rad/s]'); - legend(h.axes(4),'x','y','z'); - plot(h.axes(5),time(imintime:imaxtime),sysvector.baro_alt(imintime:imaxtime),'color','blue'); - if(bDisplayGPS) - hold on; - plot(h.axes(5),time(imintime:imaxtime),double(sysvector.gps_raw_position(imintime:imaxtime,3)).*fconv_gpsalt,'color','red'); - hold off - legend('Barometric Altitude [m]','GPS Altitude [m]'); - else - legend('Barometric Altitude [m]'); - end - title(h.axes(5),'Altitude above MSL [m]'); - - % ************************************************************************ - % PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,... - % ************************************************************************ - figure(h.figures(4)); - %Attitude Estimate - plot(h.axes(6),time(imintime:imaxtime), sysvector.attitude(imintime:imaxtime,:).*180./3.14159); - title(h.axes(6),'Estimated attitude [deg]'); - legend(h.axes(6),'roll','pitch','yaw'); - %Actuator Controls - plot(h.axes(7),time(imintime:imaxtime), sysvector.actuator_control(imintime:imaxtime,:)); - title(h.axes(7),'Actuator control [-]'); - legend(h.axes(7),'0','1','2','3'); - %Actuator Controls - plot(h.axes(8),time(imintime:imaxtime), sysvector.actuators(imintime:imaxtime,1:8)); - title(h.axes(8),'Actuator PWM (raw-)outputs [µs]'); - legend(h.axes(8),'CH1','CH2','CH3','CH4','CH5','CH6','CH7','CH8'); - set(h.axes(8), 'YLim',[800 2200]); - %Airspeeds - plot(h.axes(9),time(imintime:imaxtime), sysvector.ind_airspeed(imintime:imaxtime)); - hold on - plot(h.axes(9),time(imintime:imaxtime), sysvector.true_airspeed(imintime:imaxtime)); - hold off - %add GPS total airspeed here - title(h.axes(9),'Airspeed [m/s]'); - legend(h.axes(9),'Indicated Airspeed (IAS)','True Airspeed (TAS)','GPS Airspeed'); - %calculate time differences and plot them - intervals = zeros(0,imaxtime - imintime); - for k = imintime+1:imaxtime - intervals(k) = time(k) - time(k-1); - end - plot(h.axes(10), time(imintime:imaxtime), intervals); - - %Set same timescale for all plots - for i=2:NrAxes - set(h.axes(i),'XLim',[mintime maxtime]); - end - - set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]); -end - -%% ************************************************************************ -% DRAWCURRENTAIRCRAFTSTATE(nested function) -% ************************************************************************ -function DrawCurrentAircraftState() - %find current data index - i=find(time>=CurTime,1,'first'); - - %********************************************************************** - % Current aircraft state label update - %********************************************************************** - acstate{1,:}=[sprintf('%s \t\t','GPS Pos:'),'[lat=',num2str(double(sysvector.gps_raw_position(i,1))*fconv_gpslatlong),'°, ',... - 'lon=',num2str(double(sysvector.gps_raw_position(i,2))*fconv_gpslatlong),'°, ',... - 'alt=',num2str(double(sysvector.gps_raw_position(i,3))*fconv_gpsalt),'m]']; - acstate{2,:}=[sprintf('%s \t\t','Mags[gauss]'),'[x=',num2str(sysvector.mag(i,1)),... - ', y=',num2str(sysvector.mag(i,2)),... - ', z=',num2str(sysvector.mag(i,3)),']']; - acstate{3,:}=[sprintf('%s \t\t','Accels[m/s²]'),'[x=',num2str(sysvector.accel(i,1)),... - ', y=',num2str(sysvector.accel(i,2)),... - ', z=',num2str(sysvector.accel(i,3)),']']; - acstate{4,:}=[sprintf('%s \t\t','Gyros[rad/s]'),'[x=',num2str(sysvector.gyro(i,1)),... - ', y=',num2str(sysvector.gyro(i,2)),... - ', z=',num2str(sysvector.gyro(i,3)),']']; - acstate{5,:}=[sprintf('%s \t\t','Altitude[m]'),'[Barometric: ',num2str(sysvector.baro_alt(i)),'m, GPS: ',num2str(double(sysvector.gps_raw_position(i,3))*fconv_gpsalt),'m]']; - acstate{6,:}=[sprintf('%s \t','Est. attitude[deg]:'),'[Roll=',num2str(sysvector.attitude(i,1).*180./3.14159),... - ', Pitch=',num2str(sysvector.attitude(i,2).*180./3.14159),... - ', Yaw=',num2str(sysvector.attitude(i,3).*180./3.14159),']']; - acstate{7,:}=sprintf('%s \t[','Actuator Ctrls [-]:'); - for j=1:4 - acstate{7,:}=[acstate{7,:},num2str(sysvector.actuator_control(i,j)),',']; - end - acstate{7,:}=[acstate{7,:},']']; - acstate{8,:}=sprintf('%s \t[','Actuator Outputs [PWM/µs]:'); - for j=1:8 - acstate{8,:}=[acstate{8,:},num2str(sysvector.actuators(i,j)),',']; - end - acstate{8,:}=[acstate{8,:},']']; - acstate{9,:}=[sprintf('%s \t','Airspeed[m/s]:'),'[IAS: ',num2str(sysvector.ind_airspeed(i)),', TAS: ',num2str(sysvector.true_airspeed(i)),']']; - - set(h.edits.AircraftState,'String',acstate); - - %********************************************************************** - % GPS Plot Update - %********************************************************************** - %Plot traveled path, and and time. - figure(h.figures(2)); - hold on; - if(CurTime>mintime+1) %the +1 is only a small bugfix - h.pathline=plot3(h.axes(1),double(sysvector.gps_raw_position(imintime:i,1))*fconv_gpslatlong, ... - double(sysvector.gps_raw_position(imintime:i,2))*fconv_gpslatlong, ... - double(sysvector.gps_raw_position(imintime:i,3))*fconv_gpsalt,'b','LineWidth',2); - end; - hold off - %Plot current position - newpoint=[double(sysvector.gps_raw_position(i,1))*fconv_gpslatlong double(sysvector.gps_raw_position(i,2))*fconv_gpslatlong double(sysvector.gps_raw_position(i,3))*fconv_gpsalt]; - if(numel(h.pathpoints)<=3) %empty path - h.pathpoints(1,1:3)=newpoint; - else %Not empty, append new point - h.pathpoints(size(h.pathpoints,1)+1,:)=newpoint; - end - axes(h.axes(1)); - line(h.pathpoints(:,1),h.pathpoints(:,2),h.pathpoints(:,3),'LineStyle','none','Marker','.','MarkerEdge','black','MarkerSize',20); - - - % Plot current time (small label next to current gps position) - textdesc=strcat(' t=',num2str(time(i)),'s'); - if(isvalidhandle(h.markertext)) - delete(h.markertext); %delete old text - end - h.markertext=text(double(sysvector.gps_raw_position(i,1))*fconv_gpslatlong,double(sysvector.gps_raw_position(i,2))*fconv_gpslatlong,... - double(sysvector.gps_raw_position(i,3))*fconv_gpsalt,textdesc); - set(h.edits.CurTime,'String',CurTime); - - %********************************************************************** - % Plot the lines showing the current time in the 2-d plots - %********************************************************************** - for i=2:NrAxes - if(isvalidhandle(h.markerline(i))) delete(h.markerline(i)); end - ylims=get(h.axes(i),'YLim'); - h.markerline(i)=line([CurTime CurTime] ,get(h.axes(i),'YLim'),'Color','black'); - set(h.markerline(i),'parent',h.axes(i)); - end - - set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]); -end - -%% ************************************************************************ -% MINMAXTIME CALLBACK (nested function) -% ************************************************************************ -function minmaxtime_callback(hObj,event) %#ok - new_mintime=get(h.sliders.MinTime,'Value'); - new_maxtime=get(h.sliders.MaxTime,'Value'); - - %Safety checks: - bErr=false; - %1: mintime must be < maxtime - if((new_mintime>maxtime) || (new_maxtimeCurTime) - set(h.labels.GUIState,'String','Error: Mintime cannot be bigger than CurTime! CurTime set to new mintime.','BackgroundColor','red'); - mintime=new_mintime; - CurTime=mintime; - bErr=true; - end - %3: MaxTime must be >CurTime - if(new_maxtime - %find current time - if(hObj==h.sliders.CurTime) - CurTime=get(h.sliders.CurTime,'Value'); - elseif (hObj==h.edits.CurTime) - temp=str2num(get(h.edits.CurTime,'String')); - if(tempmintime) - CurTime=temp; - else - %Error - set(h.labels.GUIState,'String','Error: You tried to set an invalid current time! Previous value restored.','BackgroundColor','red'); - end - else - %Error - set(h.labels.GUIState,'String','Error: curtime_callback','BackgroundColor','red'); - end - - set(h.sliders.CurTime,'Value',CurTime); - set(h.edits.CurTime,'String',num2str(CurTime)); - - %Redraw time markers, but don't have to redraw the whole raw data - DrawCurrentAircraftState(); -end - -%% ************************************************************************ -% FINDMINMAXINDICES (nested function) -% ************************************************************************ -function [idxmin,idxmax] = FindMinMaxTimeIndices() - for i=1:size(sysvector.timestamp,1) - if time(i)>=mintime; idxmin=i; break; end - end - for i=1:size(sysvector.timestamp,1) - if maxtime==0; idxmax=size(sysvector.timestamp,1); break; end - if time(i)>=maxtime; idxmax=i; break; end - end - mintime=time(idxmin); - maxtime=time(idxmax); -end - -%% ************************************************************************ -% ISVALIDHANDLE (nested function) -% ************************************************************************ -function isvalid = isvalidhandle(handle) - if(exist(varname(handle))>0 && length(ishandle(handle))>0) - if(ishandle(handle)>0) - if(handle>0.0) - isvalid=true; - return; - end - end - end - isvalid=false; -end - -%% ************************************************************************ -% JUST SOME SMALL HELPER FUNCTIONS (nested function) -% ************************************************************************ -function out = varname(var) - out = inputname(1); -end - -%This is the end of the matlab file / the main function -end diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 3713e0b306..0da8ec568e 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -604,6 +604,15 @@ int sdlog2_thread_main(int argc, char *argv[]) errx(1, "unable to create logging folder, exiting."); } + const char *converter_in = "/etc/logging/log_converter.zip"; + char* converter_out = malloc(200); + sprintf(converter_out, "%s/log_converter.zip", folder_path); + + if (file_copy(converter_in, converter_out)) { + errx(1, "unable to copy conversion scripts, exiting."); + } + free(converter_out); + /* only print logging path, important to find log file later */ warnx("logging to directory: %s", folder_path); From 53b373dd829baec5858212ab966cb4f74d219b59 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 13 Aug 2013 08:50:40 +0200 Subject: [PATCH 60/80] Minor fixes to log conversion scripts --- Tools/logconv.m | 4 ++-- Tools/sdlog2_dump.py | 1 - 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/Tools/logconv.m b/Tools/logconv.m index f2ae6e5f37..c416b8095e 100644 --- a/Tools/logconv.m +++ b/Tools/logconv.m @@ -111,9 +111,9 @@ function ImportPX4LogData() time_us = sysvector.TIME_StartTime(end) - sysvector.TIME_StartTime(1); time_s = uint64(time_us*1e-6); time_m = uint64(time_s/60); - time_s = time_s - time_m * 60 + time_s = time_s - time_m * 60; - disp([sprintf('Flight log duration: %d:%d (minutes:seconds)', time_m, time_s)]); + disp([sprintf('Flight log duration: %d:%d (minutes:seconds)', time_m, time_s) char(10)]); disp(['logfile conversion finished.' char(10)]); else diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index a376e03d39..7fefc5908f 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -200,7 +200,6 @@ class SDLog2Parser: else: data = struct.unpack(self.MSG_FORMAT_STRUCT, str(self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN])) msg_type = data[0] - print(msg_type) if msg_type != self.MSG_TYPE_FORMAT: msg_length = data[1] if runningPython3: From 8c1f7a3706a15b5df2749f8ea076e457cd796f5f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 13 Aug 2013 08:52:03 +0200 Subject: [PATCH 61/80] Hotfix: Updated log converter --- ROMFS/px4fmu_common/logging/log_converter.zip | Bin 10090 -> 10087 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/ROMFS/px4fmu_common/logging/log_converter.zip b/ROMFS/px4fmu_common/logging/log_converter.zip index 2641e671068b1ea6867fc6b9fef17ba3889e5262..7cb837e5666f51eca7ed803dfef4581f01bec1f3 100644 GIT binary patch delta 7944 zcmZXZRZ|>*vM?79L4pJi4vYKZ?gV!yKp?m~K^Auj4vV|HYj9ZHo#5{7aO<4=^2t=q z+sqH>?qkIRMX<6Q9Q;=R0PqQbEsiFR)f#N*iV6U*u>%0;fNub2QyY78c0*HFTL)$b zPYrcs032`{Syf~aS=H481poto2Lk~7_rFuu$9|Oy`=kB+YehiLeVIr2s`*mDFOii3 zz1pI2$Zb#7KuFGTVx>kAsFQ~?#OL84ra&el4?Jf|41|vv-+A*8Ah`(M{gjLnMgv0sg9RjP}Oo@s(nG8HK>?rOh zvJ$SgP?Bn0q`4X-I#YNS*^5`S9{|Gg;AUFxEp(356 zG-7~k%l4jKbwmRd@#P^8%|_2A?!7s_OpR2Zi=wu1h1wnx0DjGc22;ORuPf6v| zqK(GuXLiD*x1&bJ>eI^<22@YQFseuXqvMvv)L_Jy}gX(Y&#|TYmCD`r}8w*^ds7A0$3%zBe7W z>cuA?23ez7-`-cn72`V=FF-HZRs$V+7pYNOvo!V`QZ!vf9h-@G=pzud1@sZ6jO&EJ zcn8_-oR0m(MReIQy4t{A9t7Y9b>|+{RCM4yQL)d?Zsc46dU2>UaIX*yNmR(SQsvsy zR~RYkVDo&Or7*m$8Y0cO4h_6UDSn+PdL0lBB%^PJc@VMS>N0Q0i|iRJvQ?`J;Q8L8 zB6>0|)}#pyp+H{2Flcf@BJc}TZqkR zX?xc_V7u!G@@0Bi>!6z*sO3{3!wkE^RF&pm=1~1vC&?Dn;N!r5xHxpR5)1D_2-H^l zlqDa3a)SVW5Gjih(a6?;6-Jc$Z#;WtxB7>)b-6wgu~s5KHLwXClQFy?wfbbPUAsqN zmW2z~VQ(1S+tBIzur&%*^{7OVJE(zbB{ZR0KumZKgPzUCjB1c68Tc!BU82Dzoe7`G zVy^;<(E{@#aVEK3#gx9P)CpQVv* z2s1u!%JvTqxLlzg%zB?0W#%&c*3!a~_bg&g_zRB*UZ3hklALL-NuX|U3d6dK3jz@r zJ~RKOs8$=!a3gnUoW+}(dksO5rhaAELby_Xwp8`jLqi2j_1ZY1Ib z*V07*Y^<(csJ@R~-Ew!EF+G_K;~ujK(zsbCY>XhYMb38}7usG?j0?7QD@z#tUd~d& z5zNLr8k7O>c5iA1+|`ibPWF&uwmXY)s)VkYYRhTbT%L z@2xT(k%psS%J^0f6H_d0K%%^=9d)}DfAVP*tN>$~V3ttTf;HBTi=EdMKCdZI=pEHx(w|=~H_7s~7`)-#XQLhe7WM z@oBTLn#If|!gQLu{~q80#8gwNM*r$5Oo*Kz=O7;`-Nwn{Ub_*jWn2^ol+ zrpG&de%jb^q}Ep)1C@FB`K1$JT_ka7=kxB#@*M#Kd`ul)fgJTMgn@Wm<@^HuSj=4MRB%L`lGfrZop< z2Mn4?QOPEBg-T*txW@Z>nh^t|Q(mUpv#g=J7Q7@U9cZ_|c-~o{M-GwcguB*T7-dSM zd9?PHOQF3k+w3Dq!07Qg5031J^SLAp1~KyJTO0iyrEoltOK9t}x~=+rbQP!WqP6z? zb@X{VtCAk!8R4()9U+#<<`eJ|{NS=I|g#x2-xgh0GC8G~ns~#9t;m!D3ec&-W z{yWMq)0s8)Xb^NPnRJ6j&+gZcZ)YVY|HMaUjfQ7YGFYY4n7ps481tz-+0(?V<6}FY zau1kMb_sHN-cQL-j~z5?g)fY=lRY8oCX>y7)^N|W7B|u-Hqr+=gElBxIGPG2f1&^Q zWs7Y)p@SJ)$p<8RK5hoX0d3WallD}uM5_sNIp*`-G_-N}-3f`geW!g5T(Mgde8pvD z40gI!M35`QfcOph!`nD0Pig0m%cNPg59+)zpNlJ;y~V>>B!X4*UA0AW`>@mZL8QLX z4++TCjg%WQLF&{X0`1@nHhxyfqo|9fM4}(EI-Q_jDK+_toH_VZ_6yn2@8Z>&FrCK` zoae!%t_4f`XQ~$6(geG6lkIS`diiw${OrjrrY8O)c*CB%A#raB)IRqw*QuMSGDB_I zj}lLkujIr%LWfdk_OH23Oz+AlVZsofdP675L#7*f6pZSB!hh8dDH}p)d`=1*mxXeU zV>#R^bLnLb*u%kX*DW|PT~jqs;!+Nr*l;D(4Ra_ay$DW=$YV5nv6cXG7hq*2pf`fT4K>x zf2-ahMzg{Vclk2RGPV94%Z{qP5Lt6-H*89HqPYngd}0kq;!;sq?AG$b=*}P#ku=U_ zu~pKG_B9EnS0?GRV|~-V;18l>@0{(5&rQy+If_UHBwle1o@iccL&UMGESc1~_XU+H z4sckgB#PiKd{=I)b0nsqZBcvd0G;7IEA)9cqu>Fn$e}R~!Muh#@WC|&27}Yv^R|G9 z{p0=Zwl|x3NMBsWyA~dwgT8J2K2@qlvQw-C_MFA+3<14U00|fsF#UMHO+KD zB!<=$M@D1n7aC4)T?ikWm=-l|rxNuQweQ}d=H=!vYjmA1YM@SU0EqIQ5w33m3yRr%eV$8Osfc zHh}5q0D4#bMrMLzPTPSUNr8*XLuB?gS3>NZT*IwTr>*TzkOEIJnAHp&_?Ui~wgrrh ztZ#Q7R|`BIT=VXq0%CX8;Ynf|{|Rc>{$s~v^W=XG%(37ui3+R~Cn~yg55QY2{8?PJ z*W3&>XVt%_*@r3O?LJ@^gbsx~>LZdpae>9XnVplo=P|Nv%McAuqah_Wr#xh12m2OG zf7wz3uViu8qdlkffCvFxjrIpeUY_eeUb`~eEX}9yi1~InGvDhT=I3wjp*UxZ=&55q`_ zqlxp_CgXVraIRw?;9noI3r z^*)m^pSY_{kI`gr*DV6D&6DASS!Cu(AUl?~s3Xg@aC};M(PTeVYU}GU1ql?}Z93ai zjlF@ojXc|kc`Ly@oQO|V;!J6~6TpBHF9=Sq6=BXCD3#RI*u74dmFMbJ{5L zB|$l9yi;cp@j7z=OYksGv_Wzb!yi#nH~+>vKt(@FmaOs|9iwm$IMF!+X0ePN@B!d+ zGg(&)Dg^5+;F2$q<@ndBqA)${X#zEkW<~XhO9_pHTbliQe?`GE!jG_v=gOw2f5JDa zTfj`s8%Z1}2|Ja+^v;u)RVfHMWliLowmz4zA8%wu;!s!Z^?Zf*4q|L}y0kj$jvO`k zuDeb@+4`A*y=Y|tXaH^aoR=!KAYsSQ&_c}25(RE8d+ebsWMU-^ICb5pXF5e8<3~5L z{~;qM$>hm;SG^h`FB_0qc0GMpVb9uZ=We9ruGx_CGyO&cOVf_qEqAo7M-rb!OjfOA z0CQMPjOR2pUbhlg?+Zc)vLsG8->*VAk*rEJ99_nEU9|Nkd)J-vymx{oj$@lJz1D9S z5&>Yf_61xs<$pPv8q7uuvYgeJ7+*zRPnqR026Obg1EeZ_{Sx9ReI1E!(ja>V`h$w! ztC~!!q%^Z?Qv${?624jC%Q2KnJ`(e^T(WYky4vDtJ^EUz+;hs(N|mPxj3JS zaaH9{4RZ`=K0+3$9+0J&*Ss%g;s4}O)>QzO@e0^Cnh_`!JdK$m%T<|i>Xn&ptieJ? z{wL~gjI4;MFQ5FhD@--IA?~ePz(gZgu)JOz?h^T8DH*il#2%yzrtXsg-TZsk!m&cY$8lrx(CrE2tj{XYcEKv2`3QbI?^^JDrrT$_)0j zg8UuFzGh9!%JVb_L*V*#p<^QQeN)YHzvooCdo^sN30bCKOekr zx;&AhZ`<~3cO@!*;nr*ikVNN^M*+s~DU?_e4taX_Fm0!391oNg4 z0@H!q+Z@eWrxRym9Uo+te#=s&4(rj<9ohZ4H!TfVfP+nO87R8z_ZpMW=dDhtK(_J4 zKF)tnye2VP-I-x|O`ek!n66g}-p@C^F-By8oaM{gHOz>*##2^u9mxaVp!1fow}T1q zlIAmN-;4QMkL5%1uV5z2Vzz#OL0zYJibJ(*k>yE-&RQ51rtZW0Y)NCkm)u|uhs zE7z}$mJ_can%HLN>pM5auH^}6b33o+nr}K3+IN;AV3TmOg~Xoa0^9+Eykh7Z9urNc zTHDE5IQ-d~qtKW^$81GtX=rt?i>p&iD2w?c^%p1}yD;xByh(Zj*WKSx1zaVZ4;mOF z-Se=%9J=E72Y>PjIneCUOioR!V88inHsM}a33P0u&|P`k>ROGjOOREWd{Z1RWVR() z))yc0H9c6vAk~ad#eM@THg|j0jhA3(-}h;F?u-#dwel_o*6|$A<4SkZCyl)P4({*} z9hqsBDqZ-#m@t92Ar8`w{{83{S#n?xjXi$1F{=1|3{#?^s&g-;Di zdf@X+r&2fCn=hk66jpxFB0=jgK}^efl6Uc4J4FrJzk6?**0TXeNc?rZkauDe8k#K$ z7e$$bUhuD)g&O6~}zLq3N4l#g^K6?j#P zYa3t|xbdF1V=L@T^H)=TuD>TwGmTUL`@jAPB6HkI^>6RRo)${;of6-O4esH>tBG;~ zj~NN{{GW8XgO-?$X$aVFz@FZr^~$0FqD=y$VF4Iczm~iH zv?TfbHo?p3{~jG3EVN>G0FKaj&$alq(PEo=#v?*&3oo1=@0-D*B{AcW^I*2Sa*sYR zV3(q4#E5eHlDA=A%3a!N(^0yJuG=_hymM$<)C4yZL5AFMLN=Q(b1Z;<`dhR}mGnNLMH?xl1F4yek%b}?w-W>f$s9%a9al4_l$GPLwvZ=6j zd*TnA;&G`Mkv(k-W%#d;Y{Syjo&s zw&n;FtQ*dOap99q-Z$9~-`kkYI_u0(A*<+M0 zTi;u8r|65xyQNdponGqngQXt+^wihogtP)he3l*|3drI<|8dGIm z29fR`BLXS&K>eB!&wW!;iJRRKp_2Wl6q~wOrxZx&K8OUVY=`WxLY$|1`4s_!Jk>t?|gRIFU_KRRT*dqGg7_p@ERg24sLUXWDs~(dcUb5x_sfShb zjSK@bm}V=H;=&fCKT6WG-b5vY;x@qIbkopxVWk7=$CLCik|Xgst^VnXiZ;4a#PS?L z)|y2b{Q-8*f<-yz0T#S>XBR&1mqK1^U$0OVhHFVXQo$sVx=bWak5TLq2VMB5Dv-I> zxNAhWlk@W%tK+L0665`mT8cK5IDfPJ;CfZ=tM}%Sdl6bL4lb((p?CePB}Uzx8}44h zz$fb;`#lpcwAWRCut>Z-=DUZG3@SEH`VEceyoi|h7sT5_B8I>u4HqR@y*mPw>}7YNEPZ- z65AD+Br2I{UAg|ooFbpUwopGMFj9t?&8IM=C4-As7oxzK6ilN-27B(Gl?BJ?VK~EA_{Z;1ETk@}nUkF#7X8S?t2{92hx4 z`Y41lbC!|)@$cyU?jUn)(qpi&1psz7ndmdW0;qhRIsl&949rtQ2uyY z6F*=gbdMIAqpfx=V*hdb zU2HF{6TvP9*cXDSwr+P9(@$H2Xlju`<7`GDUbK%@Nw6{0Z zGIZj^_E3_b66Rxbh`lt#sU#*8>yuWgx18e9shsBai;({67eDM%IYTxYu@N<)4xj?! z|2H(fJU0;Ai^eiZS}AiTLH-*3k4fg7y5t;q!z`^IE+Ibnrzp+Vq@&hyH=}Y~ey?cZ zYhuO(-i!&Py-jw~L#GbgG>bTLsrxX{c$U{MOq350(jS9Yw;;_w2a+jsH?jo-i z`U#s4_PaA27mVDu%f5d6F#SoAndKhba=$g``cWt{akH3cKMm{krqI|@@Vcp*lJuvl ztGb!iaSPY0v8$I41Zu@#70BbDSze@65ev68&Uy&wt+_0aX4EYqGe58Ydpt-3hm~@A z0S1(>q`@sfLMYpiQ_eq&*;k!^45;%`k_%G4Ze`a(*Vf4C>h+4lmFCBWN~$qS?vqsd zAn#hCe3?~FU+iGCiq>ixGP^!q4}TlhLUt!Hcqf(g_sb~uc~bCk#)Fcu8)ET6XEu$J zfI%S5b$mF{bDt&(D#*+KAoCo|`%G_D(NUdW+oWKQ$vB#v{Y^G|O|CE`UNA>|Mqp<` zGX3A8^%2*~gtELe!uC#@=pk=uNKk5+aDO#`HsHlvclED+G>xeMeD+Uo7)6AqCH}vs z(Rthk9}+iP0iN?=+R~4|^v#-?%!v^ja>-HJUVod6oz#7tpp+oJ2@g%7HoK8r@`ryc ze<* delta 7942 zcmZXZRa2Y|pri+P2?Pl4?l!o)JA`1t9fDin#Vt6&!{F|c!5xAJ3liKRID`AC?_BKG z)^=6jb^m~V`au0i9ne%kKzt7ZflxuKB3Lp-{OfVPm>`f64+w+}A_I9?Il0>Mm|1x_ zf8qGzr>BbsLP#7$(|-JgrtRg60fIxkfdhg5x8Ftb;<^Hb9X!^3CP4gYFr>2DZH|$S zQmoca;J93^M0ra{8cL%BHMLfri_)=NdV4)nj4ftT2GkZTq&JsD*Dud}J2~CXFI&6} zzXs&gyE3n&d^M=y1(OWPL8+y17xhf0si;O7reb4v<@#AZSZk$i@=aa+K2lQ$iLrUp zP3l|85wrKla*UoP7{A^=D=Cf9gKX$nNB-?0p{c-NM-sH~Q-?CdwTBJHdcQH!CEc>m zM-nd_0rc;0YA)DNjQjli20E2&hMeL;q*tr(dHdK6@b30eS&sdWX-~i1D}Wae&gCGq zV1E`|!h;nQ(`gKZ!xgOf%Qd!-9mmpDSKGDH8OEKcA^k2wcsvw~Z)9gjH9%vJt!64i z9xBN{WUdvZ8d6H)C5iGvFIL%pfW!>a;la*;0{P&A=-MXF7>tm@LxwtUE7DSac9Uzt z)#4>qF_fJF0T#=D2~Kt~{+wD1JY`z&a~Z|Udw&?IjbfEZdSjHbF55s9DWWBeie`c?ivD3H6-T52 zdRhu;8e=ACmfWv-wf`7nBwquiu_egGMZyo}x43O9%86B$j#5^pd8vF&{&>pHrQG(K zMSw`-3;Ebo+`Vp*oz8gJls`p3aISX-Jg9uRdA#$;e0rI|;T1<;#tIUb5EB6?JB0v@ zB-@%T+R(UMD2naZizuL?&)|IB?1w3Ul2OJ92=%0UcE9x@o0;^yUBF2AueOJ-V22&B zj)Rgi29vitnDOu3-5!Zus+fQm^`f^5?}?6^gwYS;fiSS8=eFYr2DaZ;aJ7)tY4Gy| zwS)*2S`;1jh$FV&Y49K!o(NT(jO0DXAv;Ql3t9b!(1{46X>qvl4+@H`qzpiriBvjG z6TEATW-YUxDfnz3!s&mvgM z&HfY?)L-;!JEIMFt@*eC9|HgvDV0xu@h=Z_QK7}wgT#+loNz0SKghT8W!tNa_7K}v zXmhxHl2rzbE@;)=@vLySY3^{PKaSq0IZ4AKa&&*v(WZ&7?qvc=NkL%0Ojg2Oj|KNT zd^^HM^xki|h{E-|e<)Jy=V~0??8K~^W=J-O1{6O{QIr$In?t0k%M=0Gl;-4__CmHA zfeBn^92tVGoVDKIV7?E`B$yzdochqPFE?}Ft7bj46wZDrm8%`3X_e6$$_&Tl zihpN_l5^MmS*CEKfL{`ATc$`>kZp`j#>*FPQ>o`Mz{1egM5do2*_MC%T z9^anybt3kp;};f518pZ`)eOki*Z(56hq3GPX>_HcIvLsjn*ZEsskru&OtsxPG%vc_ zW0Nm))QL?O;=~raZqcdCj!`RDCekU*X;q$E$m1QqgMIW>ivgT05G>Ml!1^A6u-&tN zsWF)qI#i@FB3sbdE1GY;Q+#Z^MhN{^>VK$8ZPL5>BLyoD7h(c?KY3hSgU{Y+cYApg zMel?i)LJ?@KXxhHmlm{wl(4eVMbu*(x4Y#?$TdC?=rX5046?e2vGYFu<=OoG?nfy} zw^5OPvSQAFoe9vC*xI5ayOo`LwCg^bjd7%Eu9m<<%_!N;ddi;kutf3`LF)J}{`PVh z1EyQQBb_0YkA%m=f30~Yz!&*4jQArFdbP#T?Ga*Th7{2_AsYF2jc`+gF9zSQ=TD41m3^0H?eUQ7f4HY*p=O@0D#2?087I&E?Yr zPcXTb_z?>>Y<(hEFZq<4QpVmDk^NaYu159CcX~)c6RI!a8Ht&YJSb4}|7;^DzYkXe z6M$3@Tef)@!u3sK&pAu0SN}tYF%5;W=j7IX)Z_V-Q1V?I+r%(D%hiyXkW=P7*<5Xa z3`i;3^R2!DPiJi1_t2FM(7HGzokxUKh_iny>?|>-M4yWpXQIsH0~cPJbHqaa?BTLX z_r+g38SiMs5cyt=HazM&>(0m5^8c(|tgqZ774tFoHX=DCvF_aw=bTDBUZRVeKez@A z`+u1*Fc$U-aVt7GRKn1`Y!h_a)da0fgL$s$cW`f*DtiYFt_0gp!nhsNr z|84{DRRkTTM%-9cC>75LWeO$Y@+v<7><~U3d4@^$ImOh$QqNR&-fux)^Vr(cfaFWP z1YsMAW@jv{zw?rEUs#$VG$7&D-{~|MbUvuT8U!S+SNB3sut*N4C_-zqq3ADuIFHQ} zbHyY9-EyPO4=!!55J5mAHh{ZF!PLe{<=dEX=h$-T%C%WCg^`!4$RB3$F+!WmPT_Khl^BMxb_t=n zT@R?FRM^v55bAClBr1`vm=R{n2W_Ki%G|RR$2$poO)@YxMPwE$_o)%cR{iz->#}YEHTygycpv2RV%yB;2 zAHM$zJy?Pi;{$TF66)Kut4!UgNvC0!G~{PN+xUA#mr(h({n+~^mO5lVE4Za9dWYkmgF7MZVld~l z5<);&#SYE0^_Q~;tluU|Ldz!YL zN#0JF#?J3QO7E`v(Yl{Kc+@4LI!5PH?3;a&X^aZ0`*ctb>wKK8N(mj?6jLHH2=*9K zI=%k|btRNSYhh^=cI`shCQ7IP)Z?c0V${xcl)lE8 zJ$Mm1F%g$)>8nWcC&lF$au0;dQ$&>-ZgzvgU+gEm7;6H2CcTCyTZOj^eh-#kp_4d; zJfv=rvFNV`f}f`nh-$D23I$~v!p$*_gh~D|lu0hdG9vRFOQnb6Z0lni%aDh)Hbgv) z{8^&f-*0*We6MbluEIl|=9*B+Vv;>;sJr!qjxM)ryy^w!7ZLl0FMq@5*wpyo=~uU? z%A&eP0iWNWBB#04d)W;%zp7tsx9cAM`T26o{eX#;@q#AQ%ZGAdT*`R4gbNu5(XHE{ zPFdID)sgf!sm=F(>(atci^oR^epofG*%R1z=QbS$3Ol$tgU5>{drNO?!~)IgM80hd z=m=b}wRRiXc0!u=`F!^NunS?-o_+tfVzq$jC8NF(-}Kg9P4k_eM{Y0Yt8_NG3HsBBpnI00b3o{W2WMTsXp@GOiPOi3=t}fmjn9lz@ zYM63Rv@wU9&M{|@0RL6??*8&7(fEbuI4w+8b(?}RUPry`pDMiC$YsKqsy&lo^|Aen zUPHjkm{&?FCb$wM%|s|4@omB^yD3{buH-C@)C-&*8*-XM%7rVL!<53%`xAqM4pk68 zjZKkB)41}sI|TDF_3R55G1gSY)!pg}iia>3mkz{5p_WA*h%e|m)_kHDYKWQs2icb{ zZ|sF2YzLl?fW`NA-H)N1f3no6OS^Bd>bVa72t|n<5i?|qiAsN#Rc7Uq(&rl}Im`6U z$;Wp=giLlUKeCTxFW4pic-%?;fOzvYgVD0=a6bqh&iS_4nVUM-71rnHi za6Y*b?lvrdl*#xPQ?GPB8}Iu{Po;=pI0i@Z5avo%!?@UynD>2*V|nl8lt-{-?D4zy z)vp(fF+8|r=;?n9YxF9NxU-_vEns)HuBH{w*T7V(>S-)1otTW9+zzh|_p)=p}wj^q=CN&Pfq$%c$_(T>WN*_Luz+5r!&~T&K8>6Y44AIdS2JH$7 z>lM(`RLoC1Kj{l}vmE7_ixi1Rwx*54Nzt_ejgHRd$a`20dVBCTHM&eaLJ6P=z2QZIda*q~7HZ-Sv3f~9`!@#*} zFj@3=i#X39)O$O(_EVPg&E_v5e?G%L{mA$;Ean5FZw>@>{i&KxTh1DIYzzx7J5q@S zni=h|OUF`|2hLEj@JQ&{8ROoYV6Y}9ZIXKurEk9P8?wsMc$H~<78@*+TXt`h&0Y)4 zR%~g_)0Zu0XOt?F4bo<_omyIuu68O z`&rdjGO#CnSZ0i>8m*<&nPYShG%dUuPN+ zpxRUWSG*d$WK#n^N>QI)Wkzmb3v}3RZA5c%d2-Sr%F4KGqY~M8V`5M&t&RNCxj|l zW7DF1DI$@%h&{7v&uF~L4})U|K;Bc>+?MUET`Eq7rMnQ>T|;>W_Cb!DAf=6AX3TM@ zob32$J2T6cl&BVyae=G$$#d^4;QZ!4mlmCPaCW~S!3nFJO4G)$)zM4NKBcGBJQ+< zCi1k+D5K0PB{VM=^JZN$8kC96l4?8>D>$sMH2RyIE87ylr<8)y5wZcok( zj5sYGuzI!MQIsRTvsrO-z==@hbc#-j)WKQk=5NGbt32S=>GI)BuoZX&X67o>!e*Sv zGS$twDTQ)>e(=ZfG9ST%>!SMIWbT{=+j`sI~qrKVB$^(o1DLL0g=Ici#3-xOeU=99Y6kG%|`-@|+ z7oY0FwZCtSGqxRUU_^FNsmpSHOaR+PVpb_5EWjz*QHA7tvjlp z$Vv)57A19B;)f1IPAckkezHQk!2gV=zka;yoT3?$W>A&#;aPIc%#ZIPf!NA_mUrgC zt%(;md+}*S-nD@lz3fm7#XC6`ZBO}X9*fJkdag{ zy-cvQ59#;@5yam)IlR*1$doXO3hXK7{+dPpxM6(wO`@?qIo`!A*6YbgzJ;kN8&^jX zFLW@%68Q{$O6tk#Q3@wef)IJdxR+<_g*)sL^{t!P(5eL;NL}NOqp^}{`On){Et+VU z2sGZDg#lihZ$1=%YjUk92^pRSiVg@1NS_F($({(xo^em{;x4d!usV+a%-N!}RRy-D zo)mp;v}7CZ>bpnox^!x)WI>*qS)JAW9kVp-?p;*kSY$7(bS8(y5@ZQ=6NY$&uXsR?yGFU5|INJZ> zShQmGFCr*?-!^A*(Q{z)`!`GJIR^@S`@7L_PsSpTP&(-i`I_6xkRwWd&1@c{;OL1b zOh=xYrt~tlu^fwUJe}EpTqDgjH~M5}>a^<3nm+gF_XR~EJ&_Zf_!!r39QV^)$rEOc zPZ0sdm{PhwwqRV1}gR>9^P@k1gZ6GFcFU;gQUN6 z9xNzpmAPK1syCVTBp}IKd4Q4jP6?%wzoTN_s%>P&zf)d7W|^gRYI-fOXE3!R%uzTQ zpjTzs1e3OgxLA6HX^&H;tbSxsr9w;4RNw+!t?Ow6pJSHi>=fHJhz+=G(W8}p7*9CX z&K@Q|T4Sw&r5_JTYBXbc_mQVA8*P`;_hUt5umvl8+T+V~dP3%oGLC1i42zW!%@93R zv4M!%?bj;#!G@)t=+Egr`u7C}ot3aE2g`xJq(vNFLpmQM+9lWnGAc=6;1KFSkMN-RiNZ|G*E`~&t^^+D63 z!Za0T!sEQ9|Jn_Tv|PF1{+=fY+v2Ng-3EPPW_%;2?~e1p7@SK|&c6>Yd7xT|8Lx_5 zJLEpT%NEp}>-`jZfYON2&iR}*oEZr4Bu+;#Zut}Xc?aYg2psag&1kN?RSXUHsfa%W zT--^<;7K_nA^M;T*D+V(*JcN8I*-m;7dL*s2et~HYS7q`{Lg-XJZv|_;KX}6E#XP@ zO7LtzWT7}(tN5yp``o9}X7_VQ8uFkGiejNA7-O1pL1Rr}%CK`%wlf)oh|IRyo7s`339}-(-?&f zVZei-;}rwKw(cuy7#_3L@BQJ_e7;-wk~Siynl4G9RgCXNU6MlU7~g@#4tg+xY2;w{ zB)E;{Q*i-P6BO6n#uc+d^2fFugHeFWrKkI1N?1u;Sgc#`;H3t6{Zg5Ri3Pn+TxcC+ z+?7-7BBX313mmThu~*mrVp6?KYD9a*@Vf>fZM9z(ipY7g%gFGjS3qiNYxXXyecG(G51Dy)UdF@4GgJ_?&~Klv6t-cpYk*%R81$t>wm8y9mwqH_e0634x=d zcusfC7>>a#AG0P*86i)xEo4D5wO!)lP>)gkx@S*LinOQ){HVQ(%?lql{wiLffHngw zn07%MOx6o~$yiAx*-kKqpGYDR`V;mL7Nlj9wt$I851i5A#*_E$A4}bz^K0>LZPNA> zwkG;#`?evHCxIZoR>4w_5_z*-hd3Owq9N4V39&I4DFY11!lrd#L4fh-vFNBjfgdoc-nU_=FM65D*f7J4K zas_e#*n5!Qa%|}eEYpphTmHRTpgUJAjDyS8Over4M91CDd!w^PYw#%)*H%(7>juFI za|C$CTYNsmhG=&U88mSamPWZ6dm(~*k~L1SYVPi9QBQ0okKs3FlBvTOz_gyAjOj*K_M_v9u|!>2#!dczmwNXVw@zL< zGW;=$_JhDh@WT)m+NwoecNugI?y|^DEp($NS!JrTX?5E63GNIL*MQKgc6*KOpI!+r zXSC-hUuZrRl`EPVq&a4HNh#S6*HT;QZ}RB+-Gut6W(^^ZsgQCKj~-ufmsz{_^X7v3 z&ZU#voFVXK%!0A?&?jIg&z1%#T{wYzFEd2>vXyN|H%vAj;$Nh8W$VYup-W0&Nc!-% zV(e+8j^0UoQkc30QUQo530Z82rGA;Y@Oq4+abCPvdk?PP?}h}oVmWRhHTHcU8$o+F zBIo=#z&oZ3JXd(EOS~)*|A5>DK}0V-u^=NV3@(Q_M(kYECqHw2+7E!ks`3U{cfzk_ zaIRcEn^BNEQ=mI%8j134Ft*ZFoCuM#zgb<$ik*lIH#tFcqAha4K`{xQ1#-w=@R#A>?M*Q!LH@`bE81)y6X%6WE94}9<2rWR)$;F8uW+Phv~>jwnLao zJa^srs~KlL#q}GJ%m(JNU++2HD-o;b^Bbs%nNA8G>;HMCQ+*hi;1dT^3mC|G|9`Uc r0ra2XKp;?YNG~Sn|8O2>JzXTwf0!rrl0g`bEtQRtAK9GYzwrM6ALT|e From b6676f6cb8306fb99274f8e0a784d8846928d920 Mon Sep 17 00:00:00 2001 From: px4dev Date: Mon, 12 Aug 2013 23:54:35 -0700 Subject: [PATCH 62/80] NuttX is confused when it doesn't know what board it's building for - since we don't tell it in the config anymore, we need to pass it a hint. --- Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Makefile b/Makefile index dc69b0ae8b..778395cee9 100644 --- a/Makefile +++ b/Makefile @@ -151,7 +151,7 @@ $(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC) $(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(board) .) $(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration)) @$(ECHO) %% Exporting NuttX for $(board) - $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) export + $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) CONFIG_ARCH_BOARD=$(board) export $(Q) mkdir -p $(dir $@) $(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@ $(Q) (cd $(NUTTX_SRC)/configs && $(RMDIR) $(board)) From cd928b64f38100e91b7ee927a4b37dc58078a844 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 13 Aug 2013 09:10:47 +0200 Subject: [PATCH 63/80] Fixed log conversion scripts copy operation. Each log comes now with the required conversion tools. Eats up only 10 KB flash for the good cause. --- .../logging/{log_converter.zip => conv.zip} | Bin src/modules/sdlog2/sdlog2.c | 8 ++++---- 2 files changed, 4 insertions(+), 4 deletions(-) rename ROMFS/px4fmu_common/logging/{log_converter.zip => conv.zip} (100%) diff --git a/ROMFS/px4fmu_common/logging/log_converter.zip b/ROMFS/px4fmu_common/logging/conv.zip similarity index 100% rename from ROMFS/px4fmu_common/logging/log_converter.zip rename to ROMFS/px4fmu_common/logging/conv.zip diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 0da8ec568e..ba7cdd91cf 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -604,9 +604,9 @@ int sdlog2_thread_main(int argc, char *argv[]) errx(1, "unable to create logging folder, exiting."); } - const char *converter_in = "/etc/logging/log_converter.zip"; - char* converter_out = malloc(200); - sprintf(converter_out, "%s/log_converter.zip", folder_path); + const char *converter_in = "/etc/logging/conv.zip"; + char* converter_out = malloc(150); + sprintf(converter_out, "%s/conv.zip", folder_path); if (file_copy(converter_in, converter_out)) { errx(1, "unable to copy conversion scripts, exiting."); @@ -1265,7 +1265,7 @@ int file_copy(const char *file_old, const char *file_new) fclose(source); fclose(target); - return ret; + return OK; } void handle_command(struct vehicle_command_s *cmd) From 56d355414cbfef92b39af6830932e7f1487b03b9 Mon Sep 17 00:00:00 2001 From: px4dev Date: Tue, 13 Aug 2013 00:34:11 -0700 Subject: [PATCH 64/80] Fix handling of board config files. Treat CONFIG_BOARD like CONFIG_ARCH in the toolchain configuration. --- makefiles/firmware.mk | 5 +---- makefiles/module.mk | 3 ++- makefiles/toolchain_gnu-arm-eabi.mk | 7 +++++++ 3 files changed, 10 insertions(+), 5 deletions(-) diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk index 0d742c37dc..ecff77db9a 100644 --- a/makefiles/firmware.mk +++ b/makefiles/firmware.mk @@ -153,11 +153,8 @@ ifeq ($(BOARD_FILE),) $(error Config $(CONFIG) references board $(BOARD), but no board definition file found) endif export BOARD +export BOARD_FILE include $(BOARD_FILE) -ifeq ($(CONFIG_BOARD),) -$(error Board config for $(BOARD) does not define CONFIG_BOARD) -endif -EXTRADEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) $(info % BOARD = $(BOARD)) # diff --git a/makefiles/module.mk b/makefiles/module.mk index 9e4cbafc9c..9c1a828cc2 100644 --- a/makefiles/module.mk +++ b/makefiles/module.mk @@ -98,6 +98,7 @@ # # CONFIG # BOARD +# BOARD_FILE # MODULE_WORK_DIR # MODULE_OBJ # MODULE_MK @@ -117,7 +118,7 @@ $(info %% MODULE_MK = $(MODULE_MK)) # # Get the board/toolchain config # -include $(PX4_MK_DIR)/board_$(BOARD).mk +include $(BOARD_FILE) # # Get the module's config diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index 3f4d3371ac..9fd2dd516d 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -85,6 +85,13 @@ ifeq ($(ARCHCPUFLAGS),) $(error Must set CONFIG_ARCH to one of CORTEXM4F, CORTEXM4 or CORTEXM3) endif +# Set the board flags +# +ifeq ($(CONFIG_BOARD),) +$(error Board config does not define CONFIG_BOARD) +endif +ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) + # optimisation flags # ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ From de749a3602423f5ee6ca56f3cf2dfff04e31ec6d Mon Sep 17 00:00:00 2001 From: px4dev Date: Tue, 13 Aug 2013 00:34:41 -0700 Subject: [PATCH 65/80] Stop expecting CONFIG_HRT_anything since we aren't baking it into the NuttX config anymore. --- nuttx-configs/px4fmu-v1/include/board.h | 12 ++++------- nuttx-configs/px4io-v1/include/board.h | 12 ++++------- nuttx-configs/px4io-v1/nsh/defconfig | 22 --------------------- src/drivers/stm32/drv_hrt.c | 20 +++++++++---------- src/drivers/stm32/tone_alarm/tone_alarm.cpp | 4 ---- src/systemcmds/tests/test_hrt.c | 2 +- 6 files changed, 19 insertions(+), 53 deletions(-) diff --git a/nuttx-configs/px4fmu-v1/include/board.h b/nuttx-configs/px4fmu-v1/include/board.h index 5529d50972..839631b3a2 100644 --- a/nuttx-configs/px4fmu-v1/include/board.h +++ b/nuttx-configs/px4fmu-v1/include/board.h @@ -158,10 +158,8 @@ /* High-resolution timer */ -#ifdef CONFIG_HRT_TIMER -# define HRT_TIMER 1 /* use timer1 for the HRT */ -# define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */ -#endif +#define HRT_TIMER 1 /* use timer1 for the HRT */ +#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */ /* LED definitions ******************************************************************/ /* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any @@ -241,10 +239,8 @@ * * PPM input is handled by the HRT timer. */ -#if defined(CONFIG_HRT_TIMER) && defined (CONFIG_HRT_PPM) -# define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */ -# define GPIO_PPM_IN (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10) -#endif +#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */ +#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10) /* * CAN diff --git a/nuttx-configs/px4io-v1/include/board.h b/nuttx-configs/px4io-v1/include/board.h index 668602ea89..6503a94cd0 100755 --- a/nuttx-configs/px4io-v1/include/board.h +++ b/nuttx-configs/px4io-v1/include/board.h @@ -118,10 +118,8 @@ /* * High-resolution timer */ -#ifdef CONFIG_HRT_TIMER -# define HRT_TIMER 1 /* use timer1 for the HRT */ -# define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */ -#endif +#define HRT_TIMER 1 /* use timer1 for the HRT */ +#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */ /* * PPM @@ -130,10 +128,8 @@ * * Pin is PA8, timer 1, channel 1 */ -#if defined(CONFIG_HRT_TIMER) && defined (CONFIG_HRT_PPM) -# define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */ -# define GPIO_PPM_IN GPIO_TIM1_CH1IN -#endif +#define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */ +#define GPIO_PPM_IN GPIO_TIM1_CH1IN /************************************************************************************ * Public Data diff --git a/nuttx-configs/px4io-v1/nsh/defconfig b/nuttx-configs/px4io-v1/nsh/defconfig index 5256722333..3785e03678 100755 --- a/nuttx-configs/px4io-v1/nsh/defconfig +++ b/nuttx-configs/px4io-v1/nsh/defconfig @@ -200,28 +200,6 @@ SERIAL_HAVE_CONSOLE_DMA=y CONFIG_USART2_RXDMA=n CONFIG_USART3_RXDMA=y -# -# PX4IO specific driver settings -# -# CONFIG_HRT_TIMER -# Enables the high-resolution timer. The board definition must -# set HRT_TIMER and HRT_TIMER_CHANNEL to the timer and capture/ -# compare channels to be used. -# CONFIG_HRT_PPM -# Enables R/C PPM input using the HRT. The board definition must -# set HRT_PPM_CHANNEL to the timer capture/compare channel to be -# used, and define GPIO_PPM_IN to configure the appropriate timer -# GPIO. -# CONFIG_PWM_SERVO -# Enables the PWM servo driver. The driver configuration must be -# supplied by the board support at initialisation time. -# Note that USART2 must be disabled on the PX4 board for this to -# be available. -# -# -CONFIG_HRT_TIMER=y -CONFIG_HRT_PPM=y - # # General build options # diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c index 7ef3db970e..83a1a1abbb 100644 --- a/src/drivers/stm32/drv_hrt.c +++ b/src/drivers/stm32/drv_hrt.c @@ -70,7 +70,7 @@ #include "stm32_gpio.h" #include "stm32_tim.h" -#ifdef CONFIG_HRT_TIMER +#ifdef HRT_TIMER /* HRT configuration */ #if HRT_TIMER == 1 @@ -155,7 +155,7 @@ # error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=11 # endif #else -# error HRT_TIMER must be set in board.h if CONFIG_HRT_TIMER=y +# error HRT_TIMER must be a value between 1 and 11 #endif /* @@ -275,7 +275,7 @@ static void hrt_call_invoke(void); /* * Specific registers and bits used by PPM sub-functions */ -#ifdef CONFIG_HRT_PPM +#ifdef HRT_PPM_CHANNEL /* * If the timer hardware doesn't support GTIM_CCER_CCxNP, then we will work around it. * @@ -326,7 +326,7 @@ static void hrt_call_invoke(void); # define CCER_PPM (GTIM_CCER_CC4E | GTIM_CCER_CC4P | GTIM_CCER_CC4NP) /* CC4, both edges */ # define CCER_PPM_FLIP GTIM_CCER_CC4P # else -# error HRT_PPM_CHANNEL must be a value between 1 and 4 if CONFIG_HRT_PPM is set +# error HRT_PPM_CHANNEL must be a value between 1 and 4 # endif /* @@ -377,7 +377,7 @@ static void hrt_ppm_decode(uint32_t status); # define CCMR1_PPM 0 # define CCMR2_PPM 0 # define CCER_PPM 0 -#endif /* CONFIG_HRT_PPM */ +#endif /* HRT_PPM_CHANNEL */ /* * Initialise the timer we are going to use. @@ -424,7 +424,7 @@ hrt_tim_init(void) up_enable_irq(HRT_TIMER_VECTOR); } -#ifdef CONFIG_HRT_PPM +#ifdef HRT_PPM_CHANNEL /* * Handle the PPM decoder state machine. */ @@ -526,7 +526,7 @@ error: ppm_decoded_channels = 0; } -#endif /* CONFIG_HRT_PPM */ +#endif /* HRT_PPM_CHANNEL */ /* * Handle the compare interupt by calling the callout dispatcher @@ -546,7 +546,7 @@ hrt_tim_isr(int irq, void *context) /* ack the interrupts we just read */ rSR = ~status; -#ifdef CONFIG_HRT_PPM +#ifdef HRT_PPM_CHANNEL /* was this a PPM edge? */ if (status & (SR_INT_PPM | SR_OVF_PPM)) { @@ -686,7 +686,7 @@ hrt_init(void) sq_init(&callout_queue); hrt_tim_init(); -#ifdef CONFIG_HRT_PPM +#ifdef HRT_PPM_CHANNEL /* configure the PPM input pin */ stm32_configgpio(GPIO_PPM_IN); #endif @@ -907,4 +907,4 @@ hrt_latency_update(void) } -#endif /* CONFIG_HRT_TIMER */ +#endif /* HRT_TIMER */ diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp index 167ef30a8e..2284be84de 100644 --- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp +++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp @@ -117,10 +117,6 @@ #include -#ifndef CONFIG_HRT_TIMER -# error This driver requires CONFIG_HRT_TIMER -#endif - /* Tone alarm configuration */ #if TONE_ALARM_TIMER == 2 # define TONE_ALARM_BASE STM32_TIM2_BASE diff --git a/src/systemcmds/tests/test_hrt.c b/src/systemcmds/tests/test_hrt.c index f21dd115b4..f6e540401f 100644 --- a/src/systemcmds/tests/test_hrt.c +++ b/src/systemcmds/tests/test_hrt.c @@ -94,7 +94,7 @@ extern uint16_t ppm_pulse_history[]; int test_ppm(int argc, char *argv[]) { -#ifdef CONFIG_HRT_PPM +#ifdef HRT_PPM_CHANNEL unsigned i; printf("channels: %u\n", ppm_decoded_channels); From 50e3bb28c90bb2cb93f9f0a549cf9c4838973e1c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 14 Aug 2013 14:56:27 +0200 Subject: [PATCH 66/80] Fixed power attribute on FMU, contributed by Tridge --- nuttx-configs/px4fmu-v1/nsh/defconfig | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig index d338161296..9f088c37a2 100644 --- a/nuttx-configs/px4fmu-v1/nsh/defconfig +++ b/nuttx-configs/px4fmu-v1/nsh/defconfig @@ -534,9 +534,10 @@ CONFIG_USBDEV=y # # CONFIG_USBDEV_ISOCHRONOUS is not set # CONFIG_USBDEV_DUALSPEED is not set -CONFIG_USBDEV_SELFPOWERED=y -# CONFIG_USBDEV_BUSPOWERED is not set +# CONFIG_USBDEV_SELFPOWERED is not set +CONFIG_USBDEV_BUSPOWERED=y CONFIG_USBDEV_MAXPOWER=500 +# CONFIG_USBDEV_REMOTEWAKEUP is not set # CONFIG_USBDEV_DMA is not set # CONFIG_USBDEV_TRACE is not set From 3a21cacdbbf507f47a45035af7fda04ac787f9b0 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 14 Aug 2013 16:00:35 +0200 Subject: [PATCH 67/80] Fix bug where IO was in override mode for copter (workaround was to disconnect and reconnect Rx --- src/modules/px4iofirmware/controls.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c index 43d96fb067..fbd82a4c6d 100644 --- a/src/modules/px4iofirmware/controls.c +++ b/src/modules/px4iofirmware/controls.c @@ -300,6 +300,8 @@ controls_tick() { } else { r_status_flags &= ~PX4IO_P_STATUS_FLAGS_OVERRIDE; } + } else { + r_status_flags &= ~PX4IO_P_STATUS_FLAGS_OVERRIDE; } } From 75e56285901cdb95f0ebbad62d841fbe9d38c1a1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 15 Aug 2013 12:52:07 +0200 Subject: [PATCH 68/80] Fixed Doxygen --- Documentation/Doxyfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Documentation/Doxyfile b/Documentation/Doxyfile index 4802ef8189..fd997baaa0 100644 --- a/Documentation/Doxyfile +++ b/Documentation/Doxyfile @@ -569,7 +569,7 @@ WARN_LOGFILE = doxy.log # directories like "/usr/src/myproject". Separate the files or directories # with spaces. -INPUT = ../apps +INPUT = ../src # This tag can be used to specify the character encoding of the source files # that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is From a1e0581facd28c8c3f2797e72f810a6674216aa5 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 15 Aug 2013 12:55:16 +0200 Subject: [PATCH 69/80] Hotfix: More Doxygen fixes --- .gitignore | 4 +++- Documentation/Doxyfile | 4 +--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.gitignore b/.gitignore index 0372b60c80..6ae5baeccb 100644 --- a/.gitignore +++ b/.gitignore @@ -24,4 +24,6 @@ Firmware.sublime-workspace Images/*.bin Images/*.px4 mavlink/include/mavlink/v0.9/ -NuttX \ No newline at end of file +/NuttX +/Documentation/doxy.log +/Documentation/html/ \ No newline at end of file diff --git a/Documentation/Doxyfile b/Documentation/Doxyfile index fd997baaa0..f45fe8b211 100644 --- a/Documentation/Doxyfile +++ b/Documentation/Doxyfile @@ -599,9 +599,7 @@ RECURSIVE = YES # excluded from the INPUT source files. This way you can easily exclude a # subdirectory from a directory tree whose root is specified with the INPUT tag. -EXCLUDE = ../dist/ \ - ../docs/html/ \ - html +EXCLUDE = ../src/mathlib/CMSIS # The EXCLUDE_SYMLINKS tag can be used select whether or not files or # directories that are symbolic links (a Unix filesystem feature) are excluded From ca877e0bc480e6f28e58a492a64b99a8afe59a21 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 15 Aug 2013 13:00:42 +0200 Subject: [PATCH 70/80] Fixed file exclude --- Documentation/Doxyfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Documentation/Doxyfile b/Documentation/Doxyfile index f45fe8b211..6283cfc9c5 100644 --- a/Documentation/Doxyfile +++ b/Documentation/Doxyfile @@ -599,7 +599,7 @@ RECURSIVE = YES # excluded from the INPUT source files. This way you can easily exclude a # subdirectory from a directory tree whose root is specified with the INPUT tag. -EXCLUDE = ../src/mathlib/CMSIS +EXCLUDE = ../src/modules/mathlib/CMSIS # The EXCLUDE_SYMLINKS tag can be used select whether or not files or # directories that are symbolic links (a Unix filesystem feature) are excluded From 74d519d9d0560cd0f54ba2667c8c198d1c933fe3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 15 Aug 2013 13:38:59 +0200 Subject: [PATCH 71/80] Hotfix: Fixed Doxygen tags for uORB topics --- .gitignore | 3 ++- src/modules/uORB/objects_common.cpp | 4 ++++ src/modules/uORB/topics/actuator_controls.h | 9 +++++++++ src/modules/uORB/topics/actuator_controls_effective.h | 9 +++++++++ src/modules/uORB/topics/actuator_outputs.h | 9 +++++++++ src/modules/uORB/topics/debug_key_value.h | 1 + src/modules/uORB/topics/esc_status.h | 11 ++++++----- src/modules/uORB/topics/mission.h | 10 +++++----- src/modules/uORB/topics/offboard_control_setpoint.h | 10 +++++----- src/modules/uORB/topics/omnidirectional_flow.h | 1 + src/modules/uORB/topics/parameter_update.h | 9 +++++++++ src/modules/uORB/topics/rc_channels.h | 10 +++++----- src/modules/uORB/topics/sensor_combined.h | 10 +++++----- src/modules/uORB/topics/subsystem_info.h | 8 ++++---- src/modules/uORB/topics/telemetry_status.h | 9 +++++++++ src/modules/uORB/topics/vehicle_attitude.h | 1 + src/modules/uORB/topics/vehicle_command.h | 9 ++++----- .../uORB/topics/vehicle_global_position_set_triplet.h | 4 ++-- src/modules/uORB/topics/vehicle_status.h | 8 ++++---- 19 files changed, 94 insertions(+), 41 deletions(-) diff --git a/.gitignore b/.gitignore index 6ae5baeccb..3fdc1bf2a2 100644 --- a/.gitignore +++ b/.gitignore @@ -26,4 +26,5 @@ Images/*.px4 mavlink/include/mavlink/v0.9/ /NuttX /Documentation/doxy.log -/Documentation/html/ \ No newline at end of file +/Documentation/html/ +/Documentation/doxygen*objdb*tmp \ No newline at end of file diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp index ae5fc6c61c..301cfa255f 100644 --- a/src/modules/uORB/objects_common.cpp +++ b/src/modules/uORB/objects_common.cpp @@ -37,6 +37,10 @@ * Common object definitions without a better home. */ +/** + * @defgroup topics List of all uORB topics. + */ + #include #include diff --git a/src/modules/uORB/topics/actuator_controls.h b/src/modules/uORB/topics/actuator_controls.h index b7c4196c0a..a27095be52 100644 --- a/src/modules/uORB/topics/actuator_controls.h +++ b/src/modules/uORB/topics/actuator_controls.h @@ -52,11 +52,20 @@ #define NUM_ACTUATOR_CONTROLS 8 #define NUM_ACTUATOR_CONTROL_GROUPS 4 /**< for sanity checking */ +/** + * @addtogroup topics + * @{ + */ + struct actuator_controls_s { uint64_t timestamp; float control[NUM_ACTUATOR_CONTROLS]; }; +/** + * @} + */ + /* actuator control sets; this list can be expanded as more controllers emerge */ ORB_DECLARE(actuator_controls_0); ORB_DECLARE(actuator_controls_1); diff --git a/src/modules/uORB/topics/actuator_controls_effective.h b/src/modules/uORB/topics/actuator_controls_effective.h index 088c4fc8fe..d7b404ad42 100644 --- a/src/modules/uORB/topics/actuator_controls_effective.h +++ b/src/modules/uORB/topics/actuator_controls_effective.h @@ -53,11 +53,20 @@ #define NUM_ACTUATOR_CONTROLS_EFFECTIVE NUM_ACTUATOR_CONTROLS #define NUM_ACTUATOR_CONTROL_GROUPS_EFFECTIVE NUM_ACTUATOR_CONTROL_GROUPS /**< for sanity checking */ +/** + * @addtogroup topics + * @{ + */ + struct actuator_controls_effective_s { uint64_t timestamp; float control_effective[NUM_ACTUATOR_CONTROLS_EFFECTIVE]; }; +/** + * @} + */ + /* actuator control sets; this list can be expanded as more controllers emerge */ ORB_DECLARE(actuator_controls_effective_0); ORB_DECLARE(actuator_controls_effective_1); diff --git a/src/modules/uORB/topics/actuator_outputs.h b/src/modules/uORB/topics/actuator_outputs.h index bbe4290731..30895ca83f 100644 --- a/src/modules/uORB/topics/actuator_outputs.h +++ b/src/modules/uORB/topics/actuator_outputs.h @@ -52,12 +52,21 @@ #define NUM_ACTUATOR_OUTPUTS 16 #define NUM_ACTUATOR_OUTPUT_GROUPS 4 /**< for sanity checking */ +/** + * @addtogroup topics + * @{ + */ + struct actuator_outputs_s { uint64_t timestamp; /**< output timestamp in us since system boot */ float output[NUM_ACTUATOR_OUTPUTS]; /**< output data, in natural output units */ int noutputs; /**< valid outputs */ }; +/** + * @} + */ + /* actuator output sets; this list can be expanded as more drivers emerge */ ORB_DECLARE(actuator_outputs_0); ORB_DECLARE(actuator_outputs_1); diff --git a/src/modules/uORB/topics/debug_key_value.h b/src/modules/uORB/topics/debug_key_value.h index a9d1b83fdc..9253c787db 100644 --- a/src/modules/uORB/topics/debug_key_value.h +++ b/src/modules/uORB/topics/debug_key_value.h @@ -47,6 +47,7 @@ /** * @addtogroup topics + * @{ */ /** diff --git a/src/modules/uORB/topics/esc_status.h b/src/modules/uORB/topics/esc_status.h index 00cf59b28f..11332d7a7a 100644 --- a/src/modules/uORB/topics/esc_status.h +++ b/src/modules/uORB/topics/esc_status.h @@ -51,10 +51,6 @@ #include #include "../uORB.h" -/** - * @addtogroup topics @{ - */ - /** * The number of ESCs supported. * Current (Q2/2013) we support 8 ESCs, @@ -76,7 +72,12 @@ enum ESC_CONNECTION_TYPE { }; /** - * + * @addtogroup topics + * @{ + */ + +/** + * Electronic speed controller status. */ struct esc_status_s { diff --git a/src/modules/uORB/topics/mission.h b/src/modules/uORB/topics/mission.h index 253f444b3f..978a3383a5 100644 --- a/src/modules/uORB/topics/mission.h +++ b/src/modules/uORB/topics/mission.h @@ -46,11 +46,6 @@ #include #include "../uORB.h" -/** - * @addtogroup topics - * @{ - */ - enum NAV_CMD { NAV_CMD_WAYPOINT = 0, NAV_CMD_LOITER_TURN_COUNT, @@ -61,6 +56,11 @@ enum NAV_CMD { NAV_CMD_TAKEOFF }; +/** + * @addtogroup topics + * @{ + */ + /** * Global position setpoint in WGS84 coordinates. * diff --git a/src/modules/uORB/topics/offboard_control_setpoint.h b/src/modules/uORB/topics/offboard_control_setpoint.h index 2e895c59c4..7901b930af 100644 --- a/src/modules/uORB/topics/offboard_control_setpoint.h +++ b/src/modules/uORB/topics/offboard_control_setpoint.h @@ -43,11 +43,6 @@ #include #include "../uORB.h" -/** - * @addtogroup topics - * @{ - */ - /** * Off-board control inputs. * @@ -66,6 +61,11 @@ enum OFFBOARD_CONTROL_MODE OFFBOARD_CONTROL_MODE_MULTIROTOR_SIMPLE = 7, /**< roll / pitch rotated aligned to the takeoff orientation, throttle stabilized, yaw pos */ }; +/** + * @addtogroup topics + * @{ + */ + struct offboard_control_setpoint_s { uint64_t timestamp; diff --git a/src/modules/uORB/topics/omnidirectional_flow.h b/src/modules/uORB/topics/omnidirectional_flow.h index 8f4be3b3fe..a6ad8a1315 100644 --- a/src/modules/uORB/topics/omnidirectional_flow.h +++ b/src/modules/uORB/topics/omnidirectional_flow.h @@ -46,6 +46,7 @@ /** * @addtogroup topics + * @{ */ /** diff --git a/src/modules/uORB/topics/parameter_update.h b/src/modules/uORB/topics/parameter_update.h index 300e895c7d..68964deb0a 100644 --- a/src/modules/uORB/topics/parameter_update.h +++ b/src/modules/uORB/topics/parameter_update.h @@ -42,11 +42,20 @@ #include #include "../uORB.h" +/** + * @addtogroup topics + * @{ + */ + struct parameter_update_s { /** time at which the latest parameter was updated */ uint64_t timestamp; }; +/** + * @} + */ + ORB_DECLARE(parameter_update); #endif \ No newline at end of file diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h index 9dd54df915..e69335b3d8 100644 --- a/src/modules/uORB/topics/rc_channels.h +++ b/src/modules/uORB/topics/rc_channels.h @@ -45,11 +45,6 @@ #include #include "../uORB.h" -/** - * @addtogroup topics - * @{ - */ - /** * The number of RC channel inputs supported. * Current (Q1/2013) radios support up to 18 channels, @@ -83,6 +78,11 @@ enum RC_CHANNELS_FUNCTION RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */ }; +/** + * @addtogroup topics + * @{ + */ + struct rc_channels_s { uint64_t timestamp; /**< In microseconds since boot time. */ diff --git a/src/modules/uORB/topics/sensor_combined.h b/src/modules/uORB/topics/sensor_combined.h index 9a76b51829..ad164555e2 100644 --- a/src/modules/uORB/topics/sensor_combined.h +++ b/src/modules/uORB/topics/sensor_combined.h @@ -46,17 +46,17 @@ #include #include "../uORB.h" -/** - * @addtogroup topics - * @{ - */ - enum MAGNETOMETER_MODE { MAGNETOMETER_MODE_NORMAL = 0, MAGNETOMETER_MODE_POSITIVE_BIAS, MAGNETOMETER_MODE_NEGATIVE_BIAS }; +/** + * @addtogroup topics + * @{ + */ + /** * Sensor readings in raw and SI-unit form. * diff --git a/src/modules/uORB/topics/subsystem_info.h b/src/modules/uORB/topics/subsystem_info.h index c415e832e0..cfe0bf69e9 100644 --- a/src/modules/uORB/topics/subsystem_info.h +++ b/src/modules/uORB/topics/subsystem_info.h @@ -50,10 +50,6 @@ #include #include "../uORB.h" -/** - * @addtogroup topics - */ - enum SUBSYSTEM_TYPE { SUBSYSTEM_TYPE_GYRO = 1, @@ -75,6 +71,10 @@ enum SUBSYSTEM_TYPE SUBSYSTEM_TYPE_RANGEFINDER = 131072 }; +/** + * @addtogroup topics + */ + /** * State of individual sub systems */ diff --git a/src/modules/uORB/topics/telemetry_status.h b/src/modules/uORB/topics/telemetry_status.h index f30852de5b..828fb31cc7 100644 --- a/src/modules/uORB/topics/telemetry_status.h +++ b/src/modules/uORB/topics/telemetry_status.h @@ -50,6 +50,11 @@ enum TELEMETRY_STATUS_RADIO_TYPE { TELEMETRY_STATUS_RADIO_TYPE_WIRE }; +/** + * @addtogroup topics + * @{ + */ + struct telemetry_status_s { uint64_t timestamp; enum TELEMETRY_STATUS_RADIO_TYPE type; /**< type of the radio hardware */ @@ -62,6 +67,10 @@ struct telemetry_status_s { uint8_t txbuf; /**< how full the tx buffer is as a percentage */ }; +/** + * @} + */ + ORB_DECLARE(telemetry_status); #endif /* TOPIC_TELEMETRY_STATUS_H */ \ No newline at end of file diff --git a/src/modules/uORB/topics/vehicle_attitude.h b/src/modules/uORB/topics/vehicle_attitude.h index c31c81d0ce..4380a5ee77 100755 --- a/src/modules/uORB/topics/vehicle_attitude.h +++ b/src/modules/uORB/topics/vehicle_attitude.h @@ -48,6 +48,7 @@ /** * @addtogroup topics + * @{ */ /** diff --git a/src/modules/uORB/topics/vehicle_command.h b/src/modules/uORB/topics/vehicle_command.h index fac571659d..31ff014de9 100644 --- a/src/modules/uORB/topics/vehicle_command.h +++ b/src/modules/uORB/topics/vehicle_command.h @@ -45,11 +45,6 @@ #include #include "../uORB.h" -/** - * @addtogroup topics - * @{ - */ - /** * Commands for commander app. * @@ -110,6 +105,10 @@ enum VEHICLE_CMD_RESULT VEHICLE_CMD_RESULT_ENUM_END=5, /* | */ }; +/** + * @addtogroup topics + * @{ + */ struct vehicle_command_s { diff --git a/src/modules/uORB/topics/vehicle_global_position_set_triplet.h b/src/modules/uORB/topics/vehicle_global_position_set_triplet.h index 318abba89f..8516b263fc 100644 --- a/src/modules/uORB/topics/vehicle_global_position_set_triplet.h +++ b/src/modules/uORB/topics/vehicle_global_position_set_triplet.h @@ -60,8 +60,8 @@ */ struct vehicle_global_position_set_triplet_s { - bool previous_valid; - bool next_valid; + bool previous_valid; /**< flag indicating previous position is valid */ + bool next_valid; /**< flag indicating next position is valid */ struct vehicle_global_position_setpoint_s previous; struct vehicle_global_position_setpoint_s current; diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h index c7c1048f60..94068a9acc 100644 --- a/src/modules/uORB/topics/vehicle_status.h +++ b/src/modules/uORB/topics/vehicle_status.h @@ -54,10 +54,6 @@ #include #include "../uORB.h" -/** - * @addtogroup topics @{ - */ - /* State Machine */ typedef enum { @@ -137,6 +133,10 @@ enum VEHICLE_BATTERY_WARNING { VEHICLE_BATTERY_WARNING_ALERT /**< aleting of low voltage 2. stage */ }; +/** + * @addtogroup topics + * @{ + */ /** * state machine / state of vehicle. From b83d07e94a0db879ff59a45f69450152ae330150 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 15 Aug 2013 13:47:36 +0200 Subject: [PATCH 72/80] Hotfix: Excluding codegen code --- Documentation/Doxyfile | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Documentation/Doxyfile b/Documentation/Doxyfile index 6283cfc9c5..65274d4a4f 100644 --- a/Documentation/Doxyfile +++ b/Documentation/Doxyfile @@ -599,7 +599,8 @@ RECURSIVE = YES # excluded from the INPUT source files. This way you can easily exclude a # subdirectory from a directory tree whose root is specified with the INPUT tag. -EXCLUDE = ../src/modules/mathlib/CMSIS +EXCLUDE = ../src/modules/mathlib/CMSIS \ + ../src/modules/attitude_estimator_ekf/codegen # The EXCLUDE_SYMLINKS tag can be used select whether or not files or # directories that are symbolic links (a Unix filesystem feature) are excluded From ab80b0e273d5b2d795c8b5f470f773052cbaeedb Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Thu, 15 Aug 2013 19:51:36 -0400 Subject: [PATCH 73/80] Doxygenate and style dsm.c One file a day... this'll take a while! --- src/modules/px4iofirmware/dsm.c | 412 +++++++++++++++++++------------- 1 file changed, 243 insertions(+), 169 deletions(-) diff --git a/src/modules/px4iofirmware/dsm.c b/src/modules/px4iofirmware/dsm.c index b2c0db4254..e014b0a519 100644 --- a/src/modules/px4iofirmware/dsm.c +++ b/src/modules/px4iofirmware/dsm.c @@ -48,158 +48,55 @@ #include -#define DEBUG - #include "px4io.h" +//! The DSM dsm frame size in bytes #define DSM_FRAME_SIZE 16 +//! Maximum supported DSM channels #define DSM_FRAME_CHANNELS 7 -static int dsm_fd = -1; - -static hrt_abstime last_rx_time; -static hrt_abstime last_frame_time; - -static uint8_t frame[DSM_FRAME_SIZE]; - -static unsigned partial_frame_count; -static unsigned channel_shift; - +//! File handle to the DSM UART +int dsm_fd = -1; +//! Timestamp when we last received +hrt_abstime dsm_last_rx_time; +//! Timestamp for start of last dsm_frame +hrt_abstime dsm_last_frame_time; +//! DSM dsm_frame receive buffer +uint8_t dsm_frame[DSM_FRAME_SIZE]; +//! Count of bytes received for current dsm_frame +unsigned dsm_partial_frame_count; +//! Channel resolution, 0=unknown, 1=10 bit, 2=11 bit +unsigned dsm_channel_shift; +//! Count of incomplete DSM frames unsigned dsm_frame_drops; -static bool dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value); -static void dsm_guess_format(bool reset); -static bool dsm_decode(hrt_abstime now, uint16_t *values, uint16_t *num_values); - -int -dsm_init(const char *device) -{ - if (dsm_fd < 0) - dsm_fd = open(device, O_RDONLY | O_NONBLOCK); - - if (dsm_fd >= 0) { - struct termios t; - - /* 115200bps, no parity, one stop bit */ - tcgetattr(dsm_fd, &t); - cfsetspeed(&t, 115200); - t.c_cflag &= ~(CSTOPB | PARENB); - tcsetattr(dsm_fd, TCSANOW, &t); - - /* initialise the decoder */ - partial_frame_count = 0; - last_rx_time = hrt_absolute_time(); - - /* reset the format detector */ - dsm_guess_format(true); - - debug("DSM: ready"); - - } else { - debug("DSM: open failed"); - } - - return dsm_fd; -} - -void -dsm_bind(uint16_t cmd, int pulses) -{ - const uint32_t usart1RxAsOutp = GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN10; - - if (dsm_fd < 0) - return; - - switch (cmd) { - case dsm_bind_power_down: - // power down DSM satellite - POWER_RELAY1(0); - break; - case dsm_bind_power_up: - POWER_RELAY1(1); - dsm_guess_format(true); - break; - case dsm_bind_set_rx_out: - stm32_configgpio(usart1RxAsOutp); - break; - case dsm_bind_send_pulses: - for (int i = 0; i < pulses; i++) { - stm32_gpiowrite(usart1RxAsOutp, false); - up_udelay(25); - stm32_gpiowrite(usart1RxAsOutp, true); - up_udelay(25); - } - break; - case dsm_bind_reinit_uart: - // Restore USART rx pin - stm32_configgpio(GPIO_USART1_RX); - break; - } -} - -bool -dsm_input(uint16_t *values, uint16_t *num_values) -{ - ssize_t ret; - hrt_abstime now; - - /* - * The DSM* protocol doesn't provide any explicit framing, - * so we detect frame boundaries by the inter-frame delay. - * - * The minimum frame spacing is 11ms; with 16 bytes at 115200bps - * frame transmission time is ~1.4ms. - * - * We expect to only be called when bytes arrive for processing, - * and if an interval of more than 5ms passes between calls, - * the first byte we read will be the first byte of a frame. - * - * In the case where byte(s) are dropped from a frame, this also - * provides a degree of protection. Of course, it would be better - * if we didn't drop bytes... - */ - now = hrt_absolute_time(); - - if ((now - last_rx_time) > 5000) { - if (partial_frame_count > 0) { - dsm_frame_drops++; - partial_frame_count = 0; - } - } - - /* - * Fetch bytes, but no more than we would need to complete - * the current frame. - */ - ret = read(dsm_fd, &frame[partial_frame_count], DSM_FRAME_SIZE - partial_frame_count); - - /* if the read failed for any reason, just give up here */ - if (ret < 1) - return false; - - last_rx_time = now; - - /* - * Add bytes to the current frame - */ - partial_frame_count += ret; - - /* - * If we don't have a full frame, return - */ - if (partial_frame_count < DSM_FRAME_SIZE) - return false; - - /* - * Great, it looks like we might have a frame. Go ahead and - * decode it. - */ - partial_frame_count = 0; - return dsm_decode(now, values, num_values); -} - -static bool -dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value) +/** + * Attempt to decode a single channel raw channel datum + * + * The DSM* protocol doesn't provide any explicit framing, + * so we detect dsm_frame boundaries by the inter-dsm_frame delay. + * + * The minimum dsm_frame spacing is 11ms; with 16 bytes at 115200bps + * dsm_frame transmission time is ~1.4ms. + * + * We expect to only be called when bytes arrive for processing, + * and if an interval of more than 5ms passes between calls, + * the first byte we read will be the first byte of a dsm_frame. + * + * In the case where byte(s) are dropped from a dsm_frame, this also + * provides a degree of protection. Of course, it would be better + * if we didn't drop bytes... + * + * Upon receiving a full dsm_frame we attempt to decode it + * + * @param[in] raw 16 bit raw channel value from dsm_frame + * @param[in] shift position of channel number in raw data + * @param[out] channel pointer to returned channel number + * @param[out] value pointer to returned channel value + * @return true=raw value successfully decoded + */ +bool dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value); +bool dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value) { if (raw == 0xffff) @@ -215,8 +112,13 @@ dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *va return true; } -static void -dsm_guess_format(bool reset) +/** + * Attempt to guess if receiving 10 or 11 bit channel values + * + * @param[in] reset true=reset the 10/11 bit state to unknow + */ +void dsm_guess_format(bool reset); +void dsm_guess_format(bool reset) { static uint32_t cs10; static uint32_t cs11; @@ -227,14 +129,14 @@ dsm_guess_format(bool reset) cs10 = 0; cs11 = 0; samples = 0; - channel_shift = 0; + dsm_channel_shift = 0; return; } - /* scan the channels in the current frame in both 10- and 11-bit mode */ + /* scan the channels in the current dsm_frame in both 10- and 11-bit mode */ for (unsigned i = 0; i < DSM_FRAME_CHANNELS; i++) { - uint8_t *dp = &frame[2 + (2 * i)]; + uint8_t *dp = &dsm_frame[2 + (2 * i)]; uint16_t raw = (dp[0] << 8) | dp[1]; unsigned channel, value; @@ -245,10 +147,10 @@ dsm_guess_format(bool reset) if (dsm_decode_channel(raw, 11, &channel, &value) && (channel < 31)) cs11 |= (1 << channel); - /* XXX if we cared, we could look for the phase bit here to decide 1 vs. 2-frame format */ + /* XXX if we cared, we could look for the phase bit here to decide 1 vs. 2-dsm_frame format */ } - /* wait until we have seen plenty of frames - 2 should normally be enough */ + /* wait until we have seen plenty of frames - 5 should normally be enough */ if (samples++ < 5) return; @@ -284,13 +186,13 @@ dsm_guess_format(bool reset) } if ((votes11 == 1) && (votes10 == 0)) { - channel_shift = 11; + dsm_channel_shift = 11; debug("DSM: 11-bit format"); return; } if ((votes10 == 1) && (votes11 == 0)) { - channel_shift = 10; + dsm_channel_shift = 10; debug("DSM: 10-bit format"); return; } @@ -300,27 +202,129 @@ dsm_guess_format(bool reset) dsm_guess_format(true); } -static bool -dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values) +/** + * Initialize the DSM receive functionality + * + * Open the UART for receiving DSM frames and configure it appropriately + * + * @param[in] device Device name of DSM UART + */ +int dsm_init(const char *device) { + if (dsm_fd < 0) + dsm_fd = open(device, O_RDONLY | O_NONBLOCK); + if (dsm_fd >= 0) { + + struct termios t; + + /* 115200bps, no parity, one stop bit */ + tcgetattr(dsm_fd, &t); + cfsetspeed(&t, 115200); + t.c_cflag &= ~(CSTOPB | PARENB); + tcsetattr(dsm_fd, TCSANOW, &t); + + /* initialise the decoder */ + dsm_partial_frame_count = 0; + dsm_last_rx_time = hrt_absolute_time(); + + /* reset the format detector */ + dsm_guess_format(true); + + debug("DSM: ready"); + + } else { + + debug("DSM: open failed"); + + } + + return dsm_fd; +} + +/** + * Handle DSM satellite receiver bind mode handler + * + * @param[in] cmd commands - dsm_bind_power_down, dsm_bind_power_up, dsm_bind_set_rx_out, dsm_bind_send_pulses, dsm_bind_reinit_uart + * @param[in] pulses Number of pulses for dsm_bind_send_pulses command + */ +void dsm_bind(uint16_t cmd, int pulses) +{ + const uint32_t usart1RxAsOutp = + GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | GPIO_OUTPUT_SET | GPIO_PORTA | GPIO_PIN10; + + if (dsm_fd < 0) + return; + + switch (cmd) { + + case dsm_bind_power_down: + + //! power down DSM satellite + POWER_RELAY1(0); + break; + + case dsm_bind_power_up: + + //! power up DSM satellite + POWER_RELAY1(1); + dsm_guess_format(true); + break; + + case dsm_bind_set_rx_out: + + //! Set UART RX pin to active output mode + stm32_configgpio(usart1RxAsOutp); + break; + + case dsm_bind_send_pulses: + + //! Pulse RX pin a number of times + for (int i = 0; i < pulses; i++) { + stm32_gpiowrite(usart1RxAsOutp, false); + up_udelay(25); + stm32_gpiowrite(usart1RxAsOutp, true); + up_udelay(25); + } + break; + + case dsm_bind_reinit_uart: + + //! Restore USART RX pin to RS232 receive mode + stm32_configgpio(GPIO_USART1_RX); + break; + + } +} + +/** + * Decode the entire dsm_frame (all contained channels) + * + * @param[in] frame_time timestamp when this dsm_frame was received. Used to detect RX loss in order to reset 10/11 bit guess. + * @param[out] values pointer to per channel array of decoded values + * @param[out] num_values pointer to number of raw channel values returned + * @return true=dsm_frame successfully decoded + */ +bool dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values); +bool dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values) +{ /* - debug("DSM frame %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x", - frame[0], frame[1], frame[2], frame[3], frame[4], frame[5], frame[6], frame[7], - frame[8], frame[9], frame[10], frame[11], frame[12], frame[13], frame[14], frame[15]); + debug("DSM dsm_frame %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x", + dsm_frame[0], dsm_frame[1], dsm_frame[2], dsm_frame[3], dsm_frame[4], dsm_frame[5], dsm_frame[6], dsm_frame[7], + dsm_frame[8], dsm_frame[9], dsm_frame[10], dsm_frame[11], dsm_frame[12], dsm_frame[13], dsm_frame[14], dsm_frame[15]); */ /* * If we have lost signal for at least a second, reset the * format guessing heuristic. */ - if (((frame_time - last_frame_time) > 1000000) && (channel_shift != 0)) + if (((frame_time - dsm_last_frame_time) > 1000000) && (dsm_channel_shift != 0)) dsm_guess_format(true); - /* we have received something we think is a frame */ - last_frame_time = frame_time; + /* we have received something we think is a dsm_frame */ + dsm_last_frame_time = frame_time; - /* if we don't know the frame format, update the guessing state machine */ - if (channel_shift == 0) { + /* if we don't know the dsm_frame format, update the guessing state machine */ + if (dsm_channel_shift == 0) { dsm_guess_format(false); return false; } @@ -332,17 +336,17 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values) * Each channel is a 16-bit unsigned value containing either a 10- * or 11-bit channel value and a 4-bit channel number, shifted * either 10 or 11 bits. The MSB may also be set to indicate the - * second frame in variants of the protocol where more than + * second dsm_frame in variants of the protocol where more than * seven channels are being transmitted. */ for (unsigned i = 0; i < DSM_FRAME_CHANNELS; i++) { - uint8_t *dp = &frame[2 + (2 * i)]; + uint8_t *dp = &dsm_frame[2 + (2 * i)]; uint16_t raw = (dp[0] << 8) | dp[1]; unsigned channel, value; - if (!dsm_decode_channel(raw, channel_shift, &channel, &value)) + if (!dsm_decode_channel(raw, dsm_channel_shift, &channel, &value)) continue; /* ignore channels out of range */ @@ -354,7 +358,7 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values) *num_values = channel + 1; /* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding in a very sloppy fashion */ - if (channel_shift == 11) + if (dsm_channel_shift == 11) value /= 2; value += 998; @@ -385,7 +389,7 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values) values[channel] = value; } - if (channel_shift == 11) + if (dsm_channel_shift == 11) *num_values |= 0x8000; /* @@ -393,3 +397,73 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values) */ return true; } + +/** + * Called periodically to check for input data from the DSM UART + * + * The DSM* protocol doesn't provide any explicit framing, + * so we detect dsm_frame boundaries by the inter-dsm_frame delay. + * + * The minimum dsm_frame spacing is 11ms; with 16 bytes at 115200bps + * dsm_frame transmission time is ~1.4ms. + * + * We expect to only be called when bytes arrive for processing, + * and if an interval of more than 5ms passes between calls, + * the first byte we read will be the first byte of a dsm_frame. + * + * In the case where byte(s) are dropped from a dsm_frame, this also + * provides a degree of protection. Of course, it would be better + * if we didn't drop bytes... + * + * Upon receiving a full dsm_frame we attempt to decode it + * + * @param[out] values pointer to per channel array of decoded values + * @param[out] num_values pointer to number of raw channel values returned + * @return true=decode raw channel values updated + */ +bool dsm_input(uint16_t *values, uint16_t *num_values) +{ + ssize_t ret; + hrt_abstime now; + + /* + */ + now = hrt_absolute_time(); + + if ((now - dsm_last_rx_time) > 5000) { + if (dsm_partial_frame_count > 0) { + dsm_frame_drops++; + dsm_partial_frame_count = 0; + } + } + + /* + * Fetch bytes, but no more than we would need to complete + * the current dsm_frame. + */ + ret = read(dsm_fd, &dsm_frame[dsm_partial_frame_count], DSM_FRAME_SIZE - dsm_partial_frame_count); + + /* if the read failed for any reason, just give up here */ + if (ret < 1) + return false; + + dsm_last_rx_time = now; + + /* + * Add bytes to the current dsm_frame + */ + dsm_partial_frame_count += ret; + + /* + * If we don't have a full dsm_frame, return + */ + if (dsm_partial_frame_count < DSM_FRAME_SIZE) + return false; + + /* + * Great, it looks like we might have a dsm_frame. Go ahead and + * decode it. + */ + dsm_partial_frame_count = 0; + return dsm_decode(now, values, num_values); +} From 6113be111e84a57715f3f3bfe81077bf1b267e52 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 16 Aug 2013 14:25:21 +0200 Subject: [PATCH 74/80] Hotfix: Do not create bug/test lists, adding noise --- Documentation/Doxyfile | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Documentation/Doxyfile b/Documentation/Doxyfile index 65274d4a4f..2417028114 100644 --- a/Documentation/Doxyfile +++ b/Documentation/Doxyfile @@ -429,19 +429,19 @@ SORT_BY_SCOPE_NAME = NO # disable (NO) the todo list. This list is created by putting \todo # commands in the documentation. -GENERATE_TODOLIST = YES +GENERATE_TODOLIST = NO # The GENERATE_TESTLIST tag can be used to enable (YES) or # disable (NO) the test list. This list is created by putting \test # commands in the documentation. -GENERATE_TESTLIST = YES +GENERATE_TESTLIST = NO # The GENERATE_BUGLIST tag can be used to enable (YES) or # disable (NO) the bug list. This list is created by putting \bug # commands in the documentation. -GENERATE_BUGLIST = YES +GENERATE_BUGLIST = NO # The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or # disable (NO) the deprecated list. This list is created by putting From bafc5ea8a1f6f55ebd8c54d673566919162f3f30 Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Fri, 16 Aug 2013 18:35:52 -0400 Subject: [PATCH 75/80] Remoce C++ style Doxygen comments Replace C++ style comments with C comments --- src/modules/px4iofirmware/dsm.c | 106 ++++++++++++++---------------- src/modules/px4iofirmware/px4io.h | 8 +-- 2 files changed, 52 insertions(+), 62 deletions(-) diff --git a/src/modules/px4iofirmware/dsm.c b/src/modules/px4iofirmware/dsm.c index e014b0a519..745cdfa403 100644 --- a/src/modules/px4iofirmware/dsm.c +++ b/src/modules/px4iofirmware/dsm.c @@ -50,53 +50,44 @@ #include "px4io.h" -//! The DSM dsm frame size in bytes -#define DSM_FRAME_SIZE 16 -//! Maximum supported DSM channels -#define DSM_FRAME_CHANNELS 7 +#define DSM_FRAME_SIZE 16 /** Date: Fri, 16 Aug 2013 20:09:12 -0400 Subject: [PATCH 76/80] Flesh out PX4IO documentation comments and delete unnecessary class var --- src/drivers/px4io/px4io.cpp | 141 +++++++++++++++++++++++------------- 1 file changed, 90 insertions(+), 51 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 960ac06ff4..c561ea83a0 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -89,21 +89,61 @@ #define PX4IO_SET_DEBUG _IOC(0xff00, 0) #define PX4IO_INAIR_RESTART_ENABLE _IOC(0xff00, 1) +/** + * The PX4IO class. + * + * Encapsulates PX4FMU to PX4IO communications modeled as file operations. + */ class PX4IO : public device::I2C { public: + /** + * Constructor. + * + * Initialize all class variables. + */ PX4IO(); + /** + * Destructor. + * + * Wait for worker thread to terminate. + */ virtual ~PX4IO(); + /** + * Initialize the PX4IO class. + * + * Initialize the physical I2C interface to PX4IO. Retrieve relevant initial system parameters. Initialize PX4IO registers. + */ virtual int init(); + /** + * IO Control handler. + * + * Handle all IOCTL calls to the PX4IO file descriptor. + * + * @param[in] filp file handle (not used). This function is always called directly through object reference + * @param[in] cmd the IOCTL command + * @param[in] the IOCTL command parameter (optional) + */ virtual int ioctl(file *filp, int cmd, unsigned long arg); + + /** + * write handler. + * + * Handle writes to the PX4IO file descriptor. + * + * @param[in] filp file handle (not used). This function is always called directly through object reference + * @param[in] buffer pointer to the data buffer to be written + * @param[in] len size in bytes to be written + * @return number of bytes written + */ virtual ssize_t write(file *filp, const char *buffer, size_t len); /** * Set the update rate for actuator outputs from FMU to IO. * - * @param rate The rate in Hz actuator outpus are sent to IO. + * @param[in] rate The rate in Hz actuator output are sent to IO. * Min 10 Hz, max 400 Hz */ int set_update_rate(int rate); @@ -111,29 +151,41 @@ public: /** * Set the battery current scaling and bias * - * @param amp_per_volt - * @param amp_bias + * @param[in] amp_per_volt + * @param[in] amp_bias */ void set_battery_current_scaling(float amp_per_volt, float amp_bias); /** * Push failsafe values to IO. * - * @param vals Failsafe control inputs: in us PPM (900 for zero, 1500 for centered, 2100 for full) - * @param len Number of channels, could up to 8 + * @param[in] vals Failsafe control inputs: in us PPM (900 for zero, 1500 for centered, 2100 for full) + * @param[in] len Number of channels, could up to 8 */ int set_failsafe_values(const uint16_t *vals, unsigned len); /** - * Print the current status of IO - */ + * Print IO status. + * + * Print all relevant IO status information + */ void print_status(); + /** + * Set the DSM VCC is controlled by relay one flag + * + * @param[in] enable true=DSM satellite VCC is controlled by relay1, false=DSM satellite VCC not controlled + */ inline void set_dsm_vcc_ctl(bool enable) { _dsm_vcc_ctl = enable; }; + /** + * Get the DSM VCC is controlled by relay one flag + * + * @return true=DSM satellite VCC is controlled by relay1, false=DSM satellite VCC not controlled + */ inline bool get_dsm_vcc_ctl() { return _dsm_vcc_ctl; @@ -141,58 +193,48 @@ public: private: // XXX - unsigned _max_actuators; - unsigned _max_controls; - unsigned _max_rc_input; - unsigned _max_relays; - unsigned _max_transfer; + unsigned _max_actuators; /// Date: Sat, 17 Aug 2013 10:29:35 -0400 Subject: [PATCH 77/80] Make it obvious that file * isn't used here --- src/drivers/px4io/px4io.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index c561ea83a0..fed83ea1ac 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1667,7 +1667,8 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg) } ssize_t -PX4IO::write(file */*filp*/, const char *buffer, size_t len) +PX4IO::write(file * /*filp*/, const char *buffer, size_t len) +/* Make it obvious that file * isn't used here */ { unsigned count = len / 2; From b08ca02410cc02f75bbfe154963edcea6767972e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 17 Aug 2013 19:55:40 +0200 Subject: [PATCH 78/80] Hotfix for UART5 --- nuttx-configs/px4fmu-v1/nsh/defconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig index 5b91930c91..ae941804ec 100644 --- a/nuttx-configs/px4fmu-v1/nsh/defconfig +++ b/nuttx-configs/px4fmu-v1/nsh/defconfig @@ -268,7 +268,7 @@ CONFIG_USART2_RXDMA=y # CONFIG_USART3_RXDMA is not set # CONFIG_UART4_RXDMA is not set # CONFIG_UART5_RS485 is not set -CONFIG_UART5_RXDMA=y +CONFIG_UART5_RXDMA=n # CONFIG_USART6_RS485 is not set CONFIG_USART6_RXDMA=y # CONFIG_USART7_RXDMA is not set From dc1dc25f1bce95b1e4c8d26a418412416f7f8b48 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 17 Aug 2013 20:44:00 +0200 Subject: [PATCH 79/80] Revert "Hotfix for UART5" This reverts commit b08ca02410cc02f75bbfe154963edcea6767972e. --- nuttx-configs/px4fmu-v1/nsh/defconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig index ae941804ec..5b91930c91 100644 --- a/nuttx-configs/px4fmu-v1/nsh/defconfig +++ b/nuttx-configs/px4fmu-v1/nsh/defconfig @@ -268,7 +268,7 @@ CONFIG_USART2_RXDMA=y # CONFIG_USART3_RXDMA is not set # CONFIG_UART4_RXDMA is not set # CONFIG_UART5_RS485 is not set -CONFIG_UART5_RXDMA=n +CONFIG_UART5_RXDMA=y # CONFIG_USART6_RS485 is not set CONFIG_USART6_RXDMA=y # CONFIG_USART7_RXDMA is not set From d90345a16619a6a056ca9158961db36787d97678 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sat, 17 Aug 2013 21:48:54 -0700 Subject: [PATCH 80/80] Some early gdb/Python macros for working with NuttX. Note; only tested with gdb 7.6. Will definitely not work with the stock PX4 toolchain's gdb. --- Debug/Nuttx.py | 298 +++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 298 insertions(+) create mode 100644 Debug/Nuttx.py diff --git a/Debug/Nuttx.py b/Debug/Nuttx.py new file mode 100644 index 0000000000..b0864a2293 --- /dev/null +++ b/Debug/Nuttx.py @@ -0,0 +1,298 @@ +# GDB/Python functions for dealing with NuttX + +import gdb, gdb.types + +class NX_task(object): + """Reference to a NuttX task and methods for introspecting it""" + + def __init__(self, tcb_ptr): + self._tcb = tcb_ptr.dereference() + self._group = self._tcb['group'].dereference() + self.pid = tcb_ptr['pid'] + + @classmethod + def for_tcb(cls, tcb): + """return a task with the given TCB pointer""" + pidhash_sym = gdb.lookup_global_symbol('g_pidhash') + pidhash_value = pidhash_sym.value() + pidhash_type = pidhash_sym.type + for i in range(pidhash_type.range()[0],pidhash_type.range()[1]): + pidhash_entry = pidhash_value[i] + if pidhash_entry['tcb'] == tcb: + return cls(pidhash_entry['tcb']) + return None + + @classmethod + def for_pid(cls, pid): + """return a task for the given PID""" + pidhash_sym = gdb.lookup_global_symbol('g_pidhash') + pidhash_value = pidhash_sym.value() + pidhash_type = pidhash_sym.type + for i in range(pidhash_type.range()[0],pidhash_type.range()[1]): + pidhash_entry = pidhash_value[i] + if pidhash_entry['pid'] == pid: + return cls(pidhash_entry['tcb']) + return None + + @staticmethod + def pids(): + """return a list of all PIDs""" + pidhash_sym = gdb.lookup_global_symbol('g_pidhash') + pidhash_value = pidhash_sym.value() + pidhash_type = pidhash_sym.type + result = [] + for i in range(pidhash_type.range()[0],pidhash_type.range()[1]): + entry = pidhash_value[i] + pid = int(entry['pid']) + if pid is not -1: + result.append(pid) + return result + + @staticmethod + def tasks(): + """return a list of all tasks""" + tasks = [] + for pid in NX_task.pids(): + tasks.append(NX_task.for_pid(pid)) + return tasks + + def _state_is(self, state): + """tests the current state of the task against the passed-in state name""" + statenames = gdb.types.make_enum_dict(gdb.lookup_type('enum tstate_e')) + if self._tcb['task_state'] == statenames[state]: + return True + return False + + @property + def stack_used(self): + """calculate the stack used by the thread""" + if 'stack_used' not in self.__dict__: + stack_base = self._tcb['stack_alloc_ptr'].cast(gdb.lookup_type('unsigned char').pointer()) + if stack_base == 0: + self.__dict__['stack_used'] = 0 + else: + stack_limit = self._tcb['adj_stack_size'] + for offset in range(0, stack_limit): + if stack_base[offset] != 0xff: + break + self.__dict__['stack_used'] = stack_limit - offset + return self.__dict__['stack_used'] + + @property + def name(self): + """return the task's name""" + return self._tcb['name'].string() + + @property + def state(self): + """return the name of the task's current state""" + statenames = gdb.types.make_enum_dict(gdb.lookup_type('enum tstate_e')) + for name,value in statenames.iteritems(): + if value == self._tcb['task_state']: + return name + return 'UNKNOWN' + + @property + def waiting_for(self): + """return a description of what the task is waiting for, if it is waiting""" + if self._state_is('TSTATE_WAIT_SEM'): + waitsem = self._tcb['waitsem'].dereference() + waitsem_holder = waitsem['holder'] + holder = NX_task.for_tcb(waitsem_holder['htcb']) + if holder is not None: + return '{}({})'.format(waitsem.address, holder.name) + else: + return '{}()'.format(waitsem.address) + if self._state_is('TSTATE_WAIT_SIG'): + return 'signal' + return None + + @property + def is_waiting(self): + """tests whether the task is waiting for something""" + if self._state_is('TSTATE_WAIT_SEM') or self._state_is('TSTATE_WAIT_SIG'): + return True + + @property + def is_runnable(self): + """tests whether the task is runnable""" + if (self._state_is('TSTATE_TASK_PENDING') or + self._state_is('TSTATE_TASK_READYTORUN') or + self._state_is('TSTATE_TASK_RUNNING')): + return True + return False + + @property + def file_descriptors(self): + """return a dictionary of file descriptors and inode pointers""" + filelist = self._group['tg_filelist'] + filearray = filelist['fl_files'] + result = dict() + for i in range(filearray.type.range()[0],filearray.type.range()[1]): + inode = long(filearray[i]['f_inode']) + if inode != 0: + result[i] = inode + return result + + @property + def registers(self): + if 'registers' not in self.__dict__: + registers = dict() + if self._state_is('TSTATE_TASK_RUNNING'): + # XXX need to fix this to handle interrupt context + registers['R0'] = long(gdb.parse_and_eval('$r0')) + registers['R1'] = long(gdb.parse_and_eval('$r1')) + registers['R2'] = long(gdb.parse_and_eval('$r2')) + registers['R3'] = long(gdb.parse_and_eval('$r3')) + registers['R4'] = long(gdb.parse_and_eval('$r4')) + registers['R5'] = long(gdb.parse_and_eval('$r5')) + registers['R6'] = long(gdb.parse_and_eval('$r6')) + registers['R7'] = long(gdb.parse_and_eval('$r7')) + registers['R8'] = long(gdb.parse_and_eval('$r8')) + registers['R9'] = long(gdb.parse_and_eval('$r9')) + registers['R10'] = long(gdb.parse_and_eval('$r10')) + registers['R11'] = long(gdb.parse_and_eval('$r11')) + registers['R12'] = long(gdb.parse_and_eval('$r12')) + registers['R13'] = long(gdb.parse_and_eval('$r13')) + registers['SP'] = long(gdb.parse_and_eval('$sp')) + registers['R14'] = long(gdb.parse_and_eval('$r14')) + registers['LR'] = long(gdb.parse_and_eval('$lr')) + registers['R15'] = long(gdb.parse_and_eval('$r15')) + registers['PC'] = long(gdb.parse_and_eval('$pc')) + registers['XPSR'] = long(gdb.parse_and_eval('$xpsr')) + # this would only be valid if we were in an interrupt + registers['EXC_RETURN'] = 0 + # we should be able to get this... + registers['PRIMASK'] = 0 + else: + context = self._tcb['xcp'] + regs = context['regs'] + registers['R0'] = long(regs[27]) + registers['R1'] = long(regs[28]) + registers['R2'] = long(regs[29]) + registers['R3'] = long(regs[30]) + registers['R4'] = long(regs[2]) + registers['R5'] = long(regs[3]) + registers['R6'] = long(regs[4]) + registers['R7'] = long(regs[5]) + registers['R8'] = long(regs[6]) + registers['R9'] = long(regs[7]) + registers['R10'] = long(regs[8]) + registers['R11'] = long(regs[9]) + registers['R12'] = long(regs[31]) + registers['R13'] = long(regs[0]) + registers['SP'] = long(regs[0]) + registers['R14'] = long(regs[32]) + registers['LR'] = long(regs[32]) + registers['R15'] = long(regs[33]) + registers['PC'] = long(regs[33]) + registers['XPSR'] = long(regs[34]) + registers['EXC_RETURN'] = long(regs[10]) + registers['PRIMASK'] = long(regs[1]) + self.__dict__['registers'] = registers + return self.__dict__['registers'] + + def __repr__(self): + return "".format(self.pid) + + def __str__(self): + return "{}:{}".format(self.pid, self.name) + + def __format__(self, format_spec): + return format_spec.format( + pid = self.pid, + name = self.name, + state = self.state, + waiting_for = self.waiting_for, + stack_used = self.stack_used, + stack_limit = self._tcb['adj_stack_size'], + file_descriptors = self.file_descriptors, + registers = self.registers + ) + +class NX_show_task (gdb.Command): + """(NuttX) prints information about a task""" + + def __init__(self): + super(NX_show_task, self).__init__("show task", gdb.COMMAND_USER) + + def invoke(self, arg, from_tty): + t = NX_task.for_pid(int(arg)) + if t is not None: + my_fmt = 'PID:{pid} name:{name} state:{state}\n' + my_fmt += ' stack used {stack_used} of {stack_limit}\n' + if t.is_waiting: + my_fmt += ' waiting for {waiting_for}\n' + my_fmt += ' open files: {file_descriptors}\n' + my_fmt += ' R0 {registers[R0]:#010x} {registers[R1]:#010x} {registers[R2]:#010x} {registers[R3]:#010x}\n' + my_fmt += ' R4 {registers[R4]:#010x} {registers[R5]:#010x} {registers[R6]:#010x} {registers[R7]:#010x}\n' + my_fmt += ' R8 {registers[R8]:#010x} {registers[R9]:#010x} {registers[R10]:#010x} {registers[R11]:#010x}\n' + my_fmt += ' R12 {registers[PC]:#010x}\n' + my_fmt += ' SP {registers[SP]:#010x} LR {registers[LR]:#010x} PC {registers[PC]:#010x} XPSR {registers[XPSR]:#010x}\n' + print format(t, my_fmt) + +class NX_show_tasks (gdb.Command): + """(NuttX) prints a list of tasks""" + + def __init__(self): + super(NX_show_tasks, self).__init__('show tasks', gdb.COMMAND_USER) + + def invoke(self, args, from_tty): + tasks = NX_task.tasks() + for t in tasks: + print format(t, '{pid:<2} {name:<16} {state:<20} {stack_used:>4}/{stack_limit:<4}') + +NX_show_task() +NX_show_tasks() + +class NX_show_heap (gdb.Command): + """(NuttX) prints the heap""" + + def __init__(self): + super(NX_show_heap, self).__init__('show heap', gdb.COMMAND_USER) + if gdb.lookup_type('struct mm_allocnode_s').sizeof == 8: + self._allocflag = 0x80000000 + self._allocnodesize = 8 + else: + self._allocflag = 0x8000 + self._allocnodesize = 4 + + def _node_allocated(self, allocnode): + if allocnode['preceding'] & self._allocflag: + return True + return False + + def _node_size(self, allocnode): + return allocnode['size'] & ~self._allocflag + + def _print_allocations(self, region_start, region_end): + if region_start >= region_end: + print 'heap region {} corrupt'.format(hex(region_start)) + return + nodecount = region_end - region_start + print 'heap {} - {}'.format(region_start, region_end) + cursor = 1 + while cursor < nodecount: + allocnode = region_start[cursor] + if self._node_allocated(allocnode): + state = '' + else: + state = '(free)' + print ' {} {} {}'.format(allocnode.address + 8, self._node_size(allocnode), state) + cursor += self._node_size(allocnode) / self._allocnodesize + + def invoke(self, args, from_tty): + heap = gdb.lookup_global_symbol('g_mmheap').value() + nregions = heap['mm_nregions'] + region_starts = heap['mm_heapstart'] + region_ends = heap['mm_heapend'] + print "{} heap(s)".format(nregions) + # walk the heaps + for i in range(0, nregions): + self._print_allocations(region_starts[i], region_ends[i]) + +NX_show_heap() + + + +