From cb5cb3d3b59e14410cbeb00f0a2bf73b77ae42e4 Mon Sep 17 00:00:00 2001 From: Daniel Gerblick Date: Sat, 22 Apr 2023 16:32:53 +0000 Subject: [PATCH 1/5] `rktl_control` documentation --- .gitignore | 1 + docs/Makefile | 1 + docs/conf.py | 6 + docs/rktl_control.md | 11 + rktl_control/README.md | 335 +-------------------- rktl_control/firmware/README.md | 144 +++++++++ rktl_control/launch/README.md | 162 ++++++++++ rktl_control/nodes/README.md | 374 ++++++++++++++++++++++++ rktl_control/nodes/controller | 22 +- rktl_control/nodes/keyboard_interface | 15 +- rktl_control/nodes/mean_odom_filter | 12 +- rktl_control/nodes/particle_odom_filter | 121 +++++--- rktl_control/nodes/pose_synchronizer | 39 ++- rktl_control/nodes/topic_delay | 12 +- rktl_control/nodes/xbox_interface | 27 +- 15 files changed, 870 insertions(+), 412 deletions(-) create mode 100644 docs/rktl_control.md create mode 100644 rktl_control/firmware/README.md create mode 100644 rktl_control/launch/README.md create mode 100644 rktl_control/nodes/README.md diff --git a/.gitignore b/.gitignore index 423d5a2b3..796c68107 100644 --- a/.gitignore +++ b/.gitignore @@ -74,6 +74,7 @@ docs/html/ docs/autoapi docs/rosdoc/ docs/rktl_*/ +~!docs/rktl_*/index.md # PyBuilder target/ diff --git a/docs/Makefile b/docs/Makefile index e7aeb6e1b..e28d1ce47 100644 --- a/docs/Makefile +++ b/docs/Makefile @@ -41,6 +41,7 @@ $(ROSDOC_OUT): @mkdir -p $@ rosdoc_lite -o $@ $(shell rospack find $(notdir $@)) > /dev/null 2>&1 @# Clean up big unnecessary files + @rm $@/html/index.html @rm $@/html/*.png @rm $@/html/*.js diff --git a/docs/conf.py b/docs/conf.py index 447966cb3..d103c26d3 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -38,6 +38,12 @@ "myst_parser", ] +myst_enable_extensions = [ + "dollarmath", + "amsmath", + "smartquotes", +] + autoapi_dirs = [ "../rktl_autonomy/src", "../rktl_perception/src", diff --git a/docs/rktl_control.md b/docs/rktl_control.md new file mode 100644 index 000000000..87b2aea99 --- /dev/null +++ b/docs/rktl_control.md @@ -0,0 +1,11 @@ +```{include} ./rktl_control/README.md +``` + +```{toctree} +:Caption: Package Contents +:maxdepth: 2 +:glob: + +./rktl_control/*/README +Msg/Srv Documentation +``` diff --git a/rktl_control/README.md b/rktl_control/README.md index a77742e41..85d73b3d3 100644 --- a/rktl_control/README.md +++ b/rktl_control/README.md @@ -1,334 +1,17 @@ -# Rocket League Control +# rktl_control + This package performs several jobs that allow it to move physical cars according to commands from either the planning or autonomy code. Specifically it has three main components: + - It filters the raw perception data using either a moving average filter or a -particle filter, while also producing estimated odometry (which includes velocity -in addition to the position given by the raw perception data) -- It has a closed loop controller which reduces the error between the desired and -estimated motion of the car by producing control signals. -- It has a hardware interface, which sends those control signals to the physical cars. + particle filter, while also producing estimated odometry (which includes + velocity in addition to the position given by the raw perception data) +- It has a closed loop controller which reduces the error between the desired + and estimated motion of the car by producing control signals. +- It has a hardware interface, which sends those control signals to the physical + cars. It also contains several MATLAB scripts that are useful in tuning and validating the Python code used for this project. - -## Filters -### Moving Average -This is a very simple filter. If you have a stream of noisy measurements, -averaging the most recent N measurements will give you a pretty good estimate. -This gets slightly complicated when handling angles, since they wrap around at -+/- pi, but it still works. - -The downside is that if you average 10 measurements, your estimate is time-delayed -by 5 sampling periods. Therefore, a balance needs to be struck between the desired -noise reduction and the acceptable delay. - -This filter also runs into problems when taking derivatives of the input. -Simply taking the derivative of the two most recent measurements, filtered or -unfiltered, will result in significant noise. To combat this, the filter computes -derivatives for each pair of points (ex: `t-1` and `t-2`, `t-2` and `t-3`, `t-3` and `t-4`), -then averages those velocity predictions using the same averaging buffer algorithm. - -The relevant parameters to the filter (defined in [`mean_odom_filter.yaml`](config/mean_odom_filter.yaml)) -are `buffer_size/position` and `buffer_size/velocity`. Note that the velocity -buffer size is the number of velocity measurements, not position measurements. -Therefore, the number of position measurements in the buffer is one greater. - -It also has predictive abilities, which extrapolate the current position and -orientation to the future. If used, this should be configured so that it outputs -an estimate of what the world will be like when the currently being calculated -controls arrive. This is controlled through the `delay` parameters. - -Overall, this filter is simple and works well enough for position as long as -slight delay is acceptable. For velocity, it runs into problems since the noise -is greater and the sampling frequency isn't high enough to get a low delay signal. - -### Particle Filter -This is a much more complex algorithm. The basic premise of why the algorithm is -useful is that by considering the noise in each individual measurement, not just -the mean value, there is more detail that can be used to improve the accuracy vs -delay trade off. Several similar algorithms were considered and are briefly -discussed below. - -The basic premise is that a particle filter has many different estimates of what -the car is doing and where it is (called a particle; perhaps 1,000 in this -application). For each new measurement that comes in: -- Each and every one of these particles are simulated one time step (using a bicycle -model) to get a prediction of the current state of the particle -- For each particle, the question is asked, "Given this measurement and what I -know about it's standard deviation, what is the probability that this particle -is correct?" -- That result is used to compute a weighed average of all the particles. -- This average is then post processed a little bit to produce an odometry estimate -since the internal states don't exactly match - -This then repeats until the end of time. - -Initially, the particles are randomly distributed all over the field, but they -eventually converge (pretty quickly) to the real state of the car. To do this, -the filter will periodically delete bad particles, and replace them with new -random ones. These random ones are uniformly distributed if there isn't a good -guess of where the car is (like when the filter first starts), or distributed -normally about the most recent guess - -The specific state of the car is tracked by five-ish variables: -- x, the x location of the car's center of mass in the field's reference frame -- y, the y location of the car's center of mass in the field's reference frame -- sin(theta), the Y component of the car's heading angle in the field's reference frame -- cos(theta), the X component of the car's heading angle in the field's reference frame -- v_rear, the linear velocity of the rear tires of the car -- psi, the steering angle (relative to the car's center) - -Theta is split into two state variables to prevent issues with wrap around and -summation. - -From these, a kinematic bicycle model is used to calculate out everything needed -for an odometry message. Basically, this just assumes there is no side-slip by -the tires and it uses a lot of trigonometry. Details are in the MATLAB script -[`bicycle_model.m`](scripts/bicycle_model.m). - -When advancing each particle one time-step, either the known control vector ( -from listening to controller output) or a random control vector is used. If the -known vector is used, a small amount of random noise is added. If a completely -random one is used, they are uniformly distributed between actuator saturation -limits. From these, a new wheel velocity and steering angle are predicted -(using a 1st order and 0 order velocity model) and fed into the bicycle model. - -All parameters to the filter are defined in [`particle_odom_filter.yaml`](config/particle_odom_filter.yaml). -The relevant ones to tweak are: -- `boundary_check`: Should the filter artificially punish particles outside of -the assumed field boundaries? -- `delay`: The `total_cycles` parameter should be the number of delta_t sized -delays between an actuation being sent to the vehicle and perception seeing it -move. The `compensate` parameter means if the filter should try to predict the -future state of the field, corresponding to when the currently being calculated -controls would arrive. -- `num_particles`: A higher number of particles should increase the accuracy of -the filter, but will consume higher computational resources. -- `resample_proportion`: The percentage of particles replaced with random guesses -at every timestep. -- `measurement_error`: These are the assumed standard deviations of the -perception data coming in. -- `generator_noise`: These are the standard deviations of the gaussian noise -added to the most recent state estimate when producing random new particles. -- `efforts`: The `max` and `min` values are actuator saturation limits. This -should match what the controller is allowed to produce. The `noise` value is the -standard deviation of gaussian noise added if the controls are known. - -A good resource I found on particle filters is here: - -#### Alternative algorithms -[Kalman filters](https://www.kalmanfilter.net/default.aspx) were also considered. -This is similar to a particle filter in that it is cognizant of measurement noise -to improve its prediction, but it estimates the state using a series of means -and covariances. This restricts it to a normal distribution, whereas a mass of -particles can take on any shape (such as uniform or bimodal). - -Since the model of the car is nonlinear, a standard Kalman filter would not work, -and extended and unscented Kalman filters were considered in detail. -A basic EFK was constructed in MATLAB in [`ekf_demo.m`](scripts/ekf_demo.m). - -A comparison of their performance can be seen by running [`compare_filters.m`](scripts/compare_filters.m) -in MATLAB. This generates a ground truth, samples noisy measurements from it, -then simulates an EKF, UKF, and particle filter on the data. The particle filter -was found to have superior performance, so it was implemented in Python for the -project. - -## Controller -The controller is responsible for making the car do what you tell it to do. -Simply, that means you give it a [`ControlCommand.msg`](../rktl_msgs/msg/ControlCommand.msg) -and it produces a [`ControlEffort.msg`](../rktl_msgs/msg/ControlEffort.msg) that -makes the car follow it. At a basic level, it uses the odometry produced by the -filter and tries to minimize the error between what you want the car to do and -what it is actually doing. - -Let's quickly discuss each control message in more detail: - -**command** -- curvature and velocity -- fixed units (m^-1 and m/s) -- specific to a desired motion, not to a desired vehicle / car - -**effort** -- steering and velocity -- range between -1.0 and +1.0 -- specific to what is being controlled - -The incoming message is different from the outgoing message because it is taking -a desired motion that could be for any mechanism, and it is converting it to -very specific hardware commands for our specific cars. This allows the software -generating the commands to ignore the specifics of the cars, and the software / -hardware getting the efforts to the actuators to also ignore the specifics of the -car as a whole. - -To get slightly more complex, let's talk about how it actually does that. First, -it uses a bicycle model (which is discussed more in the particle filter) to -convert desired the velocity and curvature of the center of mass to a desired -steering angle and linear velocity of the rear wheels. - -For steering, it calculates the actuator effort to make that happen and sends -it out. If it turns out to be off by a little bit, it ignores that. That is -called "open loop" since the information flows in a straight line and the actual -measurements are never used to correct that small error, "closing the loop." This -is OK since it probably won't be off by much, and whatever generates the command -will issue corrections (by closing its own loop) so the car goes where it is -supposed to. In the future, a closed loop controller could be implemented for -steering if testing determines it is necessary. - -For velocity, it uses one of two controllers (PID or lead-lag) to calculate the -effort. These are more complex to understand, but they are basically functions -that will minimize error, and you can "tune" them to minimize the error in -different ways (ex: faster vs slower, more vs less overshoot). See -**Closed Loop Controllers** below for more information. To use them, the controller -will calculate an error between the desired (called "reference") rear wheel -velocity and the actual (from measurements). This is the "closing the loop" part. -It will then feed that error into the controller and it will make a good guess -as to what effort (for the rear motor) will minimize that error. For example, it -might initially give the car a really high effort to make it accelerate quickly, -then lower the effort once it reaches the desired speed. It might also see that -the car is consistently moving a little too slow, so it'll bump up the effort -more than originally predicted. *If the controllers are properly tuned*, this -will result in the car better matching what you want it to do as compared to -simply predicting an effort based off velocity. - -### Closed Loop Controllers -The two types of controllers supported are PID and lead-lag. If you've never -heard of these before, PID is going to be something you can intuitively understand with some work, -and lead-lag is probably something you're going to need to take some classes or -read some textbooks to understand (ex: Purdue ME 365, 375, 475). - -PID control is very well explained in many places on the internet, so I won't -discuss the basics here. The reason it is an option is because it is a commonly -used controller that can be tuned intuitively by watching how the car is behaving. -Lead-Lag is a very similar algorithm that can result in better performance -(especially for discrete systems like this), but it is harder to tune. Intuitively -tuning likely isn't an option, so instead MATLAB scripts can be really helpful -to determine the specific gains to use. These are included in `scripts`. - -Some possibly useful references: -- -- -- - -These are all by Brian Douglas, who has many useful videos on control concepts. - -## Hardware Interface -This takes a [`ControlEffort.msg`](../rktl_msgs/msg/ControlEffort.msg) -message and sends it to a physical car. The efforts in the message range from --1.0 to +1.0 corresponding to full reverse for full forward motor speed, -or full left or full right steering angle respectively. Technically, you can -also feed in values with an absolute value greater than 1.0. This is useful for -having higher actuator saturation limits in the controller, or perhaps -implementing a "boost" for human controlled cars. - -Physically, the interface code runs on a [Teensy 3.2](https://www.pjrc.com/store/teensy32.html) -microcontroller. The microcontroller is connected to a computer via USB, and -code running on the computer allows it to pull control effort messages from the -ROS network. The microcontroller is also connected to [FrSky XJT](https://www.frsky-rc.com/xjt/) -radio transmitter, which allows it to send these controls to the car. - -To launch the node, simple give the Teensy power. To connect it to ROS on your -computer, launch the docker container with `./docker/docker-run.sh --privileged` -(this will only work on Linux), then launch the interface code with: -``` -roslaunch rktl_control hardware_interface.launch -``` - -To use a different serial port (check `ls /dev` to see what it is named), modify -the config file. - -You can enable the cars with: -``` -rostopic pub /cars/enable std_msgs/Bool "data: true" -``` - -Then manually feed it controls with: -``` -roslaunch rktl_control keyboard_control.launch -``` - -### Building and Uploading -Unfortunately, there are several steps required to build and upload code. - -First you need to configure your IDE. This is best done *outside* of the Docker -container. First, install the Arduino IDE, then Teensyduino. Make sure to install -the PulsePosition library when installing Teensyduino. - -Next, build the ROS libraries. *Inside the Docker container*, run: -``` -rosrun rosserial_arduino make_libraries.py . -``` -Copy the generated `ros_lib` folder to `/libraries/` - -Lastly, launch the Arduino IDE, load the `hardware_interface.ino` project inside the -`scripts` folder, set the target board to the Teensy 3.2, and click upload. - -### Binding the Radios -Binding the radios to the cars is a somewhat tedious process. There is a very -precise set of instructions to follow, and you may need to do it several times -in a row, until everything goes exactly right. -1. Power everything off (radio + car) -2. Ensure the dip switches on the radio are set to 1-on, 2-off -3. Hold down the white button on the radio and power it. It will beep and blink -4. Hold down the button on the car's receiver, and power it. It will also blink -5. You can release both buttons -6. Power off the car -7. Power off the radio -8. Power on the radio -9. Power on the car -If it worked, the car's receiver will have a solid red light. If it didn't work, -you'll need to try again. - -### Setting the Radio Failsafe -If the radio signal is lost, the car will automatically go in to a failsafe -mode. This mode needs to be programmed so that the default action is to do -nothing (as opposed to go absolutely bonkers and run into walls, which has a -good chance of happening if the failsafe is not explicitly set). The procedure -is simple. Run the hardware interface and manually publish an effort message -with the field's zeroed (do this on a frequency like 10 Hz). Power on the car -and within a second or two *after* power it, click the button on the receiver. -All done. - -### Programming the ESCs -The ESCs (Electronic Speed Controllers) in the cars are very advanced. They're -over-powered for what we're doing, and are some of the best on the market. They -are highly configurable through a simple user interface. - -Download and install [Castle Link](https://home.castlecreations.com/download-castle-link/) -on a Windows computer. Use the [USB adapter](https://www.castlecreations.com/en/pc-software-and-cables-4/castle-link-v3-usb-programming-kit-011-0119-00) -that we purchased with the ESCs to connect it to your computer. The battery does -not need to be connected to the car, and you will unplug the ESC from the -receiver to connect it to your computer. In Castle Link, connect to the car. -Then go to File->Load Settings, and load `esc_settings.dat` in the `config` -folder. Click Update in the bottom right to send them to the car. - -After programming them, the endpoints need to be set. This tells it what -control input maps to what speed. The procedure is a little complex, but not too -bad. -1. Power off the car and hardware interface -2. Set the throttle throw to 500 on the hardware interface config -3. Launch and enable the hardware interface -4. Manually publish an effort message with 1.0 throttle effort (at 10 Hz) -5. Power on the car **With the wheels off the ground**, it should make a lot of beeping noises -6. Manually publish an effort message with -1.0 throttle effort (at 10 Hz) -7. Manually publish an effort message with 0.0 throttle effort (at 10 Hz) -8. Power off the car and hardware interface -9. Revert the throttle throw to what it was previously at - -After step 7, the car should have made some noises, then stopped beeping. If you -run the car normally and it makes a lot of noises and doesn't move, or if it -goes *way* too fast, then you likely need to do this procedure again. - -### Further Information -`Teensyduino`, software that lets you program the Teensy using the Arduino IDE, is described here: - -The specific library used to connect to the modules is described here: - -Additional `rosserial_arduino` tutorials can be found here: - -Radio transmitter manual: - -Radio receiver manual: - -ESC manual: \ No newline at end of file diff --git a/rktl_control/firmware/README.md b/rktl_control/firmware/README.md new file mode 100644 index 000000000..a522a310e --- /dev/null +++ b/rktl_control/firmware/README.md @@ -0,0 +1,144 @@ +# Microcontroller Firmware + +This folder contains all firmware that is written to microcontollers for the +project. + +**Firmwares:** + +- [`hardware_interface`](#hardware-interface) + +--- + +## hardware_interface + +This is the firmware that is written to a +[Teensy 3.2](https://www.pjrc.com/store/teensy32.html). The Teensy is connected +to a computer via USB, and code running on the computer allows it to pull +control effort messages from the ROS network. The Teensy is also connected to +[FrSky XJT](https://www.frsky-rc.com/xjt/) radio transmitter, which allows it +to send these controls to the car. + +To launch the node, simply give the Teensy power and use the +[`hardware_interface`](../launch/README.md#hardware-interface-launch) launch +file: + +```{shell} +roslaunch rktl_control hardware_interface.launch +``` + +Note that in order for this node to work, it need to be run on a Linux computer +with that the [docker container](../../docker/README.md) needs to be run with +the `--privileged` option. + +To use a different serial port (check `ls /dev` to see what it is named), modify +the config file. + +You can enable the cars with: + +```{shell} +rostopic pub /cars/enable std_msgs/Bool "data: true" +``` + +Then manually feed it controls with: + +```{shell} +roslaunch rktl_control keyboard_control.launch +``` + +### Building and Uploading + +Unfortunately, there are several steps required to build and upload code. + +First you need to configure your IDE. This is best done *outside* of the Docker +container. First, install the Arduino IDE, then Teensyduino. Make sure to install +the PulsePosition library when installing Teensyduino. + +Next, build the ROS libraries. *Inside the Docker container*, run: + +```{shell} +rosrun rosserial_arduino make_libraries.py . +``` + +Copy the generated `ros_lib` folder to `/libraries/` + +Lastly, launch the Arduino IDE, load the `hardware_interface.ino` project inside the +`scripts` folder, set the target board to the Teensy 3.2, and click upload. + +### Binding the Radios + +Binding the radios to the cars is a somewhat tedious process. There is a very +precise set of instructions to follow, and you may need to do it several times +in a row, until everything goes exactly right. + +1. Power everything off (radio + car) +2. Ensure the dip switches on the radio are set to 1-on, 2-off +3. Hold down the white button on the radio and power it. It will beep and blink +4. Hold down the button on the car's receiver, and power it. It will also blink +5. You can release both buttons +6. Power off the car +7. Power off the radio +8. Power on the radio +9. Power on the car +If it worked, the car's receiver will have a solid red light. If it didn't work, +you'll need to try again. + +### Setting the Radio Failsafe + +If the radio signal is lost, the car will automatically go in to a failsafe +mode. This mode needs to be programmed so that the default action is to do +nothing (as opposed to go absolutely bonkers and run into walls, which has a +good chance of happening if the failsafe is not explicitly set). The procedure +is simple. Run the hardware interface and manually publish an effort message +with the field's zeroed (do this on a frequency like 10 Hz). Power on the car +and within a second or two *after* power it, click the button on the receiver. +All done. + +### Programming the ESCs + +The ESCs (Electronic Speed Controllers) in the cars are very advanced. They're +over-powered for what we're doing, and are some of the best on the market. They +are highly configurable through a simple user interface. + +Download and install +[Castle Link](https://home.castlecreations.com/download-castle-link/) +on a Windows computer. Use the +[USB adapter](https://www.castlecreations.com/en/pc-software-and-cables-4/castle-link-v3-usb-programming-kit-011-0119-00) +that we purchased with the ESCs to connect it to your computer. The battery does +not need to be connected to the car, and you will unplug the ESC from the +receiver to connect it to your computer. In Castle Link, connect to the car. +Then go to File->Load Settings, and load `esc_settings.dat` in the `config` +folder. Click Update in the bottom right to send them to the car. + +After programming them, the endpoints need to be set. This tells it what +control input maps to what speed. The procedure is a little complex, but not too +bad. + +1. Power off the car and hardware interface +2. Set the throttle throw to 500 on the hardware interface config +3. Launch and enable the hardware interface +4. Manually publish an effort message with 1.0 throttle effort (at 10 Hz) +5. Power on the car **With the wheels off the ground**, it should make a lot of beeping noises +6. Manually publish an effort message with -1.0 throttle effort (at 10 Hz) +7. Manually publish an effort message with 0.0 throttle effort (at 10 Hz) +8. Power off the car and hardware interface +9. Revert the throttle throw to what it was previously at + +After step 7, the car should have made some noises, then stopped beeping. If you +run the car normally and it makes a lot of noises and doesn't move, or if it +goes *way* too fast, then you likely need to do this procedure again. + +### Further Information + +`Teensyduino`, software that lets you program the Teensy using the Arduino IDE, is described here: + +The specific library used to connect to the modules is described here: + +Additional `rosserial_arduino` tutorials can be found here: + +Radio transmitter manual: + +Radio receiver manual: + +ESC manual: + +--- diff --git a/rktl_control/launch/README.md b/rktl_control/launch/README.md new file mode 100644 index 000000000..a30ae8cab --- /dev/null +++ b/rktl_control/launch/README.md @@ -0,0 +1,162 @@ +# Launch Files + +These are [.launch files](https://wiki.ros.org/roslaunch/XML) that can be run +using [roslaunch](https://wiki.ros.org/roslaunch): + +```shell +roslaunch rktl_control +``` + +**Launch Files:** + +- [`ball.launch`](#ball-launch) +- [`car.launch`](#car-launch) +- [`hardware_interface.launch`](#hardware-interface-launch) +- [`keyboard_control.launch`](#keyboard-control-launch) +- [`xbox_control.launch`](#xbox-control-launch) + +--- + +## ball.launch + +This launches a [`mean_odom_filter`](../nodes/README.md#mean-odom-filter) node +to start the ball tracking with parameters supplied by +`rktl_control/config/mean_odom_filter.yaml`. + +### Nodes + +- `ball/mean_odom_filter`: + [`mean_odom_filter`](../nodes/README.md#mean-odom-filter) node from the + [`rktl_control`](../README.md) package. Parameters supplied by + `rktl_control/config/mean_odom_filter.yaml`. + +--- + +## car.launch + +This launches the filter (either a +[particle filter](../nodes/README.md#particle-odom-filter) or a +[rolling average](../nodes/README.md#mean-odom-filter)) to track the car, as +well as the [controller](../nodes/README.md#controller) needed to control it. +The type of filter can be changed by the `use_particle_filter` argument. +Parameters are provided by `rktl_control/config/particle_odom_filter.yaml` or +`rktl_control/config/mean_odom_filter.yaml` (depending on the filter chosen) and +`rktl_control/config/controller.yaml`. + +### Launch Arguments + +- `car_name` (default: `car0`): Name of the car to launch the agent for. +- `use_particle_filter` (default: true): If true, a + [particle filter](../nodes/README.md#particle-odom-filter) is used. + Otherwise, a [rolling average](../nodes/README.md#mean-odom-filter) is used. + +### Nodes + +- `mean_odom_filter`: + [`mean_odom_filter`](../nodes/README.md#mean-odom-filter) node from the + [`rktl_control`](../README.md) package. Only run if `use_particle_filter` is set to false. Parameters supplied by + `rktl_control/config/mean_odom_filter.yaml`. +- `particle_odom_filter`: + [`particle_odom_filter`](../nodes/README.md#particle-odom-filter) node from the + [`rktl_control`](../README.md) package. Only run if `use_particle_filter` is set to true (the default). Parameters supplied by + `rktl_control/config/particle_odom_filter.yaml`. +- `controller`: [`controller`](../nodes/README.md#controller) node from the + [`rktl_control`](../README.md) package. Parameters supplied by + `rktl_control/config/controller.yaml`. + +--- + +## hardware_interface.launch + +This takes a [rktl_msgs/ControlEffort](/rktl_msgs/html/msg/ControlEffort.html) +message and sends it to a physical car. The efforts in the message range from +-1.0 to +1.0 corresponding to full reverse for full forward motor speed, or +full left or full right steering angle respectively. Technically, you can also +feed in values with an absolute value greater than 1.0. This is useful for +having higher actuator saturation limits in the controller, or perhaps +implementing a "boost" for human controlled cars. + +Physically, the interface code runs on a +[Teensy 3.2](https://www.pjrc.com/store/teensy32.html) microcontroller. The +microcontroller is connected to a computer via USB, and code running on the +computer allows it to pull control effort messages from the ROS network. The +microcontroller is also connected to [FrSky XJT](https://www.frsky-rc.com/xjt/) +radio transmitter, which allows it to send these controls to the car. + +Note that in order for this node to work, it need to be run on a Linux computer +with that the [docker container](../../docker/README.md) needs to be run with +the `--privileged` option. + +### Nodes + +- `hardware_interface`: `serial_node.py` node from the + [`rosserial_arduino`](https://wiki.ros.org/rosserial_arduino) package. This + node allows the firmware on a connected Teensy to interface with the rest + of the ROS network. Parameters, including the serial port used by the + Teensy, are supplied by `rktl_control/config/hardware_interface.yaml`. + +--- + +## keyboard_control.launch + +This launches a [`keyboard_interface`](../nodes/README.md#keyboard-interface) +node to allow for controlling the car using the keyboard. + +### Nodes + +- `cars/{car_name}/keyboard_interface`: + [`keyboard_interface`](../nodes/README.md#keyboard-interface) node from the + [`rktl_control`](../README.md) package. The namespace of this node is + affected by the `car_name` parameter to ensure that the node interacts with + the correct topics. + +### Parameters + +- `car_name` (default: `car0`): Name of the car to control with the keyboard + interface. + +--- + +## xbox_control.launch + +This launches a [`xbox_interface`](../nodes/README.md#xbox-interface) +node and all related nodes to allow for controlling the car using an xbox +controller. + +### Nodes + +- `cars/{car_name}/joy_node`: + [`joy_node`](https://wiki.ros.org/joy#joy_node) node from the + [`joy`](https://wiki.ros.org/joy) package. This node publishes the current + state of the joystick to be used by the + [`xbox_interface`](../nodes/README.md#xbox-interface) node. The namespace + of this node is affected by the `car_name` parameter to ensure that the + node interacts with the correct topics. +- `cars/{car_name}/xbox_interface`: + [`xbox_interface`](../nodes/README.md#xbox-interface) node from the + [`rktl_control`](../README.md) package. The namespace of this node is + affected by the `car_name` parameter to ensure that the node interacts with + the correct topics. +- `cars/{car_name}/controller_delay`: + [`topic_delay`](../nodes/README.md#topic-delay) node from the + [`rktl_control`](../README.md) package. This adds delay to the output of + the `joy_node` topic The namespace of this node is affected by the + `car_name` parameter to ensure that the node interacts with + the correct topics. +- `cars/{car_name}/controller_delay_mux`: + [`mux`](https://wiki.ros.org/topic_tools/mux) node from the + [`topic_tools`](https://wiki.ros.org/topic_tools) package. This node + subscribes to the raw joystick and delayed joystick topics and republishes + it onto a combined topic. The namespace of this node is affected by the + `car_name` parameter to ensure that the node interacts with the correct + topics. + +### Parameters + +- `device` (default: `/dev/input/js0`): Device file of the joystick. +- `car_name` (default: `car0`): Name of the car to control with the keyboard + interface. +- `delay` (default: `0.1`): Amount of simulated delay to add to the controller + input + +--- diff --git a/rktl_control/nodes/README.md b/rktl_control/nodes/README.md new file mode 100644 index 000000000..2ed410b8e --- /dev/null +++ b/rktl_control/nodes/README.md @@ -0,0 +1,374 @@ +# ROS Nodes + +These are the [ROS Nodes](http://wiki.ros.org/Nodes) provided by this package. +Most likely, you will use a launch file to run these. You can also run them +by using `rosrun`: + +```bash +rosrun rktl_control +``` + +**Nodes:** + +- [`controller`](#controller) +- [`keyboard_interface`](#keyboard-interface) +- [`mean_odom_filter`](#mean-odom-filter) +- [`particle_odom_filter`](#particle-odom-filter) +- [`pose_synchronizer`](#pose-synchronizer) +- [`topic_delay`](#topic-delay) +- [`xbox_interface`](#xbox-interface) + +--- + +## controller + +Customizable controller for the car. It implements either a PID controller or a +lead-lag controller. + +The controller is responsible for making the car do what you tell it to do. +Simply, that means you give it a +[`ControlCommand.msg`](/rktl_msgs/html/msg/ControlCommand.html) and it produces +a [`ControlEffort.msg`](/rktl_msgs/html/msg/ControlEffort.html) that makes the +car follow it. At a basic level, it uses the odometry produced by the filter and +tries to minimize the error between what you want the car to do and what it is +actually doing. + +The incoming message is different from the outgoing message because it is taking +a desired motion that could be for any mechanism, and it is converting it to +very specific hardware commands for our specific cars. This allows the software +generating the commands to ignore the specifics of the cars, and the software / +hardware getting the efforts to the actuators to also ignore the specifics of +the car as a whole. + +The two types of controllers supported are PID and lead-lag. If you've never +heard of these before, PID is going to be something you can intuitively +understand with some work, and lead-lag is probably something you're going to +need to take some classes or read some textbooks to understand (ex: Purdue ME +365, 375, 475). + +PID control is very well explained in many places on the internet, so I won't +discuss the basics here. The reason it is an option is because it is a commonly +used controller that can be tuned intuitively by watching how the car is +behaving. Lead-Lag is a very similar algorithm that can result in better +performance (especially for discrete systems like this), but it is harder to +tune. Intuitively tuning likely isn't an option, so instead MATLAB scripts can +be really helpful to determine the specific gains to use. These are included in +the `scripts` directory of this package. + +Some possibly useful references: +- +- +- + +These are all by Brian Douglas, who has many useful videos on control concepts. + +### Subscribed Topics + +- `command` ([rktl_msgs/ControlCommand](/rktl_msgs/html/msg/ControlCommand.html)): + The car's desired movement, in terms of velocity and steering angle. +- `odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html)): Odometry data + of the car's position and velocity. + +### Published Topics + +- `effort` ([rktl_msgs/ControlEffort](/rktl_msgs/html/msg/ControlEffort.html)): + The car's desired movement, in terms of throttle and steering amount. + +### Parameters + +- `/cars/throttle/max_speed` (float): Maximum velocity for the car, in meters + per second. +- `/cars/steering/max_throw` (float): Maximum steering angle for the car, in + meters per second. +- `/cars/length` (float): Length of the car, in meters. +- `~limits/throttle/min` (float, default: `-1.0`): Min value for the car throttle. +- `~limits/throttle/max` (float, default: `1.0`): Max value for the car throttle. +- `~limits/steering/min` (float, default: `-1.0`): Min value for the car steering. +- `~limits/steering/max` (float, default: `1.0`): Max value for the car steering. +- `~open_loop/publish_early` (boolean, default: true): If true, data on the + `effort` topic will be published before the controller updates its internal + state. This means that the control effort message will be based on the + previous error and controller output values, rather than current error and + controller output values. +- `~controller_type` (string): One of `'lead_lag'`, `'pid'`, or `'none'`. Sets + the controller type to use a lead-lag controller, a PID controller, or no + controller, respectively. +- `~lead/gain` (float): Parameter for the lead-lag controller. +- `~lead/alpha` (float): Parameter for the lead-lag controller. +- `~lead/beta` (float): Parameter for the lead-lag controller. +- `~lag/alpha` (float): Parameter for the lead-lag controller. +- `~lag/beta` (float): Parameter for the lead-lag controller. +- `~pid/kp` (float): Parameter for the PID controller. +- `~pid/ki` (float): Parameter for the PID controller. +- `~pid/kd` (float): Parameter for the PID controller. +- `~pid/anti_windup` (float): Parameter for the PID controller. +- `~pid/deadband` (float): Parameter for the PID controller. +- `~rate` (float, default: `10.0`): Rate at which the `effort` topic is + published, in messages per second. + +--- + +## keyboard_interface + +Allows for controlling the car using a keyboard interface. Uses the terminal +(with ncurses) as an interface. + +### Published Topics + +- `effort` ([rktl_msgs/ControlEffort](/rktl_msgs/html/msg/ControlEffort.html)): + The car's desired movement, in terms of throttle and steering amount. + +--- + +## mean_odom_filter + +This is a very simple filter. If you have a stream of noisy measurements, +averaging the most recent $N$ measurements will give you a pretty good estimate. +This gets slightly complicated when handling angles, since they wrap around at +$\pm\pi$, but it still works. + +The downside is that if you average 10 measurements, your estimate is +time-delayed by 5 sampling periods. Therefore, a balance needs to be struck +between the desired noise reduction and the acceptable delay. + +This filter also runs into problems when taking derivatives of the input. Simply +taking the derivative of the two most recent measurements, filtered or +unfiltered, will result in significant noise. To combat this, the filter computes +derivatives for each pair of points (ex: $t-1$ and $t-2$, $t-2$ and $t-3$, $t-3$ +and $t-4$), then averages those velocity predictions using the same averaging +buffer algorithm. + +Overall, this filter is simple and works well enough for position as long as slight delay is acceptable. For velocity, it runs into problems since the noise is greater and the sampling frequency isn’t high enough to get a low delay signal. + +### Subscribed Topics + +- `pose_sync` ([geometry_msgs/PoseWithCovarianceStamped](/geometry_msgs/html/msg/PoseWithCovarianceStamped.html)): + The position, rotation, and timestamp of a given element on the field, + synchronized across all cameras. + +### Published Topics + +- `odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html)): Odometry data + of a field element's position and velocity. + +### Parameters + +- `~frame_ids/map` (string, default: `'map'`): Frame ID of the common reference + frame for all objects. In the context of the project, this is the frame + centered on the middle of the field, with the x-axis pointed towards a goal, + the y-axis pointing towards a sideline, and the z-axis pointed up. By + convention, this should be called `'map'`. +- `~frame_ids/body` (string, default: `'base_link'`): Frame ID of the object + being tracked. +- `~buffer_size/position` (int, default: `3`): Buffer size for the rolling + average for position. +- `~buffer_size/velocity` (int, default: `3`): Buffer size for the rolling + average for velocity. +- `~delay/compensate` (boolean, default: false): If true, the published odom is + extrapolated to a future time defined by `~delay/duration`. +- `~delay/duration` (float, default: `0.0`): The time, in seconds, in the future + that should be predicted. Requires `~delay/compensate` to be true to have + any effect. + +--- + +## particle_odom_filter + +This is a much more complex algorithm. The basic premise of why the algorithm is +useful is that by considering the noise in each individual measurement, not just +the mean value, there is more detail that can be used to improve the accuracy vs +delay trade off. Several similar algorithms were considered and are briefly +discussed below. + +The basic premise is that a particle filter has many different estimates of what +the car is doing and where it is (called a particle; perhaps 1,000 in this +application). For each new measurement that comes in: + +- Each and every one of these particles are simulated one time step (using a + bicycle model) to get a prediction of the current state of the particle +- For each particle, the question is asked, "Given this measurement and what I + know about it's standard deviation, what is the probability that this + particle is correct?" +- That result is used to compute a weighed average of all the particles. +- This average is then post processed a little bit to produce an odometry + estimate since the internal states don't exactly match + +This then repeats until the end of time. + +Initially, the particles are randomly distributed all over the field, but they +eventually converge (pretty quickly) to the real state of the car. To do this, +the filter will periodically delete bad particles, and replace them with new +random ones. These random ones are uniformly distributed if there isn't a good +guess of where the car is (like when the filter first starts), or distributed +normally about the most recent guess + +The specific state of the car is tracked by five-ish variables: + +- $x$, the $x$ location of the car's center of mass in the field's reference frame +- $y$, the $y$ location of the car's center of mass in the field's reference frame +- $\sin(\theta)$, the $y$ component of the car's heading angle in the field's + reference frame +- $\cos(\theta)$, the $x$ component of the car's heading angle in the field's + reference frame +- $v_{rear}$, the linear velocity of the rear tires of the car +- $\psi$, the steering angle (relative to the car's center) + +$\theta$ is split into two state variables to prevent issues with wrap around +and summation. + +From these, a kinematic bicycle model is used to calculate out everything needed +for an [odometry message](/nav_msgs/html/msg/Odometry.html). Basically, this +just assumes there is no side-slip by the tires and it uses a lot of +trigonometry. Details are in the MATLAB script [`scripts/bicycle_model.m`]. + +When advancing each particle one time-step, either the known control vector +(from listening to controller output) or a random control vector is used. If the +known vector is used, a small amount of random noise is added. If a completely +random one is used, they are uniformly distributed between actuator saturation +limits. From these, a new wheel velocity and steering angle are predicted +(using a 1st order and 0 order velocity model) and fed into the bicycle model. + +All parameters to the filter are defined in `config/particle_odom_filter.yaml`. +The relevant ones to tweak are: + +[Here](https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python/blob/master/12-Particle-Filters.ipynb) +is a good resource on particle filters for more information. + +### Subscribed Topics + +- `pose_sync` ([geometry_msgs/PoseWithCovarianceStamped](/geometry_msgs/html/msg/PoseWithCovarianceStamped.html)): + The position, rotation, and timestamp of the car, synchronized across all + cameras. +- `effort` ([rktl_msgs/ControlEffort](/rktl_msgs/html/msg/ControlEffort.html)): + The car's desired movement, in terms of throttle and steering amount. + +### Published Topics + +- `odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html)): Odometry data + of a field element's position and velocity. +- `odom_particles` ([geometry_msgs](/geometry_msgs/html/msg/PoseArray.html)): + Poses of all particles used in the filter. Useful for debugging. Only + published if `~publish_particles` is true. + +### Parameters + +- `/field/width` (float): Width of the playing field, in meters. +- `/field/length` (float): Length of the playing field, in meters. +- `/cars/length` (float): Length of the car, in meters. +- `/cars/throttle/max_speed` (float): Maximum speed of the car, in meters per + second. +- `/cars/throttle/tau` (float): The throttle time constant, in seconds. +- `/cars/steering/max_throw` (float): The maximum steering throw, in radians. +- `/cars/steering/rate` (float): The maximum steering rate, in radians per + second. +- `~frame_ids/map` (string, default: `'map'`): Frame ID of the common reference + frame for all objects. In the context of the project, this is the frame + centered on the middle of the field, with the x-axis pointed towards a goal, + the y-axis pointing towards a sideline, and the z-axis pointed up. By + convention, this should be called `'map'`. +- `~frame_ids/body` (string, default: `'base_link'`): Frame ID of the object + being tracked. +- `~rate` (float, default: `10.0`): Rate at which the `effort` topic is + published, in messages per second. +- `~supersampling` (int, default: `1`): Supersampling steps in the particle + dynamics calculation. +- `~publish_particles` (boolean, default: false): If true, poses of all + particles used in the filter are published on the `odom_particles` topic. +- `~allowable_latency` (float, default: `1.2`): Allowable latency used for the + watchdog timer for dropped pose messages. +- `~open_loop_limit` (int, default: `10`): Used in the watchdog timer for + dropped pose messages +- `~delay/compensate` (boolean, default: false): If true, the published odom is + extrapolated to a future time defined by `~delay/duration`. +- `~delay/duration` (float, default: `0.0`): The time, in seconds, in the future + that should be predicted. Requires `~delay/compensate` to be true to have + any effect. +- `~boundary_check` (boolean, default: false): If true, the filter artificially + punishes particles outside of the assumed field boundaries. +- `~num_particles` (int, default: `1000`): Number of particles used in the + filter. A higher number of particles should increase the accuracy of + the filter, but will consume higher computational resources. +- `~resample_proportion` (float, default: `0.1`): The percentage of particles + replaced with random guesses at every timestep. +- `~measurement_error/location` (float, default: `0.05`): Assumed standard + deviation of the perception data coming in. +- `~measurement_error/orientation` (float, default: $5^\circ$): Assumed standard + deviation of the perception data coming in. +- `~generator_noise/location` (float, default: `0.05`): Standard deviations of + the gaussian noise added. +- `~generator_noise/orientation` (float, default: `0.05`): Standard deviations + of the gaussian noise added. +- `~generator_noise/velocity` (float, default: `0.05`): Standard deviations of + the gaussian noise added. +- `~generator_noise/steering_angle` (float, default: $1^\circ$): Standard + deviations of the gaussian noise added. +- `~efforts/enable` (boolean, default: false): If true, the filter uses historic + effort data to get a more accurate idea of where the car is. +- `~efforts/buffer_size` (int, default: `0`): Buffer size of the buffer for + effort messages. +- `efforts/throttle/noise` (float, default: `0.05`): Standard deviation of + gaussian noise added. +- `efforts/steering/noise` (float, default: `0.05`): Standard deviation of + gaussian noise added. +- `~efforts/throttle/max` (float, default: `1.0`): Max value for the car throttle. +- `~efforts/throttle/min` (float, default: `-1.0`): Min value for the car throttle. +- `~efforts/steering/max` (float, default: `1.0`): Max value for the car steering. +- `~efforts/steering/min` (float, default: `-1.0`): Min value for the car steering. + +--- + +## pose_synchronizer + +Downsample the raw perception data to produce synchronized poses. + +For every topic defined by `~topics`, that topic is subscribed to and +republished at a rate defined by `~rate`. The name of the topic published +is the original name of the topic with `_sync` appended to the end. + +## Parameters + +- `~map_frame` (string, default: `'map'`): Frame ID of the common reference + frame for all objects. In the context of the project, this is the frame + centered on the middle of the field, with the x-axis pointed towards a goal, + the y-axis pointing towards a sideline, and the z-axis pointed up. By + convention, this should be called `'map'`. +- `~topics` (array): Array of topic names to synchronize. +- `~rate` (float, default: `10.0`): Rate at which the synchronized topics are + published, in messages per second. +- `~delay` (float, default: `0.15`): Rate at which the synchronized topics are + published, in messages per second. +- `~publish_latency` (boolean, default: false): If true, the latency from + synchronizing each topic is also published +- `~use_weights` (array) :Unused + +--- + +## topic_delay + +Delay an arbitrary ROS topic without modifying message + +--- + +## xbox_interface + +Allows for controlling the car using a joystick input, e.g. an Xbox controller. + +### Subscribed Topics + +- `joy` ([sensor_msgs/Joy](/sensor_msgs/html/msg/Joy.html)): State all buttons and + axes on the Xbox controller. + + +### Published Topics + +- `effort` ([rktl_msgs/ControlEffort](/rktl_msgs/html/msg/ControlEffort.html)): + The car's desired movement, in terms of throttle and steering amount. + +### Parameters + +- `~base_throttle` (float): Throttle when not boosting. +- `~boost_throttle` (float): Throttle when boosting. +- `~cooldown_ratio` (float): How long should one second of boost take to recharge? +- `~max_boost` (float): Max time boost can be active. + +--- diff --git a/rktl_control/nodes/controller b/rktl_control/nodes/controller index 760d1112d..a8d9053cb 100755 --- a/rktl_control/nodes/controller +++ b/rktl_control/nodes/controller @@ -1,5 +1,8 @@ #!/usr/bin/env python3 -"""Customizable controller for the car. +""" +Customizable controller for the car. It implements either a PID controller or a +lead-lag controller. + License: BSD 3-Clause License Copyright (c) 2023, Autonomous Robotics Club of Purdue (Purdue ARC) @@ -11,8 +14,10 @@ from nav_msgs.msg import Odometry from rktl_msgs.msg import ControlCommand, ControlEffort from math import atan, cos, sin + class PIDController(object): """A very basic PID controller.""" + def __init__(self, kp, ki, kd, anti_windup, deadband, delta_t): # Constants self.KP = kp @@ -48,8 +53,10 @@ class PIDController(object): self.last_error = 0.0 self.last_output = 0.0 + class LeadLagController(object): """A simple discrete lead-lag controller.""" + def __init__(self, k_lead, a_lead, b_lead, a_lag, b_lag): # Constants self.GAIN_LEAD = k_lead @@ -57,7 +64,7 @@ class LeadLagController(object): self.BETA_LEAD = b_lead self.ALPHA_LAG = a_lag self.BETA_LAG = b_lag - + # State variables self.prev_R_lead = 0.0 self.prev_R_lag = 0.0 @@ -80,8 +87,10 @@ class LeadLagController(object): self.prev_R_lead = 0.0 self.prev_R_lag = 0.0 + class Controller(object): """Controller for car.""" + def __init__(self): rospy.init_node('controller') @@ -160,8 +169,12 @@ class Controller(object): steering_effort = self.psi_ref / self.STEERING_THROW # enforce actuator saturation limits - throttle_effort = max(min(throttle_effort, self.MAX_THROTTLE_EFFORT), self.MIN_THROTTLE_EFFORT) - steering_effort = max(min(steering_effort, self.MAX_STEERING_EFFORT), self.MIN_STEERING_EFFORT) + throttle_effort = max( + min(throttle_effort, self.MAX_THROTTLE_EFFORT), + self.MIN_THROTTLE_EFFORT) + steering_effort = max( + min(steering_effort, self.MAX_STEERING_EFFORT), + self.MIN_STEERING_EFFORT) # publish actuator efforts msg = ControlEffort() @@ -170,5 +183,6 @@ class Controller(object): msg.steering = steering_effort self.pub.publish(msg) + if __name__ == "__main__": Controller() diff --git a/rktl_control/nodes/keyboard_interface b/rktl_control/nodes/keyboard_interface index 604c3d1bb..046daf46c 100755 --- a/rktl_control/nodes/keyboard_interface +++ b/rktl_control/nodes/keyboard_interface @@ -1,5 +1,8 @@ #!/usr/bin/env python3 -"""Use keyboard data to control car in sim. +""" +Allows for controlling the car using a keyboard interface. Uses the terminal +(with ncurses) as an interface. + License: BSD 3-Clause License Copyright (c) 2023, Autonomous Robotics Club of Purdue (Purdue ARC) @@ -13,6 +16,7 @@ from std_srvs.srv import Empty from curses import wrapper from time import sleep + def main(win): win.nodelay(True) throttle_effort = 0 @@ -58,8 +62,9 @@ def main(win): win.addstr("q to quit") sleep(0.01) -rospy.init_node('keyboard') -effort_pub = rospy.Publisher('effort', ControlEffort, queue_size=1) -reset_srv = rospy.ServiceProxy('/sim_reset', Empty) +if __name__ == "__main__": + rospy.init_node('keyboard') + effort_pub = rospy.Publisher('effort', ControlEffort, queue_size=1) + reset_srv = rospy.ServiceProxy('/sim_reset', Empty) -wrapper(main) + wrapper(main) diff --git a/rktl_control/nodes/mean_odom_filter b/rktl_control/nodes/mean_odom_filter index 90dd704a7..8d30256f5 100755 --- a/rktl_control/nodes/mean_odom_filter +++ b/rktl_control/nodes/mean_odom_filter @@ -1,5 +1,8 @@ #!/usr/bin/env python3 -"""Very simple node to estimate odometry from poses over time using a rolling average filter. +""" +Very simple node to estimate odometry from poses over time using a rolling +average filter. + License: BSD 3-Clause License Copyright (c) 2023, Autonomous Robotics Club of Purdue (Purdue ARC) @@ -16,8 +19,10 @@ from collections import deque from angles import shortest_angular_distance as sad from math import sin, cos, atan2 + class MeanOdomFilter(object): """Class to smooth pose estimations and predict velocity.""" + def __init__(self): rospy.init_node('mean_odom_filter') @@ -43,7 +48,7 @@ class MeanOdomFilter(object): def pose_cb(self, pose_msg): """Callback for new poses.""" - assert(pose_msg.header.frame_id == self.MAP_FRAME) + assert (pose_msg.header.frame_id == self.MAP_FRAME) # add sample to buffer t = pose_msg.header.stamp @@ -142,5 +147,6 @@ class MeanOdomFilter(object): return (avg_vx, avg_vy, avg_omega) + if __name__ == "__main__": - MeanOdomFilter() \ No newline at end of file + MeanOdomFilter() diff --git a/rktl_control/nodes/particle_odom_filter b/rktl_control/nodes/particle_odom_filter index e2121ef38..dd1434f83 100755 --- a/rktl_control/nodes/particle_odom_filter +++ b/rktl_control/nodes/particle_odom_filter @@ -1,5 +1,7 @@ #!/usr/bin/env python3 -"""Node to estimate odometry from poses over time using a Kalman filter. +""" +Node to estimate odometry from poses over time using a Particle filter. + License: BSD 3-Clause License Copyright (c) 2023, Autonomous Robotics Club of Purdue (Purdue ARC) @@ -19,8 +21,10 @@ from collections import deque from threading import Lock from math import sin, cos, tan, atan, sqrt, pi, exp + class ParticleOdomFilter(object): - """Class to estimate pose and velocity using Kalman filter.""" + """Class to estimate pose and velocity using Particle filter.""" + def __init__(self): rospy.init_node('particle_odom_filter') @@ -39,12 +43,14 @@ class ParticleOdomFilter(object): self.DELTA_T = rospy.Duration(1.0/rospy.get_param('~rate', 10.0)) self.SUPERSAMPLING = rospy.get_param('~supersampling', 1) self.PUB_PARTICLES = rospy.get_param('~publish_particles', False) - self.WATCHDOG_DELTA_T = self.DELTA_T * rospy.get_param('~allowable_latency', 1.2) + self.WATCHDOG_DELTA_T = self.DELTA_T * \ + rospy.get_param('~allowable_latency', 1.2) self.OPEN_LOOP_LIMIT = rospy.get_param('~open_loop_limit', 10) # should the filter compensate for delay by trying to predict the future? self.PREDICT_ENABLE = rospy.get_param('~delay/compensate', False) - self.PREDICT_TIME = rospy.Duration(rospy.get_param('~delay/duration', 0.0)) + self.PREDICT_TIME = rospy.Duration( + rospy.get_param('~delay/duration', 0.0)) # should the filter weigh particles based on a boundary check? boundary_check = rospy.get_param('~boundary_check', False) @@ -54,22 +60,30 @@ class ParticleOdomFilter(object): resample_proportion = rospy.get_param('~resample_proportion', 0.1) # standard deviation of incoming measurements used to assign particle weights - self.MEAS_LOC_STD_DEV = rospy.get_param('~measurement_error/location', 0.05) - self.MEAS_DIR_STD_DEV = rospy.get_param('~measurement_error/orientation', np.deg2rad(5)) + self.MEAS_LOC_STD_DEV = rospy.get_param( + '~measurement_error/location', 0.05) + self.MEAS_DIR_STD_DEV = rospy.get_param( + '~measurement_error/orientation', np.deg2rad(5)) # standard deviation when generating random states based off current guess - self.GEN_LOC_STD_DEV = rospy.get_param('~generator_noise/location', 0.05) - self.GEN_DIR_STD_DEV = rospy.get_param('~generator_noise/orientation', 0.05) - self.GEN_VEL_STD_DEV = rospy.get_param('~generator_noise/velocity', 0.05) - self.GEN_PSI_STD_DEV = rospy.get_param('~generator_noise/steering_angle', np.deg2rad(1)) + self.GEN_LOC_STD_DEV = rospy.get_param( + '~generator_noise/location', 0.05) + self.GEN_DIR_STD_DEV = rospy.get_param( + '~generator_noise/orientation', 0.05) + self.GEN_VEL_STD_DEV = rospy.get_param( + '~generator_noise/velocity', 0.05) + self.GEN_PSI_STD_DEV = rospy.get_param( + '~generator_noise/steering_angle', np.deg2rad(1)) # should the filter use historic effort data to get a more accurate idea of where the car is? use_efforts = rospy.get_param('~efforts/enable', False) effort_buffer_size = rospy.get_param('~efforts/buffer_size', 0) # standard deviation to add noise to effort when effort is known and enabled - self.THR_EFFORT_STD_DEV = rospy.get_param('~efforts/throttle/noise', 0.05) - self.STR_EFFORT_STD_DEV = rospy.get_param('~efforts/steering/noise', 0.05) + self.THR_EFFORT_STD_DEV = rospy.get_param( + '~efforts/throttle/noise', 0.05) + self.STR_EFFORT_STD_DEV = rospy.get_param( + '~efforts/steering/noise', 0.05) # max and min for uniform effort distribution when effort is not known or disabled self.MAX_THROTTLE = rospy.get_param('~efforts/throttle/max', 1.0) @@ -91,8 +105,8 @@ class ParticleOdomFilter(object): dynamics_fn=self.particle_dynamics_wrapper, observe_fn=self.particle_observation, weight_fn=self.particle_weight, - internal_weight_fn=self.particle_boundary_check if boundary_check else None, - n_particles=num_particles, + internal_weight_fn=self.particle_boundary_check + if boundary_check else None, n_particles=num_particles, resample_proportion=resample_proportion) self.filter.mean_state = None @@ -102,7 +116,8 @@ class ParticleOdomFilter(object): if use_efforts: rospy.Subscriber('effort', ControlEffort, self.effort_cb) if self.PUB_PARTICLES: - self.cloud_pub = rospy.Publisher('odom_particles', PoseArray, queue_size=1) + self.cloud_pub = rospy.Publisher( + 'odom_particles', PoseArray, queue_size=1) # main loop rospy.spin() @@ -119,10 +134,12 @@ class ParticleOdomFilter(object): return assert self.current_time is not None - rospy.loginfo("Dropped pose message detected, extrapolating with no measurement") + rospy.loginfo( + "Dropped pose message detected, extrapolating with no measurement") # set a new watchdog - self.watchdog = rospy.Timer(self.WATCHDOG_DELTA_T, self.watchdog_cb, True) + self.watchdog = rospy.Timer( + self.WATCHDOG_DELTA_T, self.watchdog_cb, True) # get the exact time since the watchdog was set set_time = timer_event.current_expected - self.WATCHDOG_DELTA_T @@ -140,7 +157,7 @@ class ParticleOdomFilter(object): def pose_cb(self, pose_msg): """Callback for new poses.""" - assert(pose_msg.header.frame_id == self.MAP_FRAME) + assert (pose_msg.header.frame_id == self.MAP_FRAME) # get observation from message x = pose_msg.pose.pose.position.x @@ -157,7 +174,8 @@ class ParticleOdomFilter(object): # reset the watchdog if self.watchdog is not None: self.watchdog.shutdown() - self.watchdog = rospy.Timer(self.WATCHDOG_DELTA_T, self.watchdog_cb, True) + self.watchdog = rospy.Timer( + self.WATCHDOG_DELTA_T, self.watchdog_cb, True) # initialize the current time (as one update ago) if needed if self.current_time is None: @@ -170,7 +188,8 @@ class ParticleOdomFilter(object): self.publish_odom() self.open_loop_count = 0 else: - rospy.logwarn("Incoming measurement out of sync. Possible watchdog runaway. Resetting filter. Consider turning down supersampling") + rospy.logwarn( + "Incoming measurement out of sync. Possible watchdog runaway. Resetting filter. Consider turning down supersampling") self.filter_reset() def publish_odom(self): @@ -196,9 +215,11 @@ class ParticleOdomFilter(object): # validate output if np.isnan(state).any(): - rospy.logwarn("Performing automatic filter reset due to NaN output") + rospy.logwarn( + "Performing automatic filter reset due to NaN output") self.filter_reset() - state = np.sum(self.filter.particles.T * self.filter.weights, axis=-1).T + state = np.sum( + self.filter.particles.T * self.filter.weights, axis=-1).T # calculate odometry from filter prediction beta = atan(tan(state[5]) / 2.0) @@ -255,7 +276,8 @@ class ParticleOdomFilter(object): assert self.lock.locked() self.filter.mean_state = None self.filter.init_filter() - self.filter.weights = np.ones(self.filter.n_particles) / self.filter.n_particles + self.filter.weights = np.ones( + self.filter.n_particles) / self.filter.n_particles self.effort_buffer.clear() self.current_time = None # kill the watchdog @@ -307,8 +329,8 @@ class ParticleOdomFilter(object): """Extrapolate all particles to future state, including random control noise.""" if controls is not None: # use the provided control noise - v_rear_ref = controls[:,0] - psi_ref = controls[:,1] + v_rear_ref = controls[:, 0] + psi_ref = controls[:, 1] else: # create random control noise using uniformly distributed efforts v_rear_ref = self.MAX_SPEED * self.rng.uniform( @@ -325,25 +347,26 @@ class ParticleOdomFilter(object): delta_t = (self.DELTA_T/self.SUPERSAMPLING).to_sec() # extract current states from particles matrix - x = particles[:,0] - y = particles[:,1] + x = particles[:, 0] + y = particles[:, 1] theta = np.arctan2( - particles[:,2], - particles[:,3]) - v_rear = particles[:,4] - psi = particles[:,5] + particles[:, 2], + particles[:, 3]) + v_rear = particles[:, 4] + psi = particles[:, 5] # update rear wheel velocity using 1st order model - v_rear = (v_rear - v_rear_ref) * exp(-delta_t/self.THROTTLE_TAU) + v_rear_ref + v_rear = ( + v_rear - v_rear_ref) * exp(-delta_t/self.THROTTLE_TAU) + v_rear_ref # update steering angle using massless acceleration to a fixed rate psi = np.where(np.abs(psi_ref - psi) < self.STEERING_RATE*delta_t, - psi_ref, - np.where(psi_ref > psi, - psi + self.STEERING_RATE*delta_t, - psi - self.STEERING_RATE*delta_t - ) - ) + psi_ref, + np.where(psi_ref > psi, + psi + self.STEERING_RATE*delta_t, + psi - self.STEERING_RATE*delta_t + ) + ) # using bicycle model, extrapolate future state return np.array([ @@ -358,21 +381,22 @@ class ParticleOdomFilter(object): """Calculate expected measurements for each particle.""" # measurement is x, y, theta return np.array([ - particles[:,0], - particles[:,1], + particles[:, 0], + particles[:, 1], np.arctan2( - particles[:,2], - particles[:,3]) + particles[:, 2], + particles[:, 3]) ]).T def particle_weight(self, expected, observed): """Weigh each particle based off difference between observed and expected measurements.""" # compute error (and minimize angles) error = expected - observed - error[:,2] = np.arctan2(np.sin(error[:,2]), np.cos(error[:,2])) + error[:, 2] = np.arctan2(np.sin(error[:, 2]), np.cos(error[:, 2])) # use a standard normal distribution to calculate probability of measurement given each particle - sigma = np.array([self.MEAS_LOC_STD_DEV, self.MEAS_LOC_STD_DEV, self.MEAS_DIR_STD_DEV]) + sigma = np.array( + [self.MEAS_LOC_STD_DEV, self.MEAS_LOC_STD_DEV, self.MEAS_DIR_STD_DEV]) base = 1.0 / (sigma * sqrt(2.0*pi)) prob_z_x = base * np.exp(np.square(error / sigma) / -2.0) # assume each state is independent @@ -387,8 +411,8 @@ class ParticleOdomFilter(object): def particle_boundary_check(self, particles, __): """Apply a boundary check as an additional multiplicative weight on each particle.""" return 1.0 * ( - 1.0 * (np.abs(particles[:,1]) < self.FIELD_HEIGHT/2.0) * - 1.0 * (np.abs(particles[:,2]) < self.FIELD_WIDTH/2.0)) + 1.0 * (np.abs(particles[:, 1]) < self.FIELD_HEIGHT/2.0) * + 1.0 * (np.abs(particles[:, 2]) < self.FIELD_WIDTH/2.0)) def particle_init(self, num_particles): """Initial guesses for particle states.""" @@ -426,7 +450,7 @@ class ParticleOdomFilter(object): (num_particles, 2)) random_orientation = self.rng.uniform( -pi, - pi, + pi, (num_particles, 1)) random_internal = self.rng.uniform( (-self.MAX_SPEED, @@ -441,5 +465,6 @@ class ParticleOdomFilter(object): random_internal), axis=1) + if __name__ == "__main__": - ParticleOdomFilter() \ No newline at end of file + ParticleOdomFilter() diff --git a/rktl_control/nodes/pose_synchronizer b/rktl_control/nodes/pose_synchronizer index 1be2d678e..c5db8db03 100755 --- a/rktl_control/nodes/pose_synchronizer +++ b/rktl_control/nodes/pose_synchronizer @@ -1,5 +1,7 @@ #!/usr/bin/env python3 -"""Downsample the raw perception data to produce synchronized poses. +""" +Downsample the raw perception data to produce synchronized poses. + License: BSD 3-Clause License Copyright (c) 2023, Autonomous Robotics Club of Purdue (Purdue ARC) @@ -13,10 +15,12 @@ from std_msgs.msg import Float32 from tf.transformations import euler_from_quaternion, quaternion_from_euler from collections import deque -from math import sin,cos, atan2 +from math import sin, cos, atan2 + class PoseSynchronizer(object): """Class to synchronize and buffer all poses.""" + def __init__(self): rospy.init_node('pose_synchronizer') @@ -27,23 +31,26 @@ class PoseSynchronizer(object): self.DELAY = rospy.Duration(rospy.get_param('~delay', 0.15)) self.PUB_LATENCY = rospy.get_param('~publish_latency', False) self.USE_WEIGHTS = { - topic : rospy.get_param('~use_weights')[i] for i, topic in enumerate(self.TOPICS) - } + topic: rospy.get_param('~use_weights')[i] for i, + topic in enumerate(self.TOPICS)} # variables self.buffers = { - topic : deque(maxlen=rospy.get_param('buffer_size', 15)) for topic in self.TOPICS - } + topic: deque(maxlen=rospy.get_param('buffer_size', 15)) + for topic in self.TOPICS} self.pubs = { - topic : rospy.Publisher(topic+'_sync', PoseWithCovarianceStamped, queue_size=1) for topic in self.TOPICS - } + topic: rospy.Publisher( + topic + '_sync', PoseWithCovarianceStamped, queue_size=1) + for topic in self.TOPICS} if self.PUB_LATENCY: self.latency_pubs = { - topic : rospy.Publisher(topic+'_sync_latency', Float32, queue_size=1) for topic in self.TOPICS - } + topic: rospy.Publisher( + topic + '_sync_latency', Float32, queue_size=1) + for topic in self.TOPICS} for topic in self.TOPICS: - rospy.Subscriber(topic, PoseWithCovarianceStamped, - lambda msg, topic=topic: self.recv_pose(topic, msg)) + rospy.Subscriber( + topic, PoseWithCovarianceStamped, lambda msg, + topic=topic: self.recv_pose(topic, msg)) # main loop rate = rospy.Rate(1/self.PERIOD.to_sec()) @@ -95,11 +102,14 @@ class PoseSynchronizer(object): t, x, y, yaw, weight = self.buffers[topic].popleft() # check if too old if t < now - self.DELAY - self.PERIOD/2: - rospy.logdebug("%s: discarding pose from %0.3f sec ago", topic, (now - t).to_sec()) + rospy.logdebug( + "%s: discarding pose from %0.3f sec ago", topic, + (now - t).to_sec()) # check if too new elif t > now - self.DELAY + self.PERIOD/2: self.buffers[topic].append((t, x, y, yaw, weight)) - rospy.logdebug("%s: skipping pose from %0.3f sec ago", topic, (now - t).to_sec()) + rospy.logdebug( + "%s: skipping pose from %0.3f sec ago", topic, (now - t).to_sec()) # add to averages else: avg_x += x * weight @@ -133,5 +143,6 @@ class PoseSynchronizer(object): pose_msg.pose.pose.orientation.w = w self.pubs[topic].publish(pose_msg) + if __name__ == "__main__": PoseSynchronizer() diff --git a/rktl_control/nodes/topic_delay b/rktl_control/nodes/topic_delay index 21b2a0be7..67e97cd16 100755 --- a/rktl_control/nodes/topic_delay +++ b/rktl_control/nodes/topic_delay @@ -1,18 +1,23 @@ #!/usr/bin/env python3 -"""Delay an arbitrary ROS topic without modifying message +""" +Delay an arbitrary ROS topic without modifying message + License: BSD 3-Clause License Copyright (c) 2023, Autonomous Robotics Club of Purdue (Purdue ARC) All rights reserved. """ -import rospy, roslib.message +import rospy +import roslib.message from collections import deque from time import sleep import sys + class Delay(object): """Class to delay arbitrary messages.""" + def __init__(self): # get args assert len(sys.argv) >= 5 @@ -45,5 +50,6 @@ class Delay(object): """Callback for enqueuing new message""" self.buffer.append((rospy.Time.now(), msg)) + if __name__ == "__main__": - Delay() \ No newline at end of file + Delay() diff --git a/rktl_control/nodes/xbox_interface b/rktl_control/nodes/xbox_interface index 8b9ee6618..0731a2b5c 100755 --- a/rktl_control/nodes/xbox_interface +++ b/rktl_control/nodes/xbox_interface @@ -1,5 +1,7 @@ #!/usr/bin/env python3 -"""Use joystick data to control car in sim. +""" +Use joystick data to control car in sim. + License: BSD 3-Clause License Copyright (c) 2023, Autonomous Robotics Club of Purdue (Purdue ARC) @@ -11,19 +13,25 @@ from rktl_msgs.msg import ControlEffort from std_srvs.srv import Empty from sensor_msgs.msg import Joy + class XboxInterface(): def __init__(self): rospy.init_node('xbox_interface') - self.base_throttle = rospy.get_param('~base_throttle') # throttle when not boosting - self.boost_throttle = rospy.get_param('~boost_throttle') # throttle when boosting - self.cooldown_ratio = rospy.get_param('~cooldown_ratio') # how long should one second of boost take to recharge? - self.max_boost = rospy.get_param('~max_boost') * self.cooldown_ratio # max time boost can be active - self.boost_tank = self.max_boost # this is how much boost is left - self.is_boosting = False # is the car currently boosting? + self.base_throttle = rospy.get_param( + '~base_throttle') # throttle when not boosting + self.boost_throttle = rospy.get_param( + '~boost_throttle') # throttle when boosting + # how long should one second of boost take to recharge? + self.cooldown_ratio = rospy.get_param('~cooldown_ratio') + # max time boost can be active + self.max_boost = rospy.get_param('~max_boost') * self.cooldown_ratio + self.boost_tank = self.max_boost # this is how much boost is left + self.is_boosting = False # is the car currently boosting? # Publishers - self.effort_pub = rospy.Publisher('effort', ControlEffort, queue_size=1) + self.effort_pub = rospy.Publisher( + 'effort', ControlEffort, queue_size=1) # Subscribers rospy.Subscriber('joy', Joy, self.callback) @@ -57,5 +65,6 @@ class XboxInterface(): msg.throttle *= self.base_throttle self.effort_pub.publish(msg) + if __name__ == "__main__": - XboxInterface() \ No newline at end of file + XboxInterface() From 60fd9f1e6c2ebc806667df11bc387c23302b1987 Mon Sep 17 00:00:00 2001 From: Daniel Gerblick Date: Sun, 23 Apr 2023 06:46:03 +0000 Subject: [PATCH 2/5] `rktl_perception` documentation --- docs/packages.rst | 2 +- docs/rktl_perception.md | 11 ++ docs/templates/launch_README.md | 17 ++- docs/templates/nodes_README.md | 12 ++- docs/templates/package_README.md | 5 +- rktl_perception/BallTracking.md | 31 ------ rktl_perception/README.md | 65 +----------- rktl_perception/launch/README.md | 86 +++++++++++++++ rktl_perception/nodes/README.md | 175 +++++++++++++++++++++++++++++++ rktl_perception/nodes/pose_to_tf | 5 +- rktl_perception/nodes/projector | 37 ++++--- 11 files changed, 327 insertions(+), 119 deletions(-) create mode 100644 docs/rktl_perception.md delete mode 100644 rktl_perception/BallTracking.md create mode 100644 rktl_perception/launch/README.md create mode 100644 rktl_perception/nodes/README.md diff --git a/docs/packages.rst b/docs/packages.rst index 32139a760..adc754e30 100644 --- a/docs/packages.rst +++ b/docs/packages.rst @@ -7,7 +7,7 @@ The repo is broken down into several .. toctree:: :caption: Package Contents - :maxdepth: 4 + :maxdepth: 2 :glob: rktl_* diff --git a/docs/rktl_perception.md b/docs/rktl_perception.md new file mode 100644 index 000000000..e1e857a9c --- /dev/null +++ b/docs/rktl_perception.md @@ -0,0 +1,11 @@ +```{include} ./rktl_perception/README.md +``` + +```{toctree} +:Caption: Package Contents +:maxdepth: 2 +:glob: + +./rktl_perception/*/README +Msg/Srv Documentation +``` diff --git a/docs/templates/launch_README.md b/docs/templates/launch_README.md index 6f6dbdf17..834a140a5 100644 --- a/docs/templates/launch_README.md +++ b/docs/templates/launch_README.md @@ -7,23 +7,30 @@ using [roslaunch](https://wiki.ros.org/roslaunch): roslaunch ``` -**Launch Files:** -- [`my_launch_file.launch`](#my-launch-file-launch) +:::{contents} Launch Files in the package +:depth: 2 +:backlinks: top +:local: true +::: --- ## rocket_league.launch -This roslaunch file launches launches multiple nodes or inlcudes other launch -files, while posisbly also taking some arguments and setting some parameters. + +This roslaunch file launches launches multiple nodes or includes other launch +files, while possibly also taking some arguments and setting some parameters. ### Launch Arguments -- `arg1` (default: `true`): A boolean argument that determines something. + +- `arg1` (default: true): A boolean argument that determines something. ### Nodes + - `node_name`: `foo` node from the `my_package` package - `node_namespace/node_name`: `bar` node from the `my_package` package ### Included Launch Files + - `my_package foo.launch` - `my_package bar.launch` (Only included if `arg1` is set to `true`) diff --git a/docs/templates/nodes_README.md b/docs/templates/nodes_README.md index b76640705..32fff24b8 100644 --- a/docs/templates/nodes_README.md +++ b/docs/templates/nodes_README.md @@ -8,24 +8,32 @@ by using `rosrun`: rosrun ``` -**Nodes:** -- [`node_name`](#node-name) +:::{contents} ROS Nodes in this package +:depth: 2 +:backlinks: top +:local: true +::: --- ## node_name + This node tracks does something that you should explain here. ### Subscribed Topics: + - `topic_foo` (my_pkg/MyMsg.msg): a topic that this node subscribes to ### Published Topics: + - `topic_bar` (my_pkg/MyMsg.msg): a topic that this node publishes to ### Services: + - `service_baz` (my_pkg/MySrv.srv): a service that does something ### Parameters: + - `param` (`int`, default: `1`): A parameter that can be set. --- diff --git a/docs/templates/package_README.md b/docs/templates/package_README.md index f72ab317b..f4f44a50a 100644 --- a/docs/templates/package_README.md +++ b/docs/templates/package_README.md @@ -1,5 +1,6 @@ -# rktl_pacakge +# rktl_package + This package does something probably. This file would named -`rktl_pacakge/README.md` and really not contain all that much. More detailed +`rktl_package/README.md` and really not contain all that much. More detailed information would be provided in the other READMEs for this package. This is designed to give a high-level overview of this package's functionality. diff --git a/rktl_perception/BallTracking.md b/rktl_perception/BallTracking.md deleted file mode 100644 index ad8b7473a..000000000 --- a/rktl_perception/BallTracking.md +++ /dev/null @@ -1,31 +0,0 @@ -

Ball Tracking

-The launch file is ball_detection_to_pose.launch. This should launch the code. - - -Inside this, you will find the paramaters for the color, as well as the value for the height above the field (currently not implemented). - -You should not need to mess with the min/max colors, but if you do, they are not on the same scale as a normal HSV color scale. - -Normally, hue is a number out of 360, specifically the degree on the color wheel, and the saturation and vibrance are percents, represending the percentage of the respective value. - -For OpenCV, these numbers are all represented on a scale of 0-255, so when adjusting this that will need to be kept in mind. - -ball_detection.cpp is the main file that runs the node, and it has a BallDetection class, along with a header file. - -This node publishes a PoseWithConvarianceStamped. It subscribes to the camera info as well as the picture. -

-Inside the launch file, there are a varity of paramaters, as listed below, along with their use: -
    -
  • originX and originY, which specify where the origin in in the camera, this needs to be determined before hand.
  • -
  • showImage, this boolean is whether or not you want OpenCV to display the camera image in a frame. Useful for debugging.
  • -
  • height, this is the height from the center of the ball to the camera sensor. The units of this number will be the units that the coordinate plane is in.
  • -
  • The range of these are specified above, they control the color of the object we are looking for.
  • -
      -
    • min_hue
    • -
    • min_sat
    • -
    • min_vib
    • -
    • max_hue
    • -
    • max_sat
    • -
    • max_vib
    • -
    -
diff --git a/rktl_perception/README.md b/rktl_perception/README.md index 7a630e7ad..5bf1500cb 100644 --- a/rktl_perception/README.md +++ b/rktl_perception/README.md @@ -1,65 +1,4 @@ -# The `rktl_perception` package +# rktl_perception This packages contains all nodes, launch files, and configuration files -associated with the -[`rocket_league`](https://github.com/purdue-arc/rocket_league/) project by -the [Purdue University Autonomous Robotics Club](https://www.purduearc.com/). - -## Nodes -### ball_detection -Uses color thresholding to find a vector pointing from the camera in the direction of the ball - -Params: -- `publishThresh` (bool): Whether or not to publish the image after thresholding is applied. Default: `false` -- `minHue` (int): The lower value of the hue to threshold on a 0 - 255 scale. Default: `60` -- `minSat` (int): The lower value of the saturation to threshold on a 0 - 255 scale. Default: `135` -- `minVib` (int): The lower value of the vibrance to threshold on a 0 - 255 scale. Default: `50` -- `maxHue` (int): The upper value of the hue to threshold on a 0 - 255 scale. Default: `150` -- `maxSat` (int): The upper value of the saturation to threshold on a 0 - 255 scale. Default: `225` -- `maxVib` (int): The upper value of the vibrance to threshold on a 0 - 255 scale. Default: `255` - -### focus_vis -Publishes a version of `image_color_rect` that has had Canny Edge Detection applied. - -### localizer -Calculates the location of all objects in the cameras' view. - -## Launch files -### camera.launch -This launch file launches all nodes and nodelets associcated with a single -camera. Most arguments can be safely ignored, with the exception of -`camera_name` - -To run: `roslaunch rktl_perception camera.launch` - -Arguments: -- `camera_name` (string): The name of the camera to be launched. All topics - will be published under this name, and configuration details will be loaded - from the `.yaml` with the same name from the `config` directory. See the - 'Configuration files' section for more information. Default: `aravis_cam`. -- `load_manager` (boolean): Whether or not a nodelet manager should be created - Only one nodelet manager should exist for all cameras. Default: `true`. -- `manager_name` (string): The name of the nodelet manager. If `load_manager` is - `true`, a nodelet manager is created with this name. If `load_manager` - is `false`, the nodelet manager with this name is used. Default: - `camera_manager`. -- `manager_threads` (integer): The number of threads used by the nodelet - manager, if created. Default: `4`. -- `launch_dynamic_reconfigure` (boolean): Whether or not `rqt_reconfigure` - should be launched (One instance of `rqt_reconfigure` is enough to - control all nodes that use it, including all cameras). Default: value of - `load_manager`. - -### focus_assist.launch -This launch file launches the four nodes that generate a Canny Edge Detection copy of every camera, as to aide in focusing the cameras properly. - -To run: `roslaunch rktl_perception focus_assist.launch` - -### cal.launch -This launch file launches a calibration node for each camera with the standard settions - -To run: `roslaunch rktl_perception cal.launch` - - -## Configuration files -Configuration files are located in the `config` directory. They contain configuration information for different cameras, inculding sensor information used by the GenICam standard and distortion/rectification/rectifcation matrices. \ No newline at end of file +associated with the perception stack. diff --git a/rktl_perception/launch/README.md b/rktl_perception/launch/README.md new file mode 100644 index 000000000..051fe320b --- /dev/null +++ b/rktl_perception/launch/README.md @@ -0,0 +1,86 @@ +# Launch Files + +These are [.launch files](https://wiki.ros.org/roslaunch/XML) that can be run +using [roslaunch](https://wiki.ros.org/roslaunch): + +```shell +roslaunch rktl_perception +``` + +:::{contents} Launch Files in this package +:depth: 2 +:backlinks: top +:local: true +::: + +--- + +## cal.launch + +Utility launch file that launches an interface for calibrating all cameras. It +is configured for a 9 squares by 7 squares chessboard pattern, where each square +is 26cm is length. + +--- + +## camera.launch + +Launch file containing everything that needs to be run for 1 camera. The +`camera_name` argument can be changed to easily change the camera used. + +### Launch Arguments + +- `load_manager` (default: true): If true, a nodelet manager is started. If a + nodelet manager is already running, set this to false to avoid any errors. +- `manager_name` (default: `camera_manager`): The name of the nodelet manager to + use for nodes that require it. +- `manager_threads` (default: `4`): Number of threads to use in the nodelet + manager, if started. +- `camera_name` (default: `cam0`): Name of the camera to launch the stack for. + +### Nodes + +- `cams/{camera_name}/{manager_name}`: [Nodelet](https://wiki.ros.org/nodelet) + manager. Only run if the `load_manager` argument is set to true. +- `cams/{camera_name}/{camera_name}`: [Nodelet](https://wiki.ros.org/nodelet) of type + [pointgrey_camera_driver/PointGreyCameraNodelet](https://wiki.ros.org/pointgrey_camera_driver). + Puts camera feed onto the ROS network. Loads parameters (including camera + serial number) from `rktl_perception/config/{camera_name}/pointgrey.yaml` + and calibration from `rktl_perception/config/{camera_name}/calibration.yaml`. +- `cams/{camera_name}/apriltag`: `apriltag_ros_continuous_node` node from the + [apriltag_ros](https://wiki.ros.org/apriltag_ros) package. Looks for + AprilTags in the camera feed and outputs the result to be used by other + nodes. Loads parameters from `rktl_perception/config/apriltag_settings.yaml` + and `rktl_perception/config/tags.yaml`. +- `localizer`: [`localizer`](../nodes/README.md#localizer) node from the + `rktl_perception` package. +- `pose_to_tf`: [`pose_to_tf`](../nodes/README.md#pose_to_tf) node from the + `rktl_perception` package. +- `ball_detection`: [`ball_detection`](../nodes/README.md#ball_detection) node + from the `rktl_perception` package. Loads parameters from + `rktl_perception/config/ball_settings.yaml`. + +### Included Launch Files + +- `image_proc image_proc.launch`: Basic processing stack (image rectification + for the provided camera). + +--- + +## color_picker.launch + +Utility launch file that opens a color picker used for fine tuning the parameters used for ball detection. + +--- + +## field_view.launch + +Utility launch file used for displaying the camera positions and feeds in RViz. + +--- + +## focus_assist.launch + +Utility launch file used launching the topics needed for focusing camera lenses. + +--- diff --git a/rktl_perception/nodes/README.md b/rktl_perception/nodes/README.md new file mode 100644 index 000000000..9a91dbc02 --- /dev/null +++ b/rktl_perception/nodes/README.md @@ -0,0 +1,175 @@ +# ROS Nodes + +These are the [ROS Nodes](http://wiki.ros.org/Nodes) provided by this package. +Most likely, you will use a launch file to run these. You can also run them +by using `rosrun`: + +``` +rosrun rktl_perception +``` + +:::{contents} ROS Nodes in this package +:depth: 2 +:backlinks: top +:local: true +::: + +--- + +## ball_detection + +C++ Node. Uses color thresholding to find a vector pointing from the camera in +the direction of the ball. + +### Subscribed Topics + +- `image_rect_color` ([image_transport Camera](https://wiki.ros.org/image_transport)): + Full-color camera feed. + +### Published Topics + +- `ball_vec` ([geometry_msgs/Vector3Stamped](/geometry_msgs/html/msg/Vector3Stamped.html#http://)): + The $x$ and $y$ components of the vector comprise the the unit vector which + passes from the camera center to the detected ball. The $z$ component is + the largest contour area detected (the size of the ball as it appears to + the camera). +- `threshold_img` ([image_transport Camera](https://wiki.ros.org/image_transport)): + The black-and-white output of the thresholding. Only published to if the + `publishThresh` parameter is set to true. + +### Parameters + +- `publishThresh` (bool, default: false): Whether or not to publish the image + after thresholding is applied. +- `minHue` (int, default: `60`): The lower value of the hue to threshold on a + 0 - 255 scale. +- `minSat` (int, default: `135`): The lower value of the saturation to + threshold on a 0 - 255 scale. +- `minVib` (int, default: `50`): The lower value of the vibrance to threshold + on a 0 - 255 scale. +- `maxHue` (int, default: `150`): The upper value of the hue to threshold on a + 0 - 255 scale. +- `maxSat` (int, default: `225`): The upper value of the saturation to + threshold on a 0 - 255 scale. +- `maxVib` (int, default: `255`): The upper value of the vibrance to threshold + on a 0 - 255 scale. + +--- + +## focus_vis + +C++ Node. Publishes a version of `image_color_rect` that has had Canny Edge +Detection applied. Useful when using a +[siemens star](https://en.wikipedia.org/wiki/Siemens_star) to get the focus of +the camera just right. + +### Subscribed Topics + +- `image_rect_color` ([image_transport Camera](https://wiki.ros.org/image_transport)): + Full-color camera feed. + +### Published Topics + +- `edge_dectection` ([image_transport Camera](https://wiki.ros.org/image_transport)): + The black-and-white output of the edge detection. + +--- + +## localizer + +C++ Node. Calculates the location of all objects in the cameras' view. +Republishes AprilTag and ball detections (received in "camera space") into a +common reference frame for all cameras (referred to as "world space"). The +measurements used to put the camera into world space are "averaged out" over a +series of measurements to reduce noise. + +Multiple topics are published to, given by the `pub_topics` parameter. This +parameter is interpreted as key/value pairs, where the key is an +[AprilTag](https://wiki.ros.org/apriltag_ros) ID or the IDs of an AprilTag +bundle and the value is the name of the topic that should be published to. In +the case of a bundle, the tag IDs are given in ascending order, delimited by +commas (e.g. `"0,1,2,3"`). + +For the inclined, "camera space" is defined as the space whose origin is defined +as the center of the camera, where the $x$-axis points to the right of the +image, the $y$-axis points towards the top of the image, and the camera looks +down the positive $z$-axis (this is the same convention that OpenCV uses). +"World space" is defined as the space whose origin is the center of the field, +where the $x$-axis points towards the "right-hand" goals, the $y$-axis points +towards the "top" sideline, and the $z$-axis points directly up. + +### Subscribed Topics + +- `tag_detections` ([apriltag_ros/AprilTagDetectionArray](/apriltag_ros/html/msg/AprilTagDetectionArray.html#http://)): + Output of an AprilTag detection node. The name of this topic can be easily + adjusted by modifying the `dectection_topic` parameter. +- `ball_vector` ([geometry_msgs/Vector3Stamped](/geometry_msgs/html/msg/Vector3Stamped.html#http://)): + Output of the [`ball_detection`](#ball-detection) node. The name of this + topic can be easily adjusted by modifying the `ball_sub_topic` parameter. + +### Published Topics + +- `{pub_topic}` ([geometry_msgs/PoseWithCovarianceStamped](/geometry_msgs/html/msg/PoseWithCovarianceStamped.html#http://)): + The position/orientation of the camera in world space. +- `{pub_topics.values}` ([geometry_msgs/PoseWithCovarianceStamped](/geometry_msgs/html/msg/PoseWithCovarianceStamped.html#http://)): + The position/orientation of the given objects in world space. `pub_topics` + is a dictionary (`key`/`value` pairs) where each detections of AprilTag + with ID `key` is published on the topic named `value`. + +### Parameters + +- `dectection_topic` (string, default: `"tag_detections"`): Name of topic + subscribed to, published to by an AprilTag detection node. +- `origin_id` (string, default: `"0"`): ID of the AprilTag or AprilTag bundle + that defines the origin of world space, i.e. the center of the field. +- `pub_topic` (string) Topic name to publish camera pose to. +- `pub_topics` (dictionary): `key`/`value` pairs where each detections of + AprilTag with ID `key` is published on the topic named `value`. +- `ball_sub_topic` (string, default: `"ball_vector"`): Name of topic + subscribed to, published to by a [`ball_detection`](#ball-detection) node. +- `ball_pub_topic` (string, default: `"ball_pos"`): Name of topic + published containing the position of the ball in world space. +- `ball_radius` (float, default: `0.05`): Radius of the ball, in meters. +- `buffer_size` (int, default: `10`): Number of elements used in the "averaging" + of the camera pose. +- `queue_size` (int, default: `100`): Size of the the queue for the publishers. + +--- + +## pose_to_tf + +Publishes an output of the [localizer](#localizer) node onto the [tf tree](https://wiki.ros.org/tf2). + +### Subscribed Topics + +- `pose` ([geometry_msgs/PoseWithCovarianceStamped](/geometry_msgs/html/msg/PoseWithCovarianceStamped.html#http://)): + Data to republish onto the TF tree. + +### Parameters + +- `~cam_frame_id` (string, default: `"cam0"`): Frame ID of the camera. + +--- + +## projector + +Create a depth map to project camera data onto ground plane. + +### Subscribed Topics + +- `projector` ([sensor_msgs/CameraInfo](/sensor_msgs/html/msg/CameraInfo.html#http://)): + Camera Info, containing the projection matrix used to re-project the image + onto the plane. + +### Published Topics + +- `depth_rect` ([sensor_msgs/Image](/sensor_msgs/html/msg/Image.html#http://)): + Calculated depth of each pixel in the camera. + +### Parameters + +- `~ground_height` (float, default: `0.0`): Height of the ground, in meters. +- `~update_period` (float, default: `1`): Rate at which to re-compute depth map, + in updates per second. + +--- diff --git a/rktl_perception/nodes/pose_to_tf b/rktl_perception/nodes/pose_to_tf index ac9f7f927..94737211b 100755 --- a/rktl_perception/nodes/pose_to_tf +++ b/rktl_perception/nodes/pose_to_tf @@ -11,8 +11,10 @@ import rospy from geometry_msgs.msg import PoseWithCovarianceStamped, TransformStamped from tf2_ros import TransformBroadcaster + class Publisher(object): """Workaround class until TF is implemented""" + def __init__(self): rospy.init_node('pose_to_tf') @@ -36,5 +38,6 @@ class Publisher(object): tf.transform.rotation.w = pose_msg.pose.pose.orientation.w self.broadcaster.sendTransform(tf) + if __name__ == "__main__": - Publisher() \ No newline at end of file + Publisher() diff --git a/rktl_perception/nodes/projector b/rktl_perception/nodes/projector index 4e6bb85e5..ba861deb8 100755 --- a/rktl_perception/nodes/projector +++ b/rktl_perception/nodes/projector @@ -14,8 +14,10 @@ from tf.transformations import translation_matrix, quaternion_matrix import numpy as np + class Projector(object): """Class to synchronize and buffer all poses.""" + def __init__(self): rospy.init_node('projector') self.depth_pub = rospy.Publisher('depth_rect', Image, queue_size=1) @@ -50,7 +52,8 @@ class Projector(object): # get camera location via TF tree try: - map_to_cam_msg = buffer.lookup_transform(self.frame_id, 'map', rospy.Time()) + map_to_cam_msg = buffer.lookup_transform( + self.frame_id, 'map', rospy.Time()) except: continue @@ -65,11 +68,15 @@ class Projector(object): map_to_cam_msg.transform.rotation.z, map_to_cam_msg.transform.rotation.w]) # create transformation matrix - map_to_cam = translation_matrix(translation) @ quaternion_matrix(quaternion) + map_to_cam = translation_matrix( + translation) @ quaternion_matrix(quaternion) # ground plane in map space (X direction, Y direction, origin point) # any [a,b,1].T input results in a point on the ground plane - ground_plane = np.array([[1, 0, 0, 0], [0, 1, 0, 0], [0, 0, self.GROUND_HEIGHT, 1]]).T + ground_plane = np.array( + [[1, 0, 0, 0], + [0, 1, 0, 0], + [0, 0, self.GROUND_HEIGHT, 1]]).T # depth * [u,v,1].T = cam_to_img x map_to_cam x ground_plane x [a,b,1].T # [u,v,1].T = cam_to_img x map_to_cam x ground_plane x [A,B,1/depth].T @@ -77,23 +84,24 @@ class Projector(object): # create matrix of all pixels w = self.width h = self.height - u = np.arange(stop=w).reshape((1,w,1,1)) - v = np.arange(stop=h).reshape((h,1,1,1)) + u = np.arange(stop=w).reshape((1, w, 1, 1)) + v = np.arange(stop=h).reshape((h, 1, 1, 1)) - u = np.broadcast_to(u, (h,w,1,1)) - v = np.broadcast_to(v, (h,w,1,1)) - one = np.broadcast_to(1, (h,w,1,1)) + u = np.broadcast_to(u, (h, w, 1, 1)) + v = np.broadcast_to(v, (h, w, 1, 1)) + one = np.broadcast_to(1, (h, w, 1, 1)) - img = np.concatenate((u,v,one), axis=2) + img = np.concatenate((u, v, one), axis=2) # reshape matrix - mat = (self.cam_to_img @ map_to_cam @ ground_plane).reshape((1,1,3,3)) - mat = np.broadcast_to(mat, (h,w,3,3)) + mat = (self.cam_to_img @ map_to_cam @ + ground_plane).reshape((1, 1, 3, 3)) + mat = np.broadcast_to(mat, (h, w, 3, 3)) # solve for all pixels at once depth = np.linalg.solve(mat, img) # extract depth - depth = 1.0/(depth[:,:,2,0].reshape((h,w))) + depth = 1.0/(depth[:, :, 2, 0].reshape((h, w))) # create message if self.img_msg is None: @@ -118,7 +126,7 @@ class Projector(object): self.frame_id = info_msg.header.frame_id self.width = info_msg.width self.height = info_msg.height - self.cam_to_img = np.array(info_msg.P).reshape((3,4)) + self.cam_to_img = np.array(info_msg.P).reshape((3, 4)) self.initialized = True # publish latest depth map @@ -126,5 +134,6 @@ class Projector(object): self.img_msg.header.stamp = info_msg.header.stamp self.depth_pub.publish(self.img_msg) + if __name__ == "__main__": - Projector() \ No newline at end of file + Projector() From e41a907e6bc34b750726e7d260c268e16bd3f3c7 Mon Sep 17 00:00:00 2001 From: Daniel Gerblick Date: Sun, 23 Apr 2023 07:13:29 +0000 Subject: [PATCH 3/5] README style consistency --- rktl_autonomy/README.md | 1 + rktl_autonomy/launch/README.md | 12 ++--- rktl_autonomy/nodes/README.md | 62 +++++++++++++----------- rktl_autonomy/scripts/README.md | 29 ++++++++++++ rktl_control/firmware/README.md | 8 ++-- rktl_control/launch/README.md | 23 +++++---- rktl_control/nodes/README.md | 56 +++++++++++----------- rktl_game/nodes/README.md | 16 +++++-- rktl_launch/launch/README.md | 30 ++++++++---- rktl_planner/README.md | 3 +- rktl_planner/launch/README.md | 14 ++++-- rktl_planner/nodes/README.md | 70 +++++++++++++-------------- rktl_sim/README.md | 5 +- rktl_sim/launch/README.md | 12 +++-- rktl_sim/nodes/README.md | 83 +++++++++++++++++---------------- 15 files changed, 246 insertions(+), 178 deletions(-) diff --git a/rktl_autonomy/README.md b/rktl_autonomy/README.md index eaef6c237..51c4f2b67 100644 --- a/rktl_autonomy/README.md +++ b/rktl_autonomy/README.md @@ -1,4 +1,5 @@ # rktl_autonomy + This package provides all code required to train a neural network to drive the car and interface it into the existing control structure. It also provides equivalent interfaces for two other environments (snake game and cartpole) for diff --git a/rktl_autonomy/launch/README.md b/rktl_autonomy/launch/README.md index fa13a3d85..4d7f67601 100644 --- a/rktl_autonomy/launch/README.md +++ b/rktl_autonomy/launch/README.md @@ -7,13 +7,11 @@ using [roslaunch](https://wiki.ros.org/roslaunch): roslaunch rktl_autonomy ``` -**Launch Files:** - -- [`cartpole_train.launch`](#cartpole-train-launch) -- [`rocket_league_agent.launch`](#rocket-league-agent-launch) -- [`rocket_league_train.launch`](#rocket-league-train-launch) -- [`snake_eval.launch`](#snake-eval-launch) -- [`snake_train.launch`](#snake-train-launch) +:::{contents} Launch Files in the package +:depth: 2 +:backlinks: top +:local: true +::: --- diff --git a/rktl_autonomy/nodes/README.md b/rktl_autonomy/nodes/README.md index 6a84c4926..213609305 100644 --- a/rktl_autonomy/nodes/README.md +++ b/rktl_autonomy/nodes/README.md @@ -8,12 +8,11 @@ by using `rosrun`: rosrun rktl_autonomy ``` -**Nodes:** - -- [`cartpole_env`](#cartpole-env) -- [`plotter`](#plotter) -- [`rocket_league_agent`](#rocket-league-agent) -- [`snake_agent`](#snake-agent) +:::{contents} ROS Nodes in the package +:depth: 2 +:backlinks: top +:local: true +::: --- @@ -30,15 +29,17 @@ respectively. ### Subscribed Topics -- `cartpole/action` (std_msgs/Int32): The action that should be performed. +- `cartpole/action` ([std_msgs/Int32](/std_msgs/html/msg/Int32.html#http://)): + The action that should be performed. ### Published Topics -- `cartpole/observation` (std_msgs/Float32MultiArray): Observation of the system - at any given point. -- `cartpole/reward` (std_msgs/Float32): Reward for training. -- `cartpole/done` (std_msgs/Bool): Boolean representing the whether or not the - simulation is complete. +- `cartpole/observation` ([std_msgs/Float32MultiArray](/std_msgs/html/msg/Float32MultiArray.html#http://)): + Observation of the system at any given point. +- `cartpole/reward` ([std_msgs/Float32](/std_msgs/html/msg/Float32.html#http://)): + Reward for training. +- `cartpole/done` ([std_msgs/Bool](/std_msgs/html/msg/Bool.html#http://)): + Boolean representing the whether or not the simulation is complete. --- @@ -51,7 +52,8 @@ saved as a PNG image file. ### Subscribed Topics -- `~log` (diagnostic_msgs/DiagnosticStatus): Log for the training algorithm. +- `~log` ([diagnostic_msgs/DiagnosticStatus](/diagnostic_msgs/html/msg/DiagnosticStatus.html#http://)): + Log for the training algorithm. ### Parameters @@ -75,16 +77,17 @@ This node runs the agent trained for the Rocket League project. It uses the ### Subscribed Topics -- `cars/car0/odom` (nav_msgs/Odometry): Odometry data of the car's position and - velocity. -- `ball/odom` (nav_msgs/Odometry): Odometry data of the car's position and - velocity. -- `match_status` (rktl_msgsMatchStatus): Match status data containing the - current score of the game. +- `cars/car0/odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html#http://)): + Odometry data of the car's position and velocity. +- `ball/odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html#http://)): + Odometry data of the car's position and velocity. +- `match_status` ([rktl_msgs/MatchStatus](/rktl_msgs/html/msg/MatchStatus.html#http://)): + Match status data containing the current score of the game. ### Published Topics -- `/cars/car0/command` (rktl_msgs/ControlCommand): Control commands for the car. +- `/cars/car0/command` ([rktl_msgs/ControlCommand](/rktl_msgs/html/msg/ControlCommand.html#http://)): + ontrol commands for the car. ### Parameters @@ -135,24 +138,29 @@ This node runs the agent trained for the snake environment. It uses the ### Subscribed Topics -- `snake/pose` (geometry_msgs/PoseArray): Pose of the snake parts. -- `snake/goal` (geometry_msgs/PointStamped): Location of the apple. -- `snake/score` (std_msgs/Int32): Current Score. -- `snake/active` (std_msgs/Bool): Whether or not the snake is active. +- `snake/pose` ([geometry_msgs/PoseArray](/geometry_msgs/html/msg/PoseArray.html#http://)): + Pose of the snake parts. +- `snake/goal` ([geometry_msgs/PointStamped](/geometry_msgs/html/msg/PointStamped.html#http://)): + Location of the apple. +- `snake/score` ([std_msgs/Int32](/std_msgs/html/msg/Int32.html#http://)): + Current Score. +- `snake/active` ([std_msgs/Bool](/std_msgs/html/msg/Bool.html#http://)): + Whether or not the snake is active. ### Published Topics -- `snake/cmd_vel` (geometry_msgs/Twist): Command for the snake to follow. +- `snake/cmd_vel` ([geometry_msgs/Twist](/geometry_msgs/html/msg/Twist.html#http://)): + Command for the snake to follow. ### Parameters -- `~num_segments` (int, default: 7): Inital number of segments of the snake. +- `~num_segments` (int, default: 7): Initial number of segments of the snake. - `~field_size` (float, default: 10): Size of the field. - `~control/max_angular_velocity` (float, default: 3.0): Max angular velocity. - `~control/max_linear_velocity` (float, default: 3.0): Max velocity. - `~reward/death` (float, default: 0.0): Penalty for death. - `~reward/goal` (float, default: 50.0): Reward for eating an apple. -- `~reward/distance` (float, default: 0.0): Reward for distance travelled. +- `~reward/distance` (float, default: 0.0): Reward for distance traveled. - `~reward/constant` (float, default: 0.0): Constant reward. - `~max_episode_time` (float, default: 30.0): Maximum time in seconds for an episode. diff --git a/rktl_autonomy/scripts/README.md b/rktl_autonomy/scripts/README.md index 5b44c3856..5e401602d 100644 --- a/rktl_autonomy/scripts/README.md +++ b/rktl_autonomy/scripts/README.md @@ -1,4 +1,5 @@ # Training Scripts + These are python scripts used to train the neural network. Each script basically does everything to get an agent training. It will generate a UUID (used for logging weights / progress), build the environment(s) (which will internally @@ -11,7 +12,16 @@ several different types of agents. **You should not manually use any ROS commands when launching for training.** +:::{contents} Training scripts in the package +:depth: 2 +:backlinks: top +:local: true +::: + +--- + ## eval_rocket_league.py + If you want to evaluate a bunch of models at once, to produce a plot of performance over time (perhaps with a different environment or reward set from what it was trained on), you can use the this convenience script: @@ -30,7 +40,10 @@ For each UUID passed in, the script will generate a file in the same folder titled `eval_log_.txt`. This is a tab-delimited file, which you can open in Matlab or Excel to produce a plot. +--- + ## train_batch.sh + This script exists to simplify the process of checking out the proper code, launching a Docker container, and running the above training script when many different experiments are intended to be run simultaneously. To use, simply @@ -41,16 +54,30 @@ useful), then run the following command on the machine: ./rktl_autonomy/scripts/train_batch.sh ``` +--- + ## train_cartpole.py + Training script for the `CartPoleInterface` for testing. +--- + ## train_rocket_league.py + +--- + Training script for the Rocket League project. +--- + ## train_snake.py + Training script for the Snake game in ARC tutorials. +--- + ## tune_rocket_league.py + This script will take the current game settings (rewards, episode length, simulation parameters) as is, and only experiment with hyperparameters of the PPO model. @@ -68,3 +95,5 @@ The tuning script will output progress in the command window it was executed in. Every 5 tuning attempts, it will print out the best hyperparameters that it has found so far. These can later be copied and used in the `train_rocket_league.py` script. + +--- diff --git a/rktl_control/firmware/README.md b/rktl_control/firmware/README.md index a522a310e..2f67a474f 100644 --- a/rktl_control/firmware/README.md +++ b/rktl_control/firmware/README.md @@ -3,9 +3,11 @@ This folder contains all firmware that is written to microcontollers for the project. -**Firmwares:** - -- [`hardware_interface`](#hardware-interface) +:::{contents} Firmwares in the package +:depth: 2 +:backlinks: top +:local: true +::: --- diff --git a/rktl_control/launch/README.md b/rktl_control/launch/README.md index a30ae8cab..fc706350c 100644 --- a/rktl_control/launch/README.md +++ b/rktl_control/launch/README.md @@ -7,13 +7,11 @@ using [roslaunch](https://wiki.ros.org/roslaunch): roslaunch rktl_control ``` -**Launch Files:** - -- [`ball.launch`](#ball-launch) -- [`car.launch`](#car-launch) -- [`hardware_interface.launch`](#hardware-interface-launch) -- [`keyboard_control.launch`](#keyboard-control-launch) -- [`xbox_control.launch`](#xbox-control-launch) +:::{contents} Launch Files in the package +:depth: 2 +:backlinks: top +:local: true +::: --- @@ -54,11 +52,12 @@ Parameters are provided by `rktl_control/config/particle_odom_filter.yaml` or - `mean_odom_filter`: [`mean_odom_filter`](../nodes/README.md#mean-odom-filter) node from the - [`rktl_control`](../README.md) package. Only run if `use_particle_filter` is set to false. Parameters supplied by - `rktl_control/config/mean_odom_filter.yaml`. + [`rktl_control`](../README.md) package. Only run if `use_particle_filter` is + set to false. Parameters supplied by `rktl_control/config/mean_odom_filter.yaml`. - `particle_odom_filter`: - [`particle_odom_filter`](../nodes/README.md#particle-odom-filter) node from the - [`rktl_control`](../README.md) package. Only run if `use_particle_filter` is set to true (the default). Parameters supplied by + [`particle_odom_filter`](../nodes/README.md#particle-odom-filter) node from + the [`rktl_control`](../README.md) package. Only run if `use_particle_filter` + is set to true (the default). Parameters supplied by `rktl_control/config/particle_odom_filter.yaml`. - `controller`: [`controller`](../nodes/README.md#controller) node from the [`rktl_control`](../README.md) package. Parameters supplied by @@ -68,7 +67,7 @@ Parameters are provided by `rktl_control/config/particle_odom_filter.yaml` or ## hardware_interface.launch -This takes a [rktl_msgs/ControlEffort](/rktl_msgs/html/msg/ControlEffort.html) +This takes a [rktl_msgs/ControlEffort](/rktl_msgs/html/msg/ControlEffort.html#http://) message and sends it to a physical car. The efforts in the message range from -1.0 to +1.0 corresponding to full reverse for full forward motor speed, or full left or full right steering angle respectively. Technically, you can also diff --git a/rktl_control/nodes/README.md b/rktl_control/nodes/README.md index 2ed410b8e..1ae03598b 100644 --- a/rktl_control/nodes/README.md +++ b/rktl_control/nodes/README.md @@ -8,15 +8,11 @@ by using `rosrun`: rosrun rktl_control ``` -**Nodes:** - -- [`controller`](#controller) -- [`keyboard_interface`](#keyboard-interface) -- [`mean_odom_filter`](#mean-odom-filter) -- [`particle_odom_filter`](#particle-odom-filter) -- [`pose_synchronizer`](#pose-synchronizer) -- [`topic_delay`](#topic-delay) -- [`xbox_interface`](#xbox-interface) +:::{contents} ROS Nodes in the package +:depth: 2 +:backlinks: top +:local: true +::: --- @@ -27,11 +23,11 @@ lead-lag controller. The controller is responsible for making the car do what you tell it to do. Simply, that means you give it a -[`ControlCommand.msg`](/rktl_msgs/html/msg/ControlCommand.html) and it produces -a [`ControlEffort.msg`](/rktl_msgs/html/msg/ControlEffort.html) that makes the -car follow it. At a basic level, it uses the odometry produced by the filter and -tries to minimize the error between what you want the car to do and what it is -actually doing. +[`ControlCommand.msg`](/rktl_msgs/html/msg/ControlCommand.html#http://) and it +produces a [`ControlEffort.msg`](/rktl_msgs/html/msg/ControlEffort.html#http://) +that makes the car follow it. At a basic level, it uses the odometry produced by +the filter and tries to minimize the error between what you want the car to do +and what it is actually doing. The incoming message is different from the outgoing message because it is taking a desired motion that could be for any mechanism, and it is converting it to @@ -64,14 +60,14 @@ These are all by Brian Douglas, who has many useful videos on control concepts. ### Subscribed Topics -- `command` ([rktl_msgs/ControlCommand](/rktl_msgs/html/msg/ControlCommand.html)): +- `command` ([rktl_msgs/ControlCommand](/rktl_msgs/html/msg/ControlCommand.html#http://)): The car's desired movement, in terms of velocity and steering angle. -- `odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html)): Odometry data - of the car's position and velocity. +- `odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html#http://)): + Odometry data of the car's position and velocity. ### Published Topics -- `effort` ([rktl_msgs/ControlEffort](/rktl_msgs/html/msg/ControlEffort.html)): +- `effort` ([rktl_msgs/ControlEffort](/rktl_msgs/html/msg/ControlEffort.html#http://)): The car's desired movement, in terms of throttle and steering amount. ### Parameters @@ -115,7 +111,7 @@ Allows for controlling the car using a keyboard interface. Uses the terminal ### Published Topics -- `effort` ([rktl_msgs/ControlEffort](/rktl_msgs/html/msg/ControlEffort.html)): +- `effort` ([rktl_msgs/ControlEffort](/rktl_msgs/html/msg/ControlEffort.html#http://)): The car's desired movement, in terms of throttle and steering amount. --- @@ -142,14 +138,14 @@ Overall, this filter is simple and works well enough for position as long as sli ### Subscribed Topics -- `pose_sync` ([geometry_msgs/PoseWithCovarianceStamped](/geometry_msgs/html/msg/PoseWithCovarianceStamped.html)): +- `pose_sync` ([geometry_msgs/PoseWithCovarianceStamped](/geometry_msgs/html/msg/PoseWithCovarianceStamped.html#http://)): The position, rotation, and timestamp of a given element on the field, synchronized across all cameras. ### Published Topics -- `odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html)): Odometry data - of a field element's position and velocity. +- `odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html#http://)): + Odometry data of a field element's position and velocity. ### Parameters @@ -217,7 +213,7 @@ $\theta$ is split into two state variables to prevent issues with wrap around and summation. From these, a kinematic bicycle model is used to calculate out everything needed -for an [odometry message](/nav_msgs/html/msg/Odometry.html). Basically, this +for an [odometry message](/nav_msgs/html/msg/Odometry.html#http://). Basically, this just assumes there is no side-slip by the tires and it uses a lot of trigonometry. Details are in the MATLAB script [`scripts/bicycle_model.m`]. @@ -236,17 +232,17 @@ is a good resource on particle filters for more information. ### Subscribed Topics -- `pose_sync` ([geometry_msgs/PoseWithCovarianceStamped](/geometry_msgs/html/msg/PoseWithCovarianceStamped.html)): +- `pose_sync` ([geometry_msgs/PoseWithCovarianceStamped](/geometry_msgs/html/msg/PoseWithCovarianceStamped.html#http://)): The position, rotation, and timestamp of the car, synchronized across all cameras. -- `effort` ([rktl_msgs/ControlEffort](/rktl_msgs/html/msg/ControlEffort.html)): +- `effort` ([rktl_msgs/ControlEffort](/rktl_msgs/html/msg/ControlEffort.html#http://)): The car's desired movement, in terms of throttle and steering amount. ### Published Topics -- `odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html)): Odometry data +- `odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html#http://)): Odometry data of a field element's position and velocity. -- `odom_particles` ([geometry_msgs](/geometry_msgs/html/msg/PoseArray.html)): +- `odom_particles` ([geometry_msgs](/geometry_msgs/html/msg/PoseArray.html#http://)): Poses of all particles used in the filter. Useful for debugging. Only published if `~publish_particles` is true. @@ -355,13 +351,13 @@ Allows for controlling the car using a joystick input, e.g. an Xbox controller. ### Subscribed Topics -- `joy` ([sensor_msgs/Joy](/sensor_msgs/html/msg/Joy.html)): State all buttons and - axes on the Xbox controller. +- `joy` ([sensor_msgs/Joy](/sensor_msgs/html/msg/Joy.html#http://)): State of + all buttons and axes on the Xbox controller. ### Published Topics -- `effort` ([rktl_msgs/ControlEffort](/rktl_msgs/html/msg/ControlEffort.html)): +- `effort` ([rktl_msgs/ControlEffort](/rktl_msgs/html/msg/ControlEffort.html#http://)): The car's desired movement, in terms of throttle and steering amount. ### Parameters diff --git a/rktl_game/nodes/README.md b/rktl_game/nodes/README.md index 83196e560..3392fe695 100644 --- a/rktl_game/nodes/README.md +++ b/rktl_game/nodes/README.md @@ -8,12 +8,16 @@ by using `rosrun`: rosrun rktl_autonomy ``` -**Nodes:** -- [`game_manager`](#game-manager) +:::{contents} ROS Nodes in the package +:depth: 2 +:backlinks: top +:local: true +::: --- ## game_manager + This node tracks the score of a match played by two teams (orange and blue) and updates the match status (playing, paused, finished) based on certain conditions. It subscribes to the Odometry topic of the ball to detect goals and publishes @@ -22,16 +26,19 @@ provides three services (`reset_game`, `unpause_game`, `pause_game`) that enable resetting the game, unpausing it, or pausing it, respectively. ### Subscribed Topics: + - `ball/odom` ([nav_msgs/Odometry.msg](https://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Odometry.html)): Odometry of the ball. - `cars/enable`([std_msgs/Bool.msg](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)): Status of the cars (enabled/disabled). ### Published Topics: -- `match_status` (rktl_msgs/MatchStatus.msg): Publishes the current match status - and score. + +- `match_status` ([rktl_msgs/MatchStatus](/rktl_msgs/html/msg/MatchStatus.html#http://)): + Publishes the current match status and score. ### Services : + - `reset_game` ([std_srvs/Empty.srv](https://docs.ros.org/en/api/std_srvs/html/srv/Empty.html)): Resets the game and sets the scores to 0. - `unpause_game` ([std_srvs/Empty.srv](https://docs.ros.org/en/api/std_srvs/html/srv/Empty.html)): @@ -40,6 +47,7 @@ resetting the game, unpausing it, or pausing it, respectively. Pauses the game and disables the cars. ### Parameters: + - `/field/length` (`double`, default: `1.0`): The length of the playing field. - `/game_length` (`int`, default: `90`): The length of the game in seconds. - `manager_rate` (`int`, default: `10`): The rate at which the main loop is diff --git a/rktl_launch/launch/README.md b/rktl_launch/launch/README.md index fa7932797..3b5a848c1 100644 --- a/rktl_launch/launch/README.md +++ b/rktl_launch/launch/README.md @@ -7,33 +7,38 @@ using [roslaunch](https://wiki.ros.org/roslaunch): roslaunch rktl_launch ``` -**Launch Files:** -- [`c3po.launch`](#c3po-launch) -- [`r2d2.launch`](#r2d2-launch) -- [`rocket_league.launch`](#rocket-league-launch) -- [`rocket_league_sim.launch`](#rocket-league-sim-launch) +:::{contents} Launch Files in the package +:depth: 2 +:backlinks: top +:local: true +::: --- ## c3po.launch + This launch file includes two instances of the `camera.launch` file from the [`rktl_perception`](../../rktl_perception/README.md) package with different values for the `camera_name` argument. This is the launch file that will be run on the computer named "c3po" on the Rocket League cart. ### Launch Arguments + This launch file does not define any arguments of its own. ### Nodes + This launch file does not define any nodes of its own. ### Included Launch Files + - `rktl_perception camera.launch` (Included twice, once with `camera_name` set to `cam0` and once with `camera_name` set to `cam1`) --- ## r2d2.launch + This launch file includes two instances of the `camera.launch` file from the [`rktl_perception`](../../rktl_perception/README.md) package with different values for the `camera_name` argument, launches a node from the @@ -42,15 +47,13 @@ values for the `camera_name` argument, launches a node from the This is the launch file that will be run on the computer named "r2d2" on the Rocket League cart. -### Launch Arguments - -This launch file does not define any arguments of its own. - ### Nodes + - `rktl_control pose_sync_node` (parameters are loaded from `rktl_control/config/pose_synchronizer.yaml`) ### Included Launch Files + - `rktl_perception camera.launch` (Included twice, once with `camera_name` set to `cam2` and once with `camera_name` set to `cam3`) - `rktl_launch rocket_league.launch` @@ -58,12 +61,14 @@ This launch file does not define any arguments of its own. --- ## rocket_league.launch + This roslaunch file launches everything that is needed to run the system using actual hardware. It can be run with different types of agents and includes launch files for the game manager, control GUI, ball, cars, and agents based on the selected agent type. ### Launch Arguments + - `render` (default: `true`): A boolean argument that determines whether to enable the visualizer or not. - `agent_type` (default: `patrol`): A string argument that specifies the type of @@ -73,9 +78,11 @@ the selected agent type. `agent_type` is set to `'autonomy'`. ### Nodes + - `rqt_gui`: `rqt_gui` node from the `rqt_gui` package ### Included Launch Files + - `rktl_sim visualizer.launch` (Only included if `render` is set to `true`) - `rktl_game game.launch` - `rktl_control ball.launch` @@ -91,16 +98,19 @@ the selected agent type. --- ## rocket_league_sim.launch + This roslaunch file launches a simulation of the environment. It includes a visualizer, a simulator, simulated perception delays, and control/filtering stacks for the ball and cars. It also includes agents for controlling the cars, with options for a planner, an autonomy (ML) agent, or a patrol agent. ### Parameters + This launch file loads parametes from the `config/global_params.yaml` file in the [`rktl_launch`](../README.md) package. ### Launch Arguments + - `render` (default: `true`) - whether to launch the visualizer or not. - `sim_mode` (default: `realistic`) - the simulation mode to use, either realistic or ideal. @@ -112,6 +122,7 @@ in the [`rktl_launch`](../README.md) package. agent if agent_type is set to autonomy. ### Nodes + - `pose_sync_node`: A `pose_sync_node` node from the [`rktl_control`](../../rktl_control/README.md) package - `ball/pose_delay`: A `topic_delay` node from the @@ -122,6 +133,7 @@ in the [`rktl_launch`](../README.md) package. `perception_delay` argument. Only run if `sim_mode` is set to `'realistic'`. ### Included Launch Files + - `rktl_sim visualizer.launch` (Only included if `render` is set to `true`) - `rktl_sim simulator.launch` (Passes the `sim_mode` argument) - `rktl_control ball.launch` diff --git a/rktl_planner/README.md b/rktl_planner/README.md index a3b3b7ba8..31929cef8 100644 --- a/rktl_planner/README.md +++ b/rktl_planner/README.md @@ -1,4 +1,5 @@ # rktl_planner + This package provides classical algorithms to plan trajectories for the car, as well as algorithms to control the car. Both a "patrolling" planner and a planner based on generating bezier curves are included. In this package, path @@ -6,5 +7,5 @@ generation is handled in two parts: planner nodes decide where a car should go, and then call upon a [server](https://wiki.ros.org/Services) node to decide how it will get there. Currently, only 2 nodes adhere to this schema (path_planner and bezier_path_server, respectively), but the idea is that once -multiple of these nodes are created, they should be able to be swtiched out +multiple of these nodes are created, they should be able to be switched out seamlessly. diff --git a/rktl_planner/launch/README.md b/rktl_planner/launch/README.md index 3df1469c2..3de9ebf5a 100644 --- a/rktl_planner/launch/README.md +++ b/rktl_planner/launch/README.md @@ -7,20 +7,25 @@ using [roslaunch](https://wiki.ros.org/roslaunch): roslaunch rktl_planner ``` -**Launch Files:** -- [`patrol_agent.launch`](#patrol-agent-launch) -- [`simple_agent.launch`](#simple-agent-launch) +:::{contents} Launch Files in the package +:depth: 2 +:backlinks: top +:local: true +::: --- ## patrol_agent.launch + This launches a [`patrol_planner`](../nodes/README.md#patrol-planner) node with parameters supplied by `rktl_planner/config/patrol_planner.yaml`. ### Launch Arguments + - `car_name` (default: `car0`): Name of the car to launch the agent for. ### Nodes + - `cars/{car_name}/patrol_planner`: [`patrol_planner`](../nodes/README.md#patrol-planner) node from the [`rktl_planner`](../README.md) package. Parameters supplied by @@ -29,15 +34,18 @@ parameters supplied by `rktl_planner/config/patrol_planner.yaml`. --- ## simple_agent.launch + This launches nodes to generate and follow paths using bezier curve-based methods. It loads parameters from `rktl_planner/config/path_follower.yaml` and `rktl_planner/config/path_planner.yaml`. ### Launch Arguments + - `agent_name` (default: `agent0`): Name of the agent to run. - `car_name` (default: `car0`): Name of the car to launch the agent for. ### Nodes + - `agents/{agent_name}/path_follower`: [`path_follower`](../nodes/README.md#path-follower) node from the [`rktl_planner`](../README.md) package. Parameters supplied by diff --git a/rktl_planner/nodes/README.md b/rktl_planner/nodes/README.md index 34b8f86af..52a4efff8 100644 --- a/rktl_planner/nodes/README.md +++ b/rktl_planner/nodes/README.md @@ -8,11 +8,11 @@ by using `rosrun`: rosrun rktl_planner ``` -**Nodes:** -- [`bezier_path_server`](#bezier-path-server) -- [`path_follower`](#path-follower) -- [`path_planner`](#path-planner) -- [`patrol_planner`](#patrol-planner) +:::{contents} ROS Nodes in the package +:depth: 2 +:backlinks: top +:local: true +::: --- @@ -25,18 +25,11 @@ a series of linear segments that approximate the Bezier path). The Bezier path is designed to allow for smooth turns and gradual acceleration and deceleration, while the linear path is used for easier computation and execution. -### Subscribed Topics: -This node does not subscribe to any topics. - -### Published Topics: -This node does not publish any topics. ### Services: -- `create_bezier_path` (rktl_planner/CreateBezierPath): a service that - creates a Bezier path using the input poses and durations. -### Parameters: -This node does not have any parameters. +- `create_bezier_path` ([rktl_planner/CreateBezierPath](/rktl_planner/html/msg/CreateBezierPath.html#http://)): + A service that creates a Bezier path using the input poses and durations. --- @@ -49,15 +42,19 @@ path. It then publishes the control commands to the `/cars/{car_name}/command` topic. ### Subscribed Topics: -- `/cars/{car_name}/odom` (nav_msgs/Odometry): The car's odometry information - containing its position, orientation, and velocities. -- `linear_path` (rktl_msgs/Path): The desired path that the car should follow. + +- `/cars/{car_name}/odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html#http://)): + The car's odometry information containing its position, orientation, and velocities. +- `linear_path` ([rktl_msgs/Path](/rktl_msgs/html/msg/Path.html#http://)): + The desired path that the car should follow. ### Published Topics: -- `/cars/{car_name}/command` (rktl_msgs/ControlCommand): The control commands to - be sent to the car to follow the desired path + +- `/cars/{car_name}/command` ([rktl_msgs/ControlCommand](/rktl_msgs/html/msg/ControlCommand.html#http://)): + The control commands to be sent to the car to follow the desired path ### Parameters: + - `~frame_id` (str, default: 'map'): The frame ID for the path and pose messages. - `~max_speed` (float, default: 0.1): The maximum speed at which the car should travel along the path. @@ -81,21 +78,26 @@ takes into account the orientation of the car and decides whether to take a direct path or to generate a path in reverse. ### Subscribed Topics: -- `/cars/{car_name}/odom` (nav_msgs/Odometry): The car's odometry information - containing its position, orientation, and velocities. + +- `/cars/{car_name}/odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html#http://)): + The car's odometry information containing its position, orientation, and velocities. ### Published Topics: -- `linear_path` (rktl_msgs/Path): The desired path that the car should follow, - split into linear segments -- `bezier_path` (rktl_msgs/BezierPath): The desired path that the car should - follow, split into bezier segments + +- `linear_path` ([rktl_msgs/Path](/rktl_msgs/html/msg/Path.html#http://)): + The desired path that the car should follow, split into linear segments +- `bezier_path` ([rktl_msgs/BezierPath](/rktl_msgs/html/msg/BezierPath.html#http://)): + The desired path that the car should follow, split into bezier segments ### Services: -- `reset_planner` (std_srvs/Empty): An empty service that is used to trigger - the generation/regeneration of the path based on the odemetry of the car - and ball. The new path is published on the topics above. + +- `reset_planner` ([std_srvs/Empty](/std_srvs/html/msg/Empty.html#http://)): + An empty service that is used to trigger the generation/regeneration of the + path based on the odemetry of the car and ball. The new path is published on + the topics above. ### Parameters: + - `~frame_id` (str, default: 'map'): The frame ID for the path and pose messages. - `~max_speed` (float, default: 0.1): The maximum speed at which the car should travel along the path. @@ -118,14 +120,14 @@ and defensive modes. A Proportional Derivative (PD) controller is used to determine how much to turn. ### Subscribed Topics: -- `odom` (nav_msgs/Odometry): The car's odometry information, containing its - position, orientation, and velocities. -- `/ball/odom` (nav_msgs/Odometry): The ball's odometry information, containing - its position, orientation, and velocities. +- `odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html#http://)): + The car's odometry information, containing its position, orientation, and velocities. +- `/ball/odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html#http://)): + The ball's odometry information, containing its position, orientation, and velocities. ### Published Topics: -- `command` (rktl_msgs/ControlCommand): The control commands to be sent to the - car to perform the patrol algorithm +- `command` ([rktl_msgs/ControlCommand](/rktl_msgs/html/msg/ControlCommand.html#http://)): + The control commands to be sent to the car to perform the patrol algorithm ### Parameters: - `/field/width` (float): Physical constant, width of the field diff --git a/rktl_sim/README.md b/rktl_sim/README.md index db72fae20..12b1c51ca 100644 --- a/rktl_sim/README.md +++ b/rktl_sim/README.md @@ -1,5 +1,6 @@ # rktl_sim -This package provides a tools for simulating a physical enviornment for +This package provides a tools for simulating a physical environment for testing and training, as well as a visualizer for viewing the state of the -enviornment. Test cases are also included and can be performed by running `catkin test rktl_sim` inside of Docker. +environment. Test cases are also included and can be performed by running +`catkin test rktl_sim` inside of Docker. diff --git a/rktl_sim/launch/README.md b/rktl_sim/launch/README.md index 5a4f22a72..4b11e8938 100644 --- a/rktl_sim/launch/README.md +++ b/rktl_sim/launch/README.md @@ -7,10 +7,11 @@ using [roslaunch](https://wiki.ros.org/roslaunch): roslaunch rktl_sim ``` -**Launch Files:** - -- [`simulator.launch`](#simulator-launch) -- [`visualizer.launch`](#visualizer-launch) +:::{contents} Launch Files in the package +:depth: 2 +:backlinks: top +:local: true +::: --- @@ -25,7 +26,8 @@ information, please refer to the documentation for the ### Launch Arguments - `pybullet_render` (default: `false`): Whether or not to render the pybullet simulator. -- `sim_mode` (default: `'realistic'`): Either set to `'realistic'` or `'ideal'`. See [simulator](../nodes/README.md#simulator) for more details. +- `sim_mode` (default: `'realistic'`): Either set to `'realistic'` or `'ideal'`. + See [simulator](../nodes/README.md#simulator) for more details. ### Nodes diff --git a/rktl_sim/nodes/README.md b/rktl_sim/nodes/README.md index cfcd06510..5b88610a6 100644 --- a/rktl_sim/nodes/README.md +++ b/rktl_sim/nodes/README.md @@ -8,10 +8,11 @@ by using `rosrun`: rosrun rktl_sim ``` -**Nodes:** - -- [`simulator`](#simulator) -- [`visualizer`](#visualizer) +:::{contents} ROS Nodes in the package +:depth: 2 +:backlinks: top +:local: true +::: --- @@ -25,37 +26,41 @@ run in `'realistic'` or `'ideal`' mode by changing the `~mode` parameter. If the mode is `'ideal'`, the simulator will use perfect sensor readings and ignore any control effort messages that it receives. If the mode is `'realistic'`, the simulator will add noise to sensor readings and simulate the effects of -control effort on the car's motion. Many parameters are set in `rktl_launch/config.global_params.yaml` or `rktl_sim/config/simulator.yaml`. +control effort on the car's motion. Many parameters are set in +`rktl_launch/config.global_params.yaml` or `rktl_sim/config/simulator.yaml`. ### Subscribed Topics -- `/cars/car0/effort` (rktl_msgs/ControlEffort): The car's desired movement, in - terms of throttle and steering amount. Only subscribed to if the `~mode` - parameter is set to `'realistic'`. -- `/cars/car0/command` (rktl_msgs/ControlCommand): The car's desired movement, - in terms of velocity and steering angle. Only subscribed to if the `~mode` - parameter is set to `'ideal'`. +- `/cars/car0/effort` ([rktl_msgs/ControlEffort](/rktl_msgs/html/msg/ControlEffort.html#http://)): + The car's desired movement, in terms of throttle and steering amount. Only + subscribed to if the `~mode` parameter is set to `'realistic'`. +- `/cars/car0/command` ([rktl_msgs/ControlCommand](/rktl_msgs/html/msg/ControlCommand.html#http://)): + The car's desired movement, in terms of velocity and steering angle. Only + subscribed to if the `~mode` parameter is set to `'ideal'`. ### Published Topics -- `/ball/pose_sync_early` (geometry_msgs/PoseWithCovarianceStamped): Pose of - the ball with a timestamp and added noise. Only published if the `~mode` +- `/ball/pose_sync_early` ([geometry_msgs/PoseWithCovarianceStamped](/geometry_msgs/html/msg/PoseWithCovarianceStamped.html#http://)): + Pose of the ball with a timestamp and added noise. Only published if the + `~mode` parameter is set to `'realistic'`. +- `/ball/odom_truth` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html#http://)): + Odometry of the ball with no added noise. Only published if the `~mode` parameter is set to `'realistic'`. -- `/ball/odom_truth` (nav_msgs/Odometry): Odometry of the ball with no added - noise. Only published if the `~mode` parameter is set to `'realistic'`. -- `/ball/odom` (nav_msgs/Odometry): Odometry of the ball with no added noise. - Only published if the `~mode` parameter is set to `'ideal'`. -- `/cars/car0/pose_sync_early` (geometry_msgs/PoseWithCovarianceStamped): Pose - of the car with a timestamp and added noise. Only published if the `~mode` +- `/ball/odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html#http://)): + Odometry of the ball with no added noise. Only published if the `~mode` + parameter is set to `'ideal'`. +- `/cars/car0/pose_sync_early` ([geometry_msgs/PoseWithCovarianceStamped](/geometry_msgs/html/msg/PoseWithCovarianceStamped.html#http://)): + Pose of the car with a timestamp and added noise. Only published if the + `~mode` parameter is set to `'realistic'`. +- `/cars/car0/odom_truth` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html#http://)): + Odometry of the car with no added noise. Only published if the `~mode` parameter is set to `'realistic'`. -- `/cars/car0/odom_truth` (nav_msgs/Odometry): Odometry of the car with no - added noise. Only published if the `~mode` parameter is set to - `'realistic'`. -- `/cars/car0/odom` (nav_msgs/Odometry): Odometry of the car with no added - noise. Only published if the `~mode` parameter is set to `'ideal'`. -- `match_status` (rktl_msgs/MatchStatus): Status of the match, whether the - match is ongoing or if a goal has been scored, ending the match (and which - goal it was scored on). +- `/cars/car0/odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html#http://)): + Odometry of the car with no added noise. Only published if the `~mode` + parameter is set to `'ideal'`. +- `match_status` ([rktl_msgs/MatchStatus](/rktl_msgs/html/msg/MatchStatus.html#http://)): + Status of the match, whether the match is ongoing or if a goal has been + scored, ending the match (and which goal it was scored on). ### Parameters @@ -109,20 +114,16 @@ are set in `rktl_launch/config.global_params.yaml` or ### Subscribed Topics -- `/ball/odom` (nav_msgs/Odometry): The ball's odometry information containing - its position, orientation, and velocities. -- `/cars/car0/odom` (nav_msgs/Odometry): The car's odometry information - containing its position, orientation, and velocities. -- `/cars/car0/path` (rktl_msgs/Path): Used for visualizing the path the car - should follow as a series of waypoints. -- `/cars/car0/lookahead_pnt` (std_msgs/Float32): Used for visualizing the path - the lookahead point for a pure pursuit algorithm. -- `/agents/agent0/bezier_path` (rktl_msgs/BezierPathList): Used for visualizing - the path the car should follow as a bezier curve. - -### Published Topics - -This node does not publish any topics. +- `/ball/odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html#http://)): + The ball's odometry information containing its position, orientation, and velocities. +- `/cars/car0/odom` ([nav_msgs/Odometry](/nav_msgs/html/msg/Odometry.html#http://)): + The car's odometry information containing its position, orientation, and velocities. +- `/cars/car0/path` ([rktl_msgs/Path](/rktl_msgs/html/msg/Path.html#http://)): + Used for visualizing the path the car should follow as a series of waypoints. +- `/cars/car0/lookahead_pnt` ([std_msgs/Float32](/std_msgs/html/msg/Float32.html#http://)): + Used for visualizing the path the lookahead point for a pure pursuit algorithm. +- `/agents/agent0/bezier_path` ([rktl_msgs/BezierPathList](/rktl_msgs/html/msg/BezierPathList.html#http://)): + Used for visualizing the path the car should follow as a bezier curve. ### Parameters From 215bda36246a015b92a82a3c484d0e1802bed52a Mon Sep 17 00:00:00 2001 From: Daniel Gerblick Date: Sun, 23 Apr 2023 07:46:16 +0000 Subject: [PATCH 4/5] favicon --- .../favicons/android-chrome-192x192.png | Bin 0 -> 25575 bytes .../favicons/android-chrome-512x512.png | Bin 0 -> 65522 bytes docs/_static/favicons/apple-touch-icon.png | Bin 0 -> 22982 bytes docs/_static/favicons/favicon-16x16.png | Bin 0 -> 841 bytes docs/_static/favicons/favicon-32x32.png | Bin 0 -> 2362 bytes docs/_static/favicons/favicon.ico | Bin 0 -> 15406 bytes docs/conf.py | 20 +++++ docs/images/arc_logo.svg | 79 ++++++++++++++++++ docs/index.md | 3 - docs/requirements.in | 1 + docs/requirements.txt | 48 ++++++----- 11 files changed, 126 insertions(+), 25 deletions(-) create mode 100644 docs/_static/favicons/android-chrome-192x192.png create mode 100644 docs/_static/favicons/android-chrome-512x512.png create mode 100644 docs/_static/favicons/apple-touch-icon.png create mode 100644 docs/_static/favicons/favicon-16x16.png create mode 100644 docs/_static/favicons/favicon-32x32.png create mode 100644 docs/_static/favicons/favicon.ico create mode 100644 docs/images/arc_logo.svg diff --git a/docs/_static/favicons/android-chrome-192x192.png b/docs/_static/favicons/android-chrome-192x192.png new file mode 100644 index 0000000000000000000000000000000000000000..f9ee60c3505f964982c126713ac3c27cf50c0635 GIT binary patch literal 25575 zcmV*IKxe;+P)PyA07*naRCr$OU3q*|)%E|L`)0C0*pqV8- zkl+XbcZCqNNR=g-pm8IC;?la+wRPXCplDUL3Hz4Jym!yz!&axQ-^Kd-<~b_Mn*2Kf1w_{pBb-8S((iUD@p zD*W8>Pj&@{+wE{mgK$PvQSg@cU6CDG?a5FO} z5v^RaeEF9ik4NwRlhF1KEMB%exnE;?Dzr{hO7}MudP0-Z1X66W<#O-P+VVk}o3?FK zJMSJnV0)}{NXV_55F)XTJaqk^86fgHQbkqu6GRvuRPA%iP#26JIr7WIY(eL!cs#6d zbp4?&mvsi9P9)GkFb@JzzfhE!;U~g>7_=PVR}F<%-rbS@{$n|0b#5d-&elIOK!klO zuc|phk@+40NkP@Lw#>_mM~{A}vs>QT58=&E`1b0agi>bw7T|pdlnTJ)Q zxr>?gr9^NgVzLa{M6B-&G&auh>tC|K87y%4KPjnW=;BY500Zi3=MZd)z03T9f$anV}SC? z%F_&T_4jSxvdlAX+>UU&c7JvCFwJ;~fWBd5>4%H*b1#du>-SexoooRIG-$o_`q861 zJUE-SGqz2gQs*0NFoZGPoj!4)yOvvRod(@knw5S>r~BB$3H)Rjz*AF`l;QV}0jUQ7 z7z}&~ZQZT|f!bHn(l$JnlVd*unVDwHpWn;vN}5iJt_b&)W!B#thVh&Cwru(S!Esjv zTAaPhtEze`!#EL|uP5MKn1B>sx6ng(sO>lEwQxgeBIbS3Z3aM0t4*2L3CyUPTG1r9#_Vp zhg}ZBGyuJW+Q^~*gu!(NyPolzW`kkiTo9c`;8Q`=BLaPk!SZPQr?%)H40ELcH5f`= zNJOUt+%2fBJUAbB5nVMdH@Du&n5E8?r+gE76AhzNF(+*nOF z3AO_K^p0&jVR~-=wRhC|dYGDj1B2wDeyS6?vDYELhJLP>E90W^=Tl?s?f0w}?RjPw zGe9RNLE+}}yN!vSWxkmu?ZxG?gu=N?Mm@tPpbM{6UPHZk~1FkXei7TY4MaSRiVC(*zV zbqAoL&}xLXh7}eRJmcg*c;>B4ai{lq8O-wVbyS%3r>4O}Jr@pGDf~9I);C2FN*pkd zBl^LW#0Fw9&bcK!{UzWBLtvcJY0Uj6y1`F`0e;w?ipuJVq;OZngUfgw(DSv{|0o_k zS`Jm4a`&9-^rTe$+Awel1H%XqMhICLysTjxjk#`IZoLzg|Fk9bXMx!Zpnoiz&A?}X zy0j##-(>G77Yhxib(!(4X6xd~!v_4zX`4N@-cN)9epvqUg$oB8hU@ue z%}SenVP*~RY&MMBi$;!I9nIBY&YYTF{%(yUlu{J{1*<)Opv#!++rIVcNJh7y$~3Lk zcOw%`A;j$BpqcR!B_n_1I%`XxUTPtTMs(4^)6D#|a$93>K7TJ?7xl4A$o|hTfRig& zWaNy2hdm33^H_&s%HiK(S(8FpZ6obQh1YvNfvQ7^R?NJ@3gG++WAm0r+tF)kzD@0y zobnJ6Mn$U|?!sZvEVDztC_i{i3-MgO)(2YdY!C)k!4}(uH&d+}>-u`Akyl6j8;%ABQ%l0%F zSfw?Wx!HQ+%F(06;1;snQnz9MB(^>Qb?(qI_yaKAMc|p?;sWBGXK*`ad`{Xma?aD zo(OcdvF2K4tCFphca!}aH;o%NuGQnRY)SpEi1|%NANmNLFk>4N#A9?g0hyhhSBUm< z8ND5_%pA|~y}s@O`n!zeE?|INHW#}i&xE>pcLV=Lk5=;i_7!=+vT7qheI)bv%VNH8qAW zU`jAaBqzGyVQJPluc#pR@AA)Sb@lTA{)5ADN2}HntdsaXW<2uEnr}uwIPU-Uuy}!J zOVaW8#4k?lV@PO=8I_g4a4TaOfPG2*_r?RVGK-nJ-fEs_BZ%8q+a=;@x{38pX zHg#6fnEa&<>xZp&?}7#UB)i=Ib*g)3&0mt~|4rf8v1^)dfc4=b&^kM|;Pwps2dtNY z)oLg{oS4o9VP7YGXyE12tc){)>y|C9A5V(!WMDH}x}bD;|L2_0+7s$HX8?y^h&^Fa zGKQI6?+FHQ1&Ps%(JzwU4zpfRl%L;e*?U%1RlXu6aR;FagIWCPw}9}G*7|{f&$n#i z#ECnla+5b_eE<~Iw4Woj~?AN#M-Z;`iw7__1F*m zng2Sf`^F=bwvJ}TX2X^8ul5JiQ@twP-6QFI*7_QdI)a#q3G(+JQbxJk-S?5}&!yG? z|I6pR?cRUy1Mel~qIP3pFia3O0lZpkRBzwD^TFHm4iGKb9#ay+0A2kRZ(XfUc69li zIqqZ9dWcWX0UdULc?SrEFS*^7u|DEvEnIjIDc4g(I40CrQ!6^7cvR#^wteu@+=>56 zGPY{sNhD#O3<=Z^HVB$vyrH3IxEtNiOVE8Ay}rkzJc9=-oN;EvqiiO?+D9jJ( z4+MNeOt+^e8FL-p1T?F%axf`lDmBIAhFDK})a5qDjmyc|9BFfJT)L@G4;@JK4Pa^J zR|(XUn*56-wzy+q3NZK;kiNepEAz=%jay|;tU3TLcPSAf!o)OpEI4pSG#We7l4(oh+r2gi8@@cxZ0_s!`=17IqQiMGh?WFQ zV}fURpWWh9iLhBEkDCOW4$x1+YCGaXfUy_XYcPK-1(m?ies zWM)M~q8$l&@WRW!JijO}@6u@fmeu;Ul0#2W28*sei9mxL9=2%RhxnZYCPr9N+{c^F z3PXdi6GR_C^OKvg{=qx54{r{VXDX{*Kbi%yzi| zobI6(r@F{(xt_H?Hxi=sv^w9T0GzsTzyjIG5eD;7!)p`oYynaCj?%|O#1*BNrVH@3_sW$#J;qC#fslY`m%aFo}`R{1MdV#j5Y1$ zcX>?yn>A)A1Ab<{8nC~@ksg>Wdn*TjC7AAG#h)py$AZ))VbJHk4w!+#SC1JZzCt0( zwA%UyKx|u7ofM08fo}BGxRNtpCZdy_wCRdEati=@NJ-WJ3FZ;6)=>mVjCAaUp(U8d z?2&$H=VOh7Z-&sfM3*r@#lnRrk>L_`W0yd4w5%*^{?NT++y4beR)t!1afwKECq1l) z&S`$oZDZgY)>g^-efM1!?A<70nE}ir&?ylfn41B@*88uRDN?rYl2JDc?Xkc6Rco?|5BrD_kvRYpr5voED(^)9Jll6;KN3>EU zS()d0UgQ+_*7eT-EZV8K3j^<&e)mP5i+acHpXH?UE@J@cd`3;p{%(KZv#=tLlMzO& z!_WJc?|q)f^Mh}CG?D_9-nVaGWBmB>5iOASELd<@vdg_JoK}Wek0{E|7w5OIMLq&J z;D990*s%@K#$|sw|F-b}Sb_f#Iv`7gY|gCjEy?bG?bN#ZGZk2{j&@sN@XC^`%!8-Z zu0I>3#UnN*V6XNAXItIMe<{hz?8*L(IJq62^oZ0s)?xqsI8s5o(x3l80B^PFj zLM7p)>llDQcl`CCw6v7ee*-u?XyjUh?k~<8C67@@#m?~3tIxkdHl5ZnGvS{4#>Nt- zGPa}6+EpsAsyfGjx`he7?1(OnC+c@@o8b)WGv*$ttZv;+0JXXnhoQjC_-jda#^v(6 zc#@`Bf$C;=>=Y1E!L0!;UAMn1P%RUS1@+CM+}uwRy+FH~-fc^LCumKN z11$EAP(=>^I|hsXQQJOZLQDQ(x&ld_ng($IYwyV^ zqNPMA)id)40oF6F&d(Ra&@NA6orukm(8QyY*JTqKa|zrbMJqGjH?=tq9}IXqG6ac0 zm7v@9hWcJfuH-cB-+2@nBv$5Zz;@_!P~wu>9ng)riZK1$lI)CeF}DnE5JFT-7z317 zRqbnlK8==HQSdnn^G4kr>qPEaxUhRSmuo)QP8t`sF!)*B*jOOiisLE_=Cw=87~KsCC^hUdnG6LKFA7~`5+o(fAPTrhiEeJ9YM51 z^gWb%g&P|_MpDuriS_l)nV=JsNMKV2Hf>6__PzVu0Uh!!cczK^i2V)zI+RZey$tYa*`4zKcL~6#?P~(H@n$!_>LS6=gFBd&QA|Af~14lFCG5 zCJjwrm`K_QV}J)1EZ9f8Tpt0p`9EY4{UL!S73SyO9_u9R8$h|{gCgGmV19b1qS4pI zkdL?hSY}mK-Jw9^(d7Hzbo7`TnW(BLFE>^%$5^M@rhYgDOIh9es{t-0u8 z-pTl~y{tc_cI~MKDG4Cj+abySk!t+)#?5-r-35sggPIN}HHASZ>eV=_y83X^bP9-n zL%^7}zAd~`SytASqen;ejS1eh@`c_J%AiMsuWn{uOEwUde#1rd&segshdUAFRaJj7 zNIe+l_npvuMPWf+La*WAzNXf#IY_bb5J>Qa=s(PQTuBfP=fyQO#xbd9dWa?4CA-3& z?AEJek9o*;nh6=C}B51s7^hzXQ!q2>irT?nYj0tGeu2}0 zmOuP(hLN25I>3hpwGrHzJ6zkhPHyiB8n0bO{Dd+G9`-B)XNHyHfQNQk=GC#LQF1g_ zW-41+e+@BDZ@xVxNaVw{UvE081wBF1D5a;QJ_vBMw~(VQe@vB_v57T?mk!T(DN*C@ zQU;JgR#a7uA&^811$#I$Gf(p;xu-|71l!1NF84fA>b!Q7UawgXDbCN2Tij{Ch_kD! ze*?`mAlfVJ0y92V1`WM()To39aeH3mG}qSpMa`}stwUh&gp#aGNq2-;ti|yil0Emv zkViZ-Us9T#=_uu_llgZ!1I%3b$RL-Y#TuO2Za@tTt|G1G6&8$=l%8#hXWqP&jO66A zSz{syB1*Nr?iv4Tv;w~mCy!SwSkSM2|NS=y`}s#&5Ice1VTb*h8DfQPHMVtVBavf_ z(S-$hlFHOk5!$^EJ1irbW~yvS{XWDjPHk;GDJ2DJ@+RxV>qigRZexg^P+tnR^8kkz zfgFu2VU+|_>x*&913QV}D=~5sBkn#KOSei}G?MuqI+@iitQ>WcjO!=pbnRi!a&zV7QF&WsBFI z0#dI~M}XY50TZWtMr3>;9g52_Lst=XN&2H`(+d856_^&VK}!R=@jEhHez!rS8_|;> z5o#=8S(2wAA?M8Y|1$N3lSd@ZBAk$cgR0Ihda3hglmKK;sSJKn&xedrujh#fGV0ZXHIHEa`G=-?j-T4j|%6(%vON)uQ)mR zvrr;jc~w$|4~Wx4H|@_GyEcayWy-)i~) zv^t;MK%+pQglR7v9(~(aAN)Ln9wVkyQ{iKVT0srw22W0=7^-Z2iXg_3%Qc6I&WiaA zgd7X43IymR&+q$vXa5}UV=stymob1uMIGI}$6O*?3)EGGHS7H1{QPQpz@`rzcq>2? zLS$|iJ-&c!y{f@=mSruI*j&N%gi;q0M8s03f^4;-!!_a6V0uX_yvly{Z1I>&zM5TK zy+1V0ha&NZ7qP9q*e55$5612F+qd4)-l1+v#Yr{?1%S90biYHHiA z6K+tfuDCfneL?UK@@8Poe^K@=<1CCa{&jZLQnXf^33w?$fj@bM?p-gf?x^+k2ry<7 zA+Iyz)Qo#dvoo%9G!loE;@NaZq?=O}Jwm|$H8+s2#wG^d2J1UObO@NPBC?a&b=dUg zHUdxhrU`YAVc-C=_?mVo5+*=Ty|nnrQG+iSemFHnMLBfzax{%DsU)&22p1OR=C*n_ zPI+?eF@{Tp%Tp#E8F!g!l9gRaM*G%rdFHL`?dq3y3xNv2+@~`Ktd(ddK71`SnDL=$ z;bPB-^yOk@n!cp|aAy4&;!Od?&=%p$cD_)Z-k&aG02$c>3l|R3hHJXOkuz)Y(0r=V z?S8XGZoYj^O|P_WftyIt4IO5}9AIq?tN-e&=UO07#2x^5%5N3%g#8gQ^owKZ^iQbU?`UZ_W)-%Nk0C%hIPf{ti5bE^;>J#pY4Kv3=&%rd-?GFhVosZ(iFr5WVR@%veyfzuRR>zU#zZe`U?p7X|Zo}xibG5N{;=~`& z=4Q>SKAhbADiK9Y^V3egNHDuZ{(RbR08<@RG-jl&(P=4Vwd+qrj&U^Px=iOE4b+P+y`5>fMALsUSjv@uTQX)1cpZ&hNKHf_$gd z)r(sDt{6X3tTh*x4$Dj!RA$R4yX*}R%X(H+Ro4wi2@#hZEf*~gkUvi#*Kb?8sgKqH$%+{XbEzFw`Z~bwvpqopKy53; zFSB*|4d7&bW>;382W7~j*oGYjzO=x4dC?Q;?f67cjTzSjWyb@Tz#_YA(=}EI zBY2ruM!QEafQU&jTu&2`;L2Of{Fj~Dx*;Ban|trANlnfSEJhOoTx>-SJke`lUCV$x zNVh1L%d`T4B*QRzXpQ3(a4{23iUUJbyulxIZ{I#~+_-UVl22Sy!>Rp}eQy$xWO0dB zq^b|)vFsDTvAqOIL_r2Tu`xS`Q9j?ft%kCAc25ghCF-hN?bdc8wjAPJvz;wm71 zNn45N1&j5h@%fSA3#G5}1q+T-hFg5`e+!~CC+jF^5~S#o!ra^rek`7+Rv+j#T!L>D z?Cckf5jy*OwI=phmOj937$Sb{3hmh{*8Y=AhVApMEectI*Fh4&7WN!6YksI?Sf&L3 zC(2p5&AN371I+e%?-ldEJu&765Q+-(@?w(bJF~k@MzOhf9U_sD(|jTx6vkEN9n(xX-!q~|L{ZOi-ytd{ zoB;&8zeo49mCeAgO}8Jzo6@8ERhMOFH)j%wKIG0^ZL=yX&md(y>p)C-+3%-6Tr+m$ zH?by$vnR$(Gv?1fAjzGy2+`4*H#6blqTJjLNOsef)Sm@rac$@noM7}-O;io1zA7R6 zlN3zV+qUkQkg|Ny@^ zTC?16%KwEr{0SaL2rpF5li?($}+$*oDI@y4F90bWH5Uwn@%s~G5F=NC{I}wE{ zyk0rP4>#xG4Na5rnbzh7#iK{B46ZP>)|aJ75=yXh`$Zx~9fpRD_s{e(hzE7je@Ea< z0w75qBJtJS#@54tX!-6p8Rmp3Wiy)7@V>S^?&DGa(YocJRy*sOWV`hEAl&1tNFlkqgeDBc?p4xZVP^}*(i zGYbm~TQgvmEvXmhxxW&3!~t^BcVg?1AIuLi__#QdZpeWbIGS3``c(zj3ez;VxfN^6 zP;LhGHV6Zlv9|*DVnS~)_asGcO&XdZ#<8%aGa_*`x>46p0^WV5IUNjfL~0w^CAc$; zH$WIk(XVh39^YritKsTvZDki16bMpu)G}wz9CsikrKcwMAZ4)l|BsXDlFv2iY{g-PHT+^FZzj0(v{?r;F;y;oYnWwAdkHYueV5nZtps*fBRLr71}td zaP-K}A}wGu1j`xB_;vGFO0)=0)p(12%fFD6O5(zs@KWLRRuL%A31QpF#{6+Z(m`7r zk`F!^WH_CJtrK*#dCmqBV8SyDn$ZyOf7#9DUIxMuPMS990{ANp_UQLAtHYtyd6?C< z%C)Jzde8t?)Dx^tw<~2k?a=FQ%;~cw9wmgs@kOlWcnu$@so6*S&A)@XE+wa>`LE*( z@*?8y%v$KZMk$PIj@uO-yrXO?tui0$KU|fc-{z5?h=pvSQBhTO7LgK7kK?uVy9QuK z$}a(OVzx-+Xl)(ccNXJTZ3Gs3hVHe#Y_ablQq&H~BVwOo->AiszMFh37!yF~} zgs71irk%c%k;*{#_7LgqhFq^%pBX90eMV*FFWkylCfK9#O;;Wo`ba0nu6XHJ{MCB^ zQc0rV!nt^NAnkYc$Bq>7SK9>)(3I$UJKGuTY5vw!W9A)aH=!<1U9$ch#roM;=FZ?3 z{<}Kkya&gTWVyFX`7%!4Vs1PUunlmCx`s8j4@K(m>8fb$5uD-VHY3%_QeADEoQD$O1&On zUKJqPm};6CaJj_7DToU>Ad>7S?faE%><_wn^}Kf6(C`-H`zsfn#-tyOh}sZ&WwdYk z7s-(_N_KW(XDwQ^x6=AOfCQh@QSrMnn;Af`guA3PGO!Aa&x!CBYrLhBQr^7z{2s0N zsp2=}c1v;&*r`_?73QrL8NZ&K)vpzm+ot2<>p(0(w&8-4wu0%lN!jW0&ajKbLnxP$ zcaZo)h0M??wgF;#Tw9n^IwC!ynA}9Q2vGzFt_Z@hIO7!M=Q&A# z>S+H%Rg&DtCaHH~VbTOLfT->*FmDIco5cL7R=kp+-(rh=mMeAhCp&v=Z2IE1JqlA7 zuN_B(U>t|6C{^cJ#w-E9Zkm{@$hbI*x55gV0_#MzI{V^pj$5Y zhYmd*?dEKkcjEQ)CpnAS7t zVI^4^;zb+v+=Zj!zoIb>zV`#cPxdS9M&Tp3Q_zlh2$mChtY3V~w?5GlPpKspHe^H`1{)Myp#)S)H$%1mPmK!VLQR4z@;5Z_ZF3Tl1#c5gEXCD*MGR zP9Vz~4N`*vItbuyEgjivJn)Ua<;!P=5_`fKFKoP=frr%)@cTBb1gr<^ZCv^YFv_B_$Sp;(Z?cU4vTtG9=PvnZ9Y&sY`{N4wVP76=5hmuM4CD7pTSGaq~t$%&g*46_m$PI zJDor;h7Pg`zEAk8KtskagCDYGbw2qRM#W=lJ+VK0?;9GhuAf*Q%-i)|}v zQ&Q{5YEkADjY;mKqd_vpIv=TT8w~w{S0SKKk&lwtAhv;dBNIKbBl#EK1(NoY++bbn z3&g0~!TzFY!}k6zSZtVD>szD*%*zv*IUz+5D^ya-Vj?@%HFOad2*QQF z<;!1bg9u?mq8PPK6J&R4!1kK~uYR-Uo8PtoOqJEHYoMlNAWq9pOVbsThc#tux%r8& z_v+^A{vtI6w?r#qIbH)oPDxg#?dmL^2Gf?Te~7?iqcv{x`wud9&7`c1OJZuLJAX!krpyjdlP|rfX^<>%L|8R6Lw4$^XDH)?j&g!&iZ45u@;)g7mm(*(&^-E ze;mX8OcaZ?$r@MIfBD73(On{-4fXZQbDT%IS@e7jG#loS!A4~pe2Vo#d!?KZ3NxZ6hT8&-oDZgIjgfavY}G&Y{; zQtD&|okmUB8O2#ExXn&tTzOS~Zp^L)6_wuGL*oHq4HI5t*8hgqFC^{U`9UZg%}Bdl zQRR&SF=Dsg4DhwCZQB;cO21v-G|TI~lt8ydat4&!OtZfEm87H@?L$887}zY5 ziWSgcs|IpQvoe-CUXteTTGUs63$(Y(G!G=hm;$s3HWyXYqHWuZt8N^Z<2Z@&eU+7a zxs~y8JGGm|jA^PONera$aXska}p z&I@g{%)sy#xqIqUYtJF2DqGO19oP_Bx{|72vQ}eChV^^Bc-ivg0cM|3VE!v8v^6-) z7%ebv4ZN2=EpqDEj;*6IKx-2MX3qBxak)q|H?7uG8|ca6G4)?9uZb>B0Qc6^q$V{6 z=8|gbF)5IVn)UGU`T0%Azm7{s5yeiZXShEDcs~bZL?*p|N5Eg!%kN+BPsT zZFFA~3zD1-Q?BX!7NmyG!nI54Bdv|!P9E0RPIfZ&sddFw7Ksc@KM%fAKCc)+MMoNAs3Fx{fr<4)VW$k>;1>^HJ-*ThO z^%;$Qt zGgrjW#<}66g=mGh`W1l_57EgM4Hi6}+lq5@MZMWt?7)?7-OeB~NdziLR0-JLOrQcTq8c#brAl zopL9-cGT2jQx7W|(-DGYYOU{2iV!Y4WjNyBH~7tSlijXIW7FgRK#qZz6tI>7$7)1z zvoMt!>=~MFf9R&v`bHYSU*ZJ4ZRKbA2wLxEOcpu5tj;H?swO*H)#gf?F|{;1Bc?Wv z8Q{KoPxW>u?R+9cz&V`{j3s2JRdrC>KbaVQCdjRRmV?&KA8UMRs=(2L^(ilj zvbyy*5m+p_oeF4R#$0nv;A*V?-0wc_$h$!_!ReTqud|m*hGjTghi1Z#8KB(j9ic#T zV{({^W%NyTzqMEo8lRtUyUB(sk+kx&Dl3O6Ngz!zyH&gfd zlPFtK|0`k+3I7+aD@n>>zMFBl>)87Fq~JL1YzKPGUxCPRkdbDZS(=@0yFGYbLZS&8cr_xTY794OcQr4z%nTmRVGWn@X}WL{xQL95H~6we$U|dx)sG-J?(T zRt~F##fchF9OWX>6s?7L0fwtD$75tsL9S#$kEzHz!%XY(Hh`mJP{YO4N8&2;ij=gp zMT&`0H7y-t4AnMUX6VFnhacp52Rbiyv zy>G#SUnjZT9n!6aX(Osbu^J`>iA@4+h)6yJG7l#KH=7B3(N%eQt=^f6+A7-9%@GVe$|*~Y978(w_+n3OZ- z5^O&-$LF(!u&H_EEyFS+B^qfn2FD%Pd2|mw^aKXo#)Q|I`4KZIX=Si1+iZZ6K!*+} z$HcfRJ;`-bPEJm1h7SSJO?JBv*F={?BLIczMR|GOINy&SYEFOn;f$WiDdN)}(Ht-S z=ujxrmVRC2UIJaytO9hr7D3|^&CXY>c@~IYfKsQC=IbKSvn_j)qfA>v+Piy~)%xBd zYE3B>Z5jSs-_UUQeL4H>oL1`-)wEODS6nhg42$)^iiYf=tqsPX@5pJ2A-=U{U79Ne z9{|q9r*M;E;NNBgpQYT^`G#REjKwYyOj9%dT$&vjV<@Y z<7iumPOJ4T61*e_YhW^PeMwfv49`<5d%KM8uaM*1TVyip*NI4U>`s`##{6NzVrz>k zYzbo&Ri&||{&v-rlD0F&2I&o0ILl?YdlLC2kC{sBfrYFvG6y-u6ipxlw2q1@ zD!ofdiFML0^2M24zhcE5PFy7%9KOg^nCXE>9yvg3I^M4XUw2DR{&HMSbU!6K!+gJV zK_&QO^f7RGVP2ji6`hEAijod-yK(T&M)l^kV@G}$Zga|Neg8*9Z??zK3?7f|HUPSC za#p{$J)V~g_wh%S0W64pPQKkLyYLPX_6pItyf-$oqDx9I zOt&A;Wi{XKL&+)6#em}0M3!Nhz}dHCXT%g6EqFhh{l2qEk+%~tj-o($gMq0AR5u0} zHM`by%7)OgUYhaW&6}+w?ru)h9qlZ1WPs@I@6l++{QIn`s(eLC;&l7S>Hzq}PZ&Kh zFK?G11h)*hIY{T3$YK!xV~1tsT_3`oA?AsyU^f6s?$Ufaq%)^Kk736;<9(+WGFt!|3|L{9HTaZWk7sT~$2?gmCbT0s%AS z<)ox(kL6qeEj@ZCPs_Nfew~=ev-=4^vQluxPF{>%5N|Gv91Ete%>0 z`?^w-pC?vF0~`}PWb>d!@4gDagMkg(?h2WJj+x39uQ?Hh>rZ66!LuZ>NXVDk$->1| zhp{Tq$S2&Ilexyp?zA#MR~_zXlbBsy{Tnb|=}?dP{g;y5|JT`kVbS_;|9i!P>R-dK za}9?&RGTd`aMAcNV?v@U1k-9xp)`RR5+&B1Nisj!#Ufz6X8p(YD^@%kiW#OZUN@Eq zr6K|{^D?t>-A$gHL9KA=t^F|5)TO>dp?MfVokJv8OWZqF6{4V36RBr3^ZQU}P#P%= z&LpDYVC=Q)(y7L}TOsN*Rx_)UN{01w1k)4K4UmB0bs$kuRXv{wp|S;POVb(S3r2Nh zj;o_ws`F+AQX^N zM>3KTB#ky#&0pj&-`#(O+t$0j_Pa;%4^39pDGU_5d}8sYK6+}zMc8)lkP zyLOPFBn%b9qKu(YgR3o5-@E?1t;=VPZ^G*FEZs23ZCOt@r;AGXUdOsFyQuzZ4g`K( z^839Vc@!jcQD!Y%_`4MoL2+j06K#L!dr15Eqgc88l2O4)8w@mzFjw20#y&+B> zKThiWu)7i@KVCIuScx2yz`S)Q;i&6ExPRRG)Vklf3=*H4NO^RF&y;A2J$wZXrRPOdLiB!T;3 z5u2S(@5fN@`v4^$>lxb9k=H>?iyLY7;)c-g&_i!hk_2uy`QzIt4<@n;$K-ZtZrMod zFniIW{h;|Rr=F$^d{Mvriz8b?L2szp(5q*Pei~rG$&b5;Z#-!f2HyX;#(mVFqv3{# zWc$ZW@JG^63}IFyAL+@-?5H&hF^7aPfY6>*U46J}ifS6TTh@#DQQwN?`JIg`?#$RL zyxuDbG~4Nyn}M(WYh6c7oR}jqu{3pY{pCvWJ%EjK8oD?a$t0U+Nyh4o2Yh?gKOIZd zS7+9s>)JYclz+9xwdsf!%+hFMNhkw|cJ16Rg#Z8`07*naRAP2@^{oJvM(a4yzuWLE zraG!<%*Zd|p>1oV-0mTbmi7F^f`XWk1%msVT~+-N2$HnVQ3+-M&yrQ$-0YqwaGOpU zC|W1tJ4CDjPb0A0^EGgq5~s8O;nJ)t{=8&p`Y(5zGn|d#?{X~%$Vq6Ls23X~?=S$- zT!?j*K;&Y!ACNtrz7xb(y(lj?VuHO;dv80z_3k&E4615*yD(#cwgNMg8~T1eZd~}3 zP3`HGS5}^8D5EV>c9f4+8wRNL?d>AGLx_+8C$0m`Pg<;AG>B)#)%?fQh}7RE4ejR) zYCZ0+Oq45lR&{l;(k$xD@FsfZ27n$1@!u`xx4SnsetX$vmu>TSJVyV65AJJfHINK- z3K4$KgcG7L!nb}uXI(QkHjGm7-KPy3u2ZD0ZwIC;7T66$>IH^gV(y^lq5%Ng?$jFP z)TG&RT!I;3%HnmW8ALB7-tx-ZnQ5*=_;SZ%-xDh`cv4AL=5(iHi(3SW!~@N#l-?(z z(21XIb)CLS1J6eafEU!@nF|;0=W@9w5NKk!Nr}Ns5npzdBedrqMn2o?Edpp-b3Ais z^2}Qq_>46kT>sVb%JvY75`;s*7)9#5=H!9l62pb0AIt#L>gvU{d6Lu3i=m$QR;>di zCImEwes_6Q3+j@|S^XTxl*i2gk!CilvU03a#zP@)7}y?E5MUYqUT7d43}w@fJl%F>_hM9iPo;S zU;_f4M)!uSvn8G)JqpXICO%mH*xJ{bB*gO(+A1qgKD~Ruw8mlAxjkZDw6wzt29`wuIKjx}3I- z-Qs7%VE=z@X=~W{f`Sj6(7oU5y_`Xg5^p%67jK=G8(>xX#i~!Q`pt0!tH;~*p4ZN~ zdN<72`RPennJtlsj^@`X1`y*{uLBO~X}H~cE2xWzAQ?VFCBhcWlkKLWL$1z^J)2DM zOe!iXuP0?l61omWveXms8o&?h2KA4m%(PA65^sCv%}dE}Cw&T%#DBZ5v@pQ7L(e+c zfEGyi|AiuM83B-u|D;LcDVdW2N+F7p!!7>VGlOp~$;xbFRgXrl9RoOL!I|^DCm2ce zdoZ60kZ5Vb8*c1T&|`&pqhivKgc|%EbLZ}x);(;(oIB6=fa`OfV9d}b{VSpV6pPog^kObmC+QOhW zVPV3it>!1;VsfWH`CUKLa34-ECMx3LPR~#DMWMF>0UF`?eZQFUOT@(hw!gn=zC-Ld zr4MV%{B7~*(Jw@wNc0-Bs=QAqqKI(L_)y5VHj`i_oC zSDX(`ya|}pRi#7wi5p2wB`yY#&&4dS_c;ZUuscVE!4rz|^2!}mj#6p1xB3Gxj&>$| z+0GT06y=5m+?88kGC-b0j4g=9HqBZP+r9#L1rbT!gEZFI7et2E4A*eT z8P_slszZq~!9(p7xdvujW4@REV2k>3+R_b!G+VzTttDQ=(5%)&>Cd5QrPav)_T*%? zNfYIHYU6<}Wj^CD&1#3iN*JWcd|Is8VT4e;3?N_5eryh7{3wXV zht!CYtbT9aR=e&{O_&DQZ!;&*DO*^nTS_kIJ5!9Jo|=!7+^PMig9Ya(mV9UAx3qcs z|b(A8jNJF^C@v#f=QAu3!FnLA=51BCo^ct_=lT#mt{7 z!cg9{X`K_)hW6tV|0M!R7@-p{*4F0Cypjo5HdxlH9pawbbP|~vrqtE{!2ri3!!lzN zi2m^3)n6}b$@(7L<#h|!bWiK1f9Xzg%>qbJE*$T-W`0F8-DN02amQ zG9RD1WZgh$JfxZccO5@wZKQ6kPHTZMnNsH)YygXZkjQvpKJfH>;N5=b#A5voCggZQ zV!2)_s=S{OQ7DkvEsAjI+AqF%Dpn>aFJG2y^xb$Thzdi6Tx!;(#rgU1iV%3f>m8{< zUZ)!2k^NbE63a@u0K$14I z=_>reNk$AM|FPJ*etbcJ4e{rsh<{Ova$T(mH#8@qXxohNg~@#3guFaEYe}qS`ho@h zdK#{`Cq)wZ2~v^bnBIm%uw=@r#p&WqdGY>AIs0 zO?M%#!*6SW)|wWb?irEM8pI^XcnWanq)5*Pl9O{i=l1B3b<^n?=n@8)v7lyuml60V z%wo$UZJlDwT(^DeOwYJ+VlEF`${%^;5M}DysR?5z9LmCC0$=LP9lB#zvn#8|LE$e> z7fr+-zaPJycxmFWOC{Bi+hweEHU`p~`HIr)jJYlKr`2uv9kVru2>Z0V#pI^g46+k<}P5Q4M97lncHpS)3 zlQR$K{j#Etz+~;{HfZ2#>)rIZ@rpk}uS*!9!n>%1zyfv~sc102qnW1fXxRR?4s_eD zk{is_6?@Q^A^ME*3E@%5T+849_xAst*M4W!K9%XBAT@+Q|jtZRN!Zu z-yR{)sASvR+UPp7C0k9r<48CI+_z}afo{$JCLqJ%pd{hLMk4wQ@}&X{wjV)!C{cvK z@OJE=8Q$Xj+?X;YHYe1`2B|src%vT=i?T$G!uX?V`HKvH{Z?Yc)5Q8a(4 z%^Jur%}N&+4lb)(e=tTAdd~JB;>3jsWM4i6!6c2t5(2cv{90hc_TPpA<+T%K zZ}a^gOg9j4YK*3bzB1x}OkIXi#NwaV&zmq&Al(9r+i-nGX^RbA_E z?QVqUy(N={3qeN__7ceC9vqc1w z0mOoN*j9@cYSqhat@g$3Pl2M<7RZBFNXX2bv)BFYGf5aGnVEBv84@)6&zb#Ld+oE% z-e>K#zHgP;n)RT<23_&e;WVF5dzwH~qmgPj65`xcZh}cu7EQ@ed~#=%_E$#kHr6gr zIdp*z*DVAnNcJmOrO^`BYa;21hi)7a7wG)B8o-mAH(wzo*AP*xZ9E}rmW-b_UXVSx zQ@#N+t=dpESfu(sp_}F{0I9HTg^_di{A2F`uhs8+cY;$7mfgvEwj8?1m8Prnc2|+L zrUbw8=hn=L?GWifD0MvFo6)Rx=N3{=5u!hxoMPVl{cnwIw%fj_l#|!Yhd-35#%|ka z_2Om#3Z!;|VJt!r4m>Fy!a40jy`h<9PElUo>#FVAO`EcqTwjvJSA+0%#Xm){;0mJ* z%HYX`Zg;g)x$M?|VB3Mg15*ZV?}XnIWOaPW-x|2<;c25(NCiAQ>Obw$vGe=`yP^+F z(r#LE(@@9TVF&$ zTu~LuU=Yc{!>C@wUvMi;Tvv|_54WTKqcRcl` z>%x(vt|ijPfoLe3I4NO1zhv@AwHw;uxo|E?TZ_0EfatE~{U;HAk4 zFy072K73DJo`MWSd3kxd96WTM0B#3atc)RYoLLo>;RWUwO~Tsmx!vuT9aL6XIgg-d zNcrOSBzXpW1p4XjsvY-y{iZ1sq=ruC%Wi8a_z>8rf4`mcN_l;1kIn(40?v)hWtLDWyVbdR7JjxUC)3KqR(uAy`sgU#Z{~sMKBBM} zqH>66xNFgknF-C2h^qmpi9PA{UM!habmgb41PL~O*=QJhx`Hh)^Lq0MR2C7Igz?W- zf9tjP&7R$f?PJBJO<5^Id;<{b;^Y&|W>v$117!-fq_o0Ys0oTI2$T#4)!osprFYm! zafJ=lldjajP4Cx#_)ch;!y~oFJ}=nx68N(YyX_`!h4WD&w0KkMuK!v*amWGB^T&p0 zA}~{cia@xSfe!kdu(n57)4yE&pF?dyop(plxEp{H;zv(EJuqDiOw;|x8t=UG&W=lt zZ~;pzD?cGf?2JT8$KZ8^Znt{qB5s4Fm6d}`=ClDVEe-8sl~-2Y2NFN-jzS`}VQ@*I z+uf_sf+barUxAS8+Vqu>wTq|DLi%bk!3FZI%uTp_udXGJC???E_K4AFz6WNyy?9c_ z#stZgn2Rtc!j@HfpCO{#yJ%y|fSgctd+>wSNh$Yw?*~YcWyh^ZmJbx=<#m~iAGbl& z(LmvY!u1GCTm_=PNW=UC32Gst$wU@WMvUC+cuEtWz8HAbXwCSha@{VgJvvdavBNHp z8A~oLo}AS+CvzOWVS4>7vS!nkFA9xSDC=2Kgbe(y&^<$iRy+O(D%-sI9t%V(o<;JH z3-a9xLNTG`vFgTeOOl&l{~|G=^7OoOu9r;X7Ej82XK~G;&nC0JGXf8CmqRhIt~e(% zBIavPZJ^f;z{)QU1b$0QDwm+WFqrNv$eZ2~>*8b~)>Lk}OAxPh(k5nI=4T7?+{$~E z(DGX`czcbxBT^ZLCkHT93zr;dIPS_0@x1@AG|15~WHhSvSpwf?2avWMtIiPg%w0 zxgfX+Xf}wKhK4~{x6;fx1dL~1vU63_Ht$af-2pD=*#OzekGJvDe>TKX#> z`ghAv80!l1&URDg=H_bSa&w32hLO!CPh!Gt6oHb}jtnNt`{(E7B^0?~d2QWPDJ>}T zu93Cv2-dF05E#2?mUOfYwB-gK&3{WeN!IoxWWi9A<#CLKC`9_)HWNwS!p750EGN2Ir*+( z1PqCpOQ&S26v>2@KBKIzX1KDVVob6S_c75iX&5ghpFaJD^7XG=xiU2=Ys899jFgNA z^ya2js*W-oZD_{zOnf64f^_j%!Sw0Yg_;V39yVsoC?UjGh=`le^nyFqCMMA40EOUe+%GpCsSsL-Hra%iL0iKK3(*SeaRyNL%#>` zcZoO~AQe~_T-?DJK?yKVPn^2m<-3)my`J0>OFT$De3cURgh-L!dv77U(?2<#Qs?j%fJQ2+OR z&&1mZ)bUKeYToPQ9I&^AfqRXC8SBr0O&!kCgcwi4fMF1bj106Y5CwdnSIK ziGD9kGf6^xNf73Ms8gZ~Gr#oC(Z)$@=Fhi2gu{!+m|6L$nE}F zyuSyQRX02*h^IP`CHQVS}IU8Xjn;;8W5xZ3PE2zRr- zlVWFi6W~3PX`cY?XT$Uf?TqJ23b4jF{FX2CV5pIl)HL2gkSYe>4!ohm$1PfQ_5s>M zfq}!;v>)N(*m=aR`lJD@+_o(>*=I}uVGa|Ni!zvE$-ILIb7SHED6rc>L72nfn~b@Y z36&sPUpQli0-x&S!Yr@wu7jZ2-3*&B0Xitze3t!5Pt2b^tw$cB`(HYoHpC|y2;_)z zHNq;NW=4}b|DW|gSvqJjffY+~GJn$k-$UCDWu~X9zX~@;2s~g<#C?l=jH1LJ{sQ%*#_@0x?UOcgqt5p5Lh=^E(n$lGNPvZ2J*v z%`=ss6G=iDjNOmm$m27&NWvB(dfFcd`~!i&=>SncxLk5TQwo`b{leeeoHQ_H=m0(;NSI1hx z+6@aQ4Raj&ZhMdj75mfn`>7>`JavCV1w2w|j@3NtbQeGKC~}S(kxd8!ecj z*xxN+tl`5q5GbyZo+<~Lh>n7JKR}Hj4gi7}GKJW>aOV&4GHk#NfQ z&q5S|=_(KgcfgpCl_0*j{@r&UxAUR7rgC$ILT+voTV41l@6mB0evOz{*X`f`yX@?2 z&7VGKr2x;118PLKG!)4I6xoCxklTr1n}x@r04jj6mdxbY3vV9O7}|DOb$yN?THhVA z3WqW@NK?8OPZ{wmhwb84-O){O+(wPjk>ZXj+p^_SVPXOV6hufnX8-@R`dV-8DoH-H z%hHO9&ub)hgD4nL$$ZRY++#@Nl?5|r{%kZPnr=(@!dAcPJ!l7w!!G)~rt**Mi=G%lYp zLIs+2@`#meuNzM~ZG{>)F@+_|m38l*T(oBX*e)+8Z4Db!C$W3!wS|u@S}a3Dv(9fG&19Kjmmfa(Fv8`ca7)hTtfYSBrGqvQDmw`?`X?3PQ z1hztKKP0e=K^Fmh4YeP8LbSuoe}rj#qj2WTjZlWSMiJt-jWbR?*?Rq|;D{ez&~!L-w4vxS6ywE(6w^XEdC z9GeW7`Ac&~cHo{atF8}qA~+tps|L(?+X$FbJyS=<1=%?sLiNdy;Esp1();(23o#Y! zrRYyv+gyWPUDd1etY6)5GLRM;*Tdina=GReOq*tH^+CcteHVe$IXA|OfCJ1p2JkQa z%q0u*^Y^Pvvkaeaj)G`p!bNRd296CimH{YPAKhM`4Hv(r(Dq`>+O5ZeCF92*9DaXM zI||*hs=A3n&(0#W?*MW5;BYEnnb-T@#F)p{H9oy! zx$OiWVCHKGA|C{m6cbwBWR@Fr9714gK*B4(R?W`6s*T-^xkO%1>8c|HdFnBiqt(sBih*i$*<-QKw^#GC%$4hah<=h&mEEq{P&syy-ivP+Des ze8Ywjsk(kOh*BGyn`^_9VU)Xd?bfZ=v1A2Aby0{&4Dj2M`ElJeUpsQ};1Q3 zD#4KIF$;;r!#1YYQN_*>$b1AR$EK~xr1ksTvYx>wP$P0XkP`*yntRc@{h zxwnWZjuQh=ot0EIj)sswAt+v6j%&y=0}aF~EQCKWC3Y{FlKBUPRjRXV60yp|R_Up% z@RdSb%vOr!hl;UYO5VeuKTC->L#a<=DxnuEoVNy`bXM;5Udh0y}S%-U3 zm)6j2u|NFf6ciUf+u1p@W8o_uc6)+d~wPf%Qi*vFbvNwRnZ6i*s) zt=;^HHZLuh={t0xFh&aI^_9^FRD`M=o=6{OQymGcEt+sSFOZUd@1q z2w$*!{EDSq1#DHElbLWp;8=1b@_$DLkVrv3N`05F-!ht$vdX*Ski53Zry?Oqz5<(QVV;OoRxJRv#I`L}S5PHbGv-gh2#KRxpuFl86Pf zkW8jZHKo%aZUk!wO$r=mXdmniOO{WBjD4Zc-Zg-a@R_Q7)27cr)89G^p5@GntBba3 z-|5qH7R;S{H1Q7tlV=yS#=q>>#*P_-qetGe*1d6r!M+d1$WezLHl2NhM_)Mm%WA)7 zqIA@|29T&(^^tzdH*UO+HP7FF?tOhk)E|ukns8U5AZS9K)(S*c>wy~yB~e)=r@3m{u=ksFvd%+TMFubJ9bNL zeY(-daZUSofIj_5_6uieAc2m57&u26iCbGUlD!BnX%E)sR-u2vy2nJg;RS#@}wpMLi7v z0#KW^*w9NBkA7-5vP0L9H0ukWBxK&&uW&Kofavg);Bxf2NF3MSfd0}erCvwA1pR;>WSTTRpgdxibSnGQbM!5{cq} z{^MU2ud#o%`~QD!I%7~74bBr1%_YIz|JzAW6^DN>J3#V-(F1ks zUk~aMf$;$2qmIau|5h8r7T<#q#N!>lF;fd-{NHZcGsO+U3gRjJQkj^~BvsmD;h7SW z`_C(kf#4*-;arKYTYK1S=_Kg?>4rWl=w?m2KJdTw1N@c$b+nX|wvQ52LLU>#MRyCe zTxS=Ef-o=z8k5~4CLqkNb1EPq81_G}h*LrEN(6*4rd4D(qgZ`qBI2LZU>YG2=@ryQ z_&o{d=cf1PTfC6Q|8@fcTog+@3!*1%Nl5koZUy+aU?IZ_YTv<{{NLdIrUbQ2e99e7 zS8ELL4GK)m-@OA)Ojd7t0MCTd`%W!%?>_m@pNPgo$czmHZCp4c+@dnbeY-Yni>|=o zQZTYoqGa?0<)bFwmEJOllr(HqWz)uAJIg&4Hg??F)*R9}wY@fakX`yj3J75kL<-XI zJf)+6Z!hnTg0op|c*bnWuaZ8MQmQcI!Tu>Li+7foTk z;edCm=~{Xz@)C|@eKFu;2aRXgM10(^Jd}-Ao$>N?$M+lnmO0Zv6@d!Z_UOr6H%kfS z0KLBc2dN%`B;wK!h$lfTGvIH0~w=n0SULChHb<-tnak4bG$a zYzJ}(B)B&d5h~zX-IyNyi+>Lsn9MgZKsCdo2NFy1FHOzT%$P|Z2j`2l<72e2f>{5b zP8Q5&8$6hhy7!A+Iz5S<`t}Crhjz9dbWRWXvvmwX7r*eB+F_@~WvrJK zhp7<>ubAc@v~(BJM_9T~Qyb4NgB<^w6dpCNV0-M{U=$1Pe%8;1lwD1krh4SmqB^Qo z3?3fVZg6o09=UZAu9#C|FRyM2_~RxT@L*W8I6{A?DZkl&RhkjlQ9ArLU$hQqBdq4( z5VQj7(HngJMC_3#6ZW`HXlARa(2brfzlmsQq#sD-eevJcff%o4gBj%6LE04PJDshj z2Ys1FzEe5a(;q~ca(;>aQ{sOL59XvAf`niFe?17>?BJPgwk^R}sq|+z9ErdSLT){* zsO2oKtGRR>kWp_m3P$?n#kJ($w4Kx1Mudci-e*gP2Gzj z1(Q%Ddho{<5l%LRJ>tV&B9`DZ=THOv1*|VtoqDbRK>K8+0AY%iGC=#l@4GwWD#v@D z&tOyuq`|1T*1&WI+pUJ3@2wqPQqs>r2pll~69~<(NTR-N2n>~19x}-on=!3FXY#d2 zr*g=c31;_5SyhyuiVE*$Tj|D7?MUx3ZS?NQj%*@Av|wk`0a6~E!>H+%`%xDHkC}Y^ z8mQGUtlts5egTY!0vrR>F-)P11z&F{6H>4_!;0TWt<`#a^Z53va=07~Q;8$eOE)hW z$wsbm1FR>E*vl()dDf0zD~Y!NKb>J^&%+l{^X9{RA@2N$r*4wh4d;tCZq%B**nc|d zUQ`Y^QNWa)r$^ms@^EXsO&K`J7uCevv(Tb<|mfn3v zU#Re;c%TO01XpD=Jb2c(_3Q~y1W?7$wFK3Fj4#w1;)PivK*6Ug2=yQV$@YKqv)YpN z(T>j&hKRHUu$oPtacGq4HCg$R4Bf{K3-@5LW-?6+Z$s8gO4<~muOOyu zp1!T-QoE!`yidl^_SF7nepFLj+5GPY@HM*uCGeGe2@)RZe*U|PX~!H~ z37W3wt&o;bEb5QPAq6{On=nO=-_Ih(S`p+;?b^%A5)WkvULBxKirw$^m;tQERGokszrr zxMu4L2ljg9V%6;E{Mj(Okw|`hUT3^=y?;I2&{zWeyFj49&y4}~-`;qI=_f0d)@#Kw zu)ee2W)g(oh;}!vzSj0325}(Aq-GGGetlVz|0d1vYc(z;zh(npkpofEO=+yKm%Bj` z!0uN#SI%4TQD7Dm6s51P1`4D^+2KLV)7y`q3F4XwOo19E;u#7TSr%g$L+Wh0s{>Wu zLrvYV0ab;cz$<>E5;axK=o#mf@0R#ycAPY1LNauOtoN4)x`E<%`={`O-U+455iMs% zAZYMlPaEfIusvHuv7{gz(h1dv5`YJfJ#9fwHRDZVI<9U;TxL_!Ccnn`-B`sC(?HZ) zIbwb|c#r#zleqfj1{t%x0S95|Z~PP+Hq;_((w=3+piicGZMfUnKiu(fLp$wikn7`q z1tu}8b}SlKoC-`C>(rHM!#!wNLRnl&He`O7XZLJe3LYy&lf9)yPcBTg9-Wz`wzOpl4+%_4*IRnCM0g5J;#N) zl%rE}&Q1ZqElK${Le&@OB)Si*6Pzp0RRBvk3#_D5QS@XI3o5|{m(i6|%CG94AR;u{ zByRO-m84&Spo!=0eRtsT!nk}K?kD@d`+QP313Mj(t}v?2)W9+-1{#`8DHZh$4FQG8 zd{a|*`tjE;X>|3!Sl;&UT^#|yQmH2wg8Moo-%Ejw8uE}tMF$jq$|j}1J}qoNPLU?m*`_Zhv>v!0 z=w5nBS!uJqEsnBD@GRej9K@uWBXyRJ%B!}tN%-d!7F}rOHMxS=Mro_mM z=dH2r{AhW`2RF|KkR5F&yZKcZ2)3id2{@&x61XLO3!{)vYZts@qdj#b`r&fn1!}0s85WI@&2UlBX_U@x;78+enhi!VRzNI7l2@-LUG8Qx0w!n5 zjS|+7jU=$NiJ?n3*AhaCzr>xpErW@tN@uv>%r6;zMO zZjD-gqHj%-P3-eNxF~|XFrrwUT zt&I!4Dmn^sE<~8}(oqlzQgk-08>oK4pdE}KB~&uho%}RZ{Y&fBRj4|{V)Okga)6t)6b04ex4g3YsqLXmr~~tn!2~+VuVnxIh=) zScJh;g!?57e!cE)R3lGpt$d&7o4N4cg(3}dR_2MQQK6&Wz?BAn3NbA5uQ%r$m9 zec!o^27QG5)=r0&lYg1XJ$}qutovVq;PPMc02hJHn+1SGcuZ?W!~D%`yT@~>^_MM? z9^THI@FXKU%pb>oW$^2I_vsKpeH$VgZC`4vyMIpDnSJ;qb63ezIBW)0?*C&IB91xq zzh0r-tTh`g?40Hf8G#^fZmq9S`5iIuci-PH8X@L@5@M`3U>YIGG$*(P^N-}8`^%%) ztO<+YT}_SWxAR@9L$<0I7+&3sB!4y6K4Gpjm?b9lfu=rft4de52#5+nrhfieXn^Yj zV?Sk+F>rX|c#{LGMsEiPZdvLa?tA=lFSbC(shb1nb~0+1=~~mf*I9$Behl4e zmn){70)~bU@i;>ZSPiuqy+{(nLC2Yk#-q_cVs~dS8qG9bq*!%7OlQA_^fs$vwjBjf zQHP4prL-V8X;%P@w|^HYiARF_gJa$01@l*{s=rGVPGQ#DbOf`%25Tv}nYyE2Z+%yOV1jn>Af zV9Cp9jy5>m&&r}ABq5B_KsXVrNSaE07e$rDkog47|wH zuC$v3s&f9>9-{5o%oouEuYhl?hOk#uB^l%?2@OG*f07qo>12`)C!<&)>79^+j@?%or!?PQH4T;UXG~Fl?IikoBoFlXw`qBx>Y^bi_d?yf*1xPAjNuw zjGsn|{-d~T*gL5(42-VwpGcr7qh`vrhK!&q6t$&+oa{2^?(yto+XF_oMuhYBfh{r% z{uN7KWe46Y)dS6?TFd9>1h5J(GzGAHH(7I(C-? zolV^v#u>$|KNq@^h9<<#gZ=XgT3BQ{rEU-JO>y~vTZVyQ^JH2rGq_s9_Qh>_Ezh$`jfwQ~fZ zHdV-JPR@>>w%Z~ZH?7nlG=;MYZWlWt?b=di&!hGa&na{GDk>jls%6PSZ%x`;Bq>3& z2i4CLw6oiYQ+5YeFES%9!4GqDKqwZmPPceHyHT9Tl5nH-Y`b;8c|03lI2^VNreI+D zX34(MTbW}gp@mz#BMqu=a|E`ciTElimlip^C@VeQLEi}bWZ!1~>dQe^@Q3`M01xP$ z1qmZFx3;j}e7c3%3nO+U$yO{zk&?3`w-KV2%}P$uX<|ywc`$j(hM*W(%7%-5DAl?3 z=?zx)ebyf0%*@?fd+-tz2UCkkt-p+cM@r<6RXk+*Pr<&GX%E?<2{XoWYx1xA|;uuEN&YCI{r= zMaUKr3Dtn>g2$@&Fb$r1q~x()4)&HJVshZTB0oDXdqlyKE0+&6a&XY4VPIfiKzt~Y zcgs(Vdw_IG+m5u`|AW`UUu&tWgrC}5&cTfD+CF5xmZDJRNc8p^16sym#l#FyMGXy{ zvX_cTB-9=ma3@P5;=`SWP)&C&nUIbViF02$7-qW^Y!DzCGaxnL4PK%5;7#e0@Z4-v zB}ROsuqxn#Ed^Uv!ek{!Su`0dJt zf9fm4#M*6y< zA__I*cb#GXs9pTTWlkIDjQO3qB;wk$qev8M&P2 z7Jq!mj&i*ZvstCJpCc2;q?IvY1t})WCYTEa!D?1oO_rDIusoO8=k#IUb_Mkz1B*1l zOu@)h!I(a4A6Uu5bG`xTl@iqhN(V6Z)C2VDt1kD-=Y{c6Z|%_CPqnhDrp$oMpv zhuy!7If9LttqfODkY1IN)qmVqM z3P!75WO%YD7%Z1%8Zzmj1SYJX`$e7V?S&X2{?6&~Tc#he1c^U&M1k1^ljbQ+ugmq*ThzCs)!@6ofm?4B*LlV8$t#jPRf>SSstS%zYU>R+vGfr%Gqs&!m zwG~va&x&d3JU=((RZTb{qh(2yabt>jl4W2d@04D*Xx*=NHiYZE##n#i1bz2DVXEn9 z8`deqlp8MO|Mvyoxg<4^OrG6~UvsNvO)-7|^aMr1*TzhJs@IQX{^}J)e{4%4`^1;P znjXr1cLSs0Tm9I1of@mFpg%|Cv=H90A=w{D7)$A9y)BPBK0NNe$%!+Wb%r+qiRUrn z@KXtbOW;giR8w@#Q?Xd5tfz_G>H4sQW_Qz?b)qr+uqW3bfRb2fi zcD$JVgO(~kE`F<2v7vUyMNfd>gP|iCnKaWh77SixS&LZ0Z!`db6&OiV#Ay9kv1cQu z#cK46{uNmGb=;R2OH8PCY&SGJZIzwQt7=p0_34{r&!5?>e;>WD8~9fX2^cUjE11U) zVmv^rK!BuZ=zEQ$*7jH#$)m35Tcu9pg^=NWuR3>GS!SWt@f$Axvz~Ga<)HSDh+xW( zY~Fv$H}6G#-%SF!REYB-LOMY4EAq^WD%8X_5(rXWs~S>(l@}KNL5UIB0yOj+E`Bln zpbV^bLhj@n`@7N7>6oAaf2*~0#@KruuknsBkGU_D-0=`u!XaCVh8pxUue_&Ny&p_(q)1C_3?K4zT<6PTY=@7?D{>$kko09f> zn_Jlsj4>=-LuC9BF+ zB2Wk#?8=3kn}|fLlVisGWwKP7D~GS-f&Y!Dj%mo@RUlA|%|~;K|0~?4ePeGEFSc8V z!v_jA5rE|_z8fn=^cx6%KbCUN$d#Fb$1-=(q7?J@>SlMBz7)s9h^VAf+qJsRblu>G zgSeO;yK`A(_vByA{voiZRQtzS<-qIjzkkKXN5XsL5dSCtRD7#ia-|)Y;Z;4 zmmT49-FUr;H=Ph`&sBh*A%I^H(gxK|hO-++rRB(-+}!sWRYAv~T4AWAyWkT>3)JFY zwFjDR!X;$eyGUT_>Cve|RAdMjaE40&qCCj=>qGoSeXo#+EH8er78LfWIT)11Q;yXo z3GC!jfHBk#a17#@yobHh(6Uj`UjNq%Fm=)dQB4@PD*xn0V*KYj0~9w|{@x)-R`k5x z+u6gDcJ+HU&b=&i<95FUyB#YVeWbEQZ#bpL`;E5dP%EWpvc#{~P)*qw|rR==WXdd3apr)y5Opt$4jzxZdOyfUwdHd z)$`jcTkfa-7Dpu9oRBx2EnEx-zS%vgr_$o80;q6Qk|kvOx;64G49jYs+@~kGy2@Cl z%CFIXJ7ILLE;jvzb&C9RJrrc5&!=7);SzcoYxYW3L`+&sMmRXW)Ev2Ip^Jr1)x{zey2dfh@wyl zpO=zNRpr>)Y(u3Xa1@Ujt7gQxH!n-jd{uWNfKlOY=B4`*=+BW~kuv%N@>3>R3p@oX z%}`$>3lLTSTYAmLa3j#sEV4nU^#Jd#r7jnuGkLqeYd9BLyK5lk^WlDUJk_mDB4KQP zi=MnNX8MY%^r+u!^cT@c!kdh;ICY)Mr&yG zToXg>s{9&y06L&nDmCDb(D>7a=F;HG{gJe|1*)yRIyH3a0<7TZglGyk83)HvtD~a; zl$JJT&NU?MtQ?K0w9HTDUp#^3H_)ZOKH*NS3oK8}=sI4!L+QraGNuP!Imxf&)jO&( z7W5)F`#8M7YtDarlRyXRt*$pdn>Aw)rX?)xeyy;`86S_ONJ!MNvX&ol_mSBd?k1ZF zjbgVx8KW*pmn_|8u{<}l&pqH2Rpx=#AF7U)si42EvaPQ5l*%nF9l^loesd7af}a-m zB*4yAy13VDDrAa_^=Ru~K{GOx$9_Tsnvo4^cB}HMDAQzfaDAHW`7D1Dq!Ge>N|G$A zTG6PEBU}KECpp?~Y;`rHQ#RbfOgOYY7*PEnCL3Ik*7M5DBt!~azm3sY2M2TSuY)G~|W)SU|2D_USPMMiIb68jV-aTC_!8p;Qn5!L~;n^m8O2yR7 z^|)9)?>Kw5YnK%s1f%UV%i?ZKUo0ikOBBmuHia`ILzdSU^uzlw%Kc8VtWsLT$rj6X z2R!PEN%u{c5%A*Km(?FQR+X#91>bCLAwN1N@Egt+*A3DD8fMy54(9{WQhI&nJs_6^*^Vi|oMs?iOw z0j}RX4aS$@XxJ`yqpRtMtZFG!9zY4?3w5>?{j`$&wvawMyUWRKo4+Xe((qex@Cn@x zUDaLG{8E9LPM;_e4e**e<&v2*D40ty?c901;$S->N1wLl|SCaEN z#z++u9`0w!#Z+-IyMf@Wx~th zogRsDL#_go7>a8Pm09Kf>)F*al~x-y>>he6*F|U>=ln~JO}>bBb=lA7Hcs_Q+?_9( zGmIxYio*!wf?p{C;ht;^))o%@JLfw*cT&zT`vEbzR?tXTEM zwH^L9{h!2roU27JVUt}3KW@OH*AE$k z??!dr60WZx4BUg@qjd8C%3`dmcQ&jaz3PBzOO=H~`7((F<^Sf6FB-&tvJ#hj{0>TM zHZ&T@SW|WQ!-UIuVA--7@BsxR=cpwWnon43R&ngP4o8o$EFCKv8C?kKFNjI_88HHs zusIgo)*Wb`5~}z?@CnGegayL}?i8=9gz)iuB5(n zp)jke%o+lX|I1_yPC3-El9+WIMMVWMTSqfPG1MR7 z50l?j6CB75M4Z1@(KjxMcbM8oSn-jUSsi=Gh}&s&tTU6i>3Ce-V#UlGhEh& zCjzz<+75Z%bj>8a)*9@v1X`-nq70N=`IQG@!&on9yR#?Bw8Z=nY_U-0 zDmZ+r^<6Z!0I7K{*cQb69xZTL|2snaiw8Jw>wWFBmnCVrw*g4W1 zChUBzGPv6#ig8^iEL2#(=){)c%dNHV2@l_yRd!<1Co8UG<}S8O$A2O~#6TV2N5N8! z`2VELS5fuVKDk|Spf6)U@4^qVOhBOkk5$8Lg>PQ#YHh4s2EGWhc#SyyLbxm0=e5_} z5!ac>0nse8a640)>shTWU`x~JUKefho1}@J2v|-3nRNQ>u6k?Ta-Bosy?@UFYRMyJ zRB5le_6039N8ws*!h@7#HYcaotJ1R-Rj=^wu!bw0 zHxwC?)JV1$j~=Sj$vek)jtwmq`U6L6O@=2Whfx&7(>Otd7EuPj!EEU`ZoARa9Te8o zmhKUVqM-byzv+JATbS)wdZ4gK35fRZ=>(`;aMO>!b*zpQCU@U>+nA1?s#Rc7mR69X zKn-5lLaFRXfh;sKCadt6O$ejZVQeTfcU`-lw(o5@OKPeV6|-7KOf3*mdN@QPVW-A^ zDn5;dZA&+f7`KF4jzwf#*$XEj2ZnI+?A62X)~q=H5GF%$|8gbHSm&s*phsyL)hDzE z2}n5P2&f4qSTP0$iRA?HrD=^$VbDDVV8dEwh05aeL)MkM!;d5*&NWo0Ri z{?JDbG8c7viT~y`{Fj4P^{klc)HeK|+YRb!XQ7wR^TX|MJiO^^;)+c-GxB`ZH^h1P zUa+=0%zQDGK^-pd7d2HD`PXAL%7lLNe5I^!x=gpT7IM9^-`FhF8U zAXw7$l&~Uciak^Bi*MJU33(;MX}V4G=U_R9>j?Iu7zOWK6>FUq@66@y%(^!(Ke^(a z$bn`jQSjq$Q*b#P#E%`g@4e06IhCtzq4t%LKL(=usTX7^e9<64){=bRzMgfgux_=a zg7~)xY}Q5W1zd3-A1bdJ5w|5tX;O8Bx5BnzK6|mOUxZ%>kLAl}7Th^M+VnBfCTyRIXh1Y^ zJ8TpsdP!u1($#-_O2}Lclzo4QW>s+#wyvX}`Ix})E9g4@iMo4%NCcw_KP+)8I+H@Q zh9LRmFS6L@xI3)H9Rn?g5U^<~YjM;B2s$-Xl0M(@4=|gqawj{SbATOMTGsC^LJj~Z zZmQMJsrB1O0;co|%P-yF+i}Wf3EvMEemv)A7!#r;JHz(aYHB_xk}4>@zVO@(jcbMf zhQ{_H0K(dC8r8m2iIIk?ji+6AZ4e%U;6$vbD%Hz%aaQjX7y7}?n55L&OM*EJRAl(G zre8yHnt#)GI;3>}O8t)@7ULr@QDzepu;LzrV@Fqisk1FDaj!95v0aRWD2>%jz` z+Gbi%7TU^!FI06Y1I@DI(C3y`;>Yp>2W(RXg@%j)_ik;#vBYh}!@O$63%+yS6=p7a zIplP4Gr9u$*HEw@V1RiJ4nmTHeT(#RtS#mqnsTv;hi9wm>vtKm0bi6E+3wRj*^to| zgQjW`*AvBwO%&k}?R_GN_89ZO{)N`o+6$I6UR|&Eg9RfCukYOy2^Zg#u;bJ9%CFq5 z>BlrNHD6)HB^PyV%~aw&ud2Kjt3dkzrvzj~l(bF8D2tt$bG&EI3zGQ)bwcYLERJK= zP^Ggd`W`M+oegBJD?AahS9I8b&h9xO_~FE4rPg3dab7+rx2H>=zUPs4)eoFpomide}$XKoRWx_}K zS4M_*d|tmQvfX!Itnt&W@WK$gs#^nEZqg5SA#_%C2g~wv*(k%P$AjE7hP}oRogOndvw`$=2z)CcNOQu+GnOEP0kGiUEAp zQSiH-+Dn-q1^nk@GoXApK7@AG&G)n2T%oH;S|`hIdIQ6Yrh;p2Gx&Fp5csQ7C(zOU zAa#rU#m8O~Pr??J$@n-y=M>$E`6|DR=22BPXY(=|y1oizPGCenR<3{XJ~5|7&ysW^ zJdevsZh2(*BJIQ}Q4XQe;_c~|u0q1Qkw^7Mb?xueBZ!U?q8$IAHDV3;GhVFX3HQ-f zE^BS6l_vNsS`$>^1EriiS(cvpxn6~{ijA;Tdv06U5A4zLHXAgXxz|EWFuTZ!E1!B< zk&Q7{tpfa1X4GstV+-vsU087?3w@cd8KtSJOw%>&(yoOxpt})ps{;o~98M)DL%XAq zMXRbE1^ieYf`+`t{%c#`nQZ7Elh^gB4-xev!DC~U-RF1>35r-CK_0d{mtm>-xEyVc zbqtk8w4F(jmGzkzIP^vIR>CblAk614zk-AvrIh726_xnc$98hSS~m1Kk+TrelI9<- zK(!xwj&dm`ij{rRYMEzJ0GDN6n>*<2nRcYCDm31>tyRV)I9mx-ox(P=lUZ+V5P$9& z$mm^HxVS~Eg`)eWu)oL%-M&4m`$U?!L(GZ^f>f#(*?v5ccA;NY;%V=p0M^9H-{WmSn81yiI{sQ%Oo9 zE1!vU_Qw*=2gMp{u!>T$p(oGQ>iy6`ZE;5PbDCUM*Kuf(CtU|#*Gwf9HjCydb89L* zGRrb+3d#!f=25{CP;hq_zQ&qpQCN;3!$ zNqfz~9A836ij#Msd%|>GT%2(dp@a@A(%IZKk(s{1i+n|g+qDG6Fdij(QQG$zn@PH# z*1l*#{S^ZXkv|kpl3I^qKZdGqob#HXQi7eHWI_MQAxv!4UJq;^Q#P(ejs zRwn-SVn9=d-V!7#{8XytMCMHV{=mUw5W}=14Au#MC2G1V-qTb>F#ydvM7ie{72vKd5lJ`w^O&~q+<4h}M0zt2K4YEzW!%31=D_T` z!#L^P;!4w>>PhQs!QkcrOeE2^XJ-KZy)C)#Z z#RL1JJCo*z+K0aqk^yqCl*H~(q}2yJ4gC)A1S@PA_#3{^_Ya&SX?ZLH%6rsl3Cuuj z1hT(s0Jbii_YX9|Sz4%8T=7g;_1T4!4x70nTiYa)m3i~IqN1W+KH<<*34P1Q6Kq#d zR%G@9u{!uRuqY+PJ3s!Xb|?^=xAmWI>suGzB6#(cg2kcRHfakYd_ScV22}P?a zkEhjYT26l*3Vg1#0P(Rs@f~*&sz}UO|Hjj{2X9(h+CjbC|psbnR@ zo5jYME9$g*tl*&Yz9MocTTP~_XWaei3L!StS|U=upS-ZQdDsJC7E?OgBPpVS*lqaY zWUawwDXL@nN(khqjR%%*k7nct@TWe5{6Y~RT0`=V(!`SD|5;&g!(02239He_LWAmO z%>l$|$ey7fJeNUH;bM;0gVOALs;tU<3>#JsWjFO{e-B*P;_zheC6l8rT|7qOh0V{w zwU6n=osTDdtl&M$tnkp74_W;i-qHu7Wnw6jUOg7pI>aLLw-o#dsk~1sFvtV&}>&r?6 zd2VNqO1=blid<0+V;fMwW9d)tpXPf73c$>!rd7xRaKOJ;(qF}k7RROMoS18QZf0^h zaz~$PQg<&Cc4Wbt`b68ojZr`Nb9Ni8)DZ{bS3LvdAa3PlQo) zaHSck%bU~clw_0*?rQ{3h`6YFrzPsP(C38V?`#Y zM-C5s{7td3cpEyrK22K+6eQW6)H1&hv^TcTGn1o$5weW^T|h*na9(%*eBT-yoAAcW z?G?p0u+s=$^2|}-BhKkWn6HG>10OtZV(FPaHAM$yqubWLkI6MeJ5#fL88-|3-HF8; z2B#bViPUKeSrF^{(4vb2 zr6tJ4lM3y7m{bE84-KH2di!k`>Nu8yVq#)~a*MTS@xWjp6*DDh++@WRSOPt+2h;}5 zHK>Yv`CJoJaOcV$3P9>A8k+aZh}tKvFGyue@#!*7CqH}b#zVl~9mhW$Rcj;tA#w+g ztVj{x94hB;5#Ub%jfYmnh*OAq!qcUN&Nn2qdcce3A;Byln^q7X%AaC@~*xh;fgTbU1f5yvV3%O zw64v!Y2mGicJobaiGYd=FBa$(^n>|LiTq&^o#JAwTc8{B-^m6`n+tQ1Cocbn-!FoZ zhUiQueE`QJQ?Vo6X4zF&;kFj5!Ko+-fKR>QAD@W)Ce)e73FJI2v2X%aUCo!to|~^9 z4NK=(AfthcSN)K=;F#af%dh_ZN*BLg|X5CYcA?M_!r{e2!jRKnS0Vy59|egqIpR648D04 z1*LLl{=9nqjFl!hoda&s_VuK|*^V%QT%0K&zl0vd6)DfTg$e|%mu{s@E$HBqF4Vpl zN0gl;-xrbD6F|cn)hagbdAIEr{K_fNT0G)1wazqT%; zHxEr4JaTp*1Dqw`5jAh>VPMyOm<{SFzAQfgo`t>)e{TeIA~VHggzqDl<2&d4;)r2~ z`UNf5f-0`PAID1|?f0i2c*q{gYh#_{Hhcj>6zy2kKJ>BNC{;E?n#DKHF=#w^66X<2 zMv?i5p<3>);Q9YFgwVHB0wldZG*x7SR93Hw?5}?_f#-uju?CuSO+^5#+>hb=8ea1O zSv7A;GYNku7U=YwA(&2)+U9TVhIOsFHHT^mx;zRjrh%RSvA*J3v~T*E5JI*y6g<$Z ziwPoxb!AL5K#xSX+|a@gr6>;Ys1vLGPT zho;VcOudYkkoGqdG9%r6Lr4I~eEFH<|3gX*kCf}l0r@jZ(8$nBvq93ymg%V(Br&}0 z9tM`WMv_Z9NUh16WjlfUS4SF!Z=vczh`+Gp{uQ(!++m*9)!Cn1rk4XjaF3$rSdb%q zB}5sOYJD4NT}mXG{g*OGYM0frR_`Eg;(VHpuW;$MDg&V3Iv()bcH^H|9T1Q8ntYz_ zR2h(FgYN{<6$=IBNJFW=m?xXv)sHy!GOS_81DIIp5v!gU0a|j!tXDq4&15Li^3oHo z1p-gd$PqHsf7K+*h5bMt-1zY)JmU_vK8~akKx)Kk*b5;tEtwhP?mF{pW4CP0vvw@T zBwQ4N@pk(+a8q8LbNk}6m1?))DbOS%&7C3aKnl|PBP>d%1Le_VwW4k3t+BFHYn*uf z2<5wtK~i_WgbMCkb(NACAN4f8Y=!WVhg{K+F|$$C-?RFVeeo{xW57*)zS`4#uDr_o zVg1nrEM}&foD35Dfhku9SLg4#y1egXkc}tZoxjC3%}-w+GiflQ=7#-!F_Lc(Z7?+* zA}6kI)KoN#^cu-E(BF&mtgpqE(3nJuBbaM9U+2)HMB1vm9S+B>=^f_uK{6*2xRVcW zm4#YA`jtVdXD2MJ0&Z;gNfnO(dY1yp@CiZam4Fe}u@D5bvd;DgjSNBMvxLe}kk z`L2dOHt64kPpExZ;1m1aGia(_6F8WUCuZm_!vxn-Zqf!3&>MJYaiY#7!RM`lO z<~WQ6&6rYE+)SMJ-cLVdR~;AYUx6O9h1VD-U6&gmYnE89R^DfJAo8z5^h(Z;hjf`RTB!#_$O%j@hy)CM?a1+xo6`x zbeuC`JswFy5X>M4LvG3rGjf_8)y+`5K8rP@ppao!o% z=e&QG;lWv6L8l_`qz)1ie273EDh26Ud~Us74%by|_)di>bQ}KRlrXX8TCFP!9#_}g zp`DpbGd`aledmt-(k+<#;VH{R0!KSE@rzfrJ-xtl+*XHGB7pQ@a_Jb6Xe59Hw$>gD zi&5Eq9a}Ak1|H4tk{}^iD)l1S^MT;CjQk57krEEPI7C>l^f=*~)zLjquA!>)E^-Oqnpc03}1)sUu<6n#z85 zpo=6eAZ!j<2#>eaflLpv3oR%9L&~^tpW$H?r`M^yksyCF!xCxv2uPZJjGs_*zkeaw zhX8M9VJe~Zy~;EkEnyWT0badM5hY}^KDOMBUY#x|B{n*3Za;2`kWH}e@PKP;T->v# zP0P3^2m6O24*!^XWlxUr&Rf??u$S`ppm6TpvlcK-{wNc3X-6oX-EpLh_0fuz)v@$s z?a}D`lOIY+oQMb2B+`Cs%jJ9NJW^{Dy8wdC|4!+0Yjar>;g|*(TGMWCI#j#Hz;3iC zM6YDgG)4(J zCSxFFwm$a#i2%6>qyAiX7ahSx@wdk2nov>$cd$jGGfvueFFuD)wG7UhG&1P$esg`? zco;qb0GNG>-b^T0_df6{HBZ%ou+(?k$P95lnyhz?DX(>C>sKBvVsQS1iR+yYn*@Yc;L`n`Zt2B9c1tgYGP<_6yrV_qeXQI=aInn08`X35^`@9Pr6hD=e_VXA%2{ z*>WZl``BX92!pQEE0un8`zx!lOXRc+U~B<)@mrn{falCkpQsN z009eV1F!s>FMHEs&}g_-9*8mXl%hJ48T|FNg$12GlRuP7O3s60^nVpuwE@o=u;DEL zzHmD^E|F4FB1N}n?0UKl@@f=IIKo!h+3FsJ&YRiSN`Zy94=j!oez@9gF6yeQFB?Hp zq{eohP4v%#Xo}!v667 z@gP(?u(XE1)~kn)dWhi0rCT`wLUCCk-kMBm#SQX0>@8<-iqJMb%QN#cONmXefghxm z1#5D~#M|hOwJW!*4PmDz=wyxZz7fnd*+#e9o0s&I6jF}(#tLw$Y@rv&h0i>RGDd{& zvesl(irWG_ZY97hAtm2i+!)0|fCmD@H1ka8htbUeY#oQG zB$fOwm5MfA8Ssz=E2hbC{Aih>bA}4Qv3QlPjaeA9KWpLrYb5ZO;*AJ8(aN^aOfBS< z#rSk0u9~a=&}C4UDm;Ybt2PTHB;$KBSU@uI{&2L7WIHv&MGf4}Geys4rHO#5!i7EH zxW87uxLu@PAs*X6!|NZ(MPoeP0dO0^fC5c(;te~Cp3x~&Cqw8RS?3_nU*bFNittS1 zLsPek%pfSg@vy*gGoZ;m$P*={gPPrjA|8)612&h;)8xIDq7jO?qdva6$P%0E@XD0* z8t*1MJNu96*s2^v>sq$KxO`+=qoE}p%O;{zpYV=d+FDl|reppV{9QqnYQesB)6jza zSx4`LdDd5MgJ9#zH9bp0V=Bws`;y&<#HqTH=+47w{qx~>Xs`<=G$#2SizTz?zIAk3 z74KCv4^N2z$jQET^e+q*nf+!Uf{HMOTYQO~rN1s)6AtfLBpH^HChs#6u3ohL4Hw^} z+=93dBiKdt(FavG(SWy9W1;wm33*nX1XWv9oCb-zyvq4HilN)RQOM0Tii6Ie+d|YS zSIV%)a>3Cj@*{6bN4HGhK%IA|fX7F3eS+@;13K(9ZRakG*7M;OL2#c zwuq?6<0u^VC%mQ12jG)`o$ZahEuB^dwZ%*Ef2L$JY(UY9*dtT|xRiN&&w7&IFI3qL zYh^!B!z$b{kUE2(t-6VnG865>Jc|peyELzV^`CHq`j{Dgt2BHu+v<7~N7^3G{nE5_ zeKqavr=5=vte>5y^!8b?73*-SG}7L^-A+Shvm_kehpy9+B5D_-x*GB7LML2pJ1u_v zuVmvY#GQQo6NGX9u9geB83t`5vb&93Fxl_S^(!p?2_QQontdiFpCV6~5@*;C?*Fv3 zOhlHbuToI0LguM{ILhPTdbQTokp6>(X<{)$_WsfH`gQ4>22QAxx1ogS; z;6XZB>l}eQrf9o?wE1OmWe{gZsbwu^1U<-ER7(HUGu^b6tBTvW^4dwty z572GE&SL@uAp{@U1x7O}`t|dm@Z?$)iL0h>MnV+o9<1DP^V!fB$%l!3529e_5Ac1^gMpKE2M4sH& zh_(=O+p7IJY)N+rkFuwB_&&1l=%TY-!l{LezZ=(C3Ow)h*Vk&Iaeh$%PDjO6RFY`8 zUDBIPI}Nzs9O`Fqn_XP5yz~U#S05*WFeMYmn8(`j4iTuG(Ws`6BC%E8=^ESq$B(t@ zvZO0Xi@u))%IC%}lk9Q*dFZ&p8$tV2gV%jHNNQ^`5=j7mLubho5=NFYy|avg-KrTS}5%)yGdfmVhDiF1cBY`}vLM8)px%EHDSzM3q8`VJDw*Zf_2 z1Za>chRv>gjF;3z9sk&H%6n!m>RS%&XF%>t%tWcKJO<{yn6%0^;%R#oClzCsf9p_) z51`(WW3M*HNVM=kNwwgv;Q+b9ZF-cZQmb_gQEdcB0WCe%{Hg*qZHUwu82^8ZtgC!3 zn&Rlr;qL_|SHi^>-**`-Zk0|;$eQ)(y`epPO2+7Uts<~FMb8_$N^;~JzmNpvBmFS39dANXIcZ_KQd08Hkbug zkrSevoD4o=4w!*NK1_%0j>9*sw)~EepI;M|3w{9bLlyZB+BIUEC^Ia-m#dYJ89_u zH;{(b#DmWrmQ?`dU7ZaY)*R@SR?l&pp{M(D@3<;V#b_ZZoHSQwAS`T!Egif$Ch;dw zLSNa#zvO6cf)^uoVq>8vFYH1X0(YsR)|kn?>T=fL8xZq@$HCZ(F!9H}{&B$BW1y>B z{ci7OS8m6Tl5u4=XW=4hp^kp^O|><8F1#Bd+nP1&r#9$r2ko;7Z)syjLy}c&FxEYn zWo)%n3yX=mAad$Rsc7cv8)GrqsmWAwzTLhA zjkF9DufQKmtsB;{J`RA3wQkRNk4GWaY^7`0Agq0+o_671+@FrXfprRaJ5H}Y)7886 zh^HFlr+vP$Ah12<1`j{kGh z*mWp@PJzx@(lA1Z>%#M56ohNg<6#z2p{v;0xRV9Yhfic~j>D^^yu@er2QK~2lE&~| zCI{f`K2Cg)C5pg4NbrN@0MdXRaP3Vmks>3H8=OSP4x$qN;0!L!-FwfNJ)piq!)}W9 z|Iz^0tf6^+h5QI<8NL3l2r9OSUdOzv7ytxu{H@c!Of`G`UVBG9DL*^^p7{g@BCv-{ z1`p}=ZMHZ6jk2p~Znh-PMQD>92E&Y368@-PWiaKY^_tX zT%vtG-(E+X0genxn&GkiF2F!5kV<;LmGyiy73@8;i#MIo;b&le_3nH9sjD|zS73P# zCu)0lOW~t@=$ZwKR`ry{BX6fxHM!t}p2n4x&6Ii*rM4w3HzRB3EZY_PraheAokleI zqLaUxgo>T2O1!7(fthn6^yDH`h?(sCFYjJ;hPZ5gYhBu{qK(Z^}SL4Yop?5<0kc_HZzWgf`A<^V|JQ|YNlTqP@E_BGd9 zbM~A)G+ZWmhl(8Edk495(OzdUGcqNBwhtm>}TA3NFB!Rg+23 zm=tvKBM-Jm;aNxBkqpUce0eH)9C~L9LBG+ci1{kFVtGov&T7jY-1K9FR8g7{YNS{4 z<5}gWd4Es<@l49tN1dI08w{aHO~IIH*&7!cJ|3l$Uq)rN>=A(^fc9Tb=uJbEQ0KpL z*fHqIhqPs!Lyjni5h{P!X_jf)3^1p8G?0oLbe6I=jI*WR5-y)^>B+~BcUHw|iA)vk zs|(c${A3NdMZ7N1L%!7MGmwJ`qMIwmXJf;&$>2zg&)6X3AH<3WN<@QRdVOkk1KGb` zF%l4hI^US1UvDe-`X_6Z7BX1p&$_st_}Jj>o*ULSz^zV+uy^Y2>H$qA=E=PCFf zUc_J(=mSU-=y1rOS3tTGC@}DZ%!Lo!`&UZKp9+T5s|+OOTLZ^oe_kq4m%SRGy)h0m z=@s}KU(GgOXqMrkS74IgqO?cfDepcb*6PWS{cny3c2OI63p+z!MZ!iN9wpn~@hEX3 zQ*;wBrdUl9QS#_I{E8PDlKs=5l`~%YQe0PXa(8yhI67)ClybyY=#N8in$`>fXhI0AKl+F?? zAZobRQ#tCe_l2il!PUL`RX|x9`iEsx$9B{cMtPo=;X*6Q3ixUb(T+LqwYNvXlLgJ` zVSZrpCyp_(O*999_f|_j5nJ?)rv&X~vHJ+k&LPagvG)v>lB4@QCz1t0ab;U8T=cpx z7tb}M2-Y;^sqbbLcKE3M)xN9~AZvNVN3I_6Go*z7mv*A-Ceu*)ONXRgKIB z>OBFu6*bzIi*PuSv#N{_n7pQNbzakME;b=19KR{hNucJzC!vKBB%90?54c!IKfl6p zF#%=#`t{dg+$};JUpgMH4VFJXLF^3z<U z8L7TYlb$XrB2SVNFQpF#!k}2J07lw6Q^$|8w*~B_7G|#+(`Zv8n|vdqjayL{>nw`X z^j-}B(z1E>xXN5Dqk=p|ynagyPYN)HXhP!R$@g3VDTeS&7kbh6u&Pi)U#0T!zAhAl zYIky4L5Z(v>{7WCph+*eyT5B-9?)RxOR0k5;yQK)jgu_vIom-uPo_HG_{Pfi6_wz2 zsUj5SbY2LEwZk94?`M-P7_28fUB%A3FZcEJ(tQ?pWSGTrpn;I_Y#* zN%>A3-&k!#GcAUwO3j}(g0X*!hmQ{#n#{v*XJ_;aWNHR_D)P zEG_;ge5oISLD@7N`rpq2L4CI{blpq5^;eY8zd%v)B=gbIUnO1j0U-8(ihSqa(!*%u zjL#1{?(6%>!hCX$xm%t;ndSo>^2rdfrSG>n+Z2#6l;T*x7IBi3oOKL{`?0N>{A743 zj%Rli5EYdap0mu(30{2B4)J4`!*DTCcN?}o%!koX@8+d@1WrZiI!rV$BPLPutvfDP zb$YmYr9MH)2`f2I7+A_=wd_J;sId~6EoU=iWA6)MCCSG-g(Z*Ja=2=X%u|wWWrmJ7 zifo2?#xh)PRH?b)@0x==@PpVXPJu{c1 zsmJL~I!hI$cj7#?9($n&k(bK?9*rc5_MlFtN;8}cK;LhMS z{C4YDM1v+8bUvjmo-A&)tPjENf&TFv`$H2g=2I5=YK53aER$g$-`n<2@gF`hF0GNR zI#mDeLIX_1Ja8g;@*|%e0rZ^(yUR<4f4nBc8d@zu>^T3BBfvr0r^L}zmzc&{>n`)> zdf;PMe)HOvb|J{55i~Mc^Xhc z1PV`@?)W#+ksmdi)m!6uC>x#5f-CsNnSHWrWv7&k6#h^LQ1dVpR%-M+TKE0dZu-H+FPavQ2 zIw6W9;b1rS*}iw?Tk6w9xKD}h~>OHX~YZE2&8oN_7EAZ*HyW? zuOMWjs#`x=MFTKn6fl@U)u8wr`4 z%L_UI(D0h=Fo4t@+tQd?1Wf`Zi%Z-gonswX`~!$_X(a4-a;WWUt89He|37!65)VWk zu=5gCa`m^*8Iqtss8{+8#f%D^4rswu3!MTvuoLwuzCBcY4+WMNcEosj<^*p^?XHHN zXu%fgC2`^MXA09=I};tZh+pCk5;uJ#D;V54v3_nVztdY6n-@fh9dvI33!1wI(@$cF zls@@^Nk)iyW2E|v82G-;Ku=Er`#K0U8z{o=utA`sNqb>mVw%J0Su3-Og7xBpe_&Bu zE-4l@erFo9<&%Sv^!8p0=RFn?Qn*3LX=8x}uvD8BR_gQ0q z@69RCp;UbDGqai>uY#iRjuo6}dM5(tm#<_!VU`PhCl!DwT#!Rs4v`-AyjHnn@(`^vBP`y zQ4~q{E6hi5x1m--ORc;8P4f)ESzmi!_Rx9)1^;wW#eSIMm39P)6{o!2gn}|~e zTQgM3e5;cfI!0A4=&k-!W99SKWf_Nu=#UocI(Av=ulFPgyOZuHq9c}vOu{3*?aQ^( z13?RAxWjY*so`M34-%3$D0fI=LuqiVL>Ol<{TYO=u`IMr$I75&%HA-`rHWWG^5407 zYP@@LHN2lWwcELX|EEBeeD1jwugRs41g0O}rhmb~?ToLPhj|asE?A)6zG%dd7`i!>3t~wIJGVUK|G51w)y|2tW_tKdXe} z3uD6Z}L#ws+PtspwUdY4NRnoh7&0}ABhf?d21K{-URtfcM$`IVEtD}ag%Vsri zZ=*auSTH*LI>1Gw_+020K!N1M!DTUb@}r)&f@b(;N>Vk7q|2h}-AMz+tvTRqW&w8t zD}X-BxInLkJvi2?w0|m9;Su%p53A@U<=(Q+r{(*usetsx!pE#YWYAj<%bBWXI>5Jt z^ja|BF6&gn=#P~Jqp(Yu-h;6u{A1Z%UQ-nbiM`MYm6r6~ho@67i5|J$ddS0i zQ2xgGW3M&B@1M4nd>%y-Nci3OS1ltTSmq~EN$}R;qFW%NmbOWm6&R;3b{pLG%jg;p z9esER31%xGyc|}@(Ws0gErWVtTbx~{NS4|)dq=$8S2~DgFJbC$Al&D~z0oT$mQcI2 z=S`+jre7*vg*M|kQn1f~3QgI2gxS*lxAwg{@hPq%r~goNfPW$PyBScw?Uz`wM_RAhJX?e7gT2i9+kTR0(U4_*TSE`5W zLk2CTV<`Q*O?R=J^2%JNXAKR$9;z)StPf@2XXu}_OI>EEQ8XW4GBKktVmjRtqJC`s zJiR8y;H2u30pHMs`;hh-CnfYs@K=PTf@<|6H|S~fA@3mdc0ig-1PQ;t&0_}Daq;Ib z^R3Bz3-rD7y4%;M^p#pyfwNTcK;hz8C5Dv21js0m3L?C2P}17ICzWtLtXpb(&R(RZ z?r&c)My!ipsHy4#m-$%)_75yZ6>9Bd_tzG0K53d{0%!-*dYv!%x@G4*f@hzTT`vo@ ze|SenRmav-YAk|Yf$5;#IsRvBARoRZ6Bt#p6 zmvntn5*Ik(O)Z~&gmBs29^lDzA;O$|fo;gqbA;UCy+r`!sOGTyC*!rCa6->0kf3oe z{pXM97$pp>QW_A(fxLGNv0*M<_Z&$t^3h&kU>?Hh+1vTUPwnh>rq!J3M#+Y^0h=>J zD9C1H_X=XM{aMiw8opBvG@P@axn&?`=%B zZfWZ}!=}EM{<9x;PCaGDpz~yRsIqx1BW$oW=WVPe5o2{d;xWilQ!a$rWN2bm7mYrW zjWh6Tj0;dVS5nv0y>XFqo{$4|(SUqg1u67nx+k&2$A`P3;}Tt9NvR}o&ik?!^%`jo z!lT8zC>H7UMwO{HBHGHlbnQv3{P@fesDbJ2RI75r$7SzCia*+#>S8}eqe`*iPS0yA zsJ1;11lmvcU}uPgG)hd+GCW8`J~~B)^H>!Gwt@2Fas4_I5g49PkZa!R1Qmk`ss@n% z`w#JmbFWrp0s*5=%RUbR7KeD^2-G_VqVO4`VtHk;ae&G1rr9pohdXI(V@ALLA+<~mJx&)ha(J3hxb(A}EdA81G`MG-r_yh~=)wZYSR2j%tt6pJ zQn6Bky|ajoe7ctq)M>ucqV&w-2#NZm`r2 zN(5D? zDS0dI5N_R5d`5xG#E4gxQn~l)cc}8VM`eGnA!Cls$S-n5iGpPAn5%94tB| zaxV5P|L8VQlOqaf?-Wnwx$S1F-n>f`NgL4opESouhgI0MX3x26E%mAfS6PWa#>QoP zfL`ODu9L5#y6`uzruV*#_n1yT8>>KeQ=a8>5>gAeZ~`C$SA{$8}T zYNG+zsDZkzN{BIZHjT|_$=34y=xGXS`#*u6$pw$f&dLhk_XouwD4uMxRagO~R465L zt@yykBK7rZVRAMOdI@w{2+?A=)5x_Av46R9|6M7VWek12SNV&bv0kyJYV9vMNB#c6 zzf~GhQ=b~SL`RqBb(vp2OQO%cZZ70}+!$+#PvH6XyZubbY2Q>J@=@O7#Pu!;Z4QxU z5dM9Jv!`5VB3;3$U5evACGU@oiUhGAYZq7ObOF~9r36F$v*yd z$I#`jA`XEkoq`GP6J1imG&=O;Gcv; z3V?P65FA_w$bEShyis#(=}sHl!;&;#%Mc_t1}$dJ?OpF!|0EEXZzHo4&$@pa)~Csx z@Q+?;TCOs<3_n2Q%mZ`4VEo%UdIjNv)044y_YQOaoH*F%`&c6CQtxQBM`d_9xd;KB zNYpHTy4Tj)euBgrl_4c68867j;}(Q@_ev*&QxEd7acL$vO!2Va z2M#d-Kt^3i8;m6$U>T#j?K1ffQHX;SuaJqez);0uvEV2*4B8Z(Fd5O}goP-(?4Q$D z0Imz;qa=>Cz85)RE$M6v00-_5HifrNadE^F+9nufN`?Kb{YNt?V6zOcJL(|x;Ed)o zhNA@ULWX+#YvroElYQgn&GChqxPI2QEp^o7qw=4DXA)UMqiA{LpL7+p zN;tsuS}#kimt-v0+o`>P{GMk5U$u!#g{F_i(|olGE7qW_y~&SD!TMvhqWM6f-|g}- zDJ&<{#OYpzBQL~=KM82*KLq1^`YdguMQ&Q8=2t+n1$#OD;RIQK$Qs_L6WfBAAfRnQ zoZyQ|bvkVnE6tqDB~3LolL1Zzg(ntcjBZST(q2q`Z3Wp%^?2HEh5FTe+$*{%$fJoSH=DwB)BacBB12{R5TkLL z^Kak_Jn|F-AV>A0v2{U*8H5L5#XkqMF)$&ybv8_m{>*Qm*Be&G$%zyzU7oT>Hm6s5 z`g}xkc6*Cpf#+qoD)4_FQgN$Yl!J({>M>X;^6U z_{;(K=)&-fVa+1jf12w3?4f=t4~h7+)_M{tBa`MSE%Ye}S%yXks@!L;2gVtn0+sC& z%0L&fmYlt{legDIYJt4OmL{sM9C#f{4vxEe^1C#JRX&UCJhIg!&S0&RK?U~(iOmID zCzTY|`9K1hsH%C2ca2j=Hc363fV0J{<>LS|_b@wTD*4{6*S%gXg9GzTk)z(i@hgN! zTOP`&T}F;J1PhxgdIwEY;&pKrn%*-$6j$M<#2E&yc@u@dN#IcKlJ;N~K4cbZy&tM1 zP!f1CIX}y$kLd953G}oC&ohJd*;05WS^&3s9907Q&K&5*DW}u`q&}xmn+Xtx>2#&y zuM=GDvwvQw@{jxzi|l-4^uy}_w+G8%;J(l%!78WqLE zx0>kiE);CvQDbU&b53|0FMAU;kL|~y$vS-V9BFMqx!w>TPTx3h9@D@v!o!V-l#17& zPvXO&^+YpAurGGn5A~8wTfb45FSsdy=vwNB z#}zE9*(T?67vJB{2{(OC@6MpX4bSF$32pPo@=|UKoA(cF7IRB(=J~=#V0v>ARYE!( zssMy1fn0?cMi4HIH-8?+x~gRZ8Hk~wPDq`LB6ar@<`$68#rtWC-SkZkOlS-Z-vXQ% z48Eih-kt${#+!^|=GDNt0hZ899d?6qN?&wafbk5&!)QfJvo0ht4P10ffY~p#+ff0l z`tu_S0epT{L}e6oq$OboRD>W)GfcOs&P|@-CW`^m4VQ>|K46<70^TCN7QP7zX*1cSgWz<;@9m)3qse8w%VP9fx2?n=BG8L=oB%k%Eji=4jW4+rZA8il|zJw7J zabKGe^zKo*#{LivnMq5Hd=7PdA&$3Xg{>Z##MKsX?_tD(uMCMut+AB?ECPUUyPY2- z-3By%APWTuWpAob+36qNeaR(HRM(ICNQ*o}K_bU0(@xpMFRBRrY`(cq1)gd|_S)Ya zp{*|HaN3r~7Hax&N0pz33p!l2oe5_fSCZ$pdkVngQNl8Xz}x9Eg8uX+PTf=H1nU>o z!RwM3$+u;McT~vw+aZs`R;8{)pZH(sSwkjx2@^fNG;m-x@*ht5jzJDuy(c?p-@ZTm zW6!B+ujbfCE4}G>>b&wbXtJ!%J` zB=xWLqh(;SVr9yfFgFC^?Ly@}EUTW5re&D@Tr)WUIFL~T&#c=xyENNpa5!E4JuSyK z$;v^jfTXaQINH`vRTvt-kuE^_{7!rMTpP#gYb>Qun@ea_oD#fmo|(hp!HnqA1pvD~shU%X#*UHdYg=vfn%t#q zN!jIE*zW;`yjeu-cGK66aoHsWIhX&93>X97gqix4H>ALU*(~-el|@Gt&3Vvb>wMx~ zNX{9z1&U5R9_J7P>rHP)965F{yfYrNCQ8{oX%u>47#FPT-kz2 z7y?gZKgDl)#(nr7b(Ryqo4y&&Ed>sC#7Qo#oBfLgd;d`KucdJ%9O>l?#hEIuxBJPbOktOPTxC zhJMPWqp{Iw)1wCdWZDkjBxNoZj;Nb@ie3JPfC0R4LMB)?IMG1q@KH1J-uOs=H4y-w zmFe_PFXBCdQLcq$vM%}E2V+~zs?l1X)F~FM7{l)*#)N`m&%oyMWgjW9FaNZw_zWp> zB;_6@T-@e-tfuU%uC>;t`z`mxKl;e!jf>4ZbF(KyFu88bW_bd$DdC+So=u_|8MIbff| zsOlUhYS(n=8V`A5>-BZAQtjFvSDq!9Q!z5F4UJ;`x6=5@rgRO1|9f8LKds1;Js!I~^mvg5bHJ1Ta8Sq6xWi zbFXkoOlGRhJM6GM@>>AEH4nfo!H|dk0E^InM6_Km?1C{`Jd=LdsC?69{`5O6Q|Fq* z(Tp4%=rM$KhhtOoC_PWtqsy1!bQHbm6n^|6y8tVuqfaWbQkOYcCOQaDmG0+wJ}B%; zsUyy?faY(=NEu4tadC?nwnsKQ1ds*8pb$S?`kHT-jkJ8er8|kbLPxM<`)&! zVt@71eA0Qk^>qM&4UvYGFpc(4G9gUs5(N%?mTwBCNoVcSru?U)9xE6@j^F%v0)aub zM4HYP#s8b=`%!FWWyl(cn67OCvbX}Q)1)CKB*$Mp20}kanvwzx72Stp?t`o#(PIC0 z_H#%9GCW+3V$Ww$aU&ZOFKd?aW*lrk_*rrrwG~ib6Eg&eXIWrY(zjcV^9=jz>!yBY z6z7uZ%M&v3asEo?X3%$=vzNPHCjrOHT)&iM=8C{-ZyP^XuQPhrWvgQUNrw9CzP&mT zZ%799SRE7H5^@2Ctwm2J{+axKV0k8Dx`NtCz@!RcEEkd`y2_y41p{WJZYq8$EV>R@ zCSuRsx3$DP(`h*sF6??Q2r}hA#aA>Ua`VLIc)T8FmYP_hZ7B z!q+rJ&oj+J+{^(Lf0?+MDUE?o>#dQ<(4PwK$?EAp+pxpqtDdj-Ir|k3zE1l$1SqXTpn|2tmT zX3Ljzmsb6+ymXIutgipk%yD3Nehs9;-hgZLblvAVN)L*U-_JNn6U8zM$=xz#-kpw| zpVwKaSg_aIT#*oN@=wTO*GcCQH0GKR)%*Hmbbakp`9pUsNcUemncb6V5^?`sCGpG; zKJu_!O$~9xdQqgfl%`umH~T-q?TM$*Y$N()f+{tF%vzcJ7Lrsit7nD6Q%m;+N2^f5 zF0z2dgFb%I&A$lpBcnUPfpWv7nlmY$pnptXe>qA{#2sqwVWOLrV6Sa-cU{syn`nL( zjino0G0?Sq)dQw<+8=BXowDKb;la zP#YSne+rVz-XFL7L=Fy;YbihqkbS5Eb_mF8xPf#C67mUb%|r7nQ*9mflco>1{p#Oj zU;`@*SAh_7u?R~BGpJ1U#e0HI%~vP%hRYYM3J z4?=!|e3R(4+K{NAL;gH-Rz^BhmK5{8K#1DG_=2;I*rNbiNN+77vdj(CoQa3YiE=yp zQvjt;8R{5bV_8a-MithFcOdGqbwCY*m3b4>=FW(p$@`c{c(N9d(nQnz*0)RHTiN$ zU&Y^G%O6nJAla?jn?&Q&JrXmDB&NepUN{hQbHxC>K_Cz7tc_eN#m$cOiN3t!bM0v; z8VYnMmnI2Yxv{}4+t8B%I|n__O=HH*b9&ZEuHXzw%tQfomzTztNrarmK@NUH85z${ zbRBZ}v|h&jriV(x7w>U$ZP+9NcpCGP%A^OMR~ovnVSuiG0@ z%p@yf{*!#OQ7n_jea=$r2U#xlGh=H&V1A? z{2X*Ea66r7!WKId&423$5-Grc{rp_3>&Oof%jy;Mlq}Ih^DI|?R-=@3>KYR>0z2H1 z86Jb;Dojn0y1{WWmcE43wrD!X_jJ;O+SgzrWbWJ0e@!!QInQqj{O6!5+Xz6a=b;#i zdkJ$Zz{=y)_J3S8n%8;?xT)^-Mtj^RDSvf(?u|l>HM9M&s~{ueaF4szP#gs1eC2^@s#%F%GLv@ie2Kf5aBxIk8!+>a3AQ-+K-P44-tZ&KC;WIDnW>2+HjEhY53 zwY%)Cc7Mp|>ME(Pn?8%E0>?v0Ap;ft1UjKuBa<@UIIePj2MG@f_Knott}?0FM0oO# zt;~nV#T+iKkBEQ!uVr9-8cW*_oj}g+EjKE$%yM-9`oy%Adm8UncG>mRcsv$xIhw&Y zhmc0s(ch6mqtGKvPpoUjN>&d*l7Dt{MqP zAkY!8i?5@52KHBw)E6 zNA@0lAU=<3ku{C*M*T;&Nsi7ilgY#0TQx?(8C*}~?lfMw*x64Nvnz&Z$;)(pZJ3Rb zmo2l8_#)+#s_b=j;KTdU@6h4pSv6-Q0xqr=yJS-F()Jyl9(PBxL|qcs-qOv=`>$t4i&jHR5}=4qoEm+$baD%Ob-4brs+0=gIJw;&jKvcC zQ1IqKC^Ow?u90`QZ#A-(7Ub_c(J;|lEWwT+QdE4yL__15UiZq}v70(anhHqdq5wGJ zXTSrmFZhpN3YG<{HHz3DW~d6ehu$Q|9lOCjh^Nr;BM5bbii-Qw7Y6SHq7k)KYlKRtNNB9Cq|9QhBvE*? zoH*wLYPWg&QVRO}_Y>?7vn&#Lm_41U&JdqzrkBIY<{&hf!=UK?`c)KG@@`T^)$&|r z)5(SxIIE64I2_zf7%D%2lPrkl(=@(7zSHF#IuayaaWQLMJrZzR4}lwgvF;@V!o@V;-tfEt`N-G$w>q7;!Ew+ zbVq$#Tc47qpXnrY72DG53b^}wHqG8nigt$3HZZx3^aJy%{}YM7yKVOHLUBJG#b!X< zY?Mz$;?aZqNA&P;E3|=ma33EwQCqFGu~A;gEL&W2bP?Vg6v&nAU64=|sQ$BAhN+4+ zs{bZ_w;S;CATD8D(0Fb>hv+RsMrV zfr=y!lhGxZcwx>h5G8%?XycnDpfqz>D4{=f06{⪚5saEU9 zO_R}H2Y#LV)0pQO&Y~5x`B{~EmV84pqAnJ>w|_QAuKV14P${dMh^<)(QUuUdKes|9 zO?d^yhhyze&dzw5(PsC~26hclU`Qlt4UG0fgC-^>Hfkar+7Ff`hxo>Yu-F>BJD*fQ8S~|OA<~F7zuvu-T%J^Kr0X_0Q7$AS ztCjz}C?VNrxo07d39PN13}DfHMFIyw&RJO}=L^R*$J!!l)ghIhZ zXD=NVtv6se{|2vB8chRyqg{E1fNinGjZj(5D&RT?C1NLv!2n42uYiO}UYUNurBpB6 z*oXYevG#8If>~S_j9}}nKC!M%uNLI~k&|D=ZHF6}v|B^DU0iN$tM*b&&w6s3NtNn9 z4q3SxWgduoIg`z~^->J3wFDzK|N7Q{25-&_c+x_%*Qs*~WmihjsezJw)ss6m zK;pu~Gu^XjlL)eF`p*WLxvzktZu-O8UcH``_cgZoH~neI&}@Q=gXtcp$U0c&Q}BRAfghd zxygox;!$<+!{@;=P=YqSwiwZLQ_3%t3LPl9uNuyiGc1iSds*siu2fua!vF+k|IQ}K(@e&sW(8 zekPd+g2~(ikD9vRWsmiUI#gOQh9#UjIW?SG<0e>{l<8$Oz|sq_H6zrkDZmA$H|S*D zww;%{9Jvz+5%fDMZ!+IYwDbN~V{HHX ztn6bcfSh3FOuz~icq^t>e;jZ6@HcKqd>|zHOijU@1?(J6`dtY~2|U2!*CHaIBKwgv zAa=24JizSeQ)vV0Y(@d>N#r zp4r@gV&CWv`bBbB=EO?`8a z9(~4~9)Ry{JY6rvbl!*($14Qdf;1{+DUW5JAz&}}SVFVL%i$Fm#d4Rr{*|Bv-g7}9->zlGZ}bx@S%{9k>*J8|9t!YXT2*pb zpw(!839?jq7-#28>cq`rFhMG9%fGi`O#dUKt|B|rlTMJb{Ysp8j^ZSeJV+LJU*I)R z)>mD*H#}0O@@|vXV?-3RswVGOQp9{PF8=c*2(ZK7S^E5hzJhm$OKLucB+&CJrWr|K zP7M|dxKy##mBK^GW^ErCi>5XyZ#$F+-Lws}>o~v2C0-jV3L*<>b_-a`1uQZ|$Pz;F zna!7a!}il1mXu6P#&fvc?gcsFO&g%hK>!lJZb=s^zOd9@e4e(U$XQs&j$LKa^eKZy zAP(z4U+4B=!I+G{U`4Ys=6p2d2fxiq5s@+dPm%rgL|M}_BwWBEkP+sK2JE#VzjStK z_~_Mmtks)zNx{wFZxYwv@ozk9;rP3sMAH^-^He_@GxPdZz&k_kt+R9-Kws#q9?6ns zqGJM#fyvGOTvK)woP^ub4|B*_~tluUzbA zHyyPBU-wJOGA6N^cTsc)oarwAgp z&E=VP%YCeBmoKN|$!vj#G6re*Fv=hmyhi~9%vi0Q$qf(ijD{(_GR6rhG0OG9={n7; zOm7=|2D!*e%IFk~DKpCV)4jc!1>p(DV(A zadpw!6Wdl}+g9VGaT=?^#B7|#jT+mwIk9cqXd2u8=DqiRzhL$`v(MgZJzCHe1r2rv z@z>KQCevx7k>F1GnO^KQl1FJM1tEvCmVM{^J&|%{KtkWMDh*;{K!cRdZMsp=9*p>d z^^mSYC)L?H?Ll!Y?|=I6G?nhnH*Am0J{(A2iTyGncSxzQM6O!XFpQkPX$wFvKWT)} z>2CDXzA4iYzVc(#L)y2~8c|)(E=mP=D%DS58`A(Q5j-~G%G_f|AE=6^7rSFcxGZ0x zCm(Wf+8eB>4;!=|nTS7~QybMFuzvBK-ewe(C^RGfQpmRP)}TO7RL3s)>!I z^nJnvM4qpu{0|5aq35REC_fVa5*rzCz40$5SEhaM@sL7%Kq!7Z^MG|*E|Yz;eUO|E z8a;#OZstO#^H!B7IMl-N_WJfKh|x1PLQkEAPZ?LDDhFxMbAUM^4LPuW@)umDgFP`Ak}qB`);&OD9Zi>{a+ zCdc05I82_dS2;eK!O}Z;Dvn}?je4JBt-xoa1Ci}xX@hdR=rZ?SQSLDZ3Zt)X*Vl`9 z=X`7C#cN4+4v?ArvcX`KqzpCCuJhE~Q6?Ws23i5}H5124eLfTpd7Nm8F*Q2;)hdk+ zSdEH}_rRAy)o8Lwg-KyrZJ2gkELOLU%lDc^6zc_<`;+l-G9!f%al;{AIQ3Yd3Y47L zs}2_99xPeQ8F;xj5ABeDj$C#=rS|uY zTU-Bcy$~zMcu?JF9>OX3H}h1*ceH@rt29(h)^syJ&4?dEKXE?PKz4&`Ut_TgT(;v6 zXaz_(_PuM=T^fw)IrnpLKIRG+w}tsh!JLTV@5U&v3sb1I{fq%|alZiF#Fb8PMI=B` zKJuox&um-?9cO2Br}k&OoEDeL4hf~ovWmL58R+}%wKldizkFnqlGqKrE8!r0%`+hupJu8(e^`E@#yvJee@nI%QE=o#sjz2a?66S(d-% z%BspsdkTuyI(P_QiQp})uruS#zWtKREv+41WdqAp?4Z}MW+r=ZnmnTu^iP@aHFyKQ z$+ z+45x0GXEuG!qG7YHNDhF=&+z-$8@;3r>iuA0>e(Zo=q=vT4=DUC`_cORL-tx6Tpru zP*6LnOKGlE>!>B?^UvVSk_i^VkIPOwr;Xf1d3p=U&RBHP614HwoVf)*bOkM73Omz>XeU%h^#e8Z zRu__{kRW+U|2?uh1M!UY*MLlG7Pl>4Cj^e>FcErBR=wj4t!I)cV1Ez z9L6mkPy2?>!TlL$XaUWda}?Q2)MS%+lNYYL77pG<>cq%@aD=_}J1a)~R~Xs^^UK4# z5{8=BVefTx-PISA_%{j;W9+M~rZUrND8m@L;3g|YfW{$M#z9Ddc=SsJ8(@PCqot+9 zY|tur`6g@DVg?;N=lySKS9MK zu1ATHC{gNUYaTzYzf-Rltb!>b3jYT_uf_dsfE`fEAAwdgF}bU1xEx%&dD$7iY$v)A z9aVvsSLoBVP{0g9Q9jFJ(Os~C?fyq15bLAHvA!98p>oY5F>H8ye1KF|xSfVTOB2ug z%Ssk)i}O8MiAxn_AG$F3_8#x~2~lJ5tL^T*iuN1-Io98& z1?Qa0C^NT}drt|fIb@ZgX5Ces9NYPd+PCB_lO7eW;x2+OrYSW{&yNA&!LJ%K;ExP0 z+_BZb&AiD_UMx(#Vu~~m;f`j#*U#-j3U4oT^Md4d^}<_yowyyc=Zl;;%{d8_16;?K z^(&^iY`_`3$fSd9M|A5lqUq=kTx-OI-RoWF;~lYH`TX0)ezc*K*jN^9<&`Inx=&kl z4^eu02pviIHEO_iprZ;anqH`5SdEeED0TXW*twVSDP>EO&LHD z><hE19?4z#p(ahpaz3YACqyA>m9R}%4w#D)ACCE zMt4HN9eBF3m`y>IauDA^3bnWCNY=N#(*N|3!tu+N;E~)polW;uSpkwJrGlb-*)Fa} zsRs#F2>vGn9p>XoIEc#TBiw~_NQ}jb>Uyeby0@BDW3IL>&S={&Z9%)FA9=nRF$3WV{ack;@e$a zjg8+Og#NGbFk;Q&zcbNHYBtV6JWi|FnkGr&yP^b`PRtf4|9L4wk(PnoV%#=5xSyCg zQM8n*41?B?9JDozPjzT_WqsOC$6=li&JC^aXJ0=4z6G_o%4cN+ZlyFm_3^@mXvFaF z$YoNWD6r_-iH(AABQfSG%!rMD0XI1QyQGXSra@};+g^Bh(o?Q z6td9nR32&09Vy1fP@JC#s80P8^y+TCOV-zR|Dz;GMVpBOX1kQSN8)s;^}9!cz_LZ` z=)37qi(JOx-q1~tt*)p0-r{8PDIr~%9x~=SkUx+UKPSks1ExMIED^J`>cIuEnFwGU)+9^l#xNE(|S zA0MmtxahQx;bvc8j)D%(UFX8Ml#nE4`%8>BOA5s2`*WdS;m!y&>=O9Gb3Vuwe_+7* z{-GB+Sg6HPt_RL*$J7^x26bwDn*3TF9YX^qCHds$Jb&_ijj0le)MqIOZzNwlk^2+j zw4ykeJt>R;FJv>R3u1qw!Zo^m@KB+T>uiH)^d(K58<;#};^(A3`iEvu$pPw?+ zx=}d`M;n&lVTx2;q;y|yt(7a?MOvL&60a{z#(Yxv8{pzIzJ+@PDvM=npURI=1O6o3 zrpok+AvIvq=?mWM5^%~chpYd`*272h!s7$8rH+#ZCRjnu4jGOqm$e48djBbGvEHyT zvf>SGzRfnVf7FCP3UAsMTb^J3H2BAA;DwAd>~{|n@u_`rYwr2IQY7YHZCQo_E9_d9 z)C0~sZeM{6dQ3rKKJe%JI(SNX;vWrmoVg`>u^v;cS9#VsB2mh_2wdTe=0OmU2V-F> zz%Z|X;7K94=FXNmGa6fU;|i!5Gv5lF z{6f7R0L(M<-c%O z8GhnDPgv=q>ONeAj9bACN{gh}f4X!Hm1oPe0P9$=QuYw=(zWC-N3;Fy6IdM+kZ_d z!!CkgV+b8Qh+?zd^y^G!lAVQs_6OxU@!I$n^Vb&C)`K@Fl;sordp|!}01M!Vof*R9 zYG~QyMiS`kebB6xzD=;Ez*=YK5D>-V_FsB2brglIG zgRc6Hb618n>VYvJk~8NU88WxDJkIX~@lLj`b%%a}2NQaOtr>!*!{WJLB)8?HM4*f? zO(BrH=w{nmnfcz~`yPtzt?hv~$oKFU(E`hEht{f8aU+3tkDXjN&4(+(Z>Q$okR8 zedGR5ad$l&cH{zJ@rQ%plC6586(fmh6R$@G`#9k)K2U_E)A|?CQH_u>PYfzuBRqqC zD!lfV^+@VjWOBzd2SVFh#ER~?Rt(SkRIgduioiGB$v>LoLrp_>WdDp`&AFHkiW!b} z(icK`y2>|Wx9btSv)OKgQ$@v7H2n0E-w3J3Ci%b;h1aMH zX!^qqO|FwP7eOIMNMok~JSJ^6IuVZ%3&}zf{jlqzpX2`u9!n^JoXvUviN51hwm`rZ z)NYN7+tt7|b6{lT2v{!17}hcce`znIN5wB+9ue{>j^tuDIkprY_#BSyS{&p<#8}V7 zW>r`mP05L}W>|3DzfSNA2ZC}UQJ9QT7{fRp2~z5!QS=aOkQsc{+g^EMHaR*`|6USB zzq1eaV=hoG2NZEa-u{~$ca3!PgYOd;&`F4AL^M+8U$j_t87PEZk#&6h)Dvu}n9su% zDTj)1VFiH{$Rh5Dl0=RV`uJS)NF@H+@T1n0b+K*~Jw?a9)|8zLt zfojW4K?H(0zYdb(YwHj~NcHi0=hL2ZTmH8sv~OTZ*cXbouQi19&s%BcBCc=eJ!?1+ z=fWJif}$?4%?%Y5KNFK?x&_YV1U(g9sISFcYU#2mXm6 zRHVWJXlO&c4C_s%+7Z1o`uFtZZrt*>RLSQ*9Fgg`zCiS*Xk{6tK3os3W&kWdnc2GN z>78MN#CN|4+9xEpe`agAR{umz=T>+v-N2qa*E(Bgzaz0G31%B-hh*(sJ8VD+t_Dw> zt#ccRy@;D=&GEZfNzBr$aCjig93Qj^>p z?#*Y{yT6dK<8u3gwXHyg^Pvs%Yc&0m3Dyu#?J4wc&HfWhJ?-Rm)9!Jm#nqh9QqZQhCj|K5y2b>bn*q_qAqHTn+KN+@ zGk|0IAv+Dz0$CZ#x>7r&)Zv4$axJ-SBe(kH>`34iPb^e{fEoLlnTCNt|+5j*4bheb+Mg5mwvJRWmBr#`{SxH0%qoR_swwWG zMhJwyeC3CxYJ;9-{C*hYF&yU&+$XO^x_4qrG;hay{a9te{-Tf<38kZqVH@uab4 zm#RHXe69jjnWYcz2k>n7h_!rArHnVwT=3>lDg)rnG@w)2c~#D4H(9dFv7ivd$}!FY zy8lN9a>dvn$;qd&ds}2T)v4oV@h9_T5nHS6XWvt**#0KB zA_FVx%a5ctuG@);+v=iK_rol?O$DEHccHGl)S@ap|06gufj|N{^dDEzw70^&3-u?c zuw{q;Vf!S&kA}J6?ophgj60nV-Is@C95{gp{h!oi$7VAcb}L>yQ1t9QE$wX^S=Xw| z-~bnu=D#wLg!d9AR%{Z_j?(4_qH4NSDDp@t%ruyU?VA;Fh4`l6WI*x|F9`)~`R7dg@WyCw!n6;a=?P4BrV#-KT zp5)h>#})P85QN!BI22%L-Sm5*??;l-{Z~>Z#U2QZ)AbAtIT+`o|N20(b+>wML&~W! zmUUYjjs4~Ubfc4yIN%E}P%m`+b&<6_Qb7j|(!tYecy^wAbL(f(NzO7akjbI)7x3@; zVm0O=qqcWw;B#DLgb$p6otx+hv~&^RobZ*|u2a@Jgi!xhW@B7#bIKPN@CvUIbDZXK z?FZushcHYUh!x?g=wE5@G6<0yD2lo3m;jCvvV-N~B-37)U}0@nYzPz&^vnV*h~CZo zh@ZcY*%G*BuP`DzW8CO?b}iTn4e8rOmrV!Gy!?XckMyp1+d7Tx`R@0mFdWGr1VhpJ zFmAC$htm?>(U#w*1Q|(YKpCG= z$^IoX>445R8}`Qrevrm-(e7m2sR$sc7rj677)wlAW!+NI2E-X#n=j|)W#<^3o~T1q zlq;rhC{>MiWPLL&D%5Gun@4Sj#?OWV!DI)Qh=Ha@1bkq!5l?jz0b6c_(VyLOV4A0< ztLO0scAlE%_&9W~(`-KbUq=zNd^Lj!HouXceuMLB!MnR1t%?sgT;wNqxhDeu1lQFC z@`*?-F=A%t);=vw4NG6v&2uBwS#D!}CCShuHUwBrc--yu-ABJ_ndxN3sDPo7ctS{` zrBd2(JR4J%Ls?27%mT}KsyOCynr?G$oEp&HVrR>3`Nb1uUz&DPF^=^0mtRW54)YPg zYSk>B-ULt#2?}`w|E}e7mcpj++ZHt-YW8T>_)WNqLg-%uzHX##()?9@w09TTNzFJL(?Oms2<4i5YMK>vtpLA0!YdHBf4z7k1h7^y1w z$xawiUpWE-z={}5gas2wmzvm#C!3^gL7wj!AUl#IXeIst*~My9;oxxJG_mXH1B8V` zuD-RV6%$AXSL5}39w=${t9k2~SBQe1#=XBP8KqJ$9Ug|#O`y+F; zWEfFEzG?UsGv^s1u9h-*P>3CDQxw8)ia0j0F65teB0IOmcOUIdp!askJN=M%#Zls* z?v)Njekc3EuDUJ2g?<cO)F|juTx$dl;volKM1^nkXwsD4MKVbfzrP_KuYqEPmbm=?Z8v>?kFG zd(L$;D;7RFc-gPNrc(i%m*k4}?-`NXI8%y5XiHw$nm(78LS_5(kW&hH*2`lrW&vo3d?fMTa{xHkTH3lZ+Ss0nxZ+>a095tALqz)CT8$z+-?|T+r0hJ~( z1fML-j$bmS)&JHHx;|c&&K4NK9sOo{o++!vFS;)rCK+GK9GaMh$Sk0Am-F}hD5;RQ z@AP9h=SItGs(M$2G{`Iht@PVIM3?DMe)#Uf1PvlA9+*2=2&`4o0Dx!33#`#fj(leZ zfFK7dh%2<)I;q-Tp(1E4QdBgj*upOj6Y@5?pm{2U!?=L4KWGUsj{SSzp+eD;Gy~}v zyJ&8erw;=?t8a=0TMm_aHfWc=RLX|OgpnQhHkjMNs+sy@$Mw`TuriE3(N}GTx|XaxX#wLY)nYB{zRAc4JN=^pK1T&~V&h zJ=aGf8=~JO!n#Gt*uS)t=6cKwBP(RyjN+A_^LhOcdw(?@bR9TD3iU~}ioaojP(eVJ zqA-PcQ79gr(DMFDXIi4A`N3_pKMvG)R#%T}&sDKIF&j8KO8h#T09XJGiU8Ocs3np$ z@>>7~!t3g9JJlD9puvTJAHzCx=Idobrv8Ha-$KU@E^yLNnOLy^u6R2w0YO{y>-Q}4 ze-8tNfgcu0+ZKKp>5bZXj!zn~cjaBb-$0LZR_l}0wk8gi1FTsjjbi=d zJYoC1_{fvTl79Z=!y-QT1q_noocWzT{jdUgDi3CKd;_$(L!?uR$YLu6W9uE-!2a$7 zXDOeppC6C>c^jD)IVEm#Hm_?arBijCmExbTq{EKh3TOJ9u~Y__pkZB^GFJPwiLl?E z{HBObU?p6wHdzE!^Ak~h#IjUZIdH}%LJSQ>PuZE@GNP`eYb+TDbSMJa68vTFME!*? zI2XM`z)>tWuM2tN1RZxtAyeKv0T?h+ulf=@L}HE8s4}9|#X4EncH=b}9OeeFS(=LoMR?ZlCv}QV8l3)oVk> zl@?HSPKr7EzD{m43@VnZS`cJl399L=DZRS^MkqG4u39y zzG|h6dvZQhAps#wggHd6DPv!Y(awGtAEV3iW%*x1@Np6G2DdQ|<|sD^a zll{v9%Z&h0M&9h;4hHr#2ZY z(0kja(nS14#XZVuqJidY$Z;t$)OHo(s0;R|^q(>T#%9+^V2=7Dz1Z8EhlfM`cUGgry~0 zS1$N?buLQ`k+gO(8m38a40-ydU!ilo@yIZ*Aqqt%(@8G9sgA&d#1gVOT-ej-v3;JL z{T*Q0)>O{2dw$qDa4E&JaI&^Jp5pAcy{cClB_a$GWBlbTq^q7)T3B0jKy9JrfQ zFrjaB@MvJlrF^`@3?J$@M70RT=JSLM#h8i_-CPrIF_oG2(7Iv7q|fKF(-ZI=x-D#B zlL+ZyMmZZWz=QciMZhNYXB%>G_@_*+g!9y6BQZ~PE(bI3OE?FoAyRUCgQmqCD<%Lm zQ|)qh)Xjc`EOE&=gaXn1m=a=g0zi@~X!d8<3jG7C`r*@aNK_)uMo9sF{36LY2?F+} z_Bcgj)Sy9DsH7yh(7$KpOc+i(o!ujIeR*Ly1{;`@oCll+)Y-aX$vlH$m+JHy_jV`)bai!! z>pb=@0ZLq9?I`GDqh2|PDD|6^-`?}7Y2}rC;td#Y#NcjNoHn$nowAg}wuPdt?Tb@1;SAaT;I_KYC02 zw;oCWP!;d$H7LZm2!M$wV+6f>hpl0UlZAYj1sK5fHy+g-6XiH}ezNpM@ z89Rj*tLph87M_#NU_|;EV+=IAar#XZ9Df<0Bf5y$r#Y>e(ag@E-$g z8Fr5RXb2h_m1F-*tm-yfENAig3_iK`3>wijL^_@0*BnImwM_ZcBqVj#14cZ0bhuK@ z;EbW*gBp&q?bd)~$^<*cppr(GjNStW$ewReah60FMcxB};-!clok;bqDqgm{(i9Ew z8W|6QRzvar+Z8kbu4@ zOo88%lKdtt(E+%U1!(O1bKlm_9Uif##K8@jVm5Zi^`k^SSyYNk|}R4P&8OA9hp-zT2n1dpbU6KLKS z$u>lOEJ#L+*O>Qd`Zdk!L8`2;`66I|?kw!jR_tIWjQs;p!g;solMm_$NF|$Wg!sX8 zc%>=!;jNpw-vGZIQfpO6vRDoSI2jq{>=A4N9eloSb$VR)_z+Ji0}}D=GwS{zbX(xY zR6f`4OxN2Q{xCD;t4|GMK#A#veftxzh3VgBUPshhdsc?$jbI1soEi|k_~miB{@hOq ze1ECrn8?hs$3x-y4|192+<9vw{xgDm>&g^{#Q7uH519C}cSF#FR)?-2h={b!{*oy9 zo-ai!kXg+O1}NgEAG{R+7nbLi#(U+zqBl!d&a8ji)8GJz0JcAdnl9$Z^8<{LDf)UE zZQ>(!E6?`Xs1DJ}htd3a)~mI_bEd3!zb>;w!6jqNDpL*Fr4biXXh&vTJbsF-M(;#%AaCzg@76eZ7$!#M4NGie>qSTpE=byqK*dxS8CG{x1vevF!KB`c1@ZVQI;o%( zIxr34SR7$~dO0O_SpqP*#N4IJsQH)z&`*rjU?OhQ8*$Ao(C2a6RiMU=I8mmu!pUaU z#JS^fDxoB|Gds17#v_QiBW;TZEh2O7uYU+$^7P&%9Dm43qb!fEDQ@8Z7hE2!^AjM} zbIAQy1W77i83I3LQu}7sjkE@^;GPJ~tR9siyyc?N9p4d~**AMzJASx-LllF^(W=^?(aT*+ zpayl`8X-K{BigSpbh6D1qxxgm0B^GkkOy!?RJ&^Ls%+auYl7iySt5m5FtSqYjOLn@ zU99eZ#}8WV<3q0T%Y(KwhL?dfx`dXq->jWV%|H($MaKrLnfx8qm(^)d0 z-@vj$i741kA%6O~1V1U!FH8+^Z@Srmb}hANJFoa;&jkqOt*Kj=QO>y9)iFZ6NiRE7 zz1GdbBxkch=^-K|%@IwLq$MF#2#cr|;l=Z>tttTk@HE6)2lrhzO25-2Kwlw^cTfQ* zr>96o7=xEsvjJ(Q?A^@wiQvA^o&m}Z^maG?W|(#+Nelgt(IIIgcI;XNTn%4P1B8@% z;2Z1+qNXR5p~n?iIS6@4Ix5cqR6kcB5db$wI6a=mX50z9<*>$wKJzUeqs==zcq1Yh zv1iJ1^M~NaxGAVWb;aQmnS(Y)I>3N>a|4y!c`(9JiFW$_u4qsf#uXYH^SwAG;xxi# zVl^P~D0UKKLrT<#`9Fy*hHhwD?2S3ntffd7IYk&TUwd?wewb#u#< zyc=t{2#)9>o}|{(3vj|BvHgmUyQ=K*p$Z?)@xg$_omD@XB4pc->+%3_0rd&v7<~pE z-}gHx5KF#`Ej&KaxFH8{cNGoX?F)XTf<@7cAwyB7XOKv20b?-+rtliL;$P!Ng#4?= zlaY{r=^WhR64{9^YzQI5Q(ALXA6%#Ma$JGMj#P3dCgQA@cWJ#+@xQSaJ{!ac;H|N8 zf)WN7)FIiLtM)a1#6T)Z8~FN6-C4SNj#7ICl^e9ZxKJE((QI|9;+bM`3Q+NBHVk~a zVz+E{-go4MEPe-P;lHps&xpboy8Qt?40^P*Z3vHAD?OwFv~%qP2`Lo_;fY5Ge@xVX z?*a9C;5J!*p5>hsn-VX)5-)N?OZ(U*Z&98a9i}J9`|an4p`Y1R0n@TIe_4Ag`jzH}hL(tDqWFF%Wc+Q@J`YGAZtD6H=v**z@(t4b{!aFTrNW$2uyt*J ziOZv+sj7gO$)1eD6;J6kh>&vX_xFKDNOV%ptGy-W=%qHf!JMK#c{`gkY>GEwoK55t zI>g(u=A@LaH1Uk|Z{~h*xoEsZ{j)aWzo_$GX~v(5TkBS^*D{sGe7)$Q@ z`ykt_mi5yEht>yLSXGX>s}NLus5n+3>K6pLNr=y>$9iO-eZT(rpzM0PX$6a9U5bO2 zLs=HV*uK0Z7KGX~RgQe0r&(_OUPVd68m*>p0`ZjAw|a+u-I#!9@SQqgW_`3Z(ECXe5%j%s(-g{?lf!ne#0YsaW&m5Yi_ zIm@_}HYnZvR7PRr-WRuJ)*>DwR3JI|8bj`hGj*GMW;n1`6yaDU#2G(q3UURdn1bTA zi}jA*9>XfcU-D2xneG_W3=XUu6k*wYL4w~ND_utBzo0LRqknGfJsxj$G|M;T_Rk}@ zXD?&l(m$ssNz`CcfaFgBoc*Q8Mnu7s2>n8VF$pW{zWWEaYq6w(pM%0oG}~YfF|>KF zAG{Kia5L|+4XK_JI)7G8(8$$SLll>?8q9)T=jKnwRgr9e8(pn&@CZqpp2@V3Wl^}18O)P=|NOW8Qog8Fk*(v0Pf)02<#n<3 zAz!O#iT7rJ>&gYw^yC)8{MiWVsQ?2&FPeRX`^VeMIP3J2QutPI{Qs2NB{-)>*noSd zKilNWD>V`h`sHuT;NDV%Zq^l5jti;Bsm$0+Iur=dcgU|oqgQ=8-;#c{uem6Z5o^o| z7oiH${M{1;&JQ`H#p)>I=JB8tKR5XCB%#c)-s!`VI^BFzH`XBwaHIarwrn&bC7;5G z^_BdMaI6$>vLpIk#9`r2oy~GxT@#gl|8y^<>Q?+*axDSwLyk*PXUitj!SYh?H%i#i z-xG_tR-F*o;@fTlM*!e;m?jB{a~7hUsY8a!o0_tKYn9DZ2o;5~!dt4n1aYXQ(V1Zy zQx_Pc{|=4s>_^p*boLYI%c*VXrN+@}>znP4&{J*3Bc04d3DP8+RDjnP>6}|nr1>_q z5arD}6$AaN>rW(qc1YfkBh^>QEiSSNm2u)lFE-W(O6`D5XNb@ z_kmA0t61_0zHsAJb?^F;Ign>uua}erB0-Si%Ac_?rnuH(0wBHq{qU^(>c1MsJ-!0?6S5N)!!!zJqO=;MV zIMp@H2`~;`J(xgGffY8N1hUvG+Pr#V{-76=exE5mUX~u}Pu` zILXantPn0jyMNl>Ui&bhsNYjs{0Tldb#&pYY$DzXdo-BqX~yUpnd>eq|M*lr5uR7n z-U>iyw>ai8vOCTQ6pGGgihI!S-0L306%Tv!Vn+)><^POqsS|7#h_EoU%5s129K^P^ zA{e-q6oi0^3==d!hBd)_TA%;b^;sN|r1%bAOgkBIk|JrF9j8c)d$q{7YQExeTO;c) zmwal@H{BCW1u!{jpRC%3FN^L8*3so_GhC(AcrAw=3*RTE;l@Ey<`GecGW0tZ2WD$>2T3x7b;NI5t_k~H$ z9qZ5}ME7z%OhBGvBjNA0JE-s7KcBl8avahzw1KAJGgB1OEL>g>))0qjDtq_w@Qn^U zwC&*&O4g1xb1*_shff-gws?u21!wqBr1eBaO19=~jhP)Mv(a^dG8%!n@wEN2ZP z;v6+K>G5*n2vVVd!*iNuzp#0ln+j0&RZpVk$Mv2%Rp@-IW*o9hol3_%BO_^pw2P5< z9T{O39exb{EQ*313M26x2B+^0*0^#|g@e7w7CHY`eVa&hp8;{$@U{4X@(4M{dO#i@G6_|)Q z;eYO|PH&37RM;s3z?SToNNa$z6SXgv&bBkn*=vF@M#Fx3;~#IeUbjp`Q#+U>qI|l6 z(jLKKLAIt;H$nkZTw!O5*U(el4{Dc4u)9SlSbrpy0BzgrC~`!$f<16`Xj`K4$>t!$ zjX5nkOa!RJa|%IN(`Qj0hmNa{GWGprns1>$UG3OG=`Rc<46qSufmkNCS746T&&HZO z6-x!q(?H>OAe9nzs%M(Y)5WxDQO%}kQkQOb+fuZ&3hrT?OZR)vsd!BLa2l2MZN{AB zt2rh=3*0S4hv|5R*u)Mhq+vL%3Z>EC3s9c=W`fOBFnV&)THT&VbmD4h4OGQWiqS{klIVm3`yEc0+Wm-Ke|c>SK7Rr=(NxID z;NqkDi)aJ=Iv6|!7OPObAjSnG?5FNSxA~@Tug6xwAP4s^2Nkx$((s&c4mUvLT)wXU zk&D?Jk~M<}s9q{CZDHCcIT(*t|3{W!L+?-iRtS9XIS5Wuf zdR-u!+|diBc0vzE?tYADu)!=%(#}Q(1p^NBVjN98y!TgRW#k73x5By&wOkv7#S? zaigfXBL>K^`lF*YNj$&Pbowr|`lBGLV)qWB3y@5QRY)_GO}f(ZyVUla$cT=lAI(k% z?DGJ$5H0c4c%kI-$G7-uEp*uDS|sE$PTpc7r{a$G8c{(BK-qS%jwoYIFe7Xe6(S;P z>@-n%`>W+PPnv+@8K(-=7*Wxgt9#>h~X}xlfFOx`LKQ&15^;mYNUK7Y+LpM-M zD{)$y%&5=pV~8-xY#jI{ijh+-wZ*`}^i;PqFh^Rnr%V&$$}mB@scHBEWbg$l zlo*`>xLBg~rBFG#g{k(pW7*V?k35z}n0LYa3>2aOmPI_YEB0Y{@ir4vHR98I_o|MM zX`65steH;oM!`@=!szUbcT4F*a4OjBAC(2lO$hxKw%jx%LOW(jp7he_{c~o&i&p2? zCIVuimN*|-@8Q= zQKqv*)|xp9_dq3&2FK}RbQ(Bm)lfii@s&x>3y2Y4W5?*WME3Z{G?-i5(bQ4p4`_fv1(SxoXoXU>prEQ_V}QArTEWU z_1xvj+w83m^g2sfO_6*~enS68J0(`hYk^pdsX4bGDED>-jKJ)I4$18L{&!N;OJ$}k z3b`|wLabgBQK&ZjV&`ejR2rDK1mBcD^{WDTjxL1o<6eb8s%LRUN<^mIrb!`!+8LE@HF{4nqWQhpzOhcNHt-LNiFM-DMJj ziXOtB1$Lh-_D4w$hfoAobS8$D{ zxe>c%|N6UNdK-Q%#S0m}NAB3+dznbpMpCt2+l#)en)FmSr=v1>*RT`lf$ZvR5L}vZ zV7sVpxg~NchLw3aa?xvJ0^Y?q{`yV>@!!7AsK1aDWR_a#xrhC35g-~WHBt4KGI#aV zY5Kx8UrYlo@4(_EhOe+&?PeH@i>-F!vz#>@ zYVO?5O;7U6)g3Mesw|_=_HBHGccO)ohs_oSjon@sUCTB~dc$R?R~3X;wsFK3Vr)4z z&0FL;BkoN@u(bYyi=**kb2O?xeRb#oI|CdF%C8DTGFvo&6fl@Fbt2yZ)5kt4TPu1Q z3^CMgO4{WY$uv%}PRtx8iHd{h3lF!M0m>5%EP-S2iCXQ>47(sFFi z&i4PR`pU4lVs7hU7@VTTTHK4fTXC1-ZpDig_W_Dqafc#>;_fySYjKC-Uff;p>HFUM ze9t#OXHF(N$w~Ik&RQ!Q)DzBiv`LqLrfnWldAktv+0(aRjmciXslL$eyABxBkjsKr z&OX$exYoxADiN1`Y-k{xiXhyVVuw;ihoQ;i2oTwJ!pA5qj+VPt+^Wlkg6TBxYI$*P zJFPDtBG+gsIVvXg8ShY|^6uESWbE1nw`~{A_KAF^G9*y&c}D=inqa!In?1=DNJWL# zDj??q-PKu0gx2%SKR1KqcNU!)odSlD^0yDnjcIqAufA=bFnH+Kis>n!w+(JtfXPK4 z%BMQazAtd^J9T`SKlfojwS@g0nb%;xy6g#;knthLaey=Z3ram?MO(LmtD1W(DEt%W z%8F^5>TV#5BkB-phyKXF>r9uu#b;&n;6a@)YO{Of7@EmriAZFEe-X58!TX6US2~DGlJc+oZcb)}o!tOd zC+9N#5>~Mf(q7Ih*rYBe104~Mqlt>$KL2*YL;+*?o*Aug9H{BH>0Zbx!@G#!2Z8Q9 z0=CpG57!0#jsn;)+Z>T6>-#g#ZIlPMO9Y0dcJ(y|h6fJ}G7HY=I)Bh*E&yHn^=ZIs zto9X6CaSDnm;ZAA9Ujuh@*%sT&Cxc$)YEY{-}!aU{uoZC z3r!Vk^sj|Aax!jn z4gC&C?|H@>UscDWbc8x66Zq7$5+7&?VLQhs(^B-20Uv(h#GU?=VmbI^>PDZpm z=+L5KyvE3(4xHIElG<{vuqqz~)(-0nT?Rqf4UB<|G&G+$RKt zT~x}>%^oc1;n!{B+9p*cqXKm+hWwvtK1D6g z&(~Pgj=_rTBPLt$fO~_^c^|O1a*(`|L0nwCKGeVC&#R-C^gD;Whnf6!wr}YCY}GqT zUydA?w;0-$60C_EJyr*Og+t*k*>*b_Rts$q#kPec?e!0J!IR#2KZhIie2V5+qDH9u zSzU7Y1fd_%k&$f-u6j4D5>OU$-wufx0eHRjU17;)BVH*lt>$7u{}EJQd)VIxO~;L{ zNJ(iyII>_C^0hApM7#^yw_x8D*W9sZGqCE^tba&SKSUaF8T&HnhlFl|k*%P<>;^Mf zni{VW;d3V3j@5?5(&lzep^v4!15%FP34pt^MhmXfC#I^eu2 z$`a@fJtLq+r&~MJK-py^Fe_p#1-wBUW8*?<2L%p4AgwQeHL5UENpqFf)Qf7+GeUg! z>36e_v%JGPSle_UlbrbbkYgwo%y)YvA@gH;0#EXXOivPHz^`vF%2u!5clU)u%9$Py}ueM6efbO|s zW_FMf%4=li-Y5KH2{jhi*0wMiOge7a1&~l`HA8NK@mv-I&fM?pZV>B06AabJ9{8_+ z0U4LpxU!|Dj}iA_Sf)RnA%xt|E)|8;vGYgt#GE1d6N{k1DOCG=2^jC*Qh9~ro6r#k zo>IT|C&kYRu~d0WzZJVsQ&N}m{omT5lr-9p^g+&k;Q#TbGoSrw877M$ZeS!_^Qp$@ zBDKDH^EQa}Cb;nWieM^yPmp}&xnT9dEnw;0%&*Nz(K$O-<87epRSEW1q@plf`3?8n zznWDypNJa!^Vga7M;pa;&WOGik@=h;VE*t`ag`k1D6ep^o^*v%TIFA)_qm&z|8`tFBX}@Z1Cu|sNV7{bLQ8jbMp-^1SHygKYYZuO@vzo zEr>KoE|ZqxBON;TwhY1J*$^&Xvf~8eDiC3*OZO}qeiL7ar-9uRK|_SnA2pey%-usF zT}m5~@Zrq1idei9rvi1gXZD#BV}!|TNw=GgzVGnFvAI}3Fz!7dS`18`{5>bDjCKy_ zGDdXy(QYWyEh#opb+EWHh7M*M_-!Jw8+^Zsd1SaYH^oI7MK`O`zzqcMI+iz+f1PrL zOG@mcnCaFYg$jl-tQ-+}`fvwL&!wn*Na8xnl3ZpGrj^+tx}jJ-aGdSPyRc zI)LT)2U-U?@iUKvH~35Z@8^5M@?*l`gN0V^tkJ@zeyOO)byt6J@`A?YuFu(l$`dU| zP$Ga6a?YOaQ!v4SRHqHrv^gxjeuqnY<^C-CI->s~Z@jAML86+^rFHeitoEU}%im~j z!Jl8Y6=!Wq1B39ACM|%K8oSkAd~Zmv>Cxj{dkR030j}$~%J;gU8BcZ+VP-Q?`)SPY z^Gu#N-*h7RzD+)uiXSKX{Ll6=4;8!1D@I2Ephp2{6gmpZe#l+JnD;a7^p3w4sI&fY z{y;#~;FRaY1qoVDrwKj*ltzl)tXp{;EcZyOAgpsx?mP4Fz~=@!`6tgUZqm=U#Q!>_ z*eCEOHR!+-aYwP}I$&Vb-gzIMf|<7yF%uTwbH)&OR2nc;rImq!$`q5DYQUtvije1~ zV6I);+eJApVxxDcmL2G!EjX9G#O6?MN}@b+I;A)a#Aq5D;z~+X>kPoPkx1~WXxG!W zQ!mK)iNz03p&o>G$YEn&WjVZ!I&cUEC+4)YI;}28uxyP!3xt!I{4|BUcJ=6_@`YAb z*16-0Tz}-u#euHyy}E7pdbu&Zd`d!HQL3ovmO!!1Z;{E*LCvTzw?IrgQ>$KDwlc5q zV$OXv|3PEE{;w*j%SM8~-qAaM81birg6mAy=1>}iYYDJ09l2{FDkf%MM9O4L*9wtGtW!LR3y~04WK{&wMX-kQ6-jLkR3qGoDPpu4{@W zhkDKPqT&yJ?Fe)M&8%@ixQkd`h7u3zHolPyDRK_y0L4^axaSQwGC3QFvO)x%Mi`(pEn_*Vq zeCn9Nj?wTg2L!rQh4I=%Ci68Vu)5^x_*6Sl`_mIXz}LUQA`>J*IO(df*e#CJ_&S+b zbzY12z?T#>CAV>a;x)@XDIaAnZ2a2t?@jP_kI&M*cIJJSDxnXCq}9hBH(=WXUnO$PI~+{&`C3_vDmmH zP03Rb(ngz4bc!f^Oq22DLh+X}NKtS6*brKItB3V{x}tQEdB+~L`BUg>S2s1Udgw?K z#6*Si@C|guF=kyQ_n?bO1|Nlw=>*xxqSz(oKhFDGMg!7<*%dFt@I zw(Vgg{}9J|R`vw*V_5#gKzB3Sj1G#YXU3S|J54{%s~u*&%NX%uMn@mpMHI0ykFllI zDq)>oTsf79G_R9C^DRA~V24-U^4_0{D>`pH@FpH~$ttC}%DlyYFD;qQ@TnX@V0Q@In21-N=gR>b$Wkx#M~_C6PzIxAX@$^5vTho$*JY6l7FXvzdYRc#24#!(+aknB^OBc#l8qkDA|QBIs+a!LBLz;n8Dh z8e48s8GqP0+7z|U9+$qHP|I)_Qy$X`8FZS2-!tT|8oGl`&J%d03yQHfUtBZPT9bNf z=9F?C9kacO@GwKD-cB-n9{$mEA5)_`T2fm6Sl~bMIP=4B!AJ&YWN;Pv=vTA}6pB(O zbWG>-v(#=`1M!olRZMeqbuw*#ifx>aNd_T*nFBC6Sq=UC{PMW+Jzrtlbp0kQ6F|!f z8!i9A)^O$6niobH{~eTE9A&QQ2iN(zb?oMw=F?E9F|ZkJLusaX+i0KJ(hUl3qHc5} zCD$e%->j})XuNJh{upr_hyKjB`;Oc3OIu&+uri3FS`4^Ko?2^_-9`>PiyASSE@Crj zN94rJj0-?(A&5D==8w*Lu|(g8b+Ar-;Dvu~+o-8>?Az*_cTtO19T_CW_bR%fGG&~i)$0VrkID}-bi}`K09uyfgv&bxQFOOu*rZHiozjd`}?P&~D z0jiMB?WiPyHC<@v_WvbF^(Xj8kc-OG^Jzp=IO@f$IP;PzwaB-#qSXtf9H$FrM`NqisEza;w(7P7j7$LSXD?(& zCpr*+wXAeoGus=mdi64)gE1a5#-4GL) zs0e&nneU2kxua}E<-+W>Lii6F8Vmh*FGS?`UHd3BK1x^Wbnjc|8yLP9S<}|^N0$X} z9~);va&fEO!C!HQK9(oO#LJRU-03>NRi+(Z2%8nUU2%7Nw6^-Mk?+}BiiCtuJJ;@S zQBjQ$M)omP0%1&m9ldpI&`d)^F6Q_-vD>QqqA#LR`E~Qy($sL)EJjyw^FSqZr)|0p zAun95j+NV zfVUXVZR2qiaNVCSapr9Kh3uZuqGfOQ;1RLg5`Am?HNHby`0W?Fp37cPm&Vb%#=JH5~|FAFFN|MXKN?_)NXRJ)GSxV>Po|EggVz z?glElqOx0Jof=kjX1p7SrYn71i5jktN1NxasOg~zs+^)|!Adv=| zeA4O$>k%uEzD4U!fQaGUp7V{0FwKp}<)i_RAe?L>OtF+Vw5KVk@B(IS748GXZmjz? zRSqwhOiX$uWz6imCjj!&aldBD@X}*G4UHzEeOO35q1rRUV^RXz*a>c1u#J|)08jMw z5{|+4lKM#DQKJg1Zl7Kzd!#yl5B@tG{lZ#~mHKl-v3N^|O6Nz!A2$d?O_1@^A0$K` zi12Y<+Yw0UADpPnjvHh(+hY0&Pn>vhb@l1Q00~$g?n%;@;2NA9J_)V#ej7CWPIQaL z=sTD3a(rW@OPVPg3g}O$B+8=FBrf(yTcr-QtPV#;l0JB!FbH;)*rW~VdSZk-((U^f zcU^oS#|rnme0BtI{ddDhKT}fRanEjpK~JhG=%K$ke!_KmG;y<`3(7zpY-3)L%8zSE zn7PX`?dGrbCeUdJenul`Miq3h{D}u4{s<^7b$K8{&JgP8lKeI41&ZCSh%ge2su8Uo zJsXOrIU11v?DQ&wYCFJkhh=~Fmd`vDj3qn>!{u<4oYCK09!{g+HXf$<4b^g41A9Hr}oo z@S10M08G9M(YzF&w+$B#ze(xhp>3>@C0shrJanPY;WGBUq)i1cXPJsWYmG#!@4r*- z{ex73$rpDYCZhDHy?b#a~cJlBTke z`x=vyI29uTagPCAgmD*`j(Z=B8uNR9kA^3|86$k{!UAI>#08*#DsHQ+_D3!#u2BfY zxyDD%i^1jYy5S#<=kaywo_BuEjk)C&rNkS2y^X%?6g0mgVXgwl-_zLN4%=JeL+%A} zF=${Fjv==d&@qpEk?iH~Z!-(55+QD_W;?8w6ls-NMtk;y?ap>O<@WXg;o(f|Vj+P9 zL8Lbx-ex-q`0m8|&DV=KIQxtxbrs!4qGv%h*kWF8Ef0S(X0N3qe*7)TASw(FaW!!= zt62bzbh@*R+kwAU97*|DbXuCMw0ps$Dh!Fdk8PYdvS5CBed;xJ&yh1X$?=UX=avjw z{@RayTuPi@Kvnn7G@#wsPH(X)KK!^r`mpdAtnn{g?Re8CUf%@g)|-O7F{J=;~UH>F;RSF36LJ z3@xvbrC5ty3X+)F{;sJ<&~{zYfb?EY2-3eNNk3lN6qW^c0+Tn;e=rrp3Ksk7PVA-b zT%pR8ZszHgM+=+u0@%d?j{Wgvy6PkyKWst#w`I4SkDW^@h(kP2vcldeQ6T^)2TIDddFFT;V(&8GGc!_D>cy zQHHqbEg9h$vuop86xD>i3V7p-yGxC);E5Nt%5|{20``BS=pwGu^EH_rLA&95EVeH!*YvSn?$0q%WoSbKAg8=cJF5X3!3xSr z1Cxy!j~_e`_((Nh@U-sxhjbyzP);ccs##_#pr);ZMyFK9#Fnizil zCaC~z2!FN@D!%b$kv8c`BK3nP4i78bt_-y$NAO!lA~O%L<}o(LDlVuG-;*gTh!3IAYVwjszak%@Tk%c3bbP2vSv{AvPWt zNv8H2X;yUlZY;*(VqV?u>fMFR(?@;;A(z_Vs3_9vByjB$1rXQ|Hf7njouExzOD0_E z9Hfg`Ry4F1VON(&dMmiWYCpvjeh`U6ZzX)N=!ss3_waB!=an$O4LLtR9)$eNej}-b zXS%~I$w#$z(P2?a5e1!Vta!$Ke;+8d^k?K%H}Qwi=BnfY_pZ#QC2p&|Qb&H-d-GhS zI;OvFvHXRNk4GA@Ifm@#o5UAF1;-00V$yrcV*o0<1NTej2XRw;^!wu8L093$nO7qd z?-C#lQFE}@XvaFH&iCkDFWX6v%J~|=(Hd)@2n}V!DZ}VlcA zV6z4nR6xXy?dU&++k=YQSX$xfW{B=8KrNuOP`#e5VY%RVBBQ!*nt+e%s;$^Xa_SW~ zw_UBguFB<&Mo5&UGv5|$+ayV;h<@ukwvSF#-20cw{v}o-ze{(~#-BpO^Wx9>yu^o6 z6gI)eRtpk1Hr@>TVzLd#Xm#I0A=9qqh5Q={(uB~g5D2UiL$Q^i1Nm?l{g%Q$;LV&X z`>tGfq+{r6?lmYCNTc<`)_s%0V`o14wv8Xa<$5&TtqHhtN9a|{a=(-3A$5BZEVU?A3@aje7^4u(p2mffY;xNNv5xp5h z%l-?T^_)b=)aw1|yMAyC^}3wgXFp$nR@-V^ zLPX*SKqJtwjm@|mM0*#1g-lL#yBzty=*_JtgX%c|WL~KCrCG$;4{6?64>vbb-{qut z2V8>(_-NeRFxWg|;+bB# zry)30mR_y^BArdL<{y89!NwK(>=&p9I^T*)Ck0tAiej2{rtsgg!iBoIbFK8e#v*dY zY9$Q!h+`T5jExc$4qu-U_#NZ7TUBK?f>sz_pAr0ooZj#s4q-N!4$%n{zfR>hmdspX z!rg+yQDqR5Z`0C0UJu+>8am3R$1t~wNc)#FdDzL5JMGVXhhBBAHDl1Vie+5-Cd505 zx?b_ZJC!yO5MOwbz$Dpm!rL0w5NUXaBb#k1c11!KZ9q9>&g`XSi1t#ar=9wW`W@@R z+xp(sOmujC7#FjSQLQYavc0|xP2iEaogT`fQY;Qr(g^}x%9FAD{*%scz@ElifI+nm zjy(a(BLq(Gn>6G$?akNEdKMoGA#?qxXUwu!rpF>AWlH;Y1k^aT#-C zXGFiLGqL2OSc=8p@L)`lUuvqSN*0Taq9e_Z=V>ca+R5|pi)RYn0{twKe0j$^H3 z8Y-C^iJ^wwmC4mdpN#>!vz!O{)%$C*JwRptfv=0gLkB zdUj}bjtT8uUKr{P312lEskTtB5WyEmwy)&tLL92Pc@LWMBe-Q_@x+syEt1Yfz82%$ z?^Pleq|~Q0r&_&ZB|j*SK8(Nqb|wx+RVnSPuJ7~QeGW|X29Jy0vU3mKDJfvE(3@N- z@E(z=%%~x%RGi-(^Umy%!T{*}K!j5sg*%Zk_0JODMB+z#vn-_kPDR2RJDCAj9MIi_W>_mKF`4dH5wvFNr{)Fq z^1FeOqJ}4-h}|1}Cm|VwwXjm*@9Lj>bro7|fFU(VxtCHG@%r=wmXwZ`mzvu|e;X$fadGz_RU_ zgc8#MxD!~2gY~X4iga+Q59(Q}Tw20GEygToX(+~c)UhoibyYia=KoO(%FbT4voZGL zguxK8Nbs^$&qGEu_tEE3#P*lISG15no;IcTD%ijufmC&}EN92FJADnt+qb|ew{is= z$hYl&E2;lB*ZQcaqHwB~Nh8nEiOS$_=UQ{K&YZBW-7(^0BEev78rtSAip0+Ao(6!o zjx|A_IV3`)3X$8iRG}Z$sd4G73=hPJ^JN-rd@L$KM^GMFm#ke7_9W$Kz5UxDD8(i zs(Qfuj5EW-}Q6fP5?V?MHu;Fx$C z_nz0m;VUSK4&ZMafHH(X(zl-`bDwcy(^pm6_e407_ktVj?O15Tqv_6C#JM=N0csH0 zZ@hqt<6@vPuaGwx1q2GcywG3JW4}jP*x#Yu)KegkhXVrnR>QJE_3ugD0beLbDl>%k zl5^OmN5dcZvdFevwgXC+Xr>;#S*BJJq^UtJIpNudPHPPx{V#*ZaK94MX~mJ{VFXP2 z{d1^qssEfb`k2H9J_M8AXe<{lpmuPW0I81_en5NLoJ0~Yh&}eh5z1(LZ5_-_M~m3x(r0zJFncv zI+DnY-J*x~Zmn|I6D|3c-jT;DelMa_>hY>_ID?R%+^M`-d)(RaGo)UYkX$MJxzEXc z@mAA+^|#)~spRw<7(5j!(qVyCfL&`^-?F}TWbUfx=GI8YYj%$0|0C~FB7L{^g9X_0l9i&2Yx>Q%Zpp!jNVSU79KPF|E4cnDYwb|W!~ zFG;bl^oY|?D=X@<;R=8eD66b^LV%9`LTo}eLL4_Hob0bU zCH6qLO~u(MD;AwNG&D)t?PoV6fAfv9xX6&b;IWAdV{;wYMo;q^YI49CR}nfSjZdwZALwIQ7W^nZ z-$>r?;v5;5NOxH5C6{y# zPjcWGM)1BTEKxgAY8vvgWstC+9(;jI*i@(VQ7o0Nbc-TN2mOk3WOCzgB66?SRAC!# zW~9h+VK%0pl~MiA&I>~#0Y!L8SJk~kcH9O~t5HK!I2xix1Tx*!W+PC0^sp+LgdMwn z%V*))sxo8J$9N03g5j4|mc3!Czo?B9Kf5K+Ak|chFJT%ohH9j7AC$a2 zjI??PAs^7HVaHi6w15qbRukR=o|(I_$rIo4mlm2~ll|A4VF$B;V0n=3_8%-Qfy228Kio?Gq2A>8rGT8_hZ zp#htNv;2KGq(N)3w1V_NVW#nibwi`I6z6*^ELqE)=j$ag{guBf=`D_&T@M6dk2$MD zf4w;FMqP4KTc?=kPs|rc6&|(Hv#x$|OP4e;)`P~q?`6WI$E869hUP=w#s85FdX~Milj!k@kn$paDv-W!a={@=DA=9;6wll*>9lbP1{GQ zGwx-vzW!np=LQS% zZ!aLI%%JFBq<2(}Bx?kNlT-&)ZPw9___NGM2VKcx2rY(FkMyVEG*g(FwhYh9RDWLk zy`cp8PWMfCwv&A8H&ExXgxC4|ARR|~)rH2=&UO&^X7%9s`Gaf;V>cJUmjagwxp2FRWkJinh9X0k{_ro< zn%|wvA&0I|n3#12##97JUZNoiM?^pSV3^dcC%Os$pyx|}{Z_wdlqx^*B8K}gwMCT6 z;qWp!rj#)SDZn$)@Kl{d$}A_5CS`85;J}=hh*6EV1^xf^N)Bu3p@>@mD$>% z)z8Q71!x8MO0yA86Y|-e2&CmnlpJJ~(XPDu>P+b}TYMEU7Prw&LWa}*2xp?(;k^hA zoSW3}&(Y#`hb^Y#Yr6w|IGKA?qaz-Fe&DY&x~tLPxnf|>m|H^kM!_{$)p1ZK`kc}v z6=c2lHtjo1bcB&V^9|>PBY#2V?=PYL>0>-~Dct(8YTd4{hr`;?8ME`&N_aJuZX41+ zUw=a2Y8+N(Gd~G8ThJNY&Z1E_#1^13<_Seuua7V zHf5Cc44gRnRA0F*OcA3ykm#s^1ds<69Pk%mTxlo|P_1->#d!X?I=?sPfsmB`7? zyP_?I1PX$(RKA>PMGh8DSuMLxsEuXV)YY@Lq(J#CKly#SU^$Se%V6cZhbNm`JD8RN zdA2{~Giob`jJ_4hDf)eRI};k-;)A+iUK5~RNXol6FIN`_YGq9()ytt=;KB*ydZt>DJl)_<;E^)ieJx@0L<%%QxH!q1&UF>8lM5{3n27(f9`)mM z*U?x01r2o@TWm)Kkv6~)EnX7mjq;nLoGN(v?Hw=Mm$z0=)d_QJxZ z+)3W);YGTrAILY?MWdsy1TGz!ORHYuiJB%VE2&z_58=$RP;-fmKQ)2anj5Y$rh{(- z6S~IU&%HG41^pJ~;Y`tcNWcXD;5I)Xcx%}{X@L7&YkbapEd&fnbC{suT&#TDishXd z)+Rj3nkde%N-4>H_ag1Ubsv<$3JR{5H?Y&UN5?sEc(>UNgm?O!7Y70dsR8#ZK91HI zjjOzkhtDVbdqld8jGDoq1r&|=ju0PwWn`!+b~Vo(J>lOr?UILhBHsWPx9wz04jbLJ zJ+r>nO#;UB-^?1#d8jV11|_&x#0$O zl5=0hWaEGo$QFfSCQF)BB{}u9+JXa(xwXSoxThS{7EcD_vUr{i33+kv?@V_ECSIj0 zEvDF@6`h>Byz5J8Lk7j&{3x>NK4s^OF$5`KH2#VXq+k;zRK0|a%|dbw8}?y6O2^0h zZ^+OQ$J7|c(P8K7BIrWjkt?3M*U*rBUMg%dGPun9X(0EQlmdUpWxd`@P@5^j>-!%^ z^mPuZ+A%GOS<^^o5Rv@);q#XDVL?#qjb4L&T%WRrsv9T(S5hm^weihpQinPiCTlrX z26a%6z$?JstOI8M-ZFfJU80*w?^9$D(Gz)VX^VG4P1(Tods+XAnK-W~(CPascFtv7 zW3RWcs2hQ(7fwV``E*6Qp2xeQ%Hin#O#--&wr^LAbQ&@Jamo#93*C!}G=@?J#xM|1 zf!@aMY%|7WI|1F+hTh+Y4d3!5Dd{s^&wxs1K(T`ZW4VhQp788$nAb@9BeU9Ho23J2 zaa7>Ka1}zrKaPeaf?@NUqzeM4Y{)Y^wTvQV=(~)(=|Ty&3uFPlya2eHxh>h-MITFTHv=jEO&bU2${fRv?HU_widj)PWpB5KL zSuqtC%!nWCEYwVuo9>p|%%m)&5sv9TsDJQoJJ*;ZWlejxsCo`B5uDh7fF{)BG@t{O?Ouxm4Yqy{4@^yiSGb*0F=EG; z$tYPy$+Q;gME};O+$&&!&I^IYs|+n{=|-N_FJ84_1+WonaCQp&Bsi~h?G=A-3TUCs zaBK}s42|X`DjCYKD{9~Ps1uP)28Rv0JG(GEsI08S&P`4Bll)dr5X0u;VeZ$PNyY~f z@bT{d9{S-(lIvuRq??gL%+;CtJb^&4R2cukN@}0K$;CwhMCitP^fpaq4bOqoNl0X~ zs3^lJD!F;C^7c0TY*QmCoTYAZR7-!S*tP$LWAmqqUiw5eH=VOX1{4`I^&@hinyT|0 z5!_^15w5zds{QwFQ&zCGZ49AgC}I~4^a0&SrPW`%r`_wsvSPv_7-%x7(+xK?6AXi` zE@ZZ+qm1|qzGq*}E3k69jv)xmt=W({Sg%#}I!7YxBuZNTBlUA0Ip0mdX)$I7PqZ$f zYu-BwsMql-jOveM!NdfisHu5Mh-)x10^=K7yC%T|jR?dDS{&_QY_~e!CInbcI@AK< z@aw8j%se2SOmsNSS%$uF!2_&cH<&JY?4A~THAna$zmbiWiw9>a|E(=UvUz0qmrmN__wx1L%@(0{z=MW^QMB7cT(>^xNpSuL$V!^GQJP$GY znBVJ;okoj6pE)pGElGwQxn^Zrx3((VPcs~r@Z(+-K$l5-hzLBFk)U~IFrU+hyP|`L zTWOF50?Ul{akRP!XZcu5i)HOzjcGZyYF-Q-gXZ;3^swu9u)6LX9n^;D-Jwao3d%e< zn-}gIq)cRwZ8f> z;d}|^aYo~9B%=`b_F`>gK+)tL9XVl}p!^ll<7R&(`>L^Q$p-{-w?!E-2-NRWUmX^k z5^R1@mSJsl0`|r2m77~-#d|*D!ZHD46s1fKdm=((UW7X2x#B%Zf)yRjv+$DpK3QZP za&j;X%*2idcE{Nbr(1E~Y&DTy8}9%0U9_pL@zIwPh$My)*Zp;bpZU9BE7l{#_N67C zE~PmVq}Z{s;8Ybm-Zk82h{-T@M*sR#5SZ>IVea=agA8Va>3E-6`_&%_-sS15W8UYF zr<@}*$yNk|xwqKh09v5Z3-dhWzg)s&OWBZuvs>Wuft^pT{?!yXcMIKS-fmmVlc`w+ z!KpaA)K{u|>))pslFpLos?5DS7Mb zVZd=-%g*iOAYMoSoshb9ET)GV7>r9_4x&H9yuo2L_8&l%{6>W@7$!?J(1m|}<5KlV z_?X!*TewRw(Qr*WHrJiXI4%l3l>&8x-4e4M(%xsnJ)*2(!tH;mtlVwj{C3Nt1a9<$ zCDAIE=pk>Zzyb>biOT1ArsqVH0veyszWs~y!>hES72dm2a}I`M)v8-tozL(|v zO1U$aHogB^TKIf*rXac?ZyOujh=T=Z!f52o0{IMda-66fd0Q;vN;;)tS5f70;!^EJ zK$+vEFWcv(UodQolJQ25w z^Gwuady58_#c{f}#(yDQEtTWhJIH4mlQ_^X?zc8{kS{P}WY^veN34mn5a|!mQ7@^5v>8wqMF(Z6#8hF*Uj1}={XzCZqORWZ1ln1MzuVHdsexc+8L_;_zA2>kAYM3kXdBP7)jiIZ!DUy%LxM zUNz&1MHB5m--t!v(!YlzKj~2L9agv#7eoH{VAcO$fQAn!LBjmMB>-D80ry9Q`M(cC zzCN;QxFb1&LGz=}@ai?&QbI*UWvl z{AU|X1en5G0_0n9)|Fd@*~^fRpB9vK9?=5xfwk-#eXCj|)_+S=n8W}z*tPfS{kJ|0 za`GusG(p{`WC@XK)Ta=)9t+SEe|L^}m1Bh<#cQs;;ngW`ZzbVNuw^rKF+4 zQLMcMO8QP|Cj9tk?YCbj;S28d!56roN!?iY6bLRDfsVYZ2SJ7bBLr%UyhR6k{P2D2 z-GBcPXv?957zB!r{C~#L$O66w#l1D@6MSHPmOSfV{-<5vm)0cGYsXbQN*CbG{YEeH zpN5IUq`;IGp95LJPyA07*naRCr$OU3Yw2)%E|L`y|=fkl4;(log=t+0vHTmO_EpNgxJWaza>v*hv@x zO5y|&+l)dPu?>WhX~_WxLhLYFM#E@np+IOEr6f>hhDSn{ZAtIl^ZVQ<%aLV`Cs}q< ze!YMBW8HD?x#!(+#`h5Vq7VS?i-D|y|7iN&aNvIey%#R!-h7Dd&9ted{GUMYg#!IQk~$)Ck;lcu-Ua%3S{z*&hW_0Scm6T{y^-d=py~hB4xQ+`ebD1M)ed?A zM8izxGrlzp8Z&)T!P>r9jL;ad=)7jZJNErX9&~}md_I87h_FvLx)=cl{Ru=X_4bWR z{=W(L|0{uxE0oMs$GZzhSz?Zm%U?8&7-fz?LC1`v>o==3{xD}y?AkEc1FgFV4M+78iW5@;&lGB zx5$mv?+tZd_si~=>0*hgARGc4l~F&0We;i?s9F9wLVpz+J!{8BHHf^exk(bEQr;1L0#RD zfX{axq2|xtkV6k0?hxA7VRz?er(u%Sp5<4ActMOis04GnDTqWFN!(MFG1doWwfLDJ3JG$TYd0Hm zcF9E7T~^ppwyN<0A*ddJt)srdz~{O@kn6r=)F*XytgX|Uk7pY%Afi*EUx`xpVPJ4G zgC@_(&3@Jjy?c9|y;Gpmz_q*U>V^#T2RK&Wl_g0`4rz^eQIRbQtwH-JO#{wY1_-(PP@HQ(eUEa`CK)^x(re(5w;a$x121|R% zoN@bnHldESV;wE0Xo6P*$WAndI!-JvFykA8X#CvV|8BLO<@qLJUT^-Ms;JGcsX1OF zp)7wREz)NIrq0$h9TVUH^Pm`4i)dYb4VD)dyIhuZy%i13F9LjSBH9@AZ^^P?Zf^Gb zAmWNuo6my~PXQR1sBIFzGlACl4eet0xP23zE=ly;r&a$e1UglYxZQ4B*670@BVcm8 zK9m3x_!VY;j)*=6^G;P?2rS10+*=76FW(m7D!q#WS0WpowM4w6|K9S>CU&&AEAxX+EqH8l~R%UZ5*$YA+_@ zI_j>GP@0ZEg5`9pLO6fPl0!9z<32EQ!&G&hY?a{rX-?;gMC)Iy>#%QyuRraBD@G- z-xQXQndn6w{_%F{_z1)YrO-#BCQO9Qe!n=?eetkw5>?)tevc~9dr1D$$`|F=>~J`K z4v^ACXGKaLnDUEV1u5-7Rm;4WLBJci>oc&KByRBQz8B)D?aH5NE+P$&1DvX9d%Faj z#5|FRCZv^d9i1_-U4Tkv3-tJ3l`qNB9K`7TEQHgOtwp^vDl|nYV!GKg4+1fUKGBa(x^*ql(o{H-m9c z53UQ$;FXZrOoFENjAKz+Gq)I^66woY>CUH=c$9XUEOz+45aXyG0#|=HP70kFp2FmIXY6R{k;(AswK5Y!;bf9xA{0GGn7AvZs-SJKWWle zDRHc$(Ze-$N3hU8h@m}+?AkDN{^|5d&bQSMK;EIh}v(5NM?rPg-SX zWgP2uqKG?V2N}MDXN}*#CDczvL(@rMp3T5RrFl88Tkn6*)cjuT(C!5b`ezLsw3dLw zEwGVU8mE*L6(#gpj`vB=U$*QlO|z}B@~~5W(tf+`M>po@n^7Va4Nb}tY3W0VKcAR; z@K?-u0>FPDa6BaEku~%GCtJTWPEpQKp>fOWn|?=x8=0|I&v5+Geg2TWI@0BPA<&BX z?&|7+`|h*PFEl`DIF2Pid89?N4uZjtmpGkQTM+)3RVr(|_X|NcM5{o6pMft3_<+H+ zO*?n~!98V4t4Ze?w%Kc*wmw6vw-afjcV~Sv#A3tkkL1|x*XJjxi#B!80|r%t&~1lj;A0u^=T5);^3P%|vU}yG9J@{1+?^if z-IvNU&g`k(V0nY4i+U;aBZOxE8B1wMO?$0f>YqD&O0LoQ1w62nYFTuPzFE9 zCG+e#dD-)U?pKnSC(0VO*>*IS5b!`kp;D+##4qXFwF0+mSXhL8FWxaCh}xq9t-}9x zzwVU8BLq>aBw9ADpkPBn#wAgq%Ihs6m=?XLb5(k2fd2sIMJ(m}uV-d{6%y{cx;kxh zd;5W!-F_?^d<_Wag~k4Lqe4pKifKhfi{p`Z?;ke}@cT5=-#QIN#WpJ6>&Q1k^sY^q zFf0M^Sc|XyqahzJ^Z~a6XTi~LJM7=s*ZV6kILseS;L97D?j_I+fIA=Bu`Wmqd=1iy z^>^n#7jO4BiA=Ms?@@uS@_NrC&>uQNkdzVcz7m&9?SN@1cP?EzY_Mi~nTSrX(4lf@ z-^^g89oT7dnt31*srfzR93?M|h|aV;iXZ)h2vI zD{8|C8q`VD%uI~{`%G;MI0GP!f*;2Ysr*nxMwNTa;O0=Z5)f! z5d$g)@S16^g1DBp@`k3ZgeX9Z5q&eux3NM#L;PYO_el0-dRCn;UGLfVgU+(*@%X0#LVwCuV43Lx7)49B2b+I!-8ryg^^)KR;xR%A&u*885vJB zef+U9MT?x#qX#kb)gYl9?qe6p*V{7eOE!M|vGQ|}2OMy~fOdzYkcD;+?bb;fEcu@1 z&(_U}b%H2{mo+p!LBOR}m`hBz&dSUBZFzm;v!p)0zAvmxqu}M+UXQj|~casEH>fRCPrAvoFvnkW?s1PM7KTW#NUP@gSPMhR1862GsIIFU$Ua@E^u{po*H&NK zUAJC&WfWlX-78Vv&~yg@b1Zz+s!HYT+^p$k^^G$G(SwQR9Q-|v+z#IVYf5voCMr|- zu*}S_;`xIlqE9lV?)ipIgWfBb(%2yILstN4E{2vDX2=Ge;D94(?Hl|}BPz1&gK~Yt0 zK3(TaXH0S`aKp5gd+O^44cxiw-yNpo-F-7QHLd@2zeJDFWQZw$X7k0Q2^D-A0|IP! zZxZ~QIk`Fa%vrhlCz&=8M+lOkAi28C@PoxUL`Fkr{+Z;u2(Qgxs%iGMUE3RAHa!&R z*t0T^aerVf5gprQHYRc>mugZjjAnqC@9_*4%;%HP)SWg`wYAO%KL19i^YhgC8NH=K zS;`qbdJ%()!oNKRFDY?4qXMC)O2fQonobrPy-47piTYsB*wWmrdiTmr$JlL}3i;YI zh4B>#3iz_;GQ-#=1;)-9ldT-b(pn;jOMR=4q^jEEITb`NAn0SzS){}z(~1h8PBe=k zE}ixq2%S1l(@f2Deu=9fF3M4&zGMAf?e$)68Zn46JL>p|aNX3x!no$_WXE&YH;u9r z)N4Nx=H8AkH-0(nu_>nn+^aSoWf!)Ok{xSrt*;{QOLKEhO*ef#|JtHZWIo0;oASGz z9u~N&kU19?y9!lgcEY0WzBz{-aUBy^cHI@I-e99-y33Vz0F=8P_U=1yA99iG5H#Yi zckbL-`u-Z%Mb+RRkp3~HWA{_3 zGJ=Jf+|O?8mqGnA41L!?UG^KIkui=0P9}n~PNpHOtLJmG+Jn+O>4UN-q;3}PK2ll) zdcMbVlt$uS27VO>O5lBbXFH>~I6o;*vnsE*f8H{sSO!)Fl)w8jWLiR98Ai{B(_Qf zc4%ZX06LloQ;7MTSRcyXGWXyIsx~>}yt!jXr0s2x7J;tzcrIlU%M!rNt}b>KnxQ<& zl=(F^1)9*}I{Prod(-KqmkfP9t$SzP#%v?QHq>BUb7*$yW6}C?`@Y|<$R|_%r>-aB z#O8dBP{_dH!G|O%TxeySQr>Y}!Po)9HZVSu;1(iLVCBKtQ`&ppo(w6uc+S{t1=p5* ziE`woMW8D^o=Yi_Kr@~zb``3Kilj>AGVcVTQC<8-bYHQv;O3+{?x?Ins{8{7&LYO_ zupoeK(vZKIHqq554mGjp?g(yulmO*BVS44KWx-NmR4=t*PrqaxjFdQW}RAYI=zaQ4LqbqmRIKi@Lg=9iC=ux28UM%#bI z2f%0xY}q+9T~Xv|5$F&zRk&0CjEw6933cb~5_4xFa|#+?Tu_jVae%5lwOhM6xihyi zQLSd^vlBVfClbQSnwl9xXi-hd4Ejxpvmm~YN1_2@{?1fh-~28SPGl07m5v$K#gy-E z*mRm5+ROiK551JwVepBw$K@!z>>ii23Ur8?`Sa&zXjxhFn4tnJLn#-O+V1zouEJ}r zP;CM*=8nCF1cgUDFiUO{0XxNO;v?V3%wpmtgdmC0O48b7tD;JHNYt^8h9Q*$l}O@)BP3NCFl zBwaGSsNfAN{aLN!ernSpHoNv`qE5pKOXiw6c{!cYI~5I$w*qvx)jt25>q*AUIeFQ? zOUE2~O`zRt*4VPX-S8F>ofJW++GR^MXb~W3lpkcXZAwSKzcFr;7HsR2DB@oH;ob zf`3O3<@GHSh@{Go60%4t|G1s|wr7nj&L>l?SytaXUV!UB&@2tyOO=!#2N9Y~{XZa> zF+ANl$p0$@x_bHYpRyriJ0}63Fyl31{MFE~K}Z@3@CihG78pN{FvcL{kZ}8r%$sI!L@s zWPBzKBOo9&snOwrg!1K9@L*}#5W}w=JvDx%g`h|dna=fxj#k)j)6+HS&=|_+xOv^D zr-!`X7B61BPpczi6;v>OXW?}Q@S80`OgRq{Rg?{}L z#C102RoA*)|EgZJXn*N&j3p>nNE6>pnbZ>si^>W`;FmzOCJ?Z_Fk|9`udBS?V@So; z5sm8z?T-?Q#g8{_X}Q%seR>$^iitk@F96+w2?#WQR&JKE9Gc~}mEQ~-sAWD1Vl}^n zbS5cC@v4W%O{$Q!??ALlGB2B(oAtU{4(5koW9M)BBm-;^4 zD@>~PdhZ43rrufvmBGrsbH`78{RjU_6Re!xMNH5WR`Rdl1^5FJ%9YjhvsS{F?A+B5 z%6hkznZG5X(O~WeQW51b`%+jVSCxdNzvuu!RF=JHcjLdz&du(Ux5d4BLw`-$7YZ`< z(aF-BMj1Cxxpv92%GlC6Hza`Wr#GEucWAGIErQ)dP$WUC=HzCjErDpSFsLI)b~#}B z&niZI$>23?kVkTWZJNCRggitK`rHQai(v7zPIA4*tgMhKkB9;|QG(kB$>k+Q&bz9X zJ~5hX^4&D22u_<2C~0Q!nbTaZPK3^iXPSQjjg@{mTG0amad2cRwVBH{4Hz;+yOs!( zDY&!mv4^7R><=v6xwG}wP}+)M5+p856qO#i>99gPWjS@u*x{*}zN2ukR|J}wsk*jS z`EA@vL~jHF0k6o;{`d3?E->$t?z%chmQSBS0t)mnSUP6Qz|&;6U0$5u>BL0ypLpUB zO_%4fxl0MJY-wCNefo5>uPU$iDFTh(!@E~h>16N|&Fj`V!=qhH@IyjO6%~VKl;&nd z)jzxI8xPYMXON&P$b2|Q_tZ<<7a6-Fox%0ndCTPA<{i1iUAJwhEz?&|pvbIXaY<1T z<;3#5*&VnaF)Jr=1L+lkw!%;|kD%T0Rivq$!4pfIPRqIRsyv=?AmJqo;Y?QON@Jbv zem@<5!{n|i#zfKElJR#EG_G_^R+vh&`-G1Fd6>|6J0d3-^&F2C>;z*Qy(g1-_yK)-4&5g3*`+>8wpVP!ebSKL96t3S>n#m ziHl?!*}?2p-yYD9Y)2Bb3qh>#t9um!O$EFf2Clt*T(-Jiq62#OZp$YJ!8v$skfLnpQAGy7tf9&Mb3Fii)~q=Ble>ZCz%w!u7C%fb_LwagFpDf8KXsb|51M z=3^n_&Gll~!2`5@(yp}`Mn9WS84AR)5Kvl|kzmwm{k4jAW0$7+GFA%E8F8_l)9?iw zl1`gDHtQ|->J3>o>8K~-pC;&5xqg2%J2$6GylEOpN&l-^CGZ(Gcz_v`x78z)WbVm-7v$!d@HkD$0AO&q<+`inVBt#fXE>*e$1{mYD2Mz`|A;7KG%{#r zap7g2c({1cXmh*Wj;uouFChWt8rvn3J)%A{;k=TRwLaTD=xq5#ByW#}?@?)c#*0ti#iaozAMXQy$S_ zmB*`~$Ku_|TBI~CY5DB4*LwgOLzTn+)07*naR6q6R zi4!~X{V8(G8=49TNb4gg6~6YOptmZdCw=XQx8kUyGi{l46^QO2W~FseJKTCkprABw zRIdRxS{7(^uN-p7A)_U;Vc)jx%a9&8#87oKXK&c_DZpKvX(aQDfyT{aZ@lrw5InBg zL|sqhu3h`<$ZU^PZFN~B3p&V3kLTBd#Pcy1mswf3rY1@kVMRC;fKGEDFpq;Ekh}TU zRZ7|+ky~8Ub(gMaXucfav|@Z%p*cz&KQmg0%#$>ZktVL_2Q8-z(f!d$e`jf2{||r8 zTgPQ=I1I3lC(>H&jtAL`;QDI0wvI04^?Zxl(!{-1|sPPUav{BjP>?`4zw4 zf5{D#Cz}teo|Y;TjMDxJ5sr`1mwG`wzSGxsQ+RMdS$)&hf}k9Fx|LqsH6zE`DkVQg zf+i4fND{nIByMEjH86b!$t|p*O%T~wVgR!oN`i(Fl-Hyj#0(#U7thHX-e*@VH5W?) zJ>TQmUw}T3$RwpM_ir-eWkHw@qJ85rhZ&ndw3L`#;b=&~lL$@F#pxxJF8egpN1~1S z;o92cB=fZdnw-dEj-+wX)S{xa1ON5>OzY_wNvBAYe^y?&q84^^{Xxmy=b-`$rTy!rhyQRgFK%3dB0=mLZP`(*yFA9KM zZ^fC{UtJjU@%XUUyRX4~nt=EjgUxqimwAO*dEu~|IDLsEw zS)Mk3UB-yRM-8R+_I>>tOPgP7v)lA7x8`L>ffY_PWY2!LB+zPz>e|}bV3b+i)srDh zGNw;+6)MQDsKqp#2%gW(!zqYLYME{V-#OLkoSh6kR_dxZMfTx`F91WG5SHj^w;zc1 zOa=O%hP~Dbk>&@@U+5&R=Z*fC9NDrT+cK0ENyC=GgLb4M_JB-miWCZ8TeM zyNnmasiUdIu7cmk+?}6)K0|E%?s)=!ZfO;|R$?LOE}QH ze1^95yB7eQlfq<`&%jB=PG?%edm_iLtntninz#$hA*hD9B>L?8p)K>M;0PcH}?g@VxqCCbZp1>YgtIlol)fph)~f!kC*0UcOu2k zYiK!Iz<8BFyQBCcI$`i1TH3S6KbTL7Ubt&FWZ4GTKP5t3g+WI*x+I=yv}Hfy&L`zx zlTxuP&`Q&xf!2WNu+EW~cSvbmIc?&^s9#q2UKkY2t-k@NYXo%yh_H?@t0#$&QdEO( z=oikII5D=4IwiIR8&%eL=Ly2>L{3qm8?(W&_4Q{QwC zg>8TqUJfiJZu+M`Ykv4O#~RJST9yP_!P*XUIPMlCt_7 zLG|Bm)3Hj^Ci#Xo$R&}Mwa_q?H8qok&{R}IXP#-Rla!L@PAhU+zBfkgH_9!=1gSY} zbTx>kSmmS7HWF?95-LTakzjhpm^J`X84ySXtLn`7mWh_Nv9aXNyy0OQqOJs&t=jZU zA#5)I)=m-z)@i~x|F(-pn3)o8t=lqWP^Phg;<%%#>!ZFgFvLA&RHtuqMML8U03|hH z2EHWj_v6`l153<1d*Ve@f8@19Z+6&+RngG=B9w|XxuTMml$DOn zzCF2SadzlOz24C}!vo+His56-%)2;1r%an%sL~r-E($}VztFaVDC%z8kx=N>Vwdy0 zXq_te)FF<+IX1iTQzDuO&^Zb8(JGAboRZ69XLhwrd|1V*Wy^j{noR*j#`A4fdfewo z&|_$)_rDu@`WX*RHtH9Apkm8oz(iK$%f@Xk~?Ch5~bm zXByq^YqK4E<5l@dC7SQRlT%^+F<;xt&{E#-Wd9}}O zzceh}aXpYlWxxfI`tNy9 zZ9H0Y*gi~U+@#tl^_k?N(s9F|p7#8@j1l@iN)K)6y=0EVxMg-;w#r9{d8?X#tO>T3 zMnq|31YQW}HkW(czNX(y`Krw`Nl1%4N$=5t>b@8RKNI;>PXUwjFuf)Ty1vesH(r!FIh_EwpvvN`?tt z>*_Yf&^8~lJ(H3$K}$BSnUgodv<;NiZyqm5B+ObCKC}ehZPk6}sVjqeP!7(}SAfiS zn8kUUxBSloI)3dQpWW%-V}%uo2B7MinnOv`e#XpW33LGmW9-cDm>E^CIczs1iuwo< zvS9V<{()`V|3XA3g#H)AuAqf5S3;Gr+hv`rSNqUEwcS(lsST zg({9QzK>1B4JQb1c4)2;;&%w%Cu8xBrNLKEo9J8^ISErAoYCBB(T^f&9z-^fjBAW7 zJ8SI226l1XP1G?PMq%l=5y8OMRgIUDprjuD04eC?mjXU{xpEgRU)6E|$asv1)VnB= z%!OP7TBYO(oo4q$M0fmdq4QwPhrHg=8Y|$w-SA$fg^+N{v_fkS!}*@&S8K#d{T3Y8 z%#y=@$#K}v%FoYFm{K_2oT@#ZUm>`Y#EfMNeuN6}k#DvF=^H*?b&dCSD4lBb47Z(C z)dz}p98z+Xvoqn(?tV;=b9JBH$Kv|*uo|yyZuhx{WoB-Vlgz2x7zB)&m7D#nDbTAM zFC|V^phK&Re+Syzf9B3VU`xf*O(WTkRY^qWtH_^wOUGp2nhX;x3-p8ub=sME{u)7| zAbbF&@P`ojIhyuP9HFEtuQ!)~2Re4QP!~!EJ)@+^`A9NEN2^=q^)4sSWtRF;9}@8z zl2`~f-t%QPk!FhxPqcfbkO>;oSt#30=sMjJ!E{*{1cj2Lc_GYUV0^%dVRhbXZwK zRTr(teO~Vm`Z3)C zg8C4;m_S+SvLTA5xeB_ZV@PHKs_y*7p3^jkSd+*vI!eFl!LfmvzX7Nb;BBUsl37Jl zk2D==2-%k0RKq$~CzoXT%V;?n%Nv@WAS97Dg|U+fa|lp+U@PzkUG^J;Q7C|$h+z4V zEe$zt&bZ;`JEy#%S$WebEbEjCGrlIxxM220BR=fNpldy>e6Z!f49j2q z{3TBus@df$0R14&^>ZgnejP+#Bj|7Y0|L|+7JDI>Uujyu?pLWAK1^7#fc`>?&PypR zl7&VJD80Jnvvo5f=T+9wI9ouy`mGfO=F+YQPRq2}|3VQPf~6i9>O*e@b%*bb(Vh*^ zkLTuQ{XHnqP1grc)|88slEZHVtifqfN?_rxX=+$#7Lszr_VIEJK|! zuvMqP{x<1&kBB35^A^Zt1VB*ES=RDuGyAq?W)HjXJlbXEf;qYQQDP_*rj(0hnmQ*h z>k)U|e@56d2X@Q&6|ZB3vt2qiNBNvvD#-}+hbmL4rCyV-^nq{lrXNQJ(pu@J%IkfY zVEX1JEQw9N3A;$Df@FEOi3Al^?rdl}ivi2&oB`fEdrbDo^3~1H5=0Y@h$8OV<_0SUUCDTK5^0KZkuWzm+VwDD>7YjE@ z4xBM3Z$H!0=U&}>q)p1#sCy2_WN1*>+!yG+#=qGzavmX~E0Sq!2Idl-+7-OAqlYNQ zV~QId)6u|$$Mtw-LTKd_ymGwH;5!8Hy57>#st*~G<rm)*eqwj zM~vpkK;Kv`m~eGTVPTh-eMNoKcUDn48GJ@*ZqA>R^~Xq3XwsF{DbVmrd&&hCr2B#7`pKbtH3m!yF_$PiQPk+xd(@4Ph^ri z{C0bNq?#-Ed)61A2xLvh8~%VVHxfcXsm0_z`&=re{B}lBkxH$WbWv`tSq{fb1XAFD z-ObR1Z^8U$1|H6_+yAo3=Q~CtaV@KdD$yYn$DbsEn05v}1o%zaE*HJ=hl~$T&-If6# zc0??Y_%2;qI`*s*(UFS6bZQ9|2G1#RIxWBIt&SC{_t3Is$7n)(l88D(K~&aSuv`Qw z>zgw(*M_HhQ@$jdT3ZhyyS+#-X2tUQ3!_6lTCZX$Uz+B0s#Fx67Dfe@gLdO+sTnT8 zG%4(1s+^NvCckZB@#Oq&khm4~O)6SEZuB=Zw@T2JbMvyFxN}v@QIh0a@cLvD$pvBR%r6i9g*3}5UAS;$4;?mNle82Sij#>Uq5KTu3Zg~dOAenOE-e z8|8Q9k7^33VpUMQ^F0XgrL7?SICmghD^HU`*r!!SSO{Sf?^0W;Y;INv;Sn02`0|5^}@g7>rU*-N1 zS7Db^Ck|coz~aS2-W)JsM?C+QI~%r4VK%B`qH_Yz>U!o??(u^f-F57+Wi~xSFo9vL zuGeNiv>y$~@VEHe#mPkC5Xo`~ky;aKVKO$h1+;(Nd2x0Z6`H&5>!G&HOl8E0715nw zw?{KeUMR@+hJ-wjNU9G}C0?~kceMVM`e9b-*kSjm>|2Rsq9+3->O0}@^Or6?QPXU{ zXO-WNxlIb1HNBT02ci*ERa28sLW^moRO#H<&n{O=k;%S5nyFKG|f;Iw3N8B^G(ttlrT7Ksf4&`4>GD!01CHdZfkS zn`GQECpYVkSU@-7P4}okS9xmJ5aH}jf|vusupb5u~ksf1We8>&+_&xF}3`lqTknEO5h|F*&A>xpI&n znwj|*0Vwapq}PhUt0if7eb6@a?Px)#?lo+)ZErq-1f9#w$|Be`6?IBnO@AY1{8nF^ zbz3Ncrq8Y%$xNlv<2hE4P+1nbSRR>WNwS`B$&4FWx3b22yATnP=pB_<@|`6`iBXrT z7cU;c4u{I)FcSk9A%D_4Sh`eHBTI+97$z z)=^u&XxUsjee~|YR%UX)3eA0v8QtAkR1!{-+Rp@usRW#sj0au1)@_gU!(1I$`_c7o zcVa(~v|z(g}8@mH0KtlRHI-x`9>nts`3pT%OHse1GK2gFJa zpA6Gg&~87{?uW|#7uuzmTUpRUC545v65+C$MkjCWSFx@w3g?X>CX_fYtB*(5tlG`P z2M*B2OX8DBWe8yNtu?bdSl`;J-7_5vt<*n`dV|Ps$*{mK&>Pm7#X3GO$o*F}Al8!0%ZXcE&i&Qzf zeb^28`IOL-9N+Y9eJWJt@mvUyvek!nU4xnb0m3u7lq%99f@^wVFZK)qsM>N(2$G zv)xBW-E>94*Ilj(W&^F8eQK4UKmQ z5~ZoA_bd+9wVI`?LP|YHHd3e3+|u0aiaymtSJ%`W#zOlj*>I(vPMKI1O?9~}M>Hfe zUc5D%@9_+_39X))l}|>($FKhb zD*3q*MnU8xreh3^p0G*z;Z&!y3x-A_`W~#QJHk$Zzgvxz2^Z+{`leHe%=|1?U}h7M zq5@H0mn3FtU={V#D``U#646T)m>~tIWL935r9kSm3bgWkvuWCkP&udL7nSl?xnsU2 zK#trpScXNZ~g~_^}&R??RP+@n>Cm`e-q4d9hGr&*zchVCx zr$l!sikwcR$8(n;q0sv+m2iPBTeW$L5L#7=&OcGdlfVOlaUm!!+La|*_p(aLwY9J` zH!H5%GemP*1zO#uvkn`*h=__}Fh!-%Rld3to7b&d9ZTI-y>#j6u-R2sSQXi_`+gd3 zxMKXF*j1QRCZ~>_d37)~Le#Q>B!0Jx^#wDFidrK9+?D?O%l7un45G6&p*@vMlzF&7 zSJXFFfv7m4;3RQRW#B&)3`QQ6uwTm+_PnJ~`O^?^?(E#`_pFd@U7#&6wHFPvDd?62zWv5b0kPD;gxL zY}*^^ZIUE0tP8Y--l~@`KY$JSCkjXT?`TKBpW5xV2{-0jM=Ld>VD=q$ z7X;l9W%zbmz<sz>vrb@R2Uo|H;ryKBPto~9GXyt%p&&c>80h5{Gis6$H9Fy^_2KlRNU9OK)omAz* zg`-4fKP3dQK@OEe5%4DxRNV%=6D|Ddp_1l2}RqM*Q}EhmIEZH3O11iC|I zr5e?&)ZFX)}B0rffO_CnebeCMdd=)Wrt*r>ZVB5Jf&uXTuSbbJ|ypMpWGx1Hlv6=CQ zlISWus`Pqq7a;XGOnUCt<{Q0MNTBT*=iCayyq@&c=WQ8py}x$znJe7KSjrz*QQveK z2+ECQ?tDwkh&B6%y~`hFur&BZM&Q2*aJK2Vv0^RSNJHfaqar-^+a_vqOOXfctLO0fvPD2G!sq(eV&COPcnJkx}Kqq;rukzF`BtitFQ;bd+Z?)~(anZ~vQ=*3S zTcxzx>wOKe3?dP0Z?IfG-Q_Bb)pwQ0b03kgAXHYV<9{>oChPnu+2~&+$;aS>NrYH+jIF}gvGl`uHtY^Z< z{x;uR<@rGfu}~>r-Mk+$znN0fAm;aVk$J9r%;2QtCg~ko5o=o9fJ*?%C!!-6*e@n# z1mjx+@>kP)@F<+WXi>J7k*RX7!~#xHBCP;jK4Z`e0jV#(Ap-R?oY5U{3;!k+ZJtUY z@%8Z-9IHvGf(c?7rj!%WT4H*j+1K`T2(+fWzGVVPK2EXME-F1L zj<7U0JDU9=F8wJ9bf`x&-Es5wL!{787Q3V2-~a#_Xh}ptRG^DMCen^FK7+G8Lj@+_kU2$=7XOL;U!74qq<$|CAJ{iI0kU^8u zcrf!;n?ShEX1Mn8PeTwhy#7Z`;vo>u+}q zC4-Ix@nkZ2pB&7wDSSaVvQW;P-Rv?+r7r@0{TJ>_Mtpwfvs=z!!+0FQ%mayJrkxo} z^tIK+%C%wUA2$uyr(N?BAul*U;;WR3&e8qyXf<}S0+Wcir23m*IK03l=Qs9~dy`X(DvPMPu;uB~IssNfFsmxvI7{pBPJ$aJN)hy53+xMbioj zHl#A9YExd{bR!XdXSF>uw@6|C#oRIb{v%eKiu%ni1k=nZwWhT-Wz1!!LrAc?nneor z1_ocMznA@{cJkKq1sf_oMG~fd-X)n%4&^H>d#2@ALdX{^#y+ZN+Tzl@tShbZD7>Dv z$y@BX%Ip0B7;A{SWgS&tK_Mhv zs%mRj5aVKt0-&7CE6HJ>U7Vk9=>&)=e5;!Z!LXW5R`G4d?A#m`Z)g?;LT*34l{rDV5A=}{PKvCO2D zqYqy|FoF3Zi;6L4TcMc*BGWwFz#1TyLJz_MjObZE8@tnNAr zTA|rtn-C8AnDn3_foy0w%?|ljEA5$i?LU0kr-owbOb|s)SFW#@1b0>QZlIFbZ(%kj z3KCO5q<*tfHcCIAHRs~&_3mdk_G@d)wD%v#+>9;0$_qyOI`R{$zzLP(J*kb48Qb;D z%+c=i26d+Bo40CHp(eD1A2KsPqYut5be}^iSyIv^DMAzVZU&9|^~Z=XDP~>9TY$XJ z*Y5aJw6w|{56)9TLOqnlS*@knW;M5t2boX*zq`l)tsXo|Fjj%pMvn?MC;V?y8?N7 z9yVKX>4p1trl51L+>v9`e9AcT8-P;^Kww6FXW_$(64+8s0eBz925!s64{$_ zM>TXlf5xQls6_EbHXZzJ_V`v81cPvuUD$tdl+IxgbPT5CACAn|jx#L9l zlqrcqu;{+p+F={%BM z{uHc|bvE4^%$J>*=00M5^kI}wHn?(jUXFrgh+6Kd-*%Wz{(A-E6ef%yrDbAlmdwlM zjLk_#`xCYQvix-c!IWpb~kCRJwyGUg*BshPX)43vATlbnZwqaj?eS*;JxeWO; z0v#8{8!+my3JOfu14l-K@JfZw@HQ0XomnhaRIJ*39+P;g z8zMhLg{b{je?NP+!k}=w*Vt?)9<8)Sr}r^iQyGpKTw0o&b7v}z6Sc8w%ub6yD|b?d zJ>w5C9wh3X_6@8t5v7`N~P2kM_%!ULe5R3Bwc{+NQ zxk;%6FYPU?>bqasGQ?;zRMhv6I;YRv#-!b=Z}i>co-(S{%n^8E<4huh#$$p~^D09?c{VmXH|$ZT_Hr&7b3e!6!3lZ|=~js;M~_ zLVG@3U#xV+VB9JF?NwU_4%{{r7(#yi29=^94!EHT%Wng?N@rg9T}H-#(A4C}8ZzW6 zBB5MXy99ws@Xamj*4>|d=;+xjXs*??4e=PKauzj%#!7dX)af%F(FjJ44gIiN+KEu@II1I=h(TkOsUkWz23S6=_Rc4L@|Dy z4>lH+v&n-SEg>_ zPB=o03bUSW8rk1Yl>{D_te;7$WA>ySgJ0Asdz^A$DqGcf2?^ygO7X3ggy*(N6ogX9 z^<@0WwrLgUWC*MBc)di_-NlpfT&vVCwG#LmK3=ug+hAs(N=xCtw;IMpk@*GF(sf5C zrrN5E|gbI$!-;|RM!%3yM;#mRg^w#+kUT`;&a zot(vX39F?GA3EVc(JEAXYt?zUeKH<=t6nu~z6pzr1T$ zSCXe_3{v}Epu^}^j;{}_SdnS8w~N91?#tI)bWvL*o?Il|Ro>d)fm!84(GA$on(oRs z-3--(bm)Nx4kMfGB%x`y0;D33cbDWYmoYUh)|Whf&GOaFONcqP6IZ$h>ZN`da$;%j z@S1rIO=oGqD@mB;mHBAS?6EmP(4RDyz8B~oOu)<(AZ#xZ;drwf=K5lnGb+B_LyNtm zg`LL{=vSnSGRk3!$Z~WFGykP|{kk)ID}PHxL(}~#6=4t9u}7OK!_(Z{oVxOc=BJ4G z;v{??+jQ11yghGZw^VoOn9!aT=oqJrvOH=+96X|5|9|G^Pv}e(Q(04Uwh$^mcQCe) z0Uy9elsI?mx|QkM*T4T!(~FAC2oKelP0Kut1fNa<%Z3rfacw)nEneIN~f z8__1QX9YS6MU@MekD^Rj56}t3{HkHoW*Ti7U)r=C`wC&JK;%P;Wra=Uv6IrzL_Zh8 zb_WPYO2$1c4%_XKPWhD{&!t3SnUzcfYL_O5{rq@QDyiQ5%ARSQCNxrEQR0!;y#so;8V9b*v4Kr28`5_q!3 zIWS8sC>@)fO2oUxA@%?x;!&nnrAp;$A))e*^weGQ^AL-%qkb4XlA z1&%hWh?wjo_7y`iKWYg5mT;9WZIp-`h?2l$b0e$~b;h+FGlYYTD6$*s+SBM8HXuY;fwwj34>vpwo^O(8YkQ;tbnV~&Ib3v+C>j`;CK0bx6qU&jBUyMvw5z7doiGf(p`~TDGExRD#>vO2OC}Nh zTLRshj8w+VWUOiL+JgeGGt(!O!T6GN!lfk9WAemQ$O76_kTkWybNI6MdZ_u zgTqJEIrraR5%&g!w`E(UKw?5cGn3mZfgVr*+RRqXish;L7XwcS1Wt)H`|t(Vg9NZe z0=yvrK0{RRQl+3`?mv{WQ*3;8NB_$ps<@8M`Vgf*Sr zr66THV$w2r7SszZ2Z*n(Tv#+O0_a`c-xQKKq(9ZN&=flo!LUlo+}-kyvOji)$C zaheSR5$9%q1PB8}C=rOaGDR>_KxqaM>jLZAdx*lB`G!?czJ@Z`!eS7ck` zX?@@6$e*>}3L~hg!3lyAp>|c7%QB~-sqsRMvjWghZQXi_Lv_UDZsR1F+N#QUbq^yp z8)0!pVL-=Ve5V5%!1X_OyZ3urTILHhNqEFBI8^A4zGIl8)@e1%3P6YI8!iA4^APC!1n{kJB#(eT zl0=u(RaGV2gKgOAD^(P13k4e3Da=9lPm=VOKx*&$-~;{w2-k&k_=lj8C6<=wOm>b3 z==%1f{e?Zk&^HPjfmiol(6vO#V$*{gXxT) z(Me6JC=oXL{pSE-17avypC~ASepXvmTm_a}@kZ@**xTSyy zhJfg0O_LABqNH8Zabz`uNLaHmjTL$Tby@k);#r(?W16Nd1s^1Al3jofsk*`ED^&nF zENtk<3`x4K-CUBN|KEy=ib%2&|8IS3>!iG3@D>7mHge;e=wH=U?(alfZV*Xc@U?9y z#DrWtjR$Df@zIX%`xGK3LQj?r*e@k{Q4!wv1_}>brOc{t@2VC8Z4c*zkt~LftSBo= zK)sMIWE1z#N==cAC=~&a<=W;n_>2S=gtEe#QBYOS*n~`99iYqh| zjR%Nu7m&UOg_sP4w}cAUC(WgfWpAPt+Q8V(W9O=h_IKpHvAKuO!+TM{UkD6J-I+jC ziim|#V)`_o@<+;M@^Pi{tnKK2H4J!j!=2h%5^dLoR_j@KR=0^ns}Vsqho!R*&_3T1 z0`x~nXgJ#q=#PMcOHvr2?dXRS@eyDTAsj|vM*fpDxrA_WIDOP0ZajFfTA)~;?B+U;!JiEBN?C#knK7$k94sclkcU?VvuyHKmPEd z;>Z`EzCEy92zWA0?hk&MwwwT1J{}w!W{nKLA6EK}Tc7po*H3cJoVf}BuL4P}j)F6q z?q0aCpMTW3=FIse*WHN@6-%8eYHxGz;Qew#Q`5OlN8Y^zvJ?>4)wtceqZMs!ZB@F4 zwH1J{VoZWRhm1Mc@QOruy0)@%Um^p!Di=EQUlRxyr|O7Q0L`-2bOag@uo{3b4%_;? zv7*d%by#A3XV-;7;x53GkyR7#C%gLqk!VgwuZo?G*&h&nu6rSM7(FqNZ-h_FuT z`YW^Y^FJPYiW1MW8+^Xo6o@2HC7pm&0sYwSLoU)(rqYd>%biLUsW{3EK@iScakGmV zt&C@N`;mEy5UpmePysT37W)mCJ2wE-3J{Jg%t*HbAsG4`e1*wj=^&b)sh!0c4UPZiKC%hP$HNTs1y z5b!bpN=nS0%J|%dh~AQj46Hllhlu9 z0L^w9?4$^s2N7qbwgeS2@(_Xe%lF$OAN8*D)?GN{*?n}jGf1U6&}E2l77(et5(^Zc zN`n20fP+JWh3{oLjBUljq!VF9=;_j@v8AONP&}2&$q54f?cT~;e<%=7CM_p%RC(+B z&P(%VZ9xRL-99A%uJdy3%7sO7i-+1hW+voKIH2uWFEin)Q^zpsG8z?GF=@3ZB3x2a zwRERhO_^)i(Q&jAfNBixxELoO=6=jYH25MYweNWrl~}3=Xx5HQwV!Z6XUfp=8mFB-m^B;xZMw=Ih4_TdFv;W3iBr~0FdPf@NFQN4oF1+m?#~V zcg};rffuAfAPf-DK5Ymd^i<4D{a&IS28^?e9H4D*aHG%nSLAc^7!MJhKt;^2Ub^&6 z8-|J!LFjqm)3b##xd16xfA%ORn_=TeFul6n9g*sl-3A?9?p zS08(%rMm^q0osOnXl(Z11%lS$$SN83DX)qW0AC*t4pl9`{r2NF3}vr~bkSq4HnvDh z4Ct?*!M1p9j1Z1)<`);2l0+AwR8b-lfG!CJ@=$;K?q$m&!Hn@3|0^%k1P-%sg*Ku6 zSAHhV8)(XVrW%{qWg>cHA)qJ14Y@JndcZEw+a)K-RHYB-3@K_Aa#^mPRkO0LU$*%9 zR6u8oW?467Ifb&q14;0i{tBHHR_2t*d0@l?=>s~qqMzni$}Rv{0CaX4aGIm(v^Re& z8Z7|&wD+M!2jmt4i;gqZE%&3)l)G|`v)uzPx&14%?dR5(vfQ%h)^RTw?z-pN0iW=0K7W>Q6s-KfyGC>UEy9};a5Vv|bEq6zIz z6iqj!f@BPl1guqq6YFCk!N!?EQlV9$P-~~bh1j~v!iB_z3W2l{JCjh1Gjs2e|DPCp zxtn|WzH`3EImE^x0ByWJDHhva8a(o6_%(51DPt8RUO%+?wIoiO@0d50zH^Ivgn*qO& z?Mn}bq#-XpDCE1~cz}=vVqe!-D+k6r^2*TQ)rs>rkHO$slD!aG1UZ66uD&CC=-%rQ zz?)Y~v9`sf8~_KZBA6!u1TeZ*ZrPs(bb}s8L9~hZj?gYg_KqHGpX21@WTGjPIc>;Q z0Utxkd+Fs`wYu6I1hbW7Pp6Dc3!De>C_KL*{7-;pvi%)5_%at2f|I*bpfH~R$HS*d|1f81K^?@5;WK;WA3Ni^N{(moO&t~&VU|i5FRjJ3fc-` zOSUilK(vLanc`k!bsXV(Z)Vrb;KbTJfj)Ivki!h6%xTTMLP8q`_ysxC4X zpI>3B%cpkaBz1#+iry|{``a!zQttq0*mPanp}7Ez&CUj60|V6t4RNOn|7-nUGD=QP TzH|YX00000NkvXXu0mjf=E8q8 literal 0 HcmV?d00001 diff --git a/docs/_static/favicons/favicon-32x32.png b/docs/_static/favicons/favicon-32x32.png new file mode 100644 index 0000000000000000000000000000000000000000..28102ebeddbadcb00c8064dbdfbb01df2ee117a9 GIT binary patch literal 2362 zcmV-A3B~q_P)Px-^hrcPR9HuiS8H&TyUk#bSkg(_;P zki=1Ouq44HC{>C`AkjJ?h}lhSkk;6-)mFtztF3lyt=216&@zYw0wxm3?)N^OZ!bv} zg6;cjXTSHH^PF>@bKY}^z77GX&oAiyble^95AU2nuy1t3oR!^5=mkr*P`Uxasb!(y==)ms zEdv#n&_S|4fDQm(TUQUraGygK0JaulG__SQnJ7>pT2)#Q zO5RCY&fq}ZmM71I<31O&?lnF#%g{V^l(_niVDR6bNH`qM3XCqQDVrO-J8h_@W$z^p z&1+V=on$eg9{`@$-RCfXe(5G5>GG=5!dLq!L!dqyT`TaSve29fUd_}+BJV+HDVrOt z^bprYBR4=ASr!V_q}4C~O5W&qaS zV#v1*`R=W=XYcfav*z(FCujTopUc&wt*4Ht2v3^i)<>dufLsmeinf72tRQjiF}^o2wU)^2%xq~GWN7|`ng^Cb;w-SNrkLyL;;Fklsc zJXbcqA{6>M?NxoWaW|wP?fu3db$x>eCI45Kg!c(PEusRzAX#IKl=lLD=geS2E3c(WrF=qSunKA6R2JHyKFP0 z?MsrMxA&Wn>pFQwUfBYAM?f>IJxpWj1-vQY6+_%*k*JVA5O8GeqN;0$J)G>hp28;@ zCp!*STiJ`V$YHM7LKoLB{PCQBu70#BkUKzoCA|UJ3OUYUV^srkrYtWxn0M7pq~?n{ zOfgYz61J0=1mI~2BvC5h1JJw(*)jlsswyeCG~EqQ-_URdjQN#>0Lg=rVy!!Nd_Nq% z$37fs`l+QJfpm~$l33y)P9T<3JhXE_C^o$`(QYGazv22PfL`@@jjwfb?M+|YR z7p=gEp#v6-XDnF-DN5EiHBODk;-86(IZ{{oym_D1ZfG3l&%v2refsgA3yO+f5-_^e z?;oAt*?E=^*+&izE*?jq7Q`l+oGHh5>o zJWv;nl){)VVeP#T+Xed|h`jP(==TY(G&Ef70)dLTbDyb;G(HZfxHap%(N4}u%a~A% z-GFW*oB^U6Pp2eB&=iiONvor0RhORfQRZ6^jjRI9Vu;U^)(@~)t}4ss1y`=!vSp;- zab}X-)J10bgii_d@5sIIwzzL-Z89~8N%$8H&OfFhr9OMUr@CScBPypC?&*%e`bgwl z!aOMIqw-*|+>@wlh(<^Zh{-PT88egM3IQDie2E(Op1pn(BG$3C!=Vf;8s3hNinn zyF|oNBjXpf(v@9Y5ejWcR*Lh!pgl)AIBxNRIjvqm?`!$Wd!}m;M+F?t6m$y7Q2^h9 z?3)7Slgt(H5Wv3!T1Vr%v~tSe_xb=3ymkNq73$1PYe)f+UhqGjJ0LwpFqTHqlP<0v^G6P+#zT020V zA!%z>Y2mDNjJ$a$V;<=F0M+H$|)z z;1V#&c~)>;-|1iHPg+i5E`%2aJ|nsxQf5A(>r!pjy5!ttQwthodN;fylOQ{PaV4#c?9*uW&G2iAfY+kfsK()qr+e znpM?P3!Xl1Z%oBM#Rkuz)O`Fu7DP{AeI&ZgkQ4X$eIvrNW_8`SZQpSDu-M~(w~Yyk zRF@2UEMfFS`Z54yP`HPo2}pe`cHYLsZ#uGXzj6M-OwqoreG7&@EdO7B^-`Ij!?A05 g@0BNYw~sC8zZ!iKW%?>nCIA2c07*qoM6N<$f{w&z#Q*>R literal 0 HcmV?d00001 diff --git a/docs/_static/favicons/favicon.ico b/docs/_static/favicons/favicon.ico new file mode 100644 index 0000000000000000000000000000000000000000..3cb2ee896e214fc013b82b8798e7fcc9453780ab GIT binary patch literal 15406 zcmeI3dz@6omB)M3#77cWR5ZqD&?IU!zLH3cdFi^w7^CmnN8G}E^S zQJ5LJZ#Pba8TxU%p@Et1X+$I{LVT}LNe~|d6@_7@dj=2@dCl~GPu*L$Z}&Vz&0qUT z^SM)X>sHnIol~byojO(cd^Ns3eFq%iBOT%U-CjQ5NT1I)VubyE+%TW7nX*$(alRkp z^F2M>=R1x%G@*rEPBP%HhSD1KkCYdAm!G7WjQ_Lx-Tp{TRY(0HFD-TZ8eelu{n3`y z`0Z3IdQxnbc~CkTS-ZfRG_0rHh!=9kYh8I`Y)>wDPML~Bh(vy=q?~#jH_*qM#r9xdF(16b1!_0-H8+QcTglL6v~94g$Y0WN^B3}| zJ8w+u&Ii|Yw;OL2+l>-!-za2_&P- zd!f0IXDiREg?#YCV$K-XxxhGAz6<}hDK6%PBO`3MNUa1%x|UBkt0%8WcB)N@a{sc_DTBaK@PiU zThh;)t^NZV8tV5=rK89#bXRjr%RcF(`TL}0&O?3+k^gPb$rbYk^n!n+2i#wXATMKI#NBw3i~o`x(TQ9U||DwpQJ7;9Ta!Xe(c&M}&0Y1KD z;$F~?F#aLSLVlL{7-R8g`kW%VL)-h|qlkzXWsjTv=w~}U0X!E4`{y} z9r)j3E^w@B<}_7(IEoL#4@E`V#-WjDjYg+a zO$V#Gd=go2Y^xig0NVr|*mgS?&nL);of*M%CQpsZks0jgCFjj6U^J>ItL|iok00k# zb=``0{i0K`ferh%v@{&xmbe)&z5xrBtyDaz&rY3zt9m=D$Xm(qd~~yWF1A=c6y^sH zLm#Iy|DHf6mK54+e_hc)`gcivG_iPm+Bcc6SE931(YG^a^Uge~kHtb?m2c4A##4&N z!$+;l8b>e(JD5wh4Z?;oKd%GF8ua_=?tI`PO}hfq5HHNRvCR7il2-WF*qgRgGI~2$ zO3>Uz+J_yGd?^Ec>=?E{&EZF}>%Z^H2Yvz;ncLbX_7?NCSCq*)!cbzcW#LRUEu$J} z&q*c17tPHy{R{M;nH3A23cdG)Cf{DhwqA=(z3kDLc@T1c-=W`0nl0o4KgFK?Rh8vk zyS%w$zVQ_s!@%9q! zVJwz8cx?W&!Bz5(&C2L@Wm#yJ%O%*k%NYCfTAKa)#Ic+3ze4e?c#qsxt|@l3_EhL? zLhrP!`=!{~2I}nK=`CdZpC1f^l`!vx?j&sNoAAAo^nS16Z<8E@9$-$%Bt& zzvcq5t#RZXkB5#@bRKLxG@Xe4(C_!}0j?*6rug5;koj`b7lfXCXCC}cjYHDhD5>*oBJD#4 zjfK48oiPpM99n&(+mt=X1#6MR-&_p2KveR~gYBgknm(iHrxMeCN?$AR)AzTm2fi+I zU-k;3o2dt;h~D?Y_mhcus_3B=1R^yS--^Lg`PMI8gnr`T4*`X24vKw z-@$P^a*sf#bA3DOK)W#(eOLsojjl{YH*%~$_THw{)n;6!NtaU_#LStKzkp0PW8daO zKaY$Hq(9=hD;5i%3hmdR{T^}}i7$Qwx_D8sJ@8xPoMv7i zm2}nqNMn(`%8$J5y(nV%QrO!^knsw};KeliWo8oE^xbxCubzRv@4}w{$lH3_(ZLwE$p8emo3oGGUnH!4@*T(e6K;* zCP@GAB|f0ozRf&q3vB`XfxzYH=Z&g77fif`ZP7GszP;R+>ASutMKfkJ9BAufq}!Q) ztW&Ik_#*hkvpTZIMDJK5|EIfi!2ok@Q-RnB_{NEkSnho{avoTjOg;N}^A9pFgs!x< ztZ83|{`-u{SZG`ef6n+CZJb8~1o^52SWdL10o zp}Ur}BNPtpUCjBvq}JP<@eFc!uuLDDn=@`L_pJ%*wERVK)urC|M55_1)`AzS_UeCqv_+b~5h!Km=4-RgJ3Gie^K7tEl+@_eJ6)glK(Zcs?>tLLK*q z?7ZUh=G{7E+;TVLE%eqLEN?gTHXp3!?w5Oe8!YebjXJwi&D&(aytfl?g(1oZ`{Zr@ z3G?_}d&$~1i*;4x?RM^^aKx&v?OlJgc0oEMDv`4jOi;;eV;#MfhQ za!qq{-Eh(+;9SmG!kFfk(C~O1|5L@nY~MJ|-c)++&KehkRmZehm)$jKVNZMD1pM-M zSR=PNbymaYF9$|5RO!G>$sQd{FM&OcZ0{z&8r(OrR(_9lOUDdkFSi|^hW(@K*OvtU z`poUa!Sk}ShHvG3W^Px`e-8f3ZwlGkA0qp!%RZj=IoMyc)sE@sXAA|u;+xBhtgSQf zEgqgZGyJ7esfHL}YsJH(`6hm81!nl@rtC$Y*OM)w(?uu1PMkyS2RGvXyo6u= z3S;mvbKvl&{hFMe+>nA_Z1H?$oageNH$7UJ>fAtG;dV-?t60qg2yJajX@7jXeI$~(G4435~B z@aOGLd~5cZu`+h!u|jU*Xx<+{zLPnhs@kU-?A6$#O6*d2B0fpXT%8Si`yDv%mA{=& zsr|G0m3V?UxfQwu-I?pe59;8h1^u!2tx0ojhW&nZzlF@i&!gM2e-gRMK4L9;BYO(3 zoGbG9dVhnrq^iSyN8a@wp}K$d?uG5CP+yOapCsmGnTz~>-yU)Xs`eO3vksZ-d8_x} zf0m}zU3JFCe-2%5W*;QydKEZ_c$dA>FL-neqi^FwI!5jRI6zkI36dsfx@vBUUtZ+d zK+OJ9bmc1KE&4KvN94|#L8K&mN5N1?9=hxd}S55^(-*X z7)VA{G{ru)f@v#p^KmULkuPR=kh@>mnWQ;O*B9SFVmgX1#)5r)lioY&IugHe@X0yF zvhLQ2XT!^U>`x1rck)P#uRt8_M#{%f=Upjtp0%81ob|SfRI2e% z?4iV(iLIH-L&WoRooF;V3?BYU`6ki{nM`PSsnjRD-b#IS=0(amOr$*)n|4;JC45}6 zC4AzW*~u4ZJmM=L|Cz)d>PU;8@(;+%eSu9qZMCBJPsn%`+v{ZScs==URW}C@dE*_Y%POuHZm_9@W^TeunrOSf5hgI7dk)8&7lM1y56^=dey?UKHqK%d>N)+^lGq zWvXR6V9I(XdVg70cH+5Rxw`*E=C8oF=$cbMFsF>GGS|dhvwa2gIk2urzfZJl5bsT? zbFOuiFH0mE4kPA-?u5S&&Yd=Xb345M9evv2iiMhan4Uq zrI(tNeV*sq*2U?Di@{JCKT+{wV#vG6Q+2&U&i}PC;>w(|E!Z6HB0LFhiE*Rb=5}yD z%KLNVSBw0$$y)Nbf3Ffwk+&D>X6-RBcV?4Qj%R)ngOs>$uupWEICvBO|IBJ!_Pgts zR_T``e|TmLDq@9R+9KOovFV3f*7RYrhZ3IwEN>(0FV2`ze;|JJmt`H(ZN#225909l zjKsR7Jkio{rWGgd&bq4nJTtHsV8w%_*-7m9gG3A3FA! z4g8y?KR{ZO<~~ge_CsMwM1G6kaJ8-{ctrl4ROgC1-w=K<^wj2G267r(kgvyM6J?sw$7w9$BU zs@APk^jhZMPr&kbu;h7&kw?aWS?vL(u3!i6Qs(nqbbl-|&M-cr?|rIV%JAtZe?A!t zpVy=A5ZL|>c4RTOe6CgUXtV%~3XA+fDWXs!Y-?+;2KVor9zIV3G4xIrDr} z@?eprUeSx9WH1_>S&eU6_4>K8qG#Bd2x7PHTMWRP=mkv$jTxjvZ8=Qs}8uIrN}gK7bFq78d+}E=fJkFj6AK#3OOHk_P}kt zi{Gi%DA`ZyzEnzw8F+xN<@6=K#D-@xQ`ElE!L$pEe+9GI!(Eor-1>cc)cLYr(_}yC zKaRTgK0iP40({Rf?|S`R-kAv;rDJ)OHt z<_*aARfR8ZUSICZ<^sEUJac9yo|r!+JsyMC;Kf|#^PTa<79sf?z+x) z<8+B%l<8FGY`TI^?(aDBbEacA_poDAv~h$i^}v6x$e*WE?jniaORuy!1%Ce`ys_?O zGc)QBbk5(r^2dI=;~_Dh&5VV*<7o3~$oTAF&xsDzUI%YaV`E?L^vttL4glt0)8%6C zWi5?F@NeX9sbwZ*o+>*8Cf*+tjP}F*os`_^F~RM|A>`ZJ#D`AU*lvt+Vmq6NTEAqUuoWI^ncpEjcJN_nd^&Yuds!gQ+B!n%FnbmDBt2l`Oy6uq zAC@MX8@`2%nZqW&D0jgu?2OnO84u2%R2hCB>2}t{(LLEo$BP|ACuY3Aux>bM6VKbs zOUm4FP~#)G;fFi3+##0pIdyKU>lkmynXbk@XbOH=_rWJ;VlPR|0lm0{_gBI6tlVRe zc#y2u)Z35w@N=+t@_lu2y}XAv_Ln+QKo$ea*))4-iN(l{EO zGz?x>%Q>jLdw=gO@*fCh*{g`HTq&_m+YeIvUA-=q@rn*Pu~Lm4zWSK&XM6h{DsTHj zW&zBrd1P;{_J;7&5ubklA=0+Fx&CO*Cnke=Bx7 zvF0ithxysbJ#xz{XK!BcQuitJ%)7VQ$((M{cq;^_3#(F*aXKA6U-mEd{djYU+%rUP z&XYSvQk{8wHkfz86ZcY--F%BN5Z_heUArWXA@Pfj%!DJs^`R|GqbU9Z`AWIxj7_Ys z+yOL}_po=z_SmsQd!PA`^ic(Iw_j!7^&ofEsvD?ygk`=1<~7_Y;oQ9O&_q0Rva-8! zhk$sUv=Lw3gBPFQ;65w!Hy2<}Y%qU~g~d$ZSniL0kyzEiow>k;)R#4_7hY$$|8Jlg z0Ppr#RER@K zsj#M*ufK+Dk+E&d9Uj#BYU|JzIY2ZZry(Dv_8{2W=^#K%$g2mcM3H%d%Yd=SP*_GXG`i5S-! zOU}8tM^x5#C4X$p2l%67-_88bzAlx2EL6AK!7}!qARJC4rkycZ9Vsud4=Uy+o{v8& z_s?U<{mzZ<|2-J0<-p%Q7MtG6-u%E_tJ2-9M%~@1xjS_}C76#SF<6EE<^4;B!1m8i L|CGQdl)(Q1=R@ji literal 0 HcmV?d00001 diff --git a/docs/conf.py b/docs/conf.py index d103c26d3..f0043fc03 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -36,6 +36,7 @@ "sphinx.ext.intersphinx", "autoapi.extension", "myst_parser", + "sphinx_favicon", ] myst_enable_extensions = [ @@ -83,3 +84,22 @@ # so a file named "default.css" will overwrite the builtin "default.css". html_static_path = ["_static"] html_extra_path = ["rosdoc"] +html_logo = "images/arc_logo.svg" + +favicons = [ + {"href": "favicons/favicon.ico"}, + {"href": "favicons/favicon-16x16.png"}, + {"href": "favicons/favicon-32x32.png"}, + { + "rel": "apple-touch-icon", + "href": "favicons/apple-touch-icon.png", + }, + { + "rel": "android-chrome", + "href": "favicons/android-chrome-192x192.png", + }, + { + "rel": "android-chrome", + "href": "favicons/android-chrome-512-512.png", + }, +] diff --git a/docs/images/arc_logo.svg b/docs/images/arc_logo.svg new file mode 100644 index 000000000..716311d9d --- /dev/null +++ b/docs/images/arc_logo.svg @@ -0,0 +1,79 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/docs/index.md b/docs/index.md index 190a66cf3..403f0391c 100644 --- a/docs/index.md +++ b/docs/index.md @@ -1,9 +1,6 @@ ```{include} ../README.md ``` -```{note} -This project is under active development. -``` ```{toctree} :caption: Contents diff --git a/docs/requirements.in b/docs/requirements.in index 191a04b17..22bd1bc5e 100644 --- a/docs/requirements.in +++ b/docs/requirements.in @@ -2,3 +2,4 @@ Sphinx>=5,<6 sphinx_rtd_theme myst_parser sphinx-autoapi +sphinx-favicon diff --git a/docs/requirements.txt b/docs/requirements.txt index ae42f58ba..00a06d654 100644 --- a/docs/requirements.txt +++ b/docs/requirements.txt @@ -2,28 +2,28 @@ # This file is autogenerated by pip-compile with Python 3.8 # by the following command: # -# pip-compile requirements.in +# pip-compile --output-file==requirements.txt --resolver=backtracking requirements.in # -alabaster==0.7.12 +alabaster==0.7.13 # via sphinx -astroid==2.15.1 +astroid==2.15.3 # via sphinx-autoapi -babel==2.10.3 +babel==2.12.1 # via sphinx -certifi==2022.6.15 +certifi==2022.12.7 # via requests -charset-normalizer==2.1.0 +charset-normalizer==3.1.0 # via requests -docutils==0.17.1 +docutils==0.18.1 # via # myst-parser # sphinx # sphinx-rtd-theme -idna==3.3 +idna==3.4 # via requests imagesize==1.4.1 # via sphinx -importlib-metadata==6.1.0 +importlib-metadata==6.6.0 # via sphinx jinja2==3.1.2 # via @@ -36,7 +36,7 @@ markdown-it-py==2.2.0 # via # mdit-py-plugins # myst-parser -markupsafe==2.1.1 +markupsafe==2.1.2 # via jinja2 mdit-py-plugins==0.3.5 # via myst-parser @@ -44,38 +44,42 @@ mdurl==0.1.2 # via markdown-it-py myst-parser==1.0.0 # via -r requirements.in -packaging==21.3 +packaging==23.1 # via sphinx -pygments==2.12.0 +pygments==2.15.1 # via sphinx -pyparsing==3.0.9 - # via packaging -pytz==2022.1 +pytz==2023.3 # via babel pyyaml==6.0 # via # myst-parser # sphinx-autoapi -requests==2.28.1 +requests==2.28.2 # via sphinx snowballstemmer==2.2.0 # via sphinx -sphinx==5.0.2 +sphinx==5.3.0 # via # -r requirements.in # myst-parser # sphinx-autoapi + # sphinx-favicon # sphinx-rtd-theme -sphinx-autoapi==2.0.1 + # sphinxcontrib-jquery +sphinx-autoapi==2.1.0 # via -r requirements.in -sphinx-rtd-theme==1.0.0 +sphinx-favicon==1.0.1 # via -r requirements.in -sphinxcontrib-applehelp==1.0.2 +sphinx-rtd-theme==1.2.0 + # via -r requirements.in +sphinxcontrib-applehelp==1.0.4 # via sphinx sphinxcontrib-devhelp==1.0.2 # via sphinx -sphinxcontrib-htmlhelp==2.0.0 +sphinxcontrib-htmlhelp==2.0.1 # via sphinx +sphinxcontrib-jquery==4.1 + # via sphinx-rtd-theme sphinxcontrib-jsmath==1.0.1 # via sphinx sphinxcontrib-qthelp==1.0.3 @@ -86,7 +90,7 @@ typing-extensions==4.5.0 # via astroid unidecode==1.3.6 # via sphinx-autoapi -urllib3==1.26.9 +urllib3==1.26.15 # via requests wrapt==1.15.0 # via astroid From 2bc90cd9934972c570d64de6651adb48d9315802 Mon Sep 17 00:00:00 2001 From: Daniel Gerblick Date: Sun, 23 Apr 2023 07:50:35 +0000 Subject: [PATCH 5/5] Fixed auto-generated contents on pages --- docs/templates/launch_README.md | 4 ++-- docs/templates/nodes_README.md | 4 ++-- rktl_autonomy/launch/README.md | 4 ++-- rktl_autonomy/nodes/README.md | 4 ++-- rktl_autonomy/scripts/README.md | 4 ++-- rktl_control/firmware/README.md | 4 ++-- rktl_control/launch/README.md | 4 ++-- rktl_control/nodes/README.md | 16 ++++++++-------- rktl_game/nodes/README.md | 4 ++-- rktl_launch/launch/README.md | 4 ++-- rktl_perception/launch/README.md | 4 ++-- rktl_perception/nodes/README.md | 4 ++-- rktl_planner/launch/README.md | 4 ++-- rktl_planner/nodes/README.md | 4 ++-- rktl_sim/launch/README.md | 4 ++-- rktl_sim/nodes/README.md | 4 ++-- 16 files changed, 38 insertions(+), 38 deletions(-) diff --git a/docs/templates/launch_README.md b/docs/templates/launch_README.md index 834a140a5..91d2eb172 100644 --- a/docs/templates/launch_README.md +++ b/docs/templates/launch_README.md @@ -7,11 +7,11 @@ using [roslaunch](https://wiki.ros.org/roslaunch): roslaunch ``` -:::{contents} Launch Files in the package +```{contents} Launch Files in the package :depth: 2 :backlinks: top :local: true -::: +``` --- diff --git a/docs/templates/nodes_README.md b/docs/templates/nodes_README.md index 32fff24b8..b872826c8 100644 --- a/docs/templates/nodes_README.md +++ b/docs/templates/nodes_README.md @@ -8,11 +8,11 @@ by using `rosrun`: rosrun ``` -:::{contents} ROS Nodes in this package +```{contents} ROS Nodes in this package :depth: 2 :backlinks: top :local: true -::: +``` --- diff --git a/rktl_autonomy/launch/README.md b/rktl_autonomy/launch/README.md index 4d7f67601..802c1e97e 100644 --- a/rktl_autonomy/launch/README.md +++ b/rktl_autonomy/launch/README.md @@ -7,11 +7,11 @@ using [roslaunch](https://wiki.ros.org/roslaunch): roslaunch rktl_autonomy ``` -:::{contents} Launch Files in the package +```{contents} Launch Files in the package :depth: 2 :backlinks: top :local: true -::: +``` --- diff --git a/rktl_autonomy/nodes/README.md b/rktl_autonomy/nodes/README.md index 213609305..02b1a911a 100644 --- a/rktl_autonomy/nodes/README.md +++ b/rktl_autonomy/nodes/README.md @@ -8,11 +8,11 @@ by using `rosrun`: rosrun rktl_autonomy ``` -:::{contents} ROS Nodes in the package +```{contents} ROS Nodes in the package :depth: 2 :backlinks: top :local: true -::: +``` --- diff --git a/rktl_autonomy/scripts/README.md b/rktl_autonomy/scripts/README.md index 5e401602d..d2b567385 100644 --- a/rktl_autonomy/scripts/README.md +++ b/rktl_autonomy/scripts/README.md @@ -12,11 +12,11 @@ several different types of agents. **You should not manually use any ROS commands when launching for training.** -:::{contents} Training scripts in the package +```{contents} Training scripts in the package :depth: 2 :backlinks: top :local: true -::: +``` --- diff --git a/rktl_control/firmware/README.md b/rktl_control/firmware/README.md index 2f67a474f..32b01ece2 100644 --- a/rktl_control/firmware/README.md +++ b/rktl_control/firmware/README.md @@ -3,11 +3,11 @@ This folder contains all firmware that is written to microcontollers for the project. -:::{contents} Firmwares in the package +```{contents} Firmwares in the package :depth: 2 :backlinks: top :local: true -::: +``` --- diff --git a/rktl_control/launch/README.md b/rktl_control/launch/README.md index fc706350c..cb99d4d48 100644 --- a/rktl_control/launch/README.md +++ b/rktl_control/launch/README.md @@ -7,11 +7,11 @@ using [roslaunch](https://wiki.ros.org/roslaunch): roslaunch rktl_control ``` -:::{contents} Launch Files in the package +```{contents} Launch Files in the package :depth: 2 :backlinks: top :local: true -::: +``` --- diff --git a/rktl_control/nodes/README.md b/rktl_control/nodes/README.md index 1ae03598b..351ca7d34 100644 --- a/rktl_control/nodes/README.md +++ b/rktl_control/nodes/README.md @@ -8,11 +8,11 @@ by using `rosrun`: rosrun rktl_control ``` -:::{contents} ROS Nodes in the package +```{contents} ROS Nodes in the package :depth: 2 :backlinks: top :local: true -::: +``` --- @@ -151,8 +151,8 @@ Overall, this filter is simple and works well enough for position as long as sli - `~frame_ids/map` (string, default: `'map'`): Frame ID of the common reference frame for all objects. In the context of the project, this is the frame - centered on the middle of the field, with the x-axis pointed towards a goal, - the y-axis pointing towards a sideline, and the z-axis pointed up. By + centered on the middle of the field, with the $x$-axis pointed towards a goal, + the $y$-axis pointing towards a sideline, and the $z$-axis pointed up. By convention, this should be called `'map'`. - `~frame_ids/body` (string, default: `'base_link'`): Frame ID of the object being tracked. @@ -259,8 +259,8 @@ is a good resource on particle filters for more information. second. - `~frame_ids/map` (string, default: `'map'`): Frame ID of the common reference frame for all objects. In the context of the project, this is the frame - centered on the middle of the field, with the x-axis pointed towards a goal, - the y-axis pointing towards a sideline, and the z-axis pointed up. By + centered on the middle of the field, with the $x$-axis pointed towards a goal, + the $y$-axis pointing towards a sideline, and the $z$-axis pointed up. By convention, this should be called `'map'`. - `~frame_ids/body` (string, default: `'base_link'`): Frame ID of the object being tracked. @@ -325,8 +325,8 @@ is the original name of the topic with `_sync` appended to the end. - `~map_frame` (string, default: `'map'`): Frame ID of the common reference frame for all objects. In the context of the project, this is the frame - centered on the middle of the field, with the x-axis pointed towards a goal, - the y-axis pointing towards a sideline, and the z-axis pointed up. By + centered on the middle of the field, with the $x$-axis pointed towards a goal, + the $y$-axis pointing towards a sideline, and the $z$-axis pointed up. By convention, this should be called `'map'`. - `~topics` (array): Array of topic names to synchronize. - `~rate` (float, default: `10.0`): Rate at which the synchronized topics are diff --git a/rktl_game/nodes/README.md b/rktl_game/nodes/README.md index 3392fe695..f9e6e2c1c 100644 --- a/rktl_game/nodes/README.md +++ b/rktl_game/nodes/README.md @@ -8,11 +8,11 @@ by using `rosrun`: rosrun rktl_autonomy ``` -:::{contents} ROS Nodes in the package +```{contents} ROS Nodes in the package :depth: 2 :backlinks: top :local: true -::: +``` --- diff --git a/rktl_launch/launch/README.md b/rktl_launch/launch/README.md index 3b5a848c1..c796ee155 100644 --- a/rktl_launch/launch/README.md +++ b/rktl_launch/launch/README.md @@ -7,11 +7,11 @@ using [roslaunch](https://wiki.ros.org/roslaunch): roslaunch rktl_launch ``` -:::{contents} Launch Files in the package +```{contents} Launch Files in the package :depth: 2 :backlinks: top :local: true -::: +``` --- diff --git a/rktl_perception/launch/README.md b/rktl_perception/launch/README.md index 051fe320b..9f3f3f8ac 100644 --- a/rktl_perception/launch/README.md +++ b/rktl_perception/launch/README.md @@ -7,11 +7,11 @@ using [roslaunch](https://wiki.ros.org/roslaunch): roslaunch rktl_perception ``` -:::{contents} Launch Files in this package +```{contents} Launch Files in this package :depth: 2 :backlinks: top :local: true -::: +``` --- diff --git a/rktl_perception/nodes/README.md b/rktl_perception/nodes/README.md index 9a91dbc02..eb86e76fe 100644 --- a/rktl_perception/nodes/README.md +++ b/rktl_perception/nodes/README.md @@ -8,11 +8,11 @@ by using `rosrun`: rosrun rktl_perception ``` -:::{contents} ROS Nodes in this package +```{contents} ROS Nodes in this package :depth: 2 :backlinks: top :local: true -::: +``` --- diff --git a/rktl_planner/launch/README.md b/rktl_planner/launch/README.md index 3de9ebf5a..e4cbc92c6 100644 --- a/rktl_planner/launch/README.md +++ b/rktl_planner/launch/README.md @@ -7,11 +7,11 @@ using [roslaunch](https://wiki.ros.org/roslaunch): roslaunch rktl_planner ``` -:::{contents} Launch Files in the package +```{contents} Launch Files in the package :depth: 2 :backlinks: top :local: true -::: +``` --- diff --git a/rktl_planner/nodes/README.md b/rktl_planner/nodes/README.md index 52a4efff8..7b68e59fe 100644 --- a/rktl_planner/nodes/README.md +++ b/rktl_planner/nodes/README.md @@ -8,11 +8,11 @@ by using `rosrun`: rosrun rktl_planner ``` -:::{contents} ROS Nodes in the package +```{contents} ROS Nodes in the package :depth: 2 :backlinks: top :local: true -::: +``` --- diff --git a/rktl_sim/launch/README.md b/rktl_sim/launch/README.md index 4b11e8938..a1c2453a3 100644 --- a/rktl_sim/launch/README.md +++ b/rktl_sim/launch/README.md @@ -7,11 +7,11 @@ using [roslaunch](https://wiki.ros.org/roslaunch): roslaunch rktl_sim ``` -:::{contents} Launch Files in the package +```{contents} Launch Files in the package :depth: 2 :backlinks: top :local: true -::: +``` --- diff --git a/rktl_sim/nodes/README.md b/rktl_sim/nodes/README.md index 5b88610a6..f2c7358c3 100644 --- a/rktl_sim/nodes/README.md +++ b/rktl_sim/nodes/README.md @@ -8,11 +8,11 @@ by using `rosrun`: rosrun rktl_sim ``` -:::{contents} ROS Nodes in the package +```{contents} ROS Nodes in the package :depth: 2 :backlinks: top :local: true -::: +``` ---