From 104df38ceaef5079ebadd53cdb9abe03f8fc81de Mon Sep 17 00:00:00 2001 From: Geoffrey Biggs Date: Wed, 1 Aug 2018 11:31:49 +0900 Subject: [PATCH 01/71] Add original proposal --- articles/actions.md | 96 +++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 96 insertions(+) create mode 100644 articles/actions.md diff --git a/articles/actions.md b/articles/actions.md new file mode 100644 index 000000000..5379577a5 --- /dev/null +++ b/articles/actions.md @@ -0,0 +1,96 @@ +--- +layout: default +title: Actions +permalink: articles/actions.html +abstract: + Despite their implementation as a separate library and lack of a detailed specification, actions are one of the three core types of interaction between ROS nodes. Their asynchronous nature combined with the feedback and control mechanism gives them significantly more power than a standard RPC. This article formalises the requirements for actions, including what a ROS user should see and what the middleware layer should provide. +author: '[Geoffrey Biggs](https://github.com/gbiggs)' +published: true +--- + +{:toc} + +# {{ page.title }} + +
+{{ page.abstract }} +
+ +Original Author: {{ page.author }} + +## Background + +ROS services, which provide synchronous Remote Procedure Calls, are a useful concept for sending a request and getting a rapid reply. But in robotics there are many instances where a reply may take a significant length of time. Additionally, there are occasions when it is useful to send a request to do some processing or perform some action in the world, where the result is less important than the effect of carrying it out. The progress of such requests often needs to be tracked, success or failure must be known in addition to receiving back information produced, and the request may need to be cancelled or altered before it completes. These requirements cannot be fulfilled by a simple RPC mechanism, whether or not it is asynchronous. + +To satisfy these use cases, ROS provides a third communication paradigm known as "actions". An action is a goal-oriented request that occurs asynchronously to the requester, is typically (but not necessarily) longer-running than immediate, can be cancelled or replaced during execution, and has a server that provides feedback on execution progress. + +This document defines how actions are specified, what they look like to ROS users (both node developers and system integrators) + +## Action specification + +Actions are specified using a form of the ROS Message IDL. The specification contains three sections, each of which is a message specification: + +1. Goal + +1. Result + +1. Feedback + +Any of these sections may be empty. + +Between the three sections is a line containing three hyphens, `---`. + +Action specifications are stored in a file ending in `.action`. There is one action specification per `.action` file. + +An example action specification [taken from the actionlib wiki] is shown below. + +``` +# Define the goal +uint32 dishwasher_id # Specify which dishwasher we want to use +--- +# Define the result +uint32 total_dishes_cleaned +--- +# Define a feedback message +float32 percent_complete +uint32 number_dishes_cleaned +``` + +## Serving and using actions + +Actions are a first-class citizen in the ROS API, alongside topics and services. + +Action clients will use an API that provides a proxy object for the action. This will be a templated class, using the action class generated from the action specification as the template parameter. The client shall create an instance of this class, providing the address of the intended action server. Each instance of this class can only be related to one action server. Methods of the class will provide facilities for sending a goal to the action server, receiving a result, and getting feedback. + +Action servers will use an API that provides a templated server class, using the action class generated from the action specification as the template parameter. The node implementer will create a function that implements the action's behaviour, create an instance of the templated server class, and bind the implementing function to the server. The implementing function will receive as one of its parameters the received goal message, and as another parameter the action server instance. The implementation shall use the action server instance to provide progress feedback and to report the result and success/failure/error status of the action's execution. + +Actions may be used from or served by real-time nodes. Therefore the actions API must be real-time capable. + +## Introspection tools + +Actions, like topics and services, are introspectable from the command line. + +In ROS 1, actions are visible in the output of the `rostopic` tool. + +In ROS 2, actions will not be visible as a set of topics. Nor will they be visible as a set of services [in the case that services be used to implement them]. They will be visible using a separate `ros2 action` command line tool. + +The command line tool will be similar to the `ros2 service` tool. It will be able to: + +- list known actions, +- display the arguments for an action's goal, +- display the type of an action's feedback and result, +- display information about the server of an action, +- display the underlying topics and/or services providing the action, +- find actions by action type, and +- call an action, display feedback as it is received, display the result when received, and cancel the action (when the tool is terminated prematurely) + +Each action, despite using multiple topics and/or services in its implementation, will be listed and treated as a single unit by this tool. [This will probably be a namespace that contains the underlying topics, etc.] + +## Middleware implementation + +In ROS 1, actions are implemented using a set of topics under a namespace taken from the action name. This implementation was chosen because ROS services are inherently synchronous, and so incompatible with the asynchronous nature of the action concept. There is also a need for a status/feedback channel and a control channel. + +The Remote Procedure Call over DDS (DDS-RPC) specification does not explicitly provide facilities for interrupting service calls or receiving feedback on their progress. It does provide for receiving both a return value from a request and, at the same time, an indication of whether the request was successful or raised an exception, with the exception type included in this information. + +This means that an implementation of actions cannot simply be a DDS-style RPC. The implementation must separately provide status/feedback and control channels. While a control channel could be implemented as a separate RPC, due to the dataflow nature of feedback it would be best implemented as a separate topic. + From cc4834186a192e9c08744ea33756624953810ade Mon Sep 17 00:00:00 2001 From: Geoffrey Biggs Date: Wed, 1 Aug 2018 12:03:53 +0900 Subject: [PATCH 02/71] Reformat and revise some of the information --- articles/actions.md | 136 ++++++++++++++++++++++++++++++++++++-------- 1 file changed, 113 insertions(+), 23 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 5379577a5..110ac38f4 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -3,7 +3,9 @@ layout: default title: Actions permalink: articles/actions.html abstract: - Despite their implementation as a separate library and lack of a detailed specification, actions are one of the three core types of interaction between ROS nodes. Their asynchronous nature combined with the feedback and control mechanism gives them significantly more power than a standard RPC. This article formalises the requirements for actions, including what a ROS user should see and what the middleware layer should provide. + Despite their implementation as a separate library and lack of a detailed specification, actions are one of the three core types of interaction between ROS nodes. + Their asynchronous nature combined with the feedback and control mechanism gives them significantly more power than a remote procedure call. + This article specifies the requirements for actions, including what a ROS user should see, what the middleware layer should provide, and how actions are communicated. author: '[Geoffrey Biggs](https://github.com/gbiggs)' published: true --- @@ -20,77 +22,165 @@ Original Author: {{ page.author }} ## Background -ROS services, which provide synchronous Remote Procedure Calls, are a useful concept for sending a request and getting a rapid reply. But in robotics there are many instances where a reply may take a significant length of time. Additionally, there are occasions when it is useful to send a request to do some processing or perform some action in the world, where the result is less important than the effect of carrying it out. The progress of such requests often needs to be tracked, success or failure must be known in addition to receiving back information produced, and the request may need to be cancelled or altered before it completes. These requirements cannot be fulfilled by a simple RPC mechanism, whether or not it is asynchronous. +ROS services, which provide synchronous Remote Procedure Calls, are a useful concept for sending a request and getting a rapid reply. +But in robotics there are many instances where a reply may take a significant length of time. +Additionally, there are occasions when it is useful to send a request to do some processing or perform some action in the world, where the result is less important than the effect of carrying it out. +The progress of such requests often needs to be tracked, success or failure must be known in addition to receiving back information produced, and the request may need to be cancelled or altered before it completes. +These requirements cannot be fulfilled by a simple RPC mechanism, whether or not it is asynchronous. -To satisfy these use cases, ROS provides a third communication paradigm known as "actions". An action is a goal-oriented request that occurs asynchronously to the requester, is typically (but not necessarily) longer-running than immediate, can be cancelled or replaced during execution, and has a server that provides feedback on execution progress. +To satisfy these use cases, ROS provides a third communication paradigm known as "actions". +An action is a goal-oriented request that occurs asynchronously to the requester, is typically (but not necessarily) longer-running than immediate, can be cancelled or replaced during execution, and has a server that provides feedback on execution progress. + +This document defines how actions are specified in the ROS Message IDL, how they will be created and used by ROS users (node developers and system integrators), and how they will be communicated by the middleware. + + +## Entities involved in actions + +The following entities are involved in providing, using and executing an action. + +- Action server + + The provider of the action. + There is only one server for any unique action. + The action server is responsible for: + + - advertising the action to other ROS entities; + + - for executing the action when a request is received, or rejecting that request, as appropriate; + + - for monitoring execution of the action and providing feedback as appropriate to the action design; + + - for sending the result of the action, including a mandatory success/failure value, to the client when the action completes, whether the action succeeded or not; and + + - for managing the execution of the action in response to additional requests by the client. + +- Action client + + The entity making a request to execute an action. + There may be more than one client for each action server. + However, the semantics of multiple simultaneous clients is action-specific, i.e. it depends on what the action is and how it is implemented whether multiple simultaneous clients can be supported. + The action client is responsible for: + + - making a request to the action, passing any needed data for the action execution; + + - optionally periodically checking for updated feedback from the action server; + + - optionally requesting that the action server cancel the action execution; and + + - optionally checking the result of the action received from the action server. -This document defines how actions are specified, what they look like to ROS users (both node developers and system integrators) ## Action specification -Actions are specified using a form of the ROS Message IDL. The specification contains three sections, each of which is a message specification: +Actions are specified using a form of the ROS Message IDL. +The specification contains three sections, each of which is a message specification: 1. Goal + The "request" part of the action. + Contains the data passed to the server of the action from the client, along with the request to begin executing that action. + 1. Result + The final result part of the action. + Contains the data passed to the client of the action from the action server once the action execution ends, whether successfully or not. + This data is produced by the action server as appropriate to that action's implementation, and is used by the client to understand how the action turned out. + 1. Feedback + Contains data passed to the client of the action from the action server between commencing action execution and prior to the action completing. + This data is used by the client to understand the progress of executing the action. + Any of these sections may be empty. -Between the three sections is a line containing three hyphens, `---`. +Between each of the three sections is a line containing three hyphens, `---`. -Action specifications are stored in a file ending in `.action`. There is one action specification per `.action` file. +Action specifications are stored in a file ending in `.action`. +There is one action specification per `.action` file. -An example action specification [taken from the actionlib wiki] is shown below. +An example action specification is shown below. ``` # Define the goal uint32 dishwasher_id # Specify which dishwasher we want to use --- -# Define the result +# Define the result that will be published after the action execution ends. uint32 total_dishes_cleaned --- -# Define a feedback message +# Define a feedback message that will be published during action execution. float32 percent_complete uint32 number_dishes_cleaned -``` -## Serving and using actions + +## API Actions are a first-class citizen in the ROS API, alongside topics and services. +Action servers and clients are created using the node interface. + +### API for action servers -Action clients will use an API that provides a proxy object for the action. This will be a templated class, using the action class generated from the action specification as the template parameter. The client shall create an instance of this class, providing the address of the intended action server. Each instance of this class can only be related to one action server. Methods of the class will provide facilities for sending a goal to the action server, receiving a result, and getting feedback. +### API for action clients -Action servers will use an API that provides a templated server class, using the action class generated from the action specification as the template parameter. The node implementer will create a function that implements the action's behaviour, create an instance of the templated server class, and bind the implementing function to the server. The implementing function will receive as one of its parameters the received goal message, and as another parameter the action server instance. The implementation shall use the action server instance to provide progress feedback and to report the result and success/failure/error status of the action's execution. +### Real-time actions + +Actions may be used from or served by real-time nodes. +The action server and action client APIs should be real-time capable. -Actions may be used from or served by real-time nodes. Therefore the actions API must be real-time capable. ## Introspection tools Actions, like topics and services, are introspectable from the command line. -In ROS 1, actions are visible in the output of the `rostopic` tool. +In ROS 1, actions are visible in the output of the `rostopic` tool. -In ROS 2, actions will not be visible as a set of topics. Nor will they be visible as a set of services [in the case that services be used to implement them]. They will be visible using a separate `ros2 action` command line tool. +In ROS 2, actions will not be visible as a set of topics nor a set of services. +They will be visible using a separate `ros2 action` command line tool. -The command line tool will be similar to the `ros2 service` tool. It will be able to: +The command line tool will be similar to the `ros2 service` tool. +It will be able to: - list known actions, + - display the arguments for an action's goal, + - display the type of an action's feedback and result, + - display information about the server of an action, + - display the underlying topics and/or services providing the action, + - find actions by action type, and -- call an action, display feedback as it is received, display the result when received, and cancel the action (when the tool is terminated prematurely) -Each action, despite using multiple topics and/or services in its implementation, will be listed and treated as a single unit by this tool. [This will probably be a namespace that contains the underlying topics, etc.] +- call an action, display feedback as it is received, display the result when received, and cancel the action (when the tool is terminated prematurely). + +Each action will be listed and treated as a single unit by this tool. +This is irrespective of the implementation, which may use several topics or services to provide a single action. + ## Middleware implementation -In ROS 1, actions are implemented using a set of topics under a namespace taken from the action name. This implementation was chosen because ROS services are inherently synchronous, and so incompatible with the asynchronous nature of the action concept. There is also a need for a status/feedback channel and a control channel. +In ROS 1, actions are implemented using a set of topics under a namespace taken from the action name. +This implementation was chosen because ROS services are inherently synchronous, and so incompatible with the asynchronous nature of the action concept. +There is also a need for a status/feedback channel and a control channel. + +The Remote Procedure Call over DDS (DDS-RPC) specification does not explicitly provide facilities for interrupting service calls or receiving feedback on their progress. +It does provide for receiving both a return value from a request and, at the same time, an indication of whether the request was successful or raised an exception, with the exception type included in this information. + +This means that an implementation of actions cannot simply be a DDS-style RPC. +The implementation must separately provide status/feedback and control channels. + +An asynchronous service is used to provide the initial action request channel and the final result. +The action server shall create a server for this service upon construction. +The action client shall create a client for this service upon construction. + +A topic is used to provide the feedback channel. +The action server shall publish this topic upon construction. +The action client shall subscribe to this topic upon construction. -The Remote Procedure Call over DDS (DDS-RPC) specification does not explicitly provide facilities for interrupting service calls or receiving feedback on their progress. It does provide for receiving both a return value from a request and, at the same time, an indication of whether the request was successful or raised an exception, with the exception type included in this information. +A topic is used to provide the control channel. +The action server shall publish this topic upon construction. +The action client shall subscribe to this topic upon construction. -This means that an implementation of actions cannot simply be a DDS-style RPC. The implementation must separately provide status/feedback and control channels. While a control channel could be implemented as a separate RPC, due to the dataflow nature of feedback it would be best implemented as a separate topic. +### Topic and service naming +The topic and service used to provide an action are named as follows. From b3edf0a398f1dd6477aba6655dee0c4f98b9598c Mon Sep 17 00:00:00 2001 From: Geoffrey Biggs Date: Wed, 1 Aug 2018 12:05:02 +0900 Subject: [PATCH 03/71] Fix missing close preformat --- articles/actions.md | 1 + 1 file changed, 1 insertion(+) diff --git a/articles/actions.md b/articles/actions.md index 110ac38f4..d3ebb3503 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -110,6 +110,7 @@ uint32 total_dishes_cleaned # Define a feedback message that will be published during action execution. float32 percent_complete uint32 number_dishes_cleaned +``` ## API From 29e0280282ca05cae207aed23955ac55ca61d5bc Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 10 Oct 2018 09:07:32 -0700 Subject: [PATCH 04/71] ROS 2 action server always generates goal id --- articles/actions.md | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/articles/actions.md b/articles/actions.md index d3ebb3503..967e5eab8 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -113,6 +113,15 @@ uint32 number_dishes_cleaned ``` +## Goal Identifiers + +In ROS 1 Action clients are responsible for creating a goal ID when submitting a goal. +This leads to a race condition between goal creation and cancellation. +If a client submits a goal and immediatly tries to cancel it, the cancelation may fail if it is received by the action server prior to the goal being accepted. + +In ROS 2 the action server will be responsible for generating the goal ID and notifying the client. +It won't be possible for the client to cancel the goal until after it has received the goal ID. + ## API Actions are a first-class citizen in the ROS API, alongside topics and services. From cfe4e66798f5f45070bbe5eadae4a57c51209caa Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 10 Oct 2018 09:49:38 -0700 Subject: [PATCH 05/71] Rough description of services and topics --- articles/actions.md | 88 +++++++++++++++++++++++++++++++++++++++------ 1 file changed, 77 insertions(+), 11 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 967e5eab8..1c0291b40 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -179,18 +179,84 @@ It does provide for receiving both a return value from a request and, at the sam This means that an implementation of actions cannot simply be a DDS-style RPC. The implementation must separately provide status/feedback and control channels. -An asynchronous service is used to provide the initial action request channel and the final result. -The action server shall create a server for this service upon construction. -The action client shall create a client for this service upon construction. +### Topics and Services Used -A topic is used to provide the feedback channel. -The action server shall publish this topic upon construction. -The action client shall subscribe to this topic upon construction. +In ROS 1 an action is defined entirely using topics. +In ROS 2 an action is the combination of the following services and topics. -A topic is used to provide the control channel. -The action server shall publish this topic upon construction. -The action client shall subscribe to this topic upon construction. +#### Goal Submission Service -### Topic and service naming +* **Direction**: Client calls Server +* **Request**: Description of goal +* **Response**: Whether goal was accepted or rejected, and a unique identifier for the goal, and time goal was accepted. -The topic and service used to provide an action are named as follows. +The purpose of this service is to submit a goal to the action server. +It is the first service called to begin an action. +A user-define description of the goal is sent as the request. +The response is a standard action message indicating whether or not the goal was accepted, and if so the identifier the server will use to describe the goal. + +#### Cancel Request Service + +* **Direction**: Client calls Server +* **Request**: Goal identifier, time stamp +* **Response**: Goals that will be attempted to be cancelled + +The purpose of this service is to request to cancel one or more goals on the action server. +A cancellation request may cancel multiple goals. +The result indicates which goals will be attempted to be cancelled. +Whether or not a goal is actually cancelled is indicated by the status topic and the result service. + +The cancel request policy is the same as in ROS 1. + +* If the goal ID is empty and time is zero, cancel all goals +* If the goal ID is empty and time is not zero, cancel all goals accepted before the time stamp +* If the goal ID is not empty and time is not zero, cancel the goal with the given id regardless of the time it was accepted +* If the goal ID is not empty and time is zero, cancel the goal with the given id and all goals accepted before the time stamp + +#### Get Result Service + +* **Direction**: Client call Server +* **Request**: Goal ID +* **Response**: Status of goal and user defined result + +The purpose of this service is to get the final result of a service. +After a goal has been accepted the client should call this service to receive the result. +The result will indicate the final status of the goal and any user defined data. + +#### Goal Status Topic + +* **Direction**: Server publishes +* **Content**: Goal id, time it was accepted, and an enum indicating the status of this goal. + +This topic is published by the server to broadcast the status of goals it has accepted. +The purpose of the topic is for introspection; it is not used by the action client. +Messages are published when transitions from one status to another occur. + +The possible statuses are: + +* *Accepted* + * The goal has been accepted by the action server + * Next status *Executing* or *Accepted Cancellation* +* *Executing* + * The action server is attempting to reach the goal + * Next status *Accepted Cancellation*, *Succeeded*, *Aborted* +* *Accepted Cancellation* + * The action server will try to cancel the indicated goal + * Next status *Cancelled*, *Succeeded*, *Aborted* +* Cancelled + * The action server successfully canceled the goal + * No more statuses will be published +* Succeeded + * The action server successfully reached the goal + * No more statuses will be published +* Aborted + * The action server failed reached the goal + * No more statuses will be published + +#### Feedback Topic + +* **Direction**: Server publishes +* **Content**: Goal id, user defined feedback message + +This topic is published by the server to send application specific progress about the goal. +It is up to the author of the action server to decide how often to publish the feedback. From c00f875ebd4d3b4e59afb164b5c4654ec3491f1e Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 10 Oct 2018 10:12:32 -0700 Subject: [PATCH 06/71] ROS 1 cancels goals with stamps less than or equal to given time --- articles/actions.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 1c0291b40..ec3d9eae7 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -209,9 +209,9 @@ Whether or not a goal is actually cancelled is indicated by the status topic and The cancel request policy is the same as in ROS 1. * If the goal ID is empty and time is zero, cancel all goals -* If the goal ID is empty and time is not zero, cancel all goals accepted before the time stamp +* If the goal ID is empty and time is not zero, cancel all goals accepted at or before the time stamp * If the goal ID is not empty and time is not zero, cancel the goal with the given id regardless of the time it was accepted -* If the goal ID is not empty and time is zero, cancel the goal with the given id and all goals accepted before the time stamp +* If the goal ID is not empty and time is zero, cancel the goal with the given id and all goals accepted at or before the time stamp #### Get Result Service From 68320a4137a9d03c070d95971d27e5f3634a0ed7 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 10 Oct 2018 10:44:14 -0700 Subject: [PATCH 07/71] Add API section for action server --- articles/actions.md | 46 +++++++++++++++++++++++++++++++++++++++++++-- 1 file changed, 44 insertions(+), 2 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index ec3d9eae7..390825e97 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -124,13 +124,55 @@ It won't be possible for the client to cancel the goal until after it has receiv ## API -Actions are a first-class citizen in the ROS API, alongside topics and services. -Action servers and clients are created using the node interface. +This is a high-level overview of how to interact with action servers and action clients. ### API for action servers +Action servers are created with the node interface: + +- **create\_action\_server** - This requires the action *type* (specification), action *name* (topic string), and a *callback* for handling goals. +Optionally, a callback for **cancel** requests can also be registered. + +Handlers: + +- **handle_goal** - *Accepts* or *rejects* a goal request. +- **handle_cancel** - *Accepts* or *rejects* a cancel request for a given goal ID. +Note, 'accepting' does not mean the goal is canceled, but signals to the client that the goal will be canceled (ie. preempting). + +Once created, an action server provides the following commands: + +- **publish_feedback** - Provide feedback for a goal. +Publishes a message matching the action feedback type as defined in the specification. +- **set_canceled** - Termiante an active goal with a cancel result message. +- **set_succeeded** - Terminate an active goal with a successful result message. +- **set_aborted** - Terminate an active goal with an aborted result message. + ### API for action clients +### Example usage + +Disclaimer: These examples show how we **imagine** actions to be used, but it is subject to change. + +### C++ + +#### Action server usage + +TODO + +#### Action client usage + +TODO + +### Python + +#### Action server usage + +TODO + +#### Action client usage + +TODO + ### Real-time actions Actions may be used from or served by real-time nodes. From 85dba7d56e6ed21abb01c9148ca7d22311680ba9 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 10 Oct 2018 10:49:07 -0700 Subject: [PATCH 08/71] Actions implemented in rcl --- articles/actions.md | 18 +++++++++++++----- 1 file changed, 13 insertions(+), 5 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index ec3d9eae7..5e6d03479 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -169,15 +169,23 @@ This is irrespective of the implementation, which may use several topics or serv ## Middleware implementation -In ROS 1, actions are implemented using a set of topics under a namespace taken from the action name. +### ROS 1 Background +In ROS 1, actions are implemented as a separate library using a set of topics under a namespace taken from the action name. This implementation was chosen because ROS services are inherently synchronous, and so incompatible with the asynchronous nature of the action concept. There is also a need for a status/feedback channel and a control channel. -The Remote Procedure Call over DDS (DDS-RPC) specification does not explicitly provide facilities for interrupting service calls or receiving feedback on their progress. -It does provide for receiving both a return value from a request and, at the same time, an indication of whether the request was successful or raised an exception, with the exception type included in this information. +### ROS 2 -This means that an implementation of actions cannot simply be a DDS-style RPC. -The implementation must separately provide status/feedback and control channels. +Actions will be implemented on top of topics an services. +However, they will be included in all client libraries in ROS 2 with a common implmentation in C. +This reduces the work to implement actions at the client library level since existing middlewares do not need to be updated. + +It is possible actions could be implemented in the middlware layer in the future. +One option for DDS middlewares is Remote Procedure Call (DDS-RPC). +However, DDS-RPC does not provide facilities for interrupting service calls or receiving feedback on their progress. +It does provide for receiving a return value from a request and an indication of whether the request was successful. +Unsuccessful requests are returned with an exception. +A DDS based middlware would still need to separately provide status and feedback channels. ### Topics and Services Used From da638a9f88429d033bead518ada94ee712dbf6a0 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 10 Oct 2018 10:50:19 -0700 Subject: [PATCH 09/71] More italics --- articles/actions.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index df904fe39..e9ef6cd72 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -293,13 +293,13 @@ The possible statuses are: * *Accepted Cancellation* * The action server will try to cancel the indicated goal * Next status *Cancelled*, *Succeeded*, *Aborted* -* Cancelled +* *Cancelled* * The action server successfully canceled the goal * No more statuses will be published -* Succeeded +* *Succeeded* * The action server successfully reached the goal * No more statuses will be published -* Aborted +* *Aborted* * The action server failed reached the goal * No more statuses will be published From 45a7d0ba113be9d19b8e2559a334e480218c26c9 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 10 Oct 2018 11:03:17 -0700 Subject: [PATCH 10/71] QoS warning for goal submission service --- articles/actions.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/articles/actions.md b/articles/actions.md index e9ef6cd72..68045b918 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -245,6 +245,9 @@ It is the first service called to begin an action. A user-define description of the goal is sent as the request. The response is a standard action message indicating whether or not the goal was accepted, and if so the identifier the server will use to describe the goal. +The QoS settings of this service must be set the so the client is guaranteed to receive a response. +Otherwise it is possible for an action to be executed without a client being aware of it. + #### Cancel Request Service * **Direction**: Client calls Server From b263fd36a2455a0c664e92ffeb757bfab712cbaf Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 10 Oct 2018 11:10:51 -0700 Subject: [PATCH 11/71] Add API section for action client --- articles/actions.md | 23 +++++++++++++++++++++++ 1 file changed, 23 insertions(+) diff --git a/articles/actions.md b/articles/actions.md index 68045b918..a51d7da2c 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -149,6 +149,29 @@ Publishes a message matching the action feedback type as defined in the specific ### API for action clients +Action clients are created with the node interface: + +- **create\_action\_client** - This requires the action *type* (specification) and action *name*. +Optionally, handlers for action *feedback* and action *results* can be registered. + +Handlers: + +- **handle_feedback** - Called when the action server publishes a feedback message. +Contains the goal ID associated with the feedback. +- **handle_result** - Called when the action server invokes *set_canceled*, *set_succeeded*, or *set_aborted*. +Contains a result message and the goal ID. + +Once created, an action client provides the following commands: + +- **send_goal** - Send a goal request and get a response (accepted or rejected). +If accepted, then the response contains the goal ID. +- **cancel_goal** - Send a cancel request for a goal and get a response (accepted or rejected). +- **get_result** - Convenience method for getting the result for a particular goal ID (if a result exists). +- **get_status** - Get the current status of a goal. +Can be: *ACTIVE*, *CANCELING*, *CANCELED*, *SUCCEEDED*, *ABORTED*, or *INVALID* (goal ID is not tracked). + +TODO: state diagram + ### Example usage Disclaimer: These examples show how we **imagine** actions to be used, but it is subject to change. From 508247f6d50c1a334b024d35bdd3514b782fa9b6 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 10 Oct 2018 11:11:49 -0700 Subject: [PATCH 12/71] call -> calls --- articles/actions.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/articles/actions.md b/articles/actions.md index a51d7da2c..baf7d6965 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -291,7 +291,7 @@ The cancel request policy is the same as in ROS 1. #### Get Result Service -* **Direction**: Client call Server +* **Direction**: Client calls Server * **Request**: Goal ID * **Response**: Status of goal and user defined result From 98d2ba53fe8de5d10d0f92e050c87e455ca6cc49 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 10 Oct 2018 11:44:15 -0700 Subject: [PATCH 13/71] Server discards result after giving it to the client --- articles/actions.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/articles/actions.md b/articles/actions.md index baf7d6965..ee9c91641 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -299,6 +299,9 @@ The purpose of this service is to get the final result of a service. After a goal has been accepted the client should call this service to receive the result. The result will indicate the final status of the goal and any user defined data. +Once the server sends the result to the client it should free up any resources used by the action. +If the client never asks for the result then the server should discard the result after a timeout period. + #### Goal Status Topic * **Direction**: Server publishes From 778227658732b92ce0e4489fb495c491b9ac4739 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 10 Oct 2018 11:58:52 -0700 Subject: [PATCH 14/71] Actions namespaced separately from msg and srv definitions --- articles/actions.md | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/articles/actions.md b/articles/actions.md index ee9c91641..1e1c6f630 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -112,6 +112,13 @@ float32 percent_complete uint32 number_dishes_cleaned ``` +### Namespacing + +Multiple message and service definitions are generated from a single action definition. +In ROS 1 the generated messages were prefixed with the name of the action to avoid conflicts with other messages and services. +In ROS 2 the generated service and message definitions should be namespaced so it is impossible to conflict. +For example, in python the code generated from the generated definitions should be in the module `action` instead of `srv` and `msg`. +In C++ the generated code should be in the namespace and folder `action` instead of `srv` and `msg. ## Goal Identifiers From 23e942b414d5b36a51ddcdd47ff550ca4f20d9ca Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 10 Oct 2018 14:25:45 -0700 Subject: [PATCH 15/71] Shrink possible statuses --- articles/actions.md | 12 ++---------- 1 file changed, 2 insertions(+), 10 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 1e1c6f630..feaf0c25e 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -321,23 +321,15 @@ Messages are published when transitions from one status to another occur. The possible statuses are: * *Accepted* - * The goal has been accepted by the action server - * Next status *Executing* or *Accepted Cancellation* -* *Executing* - * The action server is attempting to reach the goal - * Next status *Accepted Cancellation*, *Succeeded*, *Aborted* -* *Accepted Cancellation* + * The goal has been accepted by the action server and may now be executing +* *Cancelling* * The action server will try to cancel the indicated goal - * Next status *Cancelled*, *Succeeded*, *Aborted* * *Cancelled* * The action server successfully canceled the goal - * No more statuses will be published * *Succeeded* * The action server successfully reached the goal - * No more statuses will be published * *Aborted* * The action server failed reached the goal - * No more statuses will be published #### Feedback Topic From 4efd85e37692167e76492941a43d7605a2dae15d Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 10 Oct 2018 14:44:32 -0700 Subject: [PATCH 16/71] Replace high-level API section with details about goal states Includes a state machine diagram for reference. --- articles/actions.md | 65 +++++++++++----------------- img/action_server_state_machine.png | Bin 0 -> 32422 bytes 2 files changed, 25 insertions(+), 40 deletions(-) create mode 100644 img/action_server_state_machine.png diff --git a/articles/actions.md b/articles/actions.md index feaf0c25e..181c45c30 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -129,62 +129,45 @@ If a client submits a goal and immediatly tries to cancel it, the cancelation ma In ROS 2 the action server will be responsible for generating the goal ID and notifying the client. It won't be possible for the client to cancel the goal until after it has received the goal ID. -## API - -This is a high-level overview of how to interact with action servers and action clients. - -### API for action servers - -Action servers are created with the node interface: - -- **create\_action\_server** - This requires the action *type* (specification), action *name* (topic string), and a *callback* for handling goals. -Optionally, a callback for **cancel** requests can also be registered. - -Handlers: +## Goal States -- **handle_goal** - *Accepts* or *rejects* a goal request. -- **handle_cancel** - *Accepts* or *rejects* a cancel request for a given goal ID. -Note, 'accepting' does not mean the goal is canceled, but signals to the client that the goal will be canceled (ie. preempting). +![Action Server State Machine](../img/action_server_state_machine.png) -Once created, an action server provides the following commands: +The action server is responsible for accepting (or rejecting) goals requested by clients. +The action server is also responsible for maintaining a separate state for each accepted goal. -- **publish_feedback** - Provide feedback for a goal. -Publishes a message matching the action feedback type as defined in the specification. -- **set_canceled** - Termiante an active goal with a cancel result message. -- **set_succeeded** - Terminate an active goal with a successful result message. -- **set_aborted** - Terminate an active goal with an aborted result message. +There are two intermediate states: -### API for action clients +- **ACTIVE** - The goal has been accepted and is currently being processed by the action server. +- **CANCELING** - The client has requested that the goal be canceled and the action server has accepted the cancel request. -Action clients are created with the node interface: +And three terminal states: -- **create\_action\_client** - This requires the action *type* (specification) and action *name*. -Optionally, handlers for action *feedback* and action *results* can be registered. +- **SUCCEEDED** - The goal was achieved successfully by the action server. +- **ABORTED** - The goal was terminated by the action server without an external request. +- **CANCELED** - The goal was canceled after an external request from an action client. -Handlers: +State transitions triggered by the action server: -- **handle_feedback** - Called when the action server publishes a feedback message. -Contains the goal ID associated with the feedback. -- **handle_result** - Called when the action server invokes *set_canceled*, *set_succeeded*, or *set_aborted*. -Contains a result message and the goal ID. +- **set_succeeded** - Notify that the goal completed successfully. +- **set_aborted** - Notify that an error was encountered during processing of the goal and it had to be aborted. +- **set_canceled** - Notify that canceling the goal completed successfully. -Once created, an action client provides the following commands: +State transitions triggered by the action client: -- **send_goal** - Send a goal request and get a response (accepted or rejected). -If accepted, then the response contains the goal ID. -- **cancel_goal** - Send a cancel request for a goal and get a response (accepted or rejected). -- **get_result** - Convenience method for getting the result for a particular goal ID (if a result exists). -- **get_status** - Get the current status of a goal. -Can be: *ACTIVE*, *CANCELING*, *CANCELED*, *SUCCEEDED*, *ABORTED*, or *INVALID* (goal ID is not tracked). +- **send_goal** - A goal is sent to the action server. +The state machine is only started if the action server *accepts* the goal. +- **cancel_goal** - Request that the action server stop processing the goal. +This transition only occurs if the action server *accepts* the request to cancel the goal. -TODO: state diagram - -### Example usage +## API Disclaimer: These examples show how we **imagine** actions to be used, but it is subject to change. ### C++ +TODO + #### Action server usage TODO @@ -195,6 +178,8 @@ TODO ### Python +TODO + #### Action server usage TODO diff --git a/img/action_server_state_machine.png b/img/action_server_state_machine.png new file mode 100644 index 0000000000000000000000000000000000000000..e755abc4e46b8082e21fc1cc61925cc66226f73d GIT binary patch literal 32422 zcmeFZ}6AEFchih$37@+tYL_9mi9+qq{VA)m}r8 zCP`HU?A?TVX_o$dY^W`oG?5h@$Ju%yu{-0m^nkcp(LG_d**YT>2eFebav&y@>@g(r z^aN$m8%>iSpw&V02>Utozkh-%Ip4&~=;|NU4*t(2jO7h3h2>@a zGf9EvOIwn7?tf=HI$erU$amQs#q=%c5tn%^sg+Eb80ZQz4aS!48oy=J-nVWqkqSz9 zl0NFgt;iTl#Z;w^sVdyw1Y?-M7@ARI*%*ToFd#VWuP|*eWBUHSc&q?pfCB@v&n_Kf zcu#^5vaGWkRig7djGOaZ!k=}Yc32lYSWZwIYdx7OnQQeaXs$>U{VeWPo#A(EFp&II z!KnVVMi2~JyTQ>!;_~0Orhi}Yw3;M}+uD6j93@U>T+aV}BdoI;prjFXMf~kg(weS! z7%kD```Z`C^n2THF@)T8-tT0+pQ~czbZ;r4w!m(**s#_nj`jKHtRH;s;@pCSRD#b< znp~YzEPs6D`7UYZ^_TQyhDOp?nA^gTEl#6@p6f}IVFeh_`wy|v*al+mTfaC8(sIH{ zxj4<*d{YD+42#QN59frGx1HO$t^Mkpy*QqB+MID2(mC1~)tc3_bNtM28&4@)fzOX+wF*=R-t_egJ53_iF{3WAG1&@6J$4uug;$LzB69ZL zt{Zpld1$@%(a4c#b>db7K9yi&_u*zmyY5)2f!pM(PwQu^nR>}jUUl*Pl;+Z}%tA)8 zsFFX}1C50mxt?rIF6CGeN}gs#NDf0J1_vGrIi@waZRXDh+?dEkkh%REFVZToJZd?f zvZt}+F>Mi+8(1Ao-_%5+NC|1h*8<=ETj(SZx2b45FOHzVrx6{=%R@%Do~@(~mWR@M zvu6kFurRugn|Q1zTW1Wf45ZG^AdBP5nPH>t0Rbl7>v=mF5b-D)v9Tj8W+D}(8F0ty zhZd1dlb zYh1*|-%n;~H%?9KtVip=dk5HJdEsi8!E_NM9DjW82VQioe|^BB)L2Lr_?*W%MIV1UVm6EC+Vlgl*gv(4wH1FCsCjT?++6Jjc<;8J)V}Nv zzvcOopT?wJ6Jlg-k*PKX(XZFYv%Ceg7kzvGc=Dp7HDaG=h z^iBj{n|h7azzod$WY%LdoU8m-EQ73eldJ8CADKEM-=$Ph&r3zSLa&3Ba;qY%ft3Du zmLCDUd2M0r8rxHKCY(gm(A=ZV@l7xuZuP_DmCtTP?xy=4Pi{=s6ex#Po#IfsAy69# zh4}E6g?D&|LsB=5-hwN)OP^#;)>t<`4x-I^5XiV69EH*(7IGEcEUlrwbGSLKCN%RV z7%QsFVRx>TfK2LQ>nSuEv5t{*r*bD2PCknJgB`ZO=g(ZC%MDIsUUT_ z4|WWXA=0*PtA)ENK~fvrl|-MZ_-$fqf_=Q?AIOpovEZxQ&$qP-I?k+Jy3M+ce-VL& zfXN{aDEAYqmHFsoVo&@O+qXzMg&`t@;uo~urh^pkQTMX%pMolNO|GtI1pL4B8#DdS zZOMlrg>P2}%ZQldnc*bw7$U9>Mvx8l^Aw!`fLqr|=T8!rMMNWbfDRL_2P_ev`jz7h3xKM)`OyZp-v zr3XHqFcHt|yMeTE0$EUrwyR?!9MTaLY(_oqnItYf_eYRM9eS}k zy%FTfa6-bR`_op|mHQX+0a12NJIWAJ9jJ!x>M%Dqg(n6w(WkUw#gc~m!PEXh7nExg zj|ate*9tQI--_P8#9Dq5v#=@v*;JGvqhqXO`W2|)tHA%5?HypI!N>M3I5-JxZuN}fa)#i5*&mRt3C6*zxWg>fle&1Onmm|;J zgR+O=u}3^6BBK=BK0RsPZQG<@gGa3qXpmf2X2GK1kM-fuq!0L1qNk@j&AZW?w@;xE z#Tx9_^nb~b^uv6Cus$MNrecMZyXG*}Um-SBQ@4ij)uHg9Du|_qmRurh;)g4gRZ(Y( zuyf94W+5?$q2bHEKlX=e+TnYZseKd2+tVft64%e~8FVOLogbNG3u}~0e`5=>q0p%A z;-RR9FfCBtc_of^fpZ0onD^m!xAjC(HM27xs1{>i%8I7c^7BB(f~=W2`WPR`cX9nf zs={7LTe4r{b(^`XY=9$PDc#h)4jl28WX4wK(U!$)o3#sI7dr zImb7FWlLQ5k~Iq0UH$T0^4ZHtsnFLOE2) z)|aF2(8punfr$kbn$lBty&Hh3Ha%{{HjlJXgH)rv)1dS+DRD?DTV=FS7()aTU1b8L zU@h!f{`2IVk32@Kcm`(vXL;ag-iQvla~sa+j3Q5%h7jE|82K9a1bYD@%4h%|Y?Pv? zepVIZ1-ElYM}bIL+;6LS7@(k&a~9yRH@V_Y%IHq5h1 zE>;*dsB))tMtQS@qeMOgeYKEAc2iN{nnq%spl%tEL=#dA|B};tw_8yDA(1@dtsw*6 zedein?XJILMow;la_3>s{5nFLin^j~9u{>h(?=Mxnq!L|%&6M$tx4KF+A<3XRJbiU*@`c^Sb}vtkvSWY9m| zi19bbur=`wAXpKi8nk3nT~Xcfi2HSdBlJXNSs(D&b3doaWgOlY`%&oj#~$v3z=u(7 zRpX_ds@~$LY>q|Tix86jrYZ-C_AaWGCKJ?ZR72q#aqL@JGY!*k6_{rr9=b!B;P!|Z zXE>ynJ@)HM93~6F}@&CMsaGKPF0nxkV0~GGEU35cPPQ| zKFVexDARdCd4$M=?>YKZ2$X!Jq0k}Iz8nq7eHdbquNIqNI0!iwB{a9j_~s{Ztc;7@ zs4y>9<8^x?yG&U zjW~oElyfWm9{->YtUr)`1sor0FtJh9TLwYrEIG1)&);ByU44W(?r9DjZv2^#N4xKj zp>%`_44xGzvXKj+2tNp$z{YLc!>PZY1oKpEt=^1tWr*z|x--&Jbr1*h2>%_VLZ4ti z(HX`EHTP9WBoxN}6-arhYGTSB+btkYC{17IP}>z7Vy0OgGs0gF>x3{oBA|YWH)O{? zgs@}4Gt$~OYbub2z6Cwh5NwyjT zJC8A562^novTTr10e3}#@Geh7xOo6XTTe_uJQO)TBhL@+ss%%vPMR|1QX zV0GK&CFP-TxTX+nH)Q5gG(@;0lH@6RydGtJ|rt9P3$W!Vo12_Ge|eamQi*-)h@ zD&>N7vh&kcALWzz-A;p>Yt8vKv?5!Gf4d1L+J21b|MM?DA_cHDvpdR7(Ek>J_ko3j znySk?KVpHrI<#4zc)b4aMUkym(MvhoEq&WnRj0u1=~jeJsvuhG1_8k~S8r*o^{gU) zp~M^Sc35~gD2D!kui5#|G%@U&?@Jfe(#d>YsX^WY77#h+y`DtT1teMx9$pU!!wcT7 zJeQ0=nsGrV=_#$IG0})FM>RO4);eWsmwX&Sg$b>C%qIyt?5}uT9ihLhD&dhUnfb2| zB-lK#7?!-!W)uxEHCDK3_E1)nU@>_URDf?WgMoGz+pRPTB6ly7Ce zJiTBvO$7b^?ws+UnA-UUm+dclC-L*vC4ya1d$3(DD1#N{yRMs>$U$$rZ%O#bu>O!f z_{PjV`S9|9_D!1ehgyqJ{x?~NhriLMd+5vnrIVQ@=tMA~(#=KY;dX;&xiMN`96=?d zq$a*-l1XjJqff7r#y;zjS?f`8c)Enf7xEm(VmwS`iNJA8;#73oK$r#a2)thF>{Fog z8jn{}<}^X1+%IJ0gk!zAKK&MqfP^{Y5Pp=r{1wb@ZaXVF#JU1m7Qd`a z=s;-32l%vnRD8YT(N^vv4y553wvRDpofd!vdNxue$fMN(9pkD%SZA!u`3_3WN7T-E z6`a&bW7X1n_XR(KVBOC?T3?d$g5aTFCUNOXeKN0{z^WL6>opFk zg>e6>cP|^MFFSF|v4)SsEQr5v%ouQ*OwsCsSMpyG*l8r)N>zT4AoTxz;yps^mgp(R zh%>rvZ^*eok```L50|%1T>y6jLaAxNzktoI%o~sW93n3LAS#iCs02licL%zV;WrjR zOSJb;XfU{TnI6xk#MGo%4(F`T~SrV+Gi);jFz9wczMir@}7mYwcfOSA}BLBIBizcfvMwDdYT1Xx$RP-lYho| zSNmVJuxDcsw|{w{^KGsrD*Ys}o5*rOkO=piYeIC@4s6uDx0oE07lkK>qiR(>if1$8oapy@QC9Vd^q*2q?b z7*po+GQZ6oCweOl!ry@%%kb`2R@{SIFAMix>d_rzrNVz8$Dm5^ETlX%x`R@KGsiBF zP(T}XK7rqNG*S&U=%BcQ>cdZdMS0cREXoxl-HBQ$pUQKpcSJN2RptIlzpjjFdekG& z^q+Uk2=k6@8m8*ca7izUxJje#Kx6GjQSwpZ`Vc#$AdUE1-Vv-a&?bz@K;$j8+3DaO zmdEU087<8y*M~&(InUvrY&u9PpCv|o^{}fB#K)bl!umJeJ|9dCi6wc}8;vfhxIVcP z+Ax2dqYSTZB-gii9{3^MAL_|aEZ|lwB)P7z5~2bh`z+KHTiivkQHWr9p!g$I&u)IM zCJsp>9Xc?96R9aH*Z;sg*B?K%X!_4Z2X`DVqr+N^gKxX97onAzXJ<`l-^1funw8Es zl_`+?Kq;`*?-!Uk=;lkWa7Z%FqVZCE7bsAOTG!hgSB(gQE`Z|3^@xA_a@~0-0 zDOcKdC>`o(Q=+5B3hcgZx*haC#&_zzC&P#|16|4ElDneT2sL;$J-6V@h9roqkRK#D zx~REAo?Ko|&8S)AYg~jeb7saKBJcWmx;?J?@bJ|M29X@W`1VJ~5#=`c9L#KEj=DPk}YeNAwjd~A7Dp8|6(2j@bX z6hzQZi@pbggFX&T{*o^(j%jCTuHj26tf~Oqv32&7TM+w?E;y$f-C9*`fwqvde#Z37=htgrLTC7fufS=$w{>m0iC4w6;KlO&DT0k+( zPqp@`(&tb!%unTpDHLde^FDEGH=nM3zO)tRo2`kepVV_b*8!N(*7)ye(_7L1Ap4^4 zU3&SdglB7bN$o)H@boJ;#@k5*lc!|B)XX?YS{Wj7KpS|Mn02j(%4tNIuN7tF_(cwC z)^c?`y)jmn+7tOO7lbdbGJ*uF!Q6g^v8jVqMN6nfj}6*-azgYyiR)AKs~`C@UtH_~ zHY|F!oKWX9FNr~#aR{jUjF(=!{>OI#9eW6THq6XV)#3G~UtOGxFU3fe2jdX3x_)9( zAi$t|-lvP9-yXj|dVzuJrQsx%2;di~1QfJi9jAI9ZxwxUS=|6YC8u6_S_S}WO#ILO zuJ4M|NZi*E_C2lKTm*P_e~LiK#RfXiubA( z;Dxbbf_=CK#YhtbiT%y>)!nPrpUDS}Hwv%KHz&Z#eIDcrW;BUl@4>v%RUfIIG0{ib zA<<24x7|4tj~VCC64^5VK95#eD3qDD8p?%}-2FkZzJ3c)q?y-$m%IreHFwyT)N1*I zOKtYx8(Vjxtqe%G+@>Z+G4YcZSVAEh7w@p~nkb3T6oe9o>M1_?WA8&OzkR^xG^nPU|qYCqFhW$L>p zhhya%bGwm<)O^@`CD|GdeJn`q_Q&wtiuO>#<`?}H7?u81q1}L$coIt!pY1wPKn<8= zI<+2s+~m9e{Tu)+GZR}6S`P-r1k5`iSC;kBzt}TFjn^rS? z_$_+wkxP8bH*#tnos6I85wIU?^dB!XTCKIX#N%!3Fqy6}lWGMpF{fc|As`d70h*@I z%r&59y)sLI#Eiv(uQ?M2HTpj=30n(gW8-FdvoU4V8nGL*ZAclwutfWscH1sSDqqN^ zzwPI^Yk~CubYT>PzH8UFKjf>X7Y|8ZJg;ck4?jO#UxMU=S#8?y=NhekrA&^U3l#up zUJ({wR>d>yH%_mduA}j{nh%dCK-{V=7<6Ts7tJf@k=c}9pY%z&VjTXmIdQ3%V z7WL#+zwp1#3_!Isw?P{L@TX8`KRyPEP+LOn4hJ%Qc3a0uMRU0{ssJ_7Bod!;ub!x^ zM6Y58vJGk)-4x#2$xrdCzn;!mYwP(w^4zNG zJp{ClA&;(nnBx*=$v1)hMCp_7O=~ie$Xt4f*aK4UeYlnlDhw5;JYsWdJIj|mTPDWA zw$Ajc4~?XEDE1)^=ZH&$uV?l+4}$hs#WPwLEqCijXT+w>6?P))!Mxm@iDX|Uv|MSc^n zjJXXt-WdHcsb8$kA*4nhcHDtQDC}twhhOi!j?N=!ao?UwQfJaF(d7}M%K;eHRUN1l zZycv-#_weIwgH1w*su!&ktt)cY$$=-u+o2z2zWEB4WMCWnr_2mfn1EDV2e>ouzjtE zBZ)*mPZJ&v`lY2N@mHGZ7xE5K8MHrNEwlV&&S%Ka9s}3p)HyH7fBL}GFAu%a(KE?2 zsIlSzB-4&)n`w)uGoZtIkCf>EYKjoBjLX?V=S4L0K@3Q?=P_t$5Pnf6;BQ1!bjyv4 zUVQuT#Rt+~?=anD59M5l+rHpOr${r}_L);9Hz?NhY}UZHNPE#H{}U%hlnD^Fx5 z3=cUfy)GOb=IV{a+;@gsqy*Q-@^!THjE9%*3H0IS&cg%@NNjNyIC)l2WB=sXq*AhG zg*UNFzwbT>rSpH&{cq%@O7asqQZ8NB;fIXRF5|)Li(v3S7!U#!$~-@rMa~PjaG;=O zEId-wZDTnHzWAOye4r{hkv?-SOz?q9E~`DjcpWveSxcmYU`^NOo9R)~zW@zU(du*3 zl;g?o_pcMjgd|+s{3Vs5BFx&C?sIN^q!%%Z#dEU9jBaIyb#Eb?3VkoH;X6pH+c^O* zd|S#&?r?R8m}6*=U<*Ne{Rlp6$>dsN`-Ux@gsG$?mWb90p|O^Lt-B$=anM2u0li{^6(IA>zJMGSHkV%$?95DvQ>2x~`y>pGesTJrLr?5CaF zN9i>29WVjiEnZY%rhH)g5j(E=drPSqE_(S5X^@3bg3DKqwcKG9o~ChC#5 z|F=Jf3}5`$6EKZ6iprBdBk^SX|K2$ThMe;WVyi3k?A@0(H793^6TqDb8xzSW0z$Rj<0kpW#c+-LwhIiB^!4$)oYz7yQEu;F_K zX%$`e@3uaFSo75VYKyHP=DIU8neJgVkclgPF!kE1cX zHE+?2+HL=o|2(e#b=>~yr((TN<;|-7$yzDG8ioz3O=ng`_Im3@1*oqfzXfwylu_|4 zH$FEJd`iACA0*h)51np;ag@Kf++5tWU&ntSNIE}ONyU$A+MM&r>!nj`7JNAcV!wl! zuVe%Da@od@t>e#xR*XM#2IE(2vgrLZc@0!EpHx0SlF>7Emh<$!S|+v~q%JZMD>4?b zoffqHNwL1BvEFtO9a?JAjPgB;4$T_T-`gkwn4R|$^Ej=qdehbMa)roS_*BDC4O2>r zjBdV9uJurc_hwl`t$8Ob9mqd=Cl8Ls%{Ge)GSHW22N*|gw8G2`3x{9?s0@mLLuAiL z$I1+dNjUHoR2n^i7twUF)9iLUXXA3sWWIP&F8Q8F&vy)@{pNpz#L zX7)35l#tSBF^hx8%Ra+aLrMW9P93H5Rl4;LRM%0K4zry2RIJbd>kJMWadw>|Mw7Q; z0Ovhi3^lbZ_4iw!c49f_HPlubbf>R$wY5EWUH@n#t|ECVeSVhOv9RcBnu{x*f5IUUJ+U300Zj+)9q;S2RgCmzbD=XB6E=a6 zHV-3d2?=JbdDWjd+)Ecw8o}GdzIYA%S&_bt+2)3+dWVwVYEmXcAO`z-;;}ooy?_^J zRA-m8)3`(chs35Fk;zVfPHx~rMA1oz@@P>>+322@*Nft$D z8WJdfs4!^aBXTuFUyMp7U#l~M;HnZ6>M%S&=ib4*oN<3nwM_Z0~nhxd^sNr>O zXM!d^7Sqgb&j(JRy|xMMdYN-4#j>9qn~rue?#3Sdp3&hnDE=AHb4OZ#;Ue{Bu8^;% zr9>}tw`4K5x5T?l8ND^1=*Zuvq?oPkf3w{%KV|{|GFowe5y|V*CEMUKY&_I(Zl3>D zd;@)vD?=tphOg$vuq>xm57s@hB(dE@|4WVYePu#nT#|p%%zC`*=bL$K8UN7HMPZh4 z#ar|9%@w*l9Kt5TmPmlLjj-o?~E;)p+_kqmlKQg&sI!3Mb>vQ|B*rUZd zS|HjvgwV0RoBFr-&22znybvDt;I5g<-D)HS@Q>s`IA{Hp&B~uP6rU=eLo0s`_+LUG z>S8+^_U@DEbxY*#GXHU}PsvsV$!uBYXgDP2Ti#Z#^R5A@O%w%d(hRo*0fU@dNqRnE z+h}m^`R&+u z3?7I4$Z-4JNm`NI=Gbi@*JofB5W3b_X8gxOot6i zYF64%B7Y`Wb$=>IdmDcH9!2bHgRWZJ-y{DOC&~hOkXzjMjnR^36;T$}^pNZO6d-~K#Y zQqDCXE^!G62bw_1dq9~mIM52jQX5lsB^PgIFd&Y8)mJ&W;pGohjtD*Gh_ehEmByPS z+l{e&$Ik&9Ejx4GS6=u5S6;JYb)Pnjrx1U+sOf^9->qi#7gP1~nJ=NUu0V`QqT^6^ za9U1vtH|ra zbm5WfntGX8`&?d~KH>l%D)boT;?3DBCFUsaDjSEeP5rO7tM(PG`FYBpMDN4$Kiqqm zvoqUV0s`%g@rq2|mVeI*%+f{OYTy1<`ZV?TWFm~w025UWe+Pwh0ebj5M=rv3R7Z~m z&j0`}WbF+>|MWQUVzsMY%3&0FK@%AgKE`HCJyBW!v`MJN^Hl3MWkj83M8ejs(PI#j z_RurPCC~;oX%i2veSU0_MusX6I9!Ejf9>L70CTG9%-ImZ zsQ9MkfZ=`vE-CK=NAl)tUmOD>4UVMr+W~e#(O9;!j0Oz9pKv_N(eF@tbA=W6Q1ca! zAwsL*x`EYxU6U`K6se0nO?yvg@g4VqZ3o0D(Y%jQRE|Hwo5wIyQZrZH)N=D|HBTnE zrQ)d?qXRre)lzKz89E@S2?&N;5xO~yb`BE@lf+0%qVJny1B?bmz8}81iA0=&@HZ2p z0p~h>2njs>(w8pQK*ndfm2;1yPMtnN?&=-bn}GvG)2Cr`12kcc*W+6ei=xS+g zpwXii2WSe=_f=p|0oX&pW#xIpFg;6Oj^j?80<8uREK-vY*~0YW!!4oTItYmPdhlz( zsuEqps)a=r8fv<$WJ=D;jmKA$8-*2P3o`B9Q%M)q0V@OzKpAbMsCJc?PejC^Msp~S z+5uE!OT=z6Py6l{Je^R8c)72E9jkvsrDsp;gJu@$k zZ^zqbHmjtcu=L*xaOkUX#&_>cqNGl)syD?%iqf#quG}L#%MAXjie925z1m= z>HFi&_!;#Vqd(UvGaQB9^K-4|-ZK;?^ZP4H?nkYA`w*Tp zw;)r`B|o>mHZ<*;&z#S6MRXMs?3MZ_X(qb0qP0e#+;(oYK6ww>q+!21C*#9 z?~RG<{KXUB_QMB9mLMjvEqc7DMHK;0S>!Y)Zr+7(gf~o<=~ZTZdb>o9m3ba7#%4dv zxLz|PerJ)oM7OMk#-APMIaVCFm8u=U!FO7Hj<>*LaO;8l8Om2eGHeM<_k|B0m+~#Owayfg)|>kVOZuTTthmiq|>xD&L*yeIbbd&M$8DuZCfkq?yM!BbFL# zZQi4}Zmo4mhPB%$cbeU|MO|!k>-nET{R%l(M@Q%)$ctBJg_FR zn3r)X9P2)+_4<8V;$Y&cKS?acl=e8TIbZfi&s2?11MTife7{~HYMyLhRCZRZPQu#|}nEdpJ((b)7?Ntwa9me_awLH8OjS z7*7R*OCKRAX0S8o3NI=@uKh!=W*p$o4@ry%(@}Qs!?O_%n$t%&)}P_I?!&lGG9rh) z)H%h5k;dw)#50Hi^@#32Cbc#ieiz#f$6Ud9SRRh zW|xgPTQu7F8_Xu4n`ZD)$jOwv^(8sSBLdgQWDxmfoExZo2SKH@jO1{^@|M!hrntp~ zqEdX~VdTT7hk)N{{_3&PTSXi6)gvbpLSET3?sbiLvClvcHcgJQyK(QheX+Fhw+>?c zlOO9SL{sYyCq!&EecX2Q8OI@(JoPb%;E1q&~{Fd%SdTI_24_Hp+ zvpXyllFRn2`ol6>>Sg57rjvCUVnKRa;n%Q5aUR2{ZVT0c{<~HxndY@qRj=pvt8#@!=(~MEb&>gj_V?4KT ziY3+XT55D5P?`OrwK1YN)iSA!qv@;0AMK6f9-z@R$g8C39V0mz%N$w^hE=|Cql9I9o%2gZm3j`V{gen|hw-`@L>LD`o-B z^Z(cS|K(^zQT3%r1+)Q5g!y_!4WtLn-h3P7Z9UZ7o~V*t%?xO}_?;z#1x_si<5?pq zjC769b@;UrYx4m4x6}Z?#U4wx7Z@VG2isEOXhh4f#j{FP%>;Hhbljp-WXoG#$<@seB>(Nj3|!0AI@nr-ksN(r?A$_bqP=PuIk zacG5X<5Wcfa#M9DCShmicXgk`Y?IC>GygAuCCq2b^nEfbh^h|;tl}nMRL8o)h;<6p zvq$C}#}(pWwqDmy`Y%D^m2DT2h+w1aOgRX|Cq*u+gDGMjwb6hYWd4RVJ3{Q%@~+wk!v7Rf;DXpt7%Xqk~7 zAf+Q;gbW;_NHF?R46O!S^JHmBorQF#0KK5gGo3HKikX9t{0r*-3p@YFj3rgc+yTsZ zE=a600o<4JrKH1S$pf1YrFy1ba^Pe{y9`N?FL9=xg^@M_l1>Ns>LB^Tgf&`?^s~5A znXcnhf#_)end^r=u`&*qk0sC6eXoPL?JA?GMdCR)zAn?U+0|f@pcH7mnEf*wDKfnH zWyz`m9;empzO4!Fda3{Fsf2zI;An~g={;3r9dmcd1$)QOxq8ROIjq`h;LkyF&(I+O zjbzS?%%8swW;f38s@X+%=iA%mV`ypI<}it8v;mjSIz^f+%+vje97`)21*+-9rc!U0 z5g;3l0VT=gMN~8i$ji|@!TrBK3NX;nPlhkgdyLLRxAK=x?-F zgX64r_A_j^?I{7&v}_RfF?Xf?TTmUt(ZlZ%?-(}0WRHDk%Pi$Kh`+Iv*Vz3=C{+rG zVpbiibhj~sjk(rl3}S^N1(t7BiGpFPcb!-Y6N!XoiBYXA87${-XE2U{&95x&bz5?U zOjrkL+%9m@$07-g zGMv8r{dg~tzczaUD)_3Or1fabh++2rJ%cUPEfDr0^-J}uFzmNSQ7>5cre?l-Awa>g z<^Ckzun}ktW{Do4qA4~(q@iy92@TTxmIAjXtux(*D*#Go3tScqWoZgVwDo+W#IVix z3%~_QVN%_K2_@gyMgl=eM9!w|?|e+Y7bdMxE}Y4kIpPLn8K?s!4vk5z z^O*DMb%1qz1fALZipMts@QBPU;m()CI0sXeFM^dmUN)#70(HSJ3~o#X*mPlu#*fxP zB5}{G_F(SBo4S?eGP7X4r#!a!fUJBx55x}wFV^$}xg-BW9rEubs7Y#+8-ID`J-C&# zrV*H#N#)om1LA4^j&Rxr%g-#C*R{_A9A?T`-8i{Y^9Y_kKY4=>5C4~16rt1R3Nb{qG^(Cxa9?cYoD+4-`QY|ezNThk7l$3eA`^B68?0O0j% zMDzXddhxxgjRvU(yNO0KH^-28PR&P|VpG|kL}GIcvR!K5=mVUl%Lb-B>@TEzYHiNs z-E0lzlKRO+%Gu0hbZhBmK2ctP)Ue@K8or&pf|AW{hlFl;Y`Ra{rw1TZ#9@! z1Q<)BG(~w5uE&{XP0$n!r((;8#vehWOi4*xN5zxSkq1OviHfk z3w1US5qgK=Y*sOfVxpFd%2)Y90|P>3-G=DPwY zJFj<-XV5VwXOQ?%@mrnkZ`SO!3=(Fd8uLC*lcri_pGYd9!BMq60j@+d?n_hvx>PS9Do- zD9qQq^-nmLF>4T^M`sjaPthy|30-mb7`Gp`0i5>w@<7c4?Nck@PFnpmTCFs@7Qiz6 z=EFI1a;{;s2m!m1Hgs+k2lWh?9Mp0oBEFMu6CwWVgJzT+}<9!PE z0`3CrO)vwVFedfdggL_g6khMLs!AS`Yo56z=np_~J?oD%!kvah98BAHD`7gm8>t}0 zyhMg^Lw;7Tk`}%|L04%<@b-VS04D4c1*TCJOoeoKZ3Opo*FMWd|B}F7wm~!{t&E3A zB(6T1D&MQ&I~AcXmYWj09~3QkHIUKA-oeV~pQ*V+Wb^o6Pjeq~vBnfUCn^}|w{jm_ z^uW_oAyCbiTg7;JAut2D`2@qA%YR{^hCG_q_G6{ai&h(XrvZjc1|)$sxpCeAWP#@f zat-bcs{j0?6iI|+MAeE z&4|Z%m30%kf#};gdM$a3Z)h2w{?VtIvyth4RLLY(Z*4c08_35HaY(YxH0TCvd{P3{ zZ}mPx16_|!mUPh1C*OKh3SfJUl?7VW$XVKoHuJq#FL*U_-UpX0(6kc~Pm2*2@&LAw`_$hyhsA^-vNtdHfL5h)(--FP2|H_1d%3*6i^Ror@#6`L9bc)1@N;APz1%=22Cjv#))`(s>D7Z?%4xaX znalMX1-;vmM5i_WSKbYHgLakZT${rgs$D#vL(i}7-nV^UC`iJ8YbCevY+12-%Wac} zN*YB-VfzvqG$ziv!INP3yLO`9kdeLh7VTxfMIW8+p1s2u*{;BQYz1f*3CX8smzxm_ zOmxWDO64&_SN4t+*{PTY#RaP9$SSf-+%9aOFSd6WTh#0zJAT8FeC_{}{AM(kFcPkO z`o>y85_R)XS&cA=>7g*e2a{}Y*s7>`xK|JY0pETQu>)?L4k*^Qk(x3$K>odiRCqtA zz06ZoKuyQ9T*a4J*3-Mr^rZ<<8tb2AP0~4IzkU(Z*u_9--i9#X%rR`a+ZpYPFerIr z95)kpZ*gt<9O;LVKF@~=2H)W_$MboQttxl25}}QJ^+{ekC^6a+xwbIo^%IlD^tAkm z>{Df^(Zo~bvzuu9HYBZCR}G6hv#hv}l$#46xEm?OnK)01bzjIfJXGaw{pITwZaq2l*7kj zl`^_Nn+ERW1r^6G|sf|kKEBEbmW;s6~q8^q;Rfw z^8t`OzZ!ba5&I5SU#T#}^dP2fLA(@@uj{|EWv76gQPg8+%apyv_v|fZXsM~*fG;;V zOJm$Y3=idTx*rI|a_uJ7V_t6opEy`sNp*5R!K6U9nkC&}8Tefs>i~J;5eNr41FkRs zB%T4O?Z#d&-8hK4k|ccGbxQSzTRma|4vOha@477a5nnAl=7=96K~59iq?w?TJR z(bY}k@&A%T&%i6zluCS}V8Q$Y40lH6m400pJ(sS8wY&9a%xh!)xv_{Eyp4P3n-%t; zZ4AvET*M&zp^>R_x=#<0Niff)b#oLdq~*w8eJgP>D%SL#T>nfV2Adb>*k36 zgt7g}PYZkwx);BN&iYvPMm}6x*#}P)Vd8ahvg;9AsJTSq5c^8u32Hy|H?NvzP~*GO zvYV~(rh(=apki8~~Md+I+oE zBqzW(Hkub9?Z68aE@Vu>NW`tRz=sY@Mr`&z;7sk8>0p6oH=bPp1p}Af;A_L169S+rRKOvi(T%E6 zEGk-9_AbsNY-!f3s~|PSINotUKd;87q2DeoFzR~s7Ly2c65F- zY(Jy(JNo@{cB(XdkjLX~S8pwpu|&FscPmauz@fD_mk%THP2$k%$-^$P{^RF4^3((b zguLk#8C;@EpId-@Y_J-wKESdM&Q%~+tu(ps=#e*^X>wTW4V#il|5hA(M!@0fu{{2qH z&brQ{Kmrg+JJ*Aki+LSFHQFlONn_gd0ld=Wy8Z|K|Fn13UsXo&nx{dOZlt@BEs|bax9JkZuqG0a4(H0@5K3(%sGM~!EO*a!BDW?GAAu*F9IC_A{>=C8C75olTFeUetG?{^PHeXSWBTQMhOW82)P@O` zb(&b*H>mgN>9BUa^ylI}CO!ra@F>JFsZ=zx@5C^%h@L@=1i>3PB!b9KL89##ym0po zq5wuk)ET~#EuNXtDbhq-l+r6mYV_!3w5_!J+M!u|k-q1D`mO54>E>W_(f{_Xkxf1K zdj<4lWsi%gV);u2K>U^PkO*>je8a?PP;YYPpa;X)(-P=|&ivGAw8Yb`G7Gi^^W zJug$pUho__uF;7_5lg?=<(<1TD3Pa^a*5zX{Px$n2nOI97xWPzg#2B92`t_E{cd1^ z-70OcO$+QW{ylCoU%1rzB79OfcWE)x5Hqs4c_r5f-_s2CamktkXUKKd>zA0sa3~L# zUoQ`y6Ly^qCIkwmK~>zPRlgU$8R|B^Ih}Yhc<N!v{&_(zm==P|8Uw|yh zE>|BJM#%D#Ms1!M-Eh~d!l=1I44P=7>4XyuR$ySg$?t|sCzePRbZK#MN6`GTRwd<# zb^-F(KT_Jd+j>3b39d*OElVHzE8)7-CgXa`Ug=hLEAB@WKe`P~5SD?ckXMg3ZC4t? zU?w&BlbZWw37^W&sWzrUp1XeaV(AOLnkn(YVU;vzzz;ByOn81A`R7_y_Mg7cwIqy{ z9f@zdSr?dtjDScuG)1e`+j8*7rCse?1kMzQ2F$SwN7A7xG_*$Wy(ybAj}aCNBaM-V zMw=+?x~%Au0&Ou~UHnYPyTM&6iKE5#1QV+do8L?FNEB!HZ!DF1Hd^=eXr9i)bjoGh z+Ij(-rnYZA=WaP6$J>k?ZaNkh^0svpZ#rWHk}mC{lKRFZzD@*5(+#UZLKp{X0IDGl zR#s_FwvK-OoCvSVFr zG@jOGH9+AOGLwBd=ixDUgpGg|EG)y`Xtbn==1?nqGmy=iI0Ij#QBm=#RfC?G7DyAL z-yu>0GF6_xi%-2n5}n*Dofr-0T_$*3WBww9W1FcpUk@;^NDNm#NSTLUgd<9WGgmeW z>L3UEtgl+@Vq)=l=rPm8K7A5928He^kPphEWUlx@=OBkgoWz3=H|2C_gnf4Inb>8WtWFG$9dzT8GDUMR9s*-2an2oQTVjX# zU8SH_=+vaDbL%oRi^|?!yFwo;P2pM7tq|IU;Gf~;Vu}Y|d%%Si;J*Ua3SrWse~=>t z8Fl-GR<~k*T8_kY(uT5(6@UJ|X&{FBm;+7}C5!#dX7qdx&`4Al#effnYE1B^XaG zFmNY=2RU*PAQ!_#jx&n{7Dcya%TQ6S(QpLIH+SGY7`09vMIA3$048u+^W$gEor-y; zS-t`z9CXGZ#J`F5Z4`LJj5T+-@!_X+{kC4|B%}Wx5BqC8cFhmVPfwZ+y48E5iRM)- zLn&Jr74RDnXh#!e8+^LRSo;AINVE(@WqWT1BGnOJLeW{fndcQO#B0ZBlI6A&$$5hw zF;Bhdmqe+d$4Z*Jr9b*+kw~PZJ2v?V#LGN>{%S{3kT`T#_hA15&X;2CTd!bw`1z7< z?R-5vX-$$>lJZz?*a8YykA8GVEG{P7HiE|yG7l~4FEI0D`#zWowzsWLaEBkpb2f2?e` zI@2d~n#{Q##HHMx(Z8z_c5P7Oks(yvNx}hB=l8AsXi*_Zo$omKv!D4lr`ODv$Y((A zm)#fDZ%oqExj+1LkTuIQK*?t|^RiF$MEdj}2!K>PX8Vu)lV-t6W&yOGTXc61>eEjG zX{M@@rvDl>KsLXDT#?6DRCw~a+E~SUAS~$h6Em{ye}{Y`Hlyl|d5PbUIj!+na5H1^ zVN&;ujomSwgKU5Qn?k(9ZEA1ZS}uNDt1?^AmQ8Dkpt&+UV~GH{yZgisi5zeIn98i7 z%oX?RA_6;&Tqs>#jPvx~{~~?A%M1y3V=zV36Z39?w2Su=hOQNvTS;OE`WY)W^-JSr z_ou|(C&4D4b>Z`<${oE?)?Q2&{UKOh3E@kR#ZZ~qI_r;}S#7c=*?O9P`J!i6iB~bd z6GG}wPN&RDQq+^TCssrF?YFc*8NY+&=ht^yIf7Iev6Sq4b6dW)H(up-ng{;q*oyS> zK4!(#*clvVrq_EyTRXL1f_w^?rjDrwQ|Sy95|j@*=z({}L?ab23bv9}ovcY-UsRVegiQQg_QqE8~C2((b0zb(x^@{TVg(k zB;wF(b7|0Oh{C=HOS$6;k0WVOpH0Q-xpaDez3M+rGC7|P zMhd?v=&bJIJ4`&gHr1kRdDL&Hz=LcUL*gGJI6@J!(mVxiKRBm(>;7F)Zm@v+?zZuJ zx?j!RiN;pGKY%(y(Wz7KFJ9QM$PRy-GGVTM#j2J?*X+c4w!XXx&ZB6QkY z&=q6FeCmK_m`WB=WoOb?(8N6sUE~+LnZ(vR9EJsgXm#ivSLgH?T28xnh9I0`@DrKN zW65u*y3$D3Zxt&_yYC2DA#?6cj4e(JVmZZ-hJ8qN^fS8W zgc0a8F*|^R&@M{a5b}0ustEVU?;&t&L?Pioti^%+h}?k z83|UCR8U5ALrLSaZLK(R(*o#;PrYvv-Dr`Vspi$7kUw6fZNA7t&_bl^q@n3|w%=ZR z#~)(tbXWQebSrNC#qk<`a%ZG-UuYG|F8XNlChC3YKJref;4m?A_}zU2mgy=2j(%IJ zr;MZLzh&%wWvz~>hQ81Xz-}}}w*T(Zl;KcZbsIBZQYpMJ;6t_4go`z&*)zF?|2p}y zAYg@aT=EfuBxbY+g?$CES!Od7$w^}1l|pG^uIcDF#w|4!6yD^%T zSW6x&aV8fr;LCnT!$3pK7Q;#W zrnH?B`u^b)LRim{On;%?WxiNN)(j!R6AJj<)ip(Z9!ItsC%0!n!5(hJ8SetG?0|+#_lk-1-+Tz11q-E7Hj9*6wfN<|L-F3=d4kXH9reNS|G8L)tBcK?3 z6~tUD|A8dP5@4(9kWz<}Q=UW@K2u+u5v>yN3Z(_#gf6-FOEh^ePF`E^a z9{%!*EdKTDmo`l)4f_d1IS4}YR+P2KR1#fm)2R7)G-KILHe0Xi&`V6dK{Epll8pI8 zUk0bhe4@hl`mzZ%9>M|wB{8N%*7P!Le}J+<@gd1ZHDFDKt-ax=+W!I)S?Yo-3io+G zwmcnQ6gcr(>Ci(#m(wD-&~Y=2`S%`=G}*OYo3#6RY9=}C%0oZgp=?#_;HY6Hv5+V@ zU)CLI`NZ2U1y(MLCewmf=XH|}rfefPVI#Ygjht+7E&--cCLT{I!j|~x+mPRR-V0=2 zJ5iB{uCd=1Csjl3;G_idFP4IGY4Cqq#fIYn=tNY6gAg}A?>78AeS_BF5=BoP1njdJ z?>kZ($E&iCG@-y$Ln!i1HA)?>SWi)Y0EOeC#vO^H z#CqHqWEgfa_fvqX>)<@w^dmkXvT1rUxB>k2%r`hyfCp|1T5n^+2g;J4d?-CNd^k`!O$OWgtKixicW3enK1xBErr34jEs+sx(kbNEwc*@gR`Dk*k%L(1pt=_ z{89-xJaqG)`+5l0GDm-XKM!KcaRcu!_XouGTV+U0Jd#8`HgV5q(BcEkpLj7C@uBuq zgKuahYQBf_r7Yp!01`Wi@8Uspp372Hp<&hTZB_U40>5omZ_zKHxk|(Rwu=CNvE`l9 z%!-?Wd5PB`%=!f&cEJ}XdL1lO59Nu)zy^TrVZQw#o=Us||bI1u>`5W~#RO z$bU(#{a`X&4iuV!B>IT+{rO5@9jF8g6L^5i>oD0-3DiexfZ+iOTqRMbh8bKY-}k?Q zx}N=bnI;>kB=}wIS0AnRv#X?Yw81l{1<>6Jv#y{9vqeyR2T~|dMcF*TOu%JM7%o#N zwfpE>Xq`(Ob|ViIyyy}px(8MR??WU>#5W@D>*K(&PzGd!O0aq$=d+0&TLB9(?*sa| zuHY`>vCAq#51<#33j0xVYGLHH$wm&6pp2(UarVyE22 zJ+hpW-1+mV_MLy@gK{dYTd*-P3f@g#;KcVPYZ zZh3xpI<~(fdlk~9I1b6%L_`Z3$>ygEHs(VegL`8R za}MXpHc^(#-ebE+swgM+o&f>R+y1lAf{zSfJ9r|nb} zmOl@P%w{#W2OcoXIp{8(R@(TKQXnyauTFSdr~s<>tJxDE2e^B_idAS!yylZUgonQc zGzpkgUF`>eP8-#88XFHmbyOK7moxw#(+p{7{x9%WiUtqO!ZHZ_sVJ$#vZMfm+t%LE z6e)H;aYa2upb5ceZ39J*&)MbRn)(bQcnI46yzxqwy zAx6SZ?JiVTM8|+HAWg*;u0)<@dHKu5YfZ++pXR(z2o^0~kkwl%ImZTC8EtIacldn| z7D4J|ik9P&nD+JUA6Ga4#S5H~`-%9xpwPUKuhDOQeFO4nnpe`^P$D6Q#4+Lv9pKf1 z-s~1#!f)fwTjxdrR7?1CHq)zsJ8lDpzTFJyG>!@qm!sdda#E%Au1_1=0iK8k8IHCw zbt+<|SpTs&u5S3#02N399jBuzmI_4z+Hkbrt_U3Nk_q60J6$!`peAI(5dKXCAkEV< zk4nt2P(7H{b2rVW;sXvVGh_-fr1Un8X42qo{sA7gcRL6}6-YHLF7w;O9`T}e#FUsQ z@c}Ga&`7a(P}_{e?t;800`IrNwm3Ke&mJ`YXG$DBna>@ztLJK*P^pqiJL@r~D;jz2 z=5iTk{Cpj8F!5jFPUy8&6b(CrI zc*tR~{zINNXv#na_rbyz%-1+1Qy>^lRl<2O%K_*|?6?$z$Nq$%AaQtBd|U8C)2v^m z-j`MAAbG81q2mcyZMPgThH2P3CjQm#pKXF;mT)6&t^}e%8R>E_3M){e<2E}l64dwK z2-Sammn~zO1mSFfPcfVyvd+L2%Oc4iL+R-heqqd+PWb~@DB;MBzyuID$c0?0Kx%N~ z#nu6M>c85pX(s+}7%3ORrIb4$iB^DITXbq6bvEUXC3No6Kx`0=nE+Bcqt|bnAIZIU z7R;Q%z@t^1M6UoQJN6kuZ2PLj4NSwvl@q}Sli6L~thVvHM$JJAI;2kWx0RAJTHzi` zOSE}L&%4ywlQhnTxvh>fk<<|#MBx=%U}dTVROxJh&1WUB#;ntJooTS%pJ0bi8N_Y| zi~`uY<9oUbfaB9{cJA-Bg(k8*6Od6x-G*ai*RWUnLqSIjCl)cDvc$Mk!LY9OC&+?(F78PWHgF3X{mxZgxC(=_!JZuJ5$^(u|kex z)gjegTj|fV#S~rc)IzFof(>c{(G$wOn%`tOlwsuup_UGrlm~onD3e1*u0E|Kdn%4# zFb*te!p{Vs2(qW>egJU_>}2#Oq~>hBQAjQK*Zm_=Q)cLfVJyL!pG@^9#QR_H#hqjY zh+OFlROrfYG9MfP* zh-a`x^1g#^zgC#U@!2xy-+KQGN7ql+64_~LjI5||{`QFcu}p(CviZFS>(g@1E7S#4IIjjLwAX81hHD>J>|d4K2@2#4Kd?*IpMv})KOj4e zeYeG&15hGhkS+2rulq-%xc^6^@H7s-TVG~%*DI6W>JYUbpNdHUdO;#IMO&@n*b}NklOuRlYOx}w2w&szrE^Uo{beyiUaH|YmWWFB~QqlQf zE~U$*5AS;W6{l&vQoGl|xRORfcHr*lW3~!|!VWj)w~NfT7cKMGTN&1Vt$}J?8UijG zU{3~tI8vUTc>BX;g6CTubM(W=NxZ<9 z(^u5$Bc)+TR>7~zsH!WoNF{Vb-f{RA!u$AtVOW%Q#IDX9(anG@M|$g#?(^HOrWWt_0M)|j?yNS!Fc_=hcE?PJ?;S_5*fg=lNo^O= z;l=KghTACC(CQ*oZ!3v`O!bue>C#LEZy$^|NQ@X9E8Sb9FM=hKHWYE zY+n0xHE}f4;I}T z{A--23D1X6SL{2=H5kA5_L-k7q_iC@b_PEF^y>U_xqqKj)FylX#^jHn#kcJO9)G2} zORno)cU4NEC+*TgOJD{HJ4@rs{H5mDZaTZd7cHN^wc&i|4X6Tf zz^dK1^5zFMe;nGcy|988!SP^uLL)3ps*(RZw6T#77-3?m#QnZMl?2VLw;Q3$l?WsU zAiPP+N`rd3m6a9O+eFoMkRYuL2yTy7#ph!)}!h$hX zYZg&lTrB+h_VUQp(^DW$ir`i6+_^x^@8hC}>k^ap?{fm<62vg&p{dafH>%m0nc`Lj z`zJV=g(njLYA=-j>+$#OzmMH+Cb5J?ZR97&J(q;+_#1-m!%5GZj=u2(ucJWKQ{-=f z71?2J@Bp(bw0QYW&AG|Z=xM~o0U*+V>ABC&?Phqy=I@3YO|w9zV-^XeH04+AAB=gL zj`uJN-VbU8FqL9J_WlsPUC1*sUxNK8Gi{duucJ7|laE%b+1ArROB57**2K}D-)vDZ z#gm7C8D_EeaH#7A2Xp5}>GpCm88&uS9b^!jkY$spb1H&^yuw%f^>pw#8CrZM1Jm~` zm=)>lM|yGr=eVISXivjfdfEDD*jLunAP>Cybo6Yvr4+%ZhZ2I-cXE<{dvpsAS#%eQ z-V31^dYIEI#LEH?#Np|dcFX|u!HQWUpO7~I2nwuBGFmTG#cT#rAMx<;RQz2bZF#-O zh0voln5&+-1N-??W!e_x6-?2w(O|) zJ+b+fCq@DY7+=9=InO|Rm&2rukc8Vb?A^O}KL%aYZ?cW19~#o_zjb#@I?cD8z5Bj` zg|J}*Lfbk88kg$*MuPR{`3?lGh%QB%8~&jXpbdKP~AtLFa*J^nE3zsojSqEf3pTk=@*@@|OpNbJB$IIx;I ztSpR}$0MK*nk4+@*%NlbeZF$MI1>(92wn}i(-_sQAm-rWQ(E}@w7sT0-hFjhUcW0S zP}^jbVJayR)oHd#34y3sC6Y2>YK`)d0h$ zq@dIEvsbOIQnJCPv^yZ3AUTvPQXl*fl*)DY8k*sH1LmaNQ&S|%%gbo=y0^62QhIOR zNCaHs#s+}d-;>@Lk_4fC(g`rDE>K!G>4~v>)NudP=)N|wH|J>(hJ!;6Bh3!*$;rdz z8Z2bzt%Cz_IU84aUzk&*@~h>A6{LU|5K*dC)b^-^0h~_*}dwaQirh9 zSTAqKjRL${?6?q#?-1BB*RMl*LC3O9cM$4O( z7;dm15pv3awC(rtUpYdrWeFqIwUquo>-~P%@WxgF2Eds-z)Tkk0H~x-Do;dXlL5z6 z0h&vy3y^}(!AS`J`!nO)(2#ln*p7;`NCTvP-hcWew7=NJO%VjPE;|BY8w_R*J99ra znfFiVkdio!1p&YiuduMNhf6gAzGV|a8U7DTa<;0AhnDqj#H0dtYPg^p?^fKdnKnugVmw$t6 ztqfCE9|C?V3|rr=QO1-S5-SoFB^YnN(R%i>(V9fJqB#gO^e#3X0S*F+E5SCO4Om^~ zy;Ofzc>e-KjFZx>PZJ+DW}SfuhL8#1jI@G+dan|;oMyKHvcZztayx6Wky`2+*y&*@ z%n8#4KAj@;hE3dKiyc|!s}d#M#Kp~DY$;_E)=m3LLucZjo-|)450#g1o+;4rOI zF25xe^F$o**A>XQk2RTINt8RTel<#_DP(1C`}+0E&bs+Ob#8mSC_~1y*QW;~#1jse zA8hj8BQ->?D-xTAgF@$Lyw_fM9$jQ=r z=Lg6;Hl${=|DD?vd1G;rq$1rJb~-GPRBe#>72siin7qjwOQeGWd4|-G%XeATV!>WaV>NLJ?3Alr9z_N6f;0d(AVR>A(fl z*RlvY1a8v~Qq`v;cnz!qDlRTAOUxV`Pk`7qH30!af$H>IFM;vR5Jy1z++2r(XrU!l zCIA(xfPAFF&@lp%xnr<0%tmp7a2&wuolVb7uA#3xTmy0+&Chhx&q!j$L zVbW+wU}SBLaWzBR8C5j-qF`NEN8fPsoTHhHQNUz*3_GwJ>%4B z16216msoVe4oRWKK01=!+^!GU4L0gj;W<;a<^#LdXu;n`ld4WMlkBuU(y5yTCqWQv zKih(+s)D(&&i60n! z@NCE?v@jPRnQ$64;V$J-K*-pfHbhFps@B$=rfTw9d0zIF%Z6_KnxCIXUCL=IfiV1} zaLgLv*^X&jeGXKFm{zjY=S#DHyPP_bEFA=af7%j@{lg2}A&Mhc)WYbK9q>%F6yK2{ zE{wr5s4)|iPa-XO?zx?6@Bo%pM2iG#t@;MM$-O)~3Juq{9xQUSKQn75a7cd#H!j$l z4|~zc`RxBvQl${beWJ?XG{zj?4PO4Z!ok)>io|0n2~>06)(X;@M2B^@q)jso8?U;Y z;xpp;&#w8s#A9TLQ62P#pIWo~#PAmc(UVRb+lM*LxJT<)$gaI^6VoUEl*;A=r1BMvf zVjRBb1+3vfxD7p%np1s*lFN(hhaI(Kh=njb!A?dKJG*X9AUY4@h;b{wOg^ z>FqgyLNqXfRsE?X0;U~kVpz#bjWCD}8*ZNlTF-g{Pn7xT`=lRWsvgrOTEe6JbrS*6 zn7W}%Tb}7XHYFR~`zEXxW`So!V5c({I(%g-Xz1^r@n@b6;OWo6OkWb4o63GMEF-LJ zRgp^b+BvcJD9ewNz>f6DnlRIEJsVp6NI%xYeW>2eOw?^9tjtpd!_amp7tumRB;)Rk zHbzLP!&ln@jY!PxHO+6g1xzzg_$#C3XNIr}7*bRs=>xYM6rx7l$le#=tYt{XD7~iH z_Pip^>uUuk9*Yh%%tibe(QUQ2o5$uPHCA?$GK%4FzJ%1-8`OGN>oSbQO(AWm$$Uy< zlqXceo??K|*Pa&h>=d*7PL zIoRUA8%*?Lq$bCh6Y5?5(*4RO4*C1^yr;UX-RLG0T2T1$@grl^y!sC_sTw3TW?iO) z7-Ltwiw}Ssw_T*#;SO;oDp;}9c{d_Z8nBrP4EO%;R;_iSTxBEt?{9q(UjcwQaeT&8 zE;Bw!^g%_ETBS=R48y8nOGpf>EHyQC(xfGS+y>8}4Cz{_+H{3hNpuJzqlqF+McJ!V zDodT7|8PHhCBnfAa)H4MXkY=sYjkExyJ0$)LjFC|F=1q&!RmNn79#n9J^cjvmZE>QKy%V3&g zc`O_$+BO#5>~GVXu@^}yC3pI;6@oSLVd_C6Z~n97fZ82!m1y?d-FRWH zzIq-^zBOtq**h@N>)+7u7Z%m`P)Q>Rf-*;WTm@9Q1f(GXwCG^7xyQ#2dag3{`1ztR z%Ovq-6<-ZKQ(KawCgdMRbG@WK8hRqN6)RD_(D+XWlV+sx1l;A`=g&khtfqpF7E*dI zyiyN2VkF-6GZmd*G)$s<37+S3xCsCF(*HLwI2~8k&Y~$&z+811VGP3Er&w#+Tc zbC*^RgWDI&@A0akQ5K6@XL6C9ZbnDdT3$Tgck;+s0V2Qde zSo2=XZnRl^L#wyvtLV9)VdMzVQ1KPXg)$`RL?*GAp z5|d`gE`$DqkIYyFus0wV*}t zZrHM1V9>mPJ8^xikuNa!$vUJ~E;_EjJX7pfnN^MLq^6r1erzhb_9=LNh;V2uNp$;u zI~({6CG2ER;u~TQ8b>L5v>v#bxWMFpiqLzmh~puFHNNl2ZGq#3t=sJu#F+VcQ7RdAa`ai#!xk|3GJi~BS|4U8Nw6=6QadoMw z%_GBY&ytyZ{04qUQQfyH%vH*2*?SCom4;*G_^+hX*#zucQo=X}v(>*W{X1lgcnQH| z(Zu*qj=f4#eWP7gT9p_*ZSKY}jh>KR`U+bjP zZPY%Ry8b(4Z~o{b#}S8Z>-2NoT6WI!)Wnj1t&>g%y=(!!1cyvp8huo$m0}~NbmQ=^ zmx(3+T1Tq_ddUrX2@Ywgu@%;ACve8Aa#QhN;|E$ttMa9W{}1RTIHa=cR+w(NQez%8 zP~cxLVOsxMmskRNNdkKLZ(u!ojGD6jvPuFcc9dh_1N*Oa|8e#}FaHg!M^D8#bVhx& z6AUaHd|>~z4mMh~HU1d%^54LUTKqdfqn%)2d%?gq{c9aetCoEb-phXjD{ArY1lgPY z>m`1J4!m_J5H&;3Fj zdTCX(>^$4(gHdJLr!cwYlzNqfFDG1km>*TQsy%ZB#cConEOFg#G0~cjn+z!pZo0uF ztR8F-kjkRjGaKRHz8Vu78&+G(t)Bnf-red`8X`J}7}|kWjq5<}SH1U6e5(Pc{KU)s zT&pQ1f4Do`U0uVBJGq@~4qJGCyHD-YGl`OOItDqj%d~uUYjK>yHZ?W1`_ocA7&kwQ z-r>3|O(79LDkUW~DWQ`?x!6ESvYg06KX+{V2{dJ=d)UlBWHZw)0H4@*WB%;Mt!y)Y z*r?y3aWz`lji^Rs>|3P|SI$IeGfn_V;kEjnFoA6Zoc3gzKOX@-@o`N}%_e~DgG1?| zQBe7!Pf>TI-cMm-bv}I8ZC(2nq5-%k7d2C-t{x7rsDQB8&{H_Op19C)_gHEt!Q3H1 zxuqQ8DS2~V9%WH+aT3@u8vNjiBf!Olt*)*f85h^QA3881b#1njgK~YZFF8506Kp

r* zDgHf#J~VfVd^iY3g}6mNrK?#s++8f&q#b*2By@F8FqJ4^MLvF#+%n$AIWh18R9HHK z?#Q)ERW<#icQ2A0LR`}%0{uX0Z=F8vWwf;emg0k>LtN?H8UD2yB}5at6zO=m7xctI z*F%OpOH@^aJ#dMePxkX&x9{5UR)`-Fqj}&5asmHYV61UH-!-f<>!Lb8KhLI&sKy*3 z1m+p6<*hAN#Gh!)p{HH5f^D=9PjMQAzq<=j(cAqrB;-t_G~}}m(@uZlI>2Fea9E#R zkPs!|hyRXw*b3M4Ok(ziP^z%QP(shGR83+0!)9zjV? LUA9Kr{O$h$L-w8r literal 0 HcmV?d00001 From 0d83eb81ef569b502adccb77dbb20700c416d600 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 10 Oct 2018 16:08:45 -0700 Subject: [PATCH 17/71] Begin section about bridging ROS 1 and ROS 2 --- articles/actions.md | 52 +++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 52 insertions(+) diff --git a/articles/actions.md b/articles/actions.md index 181c45c30..82380abdb 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -129,6 +129,58 @@ If a client submits a goal and immediatly tries to cancel it, the cancelation ma In ROS 2 the action server will be responsible for generating the goal ID and notifying the client. It won't be possible for the client to cancel the goal until after it has received the goal ID. +## Bridging between ROS 1 and ROS 2 + +### Detecting Action Servers and Clients + +There will be an API for the bridge to get a list of all ROS 2 action servers and clients. + +ROS 1 action servers and clients can be discovered by looking for topic ending in `/status` with message type `actionlib\_msgs/GoalStatusArray`. +If a publisher exists then a ROS 1 action server exists. +If a subscriber exists then a ROS 1 action client exists. + +### Bridging ROS 1 Action Client and ROS 2 Action Server + +If either a ROS 2 action server or a ROS 1 action client exists then the ROS 1 bridge will create the following: + +1. a ROS 1 action server +2. a ROS 2 action client +3. a subscription to the ROS 2 action server status topic + +#### Goal submission + +When the ROS 1 action client submits a goal the bridge will check if a ROS 2 action server exists. +If no server exists then the bridge will reject the goal. +If a server does exist then the bridge will call the ROS 2 goal submission service. +If the ROS 2 server accepts the goal then the bridge will call `setAccepted` on the ROS 1 bridge, otherwise it will call `setRejected`. + +If the goal is accepted then the bridge will store a map between the ROS 1 goal ID and the goal ID generated by the ROS 2 action server. +If a client tries to submit another goal with the same ID then it will be rejected for as long as this goal is known. + +#### Goal Cancellation + +When a ROS 1 client tries to cancel a goal the bridge must try to cancel it on the ROS 2 server. +First the bridge must look up the mapping of ROS 1 to ROS 2 goal IDs. +If a mapping exists then the bridge will call the cancellation service. + +If the mapping does not exist because the server has not yet accepted or rejected the goal then the bridge will wait until the goal is accepted. +If it is rejected the bridge will call setRejected and ignore the cancellation request. +If it is accepted then it will call the cancellation service. + +#### Feedback + +When the ROS 2 action server publishes feedback the bridge will check if it knows about the goal +If it does know about the goal then it will use the mapp of ROS 2 goal IDs to get a ROS 1 goal ID and publish the feedback. +If the goal ID is unkown then the brdige won't publish it. + +#### Result + +TODO + +### Bridging ROS 1 Action Server and ROS 2 Action Client + +TODO + ## Goal States ![Action Server State Machine](../img/action_server_state_machine.png) From 8b97ce8edf5bbaa290882ecf85a3f699286dd94a Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 10 Oct 2018 18:42:45 -0700 Subject: [PATCH 18/71] Add Action Server C++ examples --- articles/actions.md | 101 ++++++++++++++++++++++++++++++++++++++++++-- 1 file changed, 98 insertions(+), 3 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 82380abdb..684c5bed6 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -218,11 +218,106 @@ Disclaimer: These examples show how we **imagine** actions to be used, but it is ### C++ -TODO - #### Action server usage -TODO +Creating an action server: + +```c++ +auto node = rclcpp::Node::make_shared("my_node"); +auto server = node->create_action_server("fibonacci", handle_goal, handle_cancel); +``` + +Goal handler: + +```c++ +void handle_goal(const std::shared_ptr> goal) +{ + goal->accept(); + // or reject for some reason + // goal->reject(); +} +``` + +Just like in ROS 1, the `GoalHandle` encapsulates a state machine for each goal and offers methods for triggering transitions. + +Restricting the server to handle one goal at a time (e.g. [SimpleActionServer](http://wiki.ros.org/actionlib/DetailedDescription#Simple_Action_Server) from ROS 1): + +```c++ +const std::shared_ptr> g_current_goal = nullptr; + +void handle_goal(const std::shared_ptr> goal) +{ + // Only allow one goal active at a time + if (g_current_goal) + { + g_current_goal->set_canceled("New goal recevied, canceled previous goal."); + // Alternatively, the new goal could be rejected in favor of the previous + // goal->reject(); + } + goal->accept(); + g_current_goal = goal +} +``` + +Syntactic sugar could be added by wrapping `rclcpp::ActionServer` and the above logic into a new class `rclcpp::SimpleActionServer`. + +RFC(jacobperron): Alternatvely, we could make the API look more like the service that it is. +I think this would be more intuitive and ensure that implementers don't forget to accept/reject the request (the same goes for the cancel request). + +Service-like API example: + +```c++ +void handle_goal( + const std::shared_ptr request, + const std::shared_ptr response) +{ + // Get the goal handle from the request to save for later + goal = request->goal_handle; + + // Populate response + response->accepted = true; +} +``` + +Accepting/aborting a goal can be accomplished with a reference to the goal handle: + +```c++ +auto result_msg = Fibonacci::Result(); +// Populate result message +// ... +goal->set_succeeded(result_msg); +... +goal->set_aborted(result_msg); +``` + +Feedback can be provided, again with a reference to the goal handle: + +```c++ +auto feedback_msg = Fibonacci::Feedback(); +// Populate feedback message +// ... +goal->publish_feedback(feedback_msg); +``` + +Cancel handler: + +```c++ +void handle_cancel(const std::shared_ptr> goal) +{ + goal->accept_cancel(); + // or reject for some reason + // goal->rejected_cancel(); +} +``` + +After a cancel request has been accepted, the goal can be transitioned to the `CANCELED` state after any cleanup: + +```c++ +auto result_msg = Fibonacci::Result(); +// Populate result message +// ... +goal->set_canceled(result_msg); +``` #### Action client usage From 2c7e9e37931ff5e22cae094ccc82f8fb95cbb7ad Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 10 Oct 2018 19:07:18 -0700 Subject: [PATCH 19/71] Move SimpleActionServer example to separate section --- articles/actions.md | 44 ++++++++++++++++++++++++-------------------- 1 file changed, 24 insertions(+), 20 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 684c5bed6..37ad465a0 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -240,26 +240,6 @@ void handle_goal(const std::shared_ptr> goal) Just like in ROS 1, the `GoalHandle` encapsulates a state machine for each goal and offers methods for triggering transitions. -Restricting the server to handle one goal at a time (e.g. [SimpleActionServer](http://wiki.ros.org/actionlib/DetailedDescription#Simple_Action_Server) from ROS 1): - -```c++ -const std::shared_ptr> g_current_goal = nullptr; - -void handle_goal(const std::shared_ptr> goal) -{ - // Only allow one goal active at a time - if (g_current_goal) - { - g_current_goal->set_canceled("New goal recevied, canceled previous goal."); - // Alternatively, the new goal could be rejected in favor of the previous - // goal->reject(); - } - goal->accept(); - g_current_goal = goal -} -``` - -Syntactic sugar could be added by wrapping `rclcpp::ActionServer` and the above logic into a new class `rclcpp::SimpleActionServer`. RFC(jacobperron): Alternatvely, we could make the API look more like the service that it is. I think this would be more intuitive and ensure that implementers don't forget to accept/reject the request (the same goes for the cancel request). @@ -319,6 +299,30 @@ auto result_msg = Fibonacci::Result(); goal->set_canceled(result_msg); ``` +#### "Simple Action Server" + +Similar to the [SimpleActionServer](http://wiki.ros.org/actionlib/DetailedDescription#Simple_Action_Server) from ROS 1, we can restrict the server to handle one goal at a time: + +```c++ +std::shared_ptr> g_current_goal = nullptr; + +void handle_goal(const std::shared_ptr> goal) +{ + // Only allow one goal active at a time + if (g_current_goal) + { + g_current_goal->set_canceled("New goal recevied, canceled previous goal."); + // Alternatively, the new goal could be rejected in favor of the previous + // goal->reject(); + } + goal->accept(); + g_current_goal = goal +} +``` + +Syntactic sugar could be added by wrapping `rclcpp::ActionServer` and the above logic into a new class `rclcpp::SimpleActionServer`. +Other features from ROS 1 Simple Action Server could also be incorporated in the wrapper too. + #### Action client usage TODO From 2fb606c082f48cfe50e728a613378398c3788488 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 10 Oct 2018 19:13:45 -0700 Subject: [PATCH 20/71] Add include and type alias to action server example --- articles/actions.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/articles/actions.md b/articles/actions.md index 37ad465a0..8979f5f2b 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -223,6 +223,9 @@ Disclaimer: These examples show how we **imagine** actions to be used, but it is Creating an action server: ```c++ +#include "example_interfaces/action/fibonacci.hpp" +using Fibonacci = example_interfaces::action::Fibonacci; +... auto node = rclcpp::Node::make_shared("my_node"); auto server = node->create_action_server("fibonacci", handle_goal, handle_cancel); ``` From 95f6ad319a870523416e4a14346622941317ca3f Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 10 Oct 2018 19:48:19 -0700 Subject: [PATCH 21/71] Add Action Client C++ examples --- articles/actions.md | 57 ++++++++++++++++++++++++++++++++++++++++++++- 1 file changed, 56 insertions(+), 1 deletion(-) diff --git a/articles/actions.md b/articles/actions.md index 8979f5f2b..87f5add2b 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -328,7 +328,62 @@ Other features from ROS 1 Simple Action Server could also be incorporated in the #### Action client usage -TODO +Creating an action client: + +```c++ +#include "example_interfaces/action/fibonacci.hpp" +using Fibonacci = example_interfaces::action::Fibonacci; +... +auto node = rclcpp::Node::make_shared("my_node"); +auto action_client = node->create_action_client("fibonacci"); +``` + +Sending a goal: + +```c++ +// Populate goal request +auto goal_msg = Fibonacci::Goal(); +// ... + +// Send goal (synchronous) +std::shared_ptr goal_id = action_client->send_goal(goal_msg); + +// Check if accepted +if (goal_id) +{ + // Goal accepted! +} +else +{ + // Goal rejected :( +} +``` + +Similar to ROS services, sending a goal is synchronous. + +Optionally, callbacks for goal feedback and goal results can be registered: + +```c++ +// Send goal (synchronous) +std::shared_ptr goal_id = action_client->send_goal(goal_msg, feedback_callback, result_callback); +``` + +RFC: Alternatively, a future could be used in replace of the result callback (and feedback callback?). + + +Requesting a goal be canceled: + +```c++ +// Synchronous +if (action_client->cancel_goal(goal_id)) +{ + // Accepted +} +else +{ + // Rejected :( +} +``` ### Python From 8d9ccbf950a96ed134a036419ed98a94ca15d484 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 11 Oct 2018 09:28:12 -0700 Subject: [PATCH 22/71] Bridge R1 client and R2 server expanded --- articles/actions.md | 26 ++++++++++++++------------ 1 file changed, 14 insertions(+), 12 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 82380abdb..a9c82490e 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -135,9 +135,9 @@ It won't be possible for the client to cancel the goal until after it has receiv There will be an API for the bridge to get a list of all ROS 2 action servers and clients. -ROS 1 action servers and clients can be discovered by looking for topic ending in `/status` with message type `actionlib\_msgs/GoalStatusArray`. -If a publisher exists then a ROS 1 action server exists. -If a subscriber exists then a ROS 1 action client exists. +ROS 1 action servers and clients can be discovered by looking for topic ending in `/status` with message type `actionlib_msgs/GoalStatusArray`. +If a publisher exists then an action server exists. +If a subscriber exists then a client exists. ### Bridging ROS 1 Action Client and ROS 2 Action Server @@ -145,17 +145,15 @@ If either a ROS 2 action server or a ROS 1 action client exists then the ROS 1 b 1. a ROS 1 action server 2. a ROS 2 action client -3. a subscription to the ROS 2 action server status topic #### Goal submission When the ROS 1 action client submits a goal the bridge will check if a ROS 2 action server exists. -If no server exists then the bridge will reject the goal. -If a server does exist then the bridge will call the ROS 2 goal submission service. +If no server exists then the goal is rejected, otherwise the bridge calls the ROS 2 goal submission service. If the ROS 2 server accepts the goal then the bridge will call `setAccepted` on the ROS 1 bridge, otherwise it will call `setRejected`. -If the goal is accepted then the bridge will store a map between the ROS 1 goal ID and the goal ID generated by the ROS 2 action server. -If a client tries to submit another goal with the same ID then it will be rejected for as long as this goal is known. +When a goal is accepted the bridge stores a map between the ROS 1 and ROS 2 goal IDs. +If a client submits a goal with the same ID then it will be rejected until the first goal is finished. #### Goal Cancellation @@ -169,13 +167,17 @@ If it is accepted then it will call the cancellation service. #### Feedback -When the ROS 2 action server publishes feedback the bridge will check if it knows about the goal -If it does know about the goal then it will use the mapp of ROS 2 goal IDs to get a ROS 1 goal ID and publish the feedback. -If the goal ID is unkown then the brdige won't publish it. +The bridge will only publish feedback messages for goals that were sent through it. +Since the goal ID is generated by the server, the bridge can only know the mapping of ROS 1 to ROS 2 goal IDs if the bridge sent the goal. #### Result -TODO +Once a goal has been accepted the bridge will wait for the result. +When it gets the result the bridge will call + +If the bridge notices the ROS 2 action server disappears from the node graph then bridge will wait for the result indefinitely. +When the bridge reappears the bridge will try to get the result from the goal again. +If the ROS 2 server does not know of the goal, then the bridge will notify the ROS 1 client that the goal was cancelled. ### Bridging ROS 1 Action Server and ROS 2 Action Client From 1a5d958c1889d82bc9f68ab0bb99145ef841a40f Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Thu, 11 Oct 2018 11:30:13 -0700 Subject: [PATCH 23/71] Move API examples to examples repo Added references to specific packages. --- articles/actions.md | 182 ++------------------------------------------ 1 file changed, 5 insertions(+), 177 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 8af20174b..3a947b7ec 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -216,186 +216,14 @@ This transition only occurs if the action server *accepts* the request to cancel ## API -Disclaimer: These examples show how we **imagine** actions to be used, but it is subject to change. +Proposed examples can be in the respository [examples (branch: actions_proposal)](https://github.com/ros2/examples/tree/actions_proposal). -### C++ +C++: -#### Action server usage +- [examples/rclcpp/minimal_action_server](https://github.com/ros2/examples/tree/actions_proposal/rclcpp/minimal_action_server) +- [examples/rclcpp/minimal_action_client](https://github.com/ros2/examples/tree/actions_proposal/rclcpp/minimal_action_client) -Creating an action server: - -```c++ -#include "example_interfaces/action/fibonacci.hpp" -using Fibonacci = example_interfaces::action::Fibonacci; -... -auto node = rclcpp::Node::make_shared("my_node"); -auto server = node->create_action_server("fibonacci", handle_goal, handle_cancel); -``` - -Goal handler: - -```c++ -void handle_goal(const std::shared_ptr> goal) -{ - goal->accept(); - // or reject for some reason - // goal->reject(); -} -``` - -Just like in ROS 1, the `GoalHandle` encapsulates a state machine for each goal and offers methods for triggering transitions. - - -RFC(jacobperron): Alternatvely, we could make the API look more like the service that it is. -I think this would be more intuitive and ensure that implementers don't forget to accept/reject the request (the same goes for the cancel request). - -Service-like API example: - -```c++ -void handle_goal( - const std::shared_ptr request, - const std::shared_ptr response) -{ - // Get the goal handle from the request to save for later - goal = request->goal_handle; - - // Populate response - response->accepted = true; -} -``` - -Accepting/aborting a goal can be accomplished with a reference to the goal handle: - -```c++ -auto result_msg = Fibonacci::Result(); -// Populate result message -// ... -goal->set_succeeded(result_msg); -... -goal->set_aborted(result_msg); -``` - -Feedback can be provided, again with a reference to the goal handle: - -```c++ -auto feedback_msg = Fibonacci::Feedback(); -// Populate feedback message -// ... -goal->publish_feedback(feedback_msg); -``` - -Cancel handler: - -```c++ -void handle_cancel(const std::shared_ptr> goal) -{ - goal->accept_cancel(); - // or reject for some reason - // goal->rejected_cancel(); -} -``` - -After a cancel request has been accepted, the goal can be transitioned to the `CANCELED` state after any cleanup: - -```c++ -auto result_msg = Fibonacci::Result(); -// Populate result message -// ... -goal->set_canceled(result_msg); -``` - -#### "Simple Action Server" - -Similar to the [SimpleActionServer](http://wiki.ros.org/actionlib/DetailedDescription#Simple_Action_Server) from ROS 1, we can restrict the server to handle one goal at a time: - -```c++ -std::shared_ptr> g_current_goal = nullptr; - -void handle_goal(const std::shared_ptr> goal) -{ - // Only allow one goal active at a time - if (g_current_goal) - { - g_current_goal->set_canceled("New goal recevied, canceled previous goal."); - // Alternatively, the new goal could be rejected in favor of the previous - // goal->reject(); - } - goal->accept(); - g_current_goal = goal -} -``` - -Syntactic sugar could be added by wrapping `rclcpp::ActionServer` and the above logic into a new class `rclcpp::SimpleActionServer`. -Other features from ROS 1 Simple Action Server could also be incorporated in the wrapper too. - -#### Action client usage - -Creating an action client: - -```c++ -#include "example_interfaces/action/fibonacci.hpp" -using Fibonacci = example_interfaces::action::Fibonacci; -... -auto node = rclcpp::Node::make_shared("my_node"); -auto action_client = node->create_action_client("fibonacci"); -``` - -Sending a goal: - -```c++ -// Populate goal request -auto goal_msg = Fibonacci::Goal(); -// ... - -// Send goal (synchronous) -std::shared_ptr goal_id = action_client->send_goal(goal_msg); - -// Check if accepted -if (goal_id) -{ - // Goal accepted! -} -else -{ - // Goal rejected :( -} -``` - -Similar to ROS services, sending a goal is synchronous. - -Optionally, callbacks for goal feedback and goal results can be registered: - -```c++ -// Send goal (synchronous) -std::shared_ptr goal_id = action_client->send_goal(goal_msg, feedback_callback, result_callback); -``` - -RFC: Alternatively, a future could be used in replace of the result callback (and feedback callback?). - - -Requesting a goal be canceled: - -```c++ -// Synchronous -if (action_client->cancel_goal(goal_id)) -{ - // Accepted -} -else -{ - // Rejected :( -} -``` - -### Python - -TODO - -#### Action server usage - -TODO - -#### Action client usage +Python: TODO From bde9d09b8a85a3535efe702074a764a76ecd177b Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 11 Oct 2018 11:46:16 -0700 Subject: [PATCH 24/71] Rough start to bridging ROS 1 server and ROS 2 client --- articles/actions.md | 31 ++++++++++++++++++++++++++++++- 1 file changed, 30 insertions(+), 1 deletion(-) diff --git a/articles/actions.md b/articles/actions.md index 8af20174b..9e313fe4e 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -181,7 +181,36 @@ If the ROS 2 server does not know of the goal, then the bridge will notify the R ### Bridging ROS 1 Action Server and ROS 2 Action Client -TODO +If either a ROS 1 action server or a ROS 2 action client exist then the bridge will create: + +1. a ROS 1 action client +2. a ROS 2 action server + +#### Goal submission + +When the ROS 2 action client submits a goal the bridge will check if a ROS 1 action server exists. +If it does not exist the bridge will reject the goal, otherwise it will submit the goal to the ROS 1 server. +The same goal ID is to be used for both ROS 1 and ROS 2. + +Goals sent to the bridge from ROS 2 are always immediately accepted by the bridge. +The bridge will then submit the goal to the ROS 1 server. +The reason for instantly accepting the goal is that if the ROS 1 action server never responds to a goal request then the bridge cannot return a result. +Goals that are rejected by ROS 1 action servers will be reported as cancelled to ROS 2 action clients. + +#### Goal Cancellation + +When a ROS 2 client tries to cancel a goal the bridge will immediately accept the cancellation request. +It will then try to cancel the request on the ROS 1 action server. +If the cancellation request is rejected by the ROS 1 server then the ROS 2 bridge will stay in the *CANCELLING* state until the result of the goal is known. + +#### Feedback + +Since the goal ID is the same for both ROS 1 and ROS 2, the bridge will always publish feedback from ROS 1 servers to the ROS 2 feedback topic. + +#### Result + +When the ROS 1 action server publishes a result it will be set as the result on the ROS 1 bridge. +If the ROS 2 action client never calls the service to get the result then it is subject to the same timeout as if it were a normal ROS 2 action server. ## Goal States From d634a61e9a2f27f8a4a4c02d043accd36adf5d12 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Thu, 11 Oct 2018 12:02:01 -0700 Subject: [PATCH 25/71] Update goal state machine Rename ACTIVE -> EXECUTING and intermediate states to 'active' states. Also added a transition from EXECUTING to CANCELED. --- articles/actions.md | 8 +++++--- img/action_server_state_machine.png | Bin 32422 -> 33471 bytes 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 8800a284c..1f14d1c60 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -219,10 +219,11 @@ If the ROS 2 action client never calls the service to get the result then it is The action server is responsible for accepting (or rejecting) goals requested by clients. The action server is also responsible for maintaining a separate state for each accepted goal. -There are two intermediate states: +There are two active states: -- **ACTIVE** - The goal has been accepted and is currently being processed by the action server. +- **EXECUTING** - The goal has been accepted and is currently being executed by the action server. - **CANCELING** - The client has requested that the goal be canceled and the action server has accepted the cancel request. +This state is useful for any "clean up" that the action server may have to do. And three terminal states: @@ -241,7 +242,8 @@ State transitions triggered by the action client: - **send_goal** - A goal is sent to the action server. The state machine is only started if the action server *accepts* the goal. - **cancel_goal** - Request that the action server stop processing the goal. -This transition only occurs if the action server *accepts* the request to cancel the goal. +A transition only occurs if the action server *accepts* the request to cancel the goal. +The goal may transition to CANCELING or CANCELED depending on the action server implementation. ## API diff --git a/img/action_server_state_machine.png b/img/action_server_state_machine.png index e755abc4e46b8082e21fc1cc61925cc66226f73d..b450f8ec6d5fbebfd05e443dceb824852ebc7606 100644 GIT binary patch literal 33471 zcmdSBWmJ^W`!!5TD%}l3NOzay5Yiw>w=~iyDcvx1OGyX_gCZa)<&cV!(y4Sw$9v}Y z{Gau%XRY6-_xbdGV9lCg?sK2}#C7(y_r4}hM@#h~E;TL+3d%z@sFEHE3YrND3Mx7F z1MrC<{To{p6h;&^r6&df7Q5z{8Ki^c9X$(lZ!pw6vzH0cAT3`^v9%5f=OZwQ=UH1Y z@bu1&fS}x&7J+5`)tcIY+<|p*}0+rQs=?s&bVyQ#Ubhh2I>=e zLPCuHc`1nRc2s~D#8(z*{=Xk$phktIa+_ek31ei$#zyHeMgG*YlQDfA|Pnb8y3KN`uzFYa0#u9L}ib>3_m8cMfTjISn_ATRa z`p>8J&p&a}%e;zAq7j>uKJQPU5C}N5a-C^F{p`M=aB;Yj#;QU7(S3pXlgqSU+tcKN z2Alr)i=7W${62qleEv>sr0dUjyrxh~XY2p{+2d$)lqM37Vl2&CR^pxeLR(AFrJ&#b zywge0nbj_-?KwUP=qCvz^o`dM2&%x;}{i6`tpa~1^ucq#M>CkRQy$?`|@np zM6*DgNX%ogZz=S?4m(>Yp9r`1PV!0R(t&0<-) zhcu!FY_~^)4C0>4C=Mez)}Q0pwTqN;1?@?7anx84%s85voMc)B;zx+;kn24$pPi|P ze3qR)QixLX4;CE?vv7MwL1hUeLQfnt1-Kd7`vL>dO|!@_MTpBpx!Q{#rBTd$|8}Mc ztmb}JYU?&wJ%K<|<%w_{MOk3VtH0horJ3&vWq7&Thr=(Nl0+rM_D-v?CSQDLR4rjfys_H;g; zoG0Gxck|`_-Qh~_a={zwF70C3?ekY_#(Td%4|cph|CM9<+1+qGxdg$a7#(Ii<7@zj zUL@1Y)LbRe%glA{blu-2eCWKwy}kOUA2|lI8_gFZ=(@Y&8Y`5Fi6vrT4!yg1OINL5 zc_vrXmz^Wvs$P*;@>?Z|x_U{-Ea3La_oK_S)?<5v^@$3NN>W+Quy6s{;45K4yKiBj zrHE~6HOrX>Yu%1lzV<@*qnp?d>dk(6xgRKlt#E#2;grYG) zL@JKY;xL*=2BCmFckQ}4#%p$+eWPEg#bg4vqm&I254pQ^)ZrOHQe1^mnp>&$I?n1v%ixGxuIMNI(azp?rB1!?O@GiYAuF{Y$p3$r|YaBt)ve$ z?He``GY9ZI{j1fjhL*r-u%mIPXrbxd$Jn>##*IY7CofKWzjC)?6Fjjz5F!_k1Sc* z{d|AHd9km!&hWjFGyWA5KSDC}u6F&id$jL%Eq3-TWopq!{Fi1xlBmd`NYSaeIp6$u^WG`F1HsYC|7!0Xr^VYfA3$`vE zZwyzGvdFLx7adjK@e@29M?C-RUMMMsD6Kb3^GTH!U~oHLM;ML%Qkx1xMbDV~=(VAq ziQaD}R--qXC!)VT0JD<`JXU&a43U;(T6?)MoQ>uEgR+Q6=WQ7Cs{{(ZGlpy>ZZ#N0 zy@MI?yv^q^7_)a73Zl{4`J!$$u{Md60%%oHl8Dm6)3n7GwwauU88(|755`Qtda+p| z114Xf=_V(34nw$AI(LnpWyocPo_n5{$9_t8Bo4`Uxcx9n?4R{A&y}yS#H_ee_2x9o z=O7yB+u8gmRgN!DqLt7~L*bM%cy`*rfP8kz52IfSmiQaBojX`a9P+F z#lw$)JKl6d5|}!kL_DZ2%xu5hNrJ>}6Hl_cJY_e56hTxVp$7SsA*@FD{{)^5!|aZv zA=)D`ESDwlv#WnD(m@x528U3}+(BjEw7#L|EC`!p+1|2OKjWx-V?Xv1+ZNjCnyhU; z=n(jrBlFr%nVGJ?`zAYigi#nA1Z31z!#T)hN8jIG*jC^LkWPZZ(*UC7)FM^ZOyE!L@)C@*OiO;E>$@OfYLL)n4TQQ33 ze;(*P*gBK~HjzUqa94=y2oB3j0cI1;sjWb9RT#^rQyM8u#{|Y5z2!VrTb&^XW4#J1 zPh^sU)vhDbxwxtB>{@Y6AzYp~F<|*VMpO1pur_spB;Z`(6FrAf~zVy{|@odr=^~NYR_j zIcz>SGBQGjg>D#)kVqjITU-fV1r_L#^sG;oh4h9R82iBb=Q;OZ*=ms+LPXiVr{h1Q z71v3_h4I($%iUd+UCH2(#8D$~C)q{IJef{fSNjtxW3m1DpNql>_OI3+$+NYk+X?Kd zeWCPgatwlTbGnS2+x$F9Gv48}9Z0S;h@mX1nb9vQKpd!Sm#H^$Nhrn*4m9>iG`}5^-7oEQSeqp`mt%~SKBmdL=WUN zDZS~&xG0eD<}^%%L^G*PeNj(ij=GXl!%wfH;>D|3l{!hFB)795IVm;H$iP`M_#Se9 z>rVz-UvgavJ}+bzHi(${V26N3uL%i5E8@tusETX@lH&eB1m;oIUQ=z`uF6b8q9RiIn0_LgC(qkofpW7Wo+`xpJX2&kg zSfC`|F1`kDSo9Arp?6xIuu~~{|F3VUb0GSYItg6WK5~(0q(#S}Jt@fH z>t6_|Jsm@nT zA_Q}Fd5!9)IH}tiv~+GTR~H$a=BIytOqxNBTfd}LP#f>WE5*|gLLcPXDo?1gYAmHL zD->+R}j!I|mnB_s%Puk_-Dn8r(W41P2@CO;{l4r#-!8Tm|Sq z3RsGUNL>Ez3AoJ3j5Qh{TomxA%*aP2K{l&2My!tsaDK-Bg6CHB$Q}$nvq2)>SQx7d zG6B$x1f3<3(9lFeZe6(D!~X&L|9M%)#dxC`bnvq>g=-+g8yC%wh0*1^dsTTEXaM>(-tv|q9P-Duz#?eZ9%TTvz_YOWCaU^41^Bd3${yuQYnEMCkiEh4_NwaeR^ zu#np@=|Evuag_w}?z`LW)&A~hmZ(WI=;sG6gWeVep$l!)Mpy)BG@>uO5qV_B9n_Qp z3N$HOw<}n6#lis99IAsQ5LjW_VXKE6g+aI9!f$jt+EfHD?maqDRg!;UtJWBFm#KC) zSa)}acjt+8S7^xZOi`om%#mGeP*^QUGU`Fzx|%GXxrMdn?Rq5G(aGSt&SCicL6Hu9 z#J};@%f3!74tt!2Em38Dq7n<29OLeehQq>)g$0koIhabliJaFiC$&7jhL8qltn1zx z0>g+~OQy!;Hh!DN0jr=96V4aMf)(s9gunO^7I+dCbQ#8?`mteY+S0|lauh#q@e7t_ z{)5xK_i4&!DHH_XV3;}LL~m46Jx*oZlOUZ1fc~fD{)W$GMX8l;b)l0ra|ckAGF7bAK`gBT6lzfnQFn}HcTAi9iL2D_ux{8#^R7p~ zs>^N*wy7pXf?YXHp5~#brAL4N;ne~*W&kG$7-)f;089M&RZa4UPBQZRU}-IZuMl@;K-(L;W!^|?)spBg47-^-`a%jb*cQ zvwCnS8#Dk4o1ui4+t?@BrA4N8-(J0cN3VNi(yGVe)C?t8Gfk$IA1j!XP%{$$ApSCJ zZBS%FzpGPp@JR&P*vkR@b}uS@BR-`-&_fgA^`{n2Xwi(gel^%foR;_Y!UUMy;ejK?Gvok31NVX7(g;pK^; z(iJ!eTug19DC?HQ8r+k}Dp`S%!SCdXb`a_j0UKG;NitJNLOhA03&awl4F33#Pk6t- zkVmYv5x=4wJx1y9vo}if%%LU8T5J*+I5R5hYky-)t zJJbwnSH+n2RsaGe?xp41-!8j_+%J|$yaev0T>$y;1&sC zf7Qrk^sDt)Yt34TS9)Wfv9i;$ntCj@KZ(R9^4yu?fxu_7ZV$TdnV;qftIL3Fj0~h< z;UGO@GORJk5%Zv59ZX39W4h88N1~3(WmrRsWD1l=E~G?>KZE6C`z@7;Quqa-!&pHa zK$qb)B-h9D0=5GNTl4}p7`*0fksyH!fgjeU)#8$IGJ0>0Y#01|_f&uDXJ##+4&FDm zYJ9XG&Z3m`;qW_HOv-qyUlR&u(jrY2ratF;d2BBoc#KhJ`gvfn<8|gMmHa%A-?-wq zt^oq(SD?pyOG(4pMPLpDUv}w%?R?A2SQ;_j8pHR|e}7gcz&6HAaY)8l9*7n5HCIa>9yZu%v~0K~bnmU4LO;tfgpch>sLhS8Eu+1Go{?gOHLHExE#WoyoaY z{if6v)v*LokeRf{;Z0i1^+u5%-($5EtgVF+^rJlA}vh z42T3y%pqO4VZE7zGF;N{&df(SSOlyS+Yt zhQa2${p(`?%YhCc5Gvj@rv2hJZ!;j`gOQ&l(95*pmgvT@5XDpQ6>V!DlSGRJaE($U zRwef5TO)jTrkK<-IO1E<>?Q#{1=4fMq-C6y@e2ipVt8g?-&#O}>WjOR#fcu@( zQm4%RQr8D4jbWo%t5>yzps;Ek_$+oD_-y^KsBmP=Z?t7YlADzM2M zUsu`}d=~9G>k*uz@1Ew95^Ya^C}yU9RmQC3rK;ELI8HxePx)ZJ`nFi_Ba#C7>Zxhu zh<1Cv6q*9o6AQJs*+2}E0|82bhPb0ZjQsTdYV!+6OY@vG_u*wI zI+H^36JpT_0#o^FGlMC}(L#6>N6i1g*c@Wi%GBELMXmNNsq5+l6x&0|9cKa~zNde5 z`R!iJ0zxJ!o{S5ivnWT269F`lXuRBB;TWm-yQR+CGgGoxWpquB<0^oNG;}A)r9$ho(FKg(?LQFlClLXF(;9UysE=s)*G@NJ|JO8L1~*u8uNNrF_m-pKhI9^cRw zpR6A}nMKlenRsWZQC#REFjI|+#2Wf7ZpiTBB*$$n6Qh)ty*aYWxyUVS*y?3pYuu>t zm~W&Xm$!9-Zh(*?y*am6Nw2@1gE)=Tu*T|SbCi>+sMT1?Z&$v}=Wm9jqVfyCbaJu- z2EqpWC15$#|E{*qzF?o^=M06o;Xj#huW=h=Gtm?UC<;gLAc4X3UEV-JZN8XCsb;Pq zxK1UJ()k3%4T7^h)5uaJ7g}#1&(`U`H)mL_gOB;3IgLpTCUjS1m)vS!AZ93-jDS%Z zY`0veV;DiRa@`4v9N(vMkDtUDL%_MxOvEpPuxY7>rZI0b?Q^ukBOTWUlHwCngHr7T z)(1{tK8*q~@%N4#X;OPCDfCHiF!7$Vnn36@3mik)`gf966r+C_$0U?I+4K+~7@CD7 z_`)~Gi$D08!k_}|@sV+T>`oKq@w7a~4f0XfIXPo=F#HpN!T2wDxxdC$G80P_U_ITU zf{<^XoRb1~MKljCLYpl*UReW1EtZUn9Pn7l-~{4$0EQkt!7+) zh@Dep7Z^ceCV_Q}z7!-bz?Vpa2Gum7e*@88>WA7V;p`i1Nmn4yC-tRQB>cYR9nxCH zvLds|M36?=CTcE3tVnZe7{GEU&H(MdI@4&&`B619nQ084O0cRtkgZ+c?Kp#tz(D&b za%+ak<*RoPQx9wGLuaDT4?9KgI83QtD1;e zNxoP%_Yq zK6-1T%xI%z^^$qjuMk;WJQ39&A~+d znO-}X!cYbTBmfQ{wE6Ckd(CHaqdua?*q*}dyg&;$L^1w|9dJ+o=Q|T4;?)%?kahs^ znT#2FgBo;RD4JY1^@;0yY1E$V!6GW3#S6axJrdZ4+TtOuX_dpj?Mb}g>$6NV?hl7m znhJ!6AsCw4@IR&MnVi-@Ps3)AZC6kA&2hcFL^W?iDU?F5)(bwB_2=JPz$4|xc3p5b zM@ahN8+X!LEd?Bfy?ZJ`mN+#1$pr=Ry*Fm=AoK!N+!MvPl{l6Ruj)D3x1xnBXFN@K zy#=PjC>jic3TOn*XLnV0x91G}_PFxL*=!HHl~y!!!)`9a^((_L@r3Pbp+q3h4%dH4DuNpm{;r==(y^z~6Z*BM6jtn($gc}c~6 zHrKh2kJ+?~@T2i7kdTmZ`7d?=CZf%216R;tBo+YoY8|v*%|~f8KB6k6 z%a#(eqT(&!M~!7*sM1qrky#rE-c?mlE>)UP7KFk?UZlSJItwq{VzG9aezdHZ1W8i* zsLQf^>Ae>)mZp@*$?Udz`PuE~rW!5X!wU5lex>tdz!|Q7FHsctTE_-QYE)g2MCzt4 zwoZ8H=^rAv<9PkuN9(I_;U_5F&Arnv|J5_pF9gTO5`A4e9#wsl5W|!zsK(v?>h?h~ zdu;MLPFV@G+0KZ^2NyBd>}FcE)JMT<7OQXIa<>F+o*77CNKt`co(b0&22o;?`F&J@ zYZZJ~NW@QT)UC65@p9ML>e`Q|YkQF4)6!8ujqXQ;E=>9Ot9Lr139MGDP?!dKI+Md^ zR7097Ey3?f*&W0SP*7Mhod}#fV{hc2dYS^B6I^%0_K%>i^WJ>|h08jZHvOJinW~Fi z=*fc@3(v1}Q@LLo75%&d=R6unrF5etg&fBcLH1oOHz7@e3R~`tAy@+`Jfna`TTj>L zfdB0U@Ocabv$foTctc**&7ThfL~ffPMiHL|K!3nxaRPu?stzMsv~Nzw2?`Hu(pUIJS+m zh_ST_(?86I`wOpY7kqIalPD|pE8J5sU(j9?_MP!G?e4?zDPU%QSH4>N;Qf5*`57ii=`|aNdv+wMhJVi`Qa%xzb!Z;n%xM7tgil213)yO9w*O-h<+w3ec zEVHXtxhB!#BvO{#7Mzq%s8l@W_)W!YccDH0WqVd%A1-?@z3klStI?$T3|_VV$&E`r zi{?WhaV?Njtc-Q|u-!kZMtjkMeRZXlwq9~2vVT#%4ozolusR8B54c6egkv@03_-k) ze1-h!+hSj&eSP~}An8RQCSvtBLocLVK!Ad4W_`%Zu-2k33V&x3(2_r4!)gtb2;-G1?fr8K$0_!J!q#RGG%Sx-DRPQ6_eNGogn*O=fl+QtvXWgioyPGhv zPSRvB1${Wn2@>gB>-_7x-vwrcoj~6=3?H^03O@JX3d|V0v@n5rwT&coT7MxyiJ~)a zF_t(2H?HRf*J8by^9wJA&w!Lj_L)k-PEU>o!L+4T>bH(9PpootYMx_&+4}lNj{`aD zWY1rTJ^uZgjn6j_r9Z+@#apFXEOG$bH=a2yCdq&KVR~en^oE%Elv%7R_?$kS{9vG} zS$RYo-u{hmEH~c%Xkw-JQ{VYWuE=rkfL&mX4!)b<=bd{Ri~^w+?{Q|xFr_w|hGl0E z70ank!x7U&F9iFe#}fVDiHhEosR=?&K`a5G7Z@!GhpT&A964*Yk5a5Q>9BXj15lmP zRmfl)bo)2=+{VKH5F}x7cjx;~EAnhh`boA5K`URM6HEE)3YJg5&sNp8gl09qZt>1i zckhjUm?Wh^pwHAzcvvL!nm;OEy*!W=t!cVQB{4@JZ6zVnLPE~6=vOtK|KYELxK!>B z&oM?A@JrVf;%x*PwPMrSzS)myrVDN6I zXW|i{fOP+jl?Sq;ML00X|Cs+Ak;;_$jC(?AD=;k5h z%r!T47fPqFwm;DecJHNkOe%N!t?Uxha$m=Wj_%6X{*JPvvbEc!|BraX&|pr_KcGdP2!OUX!O@4@4oBB7 zNYoCR14&HB7JBnA`oIk0|L6_{%pTbsHbSuJJgD0*u$xlKgkNyr+lWkGm%~|6bPf&kvpxW-*^?dtJukZ6_ zUk^0nA^y`GkY;9I%UXSrwn{AIruy^hNMlj;1RRm{tJ7~zIsNfucp%RJP5vce$cH&-6~M+rHM&Hrr}dD%_so`3oZ za&#iFVU#1|NguEJz&`oz7%4B)%Y`IL`fe|StY552yUz~~V;$ADofhN2OqVAW;tFI( zI)Hb)0W86{Y(55?fyBRF1y!kgiybs%oCe*%*rE$)tL&7==q&(|cT=u${kJjEfKCD8 zvC(0an%lCIw*5)VmyY0TaxyL>B>?4q04I?@0pFSg5wd}Z$N#N?pK4R7Oo~WSYNS9y z=-10?)6ey|x_;Zg9{+M9LZ?-f2P>up=fBM7iUI5&;6-b67IK9gr5~gVJ55+EwE02{ zB|i<$K%!?-!oWl}dQqqt#DbGNrNO#4#0FTN@(J0sXh{LN67z`ecq!8B`pnI4C_~LW z!lcRJ;c>vGO9(LMm8m3sEmuqT{5!$gm%_jR;6cyZClQ1q&Ia5T?UX@j*IUJ*Xfxj% ztQ8NR6Ogds14gVO7Uj4ijaw5k-c0ncNz`UUUQ&B!nRmZ4KZJCXcUAtJZZ3z>CIBeb=}h-Gd1{4k!;WM zVqt^Z$@BKWTiiyQLFGaf9^Eb{8hhbs%J|pFCo}xkNA}U&Rnz5ULx%Mg16!X80AKa~ z{9SIs6pLyR+V(jSvx>nji)!+lf_>&+`+wTVb{WoM(XXrondbk#fxpk}(GEJ?rJ}@Vj!h zsGB)Wc?Z%yv|8ocpn8Z&mybJ=ST7w+dG$;@FVmB!)`Q};EMCEass`YmCYh{vMz?tCjr z=*>~g%G>?@@1@Fk|JZatIZs+W9L;}UTwJ_>k>t^J)&EV*jPq49y-JV3I)J|0@5X3o zm&Up-R`LFQ=hQ8YluX)ac~UsN7}C=?IvFhU7jJ&h7ca@q7;wp_6J)dxe;tn^TKGH-{`^LXuwNVQ<8s_slHDV zloa>~F&WO{(f4lkTtQ=2j$c10-5M`mL!`4qf$Oi#z3E!q|8kl>0&4u%k~7f3wd4sr zNAhGXMUGQY!4l~oM49zsMbwzoH|PZo8Pu*E@Nya<J4PGitH!7gS4j5dsGv>QG6G z9mj7PY>vzf>J}(}i{92@Pi~@b-DdJUQc>_fxiYMPVa6z#m_D0IUi#v~6;kyKRVu|? z6$o~jdiH#Xi9yN}7t2HGP~N3g_{Ode<8^!WtLJ64_q($~%9^`w5Ya*@f1_jD z6ndG%f76y&fgG%pAWTNA5H)}CKd6bp@1Neg}b=^UG9L;4|&? zlyUeTUiH&`$;EVf{{1{}&%u`zDrc$Ob0NT~`A<*L=9A}&Lg-gJpBuoOc7LaH*`9SC z14@Z%a;-r$t%TQG%dQX(%g%OOyzP~*;4aGM!}B8~&qp)wHs-4?Is#8rI&@&)j%5}5 zQ#zM53hTcfT0re#=QK61niZ^oAcsbV03N|GyNngfRSkujX(+_W;cp>0q^f8afkm;p zfz(pVaWt<&0S+0Nm+yc50&t;|3@&~GBd$AJNFOe6$dNtK$`|FC`e6Ct?mwQ>V&Lhl zY88Sk0Mn^*WPk^2wZnq4&DVzpOuFzEcgnL(4GfwOc!jRI6?+%gydUe#zp)Ox%w44A zNQOZ2KL365Mp=W|cPl*5B?YyNUL=*G%zo`**x1(S*W2xb7Bv(F{|BDnFu}6SF;HB1mZ^YyK z0Z$!K16UvD>H4~3?{SbCt_`NF0o&GRH8`cfpWmN9=xzRkV)w%P3PM&o;yp;V9L}7!Ci#v-{vK?3{iy1=ejrCS2A(*y2VLqdj0b*T zKl1Xk4Pj|a%_e0=G5%GwF3B}c{ZpYy4&NgG{=xGB2Vr2*Ams9yD_ z0>rFZ(MhlGKT&A~9bXW61yd1RYcDC+&b%zxv+=$VSo}vGFoV z9zyNkfRCn@o)Dthei5L1%p>)z-VABfhOukcyNkA~3A@c1L_G+!hW}krAh(h6-Ojjo zAAazVx(dT;F&1uzcmw9Qs!J8*u3zgQ*5NcB+#d@eSz>aXYTHR3s#$BtX6-Krul2ks!Vk+Ou%^jDge_P4>zCf(y?3-S5F=~} znMq9ELeJdEBJed$vX+qz3UqreN4Hdq=p2QTe)xQWZ_tbKQ zFoOp&xaT#fN`1xejnxEJ#_jO+bKn~#i(5?)JaBB^I_gi5`$=QDc((Vu(qcIgNpJOs@J6=ubsFIMa+HI zI$-A}S!aQV%i%+VwrjU(d|lkmPfbs&u%-zS#X_0fV?BC^tG_7=ysRc|1aV6xw_gs0 zyephVluoA1b?S}%KJLs>u&QUDpa0uP*wT6T!lWAAnN zU?Qd1Z?N+pn@CIy^ps0*rSdq+#$?p$4-%BUntdbw>L_lqJkZf>T8qWRY`y)cl|_}Q zg@k|?v6|1lyp{5VIsudRB9IkHN@b{#oLmH5V5`(aoxSu z(bx$Q8hfYxu~k!3tI}Q?Qj+j&Zj(}XpAoLN8CqmO^jQsPH_^4}3OsqIez-o)eSI`A zgoW-lR!9Rk~iRSA&tW!1}#mvB!%8{9KkdP^$~H z`WQSln^xWcIo2N=x8uj1sxVtMKcD$rACFO9Q#tl0%t!Ag`Ukd1)u;@Eh*j!Yhsks1 zbz5zH*dP#%am4D?G$M0jIPAR_+(J4ux$7CPLdEt!^xf@zaX$_KJmY_m+$)t)SLjw5 zKNh|#iIBrL=!`zyd-L>q?2Wp1T0u3x`+#1M`QcjA%H(i1<;?psbssq|Plh?+>S*vC zOq~ec0-2=D;mxw(=}uk*!iJ;C^vl3Z;5zl!XuK^#giY1S>ZMSQw7((Lz2^!2jxg-s zg8$Ov+*}XEqNz7DytNh`ZEc9>(Gmea9mlZaurnVoLby$>;I_FJT4Zh`IRcz#Fix(!0MZfi`aT7OyecJ%WOU4n+X`J^}55fF$&Ch31y!zYGXd=buieMla zsNUUNqC+;)=LLMavEtc9{E4u&!8z>)&S@1$oZm@!9~Si_x@f&}jSR%xEF~zFdQZ#l zTP%SkC!>Li5U}N#_JM>h};em{Qcw91HoIi#KYa0t;`>xn=O7tcymr z;whXGC(3aIiuLVVfBKR-*KZTn1lSWoHV5cyEI=X1Go`{BQnEl|=0!2JtbqHCmZ{xR zJ^Q__AT|Na2)>GsQRg<%GE~-9vH5E+p9GFl{|>R*<`!$GX>D|B+` zkbQzYlMJb6HtG9pcXwJdg6a*=`4jT*81tjkbM(n=VU-0Hxf>C3-gjzacccp*+0% zBFSj2y6yLZ1po3r8nGqQi0DM&Vd ztQ}=B=d|v3knNf&CCQ7rD7;Id&dj6sj4rkKfEA&FuQAafET1t^70KEqFz%F6dH3{3 zCk8iY=ri9(U=h^hqo-_W^#S_Jd$>TNDRic{|1jpyX?;+4Oha~!P-`nK z0*0z9JX}T6`6Q#Rkl=sIp9~!n2Gc=F!-l(DQA|l7F{P|@u6~(iidk0>$4U6NJBS&` zU!P6a*?UI`yx?J?y zz^7qo!MgV^_lt-ckBTj{W9oc?zhWcBA~>3)DaDLLL(i(qwoU&|LxwpMDS!R!(lQz{ zaQd-6Sgcds_Ky2^O~gOnlGPm1dyg+69=T2bl(+c||3)7hI=?@`GGu>mo-GS|P_?F*aRwQKqPQ7F#(-?`)r^TszRwbGsWP|@jmFQF zRuhT0ma^!+kr)JyrTQzVhzDbqI(e^m5c=9dED@i@V(sIyllvfXol?hGm`7q3(4|L6 zthKODSScTr2Y-w}(Y-CmTolh3*^y zE%D30+f8fhV5Q6mv_EdcR(a={-m4NHN*6swiq!_Q%SA)s6Ps{?B#5U8>qJ+muRcz? z)DFV4sSgJrWdUCsBSd5EH^JJ!TH#T#xnw#i&NEG_e3;l$#znINypIlwpKCmYuz^eA zF~AJ|COK1*$#*{1!(69nw?BTjnBuV;gttz^fF#}ND-RAEX|wgj)F_vltKS}pcRroq z9S+GjzC8OTCev9bP+fF?{*evvYbn_Oi;rQy%8u{+MB%&{&{ih@KKGUiNtG?Gk7{qN zg6)aOYBiZ}-g%r=9+D-DtY|o$#;^E3xuYh5uMMMSPn6=!5ss>BlA<#Q%C* z3FFQiSch)%Hf}zBA;#tepGPxfciL1!(gPtR|AjZ~{R>I3;t!3LS~fm;EWFM8k{ydg zJlCTy($r}a$npFGo&WVJR!BlvLl)`#g7g=SS3)lGt!+rNjPo!b$-LSzWm|@WJCZ!x zmHTfzp_vNYN9RJO3e2hgUbAfy@qWlpya@?(aiiT0UMaSgrT{v{$XZ91Q7Is&CpI$t zH>%K60x{8JJ<3MRlttw!idc1*B5ncp&-sx~!ryg3;-*})XZmk!*>6CTJ|X_CNPr~N zZ2A7%SN^YA%Kx8HwId%mfN0m>Qg+JEineO0-!|%AraB^*c-#-4S+JDM!wb(eO<8LK z&^M^T-Ve&)HNAhea`R8M#c%6z{lbZ2dF;x|%T1Qbl8pbTm;W9hh?P{2BY&idns7ss z7)G78vPq(N(U{CbOI$i$t87g_dZ%5S3~t%#C{NYzhJDCI1$g!*2D-OW1Wu>;9jpksN_kHCLR?0RhFgLL3DSUbpnc{CA)lW?Hh1}Jg4=Gy zeCVH;><<WY8$w*5Jh(GTCseuJ1&w;{i=^O@s~%kqBq{?K%K*#jaz?_ z@+1uBpyDJb8NYf}GQ~~+YbSi^S_g+{P9dwL7ek;|EjeqDyJMLO$V(yZZT<(zz%OUp z7fW=;0FjX)MuoixMhTnlFjRV{V#`7kd6wL=O@eWM^piT)mkbuWPhcf0mru|pA*k>09a z0HT{v$U##|<>LoD?-yeQ5^J7%JAZzZA!~Qv58eZg>CaM^T)kOq>1HahCjzSV0jQ|@ z3Tm7it$NUYRqL}u75DZWmt5&~SRq^iExy23Ru=~}Uq;}C>5(#i6(fm;Ph?bYM%C)I zLHvend(pECRpYZ|cjoU94s(9=uWEn3-#)@#iNz*^)z>`%_MtO0$Rov(@&AYqsg<_suYcisXpl0^>IMdpmG!&XuC~x9p z3W$0@w!8s8AEaFwkP2AFn@{o_nY(uqS*ep5%AR%f#YwfQ|&%W!;$Yf8I zaAWR^qk6g_${uUWP1w>ePPI;gk#j$ai$%a7*L!sG`A4l8Te&tBySyB*ESiKCtJE3` zq}?S%(r-oUQ@8^jva;%#BtbZT=KuBr1aO*K!TN);K}C9%k^!dzAj0(HssWRyw~gwN z0b~?;;4UCdv;GsUZU{`J-`fMdJ*Cco_xVSqHbVuo38#s)!{Ks|mHTKE9)%95{SzUl z`RqYJBZ`l7fCF)dA5@A5-Cb@qD8ofvXTm_yY*pjGv(c;%9CzDBXnUwpy_%0B0fWc4&FiefX*M5WAY^rS-;h;iy?dI}?1C;C@ zZ;ht_=W&}ItwgmWOLw;0V){Qhz*>IY@1^kkw@Fw2&4BiY?SPMSu-dpvuk=)fP2t$I zhhfs#IEj+#imO^3^#LhN#B&Oj^dvR%yt@f9Jl}TD{p!~^9rpn+YJkwi;TxOz=~C>( z0uHxt^kc6BOkJJv^E&e7<~J0x+c{c*qaGuUisX& z>KB&r7{K=zzBr!TWZk~W3vG~p=-|j?(t|NlDus|vU%9_nBQU6YK6ykEIFq*6%tj8p zDIi{y00TAhClF#vcs7B+-YE{KR63y7J(%{(;kW)JQxpnqzR)uVw(Mv5Ok4g;NV{&) zol_W@Y4S>CUJqWbF{~D_-PPY$K&5Ra*UilhQf{hn28LxKu4naqz)JP&019t*U#Pii zYSe*bvRZIJxTpl}P~vo~V9JJSALi(g2G&Gffim2Fywp7a3i`lq&Y*j;VW<1a<`H?O z0I_iAV*)BcrNSkc^ie_cn8z$%)nyC;!=nB0&)@V_yy!!#eT#SB&!$9H>dI&6Toy-c z3nYDUftbXTb8-!=(J1=X$ql;CV{*6lxtgV->;m=vMt3LMj`;kR+xlK+ai}g~3`%2n zsswdkPSC^=^AWO9HF2H*&GA-k3V@!nZ-k~m$N2$*N(PT9`Dc$M6;ORhss>zEpu%ve z@g?nD@erjyWm@0Sih_hh;PE==2n8tu-WTRfhC^YP^#0k0Hxg29uzo(yS;;O|1g`U4 z90|MM?5EW_0)uBLe#h%-713NyM!2 zLu5bwA;%BnFn&y3@~9cbih2l}pdzM0@KX_0N3M@e zZjAXS9}{y#W95d8doqyhTwaoKn&8t3#w5na)SWcpM*@^T)4X{wAze5j(AOwOLMtQ3gImGw&uAs0`Sd66D)Aj4E;kT@-dhk;oC z?{&z9%b>!`qGSP>-m;cG?GZ=J`YWMr z5$-UG8+}U^_~XQLR7StC2wObL?nuey+`MOD(BsH=DuX^^cb_FYRoo9FV`R5j0mceBF zQBhGZ)Y{i0mN!q_bjYQW>|Un!G~GX0F>{hB4Vc@zFRFRYV!pF}%A0ce-8JZ6xbtZL z{Nnfo-J%hUsbzR}dOGs+0sX`MSNt0Hz!hEn@u5W*H#zsHKcOcl;?>FA;FR6z*zc2h{OVk^d-{S)UR^e4 zO?{btq{>3zd^_7RL?GseO@%%YXtdNG^1O>j_DwmCO^o`VRHm=L&l$?xCTkTM3fc_j zLj^5E-d?GzMK9NLT3V2VH^R9u<)b1+F3JNRpw0J>HZXKuJXz{XqL~)LC*hh;4*RK= zC5yiK!o1~@l!ztr*^*^EgX;C8^rrl~y|>o{w};1*F6A2J`d$qM54|`F$HDk^BA;Ai zm|{ATNM$}w?$0Tjb*#m> z_^Y*iT{*5B)KV;1`hSW$%dje=cg;(8OG$TwAV^4eNOyN5At)`~-6)b6xX&{G{@-_FH?cC+_>V&^>PNSOgU@(S~p&HDQ^Y`1f#l3kjL&kny0~ zuY`BXCqb|MPE97*hz0R@_V&*k={U*5qJ0{&n+9q{1XuH*R-g5FR0^SQnO#JfjtoQR z@V;i~xgow4{7RScsDPRw@5}NlH>7nh`VW&WB{gYIN!^F#w+y$K*q8xMWk2FkyLf_J zE=?c?&MN0IK`sZM9FD@^a2O%@<5C(z{}#zMZ+TdJjD0c>M1mwUM1c`AGero?fzDmb z4$0S-TL|(oqsy@@zpmK491L)-zL5)v5kWBwVJ?xrp11*d*A`QD%`6dF5%ZAnWq6aO zN<77l+!E1(_^C4DU8qWenIIKDanWZhb8aOm@3n(=eWHfPruZv1cw3%Fk>BvIHe4r^J z0omLSU2X{-MvXG76<(#7*m&kI4oN;YKiNGq2&Iz~%_0JufBRJJSWF- zy0tml!l>6+Ik5QwzNgg~T)XA&F&GFR1TTKs*<=t;x*)yR(}R0KXtiA@nD^EErhyJ4 z4@`j4nLO;l=p^9|9gp(|jt`{P0K_s^_3)cN;@9~zwe~|Ne@B!DkY9+$km}?1?zpNE zZm!l^<8%Wh2gpc@l!Fh6VcNkltp1S~X}kqtM!G7Ac8%%dvsI_|%+v zdLp0`3j^8b+3zVTV2Tib%ED|yjh$JyA+c~nbtunD0VY_g4j?Y zX&O8_anTnA$^i^2Ph`l=q|pBH(XLVkkH*T{U)YMgv(EB+cfwt=J;Ts?^W0_xb%a&> zmq(qsc9Y-HVMo-0AZUOY!hWu|qt=q7jtHa$bco+8O*JZMV2#OFqlsrKF-1kGhJ;E0 zG}Mc4=yiq!l-_?*DRu9v{y4}~x8EPXlem$_WFe9vM$&(NdYp?XZUyKR##tHgiaP%K zbU0#(&Os-Kn9Rn8Hj&z*Jx_k2ej{wMngsdj(wRhjo!JmJwOsQ1Ah@)N-jfaXY>*_$ z%EH-9=0HIJEg$m%ZYUV6fTgdEqF!;?@#TTSDPu)MZWlmO75k_boA6WusShJrgu52M zYZkwIEQ2a-f!Eo!ad)7yyCJpWLmSOd-ub7SQ)7wtA~p6uJl=OM65FXlk~9$%GWJg( zmkStPlg$=vLuLv79#2Cm5bh>6avJ!GRcg^Am0O?8caXH?MJ#aAAqRrz{Esy`G#p|}(XS1a| zGmiLt?|r3ZYTUqU!qs2$vK);>PHRMp(#a>cdKQ0RVgJUXuJlP<%7Ql&O6{G(Mg;W; zx>mm2YpmEq?o?kH*ANK8=e5hn95%{MVs?AEwI=7nL^H%7IAGxTGMP3yj_=zUbua_M z&?BKZ{L93{g@{b+_+lXM3;WhPIw>U#)&no>V3GVLh(qFdU`1CF9HYx`UG5H!N$Kca zQWEy1AuKX*%HU0iCTB$ zKtX~|rXjo$cG}i;q#!hmetZe>pjR=bMo!>k;4zy^b9{NY$udq2!u|N@ktydjO-`XL zxc@n=77H4DTMyM^;UUTL!mim{;EKMT1KNKvfAK=2HhS=)qHH@1ElP z*p@>vG;;HfbKz}~k%70QV%&3v1GiDnuOw3yIA8Q2UZIrEgXx3=8ZznnBKx3P8JXZ% zO8S8o9LO^f*X_p!UKf#01T3Q=gm{)@569Z=0C4SHL0fRDc=0=M3Y-@&A+~p*qjJ+j zD*-72C74Z4FD`0`4CbeFT0XM?7Mk@n`?NCVDGe+!%Plz#p_g@%+kzg*MpA_2xibKb zjRI(Ri?pipq<#XCse)^(Cqk_QM&mc^_9-pR@)tgjaGbXA;?Z_{u$hZTOI+k$Zsf|8 z_lkVh*s*jNl}=QE01?Za_BfEWPbC>C4BCKQy$emw zdz4@{KfrJpRLj08#@PJ=q$IjY7Qj9O2aK9Apyl=rBo^z@`QU$y!Pite^)&@#rs1-k zCl?Jwlm?Ku{z$@ab~8!Lw)M`DfLxXfbT*+c8L%N3FNh0UNU*?+5R1&RygaAB*%LqY zHPr7}q)_a>v~Np3<-pjZQsBEibR_iMQZdI=$`|(R)Huh<^gf2mU2!BH1C;`><)(Zj z!Hc{-j(hP4zM(V`UB!rz0L2BWZhfG1^)fB}wXy$Fmu9P*6Dlb`f&0a7AE+rP0c4!s ze=U3};xzO$hd}qJ(J~B=O5h6^YbJm(m-_a@E1-GE4<$lU1&Yd8N(p2jwl?rKt%S&J zW{VT53&0f1<9<$!{F44fyU4|LYjKVFcqXA(Fsd?j#1BvrfD~|EaoKDuR@?ntZF05* zOFjvzIY`zd1*lo|8Zn!J`r{+sBedW>D!m?okxY1vrJwl-XVT84ZO-QpQHW()Q2g$B zx6d15pQ)nx+<*ua%ydUe^GV3QDbr*qXrI%5JGg?C)&!njWM2(;14i%Fa z^!dnrzKjLGv8=tId0$k_yU`7$TmRzz%KCZNO|6hpvR2@~i6LG}9q!+vuGgVXH{oL6 zaVs^~zOCSO_I>B-+u-0Qo7DKi*L1*Fy_A#KWMIDEM7Q~64xhxwfiL_*Jp+$-)(1FM zTLdgRFYd2lBJg1hy$i4kfcZzjv({ZA2A$KcXl!d;#Ha`U1FLoobg3o`mE?HSOApSTA+2-2TOBW_jR+i9%IbXNim7hB9>9;pp#op?-ti0Z85x`5WR_Ctmtp8b zsvzV^lh2hxd7Eww0{%V1;FScBhOYxom;fF!yTdwbC_yy|i zhv{`=#OqB7;A+e9_+)fyl;i0dMg4dI{6NyAk=;Rm2An_tqnZ3YMpG*EO>g-A?yeJN@TO~nx zWb^$3EM!)b!ZjiFarxCedy~1Z`qh?!f9&aAu_h);Fn7YMcCJVn1~}JYpMg`iJtmKQ z=ISjZG02b-FcPdV?0{cWaPKiQxd#sV#HC&(N=Veh2%;WiaXF5jEjIn;{MC;DqfkDG z*%LGR4Vajp6;-6-`vP5puL$O;!jKguHlCx5WrJCQRgtQ!l6ke?k2Y9%8l4YR?g5K| zXpC7Lr*dww62&@WqZeV0ij>6uj@;1+t3GGE1hhzA*L+9E_sv+I*ifaUspTf;7jr@a zmZ5v((I1vyB``;eRjanQetsLzz^I_+FWoHNxLE&TCh=SIC$9gYrwk>d(QA(1X{nt^ z_glRok{Q1`T3RWxaeDgeus06M+)x*FMT}F?jOx%P{g?*v)MP&Wf|-Z8Vmi+y>UC>z zFI0**5#o!<<6W=|rD8ZU7K^^KM-FyW7$O|ZPJL0hj5JF%#X*SgjiZ8D+JJdR(Tj%^ z-qt5F)z7;S$P*bnAgKobBCiD}gfN(s*HgI;bd$4|HZDnFO**4Lnm-@Cf|Nu)<^q*k z6j&0A8Z>pIO0b8poU0mfGXqNjFobd85U7mZ9&W0TrBwDed1bx;deyF_@=p^)2<#wL z(7So~Y}09UhLVsPiRvdveF#AP;DC&kdZ@QcNnTR!ip- zprf{i`7)x3>8xBz2Zao6@C{M^HXpW{)CK4d=#hy$rL(&W#r3^xnC2m%!iq=2CXJ`A zFIMI18-4|Fo*RoDPbI}tYF--Uv(o7-@e}&+ z3Xlw=p=ABM+OUL4P-vKAHT^aGlzk?dZ|ysiV_Gm z394;Z8mm;kxjj^XOZrS558SbLFOjgRg&_guZzo`;J@A^B#sew=*a>H)uj#zb-({OE z73KlD@a2$f7C-Oz_i5)cn=M?+GI-W+dSc&uS+*~NHi7!NR}m+65sh3e0+$RD(hD&q z)B*PQxLhU43F393)Pcx2kdpfYB_s1_p9v}MgiKJxz^NV*wp9t*5TbJem_JZiIK*XW zLc`Hy5W~oO>^vG{n+#DK*#GojOhAAyMNdk^Rr#fV!UYRE_B9Z38GzUbsj>!9O`dAncOJf_(xM#}WN z31Ty2t1iiH_BCM&jc0Eqh{w4pJAK0lMx7d$y2oRg?l(D3#o%n`VK+>GEs-_Coicd> z5+e=qNFO(OIdJzOl(QQ5_kVC<{Y8CqYi0`TV#%E|!e35xtBgi$ieh({bf8t$u)Wc+V)TmR7`C6$i}2lW+gQQOp9w zGfX+S!>$0tM4CPDXHgtpIEo&tf4z!+UVNXa%sdY*5*p3}K;E1d*&MADM@^hk$>4p+ ztCoa|l{r9FpGL=)hrm(dGUrPRe@a8kiArTylOc&N)xL0|GdBG~G$Ap^CJH-7Iv$oQ zh0VIu&&w_qG4u$GmP3E3yQnK4zT$I#$BcdL)FaClZ}pDIFf;X~qDnu>5Lm!!AaN>l z*7-+>w9@+0w3@k~Qb$v-l^CYtE2#|ZMShV-oQop@Nl(u>OQ+ra=`N^SCjez@O+&~mC-}QSs}++kEj|Tu339~yQ8Pv#`40`wB!@HUtsyu9 zQdojjQ?1wqw!;bD7G*3dzb&2z-E{KxFbH{0yyB)&9yDe&xaE%zOfNry--vz@F|9%p zx7&nR`2byEczm@J5noCqCwQ7AGTp}}AdLgdj|53sw$aEMg3R&UoGm^uwLj|E?_W7t zncY1@pm}?&a3k@ktzWcZ7xkmwg``#V#bXd>yo&}t7w9hh zLN38TqornY`Fa!{k6NA;XK?Pf#%KPql~bhiD>#vlbW4JQ$p-O$+H0|qeox!x@jcKlYqGh4dgGk*$Sn&b`aSI0L3H%wa!KEC2} zg)S`}4cQ8G4eGfMBvVjvB!r}mMF!qO7&o#wu%ZxGKBg~S$Q>0q4Vf8xBMKxR5?vbT zkBdhY+;!xZ*ObO{1g3bv#Otg5v<)Os00bg!z1P5WTNm=*r8xydbB`f}=q{2l@D;Fx z#Be`D?{02Eh7!Z}0w4Ga@g^a~I6kl<{Whu9clJ=E)V@Q#zdS4~nUNbpSh!h9nP8+I zNohOjZK|P$xhMy)16mrw%+S(IMsny?>1r*8HjqBKUF@QP{?lZ>49?|`aS+p$Iy^f` z9Yd;cPGkRf6|O{3!2Ab<%dFq*0^v@bKHNG-zT!gW{kRQ?0%5cGxQl?T5CAAoCZJPi zbW;YhnS%rgP|xWBe~o=@ED8uiIDi%{0-9uyCgtr1_EB6xoi6;LY8$3%Jw1UIktZCyf>Ln_TZyf!xnc;P zs6c_Onta92mm7o@;b7Th#8z*1v6jdJ?b|{%`jM1m5TTm_4%0zFf2bMzLJ^30Ag&Ke z3AJ=-tuoLT%ETQ)$7PEyZGeJ-r=OO}E8s4%ng6p?V;Q5eQ1(+!x42}#glO&FP*XTK_fRn7N2N{ zK!&h`ZSWou>AN|~`{SY&Q2ZM{qLyorflNX}5M)7jNeaan1gQb6nq&2cG=#tvSvJcA zDk>HT07v7}(@NoB13p^0DH0Wh;~|S$1{+rayoT{APOmtve1UO^LBbr=>7I;*gJC~# z1s|m@;DUxM2m{r2bdT0L*0LMpFqOS`-A0GaI3cB+H&C zCEAE zf$dKuhyhd#FlfKG=z^wcGOsOlAb33L*MhqVAXfVWfsG2#%aC23S*!vJiZONxn0Prc z!P^h&gA5Y>MU-))v3hZ*vA(hN?BdrzE0FX?;xcs@=UKq(#<9Rk+ZI^!D_`S>QwZ&f zooUfdycu8w6_C(ZTqPO9Tq;w_dv% z5s>yr+a{VOn5EMJ0euKrp5NSV05dioBYI;uLJEigB`TKLEg6Q45TvL3j==1Ghsf)C zxBm``g`|rE1590?TO7PT2!oo&Uoj9rdZ9t5Rgi$gs$r-N4=6zmX=r&j18|ToZbz3{ zEQSzvZGi?uT2|1lrG_Lm8-lC3m>0V_+XXU7Ss8eTPnGzia?;5k=v3s5*%hD0Rv4_0 zC4|AdbWiU}4W@fYSgegODaYZM@fS2IXhRX90YE3VOi{nad<3r`ztU|V2y>3B+AnZ> zq+Q$x$_yrUj0%`H^7_*AQVvxbxI=S*99CFvn9LWu zONjWJhHSGp?Ax$1SO_Oh<*c+QsF^sGu6^0T&1!{m9BBmW94ffP>DJzO)Q1PKssgav z*g9W!Z5-F+4dsXmE^`aT*fj*ntS*A{@D zc&@+T5E3 z*|~LT$RNF6jpsdXIvAgdX*%DtX&L09bIJicdZia2b=1f%=kdHMi!Uso4#4MK3@H@F zJp`}s6XGcjOY-xzq!oBb+#Z)(nb0X-5C`$ycdEk=aiKC7=#Zp7glw*%|7M@49j-5u zP&Eh_9Gt?V`5j7*Yh+oS8O$xZC|S3k9_Zf+4Uaj@W z0kY85@Fck|kUptZzZQC6l*c^9gLUB=(f#-PEKFQC7wZERO*m&j9CTo0e`+*NArwbF zwgR3!N5gaCC9~*YgW*WOnQ=Q7SccJo<@w5Ad-$an2~>&pit@mZ)79h%&`5yZ{dWt%C&?BAtG*L(te+O}yia|7fZ;lQJ^`p~uTA?=8E)5k zT1lPq<>Tv)PCx0j9fFQ+Hl<16X`|OgoD>1Gq?b6kdAt@#!zt`Dm%?5SVdn^6amuz$ zKlg^?%B`O(!=}!3k$jhmCWcz*n*X8e{Ss;7>swdktaq;Hz$hoy?scnn#AMwb_QKiv zQfP&y{czGg3GOgdxLxaAT zFj!aAautHZz}Niylk~-VSZRN-aG}n3QLY3oVi_ql%f&7@NHcEz&$)8pui>NGW~NmH-WnE$yrH5^1}T zUcv^sBXrlNeX4CWFpxRcGvVu3cT&=w)utBbaqf3}znm>nK-DRH6p?$fdL<{liof&P z7Z`x`I?sRwHHyoPYf1CUH@u_bPq&(Yu*%s2w6-m}LH8D&Q_+SFvpPbF!qWjM53vU! zZ*{)Z$P#j`!LN*d9%!hDdq~P|5(!nROuG+dXlMup$^nWR1{`4sY7a?LzXQ)Sh4EAq z5qiFKA!M0vSIurG+hOoUcqF0ZzE@V~OY~-}6dzpp1cb8^pH<~e$>f5)X6_Nlyo_FD zjM)^0cbqdgkodrvU1nf~W@Wn-VdskL2t8h~F>Cq2&fL$(4>Fp|nvl93)h+aP>=eod zo{wS(5{@Eh6_wh2^c3zhy!~4j-LVfXR?(;5j*Eh!sjd?*e;}5N<;WTfm>MX<7U|V{ zWEhS$E@o!bAS_N)q`vTtiNVm*)9V#tEKAQMT~~cbap>>vk?%A7`BKn@19}{;hU!%T*%`_6~#OZNY~BXdGgo{EXJf2fY-sbFMv98UV>q7eIQefc^M z%WKmT^=O^7rTBZ@#M~S}aWN}bSjRfTpU$DLuC8u+Tb2y%`yq{pt*if(Xrq-8bw62& z5m6eH$iL7f!CUB+d#qu?wqbt1^vV&w{fE9e*Tmn?XA;Rs&oVSK?<6P@=)GyM-(aae zXoTciADw?BvNk!ahszRaUY&v7ysN+DtRmWe>ped#milW=&Ynu%j^vr*XJaD|j;FBw zOj7&D!(~eka`2cnP5TYuw9gNim{ntG8af#fnY?$dd{^cf2IFXy9QR}>({_d+LvL?c1KNVs~MrPRGdaaeSEY|Moj_Nln zd*NOFruZ)Z0Db@2zB>TnTIu&up4GiJ_u0GpxAL|We|nW2v1;tw;3I_{*4TQle+V6g zTaYzGT(^CG0x1grn|Gi;hHtNK6MAMooT=@lc+aR_?3eWzlG|#F+cH5P&fn6Z8NUb2 z{X(lg&)zLDa$jGY^BYZ&6XWBDfF;Znq-9{w739p!ObBZLtQt_DirPTnaA}5kbhf;d|S1DXbe`U01ONCZlISe;fcsW~Lp0CRYn= zz;a_)4^#z4K(f7g;(ELy0v49jjSw>A3}+C+a8L^F(O=Cj?DnUg!h*C6$62sAS%du0 zy(+mX^5V7gE_2bk2ArWns(IL)&*LS2@|QO-wwlb{b)}l?zf*}$=4>OM#0Dr&4jm9{ z3Kj3LQ7jZCgChz1*52e#_)_-iPx=gMxwWlfe%0mfof1RnbM*nc`Lx>J-vllHUTU|l zuDW}_=#(#)Z9v>&wtxP6{TGUSdV|a*VG3g`ZlwbPyo*B!#kayd`yLFiS(IX>OV@il zgBIczjO+l@@|A9Op=TF#)qYgTyT62!;8Pl#HF2_?om`y9(GWuPw3e`m0_9P={(zZx_2i@yJ3M?x?JUm(WXG%D zzpZ}tVecO5J)p!Y>bJQrjR+ zkqMnH7ix>$SzjmT+-;OidGaKw3T7UM64eDvWJoa6*w~2JNX+AygUAPXt(8rqSF_jZ zQSM2$X|I406lV6>{8iV}&DoaKWRBl)HV_=^k8Xh+;oxa3;qk)>p7_hV_ z9{5>==Pyitd}8(_CW=6!@;*C^Dm^v4yNX`+w8;;qMA5V!0T{p#_P9x<|@)EF4?Kc zH*qql;^RBOYR6cLsiN|ltdcW)C|u~oPhyt1FGM!u@?0a47qoedJUi52l{{*WI&D@J zG~V834^ZwdNX*%bH4S;~alWwW%<5H6^U?Sw)q1hT83(Uol?J>BWsfZl$T@rjACZ1m zKYE5d&ICC=e0(h7nTSBNJo?0vP=H@uyEcAj!x`;O7Mhd+qoUTkjh>8Iji@<_UCB;# zI>x=01I)=oB>fg^&Knz|1Al~dY>=xrOV5@aI&zJ={CQk{W0t7ha#P76J_3&Q`q2@~ zdPvk7=&bAb4tbumg(wQ%ihGRQK6xTDD>5ec6Q8=ZQ+2dec5aH6;idq zj?NeL!ObzWXC=k9G1Az}qlUFSP{M&`F4_Urn5`}i9pAFOJ{{Y^JVOkGL4*4penqMBKgAgRslRrubwkS4FSGn!c=n3Nr@ z<`SZ3H-T-@J|29}p#j+Gb&Up=bz!bx43wIkJhk2yKxktZDR?ohp&XO3uFGsL9f zf$un%__+ROPRmQHf#VMCRS@50MsGk_7!^V|_QrNvM1o6t8^z&Wo%HMv9qhsiaSGM% z?-^JvR1oq9XFL|brW4-geoU*{Rc&YepqYKB5gxq*Jp0f~Pe9im2WN7+W74mJCimt& zo2~2Tz*Zpf&jVF0N^-g+jXfs-27RLkbYfth#`kLmf+nMWGZ1T2QgsV~8Xgu@<_--T z8{0~&I}W&E5&-CNx?h+bUItLj`kmGIass2#l@C2Cv!M7D#3~Vi*9U5Vu)a2FWxf65 z&JTbqW%aAM4zY85e0;IRwc>`#l-3r|ctkq}2M71Y@hyr#^DZ2G<59>nIIZJpwt9qR zzv8nQL;@~H*vIt@hjwc}W{W1by$L&I6~WnIudpN--pW1i>`Fa=rPg4_|FyExTQ^l} zJ>wR8*@tiFdy&RXSv;qLQ*GzOa*@7KH~7gnX9?IV&RoZ%K-~l>w(tpd9nk2*Z-rkQ zGo)fp*lhxtU*Ge^(udX7rWdJzRYXopD@j}d>Sxe)pbA4VPmx@E%X<%zTM0XZ9JBAP zcWs#?q0hain$JOHu~EUgvXA-Hmv`-(gYLv^xeEM# z`VV?Rw{Pf-r6%_+`-M!;rNtk-plTi$1YxvWC0!kKW8wllDNcLMw_P0HI}L6^*=n*z zpUvRqHSc*A?;5s<;SDut6yzbsL`v@Z$RdVmlQsI_zpc=XCR{6fX^3&KjP&V%OXRVC ztdCNs-0`zsoNOPFvPds?ZU%@LxCo9ApcYY7Li0|GEM( z#`g8YrHiCQRKaV@M1B2<2M+@em0S%nP%1n}|8xPO+^P8wx92IyO98sP+00uIEw5JP+ZD;RAy%FNY&GJ* zA2I?0`t=OwzzgB!guaQ?AFluoh6n8p%{)|^Uv~O(HOj^Kr7(MW+tZ z1_sCMU!Ypumq~uAB)0l+COP)&7YQgbVWyFZzI5NlW4<_W6-F}0;G562&yucXi&%1U&=MhWG-Y3ALT!U#$~<&> zZPZ5}LGSPq(mHmZpSy0ceK3Eo>=|sjBqCC3h3Eein_{}(THcK5XKnNT`8vc$MjEUU zCE$2>{!N_wXi3(KC85tQN`rP=5dW>NS#@JF2PYuPxwlY#GvqrpY7rDAub+fh$c0#S9C!=_K+ZAc`Ap z=}AISQ4y;V%r2r0T_+YC5Vi$9}OnvVUc0^Ai)@TuAFe@8(Jz;^1IT$RP9HH!ofjW9%cCExHGMoT4gl%CXG3n z?quZ-SGB|7YV<^d7Yo|r>7!rwP)L)1aL(CT{xXRM^ zo$s(rxwj8xvEG`?3qGd)K8rc|HJjlb7K&!;O8W@3v9Dso$;tRE~(*$-v>O7+I zsCZQ%5iv1y)~xAg5nE$pV@lP|7nWa#Hm^%Heqg7CfS!(a7Atk@Y`Ok2hg98`l45c) zl8DR)JIl3{Av5cXFl~)-GK(53OJQMOoMU|%1Sn;T!MrvGZx$S@)JIdiRGqW* zZDLA2_L;FiXqyKjO^yCm6D$${pxKUa=3#4f`z#H zfyj9M6v^sA*_M5t=EBlwZ~oJw$2xVry;j(kQ~*nX=ompV>PWJy*mAVMrU+igb;fJa zd|Lfg22=MSu>p-sEF6-kI2_B|MrVdh6pX&uFRQ;7>)4iDkIlIUn|)4L=PPs~n`Y>Y z`o0Iy>yN8f2r^8w6&Io)=`w#ko4QZ*YIXz^o6RYAcxH>YjeC+K9B1Qko~4c1!S{@* z`dhS?$>_CXQ(=T-W!M{`ewo_n(D>Z)HPn4@DT>wXr*CHZOtHUUi{f2dve)!sn_X}XepB@oSd(_c-y&h|A=k*&-~D9sHAEnUMJ+w?Hw#Ypg2!Y4iw!2ZsNKQ!|GG)m0l^FZbb}R5--}%G2Qo3CPxqwm3 z^JgSwW`ugMv&RdTYh$OcMiy~8uP^#en#d9+<=i%}=VSXu@%^$+`|6_1r3|(LiR>BH z$6iuo(-s%ij`a3Kh@wQ< zD<^_ILlIrW#S5++gyQnK1O<2;`eDm{ojtyZ?L%|Fv`v(}4L`;k+@$sFPPxh|qm=mCH-k=XTc5w0 zpgwjXaMo*LvgW!kAdNT>ma^#Sk^1#sv0`GYjV|KksOYx=ZhKF^kk}C$(@MkxYtywE z%{6HXJ}>?~wm%{ZYTyb?KQ?Jsa0Ds7+Um~hKE=*0{}JD@XS$Ww-;%UUhoUp`2xo6S z?Kk&u!UEsG3nvS_bNNkvY>-B>afThhZ11&4>qZ)2)YZGIstj;7n3 z_8Jw|fsiHCNH%sFOgD6oZtq1=-(+Xf1zOsNe_8dcCU}js9@Zum@sq(qqHHa}T%UE@ z4e@+b3GlFgLTjV;uQc>blgsI?==PHX3t?Nm{nadYE(=&Fieb1mqZWZpp4s51a9g8= zlIfT63^JP@4vx#c%TaH&R$3&ho4q0H@E2=-!AIWrTKX)Fd`Jk}$ zQ4xl_sHA=Z{Sn;Za9@`%?xK;83#CL1E5vCioL_^>i@$TaqAU@(3cMI=ZJa zlI|8w&(^bZcxKaSuj8KD5A4XF|DYu^P; zPb8U@o3K8?pSef2&}aSMp`ilmm~ZoJ?gq;K&Ydt(U8%*Ii_iUy(H2Ptqt=5_!J)R` zoDM%G7{6oiMq~O~?#DDZy+hmcStZt7YyU3>81>%?Aa_fu$v>wiwcmN0_huniM;4_& zv4cZTn0g?i{yPCUV|{xLJGz1jy@~6|+SJ5V8I1bx1aJdCH4RmMO>7TNQdsE3HQWDpk%Js% zE_VoE)PE-cXZ-KJ${POXDS(Rvhh8TcLq`2~0{)f%?(6hI<@ElmMt|mi7YU~gMtz2i z3ORuia=U-`b-#2?Q}RzS`N+SE{P%3_z_a~#0_vFa|L*JEtAEcfwg7UG)Z`-$pRDw7 zD$awsMA05@Nf-aC2Az~aeJKo7C0Ll4QIxKhUpZ z5)y`iEyVww`Ni3pUql3o$JHNezU46!N2SG2dhM55eTGPILN4dnnJBx$&7exflbt5= zd$pR6!%Uhjw|JLxKc>*9+oy;9{h{tmCi?5RInel%R8xBiT2N+`r8{rA-oC|CP*4aB z3yWJ;GA98QdIxN+0YfNlOSb1=Z#w%Nrytel+O{eYjT_}6NexQPRt5b@8jGuQr)Y#g zW5nIrLi~+lLBUkr?7Jrr({F-C5b$=)+~dr#MS1u-CV`!vBf&mzQPE0hOa%ftn+~#` zoR`rlub*_tBgB>ni2a^dBPC&CrU#2;Ly8Nh<+9QkhJS@jd~*{);Ji@sy^Oc#{4)WM zK^h5~j3yxH0EmbP_^ zkjO9n3{d>lS+_jZ=)r^x9!+l&5r&GL(Sb0-mR}y6^TzdB_U4fnZy(tNvcvaLzd2>p z6F=Y<311%*ijIy(L`CInm9HjT-`NQQ{(WT3aVruh?k2R`Ts8jO+D%W literal 32422 zcmeFZ}6AEFchih$37@+tYL_9mi9+qq{VA)m}r8 zCP`HU?A?TVX_o$dY^W`oG?5h@$Ju%yu{-0m^nkcp(LG_d**YT>2eFebav&y@>@g(r z^aN$m8%>iSpw&V02>Utozkh-%Ip4&~=;|NU4*t(2jO7h3h2>@a zGf9EvOIwn7?tf=HI$erU$amQs#q=%c5tn%^sg+Eb80ZQz4aS!48oy=J-nVWqkqSz9 zl0NFgt;iTl#Z;w^sVdyw1Y?-M7@ARI*%*ToFd#VWuP|*eWBUHSc&q?pfCB@v&n_Kf zcu#^5vaGWkRig7djGOaZ!k=}Yc32lYSWZwIYdx7OnQQeaXs$>U{VeWPo#A(EFp&II z!KnVVMi2~JyTQ>!;_~0Orhi}Yw3;M}+uD6j93@U>T+aV}BdoI;prjFXMf~kg(weS! z7%kD```Z`C^n2THF@)T8-tT0+pQ~czbZ;r4w!m(**s#_nj`jKHtRH;s;@pCSRD#b< znp~YzEPs6D`7UYZ^_TQyhDOp?nA^gTEl#6@p6f}IVFeh_`wy|v*al+mTfaC8(sIH{ zxj4<*d{YD+42#QN59frGx1HO$t^Mkpy*QqB+MID2(mC1~)tc3_bNtM28&4@)fzOX+wF*=R-t_egJ53_iF{3WAG1&@6J$4uug;$LzB69ZL zt{Zpld1$@%(a4c#b>db7K9yi&_u*zmyY5)2f!pM(PwQu^nR>}jUUl*Pl;+Z}%tA)8 zsFFX}1C50mxt?rIF6CGeN}gs#NDf0J1_vGrIi@waZRXDh+?dEkkh%REFVZToJZd?f zvZt}+F>Mi+8(1Ao-_%5+NC|1h*8<=ETj(SZx2b45FOHzVrx6{=%R@%Do~@(~mWR@M zvu6kFurRugn|Q1zTW1Wf45ZG^AdBP5nPH>t0Rbl7>v=mF5b-D)v9Tj8W+D}(8F0ty zhZd1dlb zYh1*|-%n;~H%?9KtVip=dk5HJdEsi8!E_NM9DjW82VQioe|^BB)L2Lr_?*W%MIV1UVm6EC+Vlgl*gv(4wH1FCsCjT?++6Jjc<;8J)V}Nv zzvcOopT?wJ6Jlg-k*PKX(XZFYv%Ceg7kzvGc=Dp7HDaG=h z^iBj{n|h7azzod$WY%LdoU8m-EQ73eldJ8CADKEM-=$Ph&r3zSLa&3Ba;qY%ft3Du zmLCDUd2M0r8rxHKCY(gm(A=ZV@l7xuZuP_DmCtTP?xy=4Pi{=s6ex#Po#IfsAy69# zh4}E6g?D&|LsB=5-hwN)OP^#;)>t<`4x-I^5XiV69EH*(7IGEcEUlrwbGSLKCN%RV z7%QsFVRx>TfK2LQ>nSuEv5t{*r*bD2PCknJgB`ZO=g(ZC%MDIsUUT_ z4|WWXA=0*PtA)ENK~fvrl|-MZ_-$fqf_=Q?AIOpovEZxQ&$qP-I?k+Jy3M+ce-VL& zfXN{aDEAYqmHFsoVo&@O+qXzMg&`t@;uo~urh^pkQTMX%pMolNO|GtI1pL4B8#DdS zZOMlrg>P2}%ZQldnc*bw7$U9>Mvx8l^Aw!`fLqr|=T8!rMMNWbfDRL_2P_ev`jz7h3xKM)`OyZp-v zr3XHqFcHt|yMeTE0$EUrwyR?!9MTaLY(_oqnItYf_eYRM9eS}k zy%FTfa6-bR`_op|mHQX+0a12NJIWAJ9jJ!x>M%Dqg(n6w(WkUw#gc~m!PEXh7nExg zj|ate*9tQI--_P8#9Dq5v#=@v*;JGvqhqXO`W2|)tHA%5?HypI!N>M3I5-JxZuN}fa)#i5*&mRt3C6*zxWg>fle&1Onmm|;J zgR+O=u}3^6BBK=BK0RsPZQG<@gGa3qXpmf2X2GK1kM-fuq!0L1qNk@j&AZW?w@;xE z#Tx9_^nb~b^uv6Cus$MNrecMZyXG*}Um-SBQ@4ij)uHg9Du|_qmRurh;)g4gRZ(Y( zuyf94W+5?$q2bHEKlX=e+TnYZseKd2+tVft64%e~8FVOLogbNG3u}~0e`5=>q0p%A z;-RR9FfCBtc_of^fpZ0onD^m!xAjC(HM27xs1{>i%8I7c^7BB(f~=W2`WPR`cX9nf zs={7LTe4r{b(^`XY=9$PDc#h)4jl28WX4wK(U!$)o3#sI7dr zImb7FWlLQ5k~Iq0UH$T0^4ZHtsnFLOE2) z)|aF2(8punfr$kbn$lBty&Hh3Ha%{{HjlJXgH)rv)1dS+DRD?DTV=FS7()aTU1b8L zU@h!f{`2IVk32@Kcm`(vXL;ag-iQvla~sa+j3Q5%h7jE|82K9a1bYD@%4h%|Y?Pv? zepVIZ1-ElYM}bIL+;6LS7@(k&a~9yRH@V_Y%IHq5h1 zE>;*dsB))tMtQS@qeMOgeYKEAc2iN{nnq%spl%tEL=#dA|B};tw_8yDA(1@dtsw*6 zedein?XJILMow;la_3>s{5nFLin^j~9u{>h(?=Mxnq!L|%&6M$tx4KF+A<3XRJbiU*@`c^Sb}vtkvSWY9m| zi19bbur=`wAXpKi8nk3nT~Xcfi2HSdBlJXNSs(D&b3doaWgOlY`%&oj#~$v3z=u(7 zRpX_ds@~$LY>q|Tix86jrYZ-C_AaWGCKJ?ZR72q#aqL@JGY!*k6_{rr9=b!B;P!|Z zXE>ynJ@)HM93~6F}@&CMsaGKPF0nxkV0~GGEU35cPPQ| zKFVexDARdCd4$M=?>YKZ2$X!Jq0k}Iz8nq7eHdbquNIqNI0!iwB{a9j_~s{Ztc;7@ zs4y>9<8^x?yG&U zjW~oElyfWm9{->YtUr)`1sor0FtJh9TLwYrEIG1)&);ByU44W(?r9DjZv2^#N4xKj zp>%`_44xGzvXKj+2tNp$z{YLc!>PZY1oKpEt=^1tWr*z|x--&Jbr1*h2>%_VLZ4ti z(HX`EHTP9WBoxN}6-arhYGTSB+btkYC{17IP}>z7Vy0OgGs0gF>x3{oBA|YWH)O{? zgs@}4Gt$~OYbub2z6Cwh5NwyjT zJC8A562^novTTr10e3}#@Geh7xOo6XTTe_uJQO)TBhL@+ss%%vPMR|1QX zV0GK&CFP-TxTX+nH)Q5gG(@;0lH@6RydGtJ|rt9P3$W!Vo12_Ge|eamQi*-)h@ zD&>N7vh&kcALWzz-A;p>Yt8vKv?5!Gf4d1L+J21b|MM?DA_cHDvpdR7(Ek>J_ko3j znySk?KVpHrI<#4zc)b4aMUkym(MvhoEq&WnRj0u1=~jeJsvuhG1_8k~S8r*o^{gU) zp~M^Sc35~gD2D!kui5#|G%@U&?@Jfe(#d>YsX^WY77#h+y`DtT1teMx9$pU!!wcT7 zJeQ0=nsGrV=_#$IG0})FM>RO4);eWsmwX&Sg$b>C%qIyt?5}uT9ihLhD&dhUnfb2| zB-lK#7?!-!W)uxEHCDK3_E1)nU@>_URDf?WgMoGz+pRPTB6ly7Ce zJiTBvO$7b^?ws+UnA-UUm+dclC-L*vC4ya1d$3(DD1#N{yRMs>$U$$rZ%O#bu>O!f z_{PjV`S9|9_D!1ehgyqJ{x?~NhriLMd+5vnrIVQ@=tMA~(#=KY;dX;&xiMN`96=?d zq$a*-l1XjJqff7r#y;zjS?f`8c)Enf7xEm(VmwS`iNJA8;#73oK$r#a2)thF>{Fog z8jn{}<}^X1+%IJ0gk!zAKK&MqfP^{Y5Pp=r{1wb@ZaXVF#JU1m7Qd`a z=s;-32l%vnRD8YT(N^vv4y553wvRDpofd!vdNxue$fMN(9pkD%SZA!u`3_3WN7T-E z6`a&bW7X1n_XR(KVBOC?T3?d$g5aTFCUNOXeKN0{z^WL6>opFk zg>e6>cP|^MFFSF|v4)SsEQr5v%ouQ*OwsCsSMpyG*l8r)N>zT4AoTxz;yps^mgp(R zh%>rvZ^*eok```L50|%1T>y6jLaAxNzktoI%o~sW93n3LAS#iCs02licL%zV;WrjR zOSJb;XfU{TnI6xk#MGo%4(F`T~SrV+Gi);jFz9wczMir@}7mYwcfOSA}BLBIBizcfvMwDdYT1Xx$RP-lYho| zSNmVJuxDcsw|{w{^KGsrD*Ys}o5*rOkO=piYeIC@4s6uDx0oE07lkK>qiR(>if1$8oapy@QC9Vd^q*2q?b z7*po+GQZ6oCweOl!ry@%%kb`2R@{SIFAMix>d_rzrNVz8$Dm5^ETlX%x`R@KGsiBF zP(T}XK7rqNG*S&U=%BcQ>cdZdMS0cREXoxl-HBQ$pUQKpcSJN2RptIlzpjjFdekG& z^q+Uk2=k6@8m8*ca7izUxJje#Kx6GjQSwpZ`Vc#$AdUE1-Vv-a&?bz@K;$j8+3DaO zmdEU087<8y*M~&(InUvrY&u9PpCv|o^{}fB#K)bl!umJeJ|9dCi6wc}8;vfhxIVcP z+Ax2dqYSTZB-gii9{3^MAL_|aEZ|lwB)P7z5~2bh`z+KHTiivkQHWr9p!g$I&u)IM zCJsp>9Xc?96R9aH*Z;sg*B?K%X!_4Z2X`DVqr+N^gKxX97onAzXJ<`l-^1funw8Es zl_`+?Kq;`*?-!Uk=;lkWa7Z%FqVZCE7bsAOTG!hgSB(gQE`Z|3^@xA_a@~0-0 zDOcKdC>`o(Q=+5B3hcgZx*haC#&_zzC&P#|16|4ElDneT2sL;$J-6V@h9roqkRK#D zx~REAo?Ko|&8S)AYg~jeb7saKBJcWmx;?J?@bJ|M29X@W`1VJ~5#=`c9L#KEj=DPk}YeNAwjd~A7Dp8|6(2j@bX z6hzQZi@pbggFX&T{*o^(j%jCTuHj26tf~Oqv32&7TM+w?E;y$f-C9*`fwqvde#Z37=htgrLTC7fufS=$w{>m0iC4w6;KlO&DT0k+( zPqp@`(&tb!%unTpDHLde^FDEGH=nM3zO)tRo2`kepVV_b*8!N(*7)ye(_7L1Ap4^4 zU3&SdglB7bN$o)H@boJ;#@k5*lc!|B)XX?YS{Wj7KpS|Mn02j(%4tNIuN7tF_(cwC z)^c?`y)jmn+7tOO7lbdbGJ*uF!Q6g^v8jVqMN6nfj}6*-azgYyiR)AKs~`C@UtH_~ zHY|F!oKWX9FNr~#aR{jUjF(=!{>OI#9eW6THq6XV)#3G~UtOGxFU3fe2jdX3x_)9( zAi$t|-lvP9-yXj|dVzuJrQsx%2;di~1QfJi9jAI9ZxwxUS=|6YC8u6_S_S}WO#ILO zuJ4M|NZi*E_C2lKTm*P_e~LiK#RfXiubA( z;Dxbbf_=CK#YhtbiT%y>)!nPrpUDS}Hwv%KHz&Z#eIDcrW;BUl@4>v%RUfIIG0{ib zA<<24x7|4tj~VCC64^5VK95#eD3qDD8p?%}-2FkZzJ3c)q?y-$m%IreHFwyT)N1*I zOKtYx8(Vjxtqe%G+@>Z+G4YcZSVAEh7w@p~nkb3T6oe9o>M1_?WA8&OzkR^xG^nPU|qYCqFhW$L>p zhhya%bGwm<)O^@`CD|GdeJn`q_Q&wtiuO>#<`?}H7?u81q1}L$coIt!pY1wPKn<8= zI<+2s+~m9e{Tu)+GZR}6S`P-r1k5`iSC;kBzt}TFjn^rS? z_$_+wkxP8bH*#tnos6I85wIU?^dB!XTCKIX#N%!3Fqy6}lWGMpF{fc|As`d70h*@I z%r&59y)sLI#Eiv(uQ?M2HTpj=30n(gW8-FdvoU4V8nGL*ZAclwutfWscH1sSDqqN^ zzwPI^Yk~CubYT>PzH8UFKjf>X7Y|8ZJg;ck4?jO#UxMU=S#8?y=NhekrA&^U3l#up zUJ({wR>d>yH%_mduA}j{nh%dCK-{V=7<6Ts7tJf@k=c}9pY%z&VjTXmIdQ3%V z7WL#+zwp1#3_!Isw?P{L@TX8`KRyPEP+LOn4hJ%Qc3a0uMRU0{ssJ_7Bod!;ub!x^ zM6Y58vJGk)-4x#2$xrdCzn;!mYwP(w^4zNG zJp{ClA&;(nnBx*=$v1)hMCp_7O=~ie$Xt4f*aK4UeYlnlDhw5;JYsWdJIj|mTPDWA zw$Ajc4~?XEDE1)^=ZH&$uV?l+4}$hs#WPwLEqCijXT+w>6?P))!Mxm@iDX|Uv|MSc^n zjJXXt-WdHcsb8$kA*4nhcHDtQDC}twhhOi!j?N=!ao?UwQfJaF(d7}M%K;eHRUN1l zZycv-#_weIwgH1w*su!&ktt)cY$$=-u+o2z2zWEB4WMCWnr_2mfn1EDV2e>ouzjtE zBZ)*mPZJ&v`lY2N@mHGZ7xE5K8MHrNEwlV&&S%Ka9s}3p)HyH7fBL}GFAu%a(KE?2 zsIlSzB-4&)n`w)uGoZtIkCf>EYKjoBjLX?V=S4L0K@3Q?=P_t$5Pnf6;BQ1!bjyv4 zUVQuT#Rt+~?=anD59M5l+rHpOr${r}_L);9Hz?NhY}UZHNPE#H{}U%hlnD^Fx5 z3=cUfy)GOb=IV{a+;@gsqy*Q-@^!THjE9%*3H0IS&cg%@NNjNyIC)l2WB=sXq*AhG zg*UNFzwbT>rSpH&{cq%@O7asqQZ8NB;fIXRF5|)Li(v3S7!U#!$~-@rMa~PjaG;=O zEId-wZDTnHzWAOye4r{hkv?-SOz?q9E~`DjcpWveSxcmYU`^NOo9R)~zW@zU(du*3 zl;g?o_pcMjgd|+s{3Vs5BFx&C?sIN^q!%%Z#dEU9jBaIyb#Eb?3VkoH;X6pH+c^O* zd|S#&?r?R8m}6*=U<*Ne{Rlp6$>dsN`-Ux@gsG$?mWb90p|O^Lt-B$=anM2u0li{^6(IA>zJMGSHkV%$?95DvQ>2x~`y>pGesTJrLr?5CaF zN9i>29WVjiEnZY%rhH)g5j(E=drPSqE_(S5X^@3bg3DKqwcKG9o~ChC#5 z|F=Jf3}5`$6EKZ6iprBdBk^SX|K2$ThMe;WVyi3k?A@0(H793^6TqDb8xzSW0z$Rj<0kpW#c+-LwhIiB^!4$)oYz7yQEu;F_K zX%$`e@3uaFSo75VYKyHP=DIU8neJgVkclgPF!kE1cX zHE+?2+HL=o|2(e#b=>~yr((TN<;|-7$yzDG8ioz3O=ng`_Im3@1*oqfzXfwylu_|4 zH$FEJd`iACA0*h)51np;ag@Kf++5tWU&ntSNIE}ONyU$A+MM&r>!nj`7JNAcV!wl! zuVe%Da@od@t>e#xR*XM#2IE(2vgrLZc@0!EpHx0SlF>7Emh<$!S|+v~q%JZMD>4?b zoffqHNwL1BvEFtO9a?JAjPgB;4$T_T-`gkwn4R|$^Ej=qdehbMa)roS_*BDC4O2>r zjBdV9uJurc_hwl`t$8Ob9mqd=Cl8Ls%{Ge)GSHW22N*|gw8G2`3x{9?s0@mLLuAiL z$I1+dNjUHoR2n^i7twUF)9iLUXXA3sWWIP&F8Q8F&vy)@{pNpz#L zX7)35l#tSBF^hx8%Ra+aLrMW9P93H5Rl4;LRM%0K4zry2RIJbd>kJMWadw>|Mw7Q; z0Ovhi3^lbZ_4iw!c49f_HPlubbf>R$wY5EWUH@n#t|ECVeSVhOv9RcBnu{x*f5IUUJ+U300Zj+)9q;S2RgCmzbD=XB6E=a6 zHV-3d2?=JbdDWjd+)Ecw8o}GdzIYA%S&_bt+2)3+dWVwVYEmXcAO`z-;;}ooy?_^J zRA-m8)3`(chs35Fk;zVfPHx~rMA1oz@@P>>+322@*Nft$D z8WJdfs4!^aBXTuFUyMp7U#l~M;HnZ6>M%S&=ib4*oN<3nwM_Z0~nhxd^sNr>O zXM!d^7Sqgb&j(JRy|xMMdYN-4#j>9qn~rue?#3Sdp3&hnDE=AHb4OZ#;Ue{Bu8^;% zr9>}tw`4K5x5T?l8ND^1=*Zuvq?oPkf3w{%KV|{|GFowe5y|V*CEMUKY&_I(Zl3>D zd;@)vD?=tphOg$vuq>xm57s@hB(dE@|4WVYePu#nT#|p%%zC`*=bL$K8UN7HMPZh4 z#ar|9%@w*l9Kt5TmPmlLjj-o?~E;)p+_kqmlKQg&sI!3Mb>vQ|B*rUZd zS|HjvgwV0RoBFr-&22znybvDt;I5g<-D)HS@Q>s`IA{Hp&B~uP6rU=eLo0s`_+LUG z>S8+^_U@DEbxY*#GXHU}PsvsV$!uBYXgDP2Ti#Z#^R5A@O%w%d(hRo*0fU@dNqRnE z+h}m^`R&+u z3?7I4$Z-4JNm`NI=Gbi@*JofB5W3b_X8gxOot6i zYF64%B7Y`Wb$=>IdmDcH9!2bHgRWZJ-y{DOC&~hOkXzjMjnR^36;T$}^pNZO6d-~K#Y zQqDCXE^!G62bw_1dq9~mIM52jQX5lsB^PgIFd&Y8)mJ&W;pGohjtD*Gh_ehEmByPS z+l{e&$Ik&9Ejx4GS6=u5S6;JYb)Pnjrx1U+sOf^9->qi#7gP1~nJ=NUu0V`QqT^6^ za9U1vtH|ra zbm5WfntGX8`&?d~KH>l%D)boT;?3DBCFUsaDjSEeP5rO7tM(PG`FYBpMDN4$Kiqqm zvoqUV0s`%g@rq2|mVeI*%+f{OYTy1<`ZV?TWFm~w025UWe+Pwh0ebj5M=rv3R7Z~m z&j0`}WbF+>|MWQUVzsMY%3&0FK@%AgKE`HCJyBW!v`MJN^Hl3MWkj83M8ejs(PI#j z_RurPCC~;oX%i2veSU0_MusX6I9!Ejf9>L70CTG9%-ImZ zsQ9MkfZ=`vE-CK=NAl)tUmOD>4UVMr+W~e#(O9;!j0Oz9pKv_N(eF@tbA=W6Q1ca! zAwsL*x`EYxU6U`K6se0nO?yvg@g4VqZ3o0D(Y%jQRE|Hwo5wIyQZrZH)N=D|HBTnE zrQ)d?qXRre)lzKz89E@S2?&N;5xO~yb`BE@lf+0%qVJny1B?bmz8}81iA0=&@HZ2p z0p~h>2njs>(w8pQK*ndfm2;1yPMtnN?&=-bn}GvG)2Cr`12kcc*W+6ei=xS+g zpwXii2WSe=_f=p|0oX&pW#xIpFg;6Oj^j?80<8uREK-vY*~0YW!!4oTItYmPdhlz( zsuEqps)a=r8fv<$WJ=D;jmKA$8-*2P3o`B9Q%M)q0V@OzKpAbMsCJc?PejC^Msp~S z+5uE!OT=z6Py6l{Je^R8c)72E9jkvsrDsp;gJu@$k zZ^zqbHmjtcu=L*xaOkUX#&_>cqNGl)syD?%iqf#quG}L#%MAXjie925z1m= z>HFi&_!;#Vqd(UvGaQB9^K-4|-ZK;?^ZP4H?nkYA`w*Tp zw;)r`B|o>mHZ<*;&z#S6MRXMs?3MZ_X(qb0qP0e#+;(oYK6ww>q+!21C*#9 z?~RG<{KXUB_QMB9mLMjvEqc7DMHK;0S>!Y)Zr+7(gf~o<=~ZTZdb>o9m3ba7#%4dv zxLz|PerJ)oM7OMk#-APMIaVCFm8u=U!FO7Hj<>*LaO;8l8Om2eGHeM<_k|B0m+~#Owayfg)|>kVOZuTTthmiq|>xD&L*yeIbbd&M$8DuZCfkq?yM!BbFL# zZQi4}Zmo4mhPB%$cbeU|MO|!k>-nET{R%l(M@Q%)$ctBJg_FR zn3r)X9P2)+_4<8V;$Y&cKS?acl=e8TIbZfi&s2?11MTife7{~HYMyLhRCZRZPQu#|}nEdpJ((b)7?Ntwa9me_awLH8OjS z7*7R*OCKRAX0S8o3NI=@uKh!=W*p$o4@ry%(@}Qs!?O_%n$t%&)}P_I?!&lGG9rh) z)H%h5k;dw)#50Hi^@#32Cbc#ieiz#f$6Ud9SRRh zW|xgPTQu7F8_Xu4n`ZD)$jOwv^(8sSBLdgQWDxmfoExZo2SKH@jO1{^@|M!hrntp~ zqEdX~VdTT7hk)N{{_3&PTSXi6)gvbpLSET3?sbiLvClvcHcgJQyK(QheX+Fhw+>?c zlOO9SL{sYyCq!&EecX2Q8OI@(JoPb%;E1q&~{Fd%SdTI_24_Hp+ zvpXyllFRn2`ol6>>Sg57rjvCUVnKRa;n%Q5aUR2{ZVT0c{<~HxndY@qRj=pvt8#@!=(~MEb&>gj_V?4KT ziY3+XT55D5P?`OrwK1YN)iSA!qv@;0AMK6f9-z@R$g8C39V0mz%N$w^hE=|Cql9I9o%2gZm3j`V{gen|hw-`@L>LD`o-B z^Z(cS|K(^zQT3%r1+)Q5g!y_!4WtLn-h3P7Z9UZ7o~V*t%?xO}_?;z#1x_si<5?pq zjC769b@;UrYx4m4x6}Z?#U4wx7Z@VG2isEOXhh4f#j{FP%>;Hhbljp-WXoG#$<@seB>(Nj3|!0AI@nr-ksN(r?A$_bqP=PuIk zacG5X<5Wcfa#M9DCShmicXgk`Y?IC>GygAuCCq2b^nEfbh^h|;tl}nMRL8o)h;<6p zvq$C}#}(pWwqDmy`Y%D^m2DT2h+w1aOgRX|Cq*u+gDGMjwb6hYWd4RVJ3{Q%@~+wk!v7Rf;DXpt7%Xqk~7 zAf+Q;gbW;_NHF?R46O!S^JHmBorQF#0KK5gGo3HKikX9t{0r*-3p@YFj3rgc+yTsZ zE=a600o<4JrKH1S$pf1YrFy1ba^Pe{y9`N?FL9=xg^@M_l1>Ns>LB^Tgf&`?^s~5A znXcnhf#_)end^r=u`&*qk0sC6eXoPL?JA?GMdCR)zAn?U+0|f@pcH7mnEf*wDKfnH zWyz`m9;empzO4!Fda3{Fsf2zI;An~g={;3r9dmcd1$)QOxq8ROIjq`h;LkyF&(I+O zjbzS?%%8swW;f38s@X+%=iA%mV`ypI<}it8v;mjSIz^f+%+vje97`)21*+-9rc!U0 z5g;3l0VT=gMN~8i$ji|@!TrBK3NX;nPlhkgdyLLRxAK=x?-F zgX64r_A_j^?I{7&v}_RfF?Xf?TTmUt(ZlZ%?-(}0WRHDk%Pi$Kh`+Iv*Vz3=C{+rG zVpbiibhj~sjk(rl3}S^N1(t7BiGpFPcb!-Y6N!XoiBYXA87${-XE2U{&95x&bz5?U zOjrkL+%9m@$07-g zGMv8r{dg~tzczaUD)_3Or1fabh++2rJ%cUPEfDr0^-J}uFzmNSQ7>5cre?l-Awa>g z<^Ckzun}ktW{Do4qA4~(q@iy92@TTxmIAjXtux(*D*#Go3tScqWoZgVwDo+W#IVix z3%~_QVN%_K2_@gyMgl=eM9!w|?|e+Y7bdMxE}Y4kIpPLn8K?s!4vk5z z^O*DMb%1qz1fALZipMts@QBPU;m()CI0sXeFM^dmUN)#70(HSJ3~o#X*mPlu#*fxP zB5}{G_F(SBo4S?eGP7X4r#!a!fUJBx55x}wFV^$}xg-BW9rEubs7Y#+8-ID`J-C&# zrV*H#N#)om1LA4^j&Rxr%g-#C*R{_A9A?T`-8i{Y^9Y_kKY4=>5C4~16rt1R3Nb{qG^(Cxa9?cYoD+4-`QY|ezNThk7l$3eA`^B68?0O0j% zMDzXddhxxgjRvU(yNO0KH^-28PR&P|VpG|kL}GIcvR!K5=mVUl%Lb-B>@TEzYHiNs z-E0lzlKRO+%Gu0hbZhBmK2ctP)Ue@K8or&pf|AW{hlFl;Y`Ra{rw1TZ#9@! z1Q<)BG(~w5uE&{XP0$n!r((;8#vehWOi4*xN5zxSkq1OviHfk z3w1US5qgK=Y*sOfVxpFd%2)Y90|P>3-G=DPwY zJFj<-XV5VwXOQ?%@mrnkZ`SO!3=(Fd8uLC*lcri_pGYd9!BMq60j@+d?n_hvx>PS9Do- zD9qQq^-nmLF>4T^M`sjaPthy|30-mb7`Gp`0i5>w@<7c4?Nck@PFnpmTCFs@7Qiz6 z=EFI1a;{;s2m!m1Hgs+k2lWh?9Mp0oBEFMu6CwWVgJzT+}<9!PE z0`3CrO)vwVFedfdggL_g6khMLs!AS`Yo56z=np_~J?oD%!kvah98BAHD`7gm8>t}0 zyhMg^Lw;7Tk`}%|L04%<@b-VS04D4c1*TCJOoeoKZ3Opo*FMWd|B}F7wm~!{t&E3A zB(6T1D&MQ&I~AcXmYWj09~3QkHIUKA-oeV~pQ*V+Wb^o6Pjeq~vBnfUCn^}|w{jm_ z^uW_oAyCbiTg7;JAut2D`2@qA%YR{^hCG_q_G6{ai&h(XrvZjc1|)$sxpCeAWP#@f zat-bcs{j0?6iI|+MAeE z&4|Z%m30%kf#};gdM$a3Z)h2w{?VtIvyth4RLLY(Z*4c08_35HaY(YxH0TCvd{P3{ zZ}mPx16_|!mUPh1C*OKh3SfJUl?7VW$XVKoHuJq#FL*U_-UpX0(6kc~Pm2*2@&LAw`_$hyhsA^-vNtdHfL5h)(--FP2|H_1d%3*6i^Ror@#6`L9bc)1@N;APz1%=22Cjv#))`(s>D7Z?%4xaX znalMX1-;vmM5i_WSKbYHgLakZT${rgs$D#vL(i}7-nV^UC`iJ8YbCevY+12-%Wac} zN*YB-VfzvqG$ziv!INP3yLO`9kdeLh7VTxfMIW8+p1s2u*{;BQYz1f*3CX8smzxm_ zOmxWDO64&_SN4t+*{PTY#RaP9$SSf-+%9aOFSd6WTh#0zJAT8FeC_{}{AM(kFcPkO z`o>y85_R)XS&cA=>7g*e2a{}Y*s7>`xK|JY0pETQu>)?L4k*^Qk(x3$K>odiRCqtA zz06ZoKuyQ9T*a4J*3-Mr^rZ<<8tb2AP0~4IzkU(Z*u_9--i9#X%rR`a+ZpYPFerIr z95)kpZ*gt<9O;LVKF@~=2H)W_$MboQttxl25}}QJ^+{ekC^6a+xwbIo^%IlD^tAkm z>{Df^(Zo~bvzuu9HYBZCR}G6hv#hv}l$#46xEm?OnK)01bzjIfJXGaw{pITwZaq2l*7kj zl`^_Nn+ERW1r^6G|sf|kKEBEbmW;s6~q8^q;Rfw z^8t`OzZ!ba5&I5SU#T#}^dP2fLA(@@uj{|EWv76gQPg8+%apyv_v|fZXsM~*fG;;V zOJm$Y3=idTx*rI|a_uJ7V_t6opEy`sNp*5R!K6U9nkC&}8Tefs>i~J;5eNr41FkRs zB%T4O?Z#d&-8hK4k|ccGbxQSzTRma|4vOha@477a5nnAl=7=96K~59iq?w?TJR z(bY}k@&A%T&%i6zluCS}V8Q$Y40lH6m400pJ(sS8wY&9a%xh!)xv_{Eyp4P3n-%t; zZ4AvET*M&zp^>R_x=#<0Niff)b#oLdq~*w8eJgP>D%SL#T>nfV2Adb>*k36 zgt7g}PYZkwx);BN&iYvPMm}6x*#}P)Vd8ahvg;9AsJTSq5c^8u32Hy|H?NvzP~*GO zvYV~(rh(=apki8~~Md+I+oE zBqzW(Hkub9?Z68aE@Vu>NW`tRz=sY@Mr`&z;7sk8>0p6oH=bPp1p}Af;A_L169S+rRKOvi(T%E6 zEGk-9_AbsNY-!f3s~|PSINotUKd;87q2DeoFzR~s7Ly2c65F- zY(Jy(JNo@{cB(XdkjLX~S8pwpu|&FscPmauz@fD_mk%THP2$k%$-^$P{^RF4^3((b zguLk#8C;@EpId-@Y_J-wKESdM&Q%~+tu(ps=#e*^X>wTW4V#il|5hA(M!@0fu{{2qH z&brQ{Kmrg+JJ*Aki+LSFHQFlONn_gd0ld=Wy8Z|K|Fn13UsXo&nx{dOZlt@BEs|bax9JkZuqG0a4(H0@5K3(%sGM~!EO*a!BDW?GAAu*F9IC_A{>=C8C75olTFeUetG?{^PHeXSWBTQMhOW82)P@O` zb(&b*H>mgN>9BUa^ylI}CO!ra@F>JFsZ=zx@5C^%h@L@=1i>3PB!b9KL89##ym0po zq5wuk)ET~#EuNXtDbhq-l+r6mYV_!3w5_!J+M!u|k-q1D`mO54>E>W_(f{_Xkxf1K zdj<4lWsi%gV);u2K>U^PkO*>je8a?PP;YYPpa;X)(-P=|&ivGAw8Yb`G7Gi^^W zJug$pUho__uF;7_5lg?=<(<1TD3Pa^a*5zX{Px$n2nOI97xWPzg#2B92`t_E{cd1^ z-70OcO$+QW{ylCoU%1rzB79OfcWE)x5Hqs4c_r5f-_s2CamktkXUKKd>zA0sa3~L# zUoQ`y6Ly^qCIkwmK~>zPRlgU$8R|B^Ih}Yhc<N!v{&_(zm==P|8Uw|yh zE>|BJM#%D#Ms1!M-Eh~d!l=1I44P=7>4XyuR$ySg$?t|sCzePRbZK#MN6`GTRwd<# zb^-F(KT_Jd+j>3b39d*OElVHzE8)7-CgXa`Ug=hLEAB@WKe`P~5SD?ckXMg3ZC4t? zU?w&BlbZWw37^W&sWzrUp1XeaV(AOLnkn(YVU;vzzz;ByOn81A`R7_y_Mg7cwIqy{ z9f@zdSr?dtjDScuG)1e`+j8*7rCse?1kMzQ2F$SwN7A7xG_*$Wy(ybAj}aCNBaM-V zMw=+?x~%Au0&Ou~UHnYPyTM&6iKE5#1QV+do8L?FNEB!HZ!DF1Hd^=eXr9i)bjoGh z+Ij(-rnYZA=WaP6$J>k?ZaNkh^0svpZ#rWHk}mC{lKRFZzD@*5(+#UZLKp{X0IDGl zR#s_FwvK-OoCvSVFr zG@jOGH9+AOGLwBd=ixDUgpGg|EG)y`Xtbn==1?nqGmy=iI0Ij#QBm=#RfC?G7DyAL z-yu>0GF6_xi%-2n5}n*Dofr-0T_$*3WBww9W1FcpUk@;^NDNm#NSTLUgd<9WGgmeW z>L3UEtgl+@Vq)=l=rPm8K7A5928He^kPphEWUlx@=OBkgoWz3=H|2C_gnf4Inb>8WtWFG$9dzT8GDUMR9s*-2an2oQTVjX# zU8SH_=+vaDbL%oRi^|?!yFwo;P2pM7tq|IU;Gf~;Vu}Y|d%%Si;J*Ua3SrWse~=>t z8Fl-GR<~k*T8_kY(uT5(6@UJ|X&{FBm;+7}C5!#dX7qdx&`4Al#effnYE1B^XaG zFmNY=2RU*PAQ!_#jx&n{7Dcya%TQ6S(QpLIH+SGY7`09vMIA3$048u+^W$gEor-y; zS-t`z9CXGZ#J`F5Z4`LJj5T+-@!_X+{kC4|B%}Wx5BqC8cFhmVPfwZ+y48E5iRM)- zLn&Jr74RDnXh#!e8+^LRSo;AINVE(@WqWT1BGnOJLeW{fndcQO#B0ZBlI6A&$$5hw zF;Bhdmqe+d$4Z*Jr9b*+kw~PZJ2v?V#LGN>{%S{3kT`T#_hA15&X;2CTd!bw`1z7< z?R-5vX-$$>lJZz?*a8YykA8GVEG{P7HiE|yG7l~4FEI0D`#zWowzsWLaEBkpb2f2?e` zI@2d~n#{Q##HHMx(Z8z_c5P7Oks(yvNx}hB=l8AsXi*_Zo$omKv!D4lr`ODv$Y((A zm)#fDZ%oqExj+1LkTuIQK*?t|^RiF$MEdj}2!K>PX8Vu)lV-t6W&yOGTXc61>eEjG zX{M@@rvDl>KsLXDT#?6DRCw~a+E~SUAS~$h6Em{ye}{Y`Hlyl|d5PbUIj!+na5H1^ zVN&;ujomSwgKU5Qn?k(9ZEA1ZS}uNDt1?^AmQ8Dkpt&+UV~GH{yZgisi5zeIn98i7 z%oX?RA_6;&Tqs>#jPvx~{~~?A%M1y3V=zV36Z39?w2Su=hOQNvTS;OE`WY)W^-JSr z_ou|(C&4D4b>Z`<${oE?)?Q2&{UKOh3E@kR#ZZ~qI_r;}S#7c=*?O9P`J!i6iB~bd z6GG}wPN&RDQq+^TCssrF?YFc*8NY+&=ht^yIf7Iev6Sq4b6dW)H(up-ng{;q*oyS> zK4!(#*clvVrq_EyTRXL1f_w^?rjDrwQ|Sy95|j@*=z({}L?ab23bv9}ovcY-UsRVegiQQg_QqE8~C2((b0zb(x^@{TVg(k zB;wF(b7|0Oh{C=HOS$6;k0WVOpH0Q-xpaDez3M+rGC7|P zMhd?v=&bJIJ4`&gHr1kRdDL&Hz=LcUL*gGJI6@J!(mVxiKRBm(>;7F)Zm@v+?zZuJ zx?j!RiN;pGKY%(y(Wz7KFJ9QM$PRy-GGVTM#j2J?*X+c4w!XXx&ZB6QkY z&=q6FeCmK_m`WB=WoOb?(8N6sUE~+LnZ(vR9EJsgXm#ivSLgH?T28xnh9I0`@DrKN zW65u*y3$D3Zxt&_yYC2DA#?6cj4e(JVmZZ-hJ8qN^fS8W zgc0a8F*|^R&@M{a5b}0ustEVU?;&t&L?Pioti^%+h}?k z83|UCR8U5ALrLSaZLK(R(*o#;PrYvv-Dr`Vspi$7kUw6fZNA7t&_bl^q@n3|w%=ZR z#~)(tbXWQebSrNC#qk<`a%ZG-UuYG|F8XNlChC3YKJref;4m?A_}zU2mgy=2j(%IJ zr;MZLzh&%wWvz~>hQ81Xz-}}}w*T(Zl;KcZbsIBZQYpMJ;6t_4go`z&*)zF?|2p}y zAYg@aT=EfuBxbY+g?$CES!Od7$w^}1l|pG^uIcDF#w|4!6yD^%T zSW6x&aV8fr;LCnT!$3pK7Q;#W zrnH?B`u^b)LRim{On;%?WxiNN)(j!R6AJj<)ip(Z9!ItsC%0!n!5(hJ8SetG?0|+#_lk-1-+Tz11q-E7Hj9*6wfN<|L-F3=d4kXH9reNS|G8L)tBcK?3 z6~tUD|A8dP5@4(9kWz<}Q=UW@K2u+u5v>yN3Z(_#gf6-FOEh^ePF`E^a z9{%!*EdKTDmo`l)4f_d1IS4}YR+P2KR1#fm)2R7)G-KILHe0Xi&`V6dK{Epll8pI8 zUk0bhe4@hl`mzZ%9>M|wB{8N%*7P!Le}J+<@gd1ZHDFDKt-ax=+W!I)S?Yo-3io+G zwmcnQ6gcr(>Ci(#m(wD-&~Y=2`S%`=G}*OYo3#6RY9=}C%0oZgp=?#_;HY6Hv5+V@ zU)CLI`NZ2U1y(MLCewmf=XH|}rfefPVI#Ygjht+7E&--cCLT{I!j|~x+mPRR-V0=2 zJ5iB{uCd=1Csjl3;G_idFP4IGY4Cqq#fIYn=tNY6gAg}A?>78AeS_BF5=BoP1njdJ z?>kZ($E&iCG@-y$Ln!i1HA)?>SWi)Y0EOeC#vO^H z#CqHqWEgfa_fvqX>)<@w^dmkXvT1rUxB>k2%r`hyfCp|1T5n^+2g;J4d?-CNd^k`!O$OWgtKixicW3enK1xBErr34jEs+sx(kbNEwc*@gR`Dk*k%L(1pt=_ z{89-xJaqG)`+5l0GDm-XKM!KcaRcu!_XouGTV+U0Jd#8`HgV5q(BcEkpLj7C@uBuq zgKuahYQBf_r7Yp!01`Wi@8Uspp372Hp<&hTZB_U40>5omZ_zKHxk|(Rwu=CNvE`l9 z%!-?Wd5PB`%=!f&cEJ}XdL1lO59Nu)zy^TrVZQw#o=Us||bI1u>`5W~#RO z$bU(#{a`X&4iuV!B>IT+{rO5@9jF8g6L^5i>oD0-3DiexfZ+iOTqRMbh8bKY-}k?Q zx}N=bnI;>kB=}wIS0AnRv#X?Yw81l{1<>6Jv#y{9vqeyR2T~|dMcF*TOu%JM7%o#N zwfpE>Xq`(Ob|ViIyyy}px(8MR??WU>#5W@D>*K(&PzGd!O0aq$=d+0&TLB9(?*sa| zuHY`>vCAq#51<#33j0xVYGLHH$wm&6pp2(UarVyE22 zJ+hpW-1+mV_MLy@gK{dYTd*-P3f@g#;KcVPYZ zZh3xpI<~(fdlk~9I1b6%L_`Z3$>ygEHs(VegL`8R za}MXpHc^(#-ebE+swgM+o&f>R+y1lAf{zSfJ9r|nb} zmOl@P%w{#W2OcoXIp{8(R@(TKQXnyauTFSdr~s<>tJxDE2e^B_idAS!yylZUgonQc zGzpkgUF`>eP8-#88XFHmbyOK7moxw#(+p{7{x9%WiUtqO!ZHZ_sVJ$#vZMfm+t%LE z6e)H;aYa2upb5ceZ39J*&)MbRn)(bQcnI46yzxqwy zAx6SZ?JiVTM8|+HAWg*;u0)<@dHKu5YfZ++pXR(z2o^0~kkwl%ImZTC8EtIacldn| z7D4J|ik9P&nD+JUA6Ga4#S5H~`-%9xpwPUKuhDOQeFO4nnpe`^P$D6Q#4+Lv9pKf1 z-s~1#!f)fwTjxdrR7?1CHq)zsJ8lDpzTFJyG>!@qm!sdda#E%Au1_1=0iK8k8IHCw zbt+<|SpTs&u5S3#02N399jBuzmI_4z+Hkbrt_U3Nk_q60J6$!`peAI(5dKXCAkEV< zk4nt2P(7H{b2rVW;sXvVGh_-fr1Un8X42qo{sA7gcRL6}6-YHLF7w;O9`T}e#FUsQ z@c}Ga&`7a(P}_{e?t;800`IrNwm3Ke&mJ`YXG$DBna>@ztLJK*P^pqiJL@r~D;jz2 z=5iTk{Cpj8F!5jFPUy8&6b(CrI zc*tR~{zINNXv#na_rbyz%-1+1Qy>^lRl<2O%K_*|?6?$z$Nq$%AaQtBd|U8C)2v^m z-j`MAAbG81q2mcyZMPgThH2P3CjQm#pKXF;mT)6&t^}e%8R>E_3M){e<2E}l64dwK z2-Sammn~zO1mSFfPcfVyvd+L2%Oc4iL+R-heqqd+PWb~@DB;MBzyuID$c0?0Kx%N~ z#nu6M>c85pX(s+}7%3ORrIb4$iB^DITXbq6bvEUXC3No6Kx`0=nE+Bcqt|bnAIZIU z7R;Q%z@t^1M6UoQJN6kuZ2PLj4NSwvl@q}Sli6L~thVvHM$JJAI;2kWx0RAJTHzi` zOSE}L&%4ywlQhnTxvh>fk<<|#MBx=%U}dTVROxJh&1WUB#;ntJooTS%pJ0bi8N_Y| zi~`uY<9oUbfaB9{cJA-Bg(k8*6Od6x-G*ai*RWUnLqSIjCl)cDvc$Mk!LY9OC&+?(F78PWHgF3X{mxZgxC(=_!JZuJ5$^(u|kex z)gjegTj|fV#S~rc)IzFof(>c{(G$wOn%`tOlwsuup_UGrlm~onD3e1*u0E|Kdn%4# zFb*te!p{Vs2(qW>egJU_>}2#Oq~>hBQAjQK*Zm_=Q)cLfVJyL!pG@^9#QR_H#hqjY zh+OFlROrfYG9MfP* zh-a`x^1g#^zgC#U@!2xy-+KQGN7ql+64_~LjI5||{`QFcu}p(CviZFS>(g@1E7S#4IIjjLwAX81hHD>J>|d4K2@2#4Kd?*IpMv})KOj4e zeYeG&15hGhkS+2rulq-%xc^6^@H7s-TVG~%*DI6W>JYUbpNdHUdO;#IMO&@n*b}NklOuRlYOx}w2w&szrE^Uo{beyiUaH|YmWWFB~QqlQf zE~U$*5AS;W6{l&vQoGl|xRORfcHr*lW3~!|!VWj)w~NfT7cKMGTN&1Vt$}J?8UijG zU{3~tI8vUTc>BX;g6CTubM(W=NxZ<9 z(^u5$Bc)+TR>7~zsH!WoNF{Vb-f{RA!u$AtVOW%Q#IDX9(anG@M|$g#?(^HOrWWt_0M)|j?yNS!Fc_=hcE?PJ?;S_5*fg=lNo^O= z;l=KghTACC(CQ*oZ!3v`O!bue>C#LEZy$^|NQ@X9E8Sb9FM=hKHWYE zY+n0xHE}f4;I}T z{A--23D1X6SL{2=H5kA5_L-k7q_iC@b_PEF^y>U_xqqKj)FylX#^jHn#kcJO9)G2} zORno)cU4NEC+*TgOJD{HJ4@rs{H5mDZaTZd7cHN^wc&i|4X6Tf zz^dK1^5zFMe;nGcy|988!SP^uLL)3ps*(RZw6T#77-3?m#QnZMl?2VLw;Q3$l?WsU zAiPP+N`rd3m6a9O+eFoMkRYuL2yTy7#ph!)}!h$hX zYZg&lTrB+h_VUQp(^DW$ir`i6+_^x^@8hC}>k^ap?{fm<62vg&p{dafH>%m0nc`Lj z`zJV=g(njLYA=-j>+$#OzmMH+Cb5J?ZR97&J(q;+_#1-m!%5GZj=u2(ucJWKQ{-=f z71?2J@Bp(bw0QYW&AG|Z=xM~o0U*+V>ABC&?Phqy=I@3YO|w9zV-^XeH04+AAB=gL zj`uJN-VbU8FqL9J_WlsPUC1*sUxNK8Gi{duucJ7|laE%b+1ArROB57**2K}D-)vDZ z#gm7C8D_EeaH#7A2Xp5}>GpCm88&uS9b^!jkY$spb1H&^yuw%f^>pw#8CrZM1Jm~` zm=)>lM|yGr=eVISXivjfdfEDD*jLunAP>Cybo6Yvr4+%ZhZ2I-cXE<{dvpsAS#%eQ z-V31^dYIEI#LEH?#Np|dcFX|u!HQWUpO7~I2nwuBGFmTG#cT#rAMx<;RQz2bZF#-O zh0voln5&+-1N-??W!e_x6-?2w(O|) zJ+b+fCq@DY7+=9=InO|Rm&2rukc8Vb?A^O}KL%aYZ?cW19~#o_zjb#@I?cD8z5Bj` zg|J}*Lfbk88kg$*MuPR{`3?lGh%QB%8~&jXpbdKP~AtLFa*J^nE3zsojSqEf3pTk=@*@@|OpNbJB$IIx;I ztSpR}$0MK*nk4+@*%NlbeZF$MI1>(92wn}i(-_sQAm-rWQ(E}@w7sT0-hFjhUcW0S zP}^jbVJayR)oHd#34y3sC6Y2>YK`)d0h$ zq@dIEvsbOIQnJCPv^yZ3AUTvPQXl*fl*)DY8k*sH1LmaNQ&S|%%gbo=y0^62QhIOR zNCaHs#s+}d-;>@Lk_4fC(g`rDE>K!G>4~v>)NudP=)N|wH|J>(hJ!;6Bh3!*$;rdz z8Z2bzt%Cz_IU84aUzk&*@~h>A6{LU|5K*dC)b^-^0h~_*}dwaQirh9 zSTAqKjRL${?6?q#?-1BB*RMl*LC3O9cM$4O( z7;dm15pv3awC(rtUpYdrWeFqIwUquo>-~P%@WxgF2Eds-z)Tkk0H~x-Do;dXlL5z6 z0h&vy3y^}(!AS`J`!nO)(2#ln*p7;`NCTvP-hcWew7=NJO%VjPE;|BY8w_R*J99ra znfFiVkdio!1p&YiuduMNhf6gAzGV|a8U7DTa<;0AhnDqj#H0dtYPg^p?^fKdnKnugVmw$t6 ztqfCE9|C?V3|rr=QO1-S5-SoFB^YnN(R%i>(V9fJqB#gO^e#3X0S*F+E5SCO4Om^~ zy;Ofzc>e-KjFZx>PZJ+DW}SfuhL8#1jI@G+dan|;oMyKHvcZztayx6Wky`2+*y&*@ z%n8#4KAj@;hE3dKiyc|!s}d#M#Kp~DY$;_E)=m3LLucZjo-|)450#g1o+;4rOI zF25xe^F$o**A>XQk2RTINt8RTel<#_DP(1C`}+0E&bs+Ob#8mSC_~1y*QW;~#1jse zA8hj8BQ->?D-xTAgF@$Lyw_fM9$jQ=r z=Lg6;Hl${=|DD?vd1G;rq$1rJb~-GPRBe#>72siin7qjwOQeGWd4|-G%XeATV!>WaV>NLJ?3Alr9z_N6f;0d(AVR>A(fl z*RlvY1a8v~Qq`v;cnz!qDlRTAOUxV`Pk`7qH30!af$H>IFM;vR5Jy1z++2r(XrU!l zCIA(xfPAFF&@lp%xnr<0%tmp7a2&wuolVb7uA#3xTmy0+&Chhx&q!j$L zVbW+wU}SBLaWzBR8C5j-qF`NEN8fPsoTHhHQNUz*3_GwJ>%4B z16216msoVe4oRWKK01=!+^!GU4L0gj;W<;a<^#LdXu;n`ld4WMlkBuU(y5yTCqWQv zKih(+s)D(&&i60n! z@NCE?v@jPRnQ$64;V$J-K*-pfHbhFps@B$=rfTw9d0zIF%Z6_KnxCIXUCL=IfiV1} zaLgLv*^X&jeGXKFm{zjY=S#DHyPP_bEFA=af7%j@{lg2}A&Mhc)WYbK9q>%F6yK2{ zE{wr5s4)|iPa-XO?zx?6@Bo%pM2iG#t@;MM$-O)~3Juq{9xQUSKQn75a7cd#H!j$l z4|~zc`RxBvQl${beWJ?XG{zj?4PO4Z!ok)>io|0n2~>06)(X;@M2B^@q)jso8?U;Y z;xpp;&#w8s#A9TLQ62P#pIWo~#PAmc(UVRb+lM*LxJT<)$gaI^6VoUEl*;A=r1BMvf zVjRBb1+3vfxD7p%np1s*lFN(hhaI(Kh=njb!A?dKJG*X9AUY4@h;b{wOg^ z>FqgyLNqXfRsE?X0;U~kVpz#bjWCD}8*ZNlTF-g{Pn7xT`=lRWsvgrOTEe6JbrS*6 zn7W}%Tb}7XHYFR~`zEXxW`So!V5c({I(%g-Xz1^r@n@b6;OWo6OkWb4o63GMEF-LJ zRgp^b+BvcJD9ewNz>f6DnlRIEJsVp6NI%xYeW>2eOw?^9tjtpd!_amp7tumRB;)Rk zHbzLP!&ln@jY!PxHO+6g1xzzg_$#C3XNIr}7*bRs=>xYM6rx7l$le#=tYt{XD7~iH z_Pip^>uUuk9*Yh%%tibe(QUQ2o5$uPHCA?$GK%4FzJ%1-8`OGN>oSbQO(AWm$$Uy< zlqXceo??K|*Pa&h>=d*7PL zIoRUA8%*?Lq$bCh6Y5?5(*4RO4*C1^yr;UX-RLG0T2T1$@grl^y!sC_sTw3TW?iO) z7-Ltwiw}Ssw_T*#;SO;oDp;}9c{d_Z8nBrP4EO%;R;_iSTxBEt?{9q(UjcwQaeT&8 zE;Bw!^g%_ETBS=R48y8nOGpf>EHyQC(xfGS+y>8}4Cz{_+H{3hNpuJzqlqF+McJ!V zDodT7|8PHhCBnfAa)H4MXkY=sYjkExyJ0$)LjFC|F=1q&!RmNn79#n9J^cjvmZE>QKy%V3&g zc`O_$+BO#5>~GVXu@^}yC3pI;6@oSLVd_C6Z~n97fZ82!m1y?d-FRWH zzIq-^zBOtq**h@N>)+7u7Z%m`P)Q>Rf-*;WTm@9Q1f(GXwCG^7xyQ#2dag3{`1ztR z%Ovq-6<-ZKQ(KawCgdMRbG@WK8hRqN6)RD_(D+XWlV+sx1l;A`=g&khtfqpF7E*dI zyiyN2VkF-6GZmd*G)$s<37+S3xCsCF(*HLwI2~8k&Y~$&z+811VGP3Er&w#+Tc zbC*^RgWDI&@A0akQ5K6@XL6C9ZbnDdT3$Tgck;+s0V2Qde zSo2=XZnRl^L#wyvtLV9)VdMzVQ1KPXg)$`RL?*GAp z5|d`gE`$DqkIYyFus0wV*}t zZrHM1V9>mPJ8^xikuNa!$vUJ~E;_EjJX7pfnN^MLq^6r1erzhb_9=LNh;V2uNp$;u zI~({6CG2ER;u~TQ8b>L5v>v#bxWMFpiqLzmh~puFHNNl2ZGq#3t=sJu#F+VcQ7RdAa`ai#!xk|3GJi~BS|4U8Nw6=6QadoMw z%_GBY&ytyZ{04qUQQfyH%vH*2*?SCom4;*G_^+hX*#zucQo=X}v(>*W{X1lgcnQH| z(Zu*qj=f4#eWP7gT9p_*ZSKY}jh>KR`U+bjP zZPY%Ry8b(4Z~o{b#}S8Z>-2NoT6WI!)Wnj1t&>g%y=(!!1cyvp8huo$m0}~NbmQ=^ zmx(3+T1Tq_ddUrX2@Ywgu@%;ACve8Aa#QhN;|E$ttMa9W{}1RTIHa=cR+w(NQez%8 zP~cxLVOsxMmskRNNdkKLZ(u!ojGD6jvPuFcc9dh_1N*Oa|8e#}FaHg!M^D8#bVhx& z6AUaHd|>~z4mMh~HU1d%^54LUTKqdfqn%)2d%?gq{c9aetCoEb-phXjD{ArY1lgPY z>m`1J4!m_J5H&;3Fj zdTCX(>^$4(gHdJLr!cwYlzNqfFDG1km>*TQsy%ZB#cConEOFg#G0~cjn+z!pZo0uF ztR8F-kjkRjGaKRHz8Vu78&+G(t)Bnf-red`8X`J}7}|kWjq5<}SH1U6e5(Pc{KU)s zT&pQ1f4Do`U0uVBJGq@~4qJGCyHD-YGl`OOItDqj%d~uUYjK>yHZ?W1`_ocA7&kwQ z-r>3|O(79LDkUW~DWQ`?x!6ESvYg06KX+{V2{dJ=d)UlBWHZw)0H4@*WB%;Mt!y)Y z*r?y3aWz`lji^Rs>|3P|SI$IeGfn_V;kEjnFoA6Zoc3gzKOX@-@o`N}%_e~DgG1?| zQBe7!Pf>TI-cMm-bv}I8ZC(2nq5-%k7d2C-t{x7rsDQB8&{H_Op19C)_gHEt!Q3H1 zxuqQ8DS2~V9%WH+aT3@u8vNjiBf!Olt*)*f85h^QA3881b#1njgK~YZFF8506Kp

r* zDgHf#J~VfVd^iY3g}6mNrK?#s++8f&q#b*2By@F8FqJ4^MLvF#+%n$AIWh18R9HHK z?#Q)ERW<#icQ2A0LR`}%0{uX0Z=F8vWwf;emg0k>LtN?H8UD2yB}5at6zO=m7xctI z*F%OpOH@^aJ#dMePxkX&x9{5UR)`-Fqj}&5asmHYV61UH-!-f<>!Lb8KhLI&sKy*3 z1m+p6<*hAN#Gh!)p{HH5f^D=9PjMQAzq<=j(cAqrB;-t_G~}}m(@uZlI>2Fea9E#R zkPs!|hyRXw*b3M4Ok(ziP^z%QP(shGR83+0!)9zjV? LUA9Kr{O$h$L-w8r From 4c856b22ee60e9355c128fc898f042c6bf9aebe4 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 11 Oct 2018 13:14:27 -0700 Subject: [PATCH 26/71] Move bridge to bottom --- articles/actions.md | 167 ++++++++++++++++++++++---------------------- 1 file changed, 84 insertions(+), 83 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 1f14d1c60..dab648da6 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -129,89 +129,6 @@ If a client submits a goal and immediatly tries to cancel it, the cancelation ma In ROS 2 the action server will be responsible for generating the goal ID and notifying the client. It won't be possible for the client to cancel the goal until after it has received the goal ID. -## Bridging between ROS 1 and ROS 2 - -### Detecting Action Servers and Clients - -There will be an API for the bridge to get a list of all ROS 2 action servers and clients. - -ROS 1 action servers and clients can be discovered by looking for topic ending in `/status` with message type `actionlib_msgs/GoalStatusArray`. -If a publisher exists then an action server exists. -If a subscriber exists then a client exists. - -### Bridging ROS 1 Action Client and ROS 2 Action Server - -If either a ROS 2 action server or a ROS 1 action client exists then the ROS 1 bridge will create the following: - -1. a ROS 1 action server -2. a ROS 2 action client - -#### Goal submission - -When the ROS 1 action client submits a goal the bridge will check if a ROS 2 action server exists. -If no server exists then the goal is rejected, otherwise the bridge calls the ROS 2 goal submission service. -If the ROS 2 server accepts the goal then the bridge will call `setAccepted` on the ROS 1 bridge, otherwise it will call `setRejected`. - -When a goal is accepted the bridge stores a map between the ROS 1 and ROS 2 goal IDs. -If a client submits a goal with the same ID then it will be rejected until the first goal is finished. - -#### Goal Cancellation - -When a ROS 1 client tries to cancel a goal the bridge must try to cancel it on the ROS 2 server. -First the bridge must look up the mapping of ROS 1 to ROS 2 goal IDs. -If a mapping exists then the bridge will call the cancellation service. - -If the mapping does not exist because the server has not yet accepted or rejected the goal then the bridge will wait until the goal is accepted. -If it is rejected the bridge will call setRejected and ignore the cancellation request. -If it is accepted then it will call the cancellation service. - -#### Feedback - -The bridge will only publish feedback messages for goals that were sent through it. -Since the goal ID is generated by the server, the bridge can only know the mapping of ROS 1 to ROS 2 goal IDs if the bridge sent the goal. - -#### Result - -Once a goal has been accepted the bridge will wait for the result. -When it gets the result the bridge will call - -If the bridge notices the ROS 2 action server disappears from the node graph then bridge will wait for the result indefinitely. -When the bridge reappears the bridge will try to get the result from the goal again. -If the ROS 2 server does not know of the goal, then the bridge will notify the ROS 1 client that the goal was cancelled. - -### Bridging ROS 1 Action Server and ROS 2 Action Client - -If either a ROS 1 action server or a ROS 2 action client exist then the bridge will create: - -1. a ROS 1 action client -2. a ROS 2 action server - -#### Goal submission - -When the ROS 2 action client submits a goal the bridge will check if a ROS 1 action server exists. -If it does not exist the bridge will reject the goal, otherwise it will submit the goal to the ROS 1 server. -The same goal ID is to be used for both ROS 1 and ROS 2. - -Goals sent to the bridge from ROS 2 are always immediately accepted by the bridge. -The bridge will then submit the goal to the ROS 1 server. -The reason for instantly accepting the goal is that if the ROS 1 action server never responds to a goal request then the bridge cannot return a result. -Goals that are rejected by ROS 1 action servers will be reported as cancelled to ROS 2 action clients. - -#### Goal Cancellation - -When a ROS 2 client tries to cancel a goal the bridge will immediately accept the cancellation request. -It will then try to cancel the request on the ROS 1 action server. -If the cancellation request is rejected by the ROS 1 server then the ROS 2 bridge will stay in the *CANCELLING* state until the result of the goal is known. - -#### Feedback - -Since the goal ID is the same for both ROS 1 and ROS 2, the bridge will always publish feedback from ROS 1 servers to the ROS 2 feedback topic. - -#### Result - -When the ROS 1 action server publishes a result it will be set as the result on the ROS 1 bridge. -If the ROS 2 action client never calls the service to get the result then it is subject to the same timeout as if it were a normal ROS 2 action server. - ## Goal States ![Action Server State Machine](../img/action_server_state_machine.png) @@ -393,3 +310,87 @@ The possible statuses are: This topic is published by the server to send application specific progress about the goal. It is up to the author of the action server to decide how often to publish the feedback. + +## Bridging between ROS 1 and ROS 2 + +### Detecting Action Servers and Clients + +There will be an API for the bridge to get a list of all ROS 2 action servers and clients. + +ROS 1 action servers and clients can be discovered by looking for topic ending in `/status` with message type `actionlib_msgs/GoalStatusArray`. +If a publisher exists then an action server exists. +If a subscriber exists then a client exists. + +### Bridging ROS 1 Action Client and ROS 2 Action Server + +If either a ROS 2 action server or a ROS 1 action client exists then the ROS 1 bridge will create the following: + +1. a ROS 1 action server +2. a ROS 2 action client + +#### Goal submission + +When the ROS 1 action client submits a goal the bridge will check if a ROS 2 action server exists. +If no server exists then the goal is rejected, otherwise the bridge calls the ROS 2 goal submission service. +If the ROS 2 server accepts the goal then the bridge will call `setAccepted` on the ROS 1 bridge, otherwise it will call `setRejected`. + +When a goal is accepted the bridge stores a map between the ROS 1 and ROS 2 goal IDs. +If a client submits a goal with the same ID then it will be rejected until the first goal is finished. + +#### Goal Cancellation + +When a ROS 1 client tries to cancel a goal the bridge must try to cancel it on the ROS 2 server. +First the bridge must look up the mapping of ROS 1 to ROS 2 goal IDs. +If a mapping exists then the bridge will call the cancellation service. + +If the mapping does not exist because the server has not yet accepted or rejected the goal then the bridge will wait until the goal is accepted. +If it is rejected the bridge will call setRejected and ignore the cancellation request. +If it is accepted then it will call the cancellation service. + +#### Feedback + +The bridge will only publish feedback messages for goals that were sent through it. +Since the goal ID is generated by the server, the bridge can only know the mapping of ROS 1 to ROS 2 goal IDs if the bridge sent the goal. + +#### Result + +Once a goal has been accepted the bridge will wait for the result. +When it gets the result the bridge will call + +If the bridge notices the ROS 2 action server disappears from the node graph then bridge will wait for the result indefinitely. +When the bridge reappears the bridge will try to get the result from the goal again. +If the ROS 2 server does not know of the goal, then the bridge will notify the ROS 1 client that the goal was cancelled. + +### Bridging ROS 1 Action Server and ROS 2 Action Client + +If either a ROS 1 action server or a ROS 2 action client exist then the bridge will create: + +1. a ROS 1 action client +2. a ROS 2 action server + +#### Goal submission + +When the ROS 2 action client submits a goal the bridge will check if a ROS 1 action server exists. +If it does not exist the bridge will reject the goal, otherwise it will submit the goal to the ROS 1 server. +The same goal ID is to be used for both ROS 1 and ROS 2. + +Goals sent to the bridge from ROS 2 are always immediately accepted by the bridge. +The bridge will then submit the goal to the ROS 1 server. +The reason for instantly accepting the goal is that if the ROS 1 action server never responds to a goal request then the bridge cannot return a result. +Goals that are rejected by ROS 1 action servers will be reported as cancelled to ROS 2 action clients. + +#### Goal Cancellation + +When a ROS 2 client tries to cancel a goal the bridge will immediately accept the cancellation request. +It will then try to cancel the request on the ROS 1 action server. +If the cancellation request is rejected by the ROS 1 server then the ROS 2 bridge will stay in the *CANCELLING* state until the result of the goal is known. + +#### Feedback + +Since the goal ID is the same for both ROS 1 and ROS 2, the bridge will always publish feedback from ROS 1 servers to the ROS 2 feedback topic. + +#### Result + +When the ROS 1 action server publishes a result it will be set as the result on the ROS 1 bridge. +If the ROS 2 action client never calls the service to get the result then it is subject to the same timeout as if it were a normal ROS 2 action server. + From 244c3f4676bafb9675862ec0378e7aa55ec3ed74 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 11 Oct 2018 13:17:57 -0700 Subject: [PATCH 27/71] Link to python actions api --- articles/actions.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/articles/actions.md b/articles/actions.md index dab648da6..1e2850ed6 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -173,7 +173,7 @@ C++: Python: -TODO +- [examples/rclpy/actions](https://github.com/ros2/examples/tree/actions_proposal/rclpy/actions) ### Real-time actions From 63530b5bb38858f9a805e230b378b3e7dd28418b Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Thu, 11 Oct 2018 13:30:39 -0700 Subject: [PATCH 28/71] minor grammar --- articles/actions.md | 42 +++++++++++++++++++++--------------------- 1 file changed, 21 insertions(+), 21 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 1e2850ed6..df002af2f 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -22,14 +22,14 @@ Original Author: {{ page.author }} ## Background -ROS services, which provide synchronous Remote Procedure Calls, are a useful concept for sending a request and getting a rapid reply. -But in robotics there are many instances where a reply may take a significant length of time. +ROS services, which provide synchronous Remote Procedure Calls (RPC), are a useful concept for sending a request and getting a rapid reply. +But in robotics, there are many instances where a reply may take a significant length of time. Additionally, there are occasions when it is useful to send a request to do some processing or perform some action in the world, where the result is less important than the effect of carrying it out. -The progress of such requests often needs to be tracked, success or failure must be known in addition to receiving back information produced, and the request may need to be cancelled or altered before it completes. +The progress of such requests often needs to be tracked, success or failure must be known in addition to receiving back information produced, and the request may need to be canceled or altered before it completes. These requirements cannot be fulfilled by a simple RPC mechanism, whether or not it is asynchronous. To satisfy these use cases, ROS provides a third communication paradigm known as "actions". -An action is a goal-oriented request that occurs asynchronously to the requester, is typically (but not necessarily) longer-running than immediate, can be cancelled or replaced during execution, and has a server that provides feedback on execution progress. +An action is a goal-oriented request that occurs asynchronously to the requester, is typically (but not necessarily) longer-running than immediate, can be canceled or replaced during execution, and has a server that provides feedback on execution progress. This document defines how actions are specified in the ROS Message IDL, how they will be created and used by ROS users (node developers and system integrators), and how they will be communicated by the middleware. @@ -115,16 +115,16 @@ uint32 number_dishes_cleaned ### Namespacing Multiple message and service definitions are generated from a single action definition. -In ROS 1 the generated messages were prefixed with the name of the action to avoid conflicts with other messages and services. -In ROS 2 the generated service and message definitions should be namespaced so it is impossible to conflict. -For example, in python the code generated from the generated definitions should be in the module `action` instead of `srv` and `msg`. -In C++ the generated code should be in the namespace and folder `action` instead of `srv` and `msg. +In ROS 1, the generated messages were prefixed with the name of the action to avoid conflicts with other messages and services. +In ROS 2, the generated service and message definitions should be namespaced so it is impossible to conflict. +In Python, the code from the generated definitions should be in the module `action` instead of `srv` and `msg`. +In C++, the generated code should be in the namespace and folder `action` instead of `srv` and `msg`. ## Goal Identifiers -In ROS 1 Action clients are responsible for creating a goal ID when submitting a goal. +In ROS 1, Action clients are responsible for creating a goal ID when submitting a goal. This leads to a race condition between goal creation and cancellation. -If a client submits a goal and immediatly tries to cancel it, the cancelation may fail if it is received by the action server prior to the goal being accepted. +If a client submits a goal and immediatly tries to cancel it, the cancellation may fail if it is received by the action server prior to the goal being accepted. In ROS 2 the action server will be responsible for generating the goal ID and notifying the client. It won't be possible for the client to cancel the goal until after it has received the goal ID. @@ -220,7 +220,7 @@ There is also a need for a status/feedback channel and a control channel. ### ROS 2 -Actions will be implemented on top of topics an services. +Actions will be implemented on top of topics and services. However, they will be included in all client libraries in ROS 2 with a common implmentation in C. This reduces the work to implement actions at the client library level since existing middlewares do not need to be updated. @@ -233,14 +233,14 @@ A DDS based middlware would still need to separately provide status and feedback ### Topics and Services Used -In ROS 1 an action is defined entirely using topics. -In ROS 2 an action is the combination of the following services and topics. +In ROS 1, an action is defined entirely using topics. +In ROS 2, an action is the combination of the following services and topics. #### Goal Submission Service * **Direction**: Client calls Server * **Request**: Description of goal -* **Response**: Whether goal was accepted or rejected, and a unique identifier for the goal, and time goal was accepted. +* **Response**: Whether goal was accepted or rejected, a unique identifier for the goal, and the time when the goal was accepted. The purpose of this service is to submit a goal to the action server. It is the first service called to begin an action. @@ -254,12 +254,12 @@ Otherwise it is possible for an action to be executed without a client being awa * **Direction**: Client calls Server * **Request**: Goal identifier, time stamp -* **Response**: Goals that will be attempted to be cancelled +* **Response**: Goals that will be attempted to be canceled The purpose of this service is to request to cancel one or more goals on the action server. A cancellation request may cancel multiple goals. -The result indicates which goals will be attempted to be cancelled. -Whether or not a goal is actually cancelled is indicated by the status topic and the result service. +The result indicates which goals will be attempted to be canceled. +Whether or not a goal is actually canceled is indicated by the status topic and the result service. The cancel request policy is the same as in ROS 1. @@ -284,7 +284,7 @@ If the client never asks for the result then the server should discard the resul #### Goal Status Topic * **Direction**: Server publishes -* **Content**: Goal id, time it was accepted, and an enum indicating the status of this goal. +* **Content**: Goal ID, time it was accepted, and an enum indicating the status of this goal. This topic is published by the server to broadcast the status of goals it has accepted. The purpose of the topic is for introspection; it is not used by the action client. @@ -359,7 +359,7 @@ When it gets the result the bridge will call If the bridge notices the ROS 2 action server disappears from the node graph then bridge will wait for the result indefinitely. When the bridge reappears the bridge will try to get the result from the goal again. -If the ROS 2 server does not know of the goal, then the bridge will notify the ROS 1 client that the goal was cancelled. +If the ROS 2 server does not know of the goal, then the bridge will notify the ROS 1 client that the goal was canceled. ### Bridging ROS 1 Action Server and ROS 2 Action Client @@ -377,13 +377,13 @@ The same goal ID is to be used for both ROS 1 and ROS 2. Goals sent to the bridge from ROS 2 are always immediately accepted by the bridge. The bridge will then submit the goal to the ROS 1 server. The reason for instantly accepting the goal is that if the ROS 1 action server never responds to a goal request then the bridge cannot return a result. -Goals that are rejected by ROS 1 action servers will be reported as cancelled to ROS 2 action clients. +Goals that are rejected by ROS 1 action servers will be reported as canceled to ROS 2 action clients. #### Goal Cancellation When a ROS 2 client tries to cancel a goal the bridge will immediately accept the cancellation request. It will then try to cancel the request on the ROS 1 action server. -If the cancellation request is rejected by the ROS 1 server then the ROS 2 bridge will stay in the *CANCELLING* state until the result of the goal is known. +If the cancellation request is rejected by the ROS 1 server then the ROS 2 bridge will stay in the *CANCELING* state until the result of the goal is known. #### Feedback From 08c106be397f1e9871db5c6041bccbc6eb9e1907 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Thu, 11 Oct 2018 15:40:49 -0700 Subject: [PATCH 29/71] Update background --- articles/actions.md | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index df002af2f..f4be25f1f 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -22,11 +22,10 @@ Original Author: {{ page.author }} ## Background -ROS services, which provide synchronous Remote Procedure Calls (RPC), are a useful concept for sending a request and getting a rapid reply. -But in robotics, there are many instances where a reply may take a significant length of time. -Additionally, there are occasions when it is useful to send a request to do some processing or perform some action in the world, where the result is less important than the effect of carrying it out. -The progress of such requests often needs to be tracked, success or failure must be known in addition to receiving back information produced, and the request may need to be canceled or altered before it completes. -These requirements cannot be fulfilled by a simple RPC mechanism, whether or not it is asynchronous. +ROS services are useful for sending a request with some information and getting a response indicating if the request was successful along with any other information. +But, in robotics there are many instances where a response may take a significant length of time. +In addition, often the progress of a request needs to be tracked, and the request may need to be canceled or altered before it completes. +These requirements cannot be fulfilled by a ROS service mechanism, whether or not it is asynchronous. To satisfy these use cases, ROS provides a third communication paradigm known as "actions". An action is a goal-oriented request that occurs asynchronously to the requester, is typically (but not necessarily) longer-running than immediate, can be canceled or replaced during execution, and has a server that provides feedback on execution progress. From d92fcce795840745b44371bdd07648d1a56b228c Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 11 Oct 2018 16:06:33 -0700 Subject: [PATCH 30/71] Move Goal identifier section and add more rationale --- articles/actions.md | 20 +++++++++++--------- 1 file changed, 11 insertions(+), 9 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index f4be25f1f..34d87764c 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -119,15 +119,6 @@ In ROS 2, the generated service and message definitions should be namespaced so In Python, the code from the generated definitions should be in the module `action` instead of `srv` and `msg`. In C++, the generated code should be in the namespace and folder `action` instead of `srv` and `msg`. -## Goal Identifiers - -In ROS 1, Action clients are responsible for creating a goal ID when submitting a goal. -This leads to a race condition between goal creation and cancellation. -If a client submits a goal and immediatly tries to cancel it, the cancellation may fail if it is received by the action server prior to the goal being accepted. - -In ROS 2 the action server will be responsible for generating the goal ID and notifying the client. -It won't be possible for the client to cancel the goal until after it has received the goal ID. - ## Goal States ![Action Server State Machine](../img/action_server_state_machine.png) @@ -230,6 +221,17 @@ It does provide for receiving a return value from a request and an indication of Unsuccessful requests are returned with an exception. A DDS based middlware would still need to separately provide status and feedback channels. +### Goal Identifiers + +In ROS 1, Action clients are responsible for creating a goal ID when submitting a goal. +In ROS 2 the action server will be responsible for generating the goal ID and notifying the client. + +One reason is the server is better equiped to generate a unique goal id than the client because there may be multiple clients. +Another is to avoid a race condition between goal creation and cancellation that exists in ROS 1. +In ROS 1 if a client submits a goal and immediatly tries to cancel it then the cancelation may or may not happen. +If the cancelation was received first then `actionlib` will ignore the cancellation request without notifying the action server. +Then when the goal creation request comes in the server will begin executing it. + ### Topics and Services Used In ROS 1, an action is defined entirely using topics. From 8076d964868cb67532026499becd3adf7d2e003f Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 11 Oct 2018 16:09:12 -0700 Subject: [PATCH 31/71] Minor wording in goal subscription service section --- articles/actions.md | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 34d87764c..7c5b25b97 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -244,12 +244,11 @@ In ROS 2, an action is the combination of the following services and topics. * **Response**: Whether goal was accepted or rejected, a unique identifier for the goal, and the time when the goal was accepted. The purpose of this service is to submit a goal to the action server. -It is the first service called to begin an action. +It is the first service called to begin an action, and is expected to return quickly. A user-define description of the goal is sent as the request. -The response is a standard action message indicating whether or not the goal was accepted, and if so the identifier the server will use to describe the goal. +The response indicates whether or not the goal was accepted, and if so the identifier the server will use to describe the goal. -The QoS settings of this service must be set the so the client is guaranteed to receive a response. -Otherwise it is possible for an action to be executed without a client being aware of it. +The QoS settings of this service should be set the so the client is guaranteed to receive a response or an action could be executed without a client being aware of it. #### Cancel Request Service From 5a9ccd0b41e36876513e94648a890e64c71fedc3 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 11 Oct 2018 16:18:49 -0700 Subject: [PATCH 32/71] Simplify explanation of why actions aren't in rmw --- articles/actions.md | 13 +++++-------- 1 file changed, 5 insertions(+), 8 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 7c5b25b97..874c2ba64 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -212,14 +212,11 @@ There is also a need for a status/feedback channel and a control channel. Actions will be implemented on top of topics and services. However, they will be included in all client libraries in ROS 2 with a common implmentation in C. -This reduces the work to implement actions at the client library level since existing middlewares do not need to be updated. - -It is possible actions could be implemented in the middlware layer in the future. -One option for DDS middlewares is Remote Procedure Call (DDS-RPC). -However, DDS-RPC does not provide facilities for interrupting service calls or receiving feedback on their progress. -It does provide for receiving a return value from a request and an indication of whether the request was successful. -Unsuccessful requests are returned with an exception. -A DDS based middlware would still need to separately provide status and feedback channels. + +An alternative option is to implement actions in the rmw layer. +This would enable using middleware specific features better suited actions. +However, there don't appear to be any features in DDS that are better for actions than what are already in use for services and topics. +Additionally implementing actions in the rmw implementations increases the complexity of writing an rmw implementation. ### Goal Identifiers From 9ed53591e600e1fd1e61d33672a79f3718e70879 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 11 Oct 2018 16:20:32 -0700 Subject: [PATCH 33/71] Reword goalid sentences --- articles/actions.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 874c2ba64..6a7d4aa2f 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -223,8 +223,8 @@ Additionally implementing actions in the rmw implementations increases the compl In ROS 1, Action clients are responsible for creating a goal ID when submitting a goal. In ROS 2 the action server will be responsible for generating the goal ID and notifying the client. -One reason is the server is better equiped to generate a unique goal id than the client because there may be multiple clients. -Another is to avoid a race condition between goal creation and cancellation that exists in ROS 1. +The server is better equiped to generate a unique goal id than the client because there may be multiple clients who could independently generate the same goal id. +Another reason is to avoid a race condition between goal creation and cancellation that exists in ROS 1. In ROS 1 if a client submits a goal and immediatly tries to cancel it then the cancelation may or may not happen. If the cancelation was received first then `actionlib` will ignore the cancellation request without notifying the action server. Then when the goal creation request comes in the server will begin executing it. From 0172831ac3c7eb8c8a83b9a1058f524524dc1efb Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 08:01:01 -0700 Subject: [PATCH 34/71] Stub alternatives section --- articles/actions.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/articles/actions.md b/articles/actions.md index 6a7d4aa2f..e679f6c11 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -391,3 +391,9 @@ Since the goal ID is the same for both ROS 1 and ROS 2, the bridge will always p When the ROS 1 action server publishes a result it will be set as the result on the ROS 1 bridge. If the ROS 2 action client never calls the service to get the result then it is subject to the same timeout as if it were a normal ROS 2 action server. + +## Alternatives + +These alternative approaches to actions in ROS 2 were considered. + +TODO From ad1dd1f39dfd942eb5446e02bafcaff5a0f6c2ef Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 08:06:16 -0700 Subject: [PATCH 35/71] Start section of ROS 1 vs ROS 2 and move stuff to it --- articles/actions.md | 52 ++++++++++++++++++++++----------------------- 1 file changed, 25 insertions(+), 27 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index e679f6c11..2b3e3f2ee 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -32,7 +32,6 @@ An action is a goal-oriented request that occurs asynchronously to the requester This document defines how actions are specified in the ROS Message IDL, how they will be created and used by ROS users (node developers and system integrators), and how they will be communicated by the middleware. - ## Entities involved in actions The following entities are involved in providing, using and executing an action. @@ -111,6 +110,31 @@ float32 percent_complete uint32 number_dishes_cleaned ``` +## Differences between ROS 1 and ROS 2 actions + +In ROS 1, actions are implemented as a separate library using a set of topics under a namespace taken from the action name. +This implementation was chosen because ROS services are inherently synchronous, and so incompatible with the asynchronous nature of the action concept. +There is also a need for a status/feedback channel and a control channel. + +In ROS 2 cctions will be implemented on top of topics and services. +Rather than being a separate library, they will be included in all client libraries in ROS 2 with a common implmentation in C. + +An alternative option is to implement actions in the rmw layer. +This would enable using middleware specific features better suited actions. +However, there don't appear to be any features in DDS that are better for actions than what are already in use for services and topics. +Additionally implementing actions in the rmw implementations increases the complexity of writing an rmw implementation. + +### Goal Identifiers + +In ROS 1, Action clients are responsible for creating a goal ID when submitting a goal. +In ROS 2 the action server will be responsible for generating the goal ID and notifying the client. + +The server is better equiped to generate a unique goal id than the client because there may be multiple clients who could independently generate the same goal id. +Another reason is to avoid a race condition between goal creation and cancellation that exists in ROS 1. +In ROS 1 if a client submits a goal and immediatly tries to cancel it then the cancelation may or may not happen. +If the cancelation was received first then `actionlib` will ignore the cancellation request without notifying the action server. +Then when the goal creation request comes in the server will begin executing it. + ### Namespacing Multiple message and service definitions are generated from a single action definition. @@ -203,32 +227,6 @@ This is irrespective of the implementation, which may use several topics or serv ## Middleware implementation -### ROS 1 Background -In ROS 1, actions are implemented as a separate library using a set of topics under a namespace taken from the action name. -This implementation was chosen because ROS services are inherently synchronous, and so incompatible with the asynchronous nature of the action concept. -There is also a need for a status/feedback channel and a control channel. - -### ROS 2 - -Actions will be implemented on top of topics and services. -However, they will be included in all client libraries in ROS 2 with a common implmentation in C. - -An alternative option is to implement actions in the rmw layer. -This would enable using middleware specific features better suited actions. -However, there don't appear to be any features in DDS that are better for actions than what are already in use for services and topics. -Additionally implementing actions in the rmw implementations increases the complexity of writing an rmw implementation. - -### Goal Identifiers - -In ROS 1, Action clients are responsible for creating a goal ID when submitting a goal. -In ROS 2 the action server will be responsible for generating the goal ID and notifying the client. - -The server is better equiped to generate a unique goal id than the client because there may be multiple clients who could independently generate the same goal id. -Another reason is to avoid a race condition between goal creation and cancellation that exists in ROS 1. -In ROS 1 if a client submits a goal and immediatly tries to cancel it then the cancelation may or may not happen. -If the cancelation was received first then `actionlib` will ignore the cancellation request without notifying the action server. -Then when the goal creation request comes in the server will begin executing it. - ### Topics and Services Used In ROS 1, an action is defined entirely using topics. From 70b5f8eb6dde9b36cba53a057c4b751423c8f1bc Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 08:56:22 -0700 Subject: [PATCH 36/71] Delete content in bridge section --- articles/actions.md | 82 +-------------------------------------------- 1 file changed, 1 insertion(+), 81 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 2b3e3f2ee..5d9df5a54 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -308,87 +308,7 @@ It is up to the author of the action server to decide how often to publish the f ## Bridging between ROS 1 and ROS 2 -### Detecting Action Servers and Clients - -There will be an API for the bridge to get a list of all ROS 2 action servers and clients. - -ROS 1 action servers and clients can be discovered by looking for topic ending in `/status` with message type `actionlib_msgs/GoalStatusArray`. -If a publisher exists then an action server exists. -If a subscriber exists then a client exists. - -### Bridging ROS 1 Action Client and ROS 2 Action Server - -If either a ROS 2 action server or a ROS 1 action client exists then the ROS 1 bridge will create the following: - -1. a ROS 1 action server -2. a ROS 2 action client - -#### Goal submission - -When the ROS 1 action client submits a goal the bridge will check if a ROS 2 action server exists. -If no server exists then the goal is rejected, otherwise the bridge calls the ROS 2 goal submission service. -If the ROS 2 server accepts the goal then the bridge will call `setAccepted` on the ROS 1 bridge, otherwise it will call `setRejected`. - -When a goal is accepted the bridge stores a map between the ROS 1 and ROS 2 goal IDs. -If a client submits a goal with the same ID then it will be rejected until the first goal is finished. - -#### Goal Cancellation - -When a ROS 1 client tries to cancel a goal the bridge must try to cancel it on the ROS 2 server. -First the bridge must look up the mapping of ROS 1 to ROS 2 goal IDs. -If a mapping exists then the bridge will call the cancellation service. - -If the mapping does not exist because the server has not yet accepted or rejected the goal then the bridge will wait until the goal is accepted. -If it is rejected the bridge will call setRejected and ignore the cancellation request. -If it is accepted then it will call the cancellation service. - -#### Feedback - -The bridge will only publish feedback messages for goals that were sent through it. -Since the goal ID is generated by the server, the bridge can only know the mapping of ROS 1 to ROS 2 goal IDs if the bridge sent the goal. - -#### Result - -Once a goal has been accepted the bridge will wait for the result. -When it gets the result the bridge will call - -If the bridge notices the ROS 2 action server disappears from the node graph then bridge will wait for the result indefinitely. -When the bridge reappears the bridge will try to get the result from the goal again. -If the ROS 2 server does not know of the goal, then the bridge will notify the ROS 1 client that the goal was canceled. - -### Bridging ROS 1 Action Server and ROS 2 Action Client - -If either a ROS 1 action server or a ROS 2 action client exist then the bridge will create: - -1. a ROS 1 action client -2. a ROS 2 action server - -#### Goal submission - -When the ROS 2 action client submits a goal the bridge will check if a ROS 1 action server exists. -If it does not exist the bridge will reject the goal, otherwise it will submit the goal to the ROS 1 server. -The same goal ID is to be used for both ROS 1 and ROS 2. - -Goals sent to the bridge from ROS 2 are always immediately accepted by the bridge. -The bridge will then submit the goal to the ROS 1 server. -The reason for instantly accepting the goal is that if the ROS 1 action server never responds to a goal request then the bridge cannot return a result. -Goals that are rejected by ROS 1 action servers will be reported as canceled to ROS 2 action clients. - -#### Goal Cancellation - -When a ROS 2 client tries to cancel a goal the bridge will immediately accept the cancellation request. -It will then try to cancel the request on the ROS 1 action server. -If the cancellation request is rejected by the ROS 1 server then the ROS 2 bridge will stay in the *CANCELING* state until the result of the goal is known. - -#### Feedback - -Since the goal ID is the same for both ROS 1 and ROS 2, the bridge will always publish feedback from ROS 1 servers to the ROS 2 feedback topic. - -#### Result - -When the ROS 1 action server publishes a result it will be set as the result on the ROS 1 bridge. -If the ROS 2 action client never calls the service to get the result then it is subject to the same timeout as if it were a normal ROS 2 action server. - +TODO ## Alternatives From 8abbb23a6896cc62f248624ed77a88b82cc8eb71 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 09:00:13 -0700 Subject: [PATCH 37/71] Remove realtime section stub --- articles/actions.md | 6 ------ 1 file changed, 6 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 5d9df5a54..720c5b685 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -189,12 +189,6 @@ Python: - [examples/rclpy/actions](https://github.com/ros2/examples/tree/actions_proposal/rclpy/actions) -### Real-time actions - -Actions may be used from or served by real-time nodes. -The action server and action client APIs should be real-time capable. - - ## Introspection tools Actions, like topics and services, are introspectable from the command line. From 69e36b751ef09c72f16a612f5c964e650a8f646f Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 09:02:51 -0700 Subject: [PATCH 38/71] Services promoted to 1 section type higher --- articles/actions.md | 15 +++++---------- 1 file changed, 5 insertions(+), 10 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 720c5b685..c79713cf8 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -221,12 +221,7 @@ This is irrespective of the implementation, which may use several topics or serv ## Middleware implementation -### Topics and Services Used - -In ROS 1, an action is defined entirely using topics. -In ROS 2, an action is the combination of the following services and topics. - -#### Goal Submission Service +### Goal Submission Service * **Direction**: Client calls Server * **Request**: Description of goal @@ -239,7 +234,7 @@ The response indicates whether or not the goal was accepted, and if so the ident The QoS settings of this service should be set the so the client is guaranteed to receive a response or an action could be executed without a client being aware of it. -#### Cancel Request Service +### Cancel Request Service * **Direction**: Client calls Server * **Request**: Goal identifier, time stamp @@ -257,7 +252,7 @@ The cancel request policy is the same as in ROS 1. * If the goal ID is not empty and time is not zero, cancel the goal with the given id regardless of the time it was accepted * If the goal ID is not empty and time is zero, cancel the goal with the given id and all goals accepted at or before the time stamp -#### Get Result Service +### Get Result Service * **Direction**: Client calls Server * **Request**: Goal ID @@ -270,7 +265,7 @@ The result will indicate the final status of the goal and any user defined data. Once the server sends the result to the client it should free up any resources used by the action. If the client never asks for the result then the server should discard the result after a timeout period. -#### Goal Status Topic +### Goal Status Topic * **Direction**: Server publishes * **Content**: Goal ID, time it was accepted, and an enum indicating the status of this goal. @@ -292,7 +287,7 @@ The possible statuses are: * *Aborted* * The action server failed reached the goal -#### Feedback Topic +### Feedback Topic * **Direction**: Server publishes * **Content**: Goal id, user defined feedback message From 1cce6b68f9b95c932f99d33125294bde4cef35b4 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 09:09:23 -0700 Subject: [PATCH 39/71] Move rmw note to alternatives section --- articles/actions.md | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index c79713cf8..bf5d113f8 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -119,11 +119,6 @@ There is also a need for a status/feedback channel and a control channel. In ROS 2 cctions will be implemented on top of topics and services. Rather than being a separate library, they will be included in all client libraries in ROS 2 with a common implmentation in C. -An alternative option is to implement actions in the rmw layer. -This would enable using middleware specific features better suited actions. -However, there don't appear to be any features in DDS that are better for actions than what are already in use for services and topics. -Additionally implementing actions in the rmw implementations increases the complexity of writing an rmw implementation. - ### Goal Identifiers In ROS 1, Action clients are responsible for creating a goal ID when submitting a goal. @@ -303,4 +298,10 @@ TODO These alternative approaches to actions in ROS 2 were considered. -TODO +### Actions in rmw + +An alternative to using services and topics is to implement actions in the rmw layer. +This would enable using middleware specific features better suited actions. +The default middleware in ROS 2 uses DDS, and there don't appear to be any DDS features better for actions than what are used for services and topics. +Additionally implementing actions in the rmw implementations increases the complexity of writing an rmw implementation. +For these reasons actions will be implemented at a higher level. From 2c104afc88cb6e11fa73b7e6198395e76f555487 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 09:34:39 -0700 Subject: [PATCH 40/71] More content in differences section --- articles/actions.md | 29 +++++++++++++++++++---------- 1 file changed, 19 insertions(+), 10 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index bf5d113f8..8aa140314 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -112,12 +112,18 @@ uint32 number_dishes_cleaned ## Differences between ROS 1 and ROS 2 actions -In ROS 1, actions are implemented as a separate library using a set of topics under a namespace taken from the action name. -This implementation was chosen because ROS services are inherently synchronous, and so incompatible with the asynchronous nature of the action concept. -There is also a need for a status/feedback channel and a control channel. +### First Class Support +In ROS 1, actions are implemented as a separate library `actionlib` which is built on top of the client libraries. +This was done to avoid increasing the work required to create a client library in a new language, but actions turned out to be very important to packages like the navigation stack[1](#separatelib). +In ROS 2 actions will be included in the client library implementations. +The work of writing a client library in a new language will be reduced by creating a common implmentation in C. -In ROS 2 cctions will be implemented on top of topics and services. -Rather than being a separate library, they will be included in all client libraries in ROS 2 with a common implmentation in C. +### Services used for Actions + +In ROS 1 actions were implemented using a set of topics under a namespace taken from the action name. +ROS 1 Services were not used because they are inherently synchronous, and actions need to be asynchronous. +Actions also needed to send status/feedback and be cancelable. +In ROS 2 services are asynchronous in the common C implementation, so actions will use a combination of services and topics. ### Goal Identifiers @@ -127,15 +133,14 @@ In ROS 2 the action server will be responsible for generating the goal ID and no The server is better equiped to generate a unique goal id than the client because there may be multiple clients who could independently generate the same goal id. Another reason is to avoid a race condition between goal creation and cancellation that exists in ROS 1. In ROS 1 if a client submits a goal and immediatly tries to cancel it then the cancelation may or may not happen. -If the cancelation was received first then `actionlib` will ignore the cancellation request without notifying the action server. -Then when the goal creation request comes in the server will begin executing it. +If the cancelation is processed before the goal submission then `actionlib` will ignore the cancellation request without notifying the user's code. -### Namespacing +### Namespacing of Generated Messages and Services Multiple message and service definitions are generated from a single action definition. In ROS 1, the generated messages were prefixed with the name of the action to avoid conflicts with other messages and services. -In ROS 2, the generated service and message definitions should be namespaced so it is impossible to conflict. -In Python, the code from the generated definitions should be in the module `action` instead of `srv` and `msg`. +In ROS 2, the generated service and message definitions will exist in a different namespace to be impossible to conflict with non-action message and service definitions. +For example, in Python the code from the generated definitions should be in the module `action` instead of `srv` and `msg`. In C++, the generated code should be in the namespace and folder `action` instead of `srv` and `msg`. ## Goal States @@ -305,3 +310,7 @@ This would enable using middleware specific features better suited actions. The default middleware in ROS 2 uses DDS, and there don't appear to be any DDS features better for actions than what are used for services and topics. Additionally implementing actions in the rmw implementations increases the complexity of writing an rmw implementation. For these reasons actions will be implemented at a higher level. + +## References + +1. https://discourse.ros.org/t/actions-in-ros-2/6254/5 From d71f0d1b2a3da88bc19a4326c716a8027be7c69d Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 09:38:16 -0700 Subject: [PATCH 41/71] move differences higher up --- articles/actions.md | 65 ++++++++++++++++++++++----------------------- 1 file changed, 32 insertions(+), 33 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 8aa140314..50f39f256 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -67,6 +67,38 @@ The following entities are involved in providing, using and executing an action. - optionally checking the result of the action received from the action server. +## Differences between ROS 1 and ROS 2 actions + +### First Class Support +In ROS 1, actions are implemented as a separate library `actionlib` which is built on top of the client libraries. +This was done to avoid increasing the work required to create a client library in a new language, but actions turned out to be very important to packages like the navigation stack[1](#separatelib). +In ROS 2 actions will be included in the client library implementations. +The work of writing a client library in a new language will be reduced by creating a common implmentation in C. + +### Services used for Actions + +In ROS 1 actions were implemented using a set of topics under a namespace taken from the action name. +ROS 1 Services were not used because they are inherently synchronous, and actions need to be asynchronous. +Actions also needed to send status/feedback and be cancelable. +In ROS 2 services are asynchronous in the common C implementation, so actions will use a combination of services and topics. + +### Goal Identifiers + +In ROS 1, Action clients are responsible for creating a goal ID when submitting a goal. +In ROS 2 the action server will be responsible for generating the goal ID and notifying the client. + +The server is better equiped to generate a unique goal id than the client because there may be multiple clients who could independently generate the same goal id. +Another reason is to avoid a race condition between goal creation and cancellation that exists in ROS 1. +In ROS 1 if a client submits a goal and immediatly tries to cancel it then the cancelation may or may not happen. +If the cancelation is processed before the goal submission then `actionlib` will ignore the cancellation request without notifying the user's code. + +### Namespacing of Generated Messages and Services + +Multiple message and service definitions are generated from a single action definition. +In ROS 1, the generated messages were prefixed with the name of the action to avoid conflicts with other messages and services. +In ROS 2, the generated service and message definitions will exist in a different namespace to be impossible to conflict with non-action message and service definitions. +For example, in Python the code from the generated definitions should be in the module `action` instead of `srv` and `msg`. +In C++, the generated code should be in the namespace and folder `action` instead of `srv` and `msg`. ## Action specification @@ -110,39 +142,6 @@ float32 percent_complete uint32 number_dishes_cleaned ``` -## Differences between ROS 1 and ROS 2 actions - -### First Class Support -In ROS 1, actions are implemented as a separate library `actionlib` which is built on top of the client libraries. -This was done to avoid increasing the work required to create a client library in a new language, but actions turned out to be very important to packages like the navigation stack[1](#separatelib). -In ROS 2 actions will be included in the client library implementations. -The work of writing a client library in a new language will be reduced by creating a common implmentation in C. - -### Services used for Actions - -In ROS 1 actions were implemented using a set of topics under a namespace taken from the action name. -ROS 1 Services were not used because they are inherently synchronous, and actions need to be asynchronous. -Actions also needed to send status/feedback and be cancelable. -In ROS 2 services are asynchronous in the common C implementation, so actions will use a combination of services and topics. - -### Goal Identifiers - -In ROS 1, Action clients are responsible for creating a goal ID when submitting a goal. -In ROS 2 the action server will be responsible for generating the goal ID and notifying the client. - -The server is better equiped to generate a unique goal id than the client because there may be multiple clients who could independently generate the same goal id. -Another reason is to avoid a race condition between goal creation and cancellation that exists in ROS 1. -In ROS 1 if a client submits a goal and immediatly tries to cancel it then the cancelation may or may not happen. -If the cancelation is processed before the goal submission then `actionlib` will ignore the cancellation request without notifying the user's code. - -### Namespacing of Generated Messages and Services - -Multiple message and service definitions are generated from a single action definition. -In ROS 1, the generated messages were prefixed with the name of the action to avoid conflicts with other messages and services. -In ROS 2, the generated service and message definitions will exist in a different namespace to be impossible to conflict with non-action message and service definitions. -For example, in Python the code from the generated definitions should be in the module `action` instead of `srv` and `msg`. -In C++, the generated code should be in the namespace and folder `action` instead of `srv` and `msg`. - ## Goal States ![Action Server State Machine](../img/action_server_state_machine.png) From 53c0e3c3eb2079bb661de4815a7e75b8da1b0918 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 09:39:07 -0700 Subject: [PATCH 42/71] specification -> Interface Definition --- articles/actions.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/articles/actions.md b/articles/actions.md index 50f39f256..bf89bf258 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -100,7 +100,7 @@ In ROS 2, the generated service and message definitions will exist in a differen For example, in Python the code from the generated definitions should be in the module `action` instead of `srv` and `msg`. In C++, the generated code should be in the namespace and folder `action` instead of `srv` and `msg`. -## Action specification +## Action Interface Definition Actions are specified using a form of the ROS Message IDL. The specification contains three sections, each of which is a message specification: From 0f587c09403c47c68b65e34eeeb2b51845006bf8 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Fri, 12 Oct 2018 11:01:58 -0700 Subject: [PATCH 43/71] Add goal lifecycle examples --- articles/actions.md | 23 +++++++++++++++++- .../action_server_state_machine.png | Bin img/actions/goal_lifecycle_example_0.png | Bin 0 -> 24041 bytes img/actions/goal_lifecycle_example_1.png | Bin 0 -> 26015 bytes 4 files changed, 22 insertions(+), 1 deletion(-) rename img/{ => actions}/action_server_state_machine.png (100%) create mode 100644 img/actions/goal_lifecycle_example_0.png create mode 100644 img/actions/goal_lifecycle_example_1.png diff --git a/articles/actions.md b/articles/actions.md index bf89bf258..b99708325 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -144,7 +144,7 @@ uint32 number_dishes_cleaned ## Goal States -![Action Server State Machine](../img/action_server_state_machine.png) +![Action Server State Machine](../img/actions/action_server_state_machine.png) The action server is responsible for accepting (or rejecting) goals requested by clients. The action server is also responsible for maintaining a separate state for each accepted goal. @@ -220,6 +220,8 @@ This is irrespective of the implementation, which may use several topics or serv ## Middleware implementation +Under the hood, an action is made up of three services and two topics, each descibed in detail here. + ### Goal Submission Service * **Direction**: Client calls Server @@ -294,6 +296,25 @@ The possible statuses are: This topic is published by the server to send application specific progress about the goal. It is up to the author of the action server to decide how often to publish the feedback. +### Goal Lifecycle Examples + +Here are a couple of sequence diagrams depicting typical interactions between an action client and action server. + +In this first example, the action client request a goal and gets a response from the server accepting the goal (synchronous). +Upon accepting the goal, the action server starts a user defined execution method for completing the goal. +Following the goal request, the client makes an asynchronous request for the result. +The user defined method publishes feedback to the action client as it executes the goal. +Ultimately, the user defined method populates a result message that is used as part of the result response. + +![Goal Lifecycle Example 0](../img/actions/goal_lifecycle_example_0.png) + + +This example is almost identical to the first, but this time the action client requests for the goal to be canceled mid-execution. +Note that the user defined method is allowed to perform any shutdown operations after the cancel request before returning with the cancellation result. + +![Goal Lifecycle Example 1](../img/actions/goal_lifecycle_example_1.png) + + ## Bridging between ROS 1 and ROS 2 TODO diff --git a/img/action_server_state_machine.png b/img/actions/action_server_state_machine.png similarity index 100% rename from img/action_server_state_machine.png rename to img/actions/action_server_state_machine.png diff --git a/img/actions/goal_lifecycle_example_0.png b/img/actions/goal_lifecycle_example_0.png new file mode 100644 index 0000000000000000000000000000000000000000..7fadb8d2ca8cefa543bd1c8d2904b4190b77dea7 GIT binary patch literal 24041 zcmeFZWmuG5`!6hrIDklZ$j}1_h;&KE03rhtN=S)FBi$VeNDNW}q60{WbPGreh&0lm zl$3;|@4E1Qp8x-O-@T7xe|Yz?zw8gU$L%__&?>-C{e4;6{U47{i(6)gQ@_IDTS_;Oru$R3yK~-4(PzIx?bo#c7(2TJ~cID;wesXSu>HQ{6ppzsgxt zzP9v~rrRQ~zvdo$eosm9UU$)JHp-pV9vSgHINBdG@lX6?Qe`{A?EcLuoJYS@=DNfN ze~O5M@pj_b-P_n!8J;;lJD;eWk5_YhTLLd^{)BItehzLb0IKNVYh|IRGFMNF9FXt@>4 zZVV7|B=lUv4m|s*U2Q*Y!l9XAYon6#Q7rpG5|07%n6Y;ek8y)&_WE0%s3eO6su&W% z6M|0B_WLhd&JV3J znS#+Ry>ZMT)AztsreVu!@MF!s$i`*5>Ya#({_h_7D?av5PYH1LPq5?ZJ-dlK)a#V(nf#>}tg%7LmGWz{CMcmIv+Yj^E zJK0rp{^Y+wji9(vd(D`vT2*DTQX z=*`AMW2vI$5VE@}CtdqLr}Vh=iVc|%P9YQFH~cuSGPuN^ZnqJYKl#Ee_Os&a^XwP@ zG5jnTzIq%Q{u3@w8^zz@gH-U|t_@|sK;L|*E7Gl*BA^%}x&YgM11s{~{&;n$(c4{Y zZ%{t_eu1vn#?))EXL}XtPe<~9GJ4*f@!aj^Sgvk9D|)$&XGmqQ1w!)t$yjmp>~D>lZc%uMlUtoc0q=h8^z z2hv|QBI)eb81!AiuR3~l4)KC{iDgg0{zqY@V z#~QYU5$^M7;I~(sw&5a->M9tEHCC>BUJvXr4@Q&zIbTjP*`qyBDSlA-lrQ~p|Lc^B z>7dc_=VtLrNJZJ3ZDW`d_U_WUPsP&qXE%i((G)Y;FUD=2Qz{^rdlC~8?ux5w@|z0W z*&o(k?w8m?8+>@I`s@2=p$gmy^)z7(RlK)7bi0e63C~UrlSF2Hv~R+hvcZycXD1nR zf#-N+VAgB>Ce0nc2Kr}xx9(!vg*Y-i-d05`qxCrUG)9Z#P+<;T{5qMNX{^_Lxm3by z_QyI{3}Kk5^X;eK2Qo{R$k1^4u&x{D+gAx+{`^*}o#C;7SGzy@P>4sl#_r_cr@+(U z_fi4fFVV(6JBl=t9;L=fDo9q;oTbyQ_sqfqf-Qb%Z}scp5Te;F8a-q&z^zw2%t2vR z211dVcF}4c`?QFvS4EHEP4IMmk5$+F>_qp{`#P|+k|CmsPak? zDjVrdEuW83nD%t-DVbJ@9jc!7Z*tjQP9L?`kxzY zHl5f<7ntF!gld(pbha`+GLwuYz4}H@2ji0SV8-vn&Pc~1OMrn5%w622$AV#XgYQM1 zWMI>;ehFGNzQS#VsS0at3Y)2_B0~_uhsw-5TY0&+y(v>p_SbU-PB!aH*5o2`{LYR) z<%>L|%6%qTp8d>eQq|r6&#%lsPf#DNGJV;bk3Kt~pHTaMr){8aV3)Ity*fj(F50Jv zi5V+2(C)wU$HzC*sQ1;){by@E64j0jRo9(lnLMog|D4Q*Ue@T0rsL?m;otDuXSZ7} z?Ayk~2iK-x9Jn$mYpLdv8k!THWa3xLt{vNSH?7d~mh$(JNIkWsG2W%r;`lhBY?|AT zS1vgwT=p@&Qc8VII3SzbC{7qF@%a3px*3ll`}FtX%iXzPqBR+g_@Nw)w55WQCN5MD zJI&3SMagK)J8+^^!|$dPvZSA}rA6p_Ep|ljKjwbF9V-{6?by$>Bzv09F|j~Cie>CE zf5q3DCA1rNY5{%|pDlgS^eh@1dw%E^3nrxcquIj`k3a8?tTmrZZ@C@PDuvB=7jU#K zHJxmJ<X54ozk-AgPT?QTd&FIX!<8VUTjg2 zmBOTj*}S2cIAiRP(3s&nP4cNKyRV_2H1C}0xXLIua7<#NE$qs%qR*~k?A_LeRj1b$ zDAUNFhcPj(pPy{;nfM)LPfkA@kgBd{hDBT@DNirGbznEATIP@Qu<>}UV8s0U{>@W% z?mYLc86;|BYYq{&rSgMKB9cR^!R!16|DzU0eDhgJJ2`dFHcn4%H`Pu{hJYx9K>i@Z zKn92H-MgJ%7xF01L`4Nlj22dRXbzOUEu1N;lg}uqWb2zmVVHDu@*o`6%0wi!7n>ux za2LgdZ!fv~i%9zSqjW)9p{E#$Hxe!@Z!%D3&zZ~gTg}$TO7y6b=@QA{BJLUKZddc0!$#mPoI6bODL`v%)nNpK3%tttdKZzLoRf?U(04kWL)g=wPJ@yg? zO+K}g446dy?T);pGe(auzQ=oCt_p658T9ZTV&yd}PqmL;jBV}Z-8KM$sbA~|y>I+utoZ21 z>bAkSggw<7EZJ{UXZ=gmIx&~#=RV6Yl6PHBt6P5caL+%+;Ntf*;1^V8W{4 z=RAY9K2hs|#|l29@$WQ#p%bZiiiQo<1opgKjl#^zU<*Wjtm-|hdqhiJZS+JAlH;=K z-5aEI*AHHkJCL8dyNY+P7}Z(4%K+sCT{2~EbVUNGCWdF}%JSY<%`tu&k;R}Z1TJO) z6{Ko@m=MXV$N+Sg@zJ`;pM2BjttxmW*Ua$ZiAkr-1>hA)HxRc1Nl+i3sqq|DT4QwR z$<&Du^LC}@5kH*_O&01JL@(9S7T~1T1VS_-QbF zxZG%B1dLT}LSt_z*hZz{qZ=OlSpa()W5R@`nMIbzyGIx_?`dJi0z6h1#T+G@b5+Fn z9;i=vqn~}COZE^`wsib(zvzK$^)-T_5LuOh{`#q8jxX)o)8J8J1(DS|3!|{yRhHAP z&1JwY3lC|-iad%Vh0~2P1eKaQ8u?)q9^cUXAc>dzuKj2CO@=ee%kY#}A4SbMBt7Qt zlL;)!M!L!hli`NC(r?6+(zD(23Aeh|ePv!^gOZd5@s=Oe`i>dX=S9Ap;l26gJ=Vc1 z9!n7#1j$<4y14_vAu(Hu5iNq^PmEgl8HLG{ zS^WC7S)4r{E&ceV&>hldzxF0}PzIOWREF~PDvy)b!fD6>lcsboBMdfZa8=@9++64= z2rtG%ir{m|jbAni3V5wPwoeF#Uc4|jbE;Q;K4n6Ry=~?J!;_>NwPK>_Algc=RF$NN zH(;WUxA;9T8yt+72;;XM=bskmH*1IOtJg5rw{C8ysuqNv!U*Gad)p{Xg+}k~V1k0i zghADBM@DB+e_27X=jK6ja=DuCxRe%_w5B>8htv0${-^IwXaAgK>PByR{@ev+<51;r zC!@FR%R$UUrUdq<$~%XzzOj~F5fH*ty}cDjOc|0r{ZyqyXQ3+c^x$r7#fn$H$D~TP zA|k;_p2=1uGHp~b>G?zd7cn|+#ZglpA$iS`)CnPEuQyvR6R9yp#${~ifAoLYU2peR z6tm=&UlWHCRvs@a;-6-X;i6LG0aXsAzCn$s{i4=A{{%ZC_=Xzwi%RLYVo+fp_9Xa_ zjVy~OQiF(F)U+5+Gm<)A?f8O%g3&|66AR0)u zB(D+}WHi1LDZ0mEVDd$1TsW|Q;}45LMCF5WO@n$i@mK01<#8{Zp~+C%@9LzLs>1KL zt4pWDk^v0*d|DMA+d44GY-%#9M=SW`%~HZ)g@d$O6=9eqUKO*93h^h;AL+R^uRK)YxUR2N zUM#6Wrs6bXLK2#E%#BGSBGw|!!q>9d+7ClM+~(J8Q5VOfgVz2OjehPj_4t4}ja=YG z$%rvOG-w+K7?c&hw=tppAsWv-j=C-9ydl^3M>Qe)eH6Z&jp793A`;nsoa#QM@HUq` zmNb)Xs;-UkqeX5?S}yrVnlAQG*!5IpE`Sjo_OAkl2c zPaoFPq*g9U*5*zx-SU7aH{l*O>7&_)PF0<(VOzVu(DD01TUC)37zJv+6nl#pc8Sm5 zR1iT4p&Ixk^nx#SgilUpAF->oS((ty^IreMrWFwCKboxKr{Y$AaOcm_Kx5TMM{){P zV)gH*lG`npk*L>I8Yt{3!||5SRhO!Y=OP{7YG_q;I+nvYUdode29~{Qr-|M0H~;y( z4YopL_hZ_*#mk`74m*APyp@vn0L|R{fXeuWZ(jl3$?0=&4nnu&L{r8w#I3TCamdI1 zw`ezr-9}UpnBdl&-Wqg`Mv&=^F@Vp$9n)PonflRpd*D>aBUgQ#A|}|+V!z!Q!jYv@ zj^8?1?9ZZu{sF3D`Jv-kiQkx8Oe<|WdcEVl>??b0*KNfGPkMPeiYwF3YMCvaQ)HM* zn|(orzR&%`-znxb^!+eN<9d<}->xFz3G4KvEdcPZuD3q8b;5lOej=R!0}y&(wCJI~ zr7~~$^9S8GvFR;(=c|#e@hfef*V*8#Dc*k~Fe&=LgClbBaBz2UqBT zxipJ6CWJhyWWwa&=Jdvve{$McXy>_G0x6f%>nmG{^9;1%^v)4Y+#Sfr#E*W_J9I5S z@rqfD(C*^Bqwx7$z}%+$snE$39R(l+#%CEZXsN`Z+4!F#DtB^p-${Uzx~ZRHaZIw^ zeIA7#a=4*uevM??8Wl0Wt=QBnJ&`GbX}2i}zeYpqxmbQ(fehxi&{5aRJdqrDe0q{q#kZV{DD%~81LKebiYobh#4t`vUkF>akmANrM zhuXEy;xm6`Lt%9d3>GD8Lm|O5mvBad5W7|rNsS!}pZkirr*HD}WE&1X_LN6T*OtuR z_Wb&uAE)meU%snpfED{N-L!`4(b+obup+IFy@Xl`fbI^mlsV?J%^Dvk61T zX9c;ifC-Z>T-L{Hzb_`ON#J{{KC@w^cp{Ukje6oP_*4lQCnT>esSf)shzP;c`}&FS zpQ(2Hy55#gz$XLCWJ(+Tdv)PrMmx9V*UP|dQe&UPA7PeelOMdixNZawHdqwRO&g0M zM91^Avrit|@`JAbzG)m`doD}_n9TEl6psi0toTz}T?5056r&enhl?Tb!>yAkFP4`Y`;#nS7(`blD*ySrwPFic*lu5qb=X5o1KE}hK5qVp zEJx77LMwQ4Zz7#a3asB-k;l^38_;SWS)`06y@nP$_BL_RJTuF`7hADPy`J9+1m)#x zUN-s)KIM17Uh;ees|s!OG1zED|7%58FRttn93X-L(_M>p{q&yYUym@y$uF?_4^{}W zKBpl=!S-9R$E)FhfmpH)AH-MwB*d21z@NE>j1vF5o?wS>)g?8o=7ZxVPtzT9u}>)0 zo84$(=$b9Wnwqf*Z%8XEn6NJ^;~0l zbdY2kP;`v_ccJ^n2?GV0pxeb2Equ=NU$<*eWo5%l2yQnUOQGOx7wqrF2X8$?cUo9}ZShMV*5?c-0O{cqR6E#ln0MV!K4>4ji{Eq@IU?-^bdp};i!P6E_G`6!cm=)}$ z=m9tHh>8Os=*e&1lH9%Zl4c}e94$Ym3ZV*gZx-2%mzp{+MvFjvN@(fqc$s;&TqwSP z&yX~Ln6%Z&%7TOCfXmlm*;3j0XorKOr++l0t1mXy1BxVo zu}UD|t&!pIlYAjy+0z9IhT@q|5OTR~)jurp1~5Cjxp&S~A5=Vn1NfGdf4`t-?ql$B zY1{RLH2XRP0^u}$dq9$f=+0?rU-B(^)v!MWI(ctRo8nlMdk%h1L4YEOghi>V!Sh!| z5iTJuXP%6BpuJDO>u{Ovgut2K+HhXE%PNX3`^!7!|KPl0q>rCWl$r*Ua_&k~fCoO; zDN@bk@59Hj=sh1wwG<<X4qa-5MyjCdc%fs55iH9@Z18N|?oEP$i$?%f!qk7nmk1C=? zu*!&WgITvjVE!bJSuj+ws7z_!3x3G=a9R&A1QPSstD_Gc5&_}K$A)_ACrKyy=FOZF zpor99EOj18GLE}CL@x%7%_eG}aNt&jO}E`ZtqM5M^uU z-W3l7i@;$7w{W1`|&0u2;QFd%@=<;H*5JSz6(6R)YR7rG z)$y`-IR^fKB(6Jef6#xk`WrJKi&1h+tjh2&SVT4-gRVT_!1-V|CEVDg5J{TK^aW7- z8nH|?feHjLym&Lhd~n*4JQZ!JqrZ0+M+oFz5l`1|H5K4^oge*Jr=?;wC^42YsC=5} zr4>Tg%`6Eh;XU!aUs=#Bqd=i_kw`-ay$oK$Ndg@iuE;&|eSEMnA@;S(v@I-E?5e?$ zF+}LH^$%sMNw|;Xs(!5f%1%uS#pa8IP4O~lDa@w0_OS?JeuB8J_dZ^$yAu;z*9v$} zMqPy))Tx}oDR8zlAGQAi#nlFQ_FE#W-^Jf5tP@K6<%Q`@1dLJ@zH0TKn)l-tH6;flT zD7Cb@rzq9L9ve~Z8!kJ4W3Z97fGzz%7y(hnOJN8wNF@eQp`Z+EB`)9k8XBNkMQNbf z%^vEK@?j)_DzL!@8LL$~fNwB{*K)sKsfC!67t|T4aVV#vkHv@Av4oGD`%tlSv4?~D z7vGS$R3vYp46bPq?lXXEKw8P0fhZHV$)@pBY5ylY+1$9eKY^7JDVoRc};c~;39`RQ~I6OW{Lhlnqmb^aH z_bk^)jQX?_J63Y*)ke6^4imzmX?Y^yg8bTuZ?KxXmx`U|H;b&Pu7F(>V#(&zf4xf0 zg=5HZNw4;vYd<=Y6`QiDcc-*=W~10yY%@ma#w{GfpFQ_^&89_M2?L{;A7!AF<|})A z6~GKgm(O>Tn!75jzlMyNVG6dr5{w(YR;MC7u~@gJ7A~2@sP-t%+kGl&JV=B8Wx%wvkWG zGAEA3+G7M*VCS{G+|xT;ABzNGg*o$mVNK^lSGSPbg14t=R%F zcj9KV-QeY#-HEe7eOkCj}IcAzd3a>Jh(bv>wmUxa_q;qc0M(G z&i?1n|4**?ul^zsk3WrzJAZZ6OY4hv%d32fLDL$u+rh|JWkx3}ZF(v64B?k?uf_JK zORTqlenF-w@l!B;{H4@^{#oW06Z?{c+Xg2HYqRp_?#(CZq~xq&roAV9F`|G{IMAGjuafLF@Nk(odq=cPZ@I$~MbWxf3WZ_)Zl2d^)15^!I zioQ7jddAS#p_d?2WyJ(v7gqsV6^}#X{wp-MUVkBLFHHY8Z*Ra4yZ-&WmixS&(`DaT z!U776t~fWO;b|^^7?4gNWkbHF60qnZ_S|Yb6uiZxZ@y!>3gx^^h_0Dgmh~^VwGM{-mI9}S?uHv9Mbj6R({Ed3?L@t*t+4|1uysf^_Y#T zp%moa^=x7W)(8&8Gd&~M#M2*l{%D~-O`ROCmn5RyHpWTHz6iRug#~ybP3ht!kBK); z7alpU07%zW>8j@d0`sxU=a0FyoM3^zMpgi75h0Svg^-n2-(|(R7bEta8X{G_G>8do zZiRf?=I_EhZ1k!$^gCJ(iizCyKmMAD0sD50^jhN9dCvs&i(1kF({KiMDASZqu6%hX z^ja_XE(2Ri5E9Uz5PhBiv|c0W({1^A%ja~$wy}#Z?-=WU5IcNpZE2$A|z?c0LFG;3S$5=zd&Z+A#z)54%_H ztbyD%qIqZ?)z#J9%u$zZph6g`{s1E5J%J{=__CDM! zDlt>eaHS`uhb74}1NEb-(5PPb@jynAjhxTji6-Cru<>2)XgZNs8B*R{*5!}ek0}g- zLU3p@Z}*GJpPy~{bL$fKt8%1c{K>dBKy~KjvhoXvMJvY?GbxE1ERW{vH_V%qU*z4z z7t?ij{}mz@F_OE+@LK`7m+2Y@o;&3+)^dYwUVSzJ_6moEsy)`JluO_t032AOgx;h7w&8R9N)$d_uiVZ#}0m(Jnm5@$Y z{dQHv&&9}6laT#u(&jbf{w1mmsEyXYBVzBGnNA09dG_SKxs%{Fl7D|h?NPji zSp$eY_f1M=^$v~(8OfN=%$-5KR<}7oBlHwq+{UlE;54VWz2vc)o%FQpnxsJkhfQ>5 zu~B{gd112)kYl7cj+Y)lc|~l@?d#2OyL&;Ot5^+6mC*Q!tODOr*imtK%3cy z0QHFZhjr%Pa#}jW7H^u~shy;*roZkJD8kV#9+T-J4jH^rAFh9t6Jd23Gji{q55H0D zZ9SNj>pm(1Tb02--Nw<-rP`IenUMAA7~3^Lye~*XK_31oc@PEAf;-FAqb&JSldH^_ zLA@@lAk(67U#SW;&xJ@1LBn>}mCIW5aKWd;D*aN2hHP?jW-C`dGIvhGe*f9+<;y4Y z4VHv2Jt_*T^Q30lNbJecg^B=P#ScgW`l&fA4u`;~?fjN)P^)Qw(_assD^ei9BA8wF zXfT8d19jJMb*_d>uz=R47)|LT1-!^@{4x*x_RBPLU*_QatIoF9UTlXr;xlIl@VpP_ zxfxLcxT!TE{@T~BqXug`GPvsF7EjsYNykW9&7^{>nE2!j$%i7p?1Kn0t${p^{(+S; z@9M}ff1`n@RmFqjRKwILSO~X^iSr}l>qo)MS8w>d5g?|{V8FRd6PMTVMN-yOD%fp% zJSeET%a|S(gZFBi#CmLxgNe;z=luN*`rUZa1R>MgqqT-F3XE!dYOB)h#k!KqT8*hS zJ7R{Nxi2t)CL(xckxhn2y&)DSgIM!8WCFH&1%pFE@3|CL7t=zPW+DQ>>!i;db$r`AqkMYLG)j>#VfX0oX4t?gwjHrGjx#lcp))v^-5VBusM}=gm5SX zwtop9fH~lXu74yb2dbC{Ka-C#B`sW<@mdfz-tP7#L_MWmxl`gZyRoHffv3c!+eR^V zZTpYi6MJ>sx9_Rce){@`A0dDR!bO;Zz@>J@h06)IIvZnCK2751N_{wQPbJL2Nsz>l zw4cDSC3z$x9-%tT=e$N^Rbn5_r>eeg$1b+|z>>h%jqM>5GL-yA^>Ir*J}H9=>m$1t z1H28}azqwo=@f%>Haio1^yDn*M+4>r8z-|&M1wsPDXX)9;}mm*6$- zZs2%4;pU9KLqjS(@xWF!l7}y&121ofJiSMnVr(i{7#1F9K^#k(L6}u<_^KiD`ow7H z)k~xVqOJjHh-tR1R8;x#j^NHEG3l%E>e&}%c3y>DxgSf5Fs$4(QkuAxsP$Xu{$#6r zC>%Y%W#n*R;Y^Hu8K%X*5=pSMs+%@QGS6L}2J1Wn*nCY$R;QM$aEy4=yeNX0(R!qo z(<9D9nb8#(OT5;r!dOI?G@G1X-m8UilYF}rp9bOpbPb2TJX?G~QMTM& z={FQ~nvv?fqa^x7rm@dduSrwi3RJo)IUz68N&dk_vjETK|Z+UgHkH-bDO%2r-DsXQ`yDJtkWx92jcnvH}Zj5Qwh z#sEODVX|@W8bQrW;h6+dZ_BPV<|`@tm+#(xT>dC7^K&M7`P}dMXOxWtzyWdgy7ItpFKd`QaFpdIy(n~v+y!sXl#tbfh;YLGl<5Wr z$)Z^tMsJ+A}sTI<2MWB_@^Dxn79*g(s zCvVh3UXpu1e_2^se4ilh^W1N9s!6%Vn4;&0~ABtt`APU{qBgS4_ zq4VRknBI|}zYPmIhKB{vGhKs)4#49B)S0MZ5d-k30Kpn-GSx`Bl-7F3-&r!YShaCp z{X|#d@w)h9uM$`Udp)6&N{ND($@n*1cAR_GZ*BgEG<3`<;hYe!G>ft%s8to;gQ+Xw zT;nlgs3SWgL1w~n%$S_1CMo0fed4>Hdb4690+d4}m5Hu&&WG%<-!9>ddPgdi9`A`9 z_ap9D3?v-r4z+#zG+`zI#qR-x+AR-SD-A?)#5=3194Bg$h&3EyC7#7XZD!yw(prc- zF0T5{MJ3!|E|0|8_PAV#kkyUVo(m1Jd!(NE1U{#Ipj{Drs5ZrP5)*FqJ-a6b$&pdRIMlcj_yH@nR{AAoJh#3?w@M)}p^w%W@+y*BzRZyUp z5IAqe4f^|oTM#k)<`Rx!cgKBR+edVWP&)y@$`hg4@1LNgt?ay~1?+fWnQnjRqQr)>WYWz>qp4dcXGN|c=LSNz$qH*EvcaJGZn`)s zUnlS0en=7@uERINL^A{z8JOTF`&17Y;3U8mh+V9SD5B7CL%(VoTn|EGEm^3v= z0>i*Apl^HA9GX%p?Dn30@db&_830w}Sh101O8}O03)a;T3qh1#TdRAX`C~nDLM-Tn zai>zI)c2?$o{i_|`~tWcF7$Lb7Qp7-w~8-9{=n1ov~zm^-4oDL%6i@%;tOXZmD=L<45H(hy+uivqMGc&wGS zPm#)qb$@+KkBES!kI$!5CNomA?AA#N9e7-F-pxtd8QTg@h8wNF@JvvGoP zg+D*NppsafDYsO!2KK??mx_&013f=bE+r0>Q{P8fn4+BQ!sW z*qnBsO$1)=o}(X`e869u2yB}w0K!`U2)3qJrrW-B4%7`5V5qY={k^lM2)?3mh}hqp ze(0|f%S0bOMuvHmuripddBdReQD8jrU#7SiFvWEpBM?)Z%tT`fjC@FySaO?ttm>>b zbOuz@K#Oq9dstok+HKN0|5-LNQBHt1uYd$Rru!L_6tzk%(43v8GaG(hL@MStn!qd@ z+9%f4(0S#gWxC)pO;`2aghQc`b?G=(xL;fsux3kPboQ{?Dn;$BL3yG?2=uh2 zV&*=$;fe`?MSnsuc|S~smc$WC0D}3iUgZPv8T;M+czYcEt%dN)%AoW9_QTi#8x#w|lsPEg=sRT+b z?kB%8(1z?p^?26;6>vnqU^_&Zr(Y25@4&h6sgBr62r`hbA=#b=B73Wye~!_0Vy2}N za7xzaD>f#29{OaGJ7205O2Ni%n#znr;deZGyCV}YI1PeUrh}DlCi%jxo-aSMw+^f@ zu;(!aHLfYCtL~Gf_4moM99g$uXC_oTz~iJXkp62lZdsidD0gpxM*o0My ziWFZ3+vVO(f53!jJeaiEU3vF%t(UC%c#S&`2&QozO|rqbAPkZpfur7iChPBDj51F1va@JmiO{%Yepo|El|KUn=hlpSKb6Ktre7v5;Hg~v3)xPD1=*; z0WhWl9@~%h(O{Wa3UrI&f$C+G9K99X%KgI|nE0XO0*Km&ZI3-9Le7C0#pb#;tQB+w z^5Sv_odX)kYz2P6;+qH@;7{lbA2#`TLcaF3ONixM@9^skI)9FS{pd};WsU)9+Uql5 z?uuQT&yUvyfC}eZW2qL1aHq?(Sp^e6N8Y+m~XM zk(cljm?@b(DBP!AlkS#7T^;eHp??gN<)mS=WgSEBwOAlAI$q~(ZhJeSsVovueXp|Q z!;v7^qC)_+R;m1Z6XNRuC#(9SKmD-uhDzMQHrgYcqOJ&#Z%Z_lHE`+acScX)&E{#+CqrP#M*{!(U`Jrs}=+sTe8+dIzqENn|Bd#mqei13Jk z5fdZVik+be23ZD7`?p}UebdonHp(vEGS+y~4E!1TG3^=9FR&lLBrt;uF6%l`=USjs zsITRBeq^=(9OV5tJ_Os^OtphaEnxH#eN>vB3}GTk>5dl&*(qDyrMwS@OP7F3kd>jA zjD)7O@!zKf>|npwTM77FnAzl>gmfJrZe{WzOv%+ZJp?MkuO`&wEXg4YO!`Q(e-op708fhU7Zggf(}fTXtL`9{LuAN0qp9my1*{H)IOdKo(u&!%?3oDJOf zn)0uzzd66~^2=6Bx*k2P{P`SprC$XBdHoJx3U;V2HKYe#$dBFFq5jb!5Ky(kJ~ml#J3w z_is?$2-Sx<$}M0&&A*iDb4naBiILI$1{&goc$D1I5}*7X^d}(cjRo*!1W?EkLv=sZe%lie=3{JRy3~3!l5# zIdsH)mJT}-_DBzMH}qRwp@gh|Uq>135E;6N}sJdkD-=7-@bK3A8 zLqAvW4>{cogp&7C_1S|hfdD9Z<1&5V`Wo>!r7M}26;=4Tz z7}&s&&mEIJUj3~+%5CqB8t##RF(b}lN7I*~JL+~gshqKds*%u#4vqK0fo5@NI{MDI z(zrLI20C$+J&%@?pq@8Q;t7!%4|(4I$m`3%j+6AS%)T3ur3tdJ#b}{{fZb#TrmkMM zr@$WQg6soQhp$1$X3KtgVb8^i8whdO^j(GK3|jM80e%^Ofu^n})0EWW@KebH&zdtR z9k{jFxEll@8_t#ZArRQvftvXq(qnf4|D+1)^cNP)gtUT#?(cSxsi!XPMak#D$26tV zO;IY?3-T1ry@Gy!oCO)A$T!De8EQ{8W<(>1dCq;eI$;iuyj%z=;FR43%0v&qa1VLf ztj9~UAa{}~;?A@Y9Y2JyZ#yd?Q$CJ7-KP$GA2(Fvw0O~WsK(c*^NQCff9ARcKWImU zG?_yEGC5=4{rlEq#p#8HwJ2fxZ=8@y>m~PsiceSbs^>97?2znL239>2-^#F+I@k3a z_y^E7sIR&fD}O!iWAIgi3=}|^5d0|jIdUdE+3~#xdBIjk3X*JRn~eIUPizU(=6@0& zPyN&4hxZ*oOA6x-0IMxW95%+wP+4+U?1F82fpWdr`BIO8Df`rA3pl>k?)abkfEJ~w z;rCkdB~VvjgWFtnLhA8Grd9tL2D5DLACt_hz1G?0uS7nnkoV| zYvj3{I8 zd$!5w2{?yCVvuykag{rIIxFkL67vs3!r!M^+Dzrcslf8LR zC8;mY+sFQS%#3O%FG%eC1i3R`DKmOnywrF7cRr65@u6xa`Bl&fouDr-DG*mI+WVah zJ<4rh9IU)=a`4}DcM?H0g2g97deM7rW){^3k;2#)-#*AdtI+v=Pq7-ljo-z2sT&k~ z&u)1VcMW4&Xo>D@u$9k#X@fsB@4$UB$yHc0X>Gc1apJwD8hPa&%ETXFp~h0nkB2Y# znpB>PT}~}rI`rf>$adDCp4x7lHqd%}=@LUS^j-k}Rca2(nF*1E2#Pdm19i>U$Oa z(MHmf$4IKOasVpoGyS`)mmm!aD#4o`9NYVsF=w|#U3PA@Ss+$bbBWj@G)8BfNF&Iv zkkzw;5&(RGHM_+p$Y^EaHiu33MT+vFX30DOIQdg5+DF)M{o(hEtW58$`%Ikpf+iR; zWz$tIgg%WJd8AbO;er^zi5}AFzX?I=TE(#ke83D0vTYteLFpD@pd?flj0c3%U3`f6 zc3?FbN(`l7VmW&*Hl_EJPjer<|SY~?m49mZ{o`()CMCA+R&9`^t{0=XwkKHN1 zB6k`Y2&i9_&c&yU@2IDZ!L2JHzf@{`l~jfmq+?jhdeW6$Ef-_VAEzI!KwnbYRDVDJu5tdl%qeYp)9MHSWc` zY>aCe|C<2#87(pstHxWa0J@w%$ys_DodDL34;TT`he7E7^o4jN7r4&^Y({xfgzX-n zrj59l?~4Gci|o3MF`(1dEe#TXK~+%s)4QX|M9_qJ9#p7!?X8qiA#S-rE!lTZV^Kg& zUItca-M2{Hwb3H(2KF2#Y;Vxb8avDq zzJBU5ptG*MzyIS7wi8n}oqdfgQ&a<69D2s{2ZPx6Wb=?DOUgtvqsJW95rE~(;MD~; zU(Ewl(4D}+4S;mL&1EHIv5KVC1T|9K!VyT z4#1`E-Q`}PzK%oLBfxuL^h%7&eNWuPPBuOW*@jiiuQ&kEih^uR$xzeoEVa@9p)#St zl?L^8`_8&b*Ht+Gs6McrvjRuly?Epv8s;PmUy)$ z6E%Q^vfu>R<%A?*DGYAorq19*7q_Y``6?AjdY4ZNNnfuS_2QNhyrKm2@q~^LcRbBE8 zxUZ4YtR|qfULlgucL$e@V7?xBww~(mKIbmJH^8mV_Vgf$%S{QH$NYG=Oc|g=pqvG;4-O=u`SID^C21zxf>rm>hANRlg`3m$z2%m@2c>18!e047{Nx^R zxMSeb4aujHY|=z7Keo1-PVP$G=yC-xTYHNH^#D*K#uyiH?yb9aUp=(f8YppD9m*;@ zfoPwW|4#dOs^aklZZoWN0=_;8@D3|pTIJge!5S*-kW~&G=pSmxkS0i7f?MDQYFXuD zDu8Y?f<^jXCvV7JqOBLQke3QmqH{C6kU(fDT9>~Phk7GnBM-g70kUm|U88wBFWQg= z*rDzzhvr7*Q4_PbmyKyNCO~Rn{2y%AB}BS&4}vxfyhk9RIG4X$jtR^Q4Sjb(PV&9nQ)%VY7Hq&Rv`w76IXfr7a zmyhQ@nDzIsgp*Q_r?opwvb`1tZ-rsYgzSHJrH?EEW2@|@a>kN4wd4}WnDAR8PIK;n z*Ic|xxow36YS!F@UUi>Tl5O1!@b+&2P2&67BM7kHD_8dah)J?@1hJ z#udt9D*%>H&h!Mz)3Psw5OGc}pvfZlc}jOD{RQ1dI$@_?s{0l&R)9BXH&;de`Q3SE zFLDLc2%|ds8O%l0*u@vD4PDc-pSj(kWP#A$adtdMV+$}#M-ynWU-#xv;ixo&)i4uR zsstQwV(FKNXm3$3C zTdD}B-8ubu1!qA0&EuMpdb7+y-fNnUFc~gb&17PMA(x$%ys$2Y{1R;}nW;qi7LZ)& za=vTQ6^qmtyuQ<=uUQ@ltgf{^mhwMzCL`DoS1!d}`grmP)~OHd)+CON6GqF1Q$k|$ zOt7yf^wKdxh?Gb=Y(?1%?fUuKU?VbQx*)<17@Q5|1T3(AuFyAmT}pjxvNRnO#Py4cXrqJioe zuL8)6Jp;K0WdOHwg z@I|x*N~epv#)CegZs3xSU)y|uxccoHuyKN3cri$|gUXC&kXgTwYilss6M3B}B?6FI zf9EFbLiKNIV({00(;hO)i2yMHO!A39Ev8gKLJoV$lXj6H|FN{Zv&TS+*b1+ zX%kT0uxO^+pQzSCkyw_Wu#dy=tN z9uF|?H!^fR0%9?E?+m9wnOSJlMmaE^mOC#ap?)z#@Ya_#yqlnFOp0M?6}%b?dW(^v z@BRqwTacF1!up^$GqL?oYLAW1|Fzn~zF|ix&#<<9O~h?OKkr^vP}Rpupk*Whmw3VT zSd?F#`^uo~ekN#)ivsTw0Pn}i8k0Q#z4+h|#5G<>@da!B^8o$0FF9*=7U+wB!c9~s zO4L4sq`)7;Pbfn{p$MxITE6=CMCND(TJ%f)Qct(_KU${xSWp89Dwp`ixgY{Gn)7r( zoODk{h4jRy}#o&iz*qESMe)EDeTQTz~i*-YjCQ_Pu%L)rFyJVg;2Tij9Em!ZeL+_Ghi znn7q%C<&p2$WkJ*YZ4izY@sv}a!ZyTd)aPlSu%FncPZIIdVbf;-Tl1Bd%S{(;UrA%nzYNOuQq5tzI9+x1IuSBxM zvk1y%$`de^CTZHUKVo)}1kt+EVn>F*doA>xf%4y5E!@mxvfEj^pm{FPyhgHyTd!+P zsa$D$O24h${N$gR ziW)D4R7%zwGx{Hp8jvF#T`d2mY=5iyA8%evnZp!rgo^W|KLZ2qj~HQ&WGqw}L;dv( zkQ)C_>!K|xh6-mcNyx^(k0&$xr}%v?!8EY#eD>Z9@APN%q3m5^rdfpNgRh1skZ7re z0BaK@E5x6jctBlw8jM4?r4&8&m}qJ|sWvF47tYr1esIVX=vL!!E*TP?lT&DCkYoQa zzuNEiVOd_idl9)&@7XWo+i+;ZW9OB&=}Vgf|AGIciQycNx3O{Ks&a~V@2e$pKfE2S zv+bh}Wd$ZoU$JYl^~H27%Sq!vDQ3~7k86jX2z~*rTKWdN&J4?zy6-WmEMo+UGQmay%vVh*FD@ zhaHh-u>6hZ^>;TH1apqsAG@zVy!YeNcxVqQ%O>Q`RV6wVWrW1Hz$} zdqZx%QPZx#S~@JqxQOC=GJ9!u$x%1YrHFgAa%)2FPWzERYO7OudFO@AR9`G5&&v}M zxpfS;G-71t3#uz`=1L}7S^$*8P?{NP^xOvf<@2JwXR8RS%wC zf|lsKt}!og1B7bVJIog3>P`3O%+(2>?{=;+XkyZ8h;g_=F+0*}@Uu=og=Z-?jzrk_ zQ(~VAZ`bx{VAP7jH$>MMidc-*I(5t#l;4WaMBIRQ>MhULytfgB;9Z2mQVFWE|Kbrm zTHb;=M{15wTcCU;*BucW_MUhv=0OBgfzO%H^xW36zg-`Z8cIdEQLX-vQh4sulfQyQ z4z$q}PU#$Jh#??S!vT5zoDMhS4Ym$fOs~C1A_eyZkjFdu~ zcRQUrDERvRR>xg5QAsryUE>OfxRR+<857N~p$B2UJ#bAWpbI1{iXRq6x${n4*$-P% zG}H#qES`a&e#O^%0bkU8eiiAl1;+xq-jqxwxACg6=3SX`2$3uQ5)2?JnT>y^`MM=F zt^KWvT`VoZM+b_gKC<(w_5P2NH;Zi~EP^xKBB>oC~AO05E4kM zC<7fw_{6hO>PtxT2<#Ps_&`syvG$MU&WiaN2#zMBLJLCkfa3kQt*VV@P zk)X6ywI4{+aj~?n<_rOx!lK$`FwQDML!D(*U4Oof7`%Whq#A2=0|b zmfsIb5*oN!u%h~#Py2#EOXd+$`(y0Rtk8gh$2bltbs;Sq0xaG$otY0_o+~n70mR79 zvX*2u6G)moq3mhb#ULS!g8}O!9gsK}A+94mtDRx?Gpst`3dO^;nyqP%Pn+$^$@Gqg zB0nTrUSRP-fr&VnS5uym(B+mOLRNFG=P_dAx{V=kP!+GGyN{zDQ4+FC0ZDN60dhjr zR!)Jaj9>3glsZv0L~F@Z&;P_BZ?d+}^$Q|s+Yb-2l8Dc;S=9s$!rbUg!Cux7$A z8h$6UB}v6FNzF}GXX{IdHWOxtkHqE2*Tc0LQhjH$Uc&|K;t0oh3;h5>hJzF-1+1gj z(CNyu$WNyiY=&8Mqk+aWf0$D1Z6pCawq$DI?CP`B)FHjeG>ghdu$p0<($tWXN} zC7d7L#3rkQK^R32_)*l>U(;pGnk&@|dVc)?uogbb3#FMTcj!Inuhy7y-8YW7ZlY45E2jwmM9=3>eV59^ZR0>8->0 z$(i;Pp6vc=+D529h17wxpQ5PFAZlevbFLnR+$N3QaC_Z7s_vp!yZ&s{uyEH`L$NG-t6-$R)+NsTN%+G#&Y^?8hkU1>met$@2k$i3 zrBfOQ&`jRk*|a8&zYy6R9$+gr{U+B^WcF^_8#*3re*=@CmZ!y;B!1h_Le1^n*ghO` zw!*s#=e62w`mBZ)u}nMnaiuh3FfpJN_b(r%?zR}49VjWth%4w}!z0C0&TH3rbG`<)J!}m7U1#V_%=EGJ zS`ZIc3c!amMbbVO%n{M1NW0oI202ZsB!*CSH!xrL&gL&vibO+LWLxTxyU*%*k+p-p zzu8$b^y;@h?x*SvQ-z(zr_Zw=*0$iQdz9}Nd;V3VeR1F#x!V!xE{ZEvhiNw0-sw5G zVyc5O^qGqpafrW=@l)xrHVbq7v4(BSOJtLYVeYK7~sCHiCjm*|VkBVN_*iD4>Iwy%# zFdZPBy&deJWvH=p=2cap%)|P$u? z)_!Xi&s}0ILlX?N89y(Nc^aSm?RR&ZpoQ3&Kr7u1`+`)L(YT!JXoIqM>;LQ%jN22r z<-$C<98@0WZ|h?ib}|&XP-FiYlms^Ra`30`KQ8pF^=6Car;JWxi)9-15~W?t1QqN; zJy&GMC#)C zdHE>1C{J2sAhq7IMxy8=URkSYIeBWqOCi&Q9}fCNWtGvWOzc0=%&ijOB-gkPZ}&<=!O!uJZ1laEvP> z?)LC_)GIgM_o}i~>vB#+4sdTopS$-ZIPF(pyq&}&vb!QnV8rutEPE;qDs=Ux)9cS^p=>J&hK>}{xgw4TN2Jpd2=to)esl8xHqjA&?Pj?m4_3aTC9e^o_v&~6lU+z-+R2We%g8|BggU15SxRT1|9f8 zDik}7P$;1AVS@rJPm2%@NF>jQ`HOtS&p#)x|Cm#L(=)t@Q7JHx{$7P`@eIjD(n|LM z@e|HaJj;rGD+#Ak#Y<|89q==882;f`(r{?~b!Eri)Z7wfASK1`=E%MG3&x~>_+(id z{o+E(Q27pXlrrL^Ly+iHl&%&4ZY{SvdVW!tzRfrSIi_WMRIy`ZKGOtpJ3Ph$ zO1UE8$aQOXU--Eg{lFx4;0Rlyswn5+X-!&g?4LtMLtkq`cR z1i1m*UjqFKr56Ks0 z=acIjGnJ!8FSeP;*!9Y#E{t2w51*_~HP%K_3nLyGy6aF#_;~KKoKo;&mOQRT-t#}x zd_Lu_TmNT1B40gIgu6DjY3=JpkD!&6e}uWi;d0nH2T|N$yoLmpzSj;`_eBV$6VY{%B(zyIM7B{g>FCl0 z4MW|*b2>SneM!)>@;xu#X{Kd*McY2EF%r>a&>R?#}M(I?wL~$zLN(}RN0Q$etKWl zlJp2S4Cq6ScoT~+$Q^33g;5Mg7R7q=AYI+Z|KV4(kYk#^lXtoy2PdIXKKDc)mcITx5PPXzSV`j}o(tw*; zk%+?rk+uJJ)1JEUQi9gvZZB7|>o;M=M+VOF$6$9B2UWO690+_KH9p_e`wV-xc(&J{ zj4$}J9FDLZE6x1*V!L_wV9a>kT#?2-!DqLdg@3R;f69#V0fO~rHL)bgax$vp-DiaF z#0eGNQ>J1@Fq?;evXQsVr}(D>Z$7nYHf%Ml?^h-D3C@Te#x>3c;i3G_PjryPiYdMq z$IBIiaJKI4)=SRqmebOWroC_cgPs2!{s;`eHd=R5bx`{`Ah9l}DoXL^dCBVpx_7`# zyC>|*O41j>qmKH%2O}dd>8lRMt+Tsr3NxAC7gxOAXxwh`-k99$mn%8Di%;vQy#2NoBDbY>+FRw~WSwi=rI%x=xbhnko7PiG>;?uPNNJ zljcJr(?hA&SupS~Z(^gHr@hy^dHcokHZ9gW^uv!QqJ|iw66WQ23mWDxkR7N;-S3p2 z_^aHsP`y*=AU40{q=VWAt5E6B5?@*^%ueEJJws?bqu@3RMs~{*h%=ghiPk}Q@AV0~ z&)i>^@)V5KcI)Zg7_ZECUiiEV9$1^neLxAVcc`6u)ITUk*HWZa*aHr-EXLi^=WlCTbkHfRWPgM|R?sf*?u%4KI zgd0c$W81oTBoALNu8g*?9(m*)gcE;!IO)WtYvh%Gi%LLsqQ>EU4u99L?~3X<5c=QDgk~LvY&HO*UBidU&Kl?IBHBq&`S7f@?yu<$p74(DO<^Ve+7DZGSz~iAyqi*<+6JjnTTOK6+*}2PYlHJ zRT17BAHI+c!HgRf;N0VT9pNMgY9V^|%il81-|=VJqK_s|XVn&cG+`EE{8vZARd}}G zY~VhkBSIHE87+ROhd-{C@<4i2&m3RhW6J$to2|G!h*@qnu)IL){iBkQmnks`LPCwe z+cjKNP1wHY*iVQSnuqkYG3-AoGisKP%z22&-LlWztxks^PQcAsdh_x&((w6sCyXVl zHdw#Xswf@)NQrv&b!1nz{{;*T&OnMl)_Ny zK5rZDvnf;RtgJkmkmWg#LvyWV@tSewHL{nVZkE>#-mxKhShO82xu+#j zqRz2VjD@lD3E@l>HkXaVAHJkk~(p?1?|@NkfjM5Ij3hJpFMiH^fxwRWie8np~(+e=lxu z&F{}t@26T0C+zSxEzbV@w)Kd8R4^N*#dRvaliM$TWZ)~^p5>aqu`5n@kPNv_p;M(O znM-pN%gp6nzkz&kD~EReJeE+!T$dso+@r<`+G*}KZ^D`{D!Ti-ZI?J&l`{;6|v;qrHxzf zOnF)&85E<3!!ZVX5`0i{UNR&^u()QIAvHmplw1)+8{130T*lz9hbgL%%_RmV<_9vY zo{p)=GBt+$v=kFDRB-JlGp9vZ({2x&NXz#$<`+`s&F4om{y7yoal}g>nqMX8rF=fz zNqf)0q=cLPDwq(u4wu7n$=|T@Uj5F?IBn7x94jmpuNG6k!NXheuu}5@;x(S+`$8*7 z2OJ*E-L*d(LEg1oY#B(ldVLFS%GnMok%E!rDoNuNh%^(w+G4u1>uraz-b)(F-Lo%G(6 z;o-=0{;cl#`{R3Ni_a0n>p}L+k-_fN8`0&|NQ#zr-q6L|9h&EO;c=vzG_W~MB7~JV zZapwGe%pZNCHQ!sJUsYh=j6v^n+K%ZGFbu6fBCu7)SrK>?UE7_R$1EP@os?k3|Cl3 zOaNg<&hy)$YAP2D-mCqEdU?0HjZAsXJoNL#F2V;~(K26HzjjBqg)8 z*%s%_E6WFsjg}cpI*?FVG+vjJ@8LL1Nv%-v{UNT2Ax#p$*&BcILTaXibyBXSS&NgS zA&Zrk3RZvL(()(a&Zf$If&1@#kV4PLvG&K?P!VLG^hR(i3w>X`-LzAVg``-8#oRe7 zOWbfE;fFGfX>~>=^a!^_I~?ybIcwJ|bb==-19d{fh6HGJ4g|*z3ENtNKj^J9q`89p z)$Wx*0~c(s%1M3n+w{%$B#a8tair8D%gGnwYerm8Fry_-o<{we%~71IFsuDC`<j{NBX9danag{%o{fo|kRW^o{5$@$ky>4`~Gn zjju_K+Hp=n#+F3-ni|Z*BNOJ&1iok|tKo8E*o=^d1c2(Rd})$a21kIGS2-RQz9_Pp ze(RgTq{$DDM-W)tf&Ru}ianyoU^0*oDuZ-zIY>M&I97ta3p@9#cVp0hn}Xil*C!K6 zhtPCVctqKV5kIDt|K)7F(+h|)#5%({)QXDaGd*{x+WB~)@ABkLt@|+foNBY0FLg*n zX^WLpde?peJz~Dn;EBf%hLm+a*S!Q{q3h$Q*pJe9N|u$a{x^AN4hct1yY?B+ZWRcDc=CpMXRqE_?8B6NG#3toSc*6ct}4kP;9 zn@^RRSFg@1h=9*pn8wRsVsp?X_FY_1d^NE7vth^ZvvaPM5x0D&pOU1Tpk95{Z>^}1 zZ1QHirZ%JWgVeq4q$iG=$oVP0LhQPpg>8Qw@%Wi~Gb98{of;KO+c2j2!PpWV*T(|4cyiQwV!9oKhtA=_dZs`iMT zXAco5=!4XRms%O!Xq zx|+@K`jv_&bQ$5gsLC2~jcT{uieWGKdY?s0D(0b39spP@XMMA>EP%+O^o7o?}rHNf)(XGgy z(4PX_+5&GskO$(s+c2V@`t)7&IIRMcGI2ayjydOGWYV4&!rMxmyB#%AZMSa7&73bC z(C7Lyw)gu!^_RGUSVIZ9z6-dyUA-;;=@aTZm6DPhPDBXSZ20e5i&OmhFT=KOiXS)n zY1r5(Br&1m*>Q-oLsR|&!oXPO5YpSm^NrNV^Bb~ogBMeIiZLBj$?kNikd$*K*Pk-q zMHo-+1#lW{J*5fRxgqHEQv}?4u6Cx3|%=ubtTX9}xt`ZgAa2 z;CA~S^e?LAtr0%>_aGqM7hrtE?Ya>MFn4GG^dT))WJ1r&%4)N}f1VAHdVnHDo~}J` zeAK}U<`JWcO(-I{dL1aoe*VTOshmgOMbO>P9na|*Pk9mWVv4kR2`J$pYL=w5Ac6{P zhwKUY7*Cu5D13xZU4B6SDm?aWR8^V&V;q z%GQdH_EC${bbp6?yi)08v`xf}sJ~Qz?m!-RjC6h*K7SR6gKJWh=?_;YMHNVV&g>u~_EP0(v z^w+X-6^Cf~t_+!Q=OzXNlT&CLDfiz$Lx9!0827QqhXsrq?|x=yjFSD=sAF5$ZB`@3 zjUOva^!tTc_$$EuCQ@t?AE2itzS&&FM*pu-+0IlfLQM{no4E0m7ydEwkHuV9FN?Z^ z!H_Sd=r`XH?sBqP*lQX_!<;GVal0yclmplp1V0d5A;u$qPKK8WH9ySowv|>v^_85& z@#OP}8rK^4>7LnL#Cy4atuFbzFOA3Y_1T|=7<5$_)Z!+A94u?SU_ISxENePhdw=7g z^Qa9vnZ5lZ-7jfnHXlD&0A}E|l(;*jA=y1_Oh+0uKM0I*cL!p!Gss%d=6l!A`M?gt=w`X;Wsw63PU}38Own;(k@f(W8KOunJ8a<(~vt& zRfRH%xP2G6o2`ju>{myg1#aj1Vt0JLY}jp)-wXP~MOunh{aGc`ouG=j5B_q*Nh)2y zVKFy?6Zw2|qMO{<2MV(5I0Kh%ri!(9?|ZzKGn3;JJh!@8vJ(L0rHC%dnJD~bz;gM& zj@3FDA8$2oTZ|ccBm%(maVWvPQitlN-({3<42HWcxMt-=1DI-c=AQQoltT1*F%r@0 zcaE~|&)VG|(&$Y#_Ji4#R41usis;}Z>_U~n84lK=^11#oo8QdMIs8zYlmRmJVrd>4<+AI zI$o=`4bLYH8x_44U`d>>65ihHze#YPSgf@5;zR|)(BKINFt|2B#DG!3*Gy5}&|4I_ z-uSd)dhJ0_Z#ZpQT#*HYk@&C8-yv86W;}+|1hN1ZfM3A@iZ+Z#-;_krVm`Heyqulv zKB})MUPvqMy}}#f2`4vr7AQpva_vbO20!roVP0TFV{Wyci!dTe`{|~7AArrBc#*c4 z_r13pE9J5Jde`9|g`{5-lKK4Og4y{~VERedZwpB&3oznzU&v4rxrCYlqZD ziroGi6KY!h{<$InY8ePh>8Erk=jVP7;kTe7;*&^MtEMiQkaIhS< zSaBSKqHQMO*RQF(2ggjw1_%;Hb+O-aYO!<_fpT~d9HbfkI{=%(*{j;qMguUe598&s zLmLPr{z&1tW&0j}=jT+a0Pxr@K&0N0%h$!Rw`F=v>u1Zh5;B72nF2^X4DD{aW!Ejm zL*=mA+#$gqPrd@YNtYV{qtBo8WxOnwNxpA`iuDWSgOLt8v8`kOk4t>5DDBb?5SjAW zgdKaxlny+1$8ZHD7lchqI}KZqLWV{FSIc=`&Ep3p{2Q23mHMhu1su}KzsU+voAOkQ z@1)VagF|35*fegj2A*>vE~EO^Ix-;@)i|TU@;Gr7exK9yp^MrA@+DANx`!Z^VbbWW zKXQgxAQ9Rx^* zQqen7Gb8}fYxJwu?!ZS?rdFb7nb!<@kEfmtapHj3Xr}-N;M~x6Hms|48o7TlDs^Q5j$DQ z+Z}!4)OizUEFGOYdsA_fOS#ODVgGSCk!K2?d_Cj2fDfXFF6;NEY6=LZ0zB{*%015q zLMjU<5Z{kIJ8Hd51dg9gK)(LrZ{y38c+&yjFA5^gfGmNq+&m%$b(KGU#yFnrJ?2Xv@{*Vi} zvONGrCDuK-G1eaSnL6XegiYa{vtsdwyjTEEv?@thw%NN%6^RKkOG%`x>R%E_=+(^l zy*RKi@;%U@5OI4uJuhn6Lt2k!V;a0ASg>km{7$=#UTiWgXSha(o`V0Y4q2+dle}wJ z)?8zx;lKY~u@?je7T}Pp&j6x7SZS?s?u8C*fF&u!CYC&2jIa2WX7`IG5cmeR9L?o& z)As!|@7wvl0Eu2gJFW)z^&W%@2UGKlqfrq^zxdu)Uhh_N_ZjCeG~P-aBCgAiKv=@0 z+_Z4(9ASZE7MEHH7@z4$m>bUO@YJ4^dYLB1J6@b0#1>S^{kglKjn;meCKfTvW z;FR@PNYVLM3<*yk>6zZ(@aW~J?TV4Sc#DOtDWl{tS(6B|07P$w_gc{|;8=QjdfD>? z_Yq&to59c?#Vk>%|Krp83)gcr!Yl2@$EJti=`l_XsgVChqAv&K3cHl%Qe} zsq&6|Fi(--7`S(SZo0?T6K+FlOP%D#+HK)IvJlN<4T)p9X`ekc)6JVXVvE;u96(e$ z5k`G4H54uJ_!xlUoh$6H6b~{MLma}~xu25i@*oN}5Z^KS0n(>}7#X)%x-8OzdoMOV z>;iV}e$o8qIUw)g@Jg#b+^47#wnV9qV)^hlTR)g{XqoYuL%(H;ib^c`e*k`ZE!};n zK#eVTqt1E3jhN#Qvr9%9XV(PG=tYUQO7Qr!*D?)9FYowLzr?A1kssIt6I(<+pL7uP0xaVlE{OH}lA6Iw z64s63qIhq&6<*IB6T{XvQC^rN@Ih>nzapyiR!|R3-K)K1s5@5i4sOfPGoAFObpe{L zY@KL{R19y_R<2`L-vHIAd}lZKBZLds zW#37pvKP^_>h4`z9RoXn)`z7JX|dnhvpNH3+6#E$!pl0bXfFQvd63%{*t9iy(X%7= z4!=>c7(2>{)+>c~hgVI4fUgYH0oA2O&E7UOWX`@~M2D}-lRjCisvG+q=c_-i!jR_q z5JkbOur53oOp@>*^#_E5==1824|&tDj>!k!TG&uZKSh6LIRPg`mU3oPJUEr zp&W)b;ncP?Z2x8ad(!^Q8&LuiO5#||O3a-Sz9(;6OkS35{LT?)mOS~=aq+`EW_3D) z%CSy*%p`^Gx4;gar=8gTfGoek%`Enx@gF|7#;c1cA6Rdqb1~iiaEUwgr6d7%^)eID zmG*AUK2_sMjCiB3a61{)GmA^-33sMOaaR-L5YVT09wy;bf*c#2*GFBBfz*59vZ-i~ zxhI`RhK$T9wW$x;*@4xE)lZ30)N(Aw#8X3egV|;J@YuH-ElG>OHY94=f<{IvQqr{5%89M-AaRy*$XH#?wFbC+RY-!**h7t$7;m_owrW z>lbr86trn)uaV`0tab(`CV_1Yc`NO=Lby2+2q8Mb6_$EXd{AB(_B;+M8~XI^tK|Xg z+&0l!+gTvlPBq;k++}r>eZP)1`?&O4 zCF{HUho4l`YoruBb!LT}ro}p=4>Za-s z3mZ!$aX(R;8OO^SIxZOlNKwbi37{Id7@00&mN8Q2+;^yR?llp}D0#A+-7{5td2pkP z4*B#_t*U;vvR`6|hwyF|4c2vvxctu_#Nx`6q(wdL<7PQ32(W|9U6|bDdic-7mBK4L z{f7x|kE1%|)Vd@4Uf)n0mchhdOYthMwVaVuN1kUBiXCdU^ z!A%ew=}02j97dde$d@~D#>}wa?2LiB3ZBH61?Q?7j8uy@fZM2B?nSb}bEYo!C2d$SAw| zAj;adP^no^z$88m&|fy~3&M$ugdMuaev2UQkjnza#F4liGYV@#_(NH+H7=A%EVSNr zxd&vmsK+n95M260Je~z~;J#I(LQ(E9yDV+Rz zn}@|4qWOhRI%1{RWNf8+LT7aP7gFV5i63ZiWkJv9{;{ChoLI+*!oUYG9*l+X@=!UR zYv=+bo?EdwHnDR8mqontq9YAI3oBj>Mbvo$#S~)~d-W9Y#eCLlG*&6rY5y zs|OU>IRtWwWO|3fPE}FXJWmJcI4!w7q8Bit79nU=hO+^bwILVwo50iwogFIG)_Jsi5?n zhe#>aBzbFuR}(NxA@Sx(n+S-BJgF4B$QbGa5@z7Ic5sWMxaS6rfe(~$!UAxb6J;PX zAFRXp3*KQN=ap#O!o_%WeXkPU(#^;9Zgf(=U|eA#N?_2(i20K22Ndh%>_7IN(-g)k zD+on0zI^q!;z3l9(DanxDdRDcJ)6H~jH+XLp$5}E_e}E)pw7ImOvd`x;Z4@=&e4B7 z;Wf2s@~5W^t}*Or^WeOnSRT2aEUqhjI3cAFJaSiQFiHg)91Ss!80z{y08BXrI zgmNQUy_jnHTUk|WaEKA3k(OJqT879@&?ib7Q@M(67o60f4K4ab-N@mNi`O>&S;_>M zp2|L4dWuXW$@XJ1T`(*ZVgVKh`}`QQs4Vt7z(h#e{^;Lxp$lLMmdm=kZq!7&6OV&0@>mAD(W>WOnL7U~#oeiY=iHr`~Or?vKFP}o>(AC$z{zMnd z6G6`wY0o7_t}bK6MG#LmZeUL>pJGzi8Q<^q;ujxgu%I_0<5=u*)3WO*Tkf#6fTM!b z8RKm^n_hdlNSUCOfUwY=UnKR5_Qg@(?&tNbcw@MQm-ZEGb>-#st$b8jV~)d|a~%yI zh}Yg)d86qDg#|8RODqql1rIRk-g#h?i)Z%$;-Fw>6kJWug%lBrh*D0gV3eY>xaG2Z zdlQiql>!M1LVlI)(j(23bh{ym;L6ei#X(1f8djSnsmE2r~z*w8x?8Z{db`)|lA0 zpZr+W6P_iS5%{{7NG7=W+&iW%Fw|SOpoKOdIhs^WBfjH2;M9}nddg|(3nLMOaesQC z>AXk~+_A0t*}j0$k_uWGfx?ntaYza0PBW-Ki|ij?Zu_Mge4SN4UAoIGLSk9ZpP4hb zxb!K~YL~f$(sVbv^g7+ApkjgG1P7iu!okm}ABhg{Ia^+9_}c;7>YPW}7Y!dgU%Mf`sQ# z&x_D!@2>mji7{%hipiYtlMrNA#wCM9QAmUf-{;$1`J>;nowLFD!D+-GqN`^|qVk6bzPTAP$)hLJ_sHa(A74AdgHZX(T2cxFK522B2q z;<|EhuAVV{hP4@_BT!0dT*G+IFap>Yq3Jq*@pSW@?Q)MW?TcTdA#w%eVMKBnNHxk%3ZS6{zd|nPIb=MMc`x1u- zglrQF+lOmUB-(>Y{AN%b(uu+B`ZH)iOYp0UXsNOd8sD(_T|IFr{qgF}LQBx|6X!`#`}QAD z#}ezlaa|G-tUh7oint@I$Bdr*iwQ4w9|m_y{euRZHXhZse*XcA)+jvt|dHqcAk*KUo4W>(QZBe}A;hZ3#@B1d1?a zP;4&&;-1`b+ZVuyt~F79oDBq&d`dt@A|kwsibnysyrK=4&69^R(eV@1BBmN7kW2jbxCq>;9n`^jgUYv)K6Y0Zw~3=iJ^a}Gu^`l{s(D*C0Y7h9Sx3&MVd(V&b~ znQ8G2i68_E*R2O=za_|*Cln&cIJ5;JythOE7H@Ri3PI2w_7?p6_eb?|l=s1Q|CHK&)zLz3{l- z>89oGVmCiC)2kT&E}-*)x~~n#-NdKtilpGR0J^t$pi6mA4$4to;kZFVkEtb;D5DK( zF&ra}GW;KV8g*u1(okSbPw+n4Dlx*%saH)E^(ZaH2g*Q89#A=s15Cq=DIehTMY^Hb zq(C=kKo2VMWa9jYLcV9SQY=$Ac%d?IvX;HYhy+Z2gYM7O8BVc4CCo!VjsjZGhpQ9S z@4<2uY)9VZKaRd9X@r(A8ZLaYGsXXfmLLKN;QO!;qF;D3zi*jJjlSRsd1hEp==SLb zIi$k_Acq|6hoDO829&|ub%QFRkZq;3u8~7f<}IU6r(bMyU{gN}D2-tE#Gjq9IN;XERr3>(we7ts$D=={@DV&Ni%LvT zh}EyJsV6^y@UzIyfF;W_msvG7atD;6Y*1-Lv2@&nxc3e{4J$1`lc@}_4NCy^KgwJm zdB5EKl(bXA0Pt*Y%pW5*;$H|ZRWZax2DioLw0 z|K}S8E1RAy7J8=*@JGVWfw1ET6u-6Yz7IJ)?1RT^LKy8&U_I|9hZpMDp!g>Duu z0G#EjE-DP|2IlJ}P*Ii9?sFmJJ^I#}OZ7D&?*&2S#KhDUer|@Ett`M6t_H`ogS&|% zOK0_Wrmt%wbs`M;l(J9n43lDv)DS*)>@9+|Ec=FoaV=UN~d!@l4W%QIM4%+bKT z6Yw*Q{aWC_CLma^nV09TO3i{rCj;{oaE5(l0jzI=!6aWFTd>p$fKyGX zt!RiKQx}m5)cBuXQ(zKdf}yC7_rVLV>oBLH0ljr1ZASlRxxPAR$hR9BMorJvypO21 zbZS0$1Rza~#RM(&?+n$rclPJ99;lBjUz8g(G>&#t^4VNkJaIWoiXmXV>geI8Kv$!MS}^v2v+>kM|K|}K!YxXk#*f1VA2npTd>Rm zZ`JW3YU$NGHY zuVA%hRLSdOWo0J^+cQ8pn}eTK@}#yjD>~+OEJ9+cz7g--80fs~0Xla;>XYR)8;D)C z1^87hjgQOoU%RyC`Ft+?0F|{?{Xjx#aHH(u*T@81`L8{Nw1Fr!+}K;ohuq^81bAih zX?CUGl?BG!4-;Z!Oo~4|d+c57IF*0`N>gS>2p+TNINz;Q?6{4;RXjm%FUMT zjfE6|Ss;mDehKakj!D*{foW!m*6#Qz1pu{YEG`b7r^L^~>iO4foHFp`Z2uNwJd5O* zgdOdjU!JrS{I&_+QiS>-=%b`x-t=bq0U+x_7RT8;hCrg{r3};Z;4Ir1DvUuAbdzVC z-TsinHEmKr*dn?R$;-#?HLR&vw7eA02>9X7Z%RcEJBoeQh?FK!u@MOne;Uu(Ky{QH zB#Mwi5W3936dBY_qY-+zV*+-L9ASpPUNxj152#!YGxN=f>Y;wT<2q#?PuBMQ?T-IAZ z>%B!?7|{wzbkEUP*gN`sC6Cciq5K8VDl#;gj`L*>-&vLyd&kP^+>%*jHh(VFc{qU! z2}Dt(f(-d+0bY?JolQI@BWNU=e0tXrbSyPwwK3uaE;f9lb%A~jE#&n*aTA{k;?IAY zO*|(lhT}KyOeE88uJ2gCH2fk^58VOb?z%mShTLryf^R98>RF{)4u>k4m^cwj{x*UX z;!_Jf><-Jzs+sn-3ycMrYf- z>3Bu{8Sq98eg}XoSf>bEx&3>9`7WUP4P8LuwLbGhQoiCQ4k235KwguLexEAs_(8y? z7db@$j}L_~Iv@fPx*W}e_?0Cv(dI{_!36ugw1^)$tTmnFDa*@^WpH)$G%c>1g^7D4 zfv9ogocjf@6F|YD@mWLi95v1#Ou|F{5bwr7Pay&Nl38>b`uy&sBx7joV;qN|tw>(< z4k|%Sfk;UK9+DQ3h#fe-q70+jbNl7VA%#DZZcJY_uz0U;^K_-VSp zI0VE*1-R8-s8k^Ohoq3OJ6yb1!4Hv&-;<^yfeusM_j1Z#fb~k#1iZddxuj zoIs`)NV>{5$Gmkh(IbMAgvSezIZNQa8eug9i`0)6{&g2kk6M5ZrZVDjbUPK`gbBTX zHsT$}3(&sN!;2Fh=@31^IFhYw9-KU`?u|dO>>F3G}0f`7w;JJfka<+ ztNF+X-R%gZ2MA3^3VNU1xxI5bslcH$56Oe$DCCYdXUyeSyfYi){j_$W8P z=;H*(aipU5K@HRkNKdYxvj*(2DZpp#0z$JF+)iDF_Hn=gp@lhcbP#s<_`id&BWQ`K z2e*4^K$al!gZYlDKWVm_btlH}J#fiuT*0O8>@f83RHx)NqUMi`DVULUfg&{1(I^I9&73 z)=FMXl7PcR7btq`UY$$5t_myUdvRz#;xLF(eryHOg(T1n$C{H%wYk4JsT=+lFbR~q zR1!XQNqu)(dPmPef6BlPoka~==LGak#om5^*scJL4C^AqzJOcTNK62wrLe>4yZ5EY z$JMr8=0|8}8u)*Xy-}*t0=ZSVA&NkzjeQ6E3JdTGW{=(;q0-71t9!q z;Z9TcGXOOYf&fDQUaK&g@9BV))z=g#xDZ)qz?|0pC#E0aan?zl?62l6%IJ3$tb4#JO!x8_N24asxt2BF1g`a_?84RzJ3j zAy8P2ya-PC97$1m7X~)hh_Yg1Fh9cEua~Q}N$~kq91{BP0t8@lOoT1wH2Ge8zjlE~ zSo78_-JyA@rnC-jPjcq-2^bfQ=wt$@bV6b&uoN;wkb^)Or;V-j2HbbN&0AM7zHLJ9 zf5&)m7iok++bT*ihL$qAood1&UTqPr2x464;{A@nh2Osc_I&5_R=kye2&Oek`@Y#D ziG#mk5sk*f00vd~MUh_L%A~)QIYKM|z)Dv30)GpA-=A?3J`cMj!KTUvK z&MEJZ#6%EM(q73MrtvxkYaE`GoVMX{B>+oR9r}zzfi(E=m8bVDe%!~8(~N$DoO4xy z*RffT`Rso@{7>xXs$WE=Wn9xFR9Iv=w;4o*-=Y!G7I9x=RHXH?P@e*CQ{r9)n)Xh6 zPeuUW$6nTQ@^0<_CioNMrQNL$hdzX0DyNguF;z^an5ZFRq|oVBhn6zDZoO^`$f#1A zfNm}=(A*4CM;}|I3>EcRp3q=hX1PicG*!{mo7~s5yZos_8<}*O!ySarkm@a)auG@LUf%P4G%|zBanIT? zq-OKUF{7!p3-%wKztW?nix&VjoyHRAJqLa?!n6?pMk|;sl9fy|Z^%!C56DhbbCyb? zI$H&Fd~NVL1sla8E-g|l{nQcHiaJx{CkZ6a=+OPUyxkA)k>KE+oP9m>-`CgiXRGqb zaKAHAnAL2;@0nBcV@B8^s%5(JYX1STzU74r!P>Ec z{xhE<>%CBC6Zy{+`o^ga4~n3v@l@$t01#8OMi#-B*IGypkM`*vcAYKHYaWLh>|`PM z?o+F^(cT!8VkisWnF6llJ`g!HJ1v-w-gye02~YPKIbi7zvR%GN;_c3*un zz1Y86fck<({bV(o7{XWW7h-GCMMxmHt!*9lg5y+5YK_UF1F=}}PwgJ5tKiP#Du{(E z2O@Tklu)r}>fd~!$Nr%N-xqnC42RFD7C$x35qHsXG$h9~zc)$>T{vqyM(m=*mBO_> zXOzOD0;$thD?xJdC$f3Vo6D292D3sh5cb(LLHDaesTE}|f=pu1oP8BXdSM&%vWpN7oT zKMqjNROtiIABXs4%%q6dMTYCQ?{+tY0+MwdD6!+sxj&eTVz$=Y82Ss+*)d7muN zKP9>{007J8(tyh0y35db{H@kYKQGWDdcf-7NWA2|NyMO_^d*|+fTEPWYcx>QcObph zndSf#s~j(H;txhDInw4!)~iqKnARDzZh*I2iC>MS{`U<85xW+0LM0jdZhrI|d1igf z=+J@JC6pI~a|uFg9LQl1I1&B}Ut*Hc@=1xyGuLLF_)~lD!;Sj#+tKx=ZG`~cG*5J^ zdoGe)C^v=f&VL4@WNhF586%q#^F)3;_$xQd&z$znTnP5W;LVQYb#JijzR^IuiGe-P z<^700RH;xs^Ib=}@7`M$*{X;5V_b~@tv|6o`4e@eh}$cvRe)zjDs4|Uhg1$;>}6lF z=Mu4qEyO*GUj{-}c7S9I(xW>3*hWMDh>j_^HuEMU&`=JJ(#_E2XSaJDK#74EYYwIwwZaJ1xQBn1EKJ`i7$yyW9= zlK%^lk7}YJ&EN+VsE+EPxY;7N)j|1YmL}pJZFx8$0jdgwf3D)|7440mdV3Pyq5HFg zR(48v0_f)go`~^4`a8Ae1-=`I5Sn!`ERKHv^b*@n51@(vKQnatLPG2Wc7zB^J%4@F zlX-qd6IAp%0d$M!V28MrxHAra2QBI1pBjLI7EjWHiK#R%RBV8OxHPl{pf8E++-LWF zzVJ`>r3>noMfKyHN*5RVTdqs}h`X)=r5EEIjj5AJf5>R3DiN`sJXM|1@5?`RCi@XB z2{;~=WnhX?2fAY|nEEhK)nehl`tq9sF^wBKB@Lh9@HU z2l&haX{xYm!PWN$SiB%BK#CWu5JlMy=*&DEVoyoHo@>d_F^0viJVR@WyW$uUgX!+B ziTp}2-_MZR7Xn|z;5Sf8&-i%z3fSbg8I+qm`v)t9M|(;q0E@Yh%I!y5YGX_}%3FlSM{u1~yLn4W~5Y)OhUIZ2_5vshMjh1xo z;l}`cGO}9fE=uS^gXYoLWh^^sm|0f$m;%!pP}~&`tGvc?q2~@6_R)35Ij4X?0t8gTysCw9+?hz`FM z@F%+fZnP_aT6BbyYu^37bmM*zNl5KWq)exQLlsLs!>=&`W&(eZHw!`i}z43RgCIEm$PksdC9$u1i z(rhbNKfm7lm!)e`1Vzay6!)?873o2x_m|aM5C?j?X#&jw+`lZ~N1nfLyiN2fBH_n! zhdU!01GV@4#rk4v38>|>_qR%bGEBFOSRdqt=5~3ccbuIULCyp%Yubgw-VwZ0|2w|W z|BUY(M=W^e;!if#`Gx6cdZ)MnbwaNnE2mn9kh7V=NOEzO=ysEqM$gJjtAF`+brcaTrm_t?>)+MCC~qkrUp+L-TO?W=;xKib#TWADGpSE1eetd~HR`P56`(B=9L z_|ydl;106TEwSE5THuo%2P|PEuDQb4Jre&)UOP_!Xf;F?QnUvO+0je#cVmUwe(waS zTqS0~mt(M;o&qMQuL#?B;e^DIU4R?$IF^s$neX*y9LZG|=`D%!bexF!lRtUUB5)v) zEg-+i19cU=GxkZA65Z5$@ok2VxyO~?cdXQq9M%fHNx&*CZI*!6+a`VlpG6RA&dOSd zqm#;F%J{;61d8qV=+0Z=Kp!BSOgz(@xe_;uU;J6X8;p29fLDg!4AGQHy2?Jq*T%}Y z&|m2QEd_-YFVh1?4VTe8r2F{4b`~h4wAwFusjaaDM98sd6+glAO+ejvGqL|sTvttZ zY$$314I3gK6qk}8+ZKf^fn||+f%-vmBBXbj~e%ou>L=7oq0Tz|GWPQ8C%)1WM5`# zWS4!P>{)6OLW?~`Lb7KYTb9fiTSOQNlTc(!C?Z89i55f)`9z_pbgp}*&+m86_niNF zWFGfz?(KbF*Xwyb73xPe@oq0|fPlrJIQ+fvrx!O%lD;*)3fe!td99lHlHbx)*Ze`# zAY^Kk;s`hX78KcF$wGjAOq`;34?cR9mm3OqVLqzZjb#unx4v0DUT=9nn4Z-`lRZj=_~*qgS^P|s z1Ev)T9deI&7c@v`e(#LnWMk?B?NDj)PVBSi;hgLI840uiGh0KPWmrxQIW)ZVF6@Vg>CFYL6I^bufnaTbWwgezcd?mE zL}T24dSU}ZKF`ue^wz`<^aa*B4K zivq$#usf8cL7qZHTsqIf`c2$R*s_^L_?EXg9q=w~Idsi7;>)(m`&Usg3Fev$UJDJUT}{-G;^rDWJ( zLsg|zL`N;0$Y!d)tLSXJk&yK;<#$oxZl^obFV1k7B)=*yKbxDijA2?dN2 zl0SM>*41{s4No%%$k@QmkSk0%+%(`>%Tk4YJJZI)SsMW%zFF|vTwRcN-4$mZmv?r3 zE^nYTS-e_GrLGMkpS^oBVs>3QN6KVe*dssjPFqE>$3m21Z{4<*F2(Q{x3JG3i<%So zUDtA!_z-DM?Rr*b+pw9)rx{f~^m3%?HA(r+dRrq5FP}j+hEEgQdQc3hu59PYUaE=m z`BC4(twy=9SsMeB2KNG*r;|1?6EO3|^@Q57G2a?C*!ln-1=pFk@^DHRxC(Y0@j3CD z;Yw}G`<-{k3h%0BF$a909)CLI8a<^T^1DT#s1;mTH5~KYXdJsrX*s;NT##zWlF%{v z87Td@Gd^THN=LB6GjmyVV@W!e6$DJWeb9fY%IEpI#YMSX)N`BLZ)jCj^F=40FS7OC%O4Fm(g(@QHT?+RZsY4gb-Bc6v4VQy35dt^0 zC(zmCjz61`(WgIrAy}glJ!^fC@jq3+ab@4hrW?PYEY&&EaNz(_4#$am`cDU{Lv!Zt z*7juRh}Aq~5>|H0PR+5j(lbYKyj~uqk*H~ti2dVg=%}r?#F9=}=7p(fZcMlC^dHoM z0F}#VE72sWPske`hZF@nE@QXJxW@nTfubncv(T?zZR;G(lw>TR}taclWNaNu&|eG50R< zK&2c$J}loe^@(}6XL@KtUJkaF!aS_JA~s6^McJblGqk~BBWntjT{$v^5^%Lm_3Zk8n(NM2X;Q__Gwu{yKHYq zX?l}*IsO5SjlI$y-gEsJ^h7DZrzV$I583I@X>FtlK&OmdBXT!}{s^=_)#H#sB*~EF z$!f+Vww^+rZj%_m3w--B@2MF(np%18g}#hGQC?>L#KD5pJo#!1S4*}_aZ7>`Cb;}G zZozK5ZWRKL48BZn!Dcu!5|?uDM`rmkNtKQ4G;&$%vJ>iceWvM;tOMd{6D@>W<0y_1 zyKSsJg=uRaOekcI;|(KESs$|z&2T3(?LGQ15?JDz&5z7gU0f7_K_-rYO$GO;CxwVt zx&BfuP>OaD&5Z1+jYub(AYIvph1xcUH0)^{Av#~O|D=1v++tBQI?8N(5gB)9iEiID zDCL1e-)52GcGm@++KNI+f37+o#u}B97_(Lg)qsJOP?&`ES89xMsth+{sfHfPBISTc z2(hJSCvQaE&k_ww`Kk4Qj&-wL$4M+pv8W0aj>h zV6X5_Y08kO-TjDhjY+@qnB*VJWwnsI+xTK`Kg6<8OcU6`riHzs)tOLou+yT7`!?0@ z6&)XFUaj$suEL-jM)I#qGGJb0C90#>;QKk6j7qkPqCyb{Sv0 zvAlPgL7R0ON!}rye9?5UIE{Yk3ntqJjuGYXRx-kF@_v1?)Q8SIQhFoRd!(pt)9O4k zX)Y+HAa)JFNg0CyCzW;N{#uhNgniBoi+CmdYh0e^`~Iyfo44So{P;Vbihi|=lLx3B zG2F^{)zjByY0u1BQgr|G^U$Mm*Q^@;%r}!SpmC|;(~jws7!*g~x@f>Vcz+!IDnDV) zF}JqrbSE2oSQSbnM%#(sa{j~TG->|)Dnlj1+U{Er#?{kz?7q7Dc`)qw8t#^3 z@?*t@sUMc?d%L|4<6KZ_Zz#JQSGB$Rb@pl9&q&vNU~qFMtF6ljT#%Wf z)sqVf1y!$p3_O=F=oWJl^&SZMG0c{AwLg%B_8j080fZEF6$RE`}hZbL%f zNrAhA6ki`*@YI>*54XMlVah|IhhDLp|1Gz~>HB}H^9z>V`TkW%p^IIe`X5NV-Wbr1 z=RT}BeeS%*HFzKurS@T$U4N?j3>KNz?#43b!PwGA{|BPYg}`WRd^BX;3rW#`XEgrS zqpFy>TZ20LX{-i%kauOsBJcsvW#S`+ z`(ZldYlb}78@ETSS~KFgkAl=r-LsbmpJfkO{TxtH!;#eHdube!EuJK0k(f(_$>bKT zY?sWI^MpF#H`_`LZEX>~Va^F;S-dM&pnLD>B?Zw}a@Hbx176uoTR9JiNmfL)2FnX= z1Sbx_JQ4O`pSTDTv+R6hyyN_={R^xov@G)y3a?TA_u!mUx z$5C&=hiZLu-kxdJT{Goy40A*=gh1xLu*=hYeK&LOPL6AjK$vM`DF>cPnu%5!7_@#Ng9u|rS1NX}R2z@*umlzX?m$E-sex)P&r`%s`!?iedmi?{Q z!XP@=wU@0RkWJR-c-gMJW3^zdY6WIP`$_R%W+Ttq`wjci`Q_@`3pCW}Xyn{x8xh~a zb7zhBQY_K~a;;+Q?>K#tEsxExHM&_2kJCK!t>>o{qqGFpSWXrm;AeYf&BI_)<-3zH zq&)`s?n7OL@4`JtuOFOeH1-5Ka5!=ZqMlMsm0$+NV?5u3=VU6ZU$^u$+m#qt8OR=o z$#F$1zmI8}`B=i2=9l?(vdLd&!q;VKV*=MYO4I1@YuLZPj&2bGa0D(!hZOU+^5A4l z#sJW1rcjQ&pu34ad? z5mx_p=I&5x`QCsxt~W!BU${=|o|B=3K!!O0?mcqezdT2T&i~4K+`0x3;_=v&P(Mr( zN&^G>Y_+u70y}c0u@sqb2iKt<0tqI)TS`J;K*&o&1^PDztj~4szpwU=UGz9@N@soK zrp2XE60h&|s5k^VeA^4H6;ax~4p*HZe!{!Ze=nz||HR&-c5bAeO_%{izS!||caskY zA7h@y<#XYYQp>M>xwo~FfANs?ujE}_c6y4qlVS3%f8xJyslV+%>9EkT)XlNFsX9W- zeYzTzP;8u^ZDw{Y^4f~PR4&QxeiGMek~_*5ffDr`ld}Gg#D@|ZG6z-X$6;slfn0^g zd(`9l&dw8mDwzrx z+PXfy?2yDm8aw5V;*Y1F3MqfVLjri|whXp0*>z|&3S3GZ8nn>7%c0KnhJY~0ZISTV?lh%Zdjp1~E zKjd0s>NT?=vRWX^@%QL{FQzs_Pu%IgyXTz(SrPiPUu0)j_Q+NdzpE+>2;HUf*>c^p zUbA&fr*%f>TlK={p_xsQ)gGI3>lRJ?i{!S!=3`q=ef`??U~uO?Z!w?<)52uvn-xo~E#o-@#0oPjFVT~Zb>%_w&J9!S>%ZWgnnT^|zF2`~PHuCmqC|gg z*_EIdmT#?omu0;)t6l5+1*r75fFk=&vmtA@<=1&V%T|-kjS>>DIU+tPtQUW%l)|sR zb5R#Yg>s{$Dx8e!tscSZz2>OFa-;MrlA6SCe>)dZe!@r7JR@sk1DZ~({+(kjKM-sp zMM9-U#TH3n>`8b}NxvnJeOG8{91^OWaPu0t1fdG7oO1WHkEBT<@CJ9cP~xj(8m8g7 z(Abf~jDQxTSnr(PBwGH$Us&a2>T8UE77Fk3M=vBHkcefY^|Lm2gz~WGbUHoGM&~s8 zIjLDvOWTnEM`P>)Lb*T(&_AZ~N;2}vFjPwwIgYkX&-Z6g{3!?v8F$ucS(X0DoR?Rr zEweK4D`oxSVQ*tas7w6#+UdJ{7?CZaV;@(i^U!vLHS?&i9)V3|<8;haTJCZpC?)B1 zVP$wCHynfO+|)6u44v96mvU0sCy9gKzRPSP0FH~H4Eo;U(2=(PBtk+j46+MkBAc8} z`LX-}v9jiVLNZlA8$KuF(NCojK1D8W*uMIaLen@-JbL9I8m*}G3YIIcmbu&-vQAf% z2(U00<09cfQ{gp`TX8*ts3V2$VCBJPfY2Hc>O9gNm%*(xW+ce@Q0n9(S@b^_cS12t zZJn=1pHYu~o@{`9pkD@lj+!@}Kj9wiJ-X_?>O~rH3AkJFHVz>fW*2jB(Sg&VG4im$ z@m$1{Y^%R&k4(MKK^Xq*?Xn+q@zu1!Grhuf6M75{5Vj6LpdyP*rRqWFegj>o>=vIc zq=M5q|9Lk-p;=H)8vRcy!X%DGLsGRr8)I|ZOHq&V=5M!Q4o1(jkm1-i7%qPifv81+ zA-Hy7tj=xUI`q>J8b1$mVpoXNq@mZJgD~E-S=m`ge8_OqxHNBrTf@*X8ewjp|Aa0n z$cm%CAN_q7QQN?e1^`top92@jjXZ@BB}^9LD7o7P?=CgC@|iI|$T3CO%U;~`ne2z= z&%Jzo{iRN(|0kW%sDtqKBp+fZZs@kHPlG1}hxp+p1<%RH2o(-5AK8GC*@JIJ0YOL+ zeZr}79_;c<;6-Y5;9L#|^$PnmpC9-cM7!(~t+V>0Ks=fA>Djdf%9AhFgNQ-l!jXcN zpQ{VI^dr|sCj+IDp_{cIq-Pj0opT59IE`0l_aVk%K`C^1Xx1ov@Amv_D}ZFmVU5n{ zJ^V6i+*}TV@2`j?7|yIBxPd7MIF6`9Tg<=$quv5G zYJ%nrFvU)6{Go=4tkQ$kY>i7$un&?c+p!J)rj&yIPTb4Fki?8 z_kwubpPbl}4T}^wvS}~*W*OYlMKsUUS3`AMz19p+?Wg_E5UWDI!V)RlS8ZHINqzJV zurTv!f%=!FMmSYo9)CSHR8hXTT&k*mf`1u7m%ROkkew1%8s4O=2eKIGCEKf!~a z(Z*!MHGUXDIcIxBlt$XagIgdMOVoUSU2OA`p!xBFzOYP9mp4U-R9G8^qF4X)T|Zdv z2?he4Pe0_$tp11;KeS>9H=$AM16`uE=KLHKSyBQE16(ng&rd*D&DxjDMG0&6^TCc+? zn}sx=1RSyHTaDyxVy#aPU9|WFt?s91Ii-qVelhk;>nF_Oe(0JX>5iaxE}jNV46OdR|A*6+roP1zme0)?HkUt*!pl;Fbw`u z>^>%}UIyN$%8GFJU)l2SMC~r{5Sbq-)cDxhrjwRejW+gCKp7RMmP$4E? zAvr^(@}dlX0rW7#LV^ z$lnN%7%HyQC~c3L);)Il$F?c2MEYx@rXLJXy`Vv?a-b#|(s zl7;T^CBNIlX5gW?l(?W2c96QG{^?K1=q=zX-8-5n$Rb>4mr7yUBsv*sWtznA-XSP0 zIcj!UUY5D#2@D*Uc=*Sv*CO_fXZ=U~l4LtT8a+Mm#9dvSyH&M?`@=)pTrC+A0i~5& zAYV8zX!s}UsAB{S-ZUC?2WL%m#xbcEBv7{Yp^mO|MoYHdxbw!DZO|w1cSBq5x0aiS zKP4@CO|q3v_(e+ZWnD)E@TY2q2Ur)%##PVT1#z4w4hSq2H~7B?)aQVzjB8(-=vwlV zgWFfXH4yG>6BdW+XhZiMPdxn%NZC>W3lrrQ_ar^njJ9A7%XEq;7aT-x8F;ONJ(4|m zed^yJ$V+EW?e&4iqSI}2a(O!Vi+v}dW$TD{&*+6tzUr+n)kZZY+8{J~yTQfQg-83musU+X)^JZ_|LzuBhy`9PExqu!BhOGX-> z%Fi-(4CTvXtB#Pk*HeGDG#%^@g8qQ8XPC)*;lm@3yHB;{TS^tCOPi#VyBjisRw{*l z?nyot*hqB32eHKdR*@%ty_9%xZCXi=^0o3P#N2Hd%eBi z9{%liHB`FDMzi&e6e(JWIOTGgU8UgKeKvmC_^euMGwG^Fo_3^{{Sl&tiEIg*u$H9d zD;@DAnC#1|$aS_-Q?xmi$)I7{D3qQ=+#PD|th4iC){m`$-} zFM1jXQ!t7+TY-+WVEz%8ytLnFmMbSLKEVq2LSO%ID)A8hv1)ik>-h1}nv|lY(K|qJ z=^uMYlYk_SAGevnKD-51J*g93BtAaEP;!jGh|-=yd1ft{EIv)Gc=(_)^JcPi>7^)jQW5b`Ss?;-f9M)Jd!~ zsbBx&SKKL#h_z8@s!r}vI>;Om;o)pY?#tpEEkd9jOk*^uDLV;*C9pqMeH^~c%7xex zm6_X(A$%rz!-NTcZkeNDkrc|#`Pw+2n;x9{&hw=X`h zuinad%TSGIB~78UtUgQ1mB~O z(QUble Date: Fri, 12 Oct 2018 11:03:39 -0700 Subject: [PATCH 44/71] Note about visibility of topics and services --- articles/actions.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/articles/actions.md b/articles/actions.md index b99708325..ca23dbd10 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -100,6 +100,12 @@ In ROS 2, the generated service and message definitions will exist in a differen For example, in Python the code from the generated definitions should be in the module `action` instead of `srv` and `msg`. In C++, the generated code should be in the namespace and folder `action` instead of `srv` and `msg`. +### Visibility of Action Services and Topics + +In ROS 1 `rostopic list` would show all action topics in its output. +In ROS 2 `ros2 topic list` and `ros2 service list` will not show topics and services used by actions by default. +The can still be shown by passing an option to the commands to show hidden services and topics. + ## Action Interface Definition Actions are specified using a form of the ROS Message IDL. From 72894eacc64257836931451ac68482e3e3103ee2 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 11:06:44 -0700 Subject: [PATCH 45/71] Shorten abstract --- articles/actions.md | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index ca23dbd10..f85f0208b 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -3,9 +3,8 @@ layout: default title: Actions permalink: articles/actions.html abstract: - Despite their implementation as a separate library and lack of a detailed specification, actions are one of the three core types of interaction between ROS nodes. - Their asynchronous nature combined with the feedback and control mechanism gives them significantly more power than a remote procedure call. - This article specifies the requirements for actions, including what a ROS user should see, what the middleware layer should provide, and how actions are communicated. + Actions are one of the three core types of interaction between ROS nodes. + This article specifies the requirements for actions, how they've changed from ROS 1, and how they're communicated. author: '[Geoffrey Biggs](https://github.com/gbiggs)' published: true --- From 5e6af9c42015fd25c3ea3dfec573b94d113532a0 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Fri, 12 Oct 2018 11:07:46 -0700 Subject: [PATCH 46/71] Rename 'goal lifecycle' examples to 'interaction' examples --- articles/actions.md | 16 ++++++++++++---- ..._example_0.png => interaction_example_0.png} | Bin ..._example_1.png => interaction_example_1.png} | Bin 3 files changed, 12 insertions(+), 4 deletions(-) rename img/actions/{goal_lifecycle_example_0.png => interaction_example_0.png} (100%) rename img/actions/{goal_lifecycle_example_1.png => interaction_example_1.png} (100%) diff --git a/articles/actions.md b/articles/actions.md index f85f0208b..6aaaaaea8 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -301,24 +301,32 @@ The possible statuses are: This topic is published by the server to send application specific progress about the goal. It is up to the author of the action server to decide how often to publish the feedback. -### Goal Lifecycle Examples +### Client/Server Interaction Examples Here are a couple of sequence diagrams depicting typical interactions between an action client and action server. -In this first example, the action client request a goal and gets a response from the server accepting the goal (synchronous). +#### Example 1 + +In this example, the action client request a goal and gets a response from the server accepting the goal (synchronous). Upon accepting the goal, the action server starts a user defined execution method for completing the goal. Following the goal request, the client makes an asynchronous request for the result. The user defined method publishes feedback to the action client as it executes the goal. Ultimately, the user defined method populates a result message that is used as part of the result response. -![Goal Lifecycle Example 0](../img/actions/goal_lifecycle_example_0.png) +![Goal Lifecycle Example 0](../img/actions/interaction_example_0.png) +#### Example 2 This example is almost identical to the first, but this time the action client requests for the goal to be canceled mid-execution. Note that the user defined method is allowed to perform any shutdown operations after the cancel request before returning with the cancellation result. -![Goal Lifecycle Example 1](../img/actions/goal_lifecycle_example_1.png) +![Goal Lifecycle Example 1](../img/actions/interaction_example_1.png) + +#### Example 3 +Here is a more complex example involving multiple goals. + +TODO ## Bridging between ROS 1 and ROS 2 diff --git a/img/actions/goal_lifecycle_example_0.png b/img/actions/interaction_example_0.png similarity index 100% rename from img/actions/goal_lifecycle_example_0.png rename to img/actions/interaction_example_0.png diff --git a/img/actions/goal_lifecycle_example_1.png b/img/actions/interaction_example_1.png similarity index 100% rename from img/actions/goal_lifecycle_example_1.png rename to img/actions/interaction_example_1.png From 34046847c5f79d89c1752baa0791d201c1104b13 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 11:31:23 -0700 Subject: [PATCH 47/71] Shorten introduction section --- articles/actions.md | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index f85f0208b..d2d68885e 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -21,15 +21,15 @@ Original Author: {{ page.author }} ## Background -ROS services are useful for sending a request with some information and getting a response indicating if the request was successful along with any other information. -But, in robotics there are many instances where a response may take a significant length of time. -In addition, often the progress of a request needs to be tracked, and the request may need to be canceled or altered before it completes. -These requirements cannot be fulfilled by a ROS service mechanism, whether or not it is asynchronous. +There are three forms of communication in ROS: topics, services, and actions. +Topic publishers broadcast to multiple subscribers, but communication is one-way. +Service clients request service servers to do something and get a response back, but there is no information about the progress. +Actions clients request an action server reach some end state, and the action server will report progress towards a goal as well as the final result. -To satisfy these use cases, ROS provides a third communication paradigm known as "actions". -An action is a goal-oriented request that occurs asynchronously to the requester, is typically (but not necessarily) longer-running than immediate, can be canceled or replaced during execution, and has a server that provides feedback on execution progress. +Actions are useful when a response may take a significant length of time. +They allow a client to track the progress of a request, get the final outcome, and optionally cancel the request it before it completes. -This document defines how actions are specified in the ROS Message IDL, how they will be created and used by ROS users (node developers and system integrators), and how they will be communicated by the middleware. +This document defines requirements for actions, how they are specified in the ROS Message IDL, and how they are communicated by the middleware. ## Entities involved in actions From d6f7333fc170bacc2f82f92537c9a8930e3335d1 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 11:32:34 -0700 Subject: [PATCH 48/71] Shorten sentence --- articles/actions.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/articles/actions.md b/articles/actions.md index 7310cf85d..564a1cbe2 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -24,7 +24,7 @@ Original Author: {{ page.author }} There are three forms of communication in ROS: topics, services, and actions. Topic publishers broadcast to multiple subscribers, but communication is one-way. Service clients request service servers to do something and get a response back, but there is no information about the progress. -Actions clients request an action server reach some end state, and the action server will report progress towards a goal as well as the final result. +Actions clients request an action server reach some end state, and the action server will report progress as well as the final result. Actions are useful when a response may take a significant length of time. They allow a client to track the progress of a request, get the final outcome, and optionally cancel the request it before it completes. From e24800ac9e0716c282f357d14fa38a3d9a87c6d8 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 11:35:21 -0700 Subject: [PATCH 49/71] Minor rewording at start --- articles/actions.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 564a1cbe2..fd5e5073b 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -23,8 +23,8 @@ Original Author: {{ page.author }} There are three forms of communication in ROS: topics, services, and actions. Topic publishers broadcast to multiple subscribers, but communication is one-way. -Service clients request service servers to do something and get a response back, but there is no information about the progress. -Actions clients request an action server reach some end state, and the action server will report progress as well as the final result. +Service clients send a request to a service server and get a response, but there is no information about the progress. +Actions clients ask an action server reach some end state, and the action server sends progress updates as well as the final result. Actions are useful when a response may take a significant length of time. They allow a client to track the progress of a request, get the final outcome, and optionally cancel the request it before it completes. From d7323ec6c2a5f510923f6665b973c2f0e41661ec Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 11:48:18 -0700 Subject: [PATCH 50/71] Reword/reformat section about entities involved in an action --- articles/actions.md | 46 +++++++++++++++++++++------------------------ 1 file changed, 21 insertions(+), 25 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index fd5e5073b..8e4e911dc 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -31,40 +31,36 @@ They allow a client to track the progress of a request, get the final outcome, a This document defines requirements for actions, how they are specified in the ROS Message IDL, and how they are communicated by the middleware. -## Entities involved in actions +## Entities Involved in Actions -The following entities are involved in providing, using and executing an action. +There are two entities involved in actions: an action server and an action client. -- Action server +### Action Server - The provider of the action. - There is only one server for any unique action. - The action server is responsible for: +An action server provides an action. +Like topics and services, an action server has a name and a type. +There is only one server per name. - - advertising the action to other ROS entities; +It is responsible for - - for executing the action when a request is received, or rejecting that request, as appropriate; +* advertising the action to other ROS entities +* accepting or rejecting requests from one or more action clients +* executing the action when a request is received and accepted +* optionally providing feedback about the progress of all executing actions +* optionally handling requests to cancel an action +* sending the result of the action, including whether it succeed, failed, or was cancelled, to the client when the action completes - - for monitoring execution of the action and providing feedback as appropriate to the action design; +### Action Client - - for sending the result of the action, including a mandatory success/failure value, to the client when the action completes, whether the action succeeded or not; and +An action client requests an action to be performed and monitors its progress. +There may be multiple clients per server, however it is up to the server to decide how requests from multiple clients will be handled. - - for managing the execution of the action in response to additional requests by the client. +It is responsible for -- Action client - - The entity making a request to execute an action. - There may be more than one client for each action server. - However, the semantics of multiple simultaneous clients is action-specific, i.e. it depends on what the action is and how it is implemented whether multiple simultaneous clients can be supported. - The action client is responsible for: - - - making a request to the action, passing any needed data for the action execution; - - - optionally periodically checking for updated feedback from the action server; - - - optionally requesting that the action server cancel the action execution; and - - - optionally checking the result of the action received from the action server. +* making a request to the action server +* optionally monitoring the feedback from the action server +* optionally requesting that the action server cancel the action execution +* optionally checking the result of the action received from the action server ## Differences between ROS 1 and ROS 2 actions From 206f6be091b31734c56dab9e32c16e7f2f614425 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 12:02:20 -0700 Subject: [PATCH 51/71] Make fragments in Action Inteface Definition complete sentences --- articles/actions.md | 18 ++++++++---------- 1 file changed, 8 insertions(+), 10 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 8e4e911dc..2599a4e76 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -108,31 +108,29 @@ The specification contains three sections, each of which is a message specificat 1. Goal - The "request" part of the action. - Contains the data passed to the server of the action from the client, along with the request to begin executing that action. + This describes what the action should achieve and how it should do it. + It is sent to the action server when it is requested to execute an action. 1. Result - The final result part of the action. - Contains the data passed to the client of the action from the action server once the action execution ends, whether successfully or not. - This data is produced by the action server as appropriate to that action's implementation, and is used by the client to understand how the action turned out. + This describes the outcome of an action. + It is sent from the server to the client when the action execution ends, whether successfully or not. 1. Feedback - Contains data passed to the client of the action from the action server between commencing action execution and prior to the action completing. + This describes the progress towards completing an action. + It is sent to the client of the action from the action server between commencing action execution and prior to the action completing. This data is used by the client to understand the progress of executing the action. Any of these sections may be empty. - Between each of the three sections is a line containing three hyphens, `---`. - Action specifications are stored in a file ending in `.action`. There is one action specification per `.action` file. -An example action specification is shown below. +### Example ``` -# Define the goal +# Define a goal of washing all dishes uint32 dishwasher_id # Specify which dishwasher we want to use --- # Define the result that will be published after the action execution ends. From 86b2e3043b352af161b78cef6500920bfbe7c705 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 12:05:19 -0700 Subject: [PATCH 52/71] Introdice state machine before diagram --- articles/actions.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 2599a4e76..173fe3f76 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -143,10 +143,10 @@ uint32 number_dishes_cleaned ## Goal States -![Action Server State Machine](../img/actions/action_server_state_machine.png) +The action server maintains a state machine for each goal it accepts from a client. +Rejected goals are not part of the state machine. -The action server is responsible for accepting (or rejecting) goals requested by clients. -The action server is also responsible for maintaining a separate state for each accepted goal. +![Action Server State Machine](../img/actions/action_server_state_machine.png) There are two active states: From 94b9306647cf3574a3be734c3cab4796609f2be0 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 12:06:35 -0700 Subject: [PATCH 53/71] move introspection tools section higher --- articles/actions.md | 59 ++++++++++++++++++++++----------------------- 1 file changed, 29 insertions(+), 30 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 173fe3f76..d6ed07028 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -141,6 +141,35 @@ float32 percent_complete uint32 number_dishes_cleaned ``` +## Introspection tools + +Actions, like topics and services, are introspectable from the command line. + +In ROS 1, actions are visible in the output of the `rostopic` tool. + +In ROS 2, actions will not be visible as a set of topics nor a set of services. +They will be visible using a separate `ros2 action` command line tool. + +The command line tool will be similar to the `ros2 service` tool. +It will be able to: + +- list known actions, + +- display the arguments for an action's goal, + +- display the type of an action's feedback and result, + +- display information about the server of an action, + +- display the underlying topics and/or services providing the action, + +- find actions by action type, and + +- call an action, display feedback as it is received, display the result when received, and cancel the action (when the tool is terminated prematurely). + +Each action will be listed and treated as a single unit by this tool. +This is irrespective of the implementation, which may use several topics or services to provide a single action. + ## Goal States The action server maintains a state machine for each goal it accepts from a client. @@ -187,36 +216,6 @@ Python: - [examples/rclpy/actions](https://github.com/ros2/examples/tree/actions_proposal/rclpy/actions) -## Introspection tools - -Actions, like topics and services, are introspectable from the command line. - -In ROS 1, actions are visible in the output of the `rostopic` tool. - -In ROS 2, actions will not be visible as a set of topics nor a set of services. -They will be visible using a separate `ros2 action` command line tool. - -The command line tool will be similar to the `ros2 service` tool. -It will be able to: - -- list known actions, - -- display the arguments for an action's goal, - -- display the type of an action's feedback and result, - -- display information about the server of an action, - -- display the underlying topics and/or services providing the action, - -- find actions by action type, and - -- call an action, display feedback as it is received, display the result when received, and cancel the action (when the tool is terminated prematurely). - -Each action will be listed and treated as a single unit by this tool. -This is irrespective of the implementation, which may use several topics or services to provide a single action. - - ## Middleware implementation Under the hood, an action is made up of three services and two topics, each descibed in detail here. From 970647293e32b812aa2494b62448315a569e61b7 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 12:09:30 -0700 Subject: [PATCH 54/71] Slight formating chnages to introspection tools section --- articles/actions.md | 28 +++++++++------------------- 1 file changed, 9 insertions(+), 19 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index d6ed07028..2f940e5cf 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -144,31 +144,21 @@ uint32 number_dishes_cleaned ## Introspection tools Actions, like topics and services, are introspectable from the command line. - In ROS 1, actions are visible in the output of the `rostopic` tool. -In ROS 2, actions will not be visible as a set of topics nor a set of services. -They will be visible using a separate `ros2 action` command line tool. - -The command line tool will be similar to the `ros2 service` tool. -It will be able to: - -- list known actions, - -- display the arguments for an action's goal, - -- display the type of an action's feedback and result, - -- display information about the server of an action, - -- display the underlying topics and/or services providing the action, +In ROS 2, actions will not be visible by default as a set of topics nor a set of services. +Instead they will be visible using a separate `ros2 action` command line tool. -- find actions by action type, and +The command line tool will be able to: -- call an action, display feedback as it is received, display the result when received, and cancel the action (when the tool is terminated prematurely). +* list action servers and action clients +* display active goals on an action server +* display the arguments for an action's goal +* display the type of an action's feedback and result +* find actions by action type +* call an action, display feedback as it is received, display the result when received, and cancel the action (when the tool is terminated prematurely). Each action will be listed and treated as a single unit by this tool. -This is irrespective of the implementation, which may use several topics or services to provide a single action. ## Goal States From 8187434db8646e81203d2de39a3459a98d75e9fb Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 12:15:59 -0700 Subject: [PATCH 55/71] Status topic is a list --- articles/actions.md | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/articles/actions.md b/articles/actions.md index 2f940e5cf..89b6eff62 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -257,12 +257,15 @@ If the client never asks for the result then the server should discard the resul ### Goal Status Topic * **Direction**: Server publishes -* **Content**: Goal ID, time it was accepted, and an enum indicating the status of this goal. +* **Content**: List of in-progress goals with: Goal ID, time accepted, and an enum indicating the status This topic is published by the server to broadcast the status of goals it has accepted. The purpose of the topic is for introspection; it is not used by the action client. Messages are published when transitions from one status to another occur. +The default QoS settings for a DDS middleware should be TRANSIENT LOCAL with a history size of 1. +This allows new subscribers to always get the latest state. + The possible statuses are: * *Accepted* From 1e7e6bbee5e4c8b74fd58daf006e39bcb63e6c00 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 15:26:10 -0700 Subject: [PATCH 56/71] grammar requires ; --- articles/actions.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/articles/actions.md b/articles/actions.md index 89b6eff62..e2d7ae58c 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -53,7 +53,7 @@ It is responsible for ### Action Client An action client requests an action to be performed and monitors its progress. -There may be multiple clients per server, however it is up to the server to decide how requests from multiple clients will be handled. +There may be multiple clients per server; however, it is up to the server to decide how requests from multiple clients will be handled. It is responsible for From daa529ea9ecbda219e1372899b9b10af9ec0ccb5 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 12 Oct 2018 15:29:18 -0700 Subject: [PATCH 57/71] 1 sentece becomes 2 --- articles/actions.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/articles/actions.md b/articles/actions.md index e2d7ae58c..c891a5e53 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -24,7 +24,8 @@ Original Author: {{ page.author }} There are three forms of communication in ROS: topics, services, and actions. Topic publishers broadcast to multiple subscribers, but communication is one-way. Service clients send a request to a service server and get a response, but there is no information about the progress. -Actions clients ask an action server reach some end state, and the action server sends progress updates as well as the final result. +Similar to services, actions clients ask an action server reach some end state and will get a response. +Unlike services, while the action is being peformed the action server sends progress updates to the client. Actions are useful when a response may take a significant length of time. They allow a client to track the progress of a request, get the final outcome, and optionally cancel the request it before it completes. From 5de40c7802fb39d71ea3489cc6a6ac65e17c61aa Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Fri, 12 Oct 2018 15:41:53 -0700 Subject: [PATCH 58/71] Add actions interaction overview diagram --- articles/actions.md | 2 ++ img/actions/interaction_overview.png | Bin 0 -> 10658 bytes 2 files changed, 2 insertions(+) create mode 100644 img/actions/interaction_overview.png diff --git a/articles/actions.md b/articles/actions.md index c891a5e53..c038f2ac9 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -211,6 +211,8 @@ Python: Under the hood, an action is made up of three services and two topics, each descibed in detail here. +![Action Client/Server Interaction Overview](../img/actions/interaction_overview.png) + ### Goal Submission Service * **Direction**: Client calls Server diff --git a/img/actions/interaction_overview.png b/img/actions/interaction_overview.png new file mode 100644 index 0000000000000000000000000000000000000000..4fb6d9552d56b00ff950256763dc40f40166df6a GIT binary patch literal 10658 zcmchdWmr_v+wPfxA%>EaW{{8u1(Z&KK~lOq1Vp-PhEP&QR3rpJ21L4)4v~^(=pI5+ zy8CSZ@A>e4IUnBZI_G?uYid1v?X{l0*1CVs9jl|IN(yCw;^5$rs==S=;^2Usf%jhs z@qyP!cIiYM92kz;69xSM%k4~p_cY2Uoh@wYcR1PM^KY3rpp?`g3knDxwT@Z@jIa_< z!K59BlJn3hHV#qzMk<0$=~Y2Sj_9-2Cy*!tQG1o#HH0 zjxQQZwelDO^GPS({^|d%B;1GSH^NRt_rht8ccs@n zBnK{zw}uN1im>!-sMLS`c`R&$Ukkr zy{8P#;A8vB$`272(+{}Ae{9D(v7|8B9D4a>tuHOt(HBl!3jXzqR4EdlR3}>=iDkH_ zT2lfxUsVXOesw9p5+z{OEPZjbF;ZYumPMa3H5q48<@n8L+bU#VnXw4=l|=($SZoYh zR1lWAW9kpI(9y5{XAR2Z*|ja@o*}Cx>J1Cj2~S6CJTs_l4~`Nsczh_|7_GAV2i6@j}fy zBOcKNKmA)eBFhyb@s(@bW*(i<#zLNgnnNe^)bBo1q9%+312>}U+5;C+LO!tTgcbX4 zjSnw`U6#<(#?qXfEhmjV4a7VFwQ!dQKfW`VF6}m5jofP$>Ioj@3520e;F7o79Hwe)7TJ3Dt=kC~PMH%}zUk>x>oh#t>)}f>hM~w_=`G3T%TM!% zbGzbUSj3fK+x5@4CUEt>f=_oqHa1DErocDvk(0VGX2K71(kgJJi%kRTHax`eMu`~? zF{^$F^ph09)fs#1)0YVcmcgWiB|IA`7#&lv(ac}Q%uywvk9)p%2FK#t+2mMY4@fmr+Ep9VHTW)1r zlbv#?)eeLH&eGS0Sy-iwwnq5&r#~Ml%|uJhUJYD$dn2pm#*WL~App&HL*2OC@(c69ONV0dn*4mebGaGT zy)K*oVJfzUdO6Y=P&fAwRW4{o>-Oly9e4xhr|`$L@Jl1Bq#*JQczQOo1SOX7LzMgP zWXa^^zxTRo_=z^PWruM>j}4eXX4%Z*cd+vQC8iH>t?^#gysThr^2m8JxivZ*W^Ec~^iVB;I$1l3?A?DkbisEP`GF;6{11~N}tQ(YPkJq~zk@|MQ zgMNZDWfyN=XjBQ?`r&U--4{Iy#I~8bhpL0)O%;wjbEHY@eeuc)}mI)p*m2Y`ZH$p@R$cW%7%{A^@)R47`}Qf_p|6w56qC5UmZaGu8INweLq`gFBDDHfcZQL# zxcwQpxhl~E)Y579-LN&XFW=!|@ay@|Y|QYcGK-Na*;+1AP~XpPl|+PeAlO;?i&Ton zPmx{+uyfT_PB8`ivYRJi^uG3Zl^k82**9WVU)I7oLUjK@@xLdH5KVgYdQO89p7F;M zS#5H22hO-o-jK$Ddepo8F8~|r(GaVjh#Jf-r3->_JXeCbWy}3_Oa|H}5d%S9%TLRP zPxf;FZCUODLCBHS$eZ#EHK47uAP|HV?2LPD^BCx|W1u+@L=Nct#jlrKL_pix|5FE& zP$FvMJ8*qL8lX3VfdaDxTKoPMis7fbxI{~T6s1r-2?`>If zAMYOf-^!w31A_K4&f$eyhs_X-?8nhdG9^lk_ZnErf73LmSkJhw((){PfXPA~)%&ip z+OX8zb3)8svt8{SqUCn{TJ$;2${_jQ>AYUc3RXdMdzkUa5Ix$2(eo;xiFbZP+m+Fn z=9T&<$)e!yWe*|)!}n~dbrCEd#Wed+tDL-IWKFkU@Cyi#K8Ps4HDNZRWmM7xzr$Ew zyr68aSccryoylhA?kwi+G^)vZ1EHZov7EYB)m8Pc@MIY8F0Ne+7a47t#$I25WP;We ztIXFwe<#fl^Coj17qB0r8CQ`G&@r;LsX(;ccv+s78$X!4za?B*QHygKw)rjfMk#MR zXH?v0&6T0t4T1r^n?A;kHs{ck_XgceSS1Ox4d=FgQLa}czB^sR`~42ab4<*KKdob) zjA@AYfa>VQ-$)9vq6+bN^wg=`Es^wL!u&jM!*|cz!}`|=Jti>3<7jH0qumq%-+txr zd_D6PbLp9frEpUhrl9<-nVn?*?PMM7)BRDGpaLZwCH08ed&MALv)5-+Qe4a)bm>XLS*CRO$ z;p$q`BV~>{Csc3(<&!gV1}_vB!l@qJnv_8Hm7*d=#T;b=2U#-T1l$B>yBK7uSl^@`i z#*wFFYXT`7ig0fp{zl^b6co5TR7|XJ??2Bs(Qo)Pb*70!$kLNcKO6nQr+@O)Gi);{ z{0PyB9=~wefd}vZ&qMn^UNxdVsa5)^e)0MSEFu2CT^D6Npc8+vL1X+Z*xl7y{>=)z zpt+3~Q&*w-gO?u}UT3-9jgo<26z<66C_&Lwy4}%(Cc5!_vtlkQZJm}cmk5D_ATs0} zk<8ijcQmP?HwY6(J#lJ5j1DdPHX+010{7lt&r|p1OgZ?2taLd3a%Fz-PB{3)1lw^J zR65efsbr#rdbXCM6l4=B$XW05!O}f_`*QafeEm26dS?>Ep`Pzb>6Pe|60&4E>NK!^ zO^Dk|@TOEPDP9zFc8jGG zNeWhK#~kbycPdU+aIxjUTf=VZZW3<&@D&9|2W_kP<2yQ+%K1%ukI^Q^Ka7N~PsLn) zs2iN$?QAUq`P>-5z8Eyrs8Ft}K3884CSG)-0bv8nv)J71$sW6zHnls4pjaL#E(8SF zeIbo4IRRD>Q51fVL0|cJiJ5A6uL~U}K?n9s6~n*N1I0!$F|u`E3EOn}ZKuES`6xud zq;6y4P`nf&%KrDeD>8xJS1utro^~v+IAFUnoHp@KWiB4C4Z~e@Nl<)37JU=dks*75 ziGt&AO438!JfEY%=bw3~{b6qHW7MxHbeD(hciSs9fgPrZQU-0p8U2=bW^YmcyNmq( zQpE=@W9Imt%4Bg@7Fm*w-|vu$(LVK22q!UGCxLs4Ulr-p4)K46_?V+sZ=$5kE>Bvq zKOY!aFkL#T37pi~Mr&CKi!Bj4_depA+xOsb!+y`xNd8p)Ez8s8O;UC;NiOtrvzXZ{Dnm4f`Z^bX4#S8M*Kyz8wR)Z^65$vqkWy?bw&&36 zQ<|Q%-X~;KkS+6D*NA_xBPLa1g-g>mICXDLbm{Twsc(P=?8g^}SR-_;V8^kmpkTKri=Ja7?#pH~lZbzQNjF&)Auu2^ALLxeMB z(KxpIt)vTQyZbE8)AvI#2WZ5H1|sLx0*SpYSrg~zbK8{G%9{c1ph@8-))79#U^+}A za!58`)_Ay4i&+NSm7dV2Tt$0Nq2I2eIY(qBHS$Lsrqr_Ja4+HP+@C6=@7<$eKF?{6 zx7Em` z-zy-+*o{iflbBAAC#+PPL(Z}N@-F)N)cG1|5r9%<{6-gBH-(3J3FXST)CXz9+#cd; zWlBZ^V#IpphZ~^h@GI?qgTn?HA+}^qyXrUHyuEfRZI0TOB1VnRvKA8DuH(f8=5-J6v9ni% zoO_`Gh5zopc4yBAKD#+4ptE0P`F^UtAZNThTY0BFO4|F*yMhxfGivI0*aXg!pSH&j z+51T#9(2S#AG|9geZKO}dgw>!rQgxk1o;PEgM%i7?9Q+&oNAzv&v$(YbbGmQixRYu z4EcSYcRB+M4K<$s-$^7O5ObYJ^0|#lndW`y^4w=@A5=Q@(h{fK6*SkmU8wbBPv+8$ za~Uhl3B5dlX3GShw9hvM4>tySCon$N3Z1X>c7oV+b;hLp*!NcXAuT(@8h(Xj4Lbw5 z&HU&9#Huax#DnDKuxm+`M26_GA|rNwehua_!L`u{yQjBLqMNnaP?xbC;?1b|qL z1ma^|2Tq$7@X45B4nin?C32zsl=!Dc*Pyk;&hO~uJuLzKO56v7 ze~`}Ju`iXPadFQ%tTTar^HTeVX1XZRZu6y}N)k&VFpD`X1T8;vVzhW`?dAP0j+{SU zuu;X;R+u9vP?nYUvGwfzSu$qId3IfI53Kk_x-re#~!LP5A3IxzYX3 zQT$ymF_+QS>F=&~Ka+71V`6mnIQe;OOH9ANM>GYW8e&6^$BYa{Z_d{~^TiA-UYWn{ z?D|wQA4L4!bwZ`)<=iLBKJu?7OlBUb+?Xt1!jx91`HVp0d0fn)%VvI|xYm4Hgyg`8gor@hkUnd{v&jlOUQT(N)E$o~ zPFA&aQRgo^hK+g^6yvj}AFaZkU0z*ml|i#-Q~bGBYtHEo0j(}4emd9S&lht*HW^oT zEa|+jkUs3SGh1g+AC-txX8OIbGWyoh{zk^i4Bsh8OyOYVw*fTT|6lGr!!VaxMptG& z```0zLoXo`U|!{zXnV&j?V-aSz`T~0I^vC&R%ZdGH2#3-VOC#?fZ0%movQBv_0I~EKr<)Q z>RjUG1E^C_R3h%X1T7*vm0FFGz1RH__t>4gq^Q}?@JSg8VlwZ>R(x4TtBVufiv!Nxo zb2bay-h;313(cEzUSxe0o;q**8CIXunY0`ZNb%nGiQ+K#sKzKpLl-f5>YgeXJOL*a z;oIKksamZmll)f|( zV)R^HkNwP(JcJbLQ6?zF)@d{1CygGnVUbBye!7WD`NKQKRxQmJ6%2Z*GfnbXJ3k^uK*!Q4rsqWQLEF((oA~^!8KT?|qUe>?MAX6Nq6d zU+G7Fqkojex7(-@-cGQAOF&kTL3!#lt?KAs8zj-=$Hk51MN<*uimM^3TF*GNcJ{t~ zj=T!#S?d!T*ntI$zv>`NKm3};mAExWnlEwI#5Gu(_<_r_hSex^`vKZQ2JvF88BD3x zP?q+0Q3_%nUA_B;Tc+bHLVmh+i=7S5dd}E=iAKJPS7XZozTZ3k3YL zY_EK4lPYc|niT*Ar2InC_t_T%nkp;5wpu+# z82v(eNg%H8A|!$lD{9CYe`IF|!h8d1=8sg%K(??S$Dv8%a00VpV$o%D_{|pNqC8|P zRcdi+FlMZf68JS0z#EbX-uh(a+j%ZQ@AwLJ%11zlgQiy6=kZ%ed@P_Op%8Hog~+qq zOZ870bEP0tE`p)m$JwehnPlgO)a8i|#PQ%JBe0dhL^x{;J)D*ncLPk142ninP555e zS!-I4@MLl=X};W|x1RINwlJ~Yu`F3(gdl%~;})?a@;OD(uNz57W^fwKak$eVXV2fd z>#u1>EkpBvm>o_Be21dHt$i@w{wE_PBpoKZD^kC!{)*Z_NS)gBb0+Oaqtmhh-u6X_YbyI{atpYqq+>i7Hm6R z7diD5#!QzvCmFZgx|k?+@n9}OY;ipA9;!DU`Jg6Yf26Zl_@>Rb+%jZq(r5Ne`h!wy?&D*= zL)RH2*wHfrLlj4=Bl1Z-@|!DRlx?jqIp=Ir^!_79O_pEyy@t4|eA3Rtl~rE}bXJ8^ z)$9G(@V0&GG{uHZ(~$pBEkF22(sm#je=?A)HponM>T?-hb1516DgM=h%Joe8+%xg` zH(`SdLmO{y#E@jf$Qv<)C=Y`52dJwIM}`kqZg=FZl=tx0vQ5G!x4P6%M+d)fwl7<; z$|>JG{LK?I+#1a3YZ?Vx@Gy7JkPwr%NdJhT@J5ofMl-giZ3SV=ef$tSG^Ml7dAKC+`-Q7G)KQ~z|L|p zycYGvz>4AU4P2QcFA00t;C}~M9USy~yxBk=wrwWUw58dm7DQ3+h}V;;2o6?g;D z{dZmg59lzb*`*-}S?zv&^y4wIx(0e-6OOEAeeyxj!VtJ(r9Nm%2gZCSZB8miep;r< z-gSW&s0Wl}&7W|gP7D>~{tBT^A`38iy}%VMQg~sEP&Dqns$c?72u4+CgJupL3vT`w z$W^&%OB=SG85TArB?}*%%e~uuKf5j}pLwRDS3V9M^r5kK`dF%UxaC+;A2X{5w8*l& znFneF?$I*q3-o9K@hY$yh9jpUznTD3VBxqsoLBtRF}{HyWo`)?RJ?SrUj`WE|33cA zY}iKopEE7 zBXf)Q1kUS+uQwmaU06OJmC%4+Ttxe3w!KpJDd{p$6?@+02JTrMdMnBoEmdSu%L^9w zHc-VRG-fJXe6^^D3tUS0Gm8g8QmZ-HiW+at0S;G|lNt1n-?|ZF9`CLnJmX(nF-E0) zP&2lX8fDy~d~;B5xm z3;73#Rg2-%54U>+5YIkCTvOs~H@+6{lYF8NFl9+=<HOuAhEPKw_fr*QmrXXIFPP z9sLI7D7oVK+K1rOhGP1@-bS2Y!ys-8GsH_;P~wH88itw0qA+Ym4YvK*S!P$fbc&g_ zn5g)Q9uXcbKel(KzoZ!pa|n_*IJLwNxlR@g?I@@}(v!awcez{oW=O|fm&rH;Cnf>B zNedR7$CI@H9fhiWTqsOey_+WE2{{YPXg;3;lDEGe{BM!@<;-zi9vgMM-&^12YkaTN zI~8@rPonPO^@x~&T-|}dWtD)?dYs>0Msc+`b4<{lZN`QX0hJJoxjnp(63Bd0AaR(h z6o~ESwB7(&w5N#OwF>6)8{3QeOFT9Rfbc-We=yrTq8iBs?AYjkJGRq*cI^KbJp6x* z*8Xn;`Tu7fPzV~zRu~49saWqrMl+G1qvt*wn2t^;-tH&?DMJ(>;cTzY_J4}p>sHOj z-=6+XTuI{b{mWpgRG@Z-f#c zYFj+rC20E<>48mEng?oV&z?OCxZ3ZEbWs&1zv;MZB_D7{gS?$-2B_w?$5Q1U0{p`3 zPfwanT4KrB_2~iy1qITvKYdC)x*LwrCf^vrC1t?jRPPMDsc~OW0i<5V%Q?x}27hwk zSgHSZ7bx1lf)LYYI}K*l0x~;56X+;2An!W?q!FJfmQ4q5pv>Zyl^hu6nT7&pgDiduCW13Zh(>vXSKqyvPn50$6bdC~% z2!B-tO~M{fk#G0g9v8p@aJ<3)_}f=F2(5-I>ViitM8=_6c%!k`d^~POC*{XqXjJw_ zA5Sv7wLd;+s?uTe763p>uSn?i_50n{20xdz4m`4H!=v$~!X}h{I|p0}Hh<6!{=07g zs(^ZU(=>Q=dX;$-carB!Ww@D>Osby0f`gD8IFDjs5)|i}0Jo}|_TO>9d7bxN@ ztEi~>Z%@-KgdA$_l~mS25}>b1=)bV!Cc3p;foET5Rz8q4&2YK?L6Wp}yYHqdud3W3 zdu;z3;Xe=J)eqP^{Ty~dl&g{m)}u`DQB9!Bxfu-M)uT0R2swY~w>zH*cmiyIAxxF@ zExcF< z?>v9|_AQM3;&hi4?DVcy`{$B^v5$|>f7}lpUD8?ASZwXJ=_@i+BKA;w10ItC>1SwX>-)SEm3eLjFw_xy*^p@Y`;hqETjofJZ9xQ+*G?joHrumM}(}UM?_=|F+Q%?UIjY*Ha zo^hc&!gre-h;{N4`WxL(HlXC-T~?=m7MuYoPJZzKP61)4Fy-=cC1B9`Z{8bG&86qQ zYXg}ErAd(-n5$fz-P90Igpes(D|1?o;H{-HNQmYRO8`%Hd_z|kU;yfu4J7ze{RNoE zFMzv5kVWN@w*hGNllXS;I1iaoNAh+=DPpg+MGziCpvC5v)?Sx4lCP=fZv6X5dY8Gw zSxm#tL%wG`GHPC(M+Q&fpASjd{{!G%O6T(QlClD0<8jTSVyVv0?XG8P9A9g>n=?g= z;EEF?TF&(f^?Ae$`qn=hD0V@-xWaS*S5jKR{2ojJZpP)QD2M#z3oT|9eEMqwp4VZB zIP|Ie!m!XVm?>3bniMGqcB<1=R0giMm35RtAgDC$`_5kdnLPC!$P&< zhCyS%K;Zv64FBiXkUU`jHhTJ0?h69=^-KXc+x|Pv&KY6XIbnlTrQ2P+JoEZxZ%tp7 zZt$C>{nO_pa+A|>-Q3wT4`E6!*)|l}<)tovsy$_d1ryr8XUn+h_73U&v2U^F{%331 z^y*WkPOWD)4km%8k-$ImzBI1VA8!mi)T#Bb`5wYO5whBA7=C^Hu@G}GW@NSaeZo>t z{ezctBtUs>fYr=JN>IYI&g+k{dUB^huZ}qfH1!M62Wsuf**6*f2*F-NL9l7e=x;k~ z3t=kMN|+m{EmcTwKM&em+DF4!H_L5BxpYBbo_+*CT^B7mD;Cr0=Wh$0;o07A!%LaB z0gPzai`r6Ar-EoalZUy*-KUIYZeaqaFdrmU)a>BY>?lo3Djsl17M3Qf-gZ!6LP}EN z_sqT%o(JYV{h$vbZictlM;g+6C@A1QemFc;LT`1RkUlixzEO_!Wh@1j8~$3?d|mObR?daH6EGJkBxJsN&D2eEuf%kXPoAOrE; z8~0U;C8MK+CU*W|TpILpp~HHT_d8i-kT#%Xf(t+WUDJcC?&8w2;-rq1W6dwqRLK_! zo%6*~F&+tMlcIMUVp=d0ExfcPps{0P~A4*rUO5MLb4qD7vyG6Gs) zzTp1lg$9y*b*t3nHSPfR1#=8dtB7MC;mxY#EI+Kb8uD>;uG*Q(*gC}-1=z3*Oyi5h zE0Z68jI<}!Cc9S;%(~NkF6LOUwF4Os z>{v(j!Rx|rZ=j>V&ST)=xM>HJPk7U_0G`%kBBdx<3S^tfJ+oNwjS-Nm;fa3;6?71& zFu;=LxrhA;W3nLQfu3mrBfDGuK8r*bm^YM2J9QZ~FeIFx|Gp>$bQ@4n@~bNXGR309 zKKMVG4lY2*OCoH0bDn^J&mKlV^M<(JC;!QNJRK0y2d5)NDHaTT#+CvB{Au28EC2f^ dVK(@dybIc&y%%Y&1$ZxU)ReWJlqy Date: Tue, 16 Oct 2018 09:57:49 -0700 Subject: [PATCH 59/71] Update goal state machine --- articles/actions.md | 9 +++++---- img/actions/action_server_state_machine.png | Bin 33471 -> 0 bytes img/actions/goal_state_machine.png | Bin 0 -> 36145 bytes 3 files changed, 5 insertions(+), 4 deletions(-) delete mode 100644 img/actions/action_server_state_machine.png create mode 100644 img/actions/goal_state_machine.png diff --git a/articles/actions.md b/articles/actions.md index c038f2ac9..53895d1d3 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -166,11 +166,12 @@ Each action will be listed and treated as a single unit by this tool. The action server maintains a state machine for each goal it accepts from a client. Rejected goals are not part of the state machine. -![Action Server State Machine](../img/actions/action_server_state_machine.png) +![Action Goal State Machine](../img/actions/goal_state_machine.png) -There are two active states: +There are three active states: -- **EXECUTING** - The goal has been accepted and is currently being executed by the action server. +- **ACCEPTED** - The goal has been accepted and is awaiting execution. +- **EXECUTING** - The goal is currently being executed by the action server. - **CANCELING** - The client has requested that the goal be canceled and the action server has accepted the cancel request. This state is useful for any "clean up" that the action server may have to do. @@ -182,6 +183,7 @@ And three terminal states: State transitions triggered by the action server: +- **execute** - Start execution of an accepted goal. - **set_succeeded** - Notify that the goal completed successfully. - **set_aborted** - Notify that an error was encountered during processing of the goal and it had to be aborted. - **set_canceled** - Notify that canceling the goal completed successfully. @@ -192,7 +194,6 @@ State transitions triggered by the action client: The state machine is only started if the action server *accepts* the goal. - **cancel_goal** - Request that the action server stop processing the goal. A transition only occurs if the action server *accepts* the request to cancel the goal. -The goal may transition to CANCELING or CANCELED depending on the action server implementation. ## API diff --git a/img/actions/action_server_state_machine.png b/img/actions/action_server_state_machine.png deleted file mode 100644 index b450f8ec6d5fbebfd05e443dceb824852ebc7606..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 33471 zcmdSBWmJ^W`!!5TD%}l3NOzay5Yiw>w=~iyDcvx1OGyX_gCZa)<&cV!(y4Sw$9v}Y z{Gau%XRY6-_xbdGV9lCg?sK2}#C7(y_r4}hM@#h~E;TL+3d%z@sFEHE3YrND3Mx7F z1MrC<{To{p6h;&^r6&df7Q5z{8Ki^c9X$(lZ!pw6vzH0cAT3`^v9%5f=OZwQ=UH1Y z@bu1&fS}x&7J+5`)tcIY+<|p*}0+rQs=?s&bVyQ#Ubhh2I>=e zLPCuHc`1nRc2s~D#8(z*{=Xk$phktIa+_ek31ei$#zyHeMgG*YlQDfA|Pnb8y3KN`uzFYa0#u9L}ib>3_m8cMfTjISn_ATRa z`p>8J&p&a}%e;zAq7j>uKJQPU5C}N5a-C^F{p`M=aB;Yj#;QU7(S3pXlgqSU+tcKN z2Alr)i=7W${62qleEv>sr0dUjyrxh~XY2p{+2d$)lqM37Vl2&CR^pxeLR(AFrJ&#b zywge0nbj_-?KwUP=qCvz^o`dM2&%x;}{i6`tpa~1^ucq#M>CkRQy$?`|@np zM6*DgNX%ogZz=S?4m(>Yp9r`1PV!0R(t&0<-) zhcu!FY_~^)4C0>4C=Mez)}Q0pwTqN;1?@?7anx84%s85voMc)B;zx+;kn24$pPi|P ze3qR)QixLX4;CE?vv7MwL1hUeLQfnt1-Kd7`vL>dO|!@_MTpBpx!Q{#rBTd$|8}Mc ztmb}JYU?&wJ%K<|<%w_{MOk3VtH0horJ3&vWq7&Thr=(Nl0+rM_D-v?CSQDLR4rjfys_H;g; zoG0Gxck|`_-Qh~_a={zwF70C3?ekY_#(Td%4|cph|CM9<+1+qGxdg$a7#(Ii<7@zj zUL@1Y)LbRe%glA{blu-2eCWKwy}kOUA2|lI8_gFZ=(@Y&8Y`5Fi6vrT4!yg1OINL5 zc_vrXmz^Wvs$P*;@>?Z|x_U{-Ea3La_oK_S)?<5v^@$3NN>W+Quy6s{;45K4yKiBj zrHE~6HOrX>Yu%1lzV<@*qnp?d>dk(6xgRKlt#E#2;grYG) zL@JKY;xL*=2BCmFckQ}4#%p$+eWPEg#bg4vqm&I254pQ^)ZrOHQe1^mnp>&$I?n1v%ixGxuIMNI(azp?rB1!?O@GiYAuF{Y$p3$r|YaBt)ve$ z?He``GY9ZI{j1fjhL*r-u%mIPXrbxd$Jn>##*IY7CofKWzjC)?6Fjjz5F!_k1Sc* z{d|AHd9km!&hWjFGyWA5KSDC}u6F&id$jL%Eq3-TWopq!{Fi1xlBmd`NYSaeIp6$u^WG`F1HsYC|7!0Xr^VYfA3$`vE zZwyzGvdFLx7adjK@e@29M?C-RUMMMsD6Kb3^GTH!U~oHLM;ML%Qkx1xMbDV~=(VAq ziQaD}R--qXC!)VT0JD<`JXU&a43U;(T6?)MoQ>uEgR+Q6=WQ7Cs{{(ZGlpy>ZZ#N0 zy@MI?yv^q^7_)a73Zl{4`J!$$u{Md60%%oHl8Dm6)3n7GwwauU88(|755`Qtda+p| z114Xf=_V(34nw$AI(LnpWyocPo_n5{$9_t8Bo4`Uxcx9n?4R{A&y}yS#H_ee_2x9o z=O7yB+u8gmRgN!DqLt7~L*bM%cy`*rfP8kz52IfSmiQaBojX`a9P+F z#lw$)JKl6d5|}!kL_DZ2%xu5hNrJ>}6Hl_cJY_e56hTxVp$7SsA*@FD{{)^5!|aZv zA=)D`ESDwlv#WnD(m@x528U3}+(BjEw7#L|EC`!p+1|2OKjWx-V?Xv1+ZNjCnyhU; z=n(jrBlFr%nVGJ?`zAYigi#nA1Z31z!#T)hN8jIG*jC^LkWPZZ(*UC7)FM^ZOyE!L@)C@*OiO;E>$@OfYLL)n4TQQ33 ze;(*P*gBK~HjzUqa94=y2oB3j0cI1;sjWb9RT#^rQyM8u#{|Y5z2!VrTb&^XW4#J1 zPh^sU)vhDbxwxtB>{@Y6AzYp~F<|*VMpO1pur_spB;Z`(6FrAf~zVy{|@odr=^~NYR_j zIcz>SGBQGjg>D#)kVqjITU-fV1r_L#^sG;oh4h9R82iBb=Q;OZ*=ms+LPXiVr{h1Q z71v3_h4I($%iUd+UCH2(#8D$~C)q{IJef{fSNjtxW3m1DpNql>_OI3+$+NYk+X?Kd zeWCPgatwlTbGnS2+x$F9Gv48}9Z0S;h@mX1nb9vQKpd!Sm#H^$Nhrn*4m9>iG`}5^-7oEQSeqp`mt%~SKBmdL=WUN zDZS~&xG0eD<}^%%L^G*PeNj(ij=GXl!%wfH;>D|3l{!hFB)795IVm;H$iP`M_#Se9 z>rVz-UvgavJ}+bzHi(${V26N3uL%i5E8@tusETX@lH&eB1m;oIUQ=z`uF6b8q9RiIn0_LgC(qkofpW7Wo+`xpJX2&kg zSfC`|F1`kDSo9Arp?6xIuu~~{|F3VUb0GSYItg6WK5~(0q(#S}Jt@fH z>t6_|Jsm@nT zA_Q}Fd5!9)IH}tiv~+GTR~H$a=BIytOqxNBTfd}LP#f>WE5*|gLLcPXDo?1gYAmHL zD->+R}j!I|mnB_s%Puk_-Dn8r(W41P2@CO;{l4r#-!8Tm|Sq z3RsGUNL>Ez3AoJ3j5Qh{TomxA%*aP2K{l&2My!tsaDK-Bg6CHB$Q}$nvq2)>SQx7d zG6B$x1f3<3(9lFeZe6(D!~X&L|9M%)#dxC`bnvq>g=-+g8yC%wh0*1^dsTTEXaM>(-tv|q9P-Duz#?eZ9%TTvz_YOWCaU^41^Bd3${yuQYnEMCkiEh4_NwaeR^ zu#np@=|Evuag_w}?z`LW)&A~hmZ(WI=;sG6gWeVep$l!)Mpy)BG@>uO5qV_B9n_Qp z3N$HOw<}n6#lis99IAsQ5LjW_VXKE6g+aI9!f$jt+EfHD?maqDRg!;UtJWBFm#KC) zSa)}acjt+8S7^xZOi`om%#mGeP*^QUGU`Fzx|%GXxrMdn?Rq5G(aGSt&SCicL6Hu9 z#J};@%f3!74tt!2Em38Dq7n<29OLeehQq>)g$0koIhabliJaFiC$&7jhL8qltn1zx z0>g+~OQy!;Hh!DN0jr=96V4aMf)(s9gunO^7I+dCbQ#8?`mteY+S0|lauh#q@e7t_ z{)5xK_i4&!DHH_XV3;}LL~m46Jx*oZlOUZ1fc~fD{)W$GMX8l;b)l0ra|ckAGF7bAK`gBT6lzfnQFn}HcTAi9iL2D_ux{8#^R7p~ zs>^N*wy7pXf?YXHp5~#brAL4N;ne~*W&kG$7-)f;089M&RZa4UPBQZRU}-IZuMl@;K-(L;W!^|?)spBg47-^-`a%jb*cQ zvwCnS8#Dk4o1ui4+t?@BrA4N8-(J0cN3VNi(yGVe)C?t8Gfk$IA1j!XP%{$$ApSCJ zZBS%FzpGPp@JR&P*vkR@b}uS@BR-`-&_fgA^`{n2Xwi(gel^%foR;_Y!UUMy;ejK?Gvok31NVX7(g;pK^; z(iJ!eTug19DC?HQ8r+k}Dp`S%!SCdXb`a_j0UKG;NitJNLOhA03&awl4F33#Pk6t- zkVmYv5x=4wJx1y9vo}if%%LU8T5J*+I5R5hYky-)t zJJbwnSH+n2RsaGe?xp41-!8j_+%J|$yaev0T>$y;1&sC zf7Qrk^sDt)Yt34TS9)Wfv9i;$ntCj@KZ(R9^4yu?fxu_7ZV$TdnV;qftIL3Fj0~h< z;UGO@GORJk5%Zv59ZX39W4h88N1~3(WmrRsWD1l=E~G?>KZE6C`z@7;Quqa-!&pHa zK$qb)B-h9D0=5GNTl4}p7`*0fksyH!fgjeU)#8$IGJ0>0Y#01|_f&uDXJ##+4&FDm zYJ9XG&Z3m`;qW_HOv-qyUlR&u(jrY2ratF;d2BBoc#KhJ`gvfn<8|gMmHa%A-?-wq zt^oq(SD?pyOG(4pMPLpDUv}w%?R?A2SQ;_j8pHR|e}7gcz&6HAaY)8l9*7n5HCIa>9yZu%v~0K~bnmU4LO;tfgpch>sLhS8Eu+1Go{?gOHLHExE#WoyoaY z{if6v)v*LokeRf{;Z0i1^+u5%-($5EtgVF+^rJlA}vh z42T3y%pqO4VZE7zGF;N{&df(SSOlyS+Yt zhQa2${p(`?%YhCc5Gvj@rv2hJZ!;j`gOQ&l(95*pmgvT@5XDpQ6>V!DlSGRJaE($U zRwef5TO)jTrkK<-IO1E<>?Q#{1=4fMq-C6y@e2ipVt8g?-&#O}>WjOR#fcu@( zQm4%RQr8D4jbWo%t5>yzps;Ek_$+oD_-y^KsBmP=Z?t7YlADzM2M zUsu`}d=~9G>k*uz@1Ew95^Ya^C}yU9RmQC3rK;ELI8HxePx)ZJ`nFi_Ba#C7>Zxhu zh<1Cv6q*9o6AQJs*+2}E0|82bhPb0ZjQsTdYV!+6OY@vG_u*wI zI+H^36JpT_0#o^FGlMC}(L#6>N6i1g*c@Wi%GBELMXmNNsq5+l6x&0|9cKa~zNde5 z`R!iJ0zxJ!o{S5ivnWT269F`lXuRBB;TWm-yQR+CGgGoxWpquB<0^oNG;}A)r9$ho(FKg(?LQFlClLXF(;9UysE=s)*G@NJ|JO8L1~*u8uNNrF_m-pKhI9^cRw zpR6A}nMKlenRsWZQC#REFjI|+#2Wf7ZpiTBB*$$n6Qh)ty*aYWxyUVS*y?3pYuu>t zm~W&Xm$!9-Zh(*?y*am6Nw2@1gE)=Tu*T|SbCi>+sMT1?Z&$v}=Wm9jqVfyCbaJu- z2EqpWC15$#|E{*qzF?o^=M06o;Xj#huW=h=Gtm?UC<;gLAc4X3UEV-JZN8XCsb;Pq zxK1UJ()k3%4T7^h)5uaJ7g}#1&(`U`H)mL_gOB;3IgLpTCUjS1m)vS!AZ93-jDS%Z zY`0veV;DiRa@`4v9N(vMkDtUDL%_MxOvEpPuxY7>rZI0b?Q^ukBOTWUlHwCngHr7T z)(1{tK8*q~@%N4#X;OPCDfCHiF!7$Vnn36@3mik)`gf966r+C_$0U?I+4K+~7@CD7 z_`)~Gi$D08!k_}|@sV+T>`oKq@w7a~4f0XfIXPo=F#HpN!T2wDxxdC$G80P_U_ITU zf{<^XoRb1~MKljCLYpl*UReW1EtZUn9Pn7l-~{4$0EQkt!7+) zh@Dep7Z^ceCV_Q}z7!-bz?Vpa2Gum7e*@88>WA7V;p`i1Nmn4yC-tRQB>cYR9nxCH zvLds|M36?=CTcE3tVnZe7{GEU&H(MdI@4&&`B619nQ084O0cRtkgZ+c?Kp#tz(D&b za%+ak<*RoPQx9wGLuaDT4?9KgI83QtD1;e zNxoP%_Yq zK6-1T%xI%z^^$qjuMk;WJQ39&A~+d znO-}X!cYbTBmfQ{wE6Ckd(CHaqdua?*q*}dyg&;$L^1w|9dJ+o=Q|T4;?)%?kahs^ znT#2FgBo;RD4JY1^@;0yY1E$V!6GW3#S6axJrdZ4+TtOuX_dpj?Mb}g>$6NV?hl7m znhJ!6AsCw4@IR&MnVi-@Ps3)AZC6kA&2hcFL^W?iDU?F5)(bwB_2=JPz$4|xc3p5b zM@ahN8+X!LEd?Bfy?ZJ`mN+#1$pr=Ry*Fm=AoK!N+!MvPl{l6Ruj)D3x1xnBXFN@K zy#=PjC>jic3TOn*XLnV0x91G}_PFxL*=!HHl~y!!!)`9a^((_L@r3Pbp+q3h4%dH4DuNpm{;r==(y^z~6Z*BM6jtn($gc}c~6 zHrKh2kJ+?~@T2i7kdTmZ`7d?=CZf%216R;tBo+YoY8|v*%|~f8KB6k6 z%a#(eqT(&!M~!7*sM1qrky#rE-c?mlE>)UP7KFk?UZlSJItwq{VzG9aezdHZ1W8i* zsLQf^>Ae>)mZp@*$?Udz`PuE~rW!5X!wU5lex>tdz!|Q7FHsctTE_-QYE)g2MCzt4 zwoZ8H=^rAv<9PkuN9(I_;U_5F&Arnv|J5_pF9gTO5`A4e9#wsl5W|!zsK(v?>h?h~ zdu;MLPFV@G+0KZ^2NyBd>}FcE)JMT<7OQXIa<>F+o*77CNKt`co(b0&22o;?`F&J@ zYZZJ~NW@QT)UC65@p9ML>e`Q|YkQF4)6!8ujqXQ;E=>9Ot9Lr139MGDP?!dKI+Md^ zR7097Ey3?f*&W0SP*7Mhod}#fV{hc2dYS^B6I^%0_K%>i^WJ>|h08jZHvOJinW~Fi z=*fc@3(v1}Q@LLo75%&d=R6unrF5etg&fBcLH1oOHz7@e3R~`tAy@+`Jfna`TTj>L zfdB0U@Ocabv$foTctc**&7ThfL~ffPMiHL|K!3nxaRPu?stzMsv~Nzw2?`Hu(pUIJS+m zh_ST_(?86I`wOpY7kqIalPD|pE8J5sU(j9?_MP!G?e4?zDPU%QSH4>N;Qf5*`57ii=`|aNdv+wMhJVi`Qa%xzb!Z;n%xM7tgil213)yO9w*O-h<+w3ec zEVHXtxhB!#BvO{#7Mzq%s8l@W_)W!YccDH0WqVd%A1-?@z3klStI?$T3|_VV$&E`r zi{?WhaV?Njtc-Q|u-!kZMtjkMeRZXlwq9~2vVT#%4ozolusR8B54c6egkv@03_-k) ze1-h!+hSj&eSP~}An8RQCSvtBLocLVK!Ad4W_`%Zu-2k33V&x3(2_r4!)gtb2;-G1?fr8K$0_!J!q#RGG%Sx-DRPQ6_eNGogn*O=fl+QtvXWgioyPGhv zPSRvB1${Wn2@>gB>-_7x-vwrcoj~6=3?H^03O@JX3d|V0v@n5rwT&coT7MxyiJ~)a zF_t(2H?HRf*J8by^9wJA&w!Lj_L)k-PEU>o!L+4T>bH(9PpootYMx_&+4}lNj{`aD zWY1rTJ^uZgjn6j_r9Z+@#apFXEOG$bH=a2yCdq&KVR~en^oE%Elv%7R_?$kS{9vG} zS$RYo-u{hmEH~c%Xkw-JQ{VYWuE=rkfL&mX4!)b<=bd{Ri~^w+?{Q|xFr_w|hGl0E z70ank!x7U&F9iFe#}fVDiHhEosR=?&K`a5G7Z@!GhpT&A964*Yk5a5Q>9BXj15lmP zRmfl)bo)2=+{VKH5F}x7cjx;~EAnhh`boA5K`URM6HEE)3YJg5&sNp8gl09qZt>1i zckhjUm?Wh^pwHAzcvvL!nm;OEy*!W=t!cVQB{4@JZ6zVnLPE~6=vOtK|KYELxK!>B z&oM?A@JrVf;%x*PwPMrSzS)myrVDN6I zXW|i{fOP+jl?Sq;ML00X|Cs+Ak;;_$jC(?AD=;k5h z%r!T47fPqFwm;DecJHNkOe%N!t?Uxha$m=Wj_%6X{*JPvvbEc!|BraX&|pr_KcGdP2!OUX!O@4@4oBB7 zNYoCR14&HB7JBnA`oIk0|L6_{%pTbsHbSuJJgD0*u$xlKgkNyr+lWkGm%~|6bPf&kvpxW-*^?dtJukZ6_ zUk^0nA^y`GkY;9I%UXSrwn{AIruy^hNMlj;1RRm{tJ7~zIsNfucp%RJP5vce$cH&-6~M+rHM&Hrr}dD%_so`3oZ za&#iFVU#1|NguEJz&`oz7%4B)%Y`IL`fe|StY552yUz~~V;$ADofhN2OqVAW;tFI( zI)Hb)0W86{Y(55?fyBRF1y!kgiybs%oCe*%*rE$)tL&7==q&(|cT=u${kJjEfKCD8 zvC(0an%lCIw*5)VmyY0TaxyL>B>?4q04I?@0pFSg5wd}Z$N#N?pK4R7Oo~WSYNS9y z=-10?)6ey|x_;Zg9{+M9LZ?-f2P>up=fBM7iUI5&;6-b67IK9gr5~gVJ55+EwE02{ zB|i<$K%!?-!oWl}dQqqt#DbGNrNO#4#0FTN@(J0sXh{LN67z`ecq!8B`pnI4C_~LW z!lcRJ;c>vGO9(LMm8m3sEmuqT{5!$gm%_jR;6cyZClQ1q&Ia5T?UX@j*IUJ*Xfxj% ztQ8NR6Ogds14gVO7Uj4ijaw5k-c0ncNz`UUUQ&B!nRmZ4KZJCXcUAtJZZ3z>CIBeb=}h-Gd1{4k!;WM zVqt^Z$@BKWTiiyQLFGaf9^Eb{8hhbs%J|pFCo}xkNA}U&Rnz5ULx%Mg16!X80AKa~ z{9SIs6pLyR+V(jSvx>nji)!+lf_>&+`+wTVb{WoM(XXrondbk#fxpk}(GEJ?rJ}@Vj!h zsGB)Wc?Z%yv|8ocpn8Z&mybJ=ST7w+dG$;@FVmB!)`Q};EMCEass`YmCYh{vMz?tCjr z=*>~g%G>?@@1@Fk|JZatIZs+W9L;}UTwJ_>k>t^J)&EV*jPq49y-JV3I)J|0@5X3o zm&Up-R`LFQ=hQ8YluX)ac~UsN7}C=?IvFhU7jJ&h7ca@q7;wp_6J)dxe;tn^TKGH-{`^LXuwNVQ<8s_slHDV zloa>~F&WO{(f4lkTtQ=2j$c10-5M`mL!`4qf$Oi#z3E!q|8kl>0&4u%k~7f3wd4sr zNAhGXMUGQY!4l~oM49zsMbwzoH|PZo8Pu*E@Nya<J4PGitH!7gS4j5dsGv>QG6G z9mj7PY>vzf>J}(}i{92@Pi~@b-DdJUQc>_fxiYMPVa6z#m_D0IUi#v~6;kyKRVu|? z6$o~jdiH#Xi9yN}7t2HGP~N3g_{Ode<8^!WtLJ64_q($~%9^`w5Ya*@f1_jD z6ndG%f76y&fgG%pAWTNA5H)}CKd6bp@1Neg}b=^UG9L;4|&? zlyUeTUiH&`$;EVf{{1{}&%u`zDrc$Ob0NT~`A<*L=9A}&Lg-gJpBuoOc7LaH*`9SC z14@Z%a;-r$t%TQG%dQX(%g%OOyzP~*;4aGM!}B8~&qp)wHs-4?Is#8rI&@&)j%5}5 zQ#zM53hTcfT0re#=QK61niZ^oAcsbV03N|GyNngfRSkujX(+_W;cp>0q^f8afkm;p zfz(pVaWt<&0S+0Nm+yc50&t;|3@&~GBd$AJNFOe6$dNtK$`|FC`e6Ct?mwQ>V&Lhl zY88Sk0Mn^*WPk^2wZnq4&DVzpOuFzEcgnL(4GfwOc!jRI6?+%gydUe#zp)Ox%w44A zNQOZ2KL365Mp=W|cPl*5B?YyNUL=*G%zo`**x1(S*W2xb7Bv(F{|BDnFu}6SF;HB1mZ^YyK z0Z$!K16UvD>H4~3?{SbCt_`NF0o&GRH8`cfpWmN9=xzRkV)w%P3PM&o;yp;V9L}7!Ci#v-{vK?3{iy1=ejrCS2A(*y2VLqdj0b*T zKl1Xk4Pj|a%_e0=G5%GwF3B}c{ZpYy4&NgG{=xGB2Vr2*Ams9yD_ z0>rFZ(MhlGKT&A~9bXW61yd1RYcDC+&b%zxv+=$VSo}vGFoV z9zyNkfRCn@o)Dthei5L1%p>)z-VABfhOukcyNkA~3A@c1L_G+!hW}krAh(h6-Ojjo zAAazVx(dT;F&1uzcmw9Qs!J8*u3zgQ*5NcB+#d@eSz>aXYTHR3s#$BtX6-Krul2ks!Vk+Ou%^jDge_P4>zCf(y?3-S5F=~} znMq9ELeJdEBJed$vX+qz3UqreN4Hdq=p2QTe)xQWZ_tbKQ zFoOp&xaT#fN`1xejnxEJ#_jO+bKn~#i(5?)JaBB^I_gi5`$=QDc((Vu(qcIgNpJOs@J6=ubsFIMa+HI zI$-A}S!aQV%i%+VwrjU(d|lkmPfbs&u%-zS#X_0fV?BC^tG_7=ysRc|1aV6xw_gs0 zyephVluoA1b?S}%KJLs>u&QUDpa0uP*wT6T!lWAAnN zU?Qd1Z?N+pn@CIy^ps0*rSdq+#$?p$4-%BUntdbw>L_lqJkZf>T8qWRY`y)cl|_}Q zg@k|?v6|1lyp{5VIsudRB9IkHN@b{#oLmH5V5`(aoxSu z(bx$Q8hfYxu~k!3tI}Q?Qj+j&Zj(}XpAoLN8CqmO^jQsPH_^4}3OsqIez-o)eSI`A zgoW-lR!9Rk~iRSA&tW!1}#mvB!%8{9KkdP^$~H z`WQSln^xWcIo2N=x8uj1sxVtMKcD$rACFO9Q#tl0%t!Ag`Ukd1)u;@Eh*j!Yhsks1 zbz5zH*dP#%am4D?G$M0jIPAR_+(J4ux$7CPLdEt!^xf@zaX$_KJmY_m+$)t)SLjw5 zKNh|#iIBrL=!`zyd-L>q?2Wp1T0u3x`+#1M`QcjA%H(i1<;?psbssq|Plh?+>S*vC zOq~ec0-2=D;mxw(=}uk*!iJ;C^vl3Z;5zl!XuK^#giY1S>ZMSQw7((Lz2^!2jxg-s zg8$Ov+*}XEqNz7DytNh`ZEc9>(Gmea9mlZaurnVoLby$>;I_FJT4Zh`IRcz#Fix(!0MZfi`aT7OyecJ%WOU4n+X`J^}55fF$&Ch31y!zYGXd=buieMla zsNUUNqC+;)=LLMavEtc9{E4u&!8z>)&S@1$oZm@!9~Si_x@f&}jSR%xEF~zFdQZ#l zTP%SkC!>Li5U}N#_JM>h};em{Qcw91HoIi#KYa0t;`>xn=O7tcymr z;whXGC(3aIiuLVVfBKR-*KZTn1lSWoHV5cyEI=X1Go`{BQnEl|=0!2JtbqHCmZ{xR zJ^Q__AT|Na2)>GsQRg<%GE~-9vH5E+p9GFl{|>R*<`!$GX>D|B+` zkbQzYlMJb6HtG9pcXwJdg6a*=`4jT*81tjkbM(n=VU-0Hxf>C3-gjzacccp*+0% zBFSj2y6yLZ1po3r8nGqQi0DM&Vd ztQ}=B=d|v3knNf&CCQ7rD7;Id&dj6sj4rkKfEA&FuQAafET1t^70KEqFz%F6dH3{3 zCk8iY=ri9(U=h^hqo-_W^#S_Jd$>TNDRic{|1jpyX?;+4Oha~!P-`nK z0*0z9JX}T6`6Q#Rkl=sIp9~!n2Gc=F!-l(DQA|l7F{P|@u6~(iidk0>$4U6NJBS&` zU!P6a*?UI`yx?J?y zz^7qo!MgV^_lt-ckBTj{W9oc?zhWcBA~>3)DaDLLL(i(qwoU&|LxwpMDS!R!(lQz{ zaQd-6Sgcds_Ky2^O~gOnlGPm1dyg+69=T2bl(+c||3)7hI=?@`GGu>mo-GS|P_?F*aRwQKqPQ7F#(-?`)r^TszRwbGsWP|@jmFQF zRuhT0ma^!+kr)JyrTQzVhzDbqI(e^m5c=9dED@i@V(sIyllvfXol?hGm`7q3(4|L6 zthKODSScTr2Y-w}(Y-CmTolh3*^y zE%D30+f8fhV5Q6mv_EdcR(a={-m4NHN*6swiq!_Q%SA)s6Ps{?B#5U8>qJ+muRcz? z)DFV4sSgJrWdUCsBSd5EH^JJ!TH#T#xnw#i&NEG_e3;l$#znINypIlwpKCmYuz^eA zF~AJ|COK1*$#*{1!(69nw?BTjnBuV;gttz^fF#}ND-RAEX|wgj)F_vltKS}pcRroq z9S+GjzC8OTCev9bP+fF?{*evvYbn_Oi;rQy%8u{+MB%&{&{ih@KKGUiNtG?Gk7{qN zg6)aOYBiZ}-g%r=9+D-DtY|o$#;^E3xuYh5uMMMSPn6=!5ss>BlA<#Q%C* z3FFQiSch)%Hf}zBA;#tepGPxfciL1!(gPtR|AjZ~{R>I3;t!3LS~fm;EWFM8k{ydg zJlCTy($r}a$npFGo&WVJR!BlvLl)`#g7g=SS3)lGt!+rNjPo!b$-LSzWm|@WJCZ!x zmHTfzp_vNYN9RJO3e2hgUbAfy@qWlpya@?(aiiT0UMaSgrT{v{$XZ91Q7Is&CpI$t zH>%K60x{8JJ<3MRlttw!idc1*B5ncp&-sx~!ryg3;-*})XZmk!*>6CTJ|X_CNPr~N zZ2A7%SN^YA%Kx8HwId%mfN0m>Qg+JEineO0-!|%AraB^*c-#-4S+JDM!wb(eO<8LK z&^M^T-Ve&)HNAhea`R8M#c%6z{lbZ2dF;x|%T1Qbl8pbTm;W9hh?P{2BY&idns7ss z7)G78vPq(N(U{CbOI$i$t87g_dZ%5S3~t%#C{NYzhJDCI1$g!*2D-OW1Wu>;9jpksN_kHCLR?0RhFgLL3DSUbpnc{CA)lW?Hh1}Jg4=Gy zeCVH;><<WY8$w*5Jh(GTCseuJ1&w;{i=^O@s~%kqBq{?K%K*#jaz?_ z@+1uBpyDJb8NYf}GQ~~+YbSi^S_g+{P9dwL7ek;|EjeqDyJMLO$V(yZZT<(zz%OUp z7fW=;0FjX)MuoixMhTnlFjRV{V#`7kd6wL=O@eWM^piT)mkbuWPhcf0mru|pA*k>09a z0HT{v$U##|<>LoD?-yeQ5^J7%JAZzZA!~Qv58eZg>CaM^T)kOq>1HahCjzSV0jQ|@ z3Tm7it$NUYRqL}u75DZWmt5&~SRq^iExy23Ru=~}Uq;}C>5(#i6(fm;Ph?bYM%C)I zLHvend(pECRpYZ|cjoU94s(9=uWEn3-#)@#iNz*^)z>`%_MtO0$Rov(@&AYqsg<_suYcisXpl0^>IMdpmG!&XuC~x9p z3W$0@w!8s8AEaFwkP2AFn@{o_nY(uqS*ep5%AR%f#YwfQ|&%W!;$Yf8I zaAWR^qk6g_${uUWP1w>ePPI;gk#j$ai$%a7*L!sG`A4l8Te&tBySyB*ESiKCtJE3` zq}?S%(r-oUQ@8^jva;%#BtbZT=KuBr1aO*K!TN);K}C9%k^!dzAj0(HssWRyw~gwN z0b~?;;4UCdv;GsUZU{`J-`fMdJ*Cco_xVSqHbVuo38#s)!{Ks|mHTKE9)%95{SzUl z`RqYJBZ`l7fCF)dA5@A5-Cb@qD8ofvXTm_yY*pjGv(c;%9CzDBXnUwpy_%0B0fWc4&FiefX*M5WAY^rS-;h;iy?dI}?1C;C@ zZ;ht_=W&}ItwgmWOLw;0V){Qhz*>IY@1^kkw@Fw2&4BiY?SPMSu-dpvuk=)fP2t$I zhhfs#IEj+#imO^3^#LhN#B&Oj^dvR%yt@f9Jl}TD{p!~^9rpn+YJkwi;TxOz=~C>( z0uHxt^kc6BOkJJv^E&e7<~J0x+c{c*qaGuUisX& z>KB&r7{K=zzBr!TWZk~W3vG~p=-|j?(t|NlDus|vU%9_nBQU6YK6ykEIFq*6%tj8p zDIi{y00TAhClF#vcs7B+-YE{KR63y7J(%{(;kW)JQxpnqzR)uVw(Mv5Ok4g;NV{&) zol_W@Y4S>CUJqWbF{~D_-PPY$K&5Ra*UilhQf{hn28LxKu4naqz)JP&019t*U#Pii zYSe*bvRZIJxTpl}P~vo~V9JJSALi(g2G&Gffim2Fywp7a3i`lq&Y*j;VW<1a<`H?O z0I_iAV*)BcrNSkc^ie_cn8z$%)nyC;!=nB0&)@V_yy!!#eT#SB&!$9H>dI&6Toy-c z3nYDUftbXTb8-!=(J1=X$ql;CV{*6lxtgV->;m=vMt3LMj`;kR+xlK+ai}g~3`%2n zsswdkPSC^=^AWO9HF2H*&GA-k3V@!nZ-k~m$N2$*N(PT9`Dc$M6;ORhss>zEpu%ve z@g?nD@erjyWm@0Sih_hh;PE==2n8tu-WTRfhC^YP^#0k0Hxg29uzo(yS;;O|1g`U4 z90|MM?5EW_0)uBLe#h%-713NyM!2 zLu5bwA;%BnFn&y3@~9cbih2l}pdzM0@KX_0N3M@e zZjAXS9}{y#W95d8doqyhTwaoKn&8t3#w5na)SWcpM*@^T)4X{wAze5j(AOwOLMtQ3gImGw&uAs0`Sd66D)Aj4E;kT@-dhk;oC z?{&z9%b>!`qGSP>-m;cG?GZ=J`YWMr z5$-UG8+}U^_~XQLR7StC2wObL?nuey+`MOD(BsH=DuX^^cb_FYRoo9FV`R5j0mceBF zQBhGZ)Y{i0mN!q_bjYQW>|Un!G~GX0F>{hB4Vc@zFRFRYV!pF}%A0ce-8JZ6xbtZL z{Nnfo-J%hUsbzR}dOGs+0sX`MSNt0Hz!hEn@u5W*H#zsHKcOcl;?>FA;FR6z*zc2h{OVk^d-{S)UR^e4 zO?{btq{>3zd^_7RL?GseO@%%YXtdNG^1O>j_DwmCO^o`VRHm=L&l$?xCTkTM3fc_j zLj^5E-d?GzMK9NLT3V2VH^R9u<)b1+F3JNRpw0J>HZXKuJXz{XqL~)LC*hh;4*RK= zC5yiK!o1~@l!ztr*^*^EgX;C8^rrl~y|>o{w};1*F6A2J`d$qM54|`F$HDk^BA;Ai zm|{ATNM$}w?$0Tjb*#m> z_^Y*iT{*5B)KV;1`hSW$%dje=cg;(8OG$TwAV^4eNOyN5At)`~-6)b6xX&{G{@-_FH?cC+_>V&^>PNSOgU@(S~p&HDQ^Y`1f#l3kjL&kny0~ zuY`BXCqb|MPE97*hz0R@_V&*k={U*5qJ0{&n+9q{1XuH*R-g5FR0^SQnO#JfjtoQR z@V;i~xgow4{7RScsDPRw@5}NlH>7nh`VW&WB{gYIN!^F#w+y$K*q8xMWk2FkyLf_J zE=?c?&MN0IK`sZM9FD@^a2O%@<5C(z{}#zMZ+TdJjD0c>M1mwUM1c`AGero?fzDmb z4$0S-TL|(oqsy@@zpmK491L)-zL5)v5kWBwVJ?xrp11*d*A`QD%`6dF5%ZAnWq6aO zN<77l+!E1(_^C4DU8qWenIIKDanWZhb8aOm@3n(=eWHfPruZv1cw3%Fk>BvIHe4r^J z0omLSU2X{-MvXG76<(#7*m&kI4oN;YKiNGq2&Iz~%_0JufBRJJSWF- zy0tml!l>6+Ik5QwzNgg~T)XA&F&GFR1TTKs*<=t;x*)yR(}R0KXtiA@nD^EErhyJ4 z4@`j4nLO;l=p^9|9gp(|jt`{P0K_s^_3)cN;@9~zwe~|Ne@B!DkY9+$km}?1?zpNE zZm!l^<8%Wh2gpc@l!Fh6VcNkltp1S~X}kqtM!G7Ac8%%dvsI_|%+v zdLp0`3j^8b+3zVTV2Tib%ED|yjh$JyA+c~nbtunD0VY_g4j?Y zX&O8_anTnA$^i^2Ph`l=q|pBH(XLVkkH*T{U)YMgv(EB+cfwt=J;Ts?^W0_xb%a&> zmq(qsc9Y-HVMo-0AZUOY!hWu|qt=q7jtHa$bco+8O*JZMV2#OFqlsrKF-1kGhJ;E0 zG}Mc4=yiq!l-_?*DRu9v{y4}~x8EPXlem$_WFe9vM$&(NdYp?XZUyKR##tHgiaP%K zbU0#(&Os-Kn9Rn8Hj&z*Jx_k2ej{wMngsdj(wRhjo!JmJwOsQ1Ah@)N-jfaXY>*_$ z%EH-9=0HIJEg$m%ZYUV6fTgdEqF!;?@#TTSDPu)MZWlmO75k_boA6WusShJrgu52M zYZkwIEQ2a-f!Eo!ad)7yyCJpWLmSOd-ub7SQ)7wtA~p6uJl=OM65FXlk~9$%GWJg( zmkStPlg$=vLuLv79#2Cm5bh>6avJ!GRcg^Am0O?8caXH?MJ#aAAqRrz{Esy`G#p|}(XS1a| zGmiLt?|r3ZYTUqU!qs2$vK);>PHRMp(#a>cdKQ0RVgJUXuJlP<%7Ql&O6{G(Mg;W; zx>mm2YpmEq?o?kH*ANK8=e5hn95%{MVs?AEwI=7nL^H%7IAGxTGMP3yj_=zUbua_M z&?BKZ{L93{g@{b+_+lXM3;WhPIw>U#)&no>V3GVLh(qFdU`1CF9HYx`UG5H!N$Kca zQWEy1AuKX*%HU0iCTB$ zKtX~|rXjo$cG}i;q#!hmetZe>pjR=bMo!>k;4zy^b9{NY$udq2!u|N@ktydjO-`XL zxc@n=77H4DTMyM^;UUTL!mim{;EKMT1KNKvfAK=2HhS=)qHH@1ElP z*p@>vG;;HfbKz}~k%70QV%&3v1GiDnuOw3yIA8Q2UZIrEgXx3=8ZznnBKx3P8JXZ% zO8S8o9LO^f*X_p!UKf#01T3Q=gm{)@569Z=0C4SHL0fRDc=0=M3Y-@&A+~p*qjJ+j zD*-72C74Z4FD`0`4CbeFT0XM?7Mk@n`?NCVDGe+!%Plz#p_g@%+kzg*MpA_2xibKb zjRI(Ri?pipq<#XCse)^(Cqk_QM&mc^_9-pR@)tgjaGbXA;?Z_{u$hZTOI+k$Zsf|8 z_lkVh*s*jNl}=QE01?Za_BfEWPbC>C4BCKQy$emw zdz4@{KfrJpRLj08#@PJ=q$IjY7Qj9O2aK9Apyl=rBo^z@`QU$y!Pite^)&@#rs1-k zCl?Jwlm?Ku{z$@ab~8!Lw)M`DfLxXfbT*+c8L%N3FNh0UNU*?+5R1&RygaAB*%LqY zHPr7}q)_a>v~Np3<-pjZQsBEibR_iMQZdI=$`|(R)Huh<^gf2mU2!BH1C;`><)(Zj z!Hc{-j(hP4zM(V`UB!rz0L2BWZhfG1^)fB}wXy$Fmu9P*6Dlb`f&0a7AE+rP0c4!s ze=U3};xzO$hd}qJ(J~B=O5h6^YbJm(m-_a@E1-GE4<$lU1&Yd8N(p2jwl?rKt%S&J zW{VT53&0f1<9<$!{F44fyU4|LYjKVFcqXA(Fsd?j#1BvrfD~|EaoKDuR@?ntZF05* zOFjvzIY`zd1*lo|8Zn!J`r{+sBedW>D!m?okxY1vrJwl-XVT84ZO-QpQHW()Q2g$B zx6d15pQ)nx+<*ua%ydUe^GV3QDbr*qXrI%5JGg?C)&!njWM2(;14i%Fa z^!dnrzKjLGv8=tId0$k_yU`7$TmRzz%KCZNO|6hpvR2@~i6LG}9q!+vuGgVXH{oL6 zaVs^~zOCSO_I>B-+u-0Qo7DKi*L1*Fy_A#KWMIDEM7Q~64xhxwfiL_*Jp+$-)(1FM zTLdgRFYd2lBJg1hy$i4kfcZzjv({ZA2A$KcXl!d;#Ha`U1FLoobg3o`mE?HSOApSTA+2-2TOBW_jR+i9%IbXNim7hB9>9;pp#op?-ti0Z85x`5WR_Ctmtp8b zsvzV^lh2hxd7Eww0{%V1;FScBhOYxom;fF!yTdwbC_yy|i zhv{`=#OqB7;A+e9_+)fyl;i0dMg4dI{6NyAk=;Rm2An_tqnZ3YMpG*EO>g-A?yeJN@TO~nx zWb^$3EM!)b!ZjiFarxCedy~1Z`qh?!f9&aAu_h);Fn7YMcCJVn1~}JYpMg`iJtmKQ z=ISjZG02b-FcPdV?0{cWaPKiQxd#sV#HC&(N=Veh2%;WiaXF5jEjIn;{MC;DqfkDG z*%LGR4Vajp6;-6-`vP5puL$O;!jKguHlCx5WrJCQRgtQ!l6ke?k2Y9%8l4YR?g5K| zXpC7Lr*dww62&@WqZeV0ij>6uj@;1+t3GGE1hhzA*L+9E_sv+I*ifaUspTf;7jr@a zmZ5v((I1vyB``;eRjanQetsLzz^I_+FWoHNxLE&TCh=SIC$9gYrwk>d(QA(1X{nt^ z_glRok{Q1`T3RWxaeDgeus06M+)x*FMT}F?jOx%P{g?*v)MP&Wf|-Z8Vmi+y>UC>z zFI0**5#o!<<6W=|rD8ZU7K^^KM-FyW7$O|ZPJL0hj5JF%#X*SgjiZ8D+JJdR(Tj%^ z-qt5F)z7;S$P*bnAgKobBCiD}gfN(s*HgI;bd$4|HZDnFO**4Lnm-@Cf|Nu)<^q*k z6j&0A8Z>pIO0b8poU0mfGXqNjFobd85U7mZ9&W0TrBwDed1bx;deyF_@=p^)2<#wL z(7So~Y}09UhLVsPiRvdveF#AP;DC&kdZ@QcNnTR!ip- zprf{i`7)x3>8xBz2Zao6@C{M^HXpW{)CK4d=#hy$rL(&W#r3^xnC2m%!iq=2CXJ`A zFIMI18-4|Fo*RoDPbI}tYF--Uv(o7-@e}&+ z3Xlw=p=ABM+OUL4P-vKAHT^aGlzk?dZ|ysiV_Gm z394;Z8mm;kxjj^XOZrS558SbLFOjgRg&_guZzo`;J@A^B#sew=*a>H)uj#zb-({OE z73KlD@a2$f7C-Oz_i5)cn=M?+GI-W+dSc&uS+*~NHi7!NR}m+65sh3e0+$RD(hD&q z)B*PQxLhU43F393)Pcx2kdpfYB_s1_p9v}MgiKJxz^NV*wp9t*5TbJem_JZiIK*XW zLc`Hy5W~oO>^vG{n+#DK*#GojOhAAyMNdk^Rr#fV!UYRE_B9Z38GzUbsj>!9O`dAncOJf_(xM#}WN z31Ty2t1iiH_BCM&jc0Eqh{w4pJAK0lMx7d$y2oRg?l(D3#o%n`VK+>GEs-_Coicd> z5+e=qNFO(OIdJzOl(QQ5_kVC<{Y8CqYi0`TV#%E|!e35xtBgi$ieh({bf8t$u)Wc+V)TmR7`C6$i}2lW+gQQOp9w zGfX+S!>$0tM4CPDXHgtpIEo&tf4z!+UVNXa%sdY*5*p3}K;E1d*&MADM@^hk$>4p+ ztCoa|l{r9FpGL=)hrm(dGUrPRe@a8kiArTylOc&N)xL0|GdBG~G$Ap^CJH-7Iv$oQ zh0VIu&&w_qG4u$GmP3E3yQnK4zT$I#$BcdL)FaClZ}pDIFf;X~qDnu>5Lm!!AaN>l z*7-+>w9@+0w3@k~Qb$v-l^CYtE2#|ZMShV-oQop@Nl(u>OQ+ra=`N^SCjez@O+&~mC-}QSs}++kEj|Tu339~yQ8Pv#`40`wB!@HUtsyu9 zQdojjQ?1wqw!;bD7G*3dzb&2z-E{KxFbH{0yyB)&9yDe&xaE%zOfNry--vz@F|9%p zx7&nR`2byEczm@J5noCqCwQ7AGTp}}AdLgdj|53sw$aEMg3R&UoGm^uwLj|E?_W7t zncY1@pm}?&a3k@ktzWcZ7xkmwg``#V#bXd>yo&}t7w9hh zLN38TqornY`Fa!{k6NA;XK?Pf#%KPql~bhiD>#vlbW4JQ$p-O$+H0|qeox!x@jcKlYqGh4dgGk*$Sn&b`aSI0L3H%wa!KEC2} zg)S`}4cQ8G4eGfMBvVjvB!r}mMF!qO7&o#wu%ZxGKBg~S$Q>0q4Vf8xBMKxR5?vbT zkBdhY+;!xZ*ObO{1g3bv#Otg5v<)Os00bg!z1P5WTNm=*r8xydbB`f}=q{2l@D;Fx z#Be`D?{02Eh7!Z}0w4Ga@g^a~I6kl<{Whu9clJ=E)V@Q#zdS4~nUNbpSh!h9nP8+I zNohOjZK|P$xhMy)16mrw%+S(IMsny?>1r*8HjqBKUF@QP{?lZ>49?|`aS+p$Iy^f` z9Yd;cPGkRf6|O{3!2Ab<%dFq*0^v@bKHNG-zT!gW{kRQ?0%5cGxQl?T5CAAoCZJPi zbW;YhnS%rgP|xWBe~o=@ED8uiIDi%{0-9uyCgtr1_EB6xoi6;LY8$3%Jw1UIktZCyf>Ln_TZyf!xnc;P zs6c_Onta92mm7o@;b7Th#8z*1v6jdJ?b|{%`jM1m5TTm_4%0zFf2bMzLJ^30Ag&Ke z3AJ=-tuoLT%ETQ)$7PEyZGeJ-r=OO}E8s4%ng6p?V;Q5eQ1(+!x42}#glO&FP*XTK_fRn7N2N{ zK!&h`ZSWou>AN|~`{SY&Q2ZM{qLyorflNX}5M)7jNeaan1gQb6nq&2cG=#tvSvJcA zDk>HT07v7}(@NoB13p^0DH0Wh;~|S$1{+rayoT{APOmtve1UO^LBbr=>7I;*gJC~# z1s|m@;DUxM2m{r2bdT0L*0LMpFqOS`-A0GaI3cB+H&C zCEAE zf$dKuhyhd#FlfKG=z^wcGOsOlAb33L*MhqVAXfVWfsG2#%aC23S*!vJiZONxn0Prc z!P^h&gA5Y>MU-))v3hZ*vA(hN?BdrzE0FX?;xcs@=UKq(#<9Rk+ZI^!D_`S>QwZ&f zooUfdycu8w6_C(ZTqPO9Tq;w_dv% z5s>yr+a{VOn5EMJ0euKrp5NSV05dioBYI;uLJEigB`TKLEg6Q45TvL3j==1Ghsf)C zxBm``g`|rE1590?TO7PT2!oo&Uoj9rdZ9t5Rgi$gs$r-N4=6zmX=r&j18|ToZbz3{ zEQSzvZGi?uT2|1lrG_Lm8-lC3m>0V_+XXU7Ss8eTPnGzia?;5k=v3s5*%hD0Rv4_0 zC4|AdbWiU}4W@fYSgegODaYZM@fS2IXhRX90YE3VOi{nad<3r`ztU|V2y>3B+AnZ> zq+Q$x$_yrUj0%`H^7_*AQVvxbxI=S*99CFvn9LWu zONjWJhHSGp?Ax$1SO_Oh<*c+QsF^sGu6^0T&1!{m9BBmW94ffP>DJzO)Q1PKssgav z*g9W!Z5-F+4dsXmE^`aT*fj*ntS*A{@D zc&@+T5E3 z*|~LT$RNF6jpsdXIvAgdX*%DtX&L09bIJicdZia2b=1f%=kdHMi!Uso4#4MK3@H@F zJp`}s6XGcjOY-xzq!oBb+#Z)(nb0X-5C`$ycdEk=aiKC7=#Zp7glw*%|7M@49j-5u zP&Eh_9Gt?V`5j7*Yh+oS8O$xZC|S3k9_Zf+4Uaj@W z0kY85@Fck|kUptZzZQC6l*c^9gLUB=(f#-PEKFQC7wZERO*m&j9CTo0e`+*NArwbF zwgR3!N5gaCC9~*YgW*WOnQ=Q7SccJo<@w5Ad-$an2~>&pit@mZ)79h%&`5yZ{dWt%C&?BAtG*L(te+O}yia|7fZ;lQJ^`p~uTA?=8E)5k zT1lPq<>Tv)PCx0j9fFQ+Hl<16X`|OgoD>1Gq?b6kdAt@#!zt`Dm%?5SVdn^6amuz$ zKlg^?%B`O(!=}!3k$jhmCWcz*n*X8e{Ss;7>swdktaq;Hz$hoy?scnn#AMwb_QKiv zQfP&y{czGg3GOgdxLxaAT zFj!aAautHZz}Niylk~-VSZRN-aG}n3QLY3oVi_ql%f&7@NHcEz&$)8pui>NGW~NmH-WnE$yrH5^1}T zUcv^sBXrlNeX4CWFpxRcGvVu3cT&=w)utBbaqf3}znm>nK-DRH6p?$fdL<{liof&P z7Z`x`I?sRwHHyoPYf1CUH@u_bPq&(Yu*%s2w6-m}LH8D&Q_+SFvpPbF!qWjM53vU! zZ*{)Z$P#j`!LN*d9%!hDdq~P|5(!nROuG+dXlMup$^nWR1{`4sY7a?LzXQ)Sh4EAq z5qiFKA!M0vSIurG+hOoUcqF0ZzE@V~OY~-}6dzpp1cb8^pH<~e$>f5)X6_Nlyo_FD zjM)^0cbqdgkodrvU1nf~W@Wn-VdskL2t8h~F>Cq2&fL$(4>Fp|nvl93)h+aP>=eod zo{wS(5{@Eh6_wh2^c3zhy!~4j-LVfXR?(;5j*Eh!sjd?*e;}5N<;WTfm>MX<7U|V{ zWEhS$E@o!bAS_N)q`vTtiNVm*)9V#tEKAQMT~~cbap>>vk?%A7`BKn@19}{;hU!%T*%`_6~#OZNY~BXdGgo{EXJf2fY-sbFMv98UV>q7eIQefc^M z%WKmT^=O^7rTBZ@#M~S}aWN}bSjRfTpU$DLuC8u+Tb2y%`yq{pt*if(Xrq-8bw62& z5m6eH$iL7f!CUB+d#qu?wqbt1^vV&w{fE9e*Tmn?XA;Rs&oVSK?<6P@=)GyM-(aae zXoTciADw?BvNk!ahszRaUY&v7ysN+DtRmWe>ped#milW=&Ynu%j^vr*XJaD|j;FBw zOj7&D!(~eka`2cnP5TYuw9gNim{ntG8af#fnY?$dd{^cf2IFXy9QR}>({_d+LvL?c1KNVs~MrPRGdaaeSEY|Moj_Nln zd*NOFruZ)Z0Db@2zB>TnTIu&up4GiJ_u0GpxAL|We|nW2v1;tw;3I_{*4TQle+V6g zTaYzGT(^CG0x1grn|Gi;hHtNK6MAMooT=@lc+aR_?3eWzlG|#F+cH5P&fn6Z8NUb2 z{X(lg&)zLDa$jGY^BYZ&6XWBDfF;Znq-9{w739p!ObBZLtQt_DirPTnaA}5kbhf;d|S1DXbe`U01ONCZlISe;fcsW~Lp0CRYn= zz;a_)4^#z4K(f7g;(ELy0v49jjSw>A3}+C+a8L^F(O=Cj?DnUg!h*C6$62sAS%du0 zy(+mX^5V7gE_2bk2ArWns(IL)&*LS2@|QO-wwlb{b)}l?zf*}$=4>OM#0Dr&4jm9{ z3Kj3LQ7jZCgChz1*52e#_)_-iPx=gMxwWlfe%0mfof1RnbM*nc`Lx>J-vllHUTU|l zuDW}_=#(#)Z9v>&wtxP6{TGUSdV|a*VG3g`ZlwbPyo*B!#kayd`yLFiS(IX>OV@il zgBIczjO+l@@|A9Op=TF#)qYgTyT62!;8Pl#HF2_?om`y9(GWuPw3e`m0_9P={(zZx_2i@yJ3M?x?JUm(WXG%D zzpZ}tVecO5J)p!Y>bJQrjR+ zkqMnH7ix>$SzjmT+-;OidGaKw3T7UM64eDvWJoa6*w~2JNX+AygUAPXt(8rqSF_jZ zQSM2$X|I406lV6>{8iV}&DoaKWRBl)HV_=^k8Xh+;oxa3;qk)>p7_hV_ z9{5>==Pyitd}8(_CW=6!@;*C^Dm^v4yNX`+w8;;qMA5V!0T{p#_P9x<|@)EF4?Kc zH*qql;^RBOYR6cLsiN|ltdcW)C|u~oPhyt1FGM!u@?0a47qoedJUi52l{{*WI&D@J zG~V834^ZwdNX*%bH4S;~alWwW%<5H6^U?Sw)q1hT83(Uol?J>BWsfZl$T@rjACZ1m zKYE5d&ICC=e0(h7nTSBNJo?0vP=H@uyEcAj!x`;O7Mhd+qoUTkjh>8Iji@<_UCB;# zI>x=01I)=oB>fg^&Knz|1Al~dY>=xrOV5@aI&zJ={CQk{W0t7ha#P76J_3&Q`q2@~ zdPvk7=&bAb4tbumg(wQ%ihGRQK6xTDD>5ec6Q8=ZQ+2dec5aH6;idq zj?NeL!ObzWXC=k9G1Az}qlUFSP{M&`F4_Urn5`}i9pAFOJ{{Y^JVOkGL4*4penqMBKgAgRslRrubwkS4FSGn!c=n3Nr@ z<`SZ3H-T-@J|29}p#j+Gb&Up=bz!bx43wIkJhk2yKxktZDR?ohp&XO3uFGsL9f zf$un%__+ROPRmQHf#VMCRS@50MsGk_7!^V|_QrNvM1o6t8^z&Wo%HMv9qhsiaSGM% z?-^JvR1oq9XFL|brW4-geoU*{Rc&YepqYKB5gxq*Jp0f~Pe9im2WN7+W74mJCimt& zo2~2Tz*Zpf&jVF0N^-g+jXfs-27RLkbYfth#`kLmf+nMWGZ1T2QgsV~8Xgu@<_--T z8{0~&I}W&E5&-CNx?h+bUItLj`kmGIass2#l@C2Cv!M7D#3~Vi*9U5Vu)a2FWxf65 z&JTbqW%aAM4zY85e0;IRwc>`#l-3r|ctkq}2M71Y@hyr#^DZ2G<59>nIIZJpwt9qR zzv8nQL;@~H*vIt@hjwc}W{W1by$L&I6~WnIudpN--pW1i>`Fa=rPg4_|FyExTQ^l} zJ>wR8*@tiFdy&RXSv;qLQ*GzOa*@7KH~7gnX9?IV&RoZ%K-~l>w(tpd9nk2*Z-rkQ zGo)fp*lhxtU*Ge^(udX7rWdJzRYXopD@j}d>Sxe)pbA4VPmx@E%X<%zTM0XZ9JBAP zcWs#?q0hain$JOHu~EUgvXA-Hmv`-(gYLv^xeEM# z`VV?Rw{Pf-r6%_+`-M!;rNtk-plTi$1YxvWC0!kKW8wllDNcLMw_P0HI}L6^*=n*z zpUvRqHSc*A?;5s<;SDut6yzbsL`v@Z$RdVmlQsI_zpc=XCR{6fX^3&KjP&V%OXRVC ztdCNs-0`zsoNOPFvPds?ZU%@LxCo9ApcYY7Li0|GEM( z#`g8YrHiCQRKaV@M1B2<2M+@em0S%nP%1n}|8xPO+^P8wx92IyO98sP+00uIEw5JP+ZD;RAy%FNY&GJ* zA2I?0`t=OwzzgB!guaQ?AFluoh6n8p%{)|^Uv~O(HOj^Kr7(MW+tZ z1_sCMU!Ypumq~uAB)0l+COP)&7YQgbVWyFZzI5NlW4<_W6-F}0;G562&yucXi&%1U&=MhWG-Y3ALT!U#$~<&> zZPZ5}LGSPq(mHmZpSy0ceK3Eo>=|sjBqCC3h3Eein_{}(THcK5XKnNT`8vc$MjEUU zCE$2>{!N_wXi3(KC85tQN`rP=5dW>NS#@JF2PYuPxwlY#GvqrpY7rDAub+fh$c0#S9C!=_K+ZAc`Ap z=}AISQ4y;V%r2r0T_+YC5Vi$9}OnvVUc0^Ai)@TuAFe@8(Jz;^1IT$RP9HH!ofjW9%cCExHGMoT4gl%CXG3n z?quZ-SGB|7YV<^d7Yo|r>7!rwP)L)1aL(CT{xXRM^ zo$s(rxwj8xvEG`?3qGd)K8rc|HJjlb7K&!;O8W@3v9Dso$;tRE~(*$-v>O7+I zsCZQ%5iv1y)~xAg5nE$pV@lP|7nWa#Hm^%Heqg7CfS!(a7Atk@Y`Ok2hg98`l45c) zl8DR)JIl3{Av5cXFl~)-GK(53OJQMOoMU|%1Sn;T!MrvGZx$S@)JIdiRGqW* zZDLA2_L;FiXqyKjO^yCm6D$${pxKUa=3#4f`z#H zfyj9M6v^sA*_M5t=EBlwZ~oJw$2xVry;j(kQ~*nX=ompV>PWJy*mAVMrU+igb;fJa zd|Lfg22=MSu>p-sEF6-kI2_B|MrVdh6pX&uFRQ;7>)4iDkIlIUn|)4L=PPs~n`Y>Y z`o0Iy>yN8f2r^8w6&Io)=`w#ko4QZ*YIXz^o6RYAcxH>YjeC+K9B1Qko~4c1!S{@* z`dhS?$>_CXQ(=T-W!M{`ewo_n(D>Z)HPn4@DT>wXr*CHZOtHUUi{f2dve)!sn_X}XepB@oSd(_c-y&h|A=k*&-~D9sHAEnUMJ+w?Hw#Ypg2!Y4iw!2ZsNKQ!|GG)m0l^FZbb}R5--}%G2Qo3CPxqwm3 z^JgSwW`ugMv&RdTYh$OcMiy~8uP^#en#d9+<=i%}=VSXu@%^$+`|6_1r3|(LiR>BH z$6iuo(-s%ij`a3Kh@wQ< zD<^_ILlIrW#S5++gyQnK1O<2;`eDm{ojtyZ?L%|Fv`v(}4L`;k+@$sFPPxh|qm=mCH-k=XTc5w0 zpgwjXaMo*LvgW!kAdNT>ma^#Sk^1#sv0`GYjV|KksOYx=ZhKF^kk}C$(@MkxYtywE z%{6HXJ}>?~wm%{ZYTyb?KQ?Jsa0Ds7+Um~hKE=*0{}JD@XS$Ww-;%UUhoUp`2xo6S z?Kk&u!UEsG3nvS_bNNkvY>-B>afThhZ11&4>qZ)2)YZGIstj;7n3 z_8Jw|fsiHCNH%sFOgD6oZtq1=-(+Xf1zOsNe_8dcCU}js9@Zum@sq(qqHHa}T%UE@ z4e@+b3GlFgLTjV;uQc>blgsI?==PHX3t?Nm{nadYE(=&Fieb1mqZWZpp4s51a9g8= zlIfT63^JP@4vx#c%TaH&R$3&ho4q0H@E2=-!AIWrTKX)Fd`Jk}$ zQ4xl_sHA=Z{Sn;Za9@`%?xK;83#CL1E5vCioL_^>i@$TaqAU@(3cMI=ZJa zlI|8w&(^bZcxKaSuj8KD5A4XF|DYu^P; zPb8U@o3K8?pSef2&}aSMp`ilmm~ZoJ?gq;K&Ydt(U8%*Ii_iUy(H2Ptqt=5_!J)R` zoDM%G7{6oiMq~O~?#DDZy+hmcStZt7YyU3>81>%?Aa_fu$v>wiwcmN0_huniM;4_& zv4cZTn0g?i{yPCUV|{xLJGz1jy@~6|+SJ5V8I1bx1aJdCH4RmMO>7TNQdsE3HQWDpk%Js% zE_VoE)PE-cXZ-KJ${POXDS(Rvhh8TcLq`2~0{)f%?(6hI<@ElmMt|mi7YU~gMtz2i z3ORuia=U-`b-#2?Q}RzS`N+SE{P%3_z_a~#0_vFa|L*JEtAEcfwg7UG)Z`-$pRDw7 zD$awsMA05@Nf-aC2Az~aeJKo7C0Ll4QIxKhUpZ z5)y`iEyVww`Ni3pUql3o$JHNezU46!N2SG2dhM55eTGPILN4dnnJBx$&7exflbt5= zd$pR6!%Uhjw|JLxKc>*9+oy;9{h{tmCi?5RInel%R8xBiT2N+`r8{rA-oC|CP*4aB z3yWJ;GA98QdIxN+0YfNlOSb1=Z#w%Nrytel+O{eYjT_}6NexQPRt5b@8jGuQr)Y#g zW5nIrLi~+lLBUkr?7Jrr({F-C5b$=)+~dr#MS1u-CV`!vBf&mzQPE0hOa%ftn+~#` zoR`rlub*_tBgB>ni2a^dBPC&CrU#2;Ly8Nh<+9QkhJS@jd~*{);Ji@sy^Oc#{4)WM zK^h5~j3yxH0EmbP_^ zkjO9n3{d>lS+_jZ=)r^x9!+l&5r&GL(Sb0-mR}y6^TzdB_U4fnZy(tNvcvaLzd2>p z6F=Y<311%*ijIy(L`CInm9HjT-`NQQ{(WT3aVruh?k2R`Ts8jO+D%W diff --git a/img/actions/goal_state_machine.png b/img/actions/goal_state_machine.png new file mode 100644 index 0000000000000000000000000000000000000000..40a8bd12c7914ac3a16f04b875b4353ca8a20276 GIT binary patch literal 36145 zcmdqJRa9Kf7Bz~ydvNIhK^k{=hbWTZ8YH;86M{pq;F1s_NYKXJf)m``g1g`1oRfU# zKjYq)|M9*sM)z*2YOlSjYOXnF?eNFy3fLIr7;tcK*h-4BPvPJYN#Wq&NzhQhH$=-; zC2(-Ga7waL&)xNZ>mipve?c)jtmu}^OwXR^+{X-PCR`1=o%2>8`%EA#RuXUTZupBm6tw7Hasoh!U+F z5?Z7s`Gv}9+o0(3a0;f1f9{AN)W1uvWq)K;nwAYu@jWwskzOrIJl1~?;5x*=E2J^@ zMWZxrFdiNZjn3>f%b$QyMuKZWiQhh=!&3ybg%d9KB(l-ntUkNNY_dOZaI=?;|D7BpxCRC1NP{4U!r29b3^H{RfxZPVk`IB1O(yuSiQUvTW zryJb%=Ar@+QH^(JV1n-Z*!;Mm+djNE&`V~DfF?T z9**fkPAHHE|2>J$F$0)ajDLN8;(j`55j8Yd`DU8gWSH~I^DhKH%=@gcUK=Rut^@`z zwv!sPm6~+Ma+!26%N$KPZw?#%o+w>AI^CIGzC791kBc~1?p%%%nA=B(3HsgEHCvo) zjWX-iIKPJ_v1;KwdYaEk9V+Ps_5Q+fLhO4Vx2%3%lfQ9$3*z>q&fOtjBa2!k85-rl zZZVK4xAp5wo_Ce^g=5`e4=aeNMDJ$f*{oX@I%Y1N8q9Tv9P}Kfl)$*y6oAI99}WO*+1kT>3)a?saU2@uZtJiohJ_l=yeSZ=ePSD)mU zH$eim>AB5@#E4&Z6^6-s+ANQZG{FW^xDc(!3b|Ioa~L2>zhf2+dxb8JM>M$1d&vkL zSD|~sg8QE2yS!6MpMKZ98`t;3mbl&zYOc~LGZ*MazN)>uy*k+XR!kl*i3_Gfz5P-f zdcu)(D*qeum*uaG9M!FUeGYi2l0>$|<8f#j#8CXI)Hp;(;Gn>H>sNQAl$b0NsfgPy z@0%~R_zd#d(jgcr5`GQMC)0L~e2}2ItaHPKVu}|xj96eT3tlYv7V>xT9=MNGrS0rH zuU%Lt#Bo|=>33jvXD_}zG5P7ttncQ>WKM@A+2toC-v$S3;~uJz45oZ~;4z9GZ>17>iXFG-@djCeWkN*NyzjI-sd<08r6Xm^Pic;}5e6}!qbP+42E@*E-ygimt5r^9slGX#<^mIkc|MutMGx7~vrnpA zE2bNRIUVP#>f&xAJNqo;x9_V(NnO`@_hB*;7X6fj!)1=E$}(0dztn;<2r_itxqY1- zn+HF-&3SY_@2S}VdtFh~ivJvvCxtOVnr^Ip9A514U~Lm8k8yh}W+REb|a;zCd^|JtG~=@TqWXlT9f)M(amGT&>7Aj#3&J38!z2&_?Ue z=B&G(d2{WLM}74r{JVet-OMe}W+0@z=cyb`1YfZlOGA+SJD5Z6J{j30V8)|$oR0Xr z67TNvWCi92wFP(Zx7xk7AL%kuM>)c(dq_HzEUO^{R@YLC0qU}!8Zq+Dj*H#rL)~&` zyR!$kS9|jWS?akh>A2*-9pW$NN@$4NYtQLvwnR_b7H6b#tjKxs0Y;J`;?@wNJ6LToLF7bjW8~XIs3Gbw z;w0tRy#H{`4C$S28!6(tILl%^cU;8&Se7}*e_#czF5X*d=th9ylKru^w-*NxrQqa+l5aREO$|-`> zBXpkVC*Xd9>|qBCZ!+ur6y24$A%9R7Kz{qA2vzBWYSNP2O|qs0=!|FyqWdeBoaH%~b1_R-79t=*CGnF3N4qlTo`C04Wv8d~06*&9r^2fLC3} z945IOPAKlK$YR(KbT%#J*38xl&nA793D~`cjpZE7bhKNNSyRJl(ryE#VVpWGCWcCnP1)k(4U?!!TrI6Kg zTMp-QS<^i+sbEP;U)3Ro;Hefep&R2McjJhWy5`nPbRn;k)BKrGC9>RNA*Ykv0n`S| z=Hzu*1)c`v9S$wIxuKV1_1*ES4l0DOS8<&annRNOcbL?g^b z7#F&kZW_DTU%_dLI6Y&TydxY$`=|fudQ26c2$XU_wc`&SJ#2rbqO`Fk@E`if-pj`0aWE1i_vHG2fNgaK0GA{Y`x#Ypp*omm*Q46x+lI&PijR3*Cxk7yO3?WSb@yj#B zWGKAE9hUR1&G)l!#r}030X>NU(NqCi`tXOVh)Gc7(;dXEan#FGBzEsI{Vi1%$I zB<+=bX^0^h@MY#YK5@F&`-t`z+_>5BMY^SzJ5$7hUL@yd2HDRaEnItKYtR@@aK>S- z&&Ius`%lpo;LZR-XSd;;gSU^5@T>q~x)T0u4)Z+}+jIcu`aEwnr0ab*d9Z1oHdnS3 zqCe_W-$Qi!={HR^E^sp08*(Z9*c+oitr~3}NDc&xI7;ow6sW@uge^9|KlbQ0acAqBOWwW3&4Pgk+7wU4r@<7x#LI1FrG@d4LbSF%n%hcXzQwXU zt%Z8FCi}t^Uqm`6ww7;4SpF1}=b#?Lq=Elp8!TCem#tttC%O=)z@~xJ-Tvj7WOsa1 zFnW`9F}zX&g3}rt*u6uf+hw6CF$ZgDVCj^6N7U36H#T1yBF8loK2OSQxa!9C(lid! zQ!VA0lyU1m^Xbo4h6f*BRD4}+&(;dLqYiMku93{ zSw^C@6t`sHP~~@G96m4p64&o?P;T>baSOqxsw+#I1?&ii+r^sGY&wN?Z(Vn0@}xA- zThk{pJxH-W8dIZ$BZv3FoJe4wwedec?>;On@d?F}Oy$Rq4J6OIP5!;vwhzo0H)P)>4%-q|HD6+IxBp^4?O zi0jN0E~^GtuhpgVPm>lTyQFe6^$^*=GYb#lKoaWQ%B@$D#66Iam@8Z)3ce#+GwV zVmQR&Wh50QuO-4tKb1SLwvN?6<{eJ|ktqtB-p?a0?Y?)!`Cnfgt*})5(;BGP=}5VE zDGL|z45r>x%`!SVoUm}3q7DA|=&~luX?kG1&_ld!YO7&(?fxy8UE`3Nw~NK(=hK>h zsyJF>u$;Wr9u4bgk%PkZrlZFi@>-cb3R!uS9xbB2kFY?{lJFRBPyFQFs-JOh&=};81RQS}oM9UZHHodZgrxJO&^Upph*#=^a zU-}g{DnvmPmTffuE!hRbb?aAB&OqzF)##7NE2GxJk=lWDc+J8RoI!@o^K+Ahi*@!G zsc)K18E!A$Mj$X-zAO-sz@`Nh<*wc_e zu5m6^?AU93g?b&A9xFLva&wwCx`#@meMBit^jQnHdb?<_x|A35ZyL}tgV~IP?22v0 zfOoJG7frKjOB*A~KVe|O_{bbXS%TH(H$_*vi=Qx;r- zy3UHfG>6>IRFYP}j)BkUrT46`|Kj7FX+%U+guOb%-ZWIsWO^UZZ`fiiSffjiW*8J+ zX5wND^rvvIHZ~}VZt&%h%KRZ-B++Eq5b%|t{Ghhqovk(L`@mQ2dn3GCy^MoJ#tDb( zL1?!d_KH#N9Z|Ki3C>JYLulI!KFZ^-&mUbMbkaPLFML%6rS|&GRc_v;{I&~F34`U9 z&wkIqMwTDQiNdshv|$JsHz0rX^JC@xB8whjc)S6RMT1j!D?Io;%_X;z{aDy$+T4R! zH$*=+*#KquQ`DtUr}1#*&QOVx>S7CAqt~ubgg0kQuFd4<@nOOro)yHGvZ)d@g6@MD zskv1jz1$+Q_a(*uDKqd&(Sng-f$FRas}+}rqtb<4Fdz)qge>%q__%7z*8t5`BcBt`C<>1Qpk9j9|4YLwAEPehw+u}vF_Pk_?+ZCYptJzEka|3mL9zPHYIgb z>9zkXB5z+KwFK%umWd+gYw1npiQ~0=THWUP3kSy?A)fym>yDNb)IAN$x+s0i}k?K&F^tBFiYdfT8M2u2c{TvwmIm z<`DqP0ymSH5kgLDDWy6m+pzV_)`jLEK!jne3}nq;d$qmA59N(hbjuo~}fBksAc z#@owp2TAto8e%8!Q&oDD+~%BW`goaz+5tiU+g9v84Sl^|x-Y+LI~i(`Mq z4+?ygMzD}|g$PIxF{#7R_?SL?cJ+*`Mz*-)YVQ^LL_<6>CR;AP^rA<@%MX|TY%FyO zO(u?|fC*$X-jKmFJ6!4Rh^+{L1hr&%OgEjGdSVHX^H~uAqSQPR#0HZhFC9fx!XkyJ z9{zoq#Q=G0dj4A3fH=<_A^G`x!2FSOphh`*@+k7Ywy&}p?Fr_KGkolOxygj}fE%eT zHdN&5^W&Vr=`S@5q-H(un_2HP<|?|8B^Uw(r5K1g{YD}r?GQT`g#{%r!Zkn|_fa|l zPGd~TQF3!AFN}^|^jE)2G@wWYf|tSc5^$0PthL3MjNQP1#9bsHNal{EbO9Lx0kyZ< z##Cr#pyR6lQhR;<@X_hj*(?3%jqdr(Gka^5&{uD!kjgDhJf8pe7R0c?1*0uR z@zTkscLt*qKK@~Eq>)+okxD7!n?6{v}sJ>&x@^ceoYO+19SK*@>Nh>j?VN9>+otxkGQAc!M}d)hAF1;e^+|9PHA}!X7kT` z-umE@GpAOoSifVtDYjt4$#jEQ3B8di+-MhVT&)b;g2(PR!cu@4B~$Jmts;|-u)g=rUqIIyUiy;k z|8)po4PpSHv5)o%Nq_*R$Qiu#mlnj^hr2JjC7%-B(E*iD!bZ=lKY=Mm$e{hCF1{(U z@X6n47N7`jhd#cXD$tr3h8Fo$7K#v5CjV!x#oGihQudMxZ{;KcL<1hM_{dI9ivP&dms}v-bJRbzNU%RDXvG~a{=+#g7}cH8_LNhD_eJlQqyH6b zz*RrGZ@yyp5oSmsm{DAzZ^rwI_!reSA%ap$6i!L)It+B>S8}gh00|%n9uZ|>w{}nd z_WI&}TQD8Sqyh^Iz13J@xOv})3k&-bmcRQe0HgGz_}?xEwX3^A?v7&t-f^P$8vXjB z)Vz-z2y6dBDDe;_W9j^!B=+sb=FzhM)avkbcyagP$e)t27y`FE(hhj~sN0*X<-^sV zipfwafNO#yNI7!7FAmpwG5wo!8~hNhS5JD~SVwZ({;D1m{@($4>kOhne}jW|cqs?H zE{2=-qAL!$D;@hw%+ON--9WJsF|f`Tgq_uYF2eWbGW9X@>dSK)yC~ZKgoHN!zQ!`$ z32U0V&o`u`+zc@XX7&d0fO5psc7(8z2bBD8SWns?H!-J#9=s)g0Q+eKssqbF4# z^-U>cCF;5-#Q|2psigHt{Nn{sP2=yQLy*K^LWJ=mz0TjOX>k%>R=kC}`)j`#5_D&( z;X!f5riVc(f|9R<2zVe~8#IUpPHz@2r664S8%)lXrSDb#SPzy8_Sj$f|DLp~zYW5L z^Ho^%wsrFO9Ey$j^wYInUE?i+e2lr?(0O08ftJe-#_A%);vG)e2FsWR^H3jWH~E$5 z)*xM9vOfMo&;*%F5hbPIhnx37EqSxn+w@FBM<3Ty7*KzT2Ji1|BnnnZAq_CM~Gps`5fO6Ps$oE%`)Q=S$ouUSsLW^6pFM6Z(bQ zs{oi&>y%To*Cs%-7$J^>1Iz6Zq;Wtc&C?1m!yi1_7QNZJaLH7k{r>sqzMOl5+`|xQ zA;nd#V!h7KUsyQ{oksWnmK5*631zyy4ywewDn2doGknxEP6F?-SIjr!AOOAB7h9t_AH7+ z3f5=n55M8ixA~qR*dbub_SWc$D#Bc?8^@gAoe!$m)JqKf4WMCT5VHiYXZh*-3lf3c z#CcJeX|T>RW@c81QE@fs@tozxAktTsO%#Cy=6nL3Nn}l2Uok#dYM0{pDFjqko3-8R zJ5U{P8@HjA=W+cG9~6-qkhNKS!4($~Me+SHODMvVjSNGyQ3V=!l_c#8!b+~z?M+&)?0z@sxq54`rR02wjBPpwKl*2XT6oDph>>ij?(@&09kcX8po@53CaaQLD z>0%t2a*W%%oGjr{daAQoixWQY>e1aE;)M{>!hx1p-F@FLFDqE?tq&Tzv{j^NtYZqdHo#|>CSZ3nQF*%<-zz*?zUMaz+s-vv+o64&mqciY~X8`p-j|M zYz#JU#bsh$-5oq6RXwj<-%y4s8lqsG4`ko%%dpCZ8@*iakW;(d{ndTxXX8|Gmh<{a zwxgN#E(Gh#Q=J@*_usSvewcli;2qNy6GvBb#m!w0TxW=+5Kvz=7xS`e`AV$v%N6vI zu0`*_2<|20i&l~HK(UjHb@A^E^ly*9>(V8rxnzHh$rKH1|5oXx4h@V7_z$!{>0vE) z7vKxM9JH2Vm^~>s-fiQ7eAeMHoc!_130i4aB}&Q_^0GP}-5?G#9;J3G3J8e;fpeH^ zCXX-APyyK{`amWO!8HYUTxkG9470Q^!{`Z?(~lz-eXqVl-IZ=a;_)EV?-vu9n4Y%6 zZaA+7B5iDuRnV=UnqC8^)S7@3r&BvSB|13Ot&Oj z>|0RDFNhO+9V2nkyW34BR^G2_6xomISS>%a1!m$g8h5V16w@a#q>Sm^D{Y$Q>NN?R zez!t5)3<)AH38byEa&HKSKme7bj4`Bo%V8QIX5M*(B`;QPo&YK;o{?M8>IAl;W$i-ZLJl0%9Eeh zu>%sQI8+Gnj1|(bp5!XcmdBrz5^hEM(wJh)dTr2DN+N>|qbORw+W-2MZ=mqyD5+hs zak#h)-~Mz<7MlJYB(cS|0GlT1zk3ULO3A6TIS#KJX@>qky|qkUVn>W3|5QX9t2W9Z zLREcw>Ecfy2ilO`6fizvbzHO=jnEZ*)o4^&WB4GTnOuPF{gS_uawE>;+(-=z)+d)y z+BfgO4^DvgF=nS-2-TK1Ea||;{3vJ`KU|FXo_Tp>Qu)0vgJvW6fo6SINZAPm$v4a- ze6m7^R_RALDf!3Sa1VRVohu1G&c7Wk20wVg0eZa&ZQlwsLqf5hDS7-3k@3-uuw*#5 zc*g%PhxPHPdb(f$FxsGElk+xxev+5Fv3a~XvN2MC`$;3qc8Zw!F&uE1Pzt;4dY8?P zeSdWTR^20_EANL9Tax{e&;uU0E(6kCrB-J zTJ15r+#CLgIp?uXH4^H0bLlb?HjBI7wms3&Ft*zWfHm+2iR*jq@L`ejqAA5gxW-q1 zCgTF5pENKY0Snxr|7=3@FS{m^&4qxq{)`AfZPw@+Wgq{%5~{qa2kc;1{6kFf>;2X= zr`38eB-h>)u2xapQoVtQCC|(VVpj9aFMwU2qcqu@tFJ!l7wJ37qL;%s5?Gz8uvSbL zEWL31^7P|=Cyie=u--B2R+pq=-eFPjV*wUO1{e_SPCF|NybnTPp@+Z#WCV0O?J8TU zct*8%OYIS9*4w|n5XRO*A75g38PnUx0#j7B<7!V;U62hkf)sSE?-o7_hr%E6>P~t| zHvCE5bDcVVL&3upcK=D90;6A@GMqQb^SQ4Jw31J|k{f9={l3Ipc#lVacfZRJKYw#U zuUqR$91@Y#hB>RR@X_k-hMzrCf+7pchvF6gcbT5|Re8E0EE^Y>v@5LkOqy(|F-&RW z4Hv34IF+kS4`Uka#&dDv8C60l1Z-(dKCyj%nTI2M=1r(mw#qq+O>vAO@5{NLZQ&QEE%!GARLGITOl>P0PZotji2l0}s>AR~~U0co)ofxx%;4lA(IsK8?r2DuDk^NHxfYq+DYE zB3~B4QCb4{+VQ9%!cOA04%D*F3pYn=X?F6kyWd=hALpxg&+h5MRxf}%+<}R!#P`Ni z=J3Mp^!H?x6!rAcQuh%hDXfHR66RFkq0gaTM<&MycE2pAewX2VC4p&Jd<4jL>Niv6 zT#$TFh$;dbY{S*A$dMNh@L0X)Fqq5wD&T{v+?dH`3N)fMfm9@R%8;W>K!26yiQ+ei zd|qbC@*YlDuX3l>0R+sY9LSjoon>^}6mE1N?My$AxeDBSL$no9?aUP?$onl)HOk#00IwsGp z@$B)@VraGFDt80f34BAED12G+o0d=5*8B1U>s))|Z@89Z4;MGjW`19J?Li~24e@;S z8t{153Z+9MQ?Wb*U03i>u%c?7SmJJ6-mI!5mv}6{tUHo-%O8lv&ttsBv!m*C&C%$R zD^SnaAJsAdu1>5_ID6EQ@fG8tT)EKdL0T^$d__4hI-vZ?mK_kMR^aLkY7Rop1EtLC zq1=!sj0Rf}0$^m5`uhBfEz3EelX>$qM3Q-b!B~4TR{9N=`9TjsD`|@F&Lsupp;pxNpU0 z3TeetFyC~@;k>2k7848SmHq~H`nL^gzn5#~64ocjR{}H9maG%7ikcI3?T?ne6l8Ln zw!FB#y|P8XrM9HbQL|I3fwYcmeh`K0;Qly90s=hoKS-X8-8@)B*YIf zJx|kRGZ4kSxpL-0X<#Si&}|xGK#gOXr=pIFaGTo*6|1c@Io9II+i)JL)9K3O5x^jQ z6o7)8C|55Zv-m}QHm^LDd(-K8@db0G-Q)(B$J@;g2LHwoAI@99rDvzHUqnKiSy>uqabU-kYoej$zW+N(dLZzP`xQKj?x_#k7Za%XAWKS ztPlb9D{ndI1kJk2;Rw)WB<7!Jo;42_S4B{8o1y`F%FH$F0Yc~g2jGNm3+~}Gjjr|M zwIZ8yJl{9U^V&6>ti7D+74kYQJTP@2O<%M+_B;?@?1$A4@c@ITeL`r~NcP9D$TVq- z{`Bxt4ZHEhm{TkPdajS0`TdL!06)XyKD51N7al=5vCMO92Z$12)8jDjzaAh9-}cnV zv@l4Bc>m}bfS-H(jbgxw&0RgUk_!@S;q2;kM<$w5b3%@@Eo)#8IMJ~#Y8_YKdAJHY zZy1W!A79J*H7MqTZN|K0!7i`%u^9Qt%*S;fkK1dHrJl^4gruaQ}QCD4QmiA|wjbYtpU)&R|cdqTv3_*JhcoO7bQo7;tV5|?w= z`O^mb3%GK-d2u`$D=Z1Rg@I&6n`by<)!y*44xLnMW*wv|Inp6mLkkfh975#Jy*FzU z0NYQ#%u_kBz9B^HY5?JR6$A7lf6bcRqYxM$ucAB6^J4wkwk;rdZkvy1b|BS@BckH80lU8)7Sfg# zV60G_iq3Yb<~xcTZ>@Z5Bc zXf-E{x&=rbeT}dVK!jbW)C*jltRMZf2%0k>fFrNF-pO4bn=NaqBcF3B^?+{pFgCAr ztl#^~?ReaFP3X_PQ640X6&pwdvHJ}?@+P%E3Q2=o@6X`ziTmtG$oFae7TC8V51c&F z!B%48D{!8kz!@(X+Z3D6!}ON_c`CP=svu2icBdy0QyBB3>C}2_o$6zjzuC`O7a4g{ zX3d>ky~2@N*GycV{;n`iCFG4q*x`-kN$$Eg^X@S5Yo1q@o4rQqQ)&+=bzLLgCC)Y4 z3#)5VmfymhGR0q$9{Ee0Wy&4ih4Cw7k#z@T@GM^H)yuPU*`JdoIN^_Q?hBtA}ip*9J47#h;ZW?{^xZ{_c4e1<=yUewOmb5D~gs>29OQjul6MJ$g9yp$SzM@_3Y|TlDOn|v|rDW^3J_BwAYFc z4y^qI&SMC0!0*1RiI?zX@x9s+Ak^$Ep(LlM+;4ESn3!0h2RpOvm1(qUN&Bc%b49Hu z^mYEd?=^`>D)Q~gy%9OmdFx%MU~BLr2M;L72g}HV%mp4(Og|*x#r*A~tcSM4vAnU0Fs}x( zODa-Wim(fdzR$^vggj~PCX4Y|9-zv-Hdz^IH6j#T>h6Qz8X2wK-i28-<9I$Zz7$)~ zz3{U2(orOV1+-r!WIBjY#_LOY;*&Y{!#D%7TIPM?GlN%jOK7wPkjH=GJ({wjEIZn7 z_hlk2I@<_0QQ-3Z-FbfbGfw-slbTKM98>%O;QR)z7<#_X>|F3yf3tt${CkE1OYG}- z^~0CtzAPQn8A#t{Z-1p!tZ1w>E*FtapZ|2?+AUiQ<@FIVQ?C;v9S|Gpg21M`w;Q}a z)iaV7ayHWl{#bmB&scv8_R|HNSjaWr{<;c;pEr;TYS2pq{CVMSRUzmDGjvP1qTkqu zUi8hrX0)1aNtQ_9xENkk=Xa~qiE4e(aC>QeWOR;v3Vch{1%SC5V}{YAr{WKb7C}qyEA-HzIRSQ&Tk#H7<9FCmZ-wH zSsU`icg{Ec02>r2p;Imtd1gUY%y*J}30Dg&H1%gBTfeLW^TKd1MArkiUq3Anr7oH$ z(s0|t=WvuNR{xF>!sR=q`@VYoY|pf~8`;3wIdA9<3Cj|3xDoH_-T`59Eksr(E)+v=l}+m>DUIKXWqI9x3+5Vfhr8u&>;ZC1GN~KE z<`|P@jvG)tkg;XrnHqjoqc=fLC6zdjw|Az_5k8^56aG{x72kXn)L2H$@|-i2vX!u! zP}z=n51T-IO^cK9HZMjT!HJ*jR#GMeMuO$TFl1;3oz@0U3WoShp7;oGR*JlSf6igN zpvwBd#cOTfVLf@SZbKg0iSe%#fY|VgZhl{g<~)(S8S;lbdiyV+K!7fOHAA&-%Q^2+ zNAsGwhEcCGOgDDMv0+BX91W)%8T(0pMu)@ETA!LjIM4}G=V|Bsu+|T%&Yv{`)WMTu zfW@)G)4U!4i4w}^5;JhEPSA5__*B7T6W+LetUW}s=+uXe;5I-jMga-)u6$rF&jInP zdhkQ`dh-#z(t=mOatAMm+W>SP`S|i+ZdrHZ#d0XI*ixN>Ahlmws)01svnniNlM9Pb zlY@GhVk_w`I?4u_bK)QJ-!R)c~ZF1*5B=mQQRzhWhHM12fMN<-a8!3v@gV9w!6$sbnKVw zd9QEAY+qjxguiJBpiZt$Jyl`z%!L?CIme7tUjtPo%4=49Jy7KKI>6kfoZWeQ#NX5g zx<}g4&t3iwmme`G%`+sA@&SQhI)f; z$!)LUs%VG{+i8vg;>wG6@k+q;w{{*bxp-aY=Y*8Y$URSQ7b-XZ9j8~uTRe|1UEI`> z_uN8LN`4Sv^RC@ZN;720OQ55kP)r}SSOel>#|ti9qONNm;YT*arAoyN+od zrOezQD8IQY-X$fL^V^5MTw<7zciv;?SHEp< zAij0D=QEB~bK-7YvpkA+ygMY~#gMz>UkCL~S5flfO1Q1hVO-0$`n%%m9f<2nEnR1* zMx1pdK7NTS2`nWMu8|K`AUJ4o77~?k5 zVaG~Bp-0U6gq)-Cl7E-oy59Pc3Tc0H*xqUDSl_mT*VkX4pI3YmTBm;%ty`LD!sXC` z@Qi+ZR*3BMtY}>q9MvQrrS?P;)29h$()y%G)LQE=MB>+xjUNYnJ^=q%6>bcZ zQ^~YF(}!AY@BNFs9vT+$3AP)BUcJr}XWzLG=@9?(DBEX5N7BX1cY>rP(CHa0d zuwYpDJ&GKtD@f5isGkAyUp46=mLBdTM&c@0QU)D@>nO3tnw&8>3A0NUZx%zwwX|l& zHr-{9R5P4n-#IJ3i^Q1|HEu6jgR==+C_FSSO@eJb`Pgou1R(UhbfkYp|b_fVNO-?B7~wxK{-U}Vb&ti-Fmp1iAHyk1=!E) zYMIWb-vpXL09#{M@?`p)f%c|@rq;gt=_NKQd%ItB&SwM9eB*aB3n*sCPGL)phh5cA zS6U`LPv7Yd?wg(CEj!DoZKxUQ(qTJm1Va^)eDWw#pppd0HJ>aCNBFv`H5uKxR09$r zWJygjA!G<<$uG)UbICdt1-|KtMbM!-C-SJr7n#;1UkEJcJkXRs#MdKp>xL!Nl~QI} zPhhbMS4aPB*bp=BWmm#WC{=XSoqj-SusPg8C_T5_$&YLshKt?YLta_OMc9v|xE-BwlEN?wm_N3fE&gSe-6(Lmp5f!dGSlisj+20(^#iV|0%UKs*+DgyCou48fN;thy$Zea@>7Nu= zOAK#_ocx%~@E)Sg5eL#lc|ybkI$WGkK~WuSYmrA*^KImaqNe7cy%(HT2{7I`T_lDX z-ngtGx4F7&l_YJw(I#Rwj5VC#`;@P?b99dB7fDYl_man|nV7yEvW}-e zS@0o<5F;!ddi=NBO?06wTr-h5Pl}9bc4hWL#GnaXn_uotdFZQ46@_fXAgXVG8Z2O@ zBBS?jM*i`5*t0dJ8)3Nwu40+XMBj`k|1vG6d(s{dAY{_z;DmE5o7~SfGf!&K$wZ4K ze%yg@eW$FPCv2PDgUn;EKb-|E0tInxoieCkZ1}3_M|4ppW+)w3XW%?OLz0sTy3(4$ z{vCv;*UONZgm6F)*rim<&0F}6M96mAE*z*uog+M4ai-({BW%(+p*bEZd4z?R~z_# z6T@hUc#~3_di4$-aAKE;4+5TZ1>(2Ox;2n(>0UHA+NC5I%^^BO~ z?dN?jx8wh;W#QoYH|i%~QctzaL{N#i24iuv9rV0Yomor{rUB(00noh8Ety3v*lt1# z=0r0pj<+8@U7S?E#MY?y5VnrP)QH0va0LxO6T*9X)lxW(qzAQTzrJ97#-F5*qU27G zSD35_tcAFBix80e$h))EADG{Gd0~ zFg>kl_`4`?^aT>IaAQlX@GYmI{d-mTc-cftdxL_qZWu*>gMxX{6v_IZPmcI(D~LR{ zb=}AXon^G{EPUwl;Cy%Q1Dx9=zyh0qdXv#1Z6%cMW&FN8?Y}4O+!RLEq)Ovr-naAK z=a*5qR*Ozi#}wi%mpi4n7&vg@M9gR4S?ho7p-;?SIB=fAvN}lcK7OPU0c>R|T zZEbI;Uw1xc&U{4om;1DM&3>#!cN5wWO~5U)DL}Uoa$7NMx3SGk$3p~DMDxt?`>xRy zQm>i`lSF88{L%mluT0scc;M6=RCvL2j1llJX|PCZ;j=>>eyr~@ww|^w^G#^Thb1wk zO@X<=koFLIQlp$t?i#}dEA(?^gCY1)k|p}|KuXI^q-ttcX@o}-L6cExl!6oUmr?%r zr*K^)_+vPnM~?WCC4A3&{}W6X8YC3>O#x0pRBNJ50qrhSbKU=Ziifn2%1 zfyapWYa(kf+k>ZJ!{xlBG_>}|D?)7g6?!WzsM=p6kZAGP9ETcwyzbvKu`^Yn()8QK zl9`?ppt5H_Jb_4*BPiC_jf%E$aRUFAZYm^m9`8jYZUNt7@^{5FM(lS)y}PaYqc50g zOa5h0@RDDlCwhF%;n;z_GgsyDLoQy3D+&dDz$Ki^g(;60d zDFBIM^=s(^8GnmK)9!d=Ko&(9pw_V1;0+#8@P9pY&-L^b3uXCD;d*1pCCvZrEqGx_ z$j!@gILrW6tzx6zas#e%Ct~0)BWjkTO<7q2+*r$7e1=}jBLWNB#|7$CbwDBc435z9 zkmSFpmXjPPKC;CD&Ww>SwZv~`e6XDE1pRAXM9B5$QZ+nfbR36q;Jzd30xoWQy|C-U zKqV+zKWlMa;Ll`^Wx&VbdKB_DPvFyj0f!uj=X|f;ND)c%+c&g2z(Yit(ad`7QPLsS`f;v&z#@a%mshO45Te2e7d36E*orH&shQ?7;(zX>F|x2 zIgf!3BHyfQIg~x@2jP-hF&^uwpYS?odkRqr?S1f+!722)?<02C;}xBfy3x`E3x|VY zGos#96qnrrQhPkU>^*!mWXI+gAW<>zZO_1h9|4rXJg^-Z!c>%A(>FOLvhiI3*3tNQ zV<<)3r$#zQ`q>Nk)Wpnr|EAw%QozuMrL5pwZaLr(nF_;i-|LBv+XFzS{@9u;7a^+s|FrkkUsXom-Y6;Eu|YZn z=~lX1y1Nk+q*J6rKw3mZx|9?|N*bg@DM>*<8bn$_sXMpld+s^oj{6t9n7}&SNYL4Ejla+ChXKw za)NNs;MfBMce+`WyjnH-jf4c79Pns71g|2nVd-iY2A{GQ>A%tn_#TZIZFIL*sZ@Ki zPa6&tRokn}3sq3&IHR+wr~d<#LsbRYG%~|Lo)NTAU=~A*X7%)mf8QJV`ZM_zhh7%; zVVlA2oPZMF*%WjmvO_SXz#H+1NI#gm8N9<$qfBS#`~io_0W0Aw5Z!?R;hUFCfTAvQa1~9 zc5Uv)8cg}9rALyKo)ioyWpeT=mVWjsW~C;ex%B~nECmOntQg{b9yF~R2*oWBQ};db z1W=2=@@H<)?g3B0Hje{|^J2SHsaDSY;g@gMAUVw>VXgVe8>uNcOU~~4L=n1DfEz8f zCnd|X!M&KEY>3O~wBAG(HW0rtlIMOGDE%U=TG^-T+=GSGPJ3M6w?@nx-FgABU7lP6 z-xN)XqReUlYxj_1n{)6cxk~_tVh?cro&7whhfX2wz6|=cWM2#Ixn7q;dMnr)m~`$_ za-jhTrU1cFBBBVOTlqWKqPVE+Pw~ukKe-28{@Kvvy{2vRToe)hWBLt^d^2#wcV_Fb zke)HXbS7v96s5!)K`+O3lxe|jQO6KOn4_{Lh^auB+Z(#`!BR}WV7slkEz2ALc>)(e z*IJFI1HWe8`0d>JO7rE^mpg^;yj6I?+U7AJgH+SsVQ)%CQkJ#zq}Syx;4Qk;X)CYj zpSz5G@jJ+BeT;~+2*6Iy>WxFm6L}~A8ZSH5Yl-A>#2#p9sj|GTQUZ$c%~Zm|hLv47 z{_YbZDWZN`%AKJTs4kYawhZuxkB zufu7yG|AuU+2(2lyGY01?Fv!<-RuLDN6-``U7?9fod}H!Tf}*^li&6Fy5yt8+&IWy zEh7QAnOgf=z|Q%T(yh=T$@_*{)Ps?#uhwOn7lcK92}%V{b^|F)faBt3Zhmkmh16pw zU2~>{f3-lNXaf&|*P;{9)X$HefXa%KKPBK3z+!!uVtJcC=c^X;a1qV>?C(=&Z?6RY zd6Y8o)L~!jId-^*GGp36bQSwUfhJv9mh_lctgR#_H8$Y~Mv}*)3hVx}8E`Hk$;fQN z@i+@`kbpXeia&&+{IM#tzt5(ryZ_kU+`;`hFRObXrKT12=nOzNNsSCW`mp{V^;VzK z5OFbRq^L4JUlCF9cM{`V=dWDStuW%T|G;PYeu9`FWJ8@-&}rD!q8*v$j}y2NDC)V4 zvH5MOLydf9L|5j98EL&Q(%u! z%KHWakZVCEJy1spxH#b3fK)9Ju>yxc56GephWI)%_f&bQ7(V_^2Z0m~OH9cZ=VAnS z2(h97iJ%P|s564oKw0hzkUt&IpYFQ5^OQ{!=^ACbPGUZc*+%}UHlID}LlhHZ{~IeJ^!(s46KXnebqYX`_!@+(5Sd}nA1Zl)w*x;z#Gb?sOy#kr<QVGz-gwGO8lvL=G~8!xM>%CiAymA8M~IS#3g=7Ebp;F3U&=a^wkMPvq?vY6j=2* zb(fix-9JA)Sl4!4wF7m;UHVF5M?AF;u&udy$?f3k<3C{*@S5)6YL0zyA>Fo8=*#By zUE62U-v{HgHPrzm7~fLxW6V{fWM6~B!9iY(#hqy{mF!fsv{Bix2CSZ!nUB@KIRKSJ zn61$jTIAss+#hR&aFGc(iYySN0BcUvVW^^&ZSBJRco0El^ z9i61r_yzfh@V;P}x994-qFPAxX046gZG}3}COVX>!C5i%Qw+f>`6%{9P%7}O0EF*L zK?X!GN4bsSnYU(YY$N9`TYP``)zO`KHvaE*s!d{Jdo2b-uyP-0LHqX>w>7X&ap5#R zQT}{z4I_O zn_|zYcv_><$>r5GNtnHlRi564XDZYee7&J#Ow8vT->C9iv{mx+gA<+YMQu>coZ^`H z{t!WfPQ6v2$Bmf8pPDH|sStn|j$kG1ZJ6 zpvgOI-5Rf5dKDLcLMc0yaFtU<>>R7g9b(==lXLyK?8j9#G^y6UBNC9zNTca}JHETC<`|Jpd z-{#@4`(9S6@GfUSDV9_Di=g3D<`X%-YedV?4K^U$fh(~HFNw}Q({ES{%*1?NwnW{u z36@vca)%CTsW%irQINw0PE$w8fW-yb&0!F~6|G zVc}8n^???iVDP5-R7;(Y8Gq7H2I(ik zDyqV1HhW!Pq!nJv4j(rK{NX%w&`fNd9jCHOWvSc4Nf=?POln1r0aw$6s48}iu&~-S zm+hwx#hNc~sS1tNq{c$`&6~kWY805Fx#ddbzv9fZ<6Q#ecoV(cP!rp6eH=%x0+?#| zb$`w?rPz2eIY-ONBaL>jAHKgeioL%>la>G^E@X%iPH(lMbQ3LAl{etG-jAs&&$W*f z*-}B2bmBfJ1cxx~vbNoX!{D5AI4mS(*Gd3(3=^DXRFVPwpyi@o$>~n}0VxcT>9^{% zd5)KPs}URDYR=E#+f&#yuWRH=&ZZad%{B6^kK`poh9OI+rm49z^ay1bslo(q+`2{? zs2^TjLWn4)PkI90dUto>Dk6|q2TZ%4H4r+i4m}^KjGKO(wIN^P$a1XG*FQwryf2Wy zJuCq$q_yWxl>&M=(gx1HFF_#YTH^IM;(d1H3n?d1g#!uS9+qv4Vgh)M0e?;oH1(fe zXh{ymU6ULsw41R5)5L=r`{ds3=6tNQ$t0wyADEaegQ)%kcnlIW=ND)%cdP5Oir|NH zo4#e;Bw-3<47a^vZz*b&mPe)q-cN)WV9a z@|_IWip&7jTQ#~_D$r*Rb$YyFRZF8P%FUa78+sLT4xsM(yIsI<+n9v^{@Hn(_d>|& z`f~S|c1XJ~rt20d+rj~H)1)R}Y{_plUvAx-G#Av~G=g$_m_+ky*%pJCgV((I$6sl? zSBv@WWFC})r2`=Z*;quo#VMW0&`FLR!O8O@ncXNj-eQv;n-i9@T(ouM8A>=@5w53o zS(O1f$y0Vzs;-38Fdwc|I_h zKoa`+fU{UNwL5@Bm2;E8_LOW5;tlkXw&s;22{$H?`MC14_OxgGv>fd1A(C;8C5%h0 zNNG(OINn=ae59d$2eKiN>bwSKMje9xQGNcm-6#}@p@@mOb{b0nr$o#wqqq}ZZ3scdzjS1Z`{FPcC`D1V}?14=(^&hzW@ zMA)NLFNE)?0J%L&e z^ylY}#h^W@m9AJdBylZPM(qv+KwaB9J9#T9`TO26rm3Qjjy~V+ljxRyk=&V$M~Wsr zeclKTY_G``8oz>iowQS|qb=xUL1VK)>ISRQd3M|i{;OpXjYGopns?l7oEnd=R-bC8 zaOjuH5>$CIBaIKS^#fk>0P%i8xbV*@%-oyvwX4-P{f(&Oq1O+Tpx2ci)sFi%GJCA_ z5$Jc_2M2-}1A{U>C4L;#4zOtXZX7TfXo1{Yqf^?6oG>VPEu7^`GQ;jaufgB=<-FS^ z2fLs5{EK2ubn*A2bNkQ*feWb$W^dnd-xjAzQ%a6k#Ku5FRp6y!;U+=rk_|hd_cw$^ zGlVV(iEDzNkqfCkVW>eeu;M&eANSnL@Hf{(qg6|CG`=a*Qc`HjMr1 z*lb!Yw^Ew0ytuJ8w_pzRJ?VM#@&gJ%X;r zlLd^bQ0_<@RpYxZ5`u3OtL8`h$Kgg*NN25+1$0~rw95+w+=1>}7od4;k@CCIdK?x{ z68S6PQDWSBfEIE&yUp%tSCQwlwfx({qJvN)6NOgNxqgFVnYPhRY3VUTSe1FzZavoHV6Pgy`bA zb2(oq(gK;tVDc5HTvOvZ*FU2SS^Dj{kwk&xj<_${Emst;RTQs{Yg1L|MwKYJq4ZR@ z@Rz8m>hGgICPD}2pvnc6m1pBMOf^BbYkW9HTgCW2823MNQHlW^VFTK_LH3nfr?YOC zkCsZFhaGK%w+DkZ5S6}ABv^d30+Di)g#V$i$B2|{i8^ImnQjj=`BQfD2Ni}-g1BF~ zSc&_+k0E;}{g7{S5SGti%p0W=$Kb@*e~++WnqA5o27{Ly@eAw}6N@%n@OAaQ2s%Nl zyNi0vXwm9?@vZKa5-)x5#3A#HGMFQn<$({#lG&DHKVjIfGc}!?JCXF!!#U78F}|3V zi8t<+cSz;*6q0fJZ;a)0TjB4_VZC#E5Xcj9F?nb~D}|fRi8)b$I5E+hZuQymAvkjg zW~G9Qvmlt1CPc-n53!NUSu&`?>_dxd=mWce&ROgfS^k|kdMx9D#_zLE;pczCAIyb8 z0F!JnYSVF~H8kKP$fi)D$_siri|+}&c)ap^F8qZMj~BC-ZK~qd%QvQhtdJu5Z0Db3<|J?wQXj;~*aA#Is- znnW^TP?MCyKG=R0&i8j8qGDIGamMILx<+(OuLO-v>s>4QoA&#`3}nqV^cX$mnJ!(D zIKKz8v8;O9-`=f16d%q;-EHA>b4OEnO%<=ihoy$E@J2OE(CLzoJHDANFZf#eP1|2r zlg5;@%^s*!;uD93`&qJvrMQzcO5%iupQCnKm(AZBl{hLGm1LP9L%U7Nf2#UZQq=W3 zuCsR0JOcg&_YK2x(buIw={r$*?}o9=Y5ub(BxKF`a#w55JGZ`M^cURIA8L`4m*Yb_ zV!Wv>iCV19(AYJi1MV4P`l$j%zC3C`_cZsmm%r`J`_`$E^t~9{krGvRuh?@wqDL1Z zqt!VSSroBv8`~%1-khZ+1t&Ty9&g;+GJBSh7(3TB_Jq9IgKZ#$ZSf{g5VWMu$2;9cFGcCwa1Xp7l%$r6TU@P-t@bl~Lv;HX978`>&e6z&S zI^a9zzL52^YJw#_;dJ6AOxTRRk^hhV05LWS8ibJoOgijZ*(gNwTsvMFiI(qgK`LTh zBBSORBzBNKYP7(e0Bt?76*jju;XY%VQ58zYBZ7DP1|Dolhoe&3QETpjl-KS|hwO(N zUfwbl)UHmLzcuc;y1mfztnS?od$M{Mk?*1@-9@OpQVulJ%`*b*Av zjgOiu0H$A~we}vdm=y|RvRl(5-b(@Ew}-yGo#0vNJX%Gi59mDl!BSP?LwoP~$^EuZ zWsJI;^UXpFOS1y>xX_EUFCB`hM_N;{!};OpV%8upxrf{eVz6r@H}mCWlj&vO`*fCS zPBoKOE-Btyqz4DV^5qX-8UsD(rD*8HQSjrI?v1)knK<1|=RlYI``Y(6=G-AZZZ7%7 z01MJpQH*?J7?nfM@1<gSi{cdQ%mn>Og5=%k2_cD^x3Y%VV1zF3wElvFzdt2klz z%NBk1AFlDqG7XoX(RXGtuoi0FbI+w<*WGOa7eU!7v#DlE$^DbnKZPjV*%vH6Mse92Zn{aJKkWo`>H@4J%NL*dXjqmSMF#`6aAY~41H zg3IiI#hbObZ+z{}bmb>sT{8Tmiz8X@&hYGH!z6kA%N4B%jNSGbknH`Sef3-!Ynsfd1xA_m0mQu~C`c&-EBG2QS zH4kX^SD)%mYm6u~x@A1?$(XFDvWSI*_16qronyTk?T^DbovVWxClR)$_>Y-A1NPd? zz4@r__C87|P^fY_*~3y!L<3i$zgIi6oqvvGSNeuWjqO?-~REhn)P`aSPYda6=YflXy&9W`vJe#9K6nap-gNVVyZ#VrU;ZG92rGHyYg$ zd#2FAQlwEY`%BSLVzzrW*yL>_u0xkwe{5*d7>wcyPms2bj`&nI(Y6#fm-yFCoyEp$ zlf&>w+$`=4jhlNC_0XfUnm4!#{GkF*!`eEq1IbSnNg$2|7Y)2`O#il%P$uwui9>+~ z(w1u0dC@zEfiXim7uG~Ifkvjyni9X~OSQRAIWzS`hkpD~@e5BH9#rw)0CE8vSf1{- z)4aB3$OL6L4SxOmhm-2pUNuHIgfnUHMB3_gToHcC!J7|hdG=+jG?7ACiLXC{M|S;_ zQAgmBS=_>T0?sDujkHXXlq8nl!~5^vRd%4-ZJ9mPq>3pSufJ3_zX(EZj_fzf5|NG_ zjMCUC!sHxwhHi(iMt|tM$z6-yf5z_~X=^YdiS978USX9po$RwCnbTKWc$$&%>$Z*` ze3?MjoD%D~)a$I}DTR>J;0CN4Qj1<9I| znl0SA(ZazpJ+s&y5=LmkBAWa#rEp?&=)gA$rhT$3$le4%Aftb`j-7^g`F}iOkbM-6Ew_a9C}XvU z3w6MY$0+LO5n*J5m_&Il-`?b_71XBo%mJC6H_YVWtRBB&6zYI8P=SjI#;=c^$}=YB^}orTW_FJjM*(UDxIZ zL%|xaE9xg8miCbU9mwFJL5fa40csmZdZSxtMAH89gYX;hK74<14rY7-JGK2OkiVSw zowm#ra!UHs6Sy-=)1c7zX^6#}?N_ke^ah0j_#QVnjb!Q0KTgkR0w+Z=CU z8N8q3OMal}&*?=nwmrT4Uw03ce8Ad}5U_y3_Ego&eZolva*S+M-c09K5Uwhqs4^=j z(Z(U&7U6nL1;Ed4$5n`Z*cXWgupoQq3hAvMATxn0He5H%3cybgz#^>6^CNA^!vPkz z!CrJCNgKaihKHL>_BQ%RdkJvyp+WQ7ofrEu4R8d~%AacE*HR==-)Ueny%aLLw4dKr zW!{)YEKiC>nhCj=m&@3YeNh7G3BTh<^2lDmBx`ND&@5U5NWjWcK#BYjH6_Itd&lS1 zQa+n0Wt=5CDi^14e@(@+&VMcaFU%oH0;7PS&xAWLHUxwDscZ)XXj)+BUaF?3Mvt`O zS5*KbqJ-)2|CNW?iGe&!PcTv_G4aNFF$MJ@rSoerAE1(Y_)g$(>-$nuLo3YKm>pol z$@8ge9GNwHl^m3Q5VjtEW<@?Xlm^)eZu16w$W`^jJOMoJ;TNgIpojLLTXtF(wCO}S z5^ED@l>)Nr@9WRGO%FSMSEEao+u>b>rQM{n!nikHqToC(AIq#ro?`WkmzZA{T*N)erv9Fqe_B=)#)+*}?JxG1yttqEt=L9JmvN9ri}4AXBfM{GmJdoMe5 z_yskE?)RyBR`k)`;7njEiq$Wi_g3n~$V%DAS55td&-6*IjQjHLDhq z{mtdDl9rafe{s$6;MXt1ElU9X4SopE(0?gBbxlEeFyEwGaw9q>rrf6zYIuaZFlSRV z$0nE6`tszhgoTBz`dc-BVId**`ks0hQG$tlBM(9}pSMk-8CuL=tcxY3kT3N5_06?& zq5HDzxy2Dl(sb^m7^TeL+JcO$;*jK+c;Wp;po1BcBt+qUDcpSRU4^dyvS}gw#7kFn zS_jGW0pLl0EWX)$qa5=aD~;=u5B5My;OvILk3Eky3hy)ZgBrHy^?PawH`(>yH01{Y ziNXYCtl6mMMW(Vd_vZRvd{Tlm@(`pg+_UoDjp!$>mWHuJMF>dq=$GlGTgEfm;GxO$ zy2`0l|M$4uLi6dQ>RsBEV5Np5L)FhRH=rnKwVUkcX0`axRQ>LKvFSmc)o$OJJ3|p+ zjEvX;tB!{Tf4(G+(L@-@!JlBqzow|Z3==qo-i{K3yRrJlAeZUeVpByjF^#CO6g)C& z1;u|Y?9?Z=k(MZ;`V`GR$nQ6KKz@;@tj&aoE9zC)Z@LvWSLUTF+^GL-*#sk2MBwD; z=xLP;9bUcp6z^&`&u2FIfB!Wf3(Z1UJ*}%sMNJU=FN+@A`Ax_VMEmk5S`MBX7uxvk z_}nsbbhSkK(0V-P;D|thfo8fut}2+joom=&$*G=-zgyE&rBZVKBrN3#dys;ONoJPV zM%)4zIz8WAw!=8xar^pCO-aDvhZ%yV2jepyD62>mG5)PhjPNTaez$p1d^&LhB>|*? zWep0k*Ma-(B{@G<3fLJ9lekABQ|t&a5~^I_Fe)Ga0$<}j(@UX;-Ryz6JzfeOj}0AY zhyg&zt3oPCltk8^FW#Hc7Uyp&_UGdv$IPiW21iI>gho6Hkt#keuHHuAzAGt5?qlf9 zk-BDQ?tfok&gcPZQ6)i9boDf3xunJvi4u8wsfXkM1S2V3`=Gw+SLO}qq&ZkB8wFTH z^PZ5K_tkjG9m97K?}f^5^hyygP1RdG>AHzLHRlzaQ^$E>7;Eqn^y2>0$Rgq;CMzFq z37^e;+TBw}U~p^;JLMi$-uXT_DJk-GagiZ4HFdjq3v`xdIrFU#=586h){#RPR&9HN zj8_C*OK;G*H}vv|;ivDErd;Wpu^8YV=-f)^@O=QSBsb0IU3zG0H4ts}oBYAQy=9a# z9Nq<4y@)e@4316{sTU6gfU~;R=`fU`iFZ*pf~>fNMMTdC^-G#UucR}1jhek2fr+Dl zM_0wcWInX*WaVN$ox!1hO;=YJ442=370`;OhxZ!oNh*x~_g?hjvKkr*@pk-<@vO+3 zInvRBO)DGQ+S*!CQPDXv^7-@U%n0Sd6ejdr?hBQ^6Y>oilci^DuT{^hT)?$17Ql=0 zBSBT!;>~av5~-b=X2=m`T++o(QA}}I{rnP*0cZ1(Q2bbhF&|G&O@fsUQ%(`( z+xkjM%c;9JV2aH*ksz@Ec6>;I7P8@)HM%|Urt>NYgb8bFH5cpfZ;4`~sWH|-h=L4s z{CDSdjlCMKptJRc;|Y6Xtv0XMr&KxmZk7ywDF{CMy)>*hHa1os0ZHKR-+Lab0#o3S zGrdJ45*qm>Qy$|#`$WKX3{`GON*6IBGD?6DH3K2l7X!zyF4S!{!ZCPFzUD5_k68_K zVg@xAXD3A=tr@H}6K4kMnLH8%!kDe|#<^ zv?~)3E6L{|yRftM-TGD|jSEX5I|2zvA-xIj|Ne3s_4x4$gml|y(6EZ=LcLGXC`5{q zemhiXXlN7HN!J(d9B5!PDWo4Xd#+pyNfJ#G3bl~mB^80PSZvgxnln7EbfM7}nWF*B zX-6cY0n51Sm0}o+g<`2U^dFu&sA1)Czvan2;;}V<^88Kz(qTQ-e3LIts>+r8tA{sq z--gkfr+keGvv7<9Yq*NBCQo||EUY3JA0z?suc`n$5**QY^53V$<6X9Fe=t$EW zmrGBK7L_`bj1B{bE(75&qO=Q|y7$9}B-5Ze8Lw zd$_m6A9E<$46d&(IhLPRy}|sOL$+dT!aQq@G|Q&^Wby#%TumZ=07GMbKH_p6l!0xTq#<1kh)dJ z#kw=r_zf{lRA2P$8x;A>5>*Z?8x2TWNKsWxXd$R@&lb1P*SH8vAX<49U)fBnC#v0vst!aKc?Ewk9 z&S|gDKG(~ks#Qwc2P$Dt!T_^P#35sw33+O{giCFVps+;ImqG>18&m~O9ZD`JWfAgeo#~?(xj6b#_*6T zTz?wIe)jk54C!&QPNv1GPJ*W4yJ8y-IXN|5DX+Rfl9Yq#)&{jQ2VHhvX7TlmlqczE z949U8Xe@{w<l_a>Z2Zl8Fs+m^h-Ou8WIDSvkptjXNJur4Z z!)+d&YcI59{`bJ{zXx!eiO;qZ!xp{{o>nvlM_X(@upZMIi0=Olo6f_RaAM3DyJH+r z!LJs6Q+O3L1}jN0A?W9@qTtDgOb9#cHj+_u_|?NXz;l8)s@fWA&Qvq` zFPuA1HsCG%JPx6~*CRh&;C|vS;Ck#c;W8okyHO3|w1wwS4^~EW2U3OncTRp;b0rJt zuNRsOzTIx&d3kH;D6YqIbzfTYWd7*2Ny#;7TEXjlYkX1G4Q}!+cYWa=n#E2me%K%U z>ui)Lvc_{`j6KBZOz2gDJX{x7&W*~{2|is(lb;7qy%SIcE989iOs*UaMpyIUOA`Pzs_rq{HJo8d!23VT^+DfE-xgOp2UqWC`P_B-1PH z&R@05AWc313=a=Ag}dov$oAO4c8)COs0+0reBEtq@`DNPmE3arI?aI_Xu<*+gXp}x zyzA(soOhWKaf$VPCVdCP8_|fd_m;*!n^O`-B`YdL{GP|eJAWPVb{9JyGb`OGwAW#n zs9H3z>^V_7m|yVhYX{eNrlnuE1)NV=&;0^qz6w7wv^+aKu>U2{H{~yZ)pIr3$=bjD z`!o81>(_VN3zf5vCZxI;2z&5mt$j@2zycE7EU`6aS&Dx?2b%oRayiWanG@P;_%yF* zFVIt41e&xF!fs=f-yVjL;|-nVWEFVTqqzR{6lpg*SJ*l6SuhU1BKT-n86Ri;i0rKG zM)T6pTmR`Ps{O%$*2})RfYW`{_0L%m&+Z^>dVcqaK4R?V477<>OMSxioY&^V2UDD^ zltbzcnWj(%-N!)CbGCLEPNS%6H~lGGXU>A~8AXz@C9lqpkP+dR)wo3+Ma8JJaIL%- zxL8OcCJP%|-`(2R5a80J*X>j;b8j3$;m&vsu>7Eei6IS@GeHk$bn{gx}Q*WcUU_iSfw|WqOmv zFDXwj@hJ0w17QL&QDs8LKc->8Mvgx@PMLLw^mwV}6R1MLc>yUYc2K9xe!uIN5&W}2 zRXx{H%L{q${#CL{POAI+*(;`CI7bX`xxzKtE9>1>F7W790FXgifeV1U5W8v&SD&>@ z1pBQivm{?#ES9m-F&AvpL-dd7K_DH;R_yuuY_wI=>7DZ#z3TOb=!;lw8C;{M5$^5Z zBr_~r6GiDHr~}pxm5zUmQ7YX@m%A#kx9c@~@4*{l(Sq;YVaaf2X=m?wUi&vM^s;OA z3p>B}N9Ub$F?_C&uZf_wops;~vW83JLachQTVxoQl^f0NN+U(PqurH&%RfG~CUjC> z#G$z|6?cWwS3EDSXLT4_l7zp%ED>5%dG$AO_zW^{krXiO^T&ZVt;@3hE~Hrq zzcxhub-h9M)o$?0%u0)rb=j>D8Lt73)o$nWuajH>J#R4BM$8g8C(*OVRhFOPrNx6k zt3mze*w5ftgfqPPz8osB$P(;>@mNEJqH2vL6T;JWYqA0na&_S^^3>h*G*p=#nM`S4 zzXFX(c_ALqY`UOafE^!DFx9989b&zjpui^iV~f!j?5U!@+vMXVXD4kQ`%7|={EWvoFUIsl^^L82YxZ|Bd9;0Vmn2S?KFKTLA9 z^`em$=ioqvq|nk!284nAei0NM_CyZjV${Cc{mMj{)TwhGnbt40E%ALsyK@u*jc#^_ zmF_DBZQEzjnZggTZ|#W_ik~M~n55xZX)xEit&x7Z+I=+>1pkCPnh~emWR{5Gk?5x> zH{0nSQ5G{4T4kSdh&_6T9!&HH8*)x$a#-KMoxIH?g@D+mIx4K9Dq5EhK9;(vM!>y?}}e*o4cV zkua{Cr*)XQtg-D$_nv~nH?613PpE|M;#+~m9EPKQ9F zhlcJ1Lu#q8kU%4~%(SjlJ-NVpuH+7)^=!B0V?oK$$C^M86CmrnvH(a&CE>>n-aBvZ zmcED)f^hoAOOj?)RX^~OwGJ&%dO}&w0F)V%&v%cC>{kmdn!P@TsC_;h&;9VS%X_hHK3> z$I%@^NbjUo>tjUE`!%$(6aLTr`7zb*YYrp6FP9Vo=%v!q~Ntnoc#P2M^Be!_eZ;B!om7y zdGBb@k_X0=3+=1>q~+s(#_fNtgSf`v7{|-=pgV8#TNQy-*>>_$2!livIF|`BEb`!X zHCA-%-|uty#<$9BS~I9A&WJn+RNBNVvIp8DRoHNCS2{VVBzQ0|@esYub+3pg8c3$1 zl*)rPTfY?GZ;Pl#J1@F@y{2i_kbDF2qRt^Q^v}6yfcQ15g$0}j1uxsxduCQTZ*1=* zWJ$6QzPrgnG3~{D--m&X6o#1_t}6Xq`RjF5+O-5A_&$(NOo>tcZpt&=n%Sp&va&FlT}*N zjGRu&N}E|7s}aDE+SLdz51wmz)I~hMX;?^)z-0601+8V}+P1`d%c(u&EaPJr2HIu* zxWJ3Qe!sR2!AobeZqH*pl8oHvBej&BV$^DQRNfx0mVC{dlzc(6u8pU^H-rWTFj?wo zY5tzaf&g^~8P7l_>v*>Ss{Nnh8eZp|{VG z+Em_ziG)*MKtPbpW0laWL`Yi~2JLlijyc6XxS1H=KTxN_g^rher^YjV> z&D1By)Pm(fmx0HsiIICgI|WlpqZ!Jzl+CKcCUk#$I5p@bxToAzNwFoY8CSc9!_<9u z;ZzyueRq(zd^~8M$!{NSnBOE@xlqv_AZ__~#$|Utsp~{$M>cMJZ8_x$%j1(G?;j6m zYJL)%wbA8M`XG4C^gd@*EIc*E6ZPjiw8y~`3~ z@p8ssRl86(=c6yY_jRH8Q){%DAoy2SB|f_N@eE1OurSSPM5vmm>Lyh$Kc$aQmM@6E zC=&l|Hv9vah+HAx=v1C+I@{G^P=|7Qb%i{;?QV60Fvlj1pw#^W!h-u3(M3;ZI+LpLnXV1@!mV5!X)fBx>6o8AcQA4LJf#|c^D>KKw)TOLvSwD5 z-;?{Z`D~oV6@L`lZwwMBG-))yZJ;6l@oqZ8O(Faa;!6G}r_#Z%w>s&+t5(xPh(kYP zVi`p`c9Ws9zk|<>C?_lG&;P?dTyW5r{E_M*yytyD5KB5i7m*Gr-ebM zKdg6sHR9?O*`59!LjlniTheaW%VF%FU$@>!++ zZamulA z)eoCJ@n+@(1Wp4c49K}H@E;Q?+jL^ljqSGCymOs1ED`oheZE$CO}{8>vMT1m*>D6# zm+BMdr0Hr4qbKdnpMN~Jeq*p2F}LjN`it!^;q@}g+}fy5*$KZYI(oJ>gC+?LhZzyH zip@QJHKJ}d@vY;2 zc7#Q!oKvb$3>dNNbMPeO?n@8%J;fL^Wg5iB#@5-QQZ^$W)RccK^zF%(kWY%(%k3XO zDroKLrY&lcJ%Z8vH4E!LKk^r!{t#Bi!J7CXkHbBqO!C8vx-au)Q)y6e$Re+MK46%e z#(a$Q$L6Nlni;!_zYO`~u0ceqyLzjIH6NgU{Sn+R{x|W? z(DN8n5XQ>9v9ruDtrAX|xu6yKQE|LMTuSdeFEPg6M=T*JMbZ==d zV>Kc*X<$HAN&M8!{vpK~{bHL&PBFnf3FT>d1%=7K_`mtI-ifAJ)My{%IC8Hhb@(<{ z^jQ}z9@0G+GI3GkwJUTlQ<_hZOw75Zo!I7n`dt1g<j68iUqk!OBgv2k^} zTs0vPElRby)0~K|Vm`{k`-!1No3!`MCqkat8GgI+^&M9FjqtwlaJct2*R7Sywji9{s`bl=;O=Eh!c%9Ewsl0fyW$tc8)@t$Ew{;;5vX zUs{?RZ#r>_RebtO%8bZH-M|<5VIv$Nfhq8{^M#^Yg}PHT2fri>(`CeNlmok3;U^!} z=KPm`R(+asn%BEu46}c6P~8z7(!hT)H0;X<4$8WL2R@`?k*=nyw6Pqug>A9*jt^-E zaf_I)HRo5U(I$HH#&XdKRma)X`VC_id3?I3z3Km(qO_t{W}{ostLy!XUXPqb!RGyDL%*UW`O5n$!l}f)I0YSt3(Lg=&u{h-F~nMj&PIUL zqG*5U#;8aD%KeU6oeQ^YZ<5f)n{EUhj}9JH&Y$kh-kutWt`{mxsQr4F{REgHMR%*- zZ{BuzcRk3`Fv_9{H}Kx{8g|p)wRJBPVFV+GS3&dNuN52W8~Q;Wn)&%N(-_Jg`PhP& z;=~qY1^}*NC=-)dM25A_TST_hnfW5Tx(vwevDojpikeejxnermZV>*AJ=!8PQg2V# zb+!)7c+l9G(9vMOmShb1c$JE{PkwT;R&IXbWAC0d0r1EZ#)kMrm!thu;XdcVhxSsz z$KRq;52klhvdZO|5bzOuMFV4XZC&GC&SFLi-iH0|C(7PGK5Soy-S6!Dc=Rb}wlJY% zSaI&p1Ds|L>GknKHR6=#FV*nBGYUjmh+>;OHQ*Y4_3z_{c0#l%*2#~jE~E;gs`yL@ zLNudt5gD{YFQJY^J>~*PMCUtQ2KD|C{`Ya__KnRKS60-apWTbnRd22`-`E^%b4!Fb zpa1$u4HxbKYO(Ww(LANU{rmV^la#r!UAE7<@s@R3H(s+UDRZ-|F|@q2!tv_W^AxwYzi^F;7Aa!SJK1)R`SyGOlv~ zvqiVgjsyTIzJ2GI&Jq`anfDu1*V^^vggz_Mp`!xQ85I?k54vWw_`BGO%F2cRfeSQ* zbo*stl!DK?*M2nCI-cx7+FzvBIfDufFXWtnTF626AVLh|=4TK>FQeHN7LAo^>3$X_ z^To#icVrY985wW|wvrvghtfS8b|BY7Qlsu>#fe`7%w&5GQK)61=%ev21us~WJL^VF zXU4#hXy5^F`57f~zOaJLkA;<+X&S|;;G@i!?;Ilw_5r$Z6~@5C zyjS|-wLK%_%A59J+d25FY_7Kdd}*}o2#5J-{XIia!iksNS@XXwxAc86ncrzvO9Q|9 zI~(bf%t58jp&>lLN}*cd1FwpdGmV%|P~k1DtVBY^%9k2~B>f8jnz*R`Q-!d9L%0QM{GGHGCl8QCID4U0iu~Q6+?>r|&y4#jTF=w

Wl?{%A@kB(>-ER^$Q zqHJJ!)&C4o-hRk#)j*IF5ES&IARX&om%(eeAVc~RSDssPU^k{*@bZ1*SXClma`SW5 z%xyU^0k$~-42{x@_F^<&$KM~!qL(%upDpt%>s!F~XlWUmw)6OT7oU*6BW(DWdZ9^s zA!2LwBdIW#y5X~03|xxr2EtdAUe zgQq{pGk;FS@*v-=rHhARE39)WICN-X`Mz0gbPotN;K2 literal 0 HcmV?d00001 From afaf5f3f0be46ece4328fdf1d36d60a078a4bcb7 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Tue, 16 Oct 2018 12:15:05 -0700 Subject: [PATCH 60/71] Fix typos and grammer, consistency in lingo, and let action clients generate goal IDs as UUIDs --- articles/actions.md | 175 ++++++++++++++------------- img/actions/interaction_overview.png | Bin 10658 -> 10532 bytes 2 files changed, 88 insertions(+), 87 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 53895d1d3..90a3e97e1 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -24,17 +24,17 @@ Original Author: {{ page.author }} There are three forms of communication in ROS: topics, services, and actions. Topic publishers broadcast to multiple subscribers, but communication is one-way. Service clients send a request to a service server and get a response, but there is no information about the progress. -Similar to services, actions clients ask an action server reach some end state and will get a response. -Unlike services, while the action is being peformed the action server sends progress updates to the client. +Similar to services, actions clients send a request to an action server in order to achieve some goal and will get a result. +Unlike services, while the action is being peformed an action server sends progress feedback to the client. Actions are useful when a response may take a significant length of time. -They allow a client to track the progress of a request, get the final outcome, and optionally cancel the request it before it completes. +They allow a client to track the progress of a request, get the final outcome, and optionally cancel the request before it completes. This document defines requirements for actions, how they are specified in the ROS Message IDL, and how they are communicated by the middleware. ## Entities Involved in Actions -There are two entities involved in actions: an action server and an action client. +There are two entities involved in actions: an **action server** and an **action client**. ### Action Server @@ -42,51 +42,55 @@ An action server provides an action. Like topics and services, an action server has a name and a type. There is only one server per name. -It is responsible for +It is responsible for: -* advertising the action to other ROS entities -* accepting or rejecting requests from one or more action clients -* executing the action when a request is received and accepted -* optionally providing feedback about the progress of all executing actions -* optionally handling requests to cancel an action -* sending the result of the action, including whether it succeed, failed, or was cancelled, to the client when the action completes +- advertising the action to other ROS entities +- accepting or rejecting goals from one or more action clients +- executing the action when a goal is received and accepted +- optionally providing feedback about the progress of all executing actions +- optionally handling requests to cancel one or more actions +- sending the result of an action, including whether it succeed, failed, or was canceled, to the client when the action completes ### Action Client -An action client requests an action to be performed and monitors its progress. -There may be multiple clients per server; however, it is up to the server to decide how requests from multiple clients will be handled. +An action client sends a goal (an action to be performed) and monitors its progress. +There may be multiple clients per server; however, it is up to the server to decide how goals from multiple clients will be handled. -It is responsible for +It is responsible for: -* making a request to the action server -* optionally monitoring the feedback from the action server -* optionally requesting that the action server cancel the action execution -* optionally checking the result of the action received from the action server +- sending a goal to the action server +- optionally monitoring the feedback for a goal from the action server +- optionally monitoring the status for a goal from the action server +- optionally requesting that the action server cancel an active goal +- optionally checking the result for a goal received from the action server ## Differences between ROS 1 and ROS 2 actions ### First Class Support -In ROS 1, actions are implemented as a separate library `actionlib` which is built on top of the client libraries. -This was done to avoid increasing the work required to create a client library in a new language, but actions turned out to be very important to packages like the navigation stack[1](#separatelib). -In ROS 2 actions will be included in the client library implementations. -The work of writing a client library in a new language will be reduced by creating a common implmentation in C. + +In ROS 1, actions are implemented as a separate library, [actionlib](http://wiki.ros.org/actionlib) that is built on top of the client libraries. +This was done to avoid increasing the work required to create a client library in a new language, but actions turned out to be very important to packages like the [Navigation Stack](http://wiki.ros.org/navigation) and [MoveIt!](https://moveit.ros.org/)[1](#separatelib). + +In ROS 2, actions will be included in the client library implementations. +The work of writing a client library in a new language will be reduced by creating a common implementation in C. ### Services used for Actions -In ROS 1 actions were implemented using a set of topics under a namespace taken from the action name. -ROS 1 Services were not used because they are inherently synchronous, and actions need to be asynchronous. +In ROS 1, actions were implemented using a set of topics under a namespace taken from the action name. +ROS 1 services were not used because they are inherently synchronous and actions need to be asynchronous. Actions also needed to send status/feedback and be cancelable. -In ROS 2 services are asynchronous in the common C implementation, so actions will use a combination of services and topics. + +In ROS 2, services are asynchronous in the common C implementation, so actions will use a combination of services and topics. ### Goal Identifiers -In ROS 1, Action clients are responsible for creating a goal ID when submitting a goal. -In ROS 2 the action server will be responsible for generating the goal ID and notifying the client. +In ROS 1, an action client can create a goal ID when submitting a goal. +This potentially leads to scenarios where mutliple clients independently generate the same goal ID. +If an empty goal ID is sent, the action server will create one instead, which is not very useful since the client has no way to know the goal ID. -The server is better equiped to generate a unique goal id than the client because there may be multiple clients who could independently generate the same goal id. -Another reason is to avoid a race condition between goal creation and cancellation that exists in ROS 1. -In ROS 1 if a client submits a goal and immediatly tries to cancel it then the cancelation may or may not happen. -If the cancelation is processed before the goal submission then `actionlib` will ignore the cancellation request without notifying the user's code. +In ROS 2, action clients will be the sole entities responsible for generating the goal ID. +This way clients always know the goal ID for an action. +Futhermore, a UUID will be used for each goal to mitigate the issue of goal ID collision across multiple clients. ### Namespacing of Generated Messages and Services @@ -98,9 +102,10 @@ In C++, the generated code should be in the namespace and folder `action` instea ### Visibility of Action Services and Topics -In ROS 1 `rostopic list` would show all action topics in its output. -In ROS 2 `ros2 topic list` and `ros2 service list` will not show topics and services used by actions by default. -The can still be shown by passing an option to the commands to show hidden services and topics. +In ROS 1, `rostopic list` would show all action topics in its output. +In ROS 2, `ros2 topic list` and `ros2 service list` will not show topics and services used by actions by default. +They can still be shown by passing an option to the commands to show hidden services and topics. +The tool `ros2 action list` will produce list of action names provided by action servers (see [Intropsection tools](#introspection-tools)). ## Action Interface Definition @@ -132,7 +137,7 @@ There is one action specification per `.action` file. ``` # Define a goal of washing all dishes -uint32 dishwasher_id # Specify which dishwasher we want to use +bool heavy_duty # Spend extra time cleaning --- # Define the result that will be published after the action execution ends. uint32 total_dishes_cleaned @@ -145,19 +150,17 @@ uint32 number_dishes_cleaned ## Introspection tools Actions, like topics and services, are introspectable from the command line. -In ROS 1, actions are visible in the output of the `rostopic` tool. -In ROS 2, actions will not be visible by default as a set of topics nor a set of services. -Instead they will be visible using a separate `ros2 action` command line tool. +The command line tool, `ros2 action`, will be able to: -The command line tool will be able to: - -* list action servers and action clients -* display active goals on an action server -* display the arguments for an action's goal -* display the type of an action's feedback and result -* find actions by action type -* call an action, display feedback as it is received, display the result when received, and cancel the action (when the tool is terminated prematurely). +- list action names provided by action servers +- list action servers and action clients +- display active goals on an action server +- display the arguments for an action goal +- display the type of an action's goal, feedback, and result +- find actions by action type +- echo feedback, status, and result for an action goal +- call an action, display feedback as it is received, display the result when received, and cancel the action (when the tool is terminated prematurely). Each action will be listed and treated as a single unit by this tool. @@ -210,58 +213,58 @@ Python: ## Middleware implementation -Under the hood, an action is made up of three services and two topics, each descibed in detail here. +Under the hood, an action is made up of three services and two topics. +In this section, they are descibed in detail. ![Action Client/Server Interaction Overview](../img/actions/interaction_overview.png) -### Goal Submission Service +### Send Goal Service -* **Direction**: Client calls Server -* **Request**: Description of goal -* **Response**: Whether goal was accepted or rejected, a unique identifier for the goal, and the time when the goal was accepted. +- **Direction**: client calls server +- **Request**: description of goal and a UUID for the goal ID +- **Response**: whether goal was accepted or rejected and the time when the goal was accepted -The purpose of this service is to submit a goal to the action server. +The purpose of this service is to send a goal to the action server. It is the first service called to begin an action, and is expected to return quickly. -A user-define description of the goal is sent as the request. -The response indicates whether or not the goal was accepted, and if so the identifier the server will use to describe the goal. +The description of the goal in the request is user-define as part of the [Action Interface Definition](#action-interface-definition). -The QoS settings of this service should be set the so the client is guaranteed to receive a response or an action could be executed without a client being aware of it. +The QoS settings of this service should be set so the client is guaranteed to receive a response or an action could be executed without a client being aware of it. -### Cancel Request Service +### Cancel Goal Service -* **Direction**: Client calls Server -* **Request**: Goal identifier, time stamp -* **Response**: Goals that will be attempted to be canceled +- **Direction**: client calls server +- **Request**: goal ID and timestamp +- **Response**: list of goals that have transitioned to the CANCELING state -The purpose of this service is to request to cancel one or more goals on the action server. -A cancellation request may cancel multiple goals. +The purpose of this service is to request the cancellation of one or more goals on the action server. The result indicates which goals will be attempted to be canceled. Whether or not a goal is actually canceled is indicated by the status topic and the result service. The cancel request policy is the same as in ROS 1. -* If the goal ID is empty and time is zero, cancel all goals -* If the goal ID is empty and time is not zero, cancel all goals accepted at or before the time stamp -* If the goal ID is not empty and time is not zero, cancel the goal with the given id regardless of the time it was accepted -* If the goal ID is not empty and time is zero, cancel the goal with the given id and all goals accepted at or before the time stamp +- If the goal ID is empty and timestamp is zero, cancel all goals +- If the goal ID is empty and timestamp is not zero, cancel all goals accepted at or before the time stamp +- If the goal ID is not empty and timestamp is not zero, cancel the goal with the given ID regardless of the time it was accepted +- If the goal ID is not empty and timestamp is zero, cancel the goal with the given ID and all goals accepted at or before the timestamp ### Get Result Service -* **Direction**: Client calls Server -* **Request**: Goal ID -* **Response**: Status of goal and user defined result +* **Direction**: client calls server +* **Request**: goal ID +* **Response**: status of goal and user defined result -The purpose of this service is to get the final result of a service. +The purpose of this service is to get the final result of a goal. After a goal has been accepted the client should call this service to receive the result. -The result will indicate the final status of the goal and any user defined data. +The result will indicate the final status of the goal and any user defined data as part of the [Action Interface Definition](#action-interface-definition). -Once the server sends the result to the client it should free up any resources used by the action. -If the client never asks for the result then the server should discard the result after a timeout period. +The server should cache the result once it is ready so multiple clients have to opportunity to get it. +This is useful for debugging/introspection tools. +To free up resources, the server should discard the result after a configurable timeout period. ### Goal Status Topic -* **Direction**: Server publishes -* **Content**: List of in-progress goals with: Goal ID, time accepted, and an enum indicating the status +* **Direction**: server publishes +* **Content**: list of in-progress goals with goal ID, time accepted, and an enum indicating the status This topic is published by the server to broadcast the status of goals it has accepted. The purpose of the topic is for introspection; it is not used by the action client. @@ -272,25 +275,23 @@ This allows new subscribers to always get the latest state. The possible statuses are: -* *Accepted* - * The goal has been accepted by the action server and may now be executing -* *Cancelling* - * The action server will try to cancel the indicated goal -* *Cancelled* - * The action server successfully canceled the goal -* *Succeeded* - * The action server successfully reached the goal -* *Aborted* - * The action server failed reached the goal +- *Accepted* - The goal has been accepted by the action server +- *Executing* - The goal is currently being executing by the action server +- *Canceling* - The action server will try to cancel the indicated goal +- *Succeeded* - The action server successfully reached the goal +- *Aborted* - The action server failed reached the goal +- *Canceled* - The action server successfully canceled the goal ### Feedback Topic -* **Direction**: Server publishes -* **Content**: Goal id, user defined feedback message +- **Direction**: server publishes +- **Content**: goal ID, user defined feedback message -This topic is published by the server to send application specific progress about the goal. +This topic is published by the server to send progress feedback about the goal that is user-defined as part of the [Action Interface Definition](#action-interface-definition). It is up to the author of the action server to decide how often to publish the feedback. +TODO: Something something about QoS specified by server + ### Client/Server Interaction Examples Here are a couple of sequence diagrams depicting typical interactions between an action client and action server. diff --git a/img/actions/interaction_overview.png b/img/actions/interaction_overview.png index 4fb6d9552d56b00ff950256763dc40f40166df6a..24260869692fe86ea36d4c00689c98d8cfe79d33 100644 GIT binary patch literal 10532 zcmc(_bx>SE)Ta#tgS$JE5P}l|1Pd}ifWZO;mmtC2T_?B%26qV=LV^c(4S@s*Fc91c z?(VQR@4H*I`^SFuZSB_XRL#^>_3ggr^zGC4{GQX%>aP_D@#yf-(9j4KVXxkxp`qIX z{|j-jfZtFS@egQd5H!VC(po;od%3u+s@gYw!IR?TnU6J-e4|JdSp_*Q*=?W5C>hJ9 z=u+?_369dAbNZST4)V9s7WN~2qx^?X0-74<9yS`%_VNZqCuz?`t>R7dpBXiV9CSP|(F;3$f9pLT{vM29 zk`DsoePOoUrxbBnLc8oqrVVBm_aRyPl`4C(K9u;}Ts~2i0+tAja_epg5r3p2K@SF8Ijde5nN9x6MoC z4GS_`sG?B&+))3;T3hlT@rw9;ONUvh?AL zbHVN*adpIcZPxyL%O~f>_T`$vWft$f8A=RnqE`_FvQBurtm7$IE56i9^x zrt;5WKLuM3MI*;tbt;Ua(|8OchH+^1DbN5jANn9-Vg^SAa~B3zbMPq`@7JcdH{(mlFn6(M_( z^$+*Lhxa$o3ZtOifb6#w#$YiIvH!R1aUL^28_V4t?!ouxti~B^D|PWAsKII| zghe6bsj6UH@D1S?O>7!*8k;E+b^{8LKsp*ew9PT>%WbX#71{!0iMGZ5#7?$+G|gg= z(P~)wZY1%}WMdl_QrH2Fif5$=*JT+rQp471jovtMLPj2Uy60N=Dz3qX}lXbBe<2oe;RA0R94b7jItVtDy)aA2vTiVsgiDq|e zLeEK<-voEA9|c#QvZ z<5#kNdj?DKFFg!GMa|_qR5asg(6uTnPKMajw&xCGpV`s0gr25wK-0Lzemymnx}#X) zZ>c~S*I-@Vc`vnH2rgxk`QH03{eDS4#yHsP)@*)tEY>hYZzoP_)cQq}PaM}J9~OfY zZCU+ASzbE0f4D+VyPygz-am_bn}CN4-?K$DibZIObV`sXL#?hbDF1O=fPOK%Ncto> z64z~#KC;CdBLFQFt)7m>%c-Yd)cW-ur`cd%F0JLsk4NsPtK%*DNQP{-*hUeEy-px1 zL!8#-u2Z5R(ZbQ}qtfd-2V0VC=& zQNyy=h=HN+U9uEGwl(6s2%!OHkS)gDvS2bM%F5RW;+Q6diNd<>v3-gQ^lkii0~{pb zY2=s+8PL}i804M=M!!j1ocRRky9x|)`v@U4!u(o55$N0ZAHfZAERf2vN&@;O;Q!AI zh!RP**o&uFd-KoHq`q!P7p1BlGOU(h`X`4|;o~9%pPTD1co6k(QJpU-VAvHO4a}Zp z48;Do3(D9SRXiOJ3?Ys!NVqpmA|mfO##F81B+5Lu+o0~W`(dnj$KbtDUP@6N9_6vo zB;o~WUjp{)T-2SQ6TzH2ag}ckuYYe)BZBP4OjXt!VdeP!x%p{{kN0A^qp3Cxuj_Wj z{-eHSvXU}(Sw45L1h0Ko(xah-FMwgUv2=w@n5ai&GwEiJD}FqBR;mB1M3e1pK$^W! zgFW``oiIX5O1%nF71U;2kZ&*JPH5}xNr>ww#M?c5_9>lbtd8vF45Qg|EZnMTM9QAN z{V2j8R^#-jw4zFArQ&Tf8GbC7L2AE!->k{4S#841!rT@8JaF=D^qqoIx$IZh&4Ecl zi&iGnvl+Z;>nH>c-1)8&6k=O-mBw0?uo#W|45#la0WAMJUu1aepI`g%Kf zB;-(UR!5{HLL1YeVo@vCv!36jvmjPtp`=yz=BESfDI8&Yv+(@jiM86KQu|GVfV9B9 zX^h)LjKfg{#hde#cvD60JTz{YA=qJFI?J+2Z{2=gESJoTl6pe7_BDiq5|xyEeo;!B zc87^FOO&{hW+6gh9@g46t8*_a;s}&WL(dP0Eq)UOT;x_v4HeerL56akkFgHQ)eunM z1l%~b5#PM~AhX^!oICbMZ%#S|YRys3mN%mDytJMo#@Hbpe(aU!5B*% zQh$c4NXEd9f$p;W!U0&JP;WT~FTe&6xy z?p0iJ$Myu>lt(;uzI|bbER7-`EZcR|rVGCFgeVYQkVtr`OiBzQq!&g0wukY=t~QtY z_h+ZDC~TACo{Y@JH=PhmqDkJ1SWZZ!_@c0acEBi(-yEOxx(u@J@c8JgkV9__zI}sM z8h38w?`TB`7KMnr+Du?eKL%p!V_9@RY=$CN-!foMB-hJKYglP5l`H#QE~ys|@`Fnc zAqx<;SF-H|Az%n#5yrG88au!SE;v$nr6JsB_N(XlfObt<@J~9YT^|9_KV*hv7h+?6PmZAod z-5hNuo>*LQ>4<;Tz{rqdo@yk8CCg7T|MmMlkdDC}?0L}Ur@G-VUAtsdpHkGssf{X~ z{+1Qfa;MJ}v!lZ-Sw^kLsg7o|U^J=!_fjXCn^*d}G8nz%?z0+JS^tWYk^dZHo-y)= znUBYXxfZ;Zxe)B19#!hPsmRBB+hLPvoPE^|F0fWx3a1X4Yw|SHmmhTC#vB0EaT_bs zT|Y_p5#sl_$<1e|${LqXhO< zs=imKvcUeRdTES3Fz=6HP_5Bxk6t{8F7KUK={G*&A-ZTF299-lB6sYTjanDy@45YZ zOP<9|>6@l0r&#?gmWO|4HrgDbn!&H##mVhp z-UljDLbo0UZ4B@H;u02CLs*@;QXws~g@;e>1EikH7r&uVtRdM$6^VJiD|)HtpIAp# z?xFA>FXQtdv(UM0s8~PfW~|K|(q{F6SFTqOJjR$GP#F8CTIZ4bpFu)*D(o>*ZU)1~ zst7idhU3w+&I-gr-N4;_T(!PYy`N_r^}xGtDbyzBb;l8eo)p7{^?^4}!)uFO?_6CP zFB0h@m(N4gR`HR6NnC>TFR@TZM`FEQ{h7UH)4$TOOSH#E`HI^}Q2_^alc%cRk5=KE zHcPqQA-7lLj4ODyTv_eD!Jl>XQp4A3d_qUJ(|fHtuCV&k)p~+YtO^4C8O;ne55+&w zXC;KSed-st^*$ z#y{{NjH^u1C2w{GkZSo%9k<8${Kr4ys2$e_GuaL6xnrn!VrT`dOb?g3Xe0wfehFk% ze;dkrfe&QeKq_^EU{$6{;nF24H>i{OC=>2Pd(pI!C;RPP?;)!*-_`WW>gsb_)RWfR z$otkPA;edW+0aTSKg+>7s{dD^ezF~utT)t$WQ^s?bC8(Bp{GZ6Dh;wP~ z>2WV`KzQv>f&!5QiSrD+=CV@r>TsiF$`>6Ct=;SX1pMx6zrcAeJ};y!e^H#>vCaNS zU{07c_9tYKkAniD`4F^mg0bz4l}^x4#3=SxTgpO)_VtUiYB0eT@F2blpwy)9kcB9X zPx7pazI^2_fBQ*202Qp9&fA+K>dxn}sqSg2;&{ld+u-!JOz+!cTyESEKtX~{x|1GH zRGOIJPSseefqxh02N}ri7L$uhqO z)(2j5Up!+Ac%Ay0vDUdE+f$}K|AV$jvz`bJmy;)&)fS4W?~aN9y`iC8UuTGJ^2m`N zwe_6j@Sd^KvS7Nhl<1w{xx+ri~~f4w>S$!4~`{5|_}Q}9C& zpVB%yKi<0Z5r1gY(mzy_f);Mp+(Vhx`owoFRd;+k#+p;8JL~5DdZ*GZzc-eeE5yw( zFEe9t-BLv;{j0uVy@LkH8f}&3K$@g%)~MTZcer+Q*ax)Aw=MP6;lTp@`68}`ehKG* zxjIGaKJ|A;eax)$%X`J@^#V%&=_@-oi#1jP0BUpz-j%*7!jrt-WXTctebbe?Xu>2s z_V_QD7Kj;Iu&r^E)X{fxJ1Hw%9M|dyIIF&}X(t-^t;zLK?=rgdO!Huq+nQ3+b6kF= z!Di1LKtvyuh8E*g4E>sI4iy}BnoH0S8Dnv1eg1PZh0iK%U>q-aikqE3$xA}^`FrQN z#&0o=zMtJ4Rl<>q$v;*<^hk$deN9#XfDa7yBmY4z-`61!r0<$Z;sADt z=0>pQ#c2EG3O*$t**F0eE%X|d@Jx~z2h}>bHQVrP3fFn?+tFu+VZp&szUrW}Kf2oY znYL(RDd{9dN~zsjW5p8kC`=w}dA^5%_UT3`AScQRq|GecO7vkL7u1$L+))`#764!!tQWvTW62%{m{ympJgln>T^m`Az%>)^3|&yBfr$6bAM zH`}Lvuv@G!@fB0Y$)I^lHq~Ik2VthnzWS$Fe2~*RX6L(gVPrW{)LM(Lx{i)GEuA!H zw37mSf@&39D#Kon<-kMl%XW&3_r2kXNX7`=|a>#UTxddgoVL9HL-Aa|TH|VQ;NchrEeJt9FKd^}bQ}XVdnl5Jh!l(I`^4VTc4UnHp?vkwO1}I^)SZPs^b*5^54+Xz+6=gY!8iWJ61cnKAEj>>&RAc!KNw=vDxnuFzA2dP5o4@ghg2aaUJAHyPvo_~A04QOF2^tc^V0~4 zHmL!cf1y}Y?1C};XLblVbx7<{v^@WDz_}#Ghx5@V>v24=;hB%0R*WW{BaCAv)wy%& zO&6LAjH&Utd4Iz)`lKB3N6sGIT_3k~R***{f+{Fn7SD=Eo4L`NrOMnF-Mv7QWFd`Q z*WT%o9x1nf+r$bRvQlF>k_{8?RB-QpS0qa^AtQ&bVCV_G<3d&0(3vNTI7rpwAD)Ir z?x@*>oq$@fz5G}l#Qm~erA|Y^Z_VH_a$^sap<|;Z_BGo7HM*1orlg<9)=n6!CUtIQ zC4ZA3)>I%rDT+`T1+QOxkEk4hN%l{$Sq>otcwhB zstZxE{gCwR%MVyH%a`NpxhCk0_0RVmp)J#lRAmV{*h*_yGunjhj9m;}l&G+MB%$9A zJT)2od-VMl^8R%2X1lt=pf5j0c06c4Z^rz&+ANbvWP^lK9enH1hWrPMhkV?>VR4^J4FVik0~O@Rd6M zC*lD(k)^8J2@-dwyf4Ihe@uAdjh%bAU;=#fv{{x8B`SbksXfxCz&AWcgxsKL!(2Lx z5#y0TRL&GPSmxyk>xk}zle!<}T>n~iDQkDt6P4;r!8@7OA4B&%7-b6=>kXj`M_c$V zPF~!sJ1XuhZlHO1Ia8$#?Y-^n3D+!{X`kjnoU2xvI`bfi>brwZgIgl?Z#Um~k%C)w z0QOv`^=Mih!bp}GNdF45mu*~K*M^6K-1{RivVe(#bJB#}fl<;V+Rdj1=6UV6#|!icF+q+Cf!0`uq5h6z!?B41f8Vv)jbKBqf4R)RqPZ`qKn*O1#|+Fbck9eX#(tZK16DDCG@g-o;Mn@19{8rL?cz zL7Q5I2+}|;m$s$6mfFwrtylHEV!1ZI#l#9OQjh>n=~gvR!2sz_QQeNdEy!%MW1NiAnR`M3Ho{ z$SutsnQ~f2b&fEwg?@3BA}!>e?$EFnYj3k71RHM?mX+E)|A+UM2TLU2wE`-xbzb_q zBil34;M`r1O2ma~>G4CC)0T_+$-vc=Z>vDWOYXIMeH2DmEl<-L!tt&`j(y=|O}nM$89B}X5I_dI?MX<& zYuo&0P_sj#TRaM$xw7~Zn12fVen)+#l|B&pSQ>Z|@hJ9JylXVFg~!9BWrPx?5^3SC z=HflS_XfEhL3`ey)!o>Tj$F9D z4J!2_eQV+Mpl`Z@_4Z<9OBLcc!3O{hfdh%Fs2==~@wz}dw90W-D2`U(X@Go~uZ7(RAbt4^AN3gG#W9GIX|(yB zDfwKjrT^2e8czrD{`(T4gCb3YlovsN?n?p;HX`5UZt(ZMJ{CY0nboo6gkJ2=)Bo2B zB~UtC{qaGW-Jq5o5aD(amPGX{2~zh^6%~R7pH)KZuP*oEo#dK{kD;IBq5SAQYXj+{ zg>v|}fQ)JM+M}}@|MKziB4FaXi8B37K%KucH}4ug{rfXH@ujy@0ASreI5AQ2Hum~# z$Gji$XsX4#(l24}?qX5*X3=*eSNQRk=g!2}QASpDG&G#We`f()iI^qhR(fO2yTfqV zb;>gQ@^$mDi5Q^G9$S1)bB$5g`#`mnNiK#$y3X!T&Ka%Xq0P_G%}twEJb)8$=0<9h zfKjMGt|bbnu)AK&d#{cvFndnGPizztuqMjT`K>TxC^6`Sv5q%7PeQM?R$Vk zXr2uR248QnaT~W@Vj-1N*x^BU*Iy5ML(nnC{oOZy_X5r)crW;356)K@x6u*O395Ih zWeYjJx{T}N5a;Vjy)C2W)WXqt>9q@6!mbUxIk(bVH|3&PCS}5mUY+@>+1c?xXw+Ut zoLj|fY@{%8bv%ye1-%QtzxDk)n5ilEXU+@2 zRd~Aq2#nX(5JvyKnU!@gQ-`nfx)~6KK1*6D`aEZGg2y1;vD5rAs?yffSIosY;nRd}XJ9*NX-S&a@N&y-h8;jvP(h>ZCBa)R8h(kqO zNCtf5fztz$0fVcG_z9qg+Y{o9P&?pQf)Bx=*Lb7I5{eb_Ncy2lKe*+7c(U@Xa=_x4 zSH&Fx4VqC?l8s`PAT*T|+7khdXK2uaO$j;9Xsux*&Vyal0 zfayJWdmJK-eh|wJGimi9ZT+5XBNp&mkyOKjZ%x0I24V_SOgZ7g)tTGta}zvZu`Ke{H`O`8DrfL~dx$FjZ7`BLZr6u$5*7FvBdQ48&XE!zX0 zcuY4IuYP7Xw(eR;X3gqW80o7f{w0V4R>{}w_+2gl({*XFAp`M=WjGsVyNrAbAVcLk zWqR;(!-hir8mr}o5i=^iL?b|(GkX2yjhwAubUEWZTnfGZZ1!2jsSZNp+j9UMkLZGT?=hf<%a(jA&%+%wy%`jAK_EDVOyBR(s}iHJ~EI!sqD*Nm94kPEf? zu5DuDWJDS_Qvjv;#vqmvGiD4HVqG5+zlO$DX)>7m0*6^wwk}HM6B^5NV_s!)u!<%W zXifN!*0CoG<@>;amtSW`Pory>*gFNDGBYfNQe}!8&0t$wY-v**8lx}6FATudmTuyW zU=%}?wfbu=rF=;VV}M6Nf20M@vv=l@7YB-p^*+jvqxckZ2x+WnW+a}IncI!=fZKpok?NGi_D(Ba)@8qS*$V7P&EV%DM-53wA2*a=&!fP$b*iOks zjEXz2mkR|0;ixs(RN+Y`7;*!J8ogGkCOwgRheiIv9QH$ znE4S%r3s`&W@6maL-LeERz%@HEJNlpB?h|AIve@OCf}boDDub#rzYQZ1DA?1lni7v zu=CjwR-Ka|BwwhDHAHyw3ga(-)0!BTdWb_6DVMIvHmwUV*NXwCyi_J$hs!7o5lbRX^Jnqyo@(N^Lrp}^w7pno;D9d9wPr~lC6f;wnfOUL{Ev&#jF}Q+p zFKgdLcL1>?|8L!B0NGUx+nXrHj(ZI5OKe#0wtlTBo@pX?sax7vb4iS)_Qdh=#W%gB z!6Kv#G9F~0jm2qPsknn@E2%RecUf)_HdkXclvNS}W`6Q+Ub-|!DIlQLFJrSmk;Tr@ zM(6HaYXD)d`9Ivr^{BJRXNj)VdUPE#M6SB*m;S^~31^zN{=mRu&pkj3%59nlRlgGJ z!fKvS#cEa6rvAy;_StXRP%l!V6bCjs#cc|*cB7V?bdw+r1aJes@J5+Ik0@Yc0*nhZY#|$}zP7qBf%2}D2%x%UkgF1W_&i`eADEm{&L9DaZc75a z#PAwf99y+I0$>lbZ8mzB9}47vFZ-vTGHXUY&kU`}or!+VS@rKml?G)BDx} z@aDuD{VWz^8nw9a-S2Gs>ok39S0AVv(%^XCV5We!poG`1 zUTTdOP-rrUXlRhBCjrZR0v4K}*Z}(@oe+f6_!m+y0IshjT8e0N8UuRpe4C?EaW{{8u1(Z&KK~lOq1Vp-PhEP&QR3rpJ21L4)4v~^(=pI5+ zy8CSZ@A>e4IUnBZI_G?uYid1v?X{l0*1CVs9jl|IN(yCw;^5$rs==S=;^2Usf%jhs z@qyP!cIiYM92kz;69xSM%k4~p_cY2Uoh@wYcR1PM^KY3rpp?`g3knDxwT@Z@jIa_< z!K59BlJn3hHV#qzMk<0$=~Y2Sj_9-2Cy*!tQG1o#HH0 zjxQQZwelDO^GPS({^|d%B;1GSH^NRt_rht8ccs@n zBnK{zw}uN1im>!-sMLS`c`R&$Ukkr zy{8P#;A8vB$`272(+{}Ae{9D(v7|8B9D4a>tuHOt(HBl!3jXzqR4EdlR3}>=iDkH_ zT2lfxUsVXOesw9p5+z{OEPZjbF;ZYumPMa3H5q48<@n8L+bU#VnXw4=l|=($SZoYh zR1lWAW9kpI(9y5{XAR2Z*|ja@o*}Cx>J1Cj2~S6CJTs_l4~`Nsczh_|7_GAV2i6@j}fy zBOcKNKmA)eBFhyb@s(@bW*(i<#zLNgnnNe^)bBo1q9%+312>}U+5;C+LO!tTgcbX4 zjSnw`U6#<(#?qXfEhmjV4a7VFwQ!dQKfW`VF6}m5jofP$>Ioj@3520e;F7o79Hwe)7TJ3Dt=kC~PMH%}zUk>x>oh#t>)}f>hM~w_=`G3T%TM!% zbGzbUSj3fK+x5@4CUEt>f=_oqHa1DErocDvk(0VGX2K71(kgJJi%kRTHax`eMu`~? zF{^$F^ph09)fs#1)0YVcmcgWiB|IA`7#&lv(ac}Q%uywvk9)p%2FK#t+2mMY4@fmr+Ep9VHTW)1r zlbv#?)eeLH&eGS0Sy-iwwnq5&r#~Ml%|uJhUJYD$dn2pm#*WL~App&HL*2OC@(c69ONV0dn*4mebGaGT zy)K*oVJfzUdO6Y=P&fAwRW4{o>-Oly9e4xhr|`$L@Jl1Bq#*JQczQOo1SOX7LzMgP zWXa^^zxTRo_=z^PWruM>j}4eXX4%Z*cd+vQC8iH>t?^#gysThr^2m8JxivZ*W^Ec~^iVB;I$1l3?A?DkbisEP`GF;6{11~N}tQ(YPkJq~zk@|MQ zgMNZDWfyN=XjBQ?`r&U--4{Iy#I~8bhpL0)O%;wjbEHY@eeuc)}mI)p*m2Y`ZH$p@R$cW%7%{A^@)R47`}Qf_p|6w56qC5UmZaGu8INweLq`gFBDDHfcZQL# zxcwQpxhl~E)Y579-LN&XFW=!|@ay@|Y|QYcGK-Na*;+1AP~XpPl|+PeAlO;?i&Ton zPmx{+uyfT_PB8`ivYRJi^uG3Zl^k82**9WVU)I7oLUjK@@xLdH5KVgYdQO89p7F;M zS#5H22hO-o-jK$Ddepo8F8~|r(GaVjh#Jf-r3->_JXeCbWy}3_Oa|H}5d%S9%TLRP zPxf;FZCUODLCBHS$eZ#EHK47uAP|HV?2LPD^BCx|W1u+@L=Nct#jlrKL_pix|5FE& zP$FvMJ8*qL8lX3VfdaDxTKoPMis7fbxI{~T6s1r-2?`>If zAMYOf-^!w31A_K4&f$eyhs_X-?8nhdG9^lk_ZnErf73LmSkJhw((){PfXPA~)%&ip z+OX8zb3)8svt8{SqUCn{TJ$;2${_jQ>AYUc3RXdMdzkUa5Ix$2(eo;xiFbZP+m+Fn z=9T&<$)e!yWe*|)!}n~dbrCEd#Wed+tDL-IWKFkU@Cyi#K8Ps4HDNZRWmM7xzr$Ew zyr68aSccryoylhA?kwi+G^)vZ1EHZov7EYB)m8Pc@MIY8F0Ne+7a47t#$I25WP;We ztIXFwe<#fl^Coj17qB0r8CQ`G&@r;LsX(;ccv+s78$X!4za?B*QHygKw)rjfMk#MR zXH?v0&6T0t4T1r^n?A;kHs{ck_XgceSS1Ox4d=FgQLa}czB^sR`~42ab4<*KKdob) zjA@AYfa>VQ-$)9vq6+bN^wg=`Es^wL!u&jM!*|cz!}`|=Jti>3<7jH0qumq%-+txr zd_D6PbLp9frEpUhrl9<-nVn?*?PMM7)BRDGpaLZwCH08ed&MALv)5-+Qe4a)bm>XLS*CRO$ z;p$q`BV~>{Csc3(<&!gV1}_vB!l@qJnv_8Hm7*d=#T;b=2U#-T1l$B>yBK7uSl^@`i z#*wFFYXT`7ig0fp{zl^b6co5TR7|XJ??2Bs(Qo)Pb*70!$kLNcKO6nQr+@O)Gi);{ z{0PyB9=~wefd}vZ&qMn^UNxdVsa5)^e)0MSEFu2CT^D6Npc8+vL1X+Z*xl7y{>=)z zpt+3~Q&*w-gO?u}UT3-9jgo<26z<66C_&Lwy4}%(Cc5!_vtlkQZJm}cmk5D_ATs0} zk<8ijcQmP?HwY6(J#lJ5j1DdPHX+010{7lt&r|p1OgZ?2taLd3a%Fz-PB{3)1lw^J zR65efsbr#rdbXCM6l4=B$XW05!O}f_`*QafeEm26dS?>Ep`Pzb>6Pe|60&4E>NK!^ zO^Dk|@TOEPDP9zFc8jGG zNeWhK#~kbycPdU+aIxjUTf=VZZW3<&@D&9|2W_kP<2yQ+%K1%ukI^Q^Ka7N~PsLn) zs2iN$?QAUq`P>-5z8Eyrs8Ft}K3884CSG)-0bv8nv)J71$sW6zHnls4pjaL#E(8SF zeIbo4IRRD>Q51fVL0|cJiJ5A6uL~U}K?n9s6~n*N1I0!$F|u`E3EOn}ZKuES`6xud zq;6y4P`nf&%KrDeD>8xJS1utro^~v+IAFUnoHp@KWiB4C4Z~e@Nl<)37JU=dks*75 ziGt&AO438!JfEY%=bw3~{b6qHW7MxHbeD(hciSs9fgPrZQU-0p8U2=bW^YmcyNmq( zQpE=@W9Imt%4Bg@7Fm*w-|vu$(LVK22q!UGCxLs4Ulr-p4)K46_?V+sZ=$5kE>Bvq zKOY!aFkL#T37pi~Mr&CKi!Bj4_depA+xOsb!+y`xNd8p)Ez8s8O;UC;NiOtrvzXZ{Dnm4f`Z^bX4#S8M*Kyz8wR)Z^65$vqkWy?bw&&36 zQ<|Q%-X~;KkS+6D*NA_xBPLa1g-g>mICXDLbm{Twsc(P=?8g^}SR-_;V8^kmpkTKri=Ja7?#pH~lZbzQNjF&)Auu2^ALLxeMB z(KxpIt)vTQyZbE8)AvI#2WZ5H1|sLx0*SpYSrg~zbK8{G%9{c1ph@8-))79#U^+}A za!58`)_Ay4i&+NSm7dV2Tt$0Nq2I2eIY(qBHS$Lsrqr_Ja4+HP+@C6=@7<$eKF?{6 zx7Em` z-zy-+*o{iflbBAAC#+PPL(Z}N@-F)N)cG1|5r9%<{6-gBH-(3J3FXST)CXz9+#cd; zWlBZ^V#IpphZ~^h@GI?qgTn?HA+}^qyXrUHyuEfRZI0TOB1VnRvKA8DuH(f8=5-J6v9ni% zoO_`Gh5zopc4yBAKD#+4ptE0P`F^UtAZNThTY0BFO4|F*yMhxfGivI0*aXg!pSH&j z+51T#9(2S#AG|9geZKO}dgw>!rQgxk1o;PEgM%i7?9Q+&oNAzv&v$(YbbGmQixRYu z4EcSYcRB+M4K<$s-$^7O5ObYJ^0|#lndW`y^4w=@A5=Q@(h{fK6*SkmU8wbBPv+8$ za~Uhl3B5dlX3GShw9hvM4>tySCon$N3Z1X>c7oV+b;hLp*!NcXAuT(@8h(Xj4Lbw5 z&HU&9#Huax#DnDKuxm+`M26_GA|rNwehua_!L`u{yQjBLqMNnaP?xbC;?1b|qL z1ma^|2Tq$7@X45B4nin?C32zsl=!Dc*Pyk;&hO~uJuLzKO56v7 ze~`}Ju`iXPadFQ%tTTar^HTeVX1XZRZu6y}N)k&VFpD`X1T8;vVzhW`?dAP0j+{SU zuu;X;R+u9vP?nYUvGwfzSu$qId3IfI53Kk_x-re#~!LP5A3IxzYX3 zQT$ymF_+QS>F=&~Ka+71V`6mnIQe;OOH9ANM>GYW8e&6^$BYa{Z_d{~^TiA-UYWn{ z?D|wQA4L4!bwZ`)<=iLBKJu?7OlBUb+?Xt1!jx91`HVp0d0fn)%VvI|xYm4Hgyg`8gor@hkUnd{v&jlOUQT(N)E$o~ zPFA&aQRgo^hK+g^6yvj}AFaZkU0z*ml|i#-Q~bGBYtHEo0j(}4emd9S&lht*HW^oT zEa|+jkUs3SGh1g+AC-txX8OIbGWyoh{zk^i4Bsh8OyOYVw*fTT|6lGr!!VaxMptG& z```0zLoXo`U|!{zXnV&j?V-aSz`T~0I^vC&R%ZdGH2#3-VOC#?fZ0%movQBv_0I~EKr<)Q z>RjUG1E^C_R3h%X1T7*vm0FFGz1RH__t>4gq^Q}?@JSg8VlwZ>R(x4TtBVufiv!Nxo zb2bay-h;313(cEzUSxe0o;q**8CIXunY0`ZNb%nGiQ+K#sKzKpLl-f5>YgeXJOL*a z;oIKksamZmll)f|( zV)R^HkNwP(JcJbLQ6?zF)@d{1CygGnVUbBye!7WD`NKQKRxQmJ6%2Z*GfnbXJ3k^uK*!Q4rsqWQLEF((oA~^!8KT?|qUe>?MAX6Nq6d zU+G7Fqkojex7(-@-cGQAOF&kTL3!#lt?KAs8zj-=$Hk51MN<*uimM^3TF*GNcJ{t~ zj=T!#S?d!T*ntI$zv>`NKm3};mAExWnlEwI#5Gu(_<_r_hSex^`vKZQ2JvF88BD3x zP?q+0Q3_%nUA_B;Tc+bHLVmh+i=7S5dd}E=iAKJPS7XZozTZ3k3YL zY_EK4lPYc|niT*Ar2InC_t_T%nkp;5wpu+# z82v(eNg%H8A|!$lD{9CYe`IF|!h8d1=8sg%K(??S$Dv8%a00VpV$o%D_{|pNqC8|P zRcdi+FlMZf68JS0z#EbX-uh(a+j%ZQ@AwLJ%11zlgQiy6=kZ%ed@P_Op%8Hog~+qq zOZ870bEP0tE`p)m$JwehnPlgO)a8i|#PQ%JBe0dhL^x{;J)D*ncLPk142ninP555e zS!-I4@MLl=X};W|x1RINwlJ~Yu`F3(gdl%~;})?a@;OD(uNz57W^fwKak$eVXV2fd z>#u1>EkpBvm>o_Be21dHt$i@w{wE_PBpoKZD^kC!{)*Z_NS)gBb0+Oaqtmhh-u6X_YbyI{atpYqq+>i7Hm6R z7diD5#!QzvCmFZgx|k?+@n9}OY;ipA9;!DU`Jg6Yf26Zl_@>Rb+%jZq(r5Ne`h!wy?&D*= zL)RH2*wHfrLlj4=Bl1Z-@|!DRlx?jqIp=Ir^!_79O_pEyy@t4|eA3Rtl~rE}bXJ8^ z)$9G(@V0&GG{uHZ(~$pBEkF22(sm#je=?A)HponM>T?-hb1516DgM=h%Joe8+%xg` zH(`SdLmO{y#E@jf$Qv<)C=Y`52dJwIM}`kqZg=FZl=tx0vQ5G!x4P6%M+d)fwl7<; z$|>JG{LK?I+#1a3YZ?Vx@Gy7JkPwr%NdJhT@J5ofMl-giZ3SV=ef$tSG^Ml7dAKC+`-Q7G)KQ~z|L|p zycYGvz>4AU4P2QcFA00t;C}~M9USy~yxBk=wrwWUw58dm7DQ3+h}V;;2o6?g;D z{dZmg59lzb*`*-}S?zv&^y4wIx(0e-6OOEAeeyxj!VtJ(r9Nm%2gZCSZB8miep;r< z-gSW&s0Wl}&7W|gP7D>~{tBT^A`38iy}%VMQg~sEP&Dqns$c?72u4+CgJupL3vT`w z$W^&%OB=SG85TArB?}*%%e~uuKf5j}pLwRDS3V9M^r5kK`dF%UxaC+;A2X{5w8*l& znFneF?$I*q3-o9K@hY$yh9jpUznTD3VBxqsoLBtRF}{HyWo`)?RJ?SrUj`WE|33cA zY}iKopEE7 zBXf)Q1kUS+uQwmaU06OJmC%4+Ttxe3w!KpJDd{p$6?@+02JTrMdMnBoEmdSu%L^9w zHc-VRG-fJXe6^^D3tUS0Gm8g8QmZ-HiW+at0S;G|lNt1n-?|ZF9`CLnJmX(nF-E0) zP&2lX8fDy~d~;B5xm z3;73#Rg2-%54U>+5YIkCTvOs~H@+6{lYF8NFl9+=<HOuAhEPKw_fr*QmrXXIFPP z9sLI7D7oVK+K1rOhGP1@-bS2Y!ys-8GsH_;P~wH88itw0qA+Ym4YvK*S!P$fbc&g_ zn5g)Q9uXcbKel(KzoZ!pa|n_*IJLwNxlR@g?I@@}(v!awcez{oW=O|fm&rH;Cnf>B zNedR7$CI@H9fhiWTqsOey_+WE2{{YPXg;3;lDEGe{BM!@<;-zi9vgMM-&^12YkaTN zI~8@rPonPO^@x~&T-|}dWtD)?dYs>0Msc+`b4<{lZN`QX0hJJoxjnp(63Bd0AaR(h z6o~ESwB7(&w5N#OwF>6)8{3QeOFT9Rfbc-We=yrTq8iBs?AYjkJGRq*cI^KbJp6x* z*8Xn;`Tu7fPzV~zRu~49saWqrMl+G1qvt*wn2t^;-tH&?DMJ(>;cTzY_J4}p>sHOj z-=6+XTuI{b{mWpgRG@Z-f#c zYFj+rC20E<>48mEng?oV&z?OCxZ3ZEbWs&1zv;MZB_D7{gS?$-2B_w?$5Q1U0{p`3 zPfwanT4KrB_2~iy1qITvKYdC)x*LwrCf^vrC1t?jRPPMDsc~OW0i<5V%Q?x}27hwk zSgHSZ7bx1lf)LYYI}K*l0x~;56X+;2An!W?q!FJfmQ4q5pv>Zyl^hu6nT7&pgDiduCW13Zh(>vXSKqyvPn50$6bdC~% z2!B-tO~M{fk#G0g9v8p@aJ<3)_}f=F2(5-I>ViitM8=_6c%!k`d^~POC*{XqXjJw_ zA5Sv7wLd;+s?uTe763p>uSn?i_50n{20xdz4m`4H!=v$~!X}h{I|p0}Hh<6!{=07g zs(^ZU(=>Q=dX;$-carB!Ww@D>Osby0f`gD8IFDjs5)|i}0Jo}|_TO>9d7bxN@ ztEi~>Z%@-KgdA$_l~mS25}>b1=)bV!Cc3p;foET5Rz8q4&2YK?L6Wp}yYHqdud3W3 zdu;z3;Xe=J)eqP^{Ty~dl&g{m)}u`DQB9!Bxfu-M)uT0R2swY~w>zH*cmiyIAxxF@ zExcF< z?>v9|_AQM3;&hi4?DVcy`{$B^v5$|>f7}lpUD8?ASZwXJ=_@i+BKA;w10ItC>1SwX>-)SEm3eLjFw_xy*^p@Y`;hqETjofJZ9xQ+*G?joHrumM}(}UM?_=|F+Q%?UIjY*Ha zo^hc&!gre-h;{N4`WxL(HlXC-T~?=m7MuYoPJZzKP61)4Fy-=cC1B9`Z{8bG&86qQ zYXg}ErAd(-n5$fz-P90Igpes(D|1?o;H{-HNQmYRO8`%Hd_z|kU;yfu4J7ze{RNoE zFMzv5kVWN@w*hGNllXS;I1iaoNAh+=DPpg+MGziCpvC5v)?Sx4lCP=fZv6X5dY8Gw zSxm#tL%wG`GHPC(M+Q&fpASjd{{!G%O6T(QlClD0<8jTSVyVv0?XG8P9A9g>n=?g= z;EEF?TF&(f^?Ae$`qn=hD0V@-xWaS*S5jKR{2ojJZpP)QD2M#z3oT|9eEMqwp4VZB zIP|Ie!m!XVm?>3bniMGqcB<1=R0giMm35RtAgDC$`_5kdnLPC!$P&< zhCyS%K;Zv64FBiXkUU`jHhTJ0?h69=^-KXc+x|Pv&KY6XIbnlTrQ2P+JoEZxZ%tp7 zZt$C>{nO_pa+A|>-Q3wT4`E6!*)|l}<)tovsy$_d1ryr8XUn+h_73U&v2U^F{%331 z^y*WkPOWD)4km%8k-$ImzBI1VA8!mi)T#Bb`5wYO5whBA7=C^Hu@G}GW@NSaeZo>t z{ezctBtUs>fYr=JN>IYI&g+k{dUB^huZ}qfH1!M62Wsuf**6*f2*F-NL9l7e=x;k~ z3t=kMN|+m{EmcTwKM&em+DF4!H_L5BxpYBbo_+*CT^B7mD;Cr0=Wh$0;o07A!%LaB z0gPzai`r6Ar-EoalZUy*-KUIYZeaqaFdrmU)a>BY>?lo3Djsl17M3Qf-gZ!6LP}EN z_sqT%o(JYV{h$vbZictlM;g+6C@A1QemFc;LT`1RkUlixzEO_!Wh@1j8~$3?d|mObR?daH6EGJkBxJsN&D2eEuf%kXPoAOrE; z8~0U;C8MK+CU*W|TpILpp~HHT_d8i-kT#%Xf(t+WUDJcC?&8w2;-rq1W6dwqRLK_! zo%6*~F&+tMlcIMUVp=d0ExfcPps{0P~A4*rUO5MLb4qD7vyG6Gs) zzTp1lg$9y*b*t3nHSPfR1#=8dtB7MC;mxY#EI+Kb8uD>;uG*Q(*gC}-1=z3*Oyi5h zE0Z68jI<}!Cc9S;%(~NkF6LOUwF4Os z>{v(j!Rx|rZ=j>V&ST)=xM>HJPk7U_0G`%kBBdx<3S^tfJ+oNwjS-Nm;fa3;6?71& zFu;=LxrhA;W3nLQfu3mrBfDGuK8r*bm^YM2J9QZ~FeIFx|Gp>$bQ@4n@~bNXGR309 zKKMVG4lY2*OCoH0bDn^J&mKlV^M<(JC;!QNJRK0y2d5)NDHaTT#+CvB{Au28EC2f^ dVK(@dybIc&y%%Y&1$ZxU)ReWJlqy Date: Tue, 16 Oct 2018 13:13:11 -0700 Subject: [PATCH 61/71] Add a couple sentences regarding QoS for action feedback and status topics --- articles/actions.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/articles/actions.md b/articles/actions.md index 90a3e97e1..2e5ffebf3 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -270,6 +270,7 @@ This topic is published by the server to broadcast the status of goals it has ac The purpose of the topic is for introspection; it is not used by the action client. Messages are published when transitions from one status to another occur. +The QoS settings for an action server can be configured by the user. The default QoS settings for a DDS middleware should be TRANSIENT LOCAL with a history size of 1. This allows new subscribers to always get the latest state. @@ -290,7 +291,8 @@ The possible statuses are: This topic is published by the server to send progress feedback about the goal that is user-defined as part of the [Action Interface Definition](#action-interface-definition). It is up to the author of the action server to decide how often to publish the feedback. -TODO: Something something about QoS specified by server +The QoS settings for feedback coming from an action server can be configured by the user. +It is up to the clients to use compatible QoS settings. ### Client/Server Interaction Examples From 77216b1d954b49563f462983f97ee8e9cf632594 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Tue, 16 Oct 2018 14:54:13 -0700 Subject: [PATCH 62/71] Add section about using multiple topics for feedback/status in 'Alternatives' --- articles/actions.md | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) diff --git a/articles/actions.md b/articles/actions.md index 2e5ffebf3..63ceffbed 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -337,6 +337,27 @@ The default middleware in ROS 2 uses DDS, and there don't appear to be any DDS f Additionally implementing actions in the rmw implementations increases the complexity of writing an rmw implementation. For these reasons actions will be implemented at a higher level. +### Multiple topics for feedback and status + +When there are many goals from many clients, the choice to have a single feedback (and status) topic per action server is suboptimal in terms of processing and bandwidth resource. +It is up to clients to filter out feedback/status messages that are not pertinent to them. +In this scenario, M goals are sent to N clients there is an unecessary use of bandwidth and processing; especially in extreme cases where M and N are large. + +One approach is to use multiple topics (distinguished by goal IDs) or the "keyed data" feature in DDS that allows for "content filtered subscription". +This would allow clients to only subscribe to the feedback and status messages that they care about. + +A second approach is to give clients the option to specify a custom feedback topic as part of the goal request. +This would be useful to alleviate extreme cases without the overhead of creating/destroying topics for every goal when the number of goals/clients is small. + + +Reasons against using separate topics for feedback and status: +- Most anticipated use cases will not involve many goals/clients (premature optimization) +- Topics dynamically namespaced (e.g. by goal ID) would complicate ROS security by not having deterministic topic names before runtime and outside user control. +- Added complexity in C implementation and client libraries + +It seems reasonable in the future that the "keyed data" feature in DDS can be employed to reduce overhead in the "many goal/client" scenario. +This will require that the feature be exposed in the middleware, which it is not at the time of writing this proposal. + ## References 1. https://discourse.ros.org/t/actions-in-ros-2/6254/5 From a6144c76a74fdea45b39c36629fdc9e1e67f9747 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Thu, 18 Oct 2018 15:30:40 -0700 Subject: [PATCH 63/71] Fix logic in cancel policy --- articles/actions.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 63ceffbed..cf330c188 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -243,9 +243,9 @@ Whether or not a goal is actually canceled is indicated by the status topic and The cancel request policy is the same as in ROS 1. - If the goal ID is empty and timestamp is zero, cancel all goals -- If the goal ID is empty and timestamp is not zero, cancel all goals accepted at or before the time stamp -- If the goal ID is not empty and timestamp is not zero, cancel the goal with the given ID regardless of the time it was accepted -- If the goal ID is not empty and timestamp is zero, cancel the goal with the given ID and all goals accepted at or before the timestamp +- If the goal ID is empty and timestamp is not zero, cancel all goals accepted at or before the timestamp +- If the goal ID is not empty and timestamp is zero, cancel the goal with the given ID regardless of the time it was accepted +- If the goal ID is not empty and timestamp is not zero, cancel the goal with the given ID and all goals accepted at or before the timestamp ### Get Result Service From ad1b326c05ebfbbb2496c7dd0dbca7cbe04398a0 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Tue, 30 Oct 2018 17:34:20 -0700 Subject: [PATCH 64/71] Minor clarifications --- articles/actions.md | 23 +++++++++++++++-------- 1 file changed, 15 insertions(+), 8 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index cf330c188..c4c0a9307 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -39,8 +39,9 @@ There are two entities involved in actions: an **action server** and an **action ### Action Server An action server provides an action. -Like topics and services, an action server has a name and a type. -There is only one server per name. +Like topics and services, an action server has a *name* and a *type*. +The name is allowed to be namespaced and must be unique across action servers. +This means there may be multiple action servers that have the same type running simultaneously (under different namespaces). It is responsible for: @@ -49,12 +50,12 @@ It is responsible for: - executing the action when a goal is received and accepted - optionally providing feedback about the progress of all executing actions - optionally handling requests to cancel one or more actions -- sending the result of an action, including whether it succeed, failed, or was canceled, to the client when the action completes +- sending the result of a completed action, including whether it succeeded, failed, or was canceled, to a client that makes a result request. ### Action Client An action client sends a goal (an action to be performed) and monitors its progress. -There may be multiple clients per server; however, it is up to the server to decide how goals from multiple clients will be handled. +There may be multiple clients per server; however, it is up to the server to decide how goals from multiple clients will be handled simultaneously. It is responsible for: @@ -153,7 +154,7 @@ Actions, like topics and services, are introspectable from the command line. The command line tool, `ros2 action`, will be able to: -- list action names provided by action servers +- list action names associated with any running action servers or action clients - list action servers and action clients - display active goals on an action server - display the arguments for an action goal @@ -176,7 +177,7 @@ There are three active states: - **ACCEPTED** - The goal has been accepted and is awaiting execution. - **EXECUTING** - The goal is currently being executed by the action server. - **CANCELING** - The client has requested that the goal be canceled and the action server has accepted the cancel request. -This state is useful for any "clean up" that the action server may have to do. +This state is useful for any user-defined "clean up" that the action server may have to do. And three terminal states: @@ -238,7 +239,7 @@ The QoS settings of this service should be set so the client is guaranteed to re The purpose of this service is to request the cancellation of one or more goals on the action server. The result indicates which goals will be attempted to be canceled. -Whether or not a goal is actually canceled is indicated by the status topic and the result service. +Whether or not a goal transitions to the CANCELED state is indicated by the status topic and the result service. The cancel request policy is the same as in ROS 1. @@ -257,9 +258,15 @@ The purpose of this service is to get the final result of a goal. After a goal has been accepted the client should call this service to receive the result. The result will indicate the final status of the goal and any user defined data as part of the [Action Interface Definition](#action-interface-definition). +#### Result caching + The server should cache the result once it is ready so multiple clients have to opportunity to get it. -This is useful for debugging/introspection tools. +This is also useful for debugging/introspection tools. + To free up resources, the server should discard the result after a configurable timeout period. +The timeout can be set as part of options to the action server. +If the timeout is configured to have value **-1**, then goal results will be "kept forever" (until the action server shuts down). +If the timeout is configured to have value **0**, then goal results are discarded immediately (after responding to any pending result requests). ### Goal Status Topic From a4397401f83ebbb9dab22c7b04f35902909c950a Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 1 Nov 2018 15:38:24 -0700 Subject: [PATCH 65/71] Add topic and service name generation --- articles/actions.md | 58 +++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 58 insertions(+) diff --git a/articles/actions.md b/articles/actions.md index c4c0a9307..94d3a1c63 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -328,6 +328,64 @@ Here is a more complex example involving multiple goals. TODO +### Topic and Service Name Examples + +Topic and service names for actions will include a token `_action`. +The leading underscore makes the name hidden, and the combined text allows tools to identify topics and services used by actions. +Topic and Service names will be generated by prefixing the action name to one of `/_action/status`, `/_action/feedback`, `/_action/get_result`, `/_action/cancel_goal`, or `/_action/send_goal`. +The resulting topic or service name is expanded to a fully qualified name as usual. + +#### Example: fully qualified action name +Given: +* Action name: `/action/name` +* Namespace: `/name/space` +* Node name: `nodename` + +Topic Names: + +* `/action/name/_action/status` +* `/action/name/_action/feedback` + +Service Names: + +* `/action/name/_action/send_goal` +* `/action/name/_action/cancel_goal` +* `/action/name/_action/get_result` + +#### Example: relative action name +Given: +* Action name: `action/name` +* Namespace: `/name/space` +* Node name: `nodename` + +Topic Names: + +* `/name/space/action/name/_action/status` +* `/name/space/action/name/_action/feedback` + +Service Names: + +* `/name/space/action/name/_action/send_goal` +* `/name/space/action/name/_action/cancel_goal` +* `/name/space/action/name/_action/get_result` + +#### Example: private action name +Given: +* Action name: `~/action/name` +* Namespace: `/name/space` +* Node name: `nodename` + +Topic Names: + +* `/name/space/nodename/action/name/_action/status` +* `/name/space/nodename/action/name/_action/feedback` + +Service Names: + +* `/name/space/nodename/action/name/_action/send_goal` +* `/name/space/nodename/action/name/_action/cancel_goal` +* `/name/space/nodename/action/name/_action/get_result` + ## Bridging between ROS 1 and ROS 2 TODO From 1ff406da8c786393feaaf21e138ed98cad63b317 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 13 Feb 2019 10:38:31 -0800 Subject: [PATCH 66/71] Address feedback from review * Update authors * Update description of Cancel Service response * Minor wording change related to feedback and status topics --- articles/actions.md | 23 ++++++++++++----------- 1 file changed, 12 insertions(+), 11 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 94d3a1c63..d440fe439 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -5,7 +5,7 @@ permalink: articles/actions.html abstract: Actions are one of the three core types of interaction between ROS nodes. This article specifies the requirements for actions, how they've changed from ROS 1, and how they're communicated. -author: '[Geoffrey Biggs](https://github.com/gbiggs)' +author: '[Geoffrey Biggs](https://github.com/gbiggs)', '[Jacob Perron](https://github.com/jacobperron)', '[Shane Loretz](https://github.com/sloretz)' published: true --- @@ -54,14 +54,14 @@ It is responsible for: ### Action Client -An action client sends a goal (an action to be performed) and monitors its progress. +An action client sends one or more goals (an action to be performed) and monitors their progress. There may be multiple clients per server; however, it is up to the server to decide how goals from multiple clients will be handled simultaneously. It is responsible for: -- sending a goal to the action server -- optionally monitoring the feedback for a goal from the action server -- optionally monitoring the status for a goal from the action server +- sending goals to the action server +- optionally monitoring the user-defined feedback for goals from the action server +- optionally monitoring the current state of accepted goals from the action server (see [Goal States](#goal-states)) - optionally requesting that the action server cancel an active goal - optionally checking the result for a goal received from the action server @@ -201,16 +201,16 @@ A transition only occurs if the action server *accepts* the request to cancel th ## API -Proposed examples can be in the respository [examples (branch: actions_proposal)](https://github.com/ros2/examples/tree/actions_proposal). +Proposed examples can be in the respository [examples](https://github.com/ros2/examples/tree/actions_proposal). C++: -- [examples/rclcpp/minimal_action_server](https://github.com/ros2/examples/tree/actions_proposal/rclcpp/minimal_action_server) -- [examples/rclcpp/minimal_action_client](https://github.com/ros2/examples/tree/actions_proposal/rclcpp/minimal_action_client) +- [examples/rclcpp/minimal_action_server](https://github.com/ros2/examples/tree/master/rclcpp/minimal_action_server) +- [examples/rclcpp/minimal_action_client](https://github.com/ros2/examples/tree/master/rclcpp/minimal_action_client) Python: -- [examples/rclpy/actions](https://github.com/ros2/examples/tree/actions_proposal/rclpy/actions) +- [examples/rclpy/actions](https://github.com/ros2/examples/tree/master/rclpy/actions) ## Middleware implementation @@ -235,10 +235,11 @@ The QoS settings of this service should be set so the client is guaranteed to re - **Direction**: client calls server - **Request**: goal ID and timestamp -- **Response**: list of goals that have transitioned to the CANCELING state +- **Response**: response code and a list of goals that have transitioned to the CANCELING state The purpose of this service is to request the cancellation of one or more goals on the action server. -The result indicates which goals will be attempted to be canceled. +The response code indicates any failures in processing the request (e.g. `OK`, `REJECTED` or `INVALID_GOAL_ID`). +The list of goals in the response indicates which goals will be attempted to be canceled. Whether or not a goal transitions to the CANCELED state is indicated by the status topic and the result service. The cancel request policy is the same as in ROS 1. From b7ac32a6da228fe6c48f8ee5b4b88411d20053d0 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 13 Feb 2019 18:34:27 -0800 Subject: [PATCH 67/71] Add sub-section to alternavtives on action server goal ID generation Signed-off-by: Jacob Perron --- articles/actions.md | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index d440fe439..112a1bb8a 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -185,7 +185,7 @@ And three terminal states: - **ABORTED** - The goal was terminated by the action server without an external request. - **CANCELED** - The goal was canceled after an external request from an action client. -State transitions triggered by the action server: +State transitions triggered by the action server according to its designed behavior: - **execute** - Start execution of an accepted goal. - **set_succeeded** - Notify that the goal completed successfully. @@ -415,7 +415,6 @@ This would allow clients to only subscribe to the feedback and status messages t A second approach is to give clients the option to specify a custom feedback topic as part of the goal request. This would be useful to alleviate extreme cases without the overhead of creating/destroying topics for every goal when the number of goals/clients is small. - Reasons against using separate topics for feedback and status: - Most anticipated use cases will not involve many goals/clients (premature optimization) - Topics dynamically namespaced (e.g. by goal ID) would complicate ROS security by not having deterministic topic names before runtime and outside user control. @@ -424,6 +423,15 @@ Reasons against using separate topics for feedback and status: It seems reasonable in the future that the "keyed data" feature in DDS can be employed to reduce overhead in the "many goal/client" scenario. This will require that the feature be exposed in the middleware, which it is not at the time of writing this proposal. +### Server-side goal ID generation + +Since new goals are created by an action client making a service call to an action server, it is possible for the action server to generate the UUID for the goal and return it as part of the service response to the action client. +The action server can better ensure uniqueness of the goal ID with this approach, but should still handle the potential race of two goal requests arriving simulataneously. + +On the other hand, it would be nice to expose the method for generating goal IDs and let the user correlate the goals with other libraries/systems. +Imagine an action client being used to request a robot to perform tasks from a database where each task already has a UUID associated with it. +In this case, it is still the action servers responsibility to ensure goal ID uniqueness and handle any potential races with concurrent goal requests, but we have the added benefit of the user being able to correlate goals to other existing entities. + ## References 1. https://discourse.ros.org/t/actions-in-ros-2/6254/5 From 0baa62656fa3bf2d348333574c15659d419e834e Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 13 Feb 2019 18:36:33 -0800 Subject: [PATCH 68/71] Update interaction example diagram Add arrow depicting user execution method being notified of cancel event Signed-off-by: Jacob Perron --- img/actions/interaction_example_1.png | Bin 26015 -> 26738 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/img/actions/interaction_example_1.png b/img/actions/interaction_example_1.png index 9daff059c45ebb0f0b17af39f32a88d6c66627ad..2e5bc373a68546a2443d6d0b52798b93b53e4abf 100644 GIT binary patch literal 26738 zcmd?R^4bq|1rV$hg>2B$e5a}*akPeZM zKG(wMdEf7O&pCg=`QiS2yiwM=a?UZw7;}YdJy0gZr^ZJ^LnBmGQ9z=hq33}Aba1i3 zPkP5*Q=y?TqNys#K7M7g{SK$@J!b)H-r+&r}y?1i2ZE z?k#m#AFK_#j6GEDeIvYZch<4d;T;pq;#BvdMEK&2;a9HT(pqL58J)|lLv61-vE*Z) z-XbN%_x6(|E<>_7y)S1Sblt;}FUOnvHLjkW7v@l~9y%rB-C|WYbR7_~ZV$q%M)ht` z#CB1d8cCh+$?HEW@7lm7He${7Gk;OLZhGfJs}w16k(T3iyfb=#;g#jI+obU(d8FBl z&+)u_|EyCBcan*x?LB^NgBUOgr1}-dn+nsDTt8nC{gOV$?*~qaFSlnj8c%+uIS}Ua zi%@EB41JJaiIFFYbzk(U{d8QBPQ}@Kz#By`ctP-yVM7}~&#&^u#+dC)KW~dssR-8O zj>i3Ig^hgajpC*@cB8j4hZ78k6AN5xi(E``QTW8hzt&dLtP}OuV%BEYsr8(;37af8 zi=lt5KP1hZ)9RVOAQk6n?_{=dKVIa&zndA0G;4b7#Gu+#Equ>S09ha~s6cTrsKQ=m zQcx?~urNcD+(5-{osN<^U1Ns5cKbr-K9(6gGF5K5GGXYHP`{dCs2Rg9d@^D9Ofm{b z3DK3MvvhuVUuDwJi?c||n$pziBKD=1Q{57_=)sWuN>SyvxSwyuAApl0<#Ba!yb>kw zZRp~agrRfWjsBfHD|EJuS6N)Ob1sB&$klJ}R*q(!l1iIT5vKEAyG<)UqosM&h%!AR zi(6Il^*Re;q_?B9@tKme6`QJSxylOmT$&D*;WOfATa^Tf3WYkwxyMtAl*ZX#!iqod z_vIh|P-T0^!fjAx6N3^l{4=U4op7?6X?l77N7G~Vox4>Bp)i*k#s7GG3mJndc_&YO z1X#6R8SV8h&&_B=RV@tp`cs43CaW4(c~HiJOFwsQ4^t#p7RBw7YE7vVg$DOs9s=&F zm}iv(_dV&?1qLNPerYW(YsVk0_Gez&Y2204f8IszM$ilXSdy*a;q>`;$oZc^>53V< z!d|{Fw9M}FZb|g!-B*n-)|qaxJs3L`(YUd>zV_Dg6vqv{9^u?u!2tWuF}x6>vYuq>8!P2=+G80l$@;VV z&FIH2Y(na6E0;mZ*4xzkckov*EzeEN67hXkadZlrY}ENx%hhG!ZkdPQ*r$gAy$8$jn!k!` zKU5c4jF0}?tpCr|G;ryKTOW?=PJXPu^L5hDNm6t*-E}!XFC%V1c+tq%K4t)uSmJ#) z*29&C^E%|Gr-K>$;QSQmh#(E@i>s|_=U>JL5=-f2wj53vx?CJi_Vf31{ZvGJuG}an zw42vcsON_{HG9566&yUDC`d(kvsBwfYBn8Cm@uf@rQ|J~ek9xOD)0aUNbok=m~X5- zKW@3wKAu9cKU!Y!+D!m6eKhYF7PpMKSHg< z;FE@akF%PLqyxL2@6@l_<$ZSqf#hP$`nU~;p(iVnheM6K8g=Qj;ITUHkIO|e@#0sq z<=b^S{V-JB@CS$4nug1K0OkoumTgZmS_s?>HZQ@Dz|mv|Jpe zZGHapZRCSIPHFP1CwPlK$L~_}6@s%#OH`uIFOC;o+HO#OG9`!0@St8RN>d!6-C7Ai ziKNhEF=bay30n1#7(cf9P%-y7JUZJbh2z9`X50E<64e^Gl6lPs-DCnYZ|TJCYUo~0 z$-bPnrkn=hjK-_Dt);TZd%u^>K4bbxnuc|o;%KwaSw&xQcfakivXB)|-djY~@n&hu z#QWE~EmtPLQtf%*)Tf!{*qqpfc)B#p0dAdQM3$r3J26e?J_k#$@);1C>_KoAv)C7vhmgRI4@NaNU*X`%y~R>_pShd~POf!n z)6s|-e*0v8yby19k5Nk9pHEs%G4|B?7WN2Y>GQIeXbhsQ!ii{+-^?)e43;9s@IIly zMV!QY0|!US)CC+5du29N+w;G__rYaNx?Q2FK=4bXGS=l0Tq@4Rx?uUtwl>Lz$$OpV zSy_PZGeS5kyMjnPrZbHAeD|wWziJVt#MSv9&$N5tZP@b`aTK12M(Lua56mQq-sH^i zB0`GU`|~dztxuL_p07$@r7XDIp$cIu$-s?QuCCE9wjz9 zA1Q1GkIr%tJMs3J^3XUqFQ(j2cF2FSJyiWd?^P6c`%F9;zAxPF5&pn}H9~uEx5@J` zRo3PpZJM2s8l+UmWgCv{Uq)sM48u83b{0FHgPuRD0PDBGwtE|E;vMPB8+BPqgZ zqW;jC*TR>w;8wd;Wx771tI#SnkdfkEpumUX0|tUNF0S|~^JqgtIwte!9}60(Q#%Fa+JggfsqVDj?9TJToSc{(bS-0Tm9Q^*mPY<9ufrYh7)ky;gQ>n~PDefQLoq8?FBI1v=@3jJH}i4X zmpCljh#2lNP<{yR{PO3_zO*TqrrL$K{3qr&WyDvEllQPYWDF-ONv1ps0W5e-syswD zjYRZpK;UisCiW*sF1xCW!f;JJ^@hs*RK7BhENpLV3L-hQZz!_ev^5$>Uosnzp=asA ze77|F&!nnO*>2K@wI_#xwqXw{^&&wGAzV_U~PNo5sI4ePAc zRlg4_U&ioSQSv{xZg62#W_49xNS=~aKRF}U6M&(?M5 z>#n469Nm;&eAM*_4u1*zx%f+-g(V4>^-0vt%es4EWtO>!_n22-;N2E{JY@Inj6GHo zPW>jLjOv&wXU=w8Oc!C&%L-EGt6!;mLvJW~O9>#bX?_J?vOr?Aqe(De_x{$`AHHC)G-i@tG>r_l)7J4zxM+;EF(_rJB`+{ho{m8)}ae&~#U@7aB(HcfmF{cSbzn}>d)^4n&x>361y)vx0 zgM-J)w=PQ)=NxXW#KaBe|4>4VZy66Z$epQ3bn%E90yJv%zTm(Dpi#^1fm%tdT3$!4 ziPODbv@SicjV!lgI9&7Wm(}*1!@Xxzj1BSJc&~itq!ZD~Jg3RZ2BpqE3F8pV*Y_jl z=>rv`(^CH&l@;kLnR8+unjhW@lNaBwCfA>@!LxdD#n2{KG*0HzH^aS9?p;Cp#%K!~ zi}vYIWPWaWbarw@MNBP#@Sd4thJJz*3v#paxJyqRNNagFIYDr#iPPM%U6kmrB@D5~ zt6`E+A?Zpqbj-I;taCnD=Yl^?DKjzNIJ)zK=p^QikS9jJUW9-0tD`yB!S#hm9_F^dw6)hQ5%U6OkS{7#PFGwjc-mIH`*oI-jXx+vhQaeP^M7G|! zf4G`)WNbsDUY@;dWS{da`Zqks+hJh7KdA~u%l?~daf0p$_m}v<99K?RbAVEg?H03b zm4B2q2wfoylAt(xQ(ZfBL^5F>cF=jDL{-FIz70RN+LoI&6S5v;s?~rv zFFuAAuWYwCeVb49*chh9ZffXStFg=spL+#H?IO5n`%4M&AsRz;U+5^-sz~%rgrU>6 z!|fRAr=PA@^< zF56iwc-cTO;oLIuTSFc{pg$4 zjS1Qy`r#9y)Cozu(A43SRK3 zHNM==EoY{`HGp&={jM%^B(Y4dXK0wuVJPk;4ocz3a;NoNzh)KvX2f+V{4rX}lln`M zvr%-;3{z_}&I4h0SZ;Mfu2{9}m)Lbvw=%~fiqV#Cl8P2xGIUS~tEY=Rr>4miX}o^^ zXPIv#Mpm(kcAP5Y_D^Bc2c;4I!deOcyGXa5sj?l-c=ZEM@@||w7xy?e`rBJety)BQ z#kE$ax@Yvl7nQ$D6AhBbq~Y)&*j&tLndp4-Xk&aH{UmZKd9ypTPYO*=YPwb{I%xTH z@}TrI)$#OL`m4rO`*6#8c96;z^{>CaZ#hgs*?OqrtCk?^FNtrY(1X{yggpDl7P+6a}IwKtUGKM%%Zao-e;OtM4!r)s6HTdbNIeY?! z!AFSiHszDzCVYup57A!~IE)LJ( z-&^ltVkjYUNx=Kfzz^CONeJ1yteUYu(y@jKW90fRXz6$3Gm`v!7WaX+%+ul?d}gy# zU3359zu2T}YrmgZbS=muI{KX8d{`|5oRJ{{MQyLe*dC!JDTyE0bB?UJo~!;?&|)ZzG30 z*Y9v-)VxN3^+EuN|LBW)K@^N+^nDE9nuZbSznLX})jjL02n9=gbjrmVZaLCoqr%R5 zqq63DiM2{`@34>C4;nTSqJu@oB?*B3_K%Q^BwsAGEZD@y*@^!hK7mj5W5>cqK`iwv zM907a0w*9DVp8bdl_581p;Z>!?Nh%m{cl6~O$AQ0$Lfc`HkF_WIr?7j__!Whk>~YZ z-URD&4~alm;B5cTOzE(|HY9(Ye9;nlP|4H2QA`6 zpy@`a3KVk-$us84et5!Y&;@7y&z_`|!tHaL^aQ{#?Xa7)xtRVPs?`6#AF7B0EGkg0 z(|Rn&R-ElL_M3;&C7QJ9#9beAa;1NFOXK4pEC+;RArYh}C<${czr3{-Hpzh|-EajzSxKpR=O`h;Rd>7p(3A`{o@+ zh)_uP+{oXbcVASkd@`{7O?(#>O7E$%;QdFVeygH?888?zvVqvDlO@K7@8F4ga{b9( zJM}B^no`4JVlUPh=NsHcTYUa5g%G@DlL&}3VVMK9TkPP}31V#( z8!-Jlb>+#WV5t&7x&9Exmn#x5#(kjbem~I#RWpD!%ig%mO>^YPOLvKQu`{PHb+#p7 zJ6(~J?t8jkvDZ$}kH?lClZ1M;8>>toYv|OZP4D~H98TqH>R7)rHsHRVlhn7|8*lyb z&HXqCNn#VxesU{rI+{Un#Jr7vv-(+?sw0$mvSrbAP?G=I)IE64<;9s=rj*Ze`4{^5 z=Rdo9e?;=~K)e>&-4jc-@-@?E7f9aie*r=dwF>}clJCW-23t@tg@H=*`Mw%F8*HyW z&*wck2ae9sY}H%UT0C{%F{;xcVyIf{f%tY6wkqEKcLv)??i#Hh_TvQ!AcZ|l1PpPC zm|KCt!*68vQ7A`HT6q9I-0IJOaFX=Z`J?VADrVt1=fEOx0xEuY(-d-T7T0EY9}FuG z$04~+pKjm7vU}qni!AnH%=0b63%enFha~_WbVeXd!y~DT_`=}#nX6$fi+}c6WiMb= zc)p^(N&Hby@j04~WPp%K@kh!CX5WrHi3oOSMaNk~llnsI+5^fiHo(d}Osz?{ev{ zb!gYNVbgqCk+tB)ZfCT6BgDdWCoHlRXU-dNXEj@myUo;3E&#Q(aeB*MRMPVx=GQ

| z8vxfZj?cu)({Q}#XNva%Y{rBTkBUoi^+epmk4pLE!HuzZ+X;o|v=-%?^}q&EssVf? zetn%=tC9}yV30ab#xi0}Jk0&KonE{=0u9LHn_Y^9;yx_OF;_wO#d{L^f`gTcJwL^cU5i|ceH zA;hkc_50@+f=vm9jwM#+RKh~MtO7-*WiP;MCxVNs|5o%@vO$>ExR`#WCEYG4_$EpI z8oSR|-*qV{DAP%Sk-$JwCw*BUl>Y)NE_)fl=fXj!=`~7nmm)wtj_mT$V&?*t+O)D+ zc^5@Iw8%dQKM=WBJ#w^Gppg3Ad21v`jnYXJm#5qc_c1lP>!LRGl2YHX@fb5h+Cy$@ z2J|CKQV+fL&QvmcRRuoQTf=XQgvx7bzw-Cnuvl95>T1$(ez|nS6%3J4Z%EWv15{M^ z*x02BK1ThHxUy3EbS(%=cCpQv{!Y!vI`S_=LvO1I5P9wE@+U}Q~w9@W@@(qCye`r|!dVe&GKTx9 z4xcQ>GArlm_?F*zemn_e0jpMj^sZ*RlYW`jId^OSr0&8TB7EC12kSc+IU5W#E|hv^ z=uN3C#V-J*+*>&)#VNe->Z8Qbl%>nrc5Odk3Nv+nD<*XebaNJ!y?(K~(6r{h9Xvw1 zH{Ls9|7juZ3A;A2eIYv;mN$<7oOk0^MPyO!f~Q^Y=kxvk_E;sO^q%}>+NYh>hZ0|I z0G5BY7nG;$K!HkcI5PqK#rlafND~7son&fjLWe-~iB5NJ$8!N(c`rDktUjj)!EdV>VS_pud!)JUc4+vlJa`T$c>6%nPyy*MNdEcR;bxxV z_YAM|-(L9`n8aAx}6Re$5?`1!#A^ax0wsQEU>ASCTAc9v6sj*sW;r=B;t3R2k zao_|owDw?QT#ZOu2 z3gAQjDZi@=>%!uiIEdF|lv(I{H`(mtRe!osm>{?hS9$yAk}(zJR^30wZsXeR)q5ng z3V5*RgkOPF^3j7x`rO&$cNeAgH__FxSr2y0%ahe43T^{jwqoA;<7`5r)WN=hgej`1_aHwQlWxk?mI;*KsGw`ED&`gM<~;KWRo!}bgZ8d@YKCm zPrfG`j?eiFfS5^Ln3xKQTEu?+2Z-<2L3YiYfvk^0iAWE{!L&G_YZsB;q+5%Nl0(E0 z2TI7IvFun;^H~HLXpj)t^VQ9j-3!Y;+v^~PNc^~^j?lrFE7YS0vG*Nj*2WK(P3`h? z4tChA41naklIGO>u-4$}@?!j5EyyA4y@IF-6E6p_3TjpmI?$B9cnqo0P_8ek8bP$D zj#JwgeJK5N2I!)EiaXMi2KL-;+r~hlv#W0cSb~Gn%BGj(E;%}L4l=fI#H&d9Uc7aU z=ahMD+ZFYr}^0Z+6>?C!MF{4`0_|!P-C$*K?YaJf3q+aMm&Pal4Q%X?L7& z$X5)N0Cy&>#MJzqegO~0ubye?=Kp#DnhSXr1jcpxz-fr>FQ7+S$VyNknGiQCtXm6T zS`2MXm4DRfZ^bXcBEKDv7?#HNGP2Bj_cFC%vFv^s4@80jk*dk8n5*S{AAudyS3PM` zxG7S9!fpwqcWnzjuz2H0*y&Ew@xm=!0s`!Q?AH({H{Jk~-l>rbH^b{8CA09mwW$D9 z$$A49z^K+3Sk^7qxlv*?0I)jN{&6n+78^&tT*d+0P8VnCXXIk}V@WJ;w+c_P1e17u zM2@BILE7JWeF>fkv9NHIjWogG&8(ZgQ zxaS+&i{2?L->!6ja`06|->C;s@yXK!{GJCk`ql~BRYicnw8Q0#9MEHWW@a_CL?!SG z0LpdsR53=CC$sXQMB^?*5_>Xm^(V7M?qxMY)%LoObHL4C&auyI-hVMRQ(ue?KPFT5 z-TXNaz9U2KT>*WmA)}32p1+)AaPhf#YzzZumUVyPMvcV;k-jnD95{HV7&&P)^P{Om zw>xHD?X}^!b*xz@8RrI|f1PFh@>J&YaskR*_=ZhL>VQ`3-eWAkj`z049!IHU+^?1ru4h)l9!;LE8}pVRt6p z9Tti?eM|q_e?!$m?^*8uY=&7S-*D=C!b?DEMnV`a$y?+Gsn4UZkn@-}2gYDr)hcoq ze>1&J^N;L@ap2II7`J?vTn_l;tX~YuCb49>prT<$N-Q-gip{o6`+?Z-8rckz3Ih7~ z&sZ^wI&Qo6y@t|lA?or3r8Wy&*C{s0=aE?sN`$DFV1IoCxkAQ}Nf8>Zf2UFhZ_7Cn z56@3JvV$cIhrczeP0nm+g;s!KN&k^e7>ZV3i^#l#gaPxW4rb*%WY^%P@9{@Z8(Lyv z|4q-sMKP66u;1RLXyHdt0YG%^sA~9?rN=#gbGJSEP12js>Xz?}{gn<6eo4^;!%UjX z)vEn@1(jVABzF?&urR4e#Rl}B^OUzfkkos|W6oV6di%9y_n;^CnZHdmGko9T;-Qqt zava$N=B7xI>j|rA#qWVt!_pN2tPOM!zwnRvbuc>HTM1On@c2f*41}l+#*!(Ntz|`S zwBP5st^PbK?~Y9*4Bq#&?2DKhYZ!?d8YRVtUOk&{NEaY)5F}A_uBqS=ggKjX@hJPM zB7YdGU=-dwX2DXwP*r20G@&@u*OLAb#(bc8-l7~$kH{dwn_{HNR!FW;t3xru=iaCy zEnw~!Jvpd_x-By|5ti;h$r=MzBA=e zWZnHwifSq}Qj~m!vGP%o)|yshoF`b=+75 z>QE8+Qg>TIu+Zw9d%8Jx_>$vSWkks{E(#;}BFiPI&V-E!u{xQW=|va#rQ)PjUqUZXSeU@+W?67`GH zGM~_?^YuSun|M~na%UMvSc^tTYG!UOTPI5w8E~vG&m{9&g#-IJ2EnV$`Qw|-SOjM1 zO9)GU)@1a}z8hjBDy=gVgFxhC69ou-JO}#$D%6Vz$*hMy@}4e+)R8{}My#N0iHbG%cJdL^7u9nc(bz_7aAfh zVyw+9oWE!U6>@9`9m+CdR6Zvgw!oq+BhE<-7lLPowLgi4StXpx zGlwkJs;&c<-#I(TI&iZjkzIJ`!%PK9m5dqsm+wQ$ws~_xIo>M*RBaf`62dAK$&cS& zl0S-G5yGOyQ0VzV!M3E|))1PGU*B69Wi+pc7-wP5BdL4qY)VQPD!wx)ef1bBp|mZU zuxsh<73=nJ3riH+BRcI|Rts|2F-Zf8hL@CBsPCCFA!B?Hb>|TpF=Qo5a)aS0E>w@Q zSy)atK(*vv0d)<%pr*$Y(^G!b8UrfLI6EUA|GT?B|Gyl^EL z%Xiv+nVt;YMH9G1R_U1$uXoRBOVp9i5flEr6;7j~8k|8)EvO=&pPv-$D-57&hb!48 z*RvOJp@Z}{S*XCQhDXeGZ~a@b?+^bN;aIH~R~M{Jzms`uMfp44rmG(EfG}KOT`%yD zhJv<%9WD9)s`FJ$^=(OZQqk^9I;JW{_=MY?PpVtC=B;ecQ>Z*( zybqqf3?!iuo-Y^V3K4fV{jfTBx_;k>UoA9QB{)N%M^=5T-)xl#SMfnuR8VAo`6}%~ zxP6RE91r{bv5F^hGB?g%Fd8A*2iY@Gh7Y0!Q?i|L*-OY?v@LZ91xh~AOWv`ezgM2( zI}y_StT*k&qG)gV0iF(%3g_Z7TcH@0Bzt`d#wKM9*_m^C7mB-D&{kfFu@Fy)2-j?6<15M%qA8 zo01wA$VP`@y_OK?E`#~6A{}bIkHjxlR;RzFh(Ym@gV`*Aw&*==*Q83r1Rg+8uKNSk z>u&T1JOJ^8J$QndRg;ypX9F!pwQSSK#?%=4i}Zg_j#tI15JR&f+Y+Ok(Vg`E6O5e~ zi?orn*ta4Bld`UuD`<2Ek$Ta|s4jHow zER-lvQt9#v7y;b-=Obv1%)LAy6*A_ z2oKv&gZgymefIK`d0;BShCj-0w{k%I@T*fjN|`Fk6JJH z#Cnn@Gv_!ppD5MLzcl1N0}zX(M4R=wD}3cGy`+JTzBTy?sCu%U7Ml&6A}P45($O)o z*WCJ{!qgj7Md;uYu1?ynQ$38>k1EJ3=3YfFvi~gWAc}{G z1jzhG<4_grO!}iW0JHinfc%Emf%pE5OM3rx=ACZ&`-5N_yd&s55xOD_=-1H0)YZ*} znq3=b727@_h>^I6dIXfK%$kyisAquw+XtYpFPYDBIfTYBW?a|Q7&6t0?)NZT1GX!^ z-11AJ27-j)N(HLW1p(qTsJ4RxJ0vP6$;1HEAO$*OfX3KVL#z$&N*$^*v>> zBD#JzB{iB70{uXRhy8GKQnUEBk!!D@b>D4c8nHiL1y*Wi9peF9zORkkn5(Zeu-22| zc?Sr(eGvBVK0MV!Kr}|uR^1ItCb;Y3jXl_SI4(r~@Cr^vp)l5BjgX$e*ap?{{4dtD zQY_z!K5i#vR)YL`1@;np+(m8IemhXWSC?tE%I%0Rv=R1rYVt3Ys2L#G-o1#E@t!nt z9XNPKEcN%j5fB3!zA4gu^HCmBXl?*ZiZSmrs9iayfdKKshbsg%j?Rd^wOLFE1ruJu zb7%;pJ?6mHH_G^WyJq&m<;Ah7+i=s><=IHC2FfVw&suloviL>nWqu%{Qx3}L%vBbp{I)bk0TWZ<^Bfs z&cS>W7ln(VsRg+S;901c(l;5k$>roZ|Tj(DI?tRHPEu$dS9Z-bVjpvd6A z0(+M3R`g%u(;v=lT&2w5^O#%KsDPz?3C7mG49knT&zQ7;@Dk|%PjD>@%Rm8%C3@%{ zF_Qjv@?G)E^4u=z<133y^0dX;5<67?CA-nfbcSU0BqNvbI5I26wa-o#+u!0~F|60z zAg{*s$X!lPBmklHBdzSG{E$`b1Vk5W5Rpb@a4zewD9?(f&YRt|KN@AxhClWOme1Vd z6A&u%f;v5^6K}~Iu7VOc>3cE8v*igcgD{J}(#7`RKcC-aA%6Fx5If z2#InD6uZXNLJnox8KPL;*Ka|)^DkLwkeW$T%F<%Fma%b}?q5v#{28xm)A9HPq9-Sa zH|S>Bw+*6`CEA$3pOv5eB4}=7H3Q@q#C*P|4)yXjz@{|zZaW&FG{{SqFlYW=sM~zf z?pUl!N&RnBbw^a-J#bddHQa0JRL-9FixlZzTXU5alX`~bClk+gxa4^Ahl6e!ryf9@ zaPR_w<)a5E%k56U&a4c{6OUU~M`-kP7@MaT4LbCnSRHf6i;5jbNCNuL6H7Pj8i@x_ zC{Agu6ox|cjf_p{=EZT-V+pAwy07cL_GVnAT#gn09K*#u9?SAu#Tws)JiWxC3voKtB z9WWj7zNtC7q~tx3wDyjh2y)g1EbFy>F^GH6H>hG@!HZFO%;18NsAA8-0|9tXum#19+3NTvTQQP?W6>WS^8lZ6{(N<;8qC(t1vnL(j|wXTYu z&*Qan>#^nWfbKfBJpVf}w~@9)=67Wr-=wd+>8$=3+iLo*VpzVh1`kUzY4T)Og>%EP z9dQYeGoVc)M>A7uv{c8uS0XR7k6?8Xth zHw-=3bKG17bV$EQku&9FZyA|+0LS&+6B6%X;K_#HU+$t-XPt9brgK9zz(MHQl;6j z8$*~xk(ccR_{kfpc$2ySlpVY`z}*7N!=8$2KHCwm&SeZ(*67p|eUz&{OcQ6^0FG~t z-_>P<)EEi7=(Ik~kKA9k9*D>~Id{{A3UzW105F&W+u)^I^G^t|?tcF01B+?X{s1MS zF`f1we!V4uaUJy#!gu2ILA^RoDC~Rws_9mQECoiddyeGt>oh{Or=YE;9dEygy&e>4 zS7j`J!@GhB2qUdQ;MLi@VKEKl_3CGD?V%PPp=Y#7ur_jFf6lv~f`)y>`uo=A4fh#H zB3-T=L2&j0o)|^~*o*iBp9k@5BIsGI7C+gxZD(tWB~F&(A-p&ZOm+Kx-`=#NhRZFL zPk?RQ?IL1y(bV_EI)U!ThX?l>)^pRAL97{XDff#oBg9~Ypen*WLH7jO?ZLtkjwc27 zNNQon^lud0R2W^1*I|}3cL%vIhft{HYc=ST`cHgU*oZ^@6-fyo_3V2VPL&FmZ>2d%GKkW-(2Qtcf-5U+_5NMY%M@(Dc9(NO7pfxS_h^^@ z&po9eBXi+I_WYrB;a22o6y)jzRKJ)jzn0#Mhv!ghfLagO{fGKD)f^zke~p z!=`+Y-H9zCXNre2prMf}IIOq`RPwu3zI+}SO8zm{uhFR0nop>&6+RYHnNnOL_7|T= z588YZ^#zmR_UxX>)6276w>;4=5oN*wgzmsoSQ}EzZmr>9&&eD6jCOKVZy%5iqJV5* z3`g@6a@%-JHwcwC+7F$)+aCN1jCvrtf}-l_opaaTstPOMP`qNYYZl7s#_cTe8#YAL z|FVxu7r_t4WaJ+D&~2*UT@dY~)uZP=_O7mc({w&IZq&@(ks^e>?#A>03+bMN7D7Z#7K2iqyeJe31+}q*Mug5y; z9dST!qGH$9|4`Jh#Y}ScKIVcxqVY!gCdd|Zr}o8#Xc*A9{OViDT-rkR0@Or80x+3~2gFh>Qrc>6_@#NM9emnELlK^UX|E zN=E3J=yHxsaFQ@+oa*z00Zh;=?~)Pqn^hblWB(<9M3Aa;7D$nN zqC|>;W*e;b9t~Bb=Wf%nRf=^YspE5=|DE7ht{Zd$fPO|-58C@w?V5PtNazhCWggr9vS@q?VCM=* z{)xTuZ2eEt9C956is+2|KnF^6QO%4U;vOiJi=AOlK}Gtw8C0Y_NHy*pw>?M55Olg( zs!PR~BUiBt+%X(ig{93Lpxq&-%5mOcu^zartF}M^VNCD6Crc&%a_fcK`cf#vM2jhq z-zw%@`p1nLD?j;l`9H~ieA6Itl7wV9AjK`TJI<-OyHEA!Zj5@~gLf~=fHv%Rqwoh9 z<)rLOAn86vGW{0cR9SZCxilf58&t;u0jzICjh7pO?FNd##$h6h zMD+QNsIv9mpfq~FEWf7+ghtd<45j_O6z4@c;CO&OJ@M6X`FCT&rF*%*CY~oj-b#rliKfnlThNz~8<$RD2{ic8bG)Ybam)F7C zhr~sRKVKicDY2^}g3|V+O|bSiv+T##t;Ha~T_?3dY^M6`paejryP=M@XZr#5@zJr@ zdq;e^Bgd^5p45X)^GquS>#iWVXO2Wl`|vO+8`Lq)^Lyc!;A3L0d%C69agZ?KtSy^W0*a6lH?bXVjq#)wJ-IVsGJCkPEc&x-y6S_9nuxm9nnho) zH&xHAmeCAsJ_K8Jk?W3K5VK4U_Y!ITy!wEOeMz%fZOm09aIX%F2xNsK$9;8HY?7=d zE-DOLSZnvw*HTfSX;v`D#rx^|WlJ34GZJ7bA(!0ZOGy>9&GNIv5e+}@&9uE(OfY=l zVGBKPG=}{Rf5ALYRuv;_l8wC7yP&!-qe?5>>~NqG+GeF7^}Ax?(jJnyDcIP?r8_S^ z7yAvGq~FC^>8MLGYDHX*WAaRNZ!m&nuejUXFXSrvh``07R@AQ%*i8ecytL@tY79o8 z#0n#fDvIiZLHL7?T~s?DT|^?zc*9X6-^I=f{v`;)4eCDRmWCFSEe-ITI|<`6kLjQ! zT@aWxj^x0&1`heD=DXwEP?C3>EvK@51;Gv!siOKLbsp8e3PpkcdI5eK34CMz=}WEF z1p~-KiExscnxw;GKpOGVVQ(O$}q)da0;p)o~ zYmgiE^k}0GNl~fX@z#0&6yV=8%OA@%bWYPVJ_82?_~qCfj8rnXp(%n zuhmDYXJD}|;uP43NWZZxA0Zv-awPwJ6L*qn`Xl`itlw*_`JmLd*9h%)SVd+2G1Q(u z(3B0rDxkcme>y?qqqX5MVR4K@WuXeZ^f_@&H9Dt)*%yQRyDxsOxm?` za3mc_21)(OjG#15Iv%F+2rnvM|BV8W~iiAg*gMTWq0#DYX}5QeFVO ze%}mpZ4jWqTm9q%EMfcY1iW8m5JqpiXGr{3`)uB7{E*{M0{$S{ri?&>NvP-j+F=5^ zLkZ*Jm?iqAEF!tbe%SrTr^+jrcI{HFpVXpcg7c{NCj>+;K<<)h5UaEk0s7FK1t|DC z&Qqov!7@=lP07qEQ5X+}=d5DL(magYk?Wwt&_GiUzHA$YVx(6I$Fwniy;bH|RuPvE znq*WFBydAq*h;-4 z9^B=FYuytA+rVai-Xw6m_`TxiE{VE)_81^KCGVm*i;c6QG9?S)5gGG6G&Ow6SwQ9&D9@HcP5(F^xN9I=CP8kcrAjOnvkQ>EjPTHtXv1Yf!8tO) zCZ;c9!D`c*01w~<)M#PfbMU>2{Kgou`hnYWue0?6?Ldt=(JS-^SoZScm~}`zT&>?r z#@wyFd`m5a;1+%0;51qC?pfVZ$SM7Pa56Z@a-DNlrwrF|AkNln8rS&{C)PDa`)l|o zxt{c%_T=5l@OolPo3vP@f72bWJS<#~Kqk>+(oN7Q16WH!1SUw$Q|KFH?>b1R&EM%N*v?xAC6D zi{VL=&vg+hD3QemXPVfDixnlWE^{BflRHskFGRT)U7q_G;V1UG69EK9^%%$H6qv(4 zw>U6NX1bdvmhX`4T}vJ4cYqA2@4&Mcj2#k!9c2N$>s-sVr+F(Ez7btHx4GhX%f4`= z(6W~gr-XHcAa!sehOkRK6Tj$&LS?M=LAF)p$k1b++5NK8h^EIZJz<{|9@L5ew*uE+ z*sO6H)w&NPOW6<#|3gggNxv6KwJ%db2ph~NFSBAt91VzJ)L6GlaslHRa+WFp&8tC+ht#(nJZ-=KgRD;}o*E4z+@2y?+2vB_360o6M=Y z05160%z)d`+`u77{p%NoLFKORdbTPDGYsew?uPXN2kf#{coiTgq=~Q*?flbB6v*3n8Ro1OH-E*PCRuXuIHzF70@1 zYxUmH#}f|LN0t3tWPXFT3vNI~7f67*vjW6R^3F3rrc4+Hv;P6@Y$I2coRdJ#I(TVW z(!?P4;*%L6_vgKKkCpchMgi@`U5S7S_>W$jV)q%(&=qTh1zr-f2y#n~ZmEgqxCAEu z@uTN(iR^OVcHY=MC$wOao*X^insyC2zd9N8L%nC@+jnik4m<~RNvZCbYZw<+Ph;Jm zx{XUo7w8e7;edI*)3aaQ!TP_<6U@ZGU3XDY97- zz$46s!?X^4+ozh}Mw$N#LbafcVK~jNH@a{ODja{bX&(V5qX$awpy628eF3x~QQ4hfhOj3=I`JXh@XdJ^BUaqb)yQ0M>{p(Ju$qlXzDzo?AApgZAiLJdhm6MFK+6;O|jj)5(FAeyFF z%Yr-HjT1NhoCF@|%;#cG{^;qSUjySpU$6-5?`6`G+;QxIgo^*GuJewk^8fp|y~{Bo zD+lM$;n>;xkZiK)$X-#|%HDg$iH4Po%rCNKMD~h8B3o8bLW%1BTu0yg@w@NGegEMP z<6Ot}xjyH7uFw1Rd_Rw1n}MMhrknNQwJcS|FFdthLHS~$z04FJm`|q9HeP^uPqozu zYN0g1X}VGfU)A^|Y8z%_#BEBDIDi)O-=5ONGoTMVwZF&-v5;wC8HWu@bRKd8%hlv} z3j?Qy1F+t?NV|hV#@pa5Hbu_?8 zIyfzIQzhU*&~TCSP3O^yzxItbf!gX5xQ?W=ond{S(oSf$-0!?t%e;1pHEHHj71#R* zIu)*8{GGlOg0Noooi_0W8tg6J99rwGZn6AenmM&FQR(ZT2fw9P%yU_-p0^qXx=YYA zpn>Nt2brIlmG6D^!mqoa_hw4b=4Lc$Ae!%I5e~YE%C*>)mVJvVr&HWzAe?m%JI9o&rlSJp%ru@ z-I%*9mspx8$9x^pb+0k9&oZ)JGS=FB5p+OZl`K?#C;U7Z-=XEh1Okw(vTIHd0vhc- zg-{0wC|%?QE6CWU&<4Bi&~nAEg~GH%Ru;?`^rY5_8+H0{Y7qNGm>a;#ovr?m;D4Fv%Q))+3V%#aq$r5h^$ax~3 zC4;ry>}Ligb%s3l{syaTdiHBrPrp=eRC1mUE-uc2s9}Kj@v~XFHgLbz>bo2{ng@dD zt=~FwN6?a5wnKJ3;H^{=hxn3HHbR$1=FP(>a6>gWvat#=)-riVLUEz7Tywq*e$x9`msr4e3 zntG<@EnFCjMKCo$H@0n7lam?l#GL%Q<7X>qol?#DPV!zoBIUg3u$Vq;y&`!Tvv{I< zOA(814f;{Lp{rn?1JF@B6O4!Xv!nH~eDuq2P|zsNBoIO?$|_1bqht)b)_Q2@%<_1UXt*M;!{8OI7eld0 zCcWhGCvWrW)V#Qg+J?`kN-t9&;ZDm<^bfD@5q?91iLo8d{QNxvRr5{}IB@D~v6xJ( zVZnthkfKGIEB)Mfn%kyiFUeDsZc~1wt!aok&zq=25KrMynXF7lKOS+1)?8^1iJV`V zwM`#Dz;4Grepd9s1G=ZmY6x1(bS_+thf}Z7q^YTh8u5v~wgx4mEuzI;n%8IU(U0o@ zf-;Y*D^ASZz-bW~F^IG_?6T|p70oWR^bt_N%Y0Sm=i*5%rrY{Nyg?w+`*EaMtnR{=uX$S zn&R|~;!D?dp?k0ioM3Wo5>CzGb-oI;FO^8(bHg+RpNGdg*;PCGjpowlKAF>({~9H< zVXxpx#zM?5&Pzdfy486eM0RaT=e!6Poay&fp#7S+q$J*sRJpJq87WQ4y%_m2A}q?I z{wmYeYZY8vz+ ztEe|!x)USce@3Wzz3Hk{<^WirD?ZzpDS6SkhY7%}l`@Tm+HsK*Dr>Z%DOQ*gao3D+;X(%>#SO{p7Vgp9Q+* z5h*X(=~bZU=C#Z{>lva{ zG^7KKJ=#pTMXRg%VkL@W=n*~Rvi-~GdAl`HLw=?jkv(x+hi{^EIiMbxr$YPaIKDL?+5MQgy~MzgP` zR!WjI1%qK%M7+WpnXGYZ8;Kyyypw#SFWqm@%4pC`F_V`G?navCP&%MdYP`A}O1sU@ zp{<_BG<$>l$Gahui}-`tt(E)yZs9HpK=3fejXY>NFc;{GzGChxNbhEDuG{ouLa&L? zvw2Y+eMuW>n6^lT4Os(|$?J9EH!JLdT83AYVRK35mt^{LiRZFf*J=0hP@jteJzz*@ zdLk5bV*~Xl+5%HrXB7H=`i@a$Cn{$LSx~u?{m>3-?Ddm75skGnau2eB}&!w;Pc;&`UEoea>ZgyPV6At$cmeKT`6D@{{M$xMo%!;ryDvJ;9NT z{_8dWS&2JfM<}GUeZPvG=xP6$5|InmE+_ruMEioQPE^^DeszjA$)~21f#BdzQa(pq zOx1Ar9A$WQ@B1t5z3KN1?J0_W_*+*G^!1Hh=a9vb>W0u0>DoQ#uM(tBoWJO=IyNu_ z$1KxGF~&NKvGs-%CWImsF^$Ez$@P7?NDS9ePTBev>eZTuMlNAoO3V7dw;yx7`h(iJ z$)h@k1(*nZ<>WPE}j?(Gx$c#VUks(>j zWtiE>WiVdJ_3mm4JPZE*(>?DoN+B?!?Fp}TX$DV7{3FiHc^8NuUAV^?;WaixyS~?2 zNq;ixetY^k(SdBf&VPR?ym_WRtm z)HNxRckjcGQ;h84&W9XgPr$BJM{1CRF)5p9`*l*hQPpq9ie}zhXJ9tRz=G!F-GA|J z%=J${nSVVpR28SXqL*Ef{Ld69Z%0CDDJ@xMi5Ern)JTY2f1Gc}93v>kN}!rYokX*8 zW&!2M2^Cy}M5^WQtA^ayO;9(fE^K zWqFD5#9_IGu3)?Aex?9Bs}}k-!;?P3p5!&h74aSZf+1cz zKIlhr(!~h{&42%JV+~(fEi2MA)xQKi&7$IR+9Fudh(Gw!?nLyg9xOI<3}5FsB$QOs zVpqC+M{;S={k(22nRQav;?DB&mCXEmI4`b%Nz1SR$Cm}V+Vpsv|VP$4qgBI{4{x$oD8CBe(CvGmCWPka3q+7wLBf(;WfQoqL=3k zXaJa0wE7E!o#||6y=5I8B~320*}igCP!HqL_gfnIzcRpiY0(2FBW z9!FZMU5vm(NX>4q76P^f>%-t;dW#>2l}4ji&R3x>1MZJKDQ*~OnT*Bqyy=es^3pU2Rd-OZPLZxoQ zh6T?(pDb~&$Q}cao8sT-5S58D?_Rc=@ zOFV8(H0Qh#hs*v{aYhgnJ-R5@vei@m&tPz+A>649>MWRW%P>b3B^ajvYiB(YalS;7_cA+M-)kYts&z8Ijpw1*w0@K_a zon4oDKvd%)f7a1^l4M$~x`Ps;jCP`Yh|a%z{7QeTC#QFkIgQp#-lIh_3beo>g7e-q zQtE|WgkK4n$ZfbeI|u?06r|j6ySg_pTKWOc7TpxyHiL>GxqHcqsx@1D_ z|1iE}B~kV$xZ z`W#9{9o`n*cT=`j;@(mP8M}s zt9$%{Y*T(alq3};u!7;Rm+#4yEWB++6_1ksw1x^ff^Ms)^RJ~gWTy-j2wvfu9GHCY&(-l6K)5?C-Ucv8bL?W zDT5m~g+w*${Q!`5@$FUWN_(ALkJH#bde$%lt@ih?Zh|{ds!DO4T=!ErY)HLachKN3 zpIbLHVEb>~%|tP9t0@Zf29{dxlp% zESyx~fqb&&c|Fl#r?qH~|E@(tsG0SbGm?bBWB`$3q?6L#3(->?y!uS1XXf~1gx6mB zlnwT0#H07JwR$9>}0O4dz)~8{%0g zPPw);Ctc?5Ie(~6=3g3ckv4L*OLfE01OLC{ zK0FqxOSx#4`!CSc=I9U75TQotzz)LG|AWjgfFg-q#xO;GPXmhfqaPF4>6``~N$$F! z`iD}@1)d<23wIU?kwpML=m(`lUhJEjD67*0Y-%yza)rvtpcq)QOoY)2qE5kqEC|g3 zYR7llCd=^SYNCB>As`8?xr55>2o%IZKn<>tU0oc0w?SU9g$G(4VKT!Ac(>+lX$5hAO?2h{GZ)}E~@>{5RwxAjZ`Cs?7)8h?F?5Y{dD_nP|~$L1R_~D zP!gMbl?lx90u7*oKPtvP9^^TiRAG}AzN z5)0*vEa2oby#WX|n5y*qB7|k3pAU=efjWDcJm8PZ2Y&%;_6-)O%>8>F^u@G2`VAuX z$rH#qaJ^2W^}IZ&@^jYjK)#c@CB1ri{6sD5GHI?BZvSD&Yjp&+R?ZWp5X&sovcWC$ zV=>Z%_9MV+?)$u}w$(D-;BWB+UF?)hCRK{7TO+2|ZX&^AmMLoA+Yi_vI54Mlu!DfL ztRw|@2M`FylwvzjS^&E8O;~aUjn^TbgrCQ8vxpUSKgG)8w%CJ4z)kV$Jjjof>=2iR z3`9Slh;4iadi$UIn>^s$AEb9f_90L!$b$4pn(=jD#0LO6D?^N0YL6@g=Jlr!(M7WpaC@I z1C2c)Inp;lbCLKaF+)z_e13+G`^DS99rI>@c^9cknbQt*&--#B+NBeZ(yjwEe$&>% zSThZ_`jS9j_CMv{P)?mgh#@fN1-_G-QRrGL0O-tprf{`CBB1e|9kuIU%9>X%`yyym zs&fYz_>HeNlqxA;?th{wd=*H8FtZM>&j!S_*7adO&Cj!qS&&ixfnaOE4<%Ffn~ty* z1*iJqM<9t&fU2kae+q$xM7yfvcL0Y6Mi<{#^49NX{{dhIM+yawd~N^>xN92j^||&~ z0KzH!qxj`};ruWFnAEkBeGE(ipEJGcniv?_?i9*Xj?a)CL_68 zRfIzzv2YlzBkvn;fPDLBylAnV(+xaD0KMd}047ME+__G@=} zs+<29ggsGyMxpI2KBPAKMH=|)!H=1&PQzN+rr#?!+AvVfOy@yrRHZ2*4#>(spo?PU z6v_epVf-{zCJT3d-!riKx;XGSJu_}+`$gdouy$P4PZD`Zw70H?Th*VNpW6e-G7_YG(} z*`&@?$xYR`5Ldkb_ND1(QVHc#_=W)NXWO;W5`m@wZ(pkKXdx`NwVASf_TB_Aqhy(J zdL5Ac>TBt%PZszm?KmZ#VS&)p6n)y%5u3fBvL4WpulY-UD^ve`*1LT~PYSjo0)k`f81iMlIeE_cQVGoz6`J_^>JsPJOXAPo;*bxg|)2_sA%O7)0#HGE*m$0 z_3WCsZI@jv4b%(rD@So4U=NRIEdfM}gypNP$YW=+UK^KETapLA=+F6rfMrU-7|+MI zkiR9kNJWTW0F2j6`mtt(IM6{&nX!=0Ni?t_*CDk$vUXe}l}YRW8LT0dB_8HtBtdj8 zI{#p0KwHFirD=N$9Le)^@2x8|>QnZW6wLErEUmAHvxLrmw-?5xzIOUO0+yZxlJQKi zF}5ZdoK#u}xN%=Nz_6=v#IhHpCFodouef1}X>5Xon^@?{*Vx~AzvvF04 z;gv;TGR8S4KslQmCVgBltr-bFH}w^3x4^RPNW-5JM{&cJ!5bZ4kNI7rzV&-d-$TQW zPCL+T{OqCQkrp+bZ|UKo|ux(Iw;;tUtx`E&BBrPsu@G>9b5 zU|&~pb?usI{hnhwZZF)(#nc1f$F2s%k!O{1E*lGmRp$Ow&VORD2~i&m`9MS!%qwzd z7bt25=&!6rPZZlIbUZNsFmh5m1VjGuE0`(c-0|>H4YHE~w_yk=U^^Ry=a5Oo1TO zX*WY8UiXg<`HlF~p8-Wo#jU@xOCLyfNq$A3=dbLN^snra@#kd1Gch2$G$ETSdrSy~ zn!>>N>H1`>z3~&5&Cjeh#YD|zyk(Pjq^{vD4P@DT6z*~^E9t+VH?!j5q1_1dPqOTr z*2Ljeqv@{2c&lTK@*zN}217V4siC%2SRC2kGiLo<_A~~3R?Jmr@^^3leNtiN9I5{y z{Z!Yge~T!WV};JOU=t^ML*w6*of>as)HTxmQ?Ln)p9s9SPOMaux9;>=J81y4@eqR- zjM`9;L_&(aj3d@0zX$Mnpzyq_>c}DhWMTM$t9xxmm{ZR!kOTy!(S!}lY-+&xDQ+m{ zC`DqZ4BVbvq|y~}pn>3DcdN;ibGZ;HaC;gOj3-=VIUObc7;36w0Ug-s q_k=viH_)jAy=wUX`c?QJ@`BA5qlv!G&fv3z2sAJ2sa0WYBK`{)bT0(} literal 26015 zcma&ObySpF*gh--Eg{lFx4;0Rlyswn5+X-!&g?4LtMLtkq`cR z1i1m*UjqFKr56Ks0 z=acIjGnJ!8FSeP;*!9Y#E{t2w51*_~HP%K_3nLyGy6aF#_;~KKoKo;&mOQRT-t#}x zd_Lu_TmNT1B40gIgu6DjY3=JpkD!&6e}uWi;d0nH2T|N$yoLmpzSj;`_eBV$6VY{%B(zyIM7B{g>FCl0 z4MW|*b2>SneM!)>@;xu#X{Kd*McY2EF%r>a&>R?#}M(I?wL~$zLN(}RN0Q$etKWl zlJp2S4Cq6ScoT~+$Q^33g;5Mg7R7q=AYI+Z|KV4(kYk#^lXtoy2PdIXKKDc)mcITx5PPXzSV`j}o(tw*; zk%+?rk+uJJ)1JEUQi9gvZZB7|>o;M=M+VOF$6$9B2UWO690+_KH9p_e`wV-xc(&J{ zj4$}J9FDLZE6x1*V!L_wV9a>kT#?2-!DqLdg@3R;f69#V0fO~rHL)bgax$vp-DiaF z#0eGNQ>J1@Fq?;evXQsVr}(D>Z$7nYHf%Ml?^h-D3C@Te#x>3c;i3G_PjryPiYdMq z$IBIiaJKI4)=SRqmebOWroC_cgPs2!{s;`eHd=R5bx`{`Ah9l}DoXL^dCBVpx_7`# zyC>|*O41j>qmKH%2O}dd>8lRMt+Tsr3NxAC7gxOAXxwh`-k99$mn%8Di%;vQy#2NoBDbY>+FRw~WSwi=rI%x=xbhnko7PiG>;?uPNNJ zljcJr(?hA&SupS~Z(^gHr@hy^dHcokHZ9gW^uv!QqJ|iw66WQ23mWDxkR7N;-S3p2 z_^aHsP`y*=AU40{q=VWAt5E6B5?@*^%ueEJJws?bqu@3RMs~{*h%=ghiPk}Q@AV0~ z&)i>^@)V5KcI)Zg7_ZECUiiEV9$1^neLxAVcc`6u)ITUk*HWZa*aHr-EXLi^=WlCTbkHfRWPgM|R?sf*?u%4KI zgd0c$W81oTBoALNu8g*?9(m*)gcE;!IO)WtYvh%Gi%LLsqQ>EU4u99L?~3X<5c=QDgk~LvY&HO*UBidU&Kl?IBHBq&`S7f@?yu<$p74(DO<^Ve+7DZGSz~iAyqi*<+6JjnTTOK6+*}2PYlHJ zRT17BAHI+c!HgRf;N0VT9pNMgY9V^|%il81-|=VJqK_s|XVn&cG+`EE{8vZARd}}G zY~VhkBSIHE87+ROhd-{C@<4i2&m3RhW6J$to2|G!h*@qnu)IL){iBkQmnks`LPCwe z+cjKNP1wHY*iVQSnuqkYG3-AoGisKP%z22&-LlWztxks^PQcAsdh_x&((w6sCyXVl zHdw#Xswf@)NQrv&b!1nz{{;*T&OnMl)_Ny zK5rZDvnf;RtgJkmkmWg#LvyWV@tSewHL{nVZkE>#-mxKhShO82xu+#j zqRz2VjD@lD3E@l>HkXaVAHJkk~(p?1?|@NkfjM5Ij3hJpFMiH^fxwRWie8np~(+e=lxu z&F{}t@26T0C+zSxEzbV@w)Kd8R4^N*#dRvaliM$TWZ)~^p5>aqu`5n@kPNv_p;M(O znM-pN%gp6nzkz&kD~EReJeE+!T$dso+@r<`+G*}KZ^D`{D!Ti-ZI?J&l`{;6|v;qrHxzf zOnF)&85E<3!!ZVX5`0i{UNR&^u()QIAvHmplw1)+8{130T*lz9hbgL%%_RmV<_9vY zo{p)=GBt+$v=kFDRB-JlGp9vZ({2x&NXz#$<`+`s&F4om{y7yoal}g>nqMX8rF=fz zNqf)0q=cLPDwq(u4wu7n$=|T@Uj5F?IBn7x94jmpuNG6k!NXheuu}5@;x(S+`$8*7 z2OJ*E-L*d(LEg1oY#B(ldVLFS%GnMok%E!rDoNuNh%^(w+G4u1>uraz-b)(F-Lo%G(6 z;o-=0{;cl#`{R3Ni_a0n>p}L+k-_fN8`0&|NQ#zr-q6L|9h&EO;c=vzG_W~MB7~JV zZapwGe%pZNCHQ!sJUsYh=j6v^n+K%ZGFbu6fBCu7)SrK>?UE7_R$1EP@os?k3|Cl3 zOaNg<&hy)$YAP2D-mCqEdU?0HjZAsXJoNL#F2V;~(K26HzjjBqg)8 z*%s%_E6WFsjg}cpI*?FVG+vjJ@8LL1Nv%-v{UNT2Ax#p$*&BcILTaXibyBXSS&NgS zA&Zrk3RZvL(()(a&Zf$If&1@#kV4PLvG&K?P!VLG^hR(i3w>X`-LzAVg``-8#oRe7 zOWbfE;fFGfX>~>=^a!^_I~?ybIcwJ|bb==-19d{fh6HGJ4g|*z3ENtNKj^J9q`89p z)$Wx*0~c(s%1M3n+w{%$B#a8tair8D%gGnwYerm8Fry_-o<{we%~71IFsuDC`<j{NBX9danag{%o{fo|kRW^o{5$@$ky>4`~Gn zjju_K+Hp=n#+F3-ni|Z*BNOJ&1iok|tKo8E*o=^d1c2(Rd})$a21kIGS2-RQz9_Pp ze(RgTq{$DDM-W)tf&Ru}ianyoU^0*oDuZ-zIY>M&I97ta3p@9#cVp0hn}Xil*C!K6 zhtPCVctqKV5kIDt|K)7F(+h|)#5%({)QXDaGd*{x+WB~)@ABkLt@|+foNBY0FLg*n zX^WLpde?peJz~Dn;EBf%hLm+a*S!Q{q3h$Q*pJe9N|u$a{x^AN4hct1yY?B+ZWRcDc=CpMXRqE_?8B6NG#3toSc*6ct}4kP;9 zn@^RRSFg@1h=9*pn8wRsVsp?X_FY_1d^NE7vth^ZvvaPM5x0D&pOU1Tpk95{Z>^}1 zZ1QHirZ%JWgVeq4q$iG=$oVP0LhQPpg>8Qw@%Wi~Gb98{of;KO+c2j2!PpWV*T(|4cyiQwV!9oKhtA=_dZs`iMT zXAco5=!4XRms%O!Xq zx|+@K`jv_&bQ$5gsLC2~jcT{uieWGKdY?s0D(0b39spP@XMMA>EP%+O^o7o?}rHNf)(XGgy z(4PX_+5&GskO$(s+c2V@`t)7&IIRMcGI2ayjydOGWYV4&!rMxmyB#%AZMSa7&73bC z(C7Lyw)gu!^_RGUSVIZ9z6-dyUA-;;=@aTZm6DPhPDBXSZ20e5i&OmhFT=KOiXS)n zY1r5(Br&1m*>Q-oLsR|&!oXPO5YpSm^NrNV^Bb~ogBMeIiZLBj$?kNikd$*K*Pk-q zMHo-+1#lW{J*5fRxgqHEQv}?4u6Cx3|%=ubtTX9}xt`ZgAa2 z;CA~S^e?LAtr0%>_aGqM7hrtE?Ya>MFn4GG^dT))WJ1r&%4)N}f1VAHdVnHDo~}J` zeAK}U<`JWcO(-I{dL1aoe*VTOshmgOMbO>P9na|*Pk9mWVv4kR2`J$pYL=w5Ac6{P zhwKUY7*Cu5D13xZU4B6SDm?aWR8^V&V;q z%GQdH_EC${bbp6?yi)08v`xf}sJ~Qz?m!-RjC6h*K7SR6gKJWh=?_;YMHNVV&g>u~_EP0(v z^w+X-6^Cf~t_+!Q=OzXNlT&CLDfiz$Lx9!0827QqhXsrq?|x=yjFSD=sAF5$ZB`@3 zjUOva^!tTc_$$EuCQ@t?AE2itzS&&FM*pu-+0IlfLQM{no4E0m7ydEwkHuV9FN?Z^ z!H_Sd=r`XH?sBqP*lQX_!<;GVal0yclmplp1V0d5A;u$qPKK8WH9ySowv|>v^_85& z@#OP}8rK^4>7LnL#Cy4atuFbzFOA3Y_1T|=7<5$_)Z!+A94u?SU_ISxENePhdw=7g z^Qa9vnZ5lZ-7jfnHXlD&0A}E|l(;*jA=y1_Oh+0uKM0I*cL!p!Gss%d=6l!A`M?gt=w`X;Wsw63PU}38Own;(k@f(W8KOunJ8a<(~vt& zRfRH%xP2G6o2`ju>{myg1#aj1Vt0JLY}jp)-wXP~MOunh{aGc`ouG=j5B_q*Nh)2y zVKFy?6Zw2|qMO{<2MV(5I0Kh%ri!(9?|ZzKGn3;JJh!@8vJ(L0rHC%dnJD~bz;gM& zj@3FDA8$2oTZ|ccBm%(maVWvPQitlN-({3<42HWcxMt-=1DI-c=AQQoltT1*F%r@0 zcaE~|&)VG|(&$Y#_Ji4#R41usis;}Z>_U~n84lK=^11#oo8QdMIs8zYlmRmJVrd>4<+AI zI$o=`4bLYH8x_44U`d>>65ihHze#YPSgf@5;zR|)(BKINFt|2B#DG!3*Gy5}&|4I_ z-uSd)dhJ0_Z#ZpQT#*HYk@&C8-yv86W;}+|1hN1ZfM3A@iZ+Z#-;_krVm`Heyqulv zKB})MUPvqMy}}#f2`4vr7AQpva_vbO20!roVP0TFV{Wyci!dTe`{|~7AArrBc#*c4 z_r13pE9J5Jde`9|g`{5-lKK4Og4y{~VERedZwpB&3oznzU&v4rxrCYlqZD ziroGi6KY!h{<$InY8ePh>8Erk=jVP7;kTe7;*&^MtEMiQkaIhS< zSaBSKqHQMO*RQF(2ggjw1_%;Hb+O-aYO!<_fpT~d9HbfkI{=%(*{j;qMguUe598&s zLmLPr{z&1tW&0j}=jT+a0Pxr@K&0N0%h$!Rw`F=v>u1Zh5;B72nF2^X4DD{aW!Ejm zL*=mA+#$gqPrd@YNtYV{qtBo8WxOnwNxpA`iuDWSgOLt8v8`kOk4t>5DDBb?5SjAW zgdKaxlny+1$8ZHD7lchqI}KZqLWV{FSIc=`&Ep3p{2Q23mHMhu1su}KzsU+voAOkQ z@1)VagF|35*fegj2A*>vE~EO^Ix-;@)i|TU@;Gr7exK9yp^MrA@+DANx`!Z^VbbWW zKXQgxAQ9Rx^* zQqen7Gb8}fYxJwu?!ZS?rdFb7nb!<@kEfmtapHj3Xr}-N;M~x6Hms|48o7TlDs^Q5j$DQ z+Z}!4)OizUEFGOYdsA_fOS#ODVgGSCk!K2?d_Cj2fDfXFF6;NEY6=LZ0zB{*%015q zLMjU<5Z{kIJ8Hd51dg9gK)(LrZ{y38c+&yjFA5^gfGmNq+&m%$b(KGU#yFnrJ?2Xv@{*Vi} zvONGrCDuK-G1eaSnL6XegiYa{vtsdwyjTEEv?@thw%NN%6^RKkOG%`x>R%E_=+(^l zy*RKi@;%U@5OI4uJuhn6Lt2k!V;a0ASg>km{7$=#UTiWgXSha(o`V0Y4q2+dle}wJ z)?8zx;lKY~u@?je7T}Pp&j6x7SZS?s?u8C*fF&u!CYC&2jIa2WX7`IG5cmeR9L?o& z)As!|@7wvl0Eu2gJFW)z^&W%@2UGKlqfrq^zxdu)Uhh_N_ZjCeG~P-aBCgAiKv=@0 z+_Z4(9ASZE7MEHH7@z4$m>bUO@YJ4^dYLB1J6@b0#1>S^{kglKjn;meCKfTvW z;FR@PNYVLM3<*yk>6zZ(@aW~J?TV4Sc#DOtDWl{tS(6B|07P$w_gc{|;8=QjdfD>? z_Yq&to59c?#Vk>%|Krp83)gcr!Yl2@$EJti=`l_XsgVChqAv&K3cHl%Qe} zsq&6|Fi(--7`S(SZo0?T6K+FlOP%D#+HK)IvJlN<4T)p9X`ekc)6JVXVvE;u96(e$ z5k`G4H54uJ_!xlUoh$6H6b~{MLma}~xu25i@*oN}5Z^KS0n(>}7#X)%x-8OzdoMOV z>;iV}e$o8qIUw)g@Jg#b+^47#wnV9qV)^hlTR)g{XqoYuL%(H;ib^c`e*k`ZE!};n zK#eVTqt1E3jhN#Qvr9%9XV(PG=tYUQO7Qr!*D?)9FYowLzr?A1kssIt6I(<+pL7uP0xaVlE{OH}lA6Iw z64s63qIhq&6<*IB6T{XvQC^rN@Ih>nzapyiR!|R3-K)K1s5@5i4sOfPGoAFObpe{L zY@KL{R19y_R<2`L-vHIAd}lZKBZLds zW#37pvKP^_>h4`z9RoXn)`z7JX|dnhvpNH3+6#E$!pl0bXfFQvd63%{*t9iy(X%7= z4!=>c7(2>{)+>c~hgVI4fUgYH0oA2O&E7UOWX`@~M2D}-lRjCisvG+q=c_-i!jR_q z5JkbOur53oOp@>*^#_E5==1824|&tDj>!k!TG&uZKSh6LIRPg`mU3oPJUEr zp&W)b;ncP?Z2x8ad(!^Q8&LuiO5#||O3a-Sz9(;6OkS35{LT?)mOS~=aq+`EW_3D) z%CSy*%p`^Gx4;gar=8gTfGoek%`Enx@gF|7#;c1cA6Rdqb1~iiaEUwgr6d7%^)eID zmG*AUK2_sMjCiB3a61{)GmA^-33sMOaaR-L5YVT09wy;bf*c#2*GFBBfz*59vZ-i~ zxhI`RhK$T9wW$x;*@4xE)lZ30)N(Aw#8X3egV|;J@YuH-ElG>OHY94=f<{IvQqr{5%89M-AaRy*$XH#?wFbC+RY-!**h7t$7;m_owrW z>lbr86trn)uaV`0tab(`CV_1Yc`NO=Lby2+2q8Mb6_$EXd{AB(_B;+M8~XI^tK|Xg z+&0l!+gTvlPBq;k++}r>eZP)1`?&O4 zCF{HUho4l`YoruBb!LT}ro}p=4>Za-s z3mZ!$aX(R;8OO^SIxZOlNKwbi37{Id7@00&mN8Q2+;^yR?llp}D0#A+-7{5td2pkP z4*B#_t*U;vvR`6|hwyF|4c2vvxctu_#Nx`6q(wdL<7PQ32(W|9U6|bDdic-7mBK4L z{f7x|kE1%|)Vd@4Uf)n0mchhdOYthMwVaVuN1kUBiXCdU^ z!A%ew=}02j97dde$d@~D#>}wa?2LiB3ZBH61?Q?7j8uy@fZM2B?nSb}bEYo!C2d$SAw| zAj;adP^no^z$88m&|fy~3&M$ugdMuaev2UQkjnza#F4liGYV@#_(NH+H7=A%EVSNr zxd&vmsK+n95M260Je~z~;J#I(LQ(E9yDV+Rz zn}@|4qWOhRI%1{RWNf8+LT7aP7gFV5i63ZiWkJv9{;{ChoLI+*!oUYG9*l+X@=!UR zYv=+bo?EdwHnDR8mqontq9YAI3oBj>Mbvo$#S~)~d-W9Y#eCLlG*&6rY5y zs|OU>IRtWwWO|3fPE}FXJWmJcI4!w7q8Bit79nU=hO+^bwILVwo50iwogFIG)_Jsi5?n zhe#>aBzbFuR}(NxA@Sx(n+S-BJgF4B$QbGa5@z7Ic5sWMxaS6rfe(~$!UAxb6J;PX zAFRXp3*KQN=ap#O!o_%WeXkPU(#^;9Zgf(=U|eA#N?_2(i20K22Ndh%>_7IN(-g)k zD+on0zI^q!;z3l9(DanxDdRDcJ)6H~jH+XLp$5}E_e}E)pw7ImOvd`x;Z4@=&e4B7 z;Wf2s@~5W^t}*Or^WeOnSRT2aEUqhjI3cAFJaSiQFiHg)91Ss!80z{y08BXrI zgmNQUy_jnHTUk|WaEKA3k(OJqT879@&?ib7Q@M(67o60f4K4ab-N@mNi`O>&S;_>M zp2|L4dWuXW$@XJ1T`(*ZVgVKh`}`QQs4Vt7z(h#e{^;Lxp$lLMmdm=kZq!7&6OV&0@>mAD(W>WOnL7U~#oeiY=iHr`~Or?vKFP}o>(AC$z{zMnd z6G6`wY0o7_t}bK6MG#LmZeUL>pJGzi8Q<^q;ujxgu%I_0<5=u*)3WO*Tkf#6fTM!b z8RKm^n_hdlNSUCOfUwY=UnKR5_Qg@(?&tNbcw@MQm-ZEGb>-#st$b8jV~)d|a~%yI zh}Yg)d86qDg#|8RODqql1rIRk-g#h?i)Z%$;-Fw>6kJWug%lBrh*D0gV3eY>xaG2Z zdlQiql>!M1LVlI)(j(23bh{ym;L6ei#X(1f8djSnsmE2r~z*w8x?8Z{db`)|lA0 zpZr+W6P_iS5%{{7NG7=W+&iW%Fw|SOpoKOdIhs^WBfjH2;M9}nddg|(3nLMOaesQC z>AXk~+_A0t*}j0$k_uWGfx?ntaYza0PBW-Ki|ij?Zu_Mge4SN4UAoIGLSk9ZpP4hb zxb!K~YL~f$(sVbv^g7+ApkjgG1P7iu!okm}ABhg{Ia^+9_}c;7>YPW}7Y!dgU%Mf`sQ# z&x_D!@2>mji7{%hipiYtlMrNA#wCM9QAmUf-{;$1`J>;nowLFD!D+-GqN`^|qVk6bzPTAP$)hLJ_sHa(A74AdgHZX(T2cxFK522B2q z;<|EhuAVV{hP4@_BT!0dT*G+IFap>Yq3Jq*@pSW@?Q)MW?TcTdA#w%eVMKBnNHxk%3ZS6{zd|nPIb=MMc`x1u- zglrQF+lOmUB-(>Y{AN%b(uu+B`ZH)iOYp0UXsNOd8sD(_T|IFr{qgF}LQBx|6X!`#`}QAD z#}ezlaa|G-tUh7oint@I$Bdr*iwQ4w9|m_y{euRZHXhZse*XcA)+jvt|dHqcAk*KUo4W>(QZBe}A;hZ3#@B1d1?a zP;4&&;-1`b+ZVuyt~F79oDBq&d`dt@A|kwsibnysyrK=4&69^R(eV@1BBmN7kW2jbxCq>;9n`^jgUYv)K6Y0Zw~3=iJ^a}Gu^`l{s(D*C0Y7h9Sx3&MVd(V&b~ znQ8G2i68_E*R2O=za_|*Cln&cIJ5;JythOE7H@Ri3PI2w_7?p6_eb?|l=s1Q|CHK&)zLz3{l- z>89oGVmCiC)2kT&E}-*)x~~n#-NdKtilpGR0J^t$pi6mA4$4to;kZFVkEtb;D5DK( zF&ra}GW;KV8g*u1(okSbPw+n4Dlx*%saH)E^(ZaH2g*Q89#A=s15Cq=DIehTMY^Hb zq(C=kKo2VMWa9jYLcV9SQY=$Ac%d?IvX;HYhy+Z2gYM7O8BVc4CCo!VjsjZGhpQ9S z@4<2uY)9VZKaRd9X@r(A8ZLaYGsXXfmLLKN;QO!;qF;D3zi*jJjlSRsd1hEp==SLb zIi$k_Acq|6hoDO829&|ub%QFRkZq;3u8~7f<}IU6r(bMyU{gN}D2-tE#Gjq9IN;XERr3>(we7ts$D=={@DV&Ni%LvT zh}EyJsV6^y@UzIyfF;W_msvG7atD;6Y*1-Lv2@&nxc3e{4J$1`lc@}_4NCy^KgwJm zdB5EKl(bXA0Pt*Y%pW5*;$H|ZRWZax2DioLw0 z|K}S8E1RAy7J8=*@JGVWfw1ET6u-6Yz7IJ)?1RT^LKy8&U_I|9hZpMDp!g>Duu z0G#EjE-DP|2IlJ}P*Ii9?sFmJJ^I#}OZ7D&?*&2S#KhDUer|@Ett`M6t_H`ogS&|% zOK0_Wrmt%wbs`M;l(J9n43lDv)DS*)>@9+|Ec=FoaV=UN~d!@l4W%QIM4%+bKT z6Yw*Q{aWC_CLma^nV09TO3i{rCj;{oaE5(l0jzI=!6aWFTd>p$fKyGX zt!RiKQx}m5)cBuXQ(zKdf}yC7_rVLV>oBLH0ljr1ZASlRxxPAR$hR9BMorJvypO21 zbZS0$1Rza~#RM(&?+n$rclPJ99;lBjUz8g(G>&#t^4VNkJaIWoiXmXV>geI8Kv$!MS}^v2v+>kM|K|}K!YxXk#*f1VA2npTd>Rm zZ`JW3YU$NGHY zuVA%hRLSdOWo0J^+cQ8pn}eTK@}#yjD>~+OEJ9+cz7g--80fs~0Xla;>XYR)8;D)C z1^87hjgQOoU%RyC`Ft+?0F|{?{Xjx#aHH(u*T@81`L8{Nw1Fr!+}K;ohuq^81bAih zX?CUGl?BG!4-;Z!Oo~4|d+c57IF*0`N>gS>2p+TNINz;Q?6{4;RXjm%FUMT zjfE6|Ss;mDehKakj!D*{foW!m*6#Qz1pu{YEG`b7r^L^~>iO4foHFp`Z2uNwJd5O* zgdOdjU!JrS{I&_+QiS>-=%b`x-t=bq0U+x_7RT8;hCrg{r3};Z;4Ir1DvUuAbdzVC z-TsinHEmKr*dn?R$;-#?HLR&vw7eA02>9X7Z%RcEJBoeQh?FK!u@MOne;Uu(Ky{QH zB#Mwi5W3936dBY_qY-+zV*+-L9ASpPUNxj152#!YGxN=f>Y;wT<2q#?PuBMQ?T-IAZ z>%B!?7|{wzbkEUP*gN`sC6Cciq5K8VDl#;gj`L*>-&vLyd&kP^+>%*jHh(VFc{qU! z2}Dt(f(-d+0bY?JolQI@BWNU=e0tXrbSyPwwK3uaE;f9lb%A~jE#&n*aTA{k;?IAY zO*|(lhT}KyOeE88uJ2gCH2fk^58VOb?z%mShTLryf^R98>RF{)4u>k4m^cwj{x*UX z;!_Jf><-Jzs+sn-3ycMrYf- z>3Bu{8Sq98eg}XoSf>bEx&3>9`7WUP4P8LuwLbGhQoiCQ4k235KwguLexEAs_(8y? z7db@$j}L_~Iv@fPx*W}e_?0Cv(dI{_!36ugw1^)$tTmnFDa*@^WpH)$G%c>1g^7D4 zfv9ogocjf@6F|YD@mWLi95v1#Ou|F{5bwr7Pay&Nl38>b`uy&sBx7joV;qN|tw>(< z4k|%Sfk;UK9+DQ3h#fe-q70+jbNl7VA%#DZZcJY_uz0U;^K_-VSp zI0VE*1-R8-s8k^Ohoq3OJ6yb1!4Hv&-;<^yfeusM_j1Z#fb~k#1iZddxuj zoIs`)NV>{5$Gmkh(IbMAgvSezIZNQa8eug9i`0)6{&g2kk6M5ZrZVDjbUPK`gbBTX zHsT$}3(&sN!;2Fh=@31^IFhYw9-KU`?u|dO>>F3G}0f`7w;JJfka<+ ztNF+X-R%gZ2MA3^3VNU1xxI5bslcH$56Oe$DCCYdXUyeSyfYi){j_$W8P z=;H*(aipU5K@HRkNKdYxvj*(2DZpp#0z$JF+)iDF_Hn=gp@lhcbP#s<_`id&BWQ`K z2e*4^K$al!gZYlDKWVm_btlH}J#fiuT*0O8>@f83RHx)NqUMi`DVULUfg&{1(I^I9&73 z)=FMXl7PcR7btq`UY$$5t_myUdvRz#;xLF(eryHOg(T1n$C{H%wYk4JsT=+lFbR~q zR1!XQNqu)(dPmPef6BlPoka~==LGak#om5^*scJL4C^AqzJOcTNK62wrLe>4yZ5EY z$JMr8=0|8}8u)*Xy-}*t0=ZSVA&NkzjeQ6E3JdTGW{=(;q0-71t9!q z;Z9TcGXOOYf&fDQUaK&g@9BV))z=g#xDZ)qz?|0pC#E0aan?zl?62l6%IJ3$tb4#JO!x8_N24asxt2BF1g`a_?84RzJ3j zAy8P2ya-PC97$1m7X~)hh_Yg1Fh9cEua~Q}N$~kq91{BP0t8@lOoT1wH2Ge8zjlE~ zSo78_-JyA@rnC-jPjcq-2^bfQ=wt$@bV6b&uoN;wkb^)Or;V-j2HbbN&0AM7zHLJ9 zf5&)m7iok++bT*ihL$qAood1&UTqPr2x464;{A@nh2Osc_I&5_R=kye2&Oek`@Y#D ziG#mk5sk*f00vd~MUh_L%A~)QIYKM|z)Dv30)GpA-=A?3J`cMj!KTUvK z&MEJZ#6%EM(q73MrtvxkYaE`GoVMX{B>+oR9r}zzfi(E=m8bVDe%!~8(~N$DoO4xy z*RffT`Rso@{7>xXs$WE=Wn9xFR9Iv=w;4o*-=Y!G7I9x=RHXH?P@e*CQ{r9)n)Xh6 zPeuUW$6nTQ@^0<_CioNMrQNL$hdzX0DyNguF;z^an5ZFRq|oVBhn6zDZoO^`$f#1A zfNm}=(A*4CM;}|I3>EcRp3q=hX1PicG*!{mo7~s5yZos_8<}*O!ySarkm@a)auG@LUf%P4G%|zBanIT? zq-OKUF{7!p3-%wKztW?nix&VjoyHRAJqLa?!n6?pMk|;sl9fy|Z^%!C56DhbbCyb? zI$H&Fd~NVL1sla8E-g|l{nQcHiaJx{CkZ6a=+OPUyxkA)k>KE+oP9m>-`CgiXRGqb zaKAHAnAL2;@0nBcV@B8^s%5(JYX1STzU74r!P>Ec z{xhE<>%CBC6Zy{+`o^ga4~n3v@l@$t01#8OMi#-B*IGypkM`*vcAYKHYaWLh>|`PM z?o+F^(cT!8VkisWnF6llJ`g!HJ1v-w-gye02~YPKIbi7zvR%GN;_c3*un zz1Y86fck<({bV(o7{XWW7h-GCMMxmHt!*9lg5y+5YK_UF1F=}}PwgJ5tKiP#Du{(E z2O@Tklu)r}>fd~!$Nr%N-xqnC42RFD7C$x35qHsXG$h9~zc)$>T{vqyM(m=*mBO_> zXOzOD0;$thD?xJdC$f3Vo6D292D3sh5cb(LLHDaesTE}|f=pu1oP8BXdSM&%vWpN7oT zKMqjNROtiIABXs4%%q6dMTYCQ?{+tY0+MwdD6!+sxj&eTVz$=Y82Ss+*)d7muN zKP9>{007J8(tyh0y35db{H@kYKQGWDdcf-7NWA2|NyMO_^d*|+fTEPWYcx>QcObph zndSf#s~j(H;txhDInw4!)~iqKnARDzZh*I2iC>MS{`U<85xW+0LM0jdZhrI|d1igf z=+J@JC6pI~a|uFg9LQl1I1&B}Ut*Hc@=1xyGuLLF_)~lD!;Sj#+tKx=ZG`~cG*5J^ zdoGe)C^v=f&VL4@WNhF586%q#^F)3;_$xQd&z$znTnP5W;LVQYb#JijzR^IuiGe-P z<^700RH;xs^Ib=}@7`M$*{X;5V_b~@tv|6o`4e@eh}$cvRe)zjDs4|Uhg1$;>}6lF z=Mu4qEyO*GUj{-}c7S9I(xW>3*hWMDh>j_^HuEMU&`=JJ(#_E2XSaJDK#74EYYwIwwZaJ1xQBn1EKJ`i7$yyW9= zlK%^lk7}YJ&EN+VsE+EPxY;7N)j|1YmL}pJZFx8$0jdgwf3D)|7440mdV3Pyq5HFg zR(48v0_f)go`~^4`a8Ae1-=`I5Sn!`ERKHv^b*@n51@(vKQnatLPG2Wc7zB^J%4@F zlX-qd6IAp%0d$M!V28MrxHAra2QBI1pBjLI7EjWHiK#R%RBV8OxHPl{pf8E++-LWF zzVJ`>r3>noMfKyHN*5RVTdqs}h`X)=r5EEIjj5AJf5>R3DiN`sJXM|1@5?`RCi@XB z2{;~=WnhX?2fAY|nEEhK)nehl`tq9sF^wBKB@Lh9@HU z2l&haX{xYm!PWN$SiB%BK#CWu5JlMy=*&DEVoyoHo@>d_F^0viJVR@WyW$uUgX!+B ziTp}2-_MZR7Xn|z;5Sf8&-i%z3fSbg8I+qm`v)t9M|(;q0E@Yh%I!y5YGX_}%3FlSM{u1~yLn4W~5Y)OhUIZ2_5vshMjh1xo z;l}`cGO}9fE=uS^gXYoLWh^^sm|0f$m;%!pP}~&`tGvc?q2~@6_R)35Ij4X?0t8gTysCw9+?hz`FM z@F%+fZnP_aT6BbyYu^37bmM*zNl5KWq)exQLlsLs!>=&`W&(eZHw!`i}z43RgCIEm$PksdC9$u1i z(rhbNKfm7lm!)e`1Vzay6!)?873o2x_m|aM5C?j?X#&jw+`lZ~N1nfLyiN2fBH_n! zhdU!01GV@4#rk4v38>|>_qR%bGEBFOSRdqt=5~3ccbuIULCyp%Yubgw-VwZ0|2w|W z|BUY(M=W^e;!if#`Gx6cdZ)MnbwaNnE2mn9kh7V=NOEzO=ysEqM$gJjtAF`+brcaTrm_t?>)+MCC~qkrUp+L-TO?W=;xKib#TWADGpSE1eetd~HR`P56`(B=9L z_|ydl;106TEwSE5THuo%2P|PEuDQb4Jre&)UOP_!Xf;F?QnUvO+0je#cVmUwe(waS zTqS0~mt(M;o&qMQuL#?B;e^DIU4R?$IF^s$neX*y9LZG|=`D%!bexF!lRtUUB5)v) zEg-+i19cU=GxkZA65Z5$@ok2VxyO~?cdXQq9M%fHNx&*CZI*!6+a`VlpG6RA&dOSd zqm#;F%J{;61d8qV=+0Z=Kp!BSOgz(@xe_;uU;J6X8;p29fLDg!4AGQHy2?Jq*T%}Y z&|m2QEd_-YFVh1?4VTe8r2F{4b`~h4wAwFusjaaDM98sd6+glAO+ejvGqL|sTvttZ zY$$314I3gK6qk}8+ZKf^fn||+f%-vmBBXbj~e%ou>L=7oq0Tz|GWPQ8C%)1WM5`# zWS4!P>{)6OLW?~`Lb7KYTb9fiTSOQNlTc(!C?Z89i55f)`9z_pbgp}*&+m86_niNF zWFGfz?(KbF*Xwyb73xPe@oq0|fPlrJIQ+fvrx!O%lD;*)3fe!td99lHlHbx)*Ze`# zAY^Kk;s`hX78KcF$wGjAOq`;34?cR9mm3OqVLqzZjb#unx4v0DUT=9nn4Z-`lRZj=_~*qgS^P|s z1Ev)T9deI&7c@v`e(#LnWMk?B?NDj)PVBSi;hgLI840uiGh0KPWmrxQIW)ZVF6@Vg>CFYL6I^bufnaTbWwgezcd?mE zL}T24dSU}ZKF`ue^wz`<^aa*B4K zivq$#usf8cL7qZHTsqIf`c2$R*s_^L_?EXg9q=w~Idsi7;>)(m`&Usg3Fev$UJDJUT}{-G;^rDWJ( zLsg|zL`N;0$Y!d)tLSXJk&yK;<#$oxZl^obFV1k7B)=*yKbxDijA2?dN2 zl0SM>*41{s4No%%$k@QmkSk0%+%(`>%Tk4YJJZI)SsMW%zFF|vTwRcN-4$mZmv?r3 zE^nYTS-e_GrLGMkpS^oBVs>3QN6KVe*dssjPFqE>$3m21Z{4<*F2(Q{x3JG3i<%So zUDtA!_z-DM?Rr*b+pw9)rx{f~^m3%?HA(r+dRrq5FP}j+hEEgQdQc3hu59PYUaE=m z`BC4(twy=9SsMeB2KNG*r;|1?6EO3|^@Q57G2a?C*!ln-1=pFk@^DHRxC(Y0@j3CD z;Yw}G`<-{k3h%0BF$a909)CLI8a<^T^1DT#s1;mTH5~KYXdJsrX*s;NT##zWlF%{v z87Td@Gd^THN=LB6GjmyVV@W!e6$DJWeb9fY%IEpI#YMSX)N`BLZ)jCj^F=40FS7OC%O4Fm(g(@QHT?+RZsY4gb-Bc6v4VQy35dt^0 zC(zmCjz61`(WgIrAy}glJ!^fC@jq3+ab@4hrW?PYEY&&EaNz(_4#$am`cDU{Lv!Zt z*7juRh}Aq~5>|H0PR+5j(lbYKyj~uqk*H~ti2dVg=%}r?#F9=}=7p(fZcMlC^dHoM z0F}#VE72sWPske`hZF@nE@QXJxW@nTfubncv(T?zZR;G(lw>TR}taclWNaNu&|eG50R< zK&2c$J}loe^@(}6XL@KtUJkaF!aS_JA~s6^McJblGqk~BBWntjT{$v^5^%Lm_3Zk8n(NM2X;Q__Gwu{yKHYq zX?l}*IsO5SjlI$y-gEsJ^h7DZrzV$I583I@X>FtlK&OmdBXT!}{s^=_)#H#sB*~EF z$!f+Vww^+rZj%_m3w--B@2MF(np%18g}#hGQC?>L#KD5pJo#!1S4*}_aZ7>`Cb;}G zZozK5ZWRKL48BZn!Dcu!5|?uDM`rmkNtKQ4G;&$%vJ>iceWvM;tOMd{6D@>W<0y_1 zyKSsJg=uRaOekcI;|(KESs$|z&2T3(?LGQ15?JDz&5z7gU0f7_K_-rYO$GO;CxwVt zx&BfuP>OaD&5Z1+jYub(AYIvph1xcUH0)^{Av#~O|D=1v++tBQI?8N(5gB)9iEiID zDCL1e-)52GcGm@++KNI+f37+o#u}B97_(Lg)qsJOP?&`ES89xMsth+{sfHfPBISTc z2(hJSCvQaE&k_ww`Kk4Qj&-wL$4M+pv8W0aj>h zV6X5_Y08kO-TjDhjY+@qnB*VJWwnsI+xTK`Kg6<8OcU6`riHzs)tOLou+yT7`!?0@ z6&)XFUaj$suEL-jM)I#qGGJb0C90#>;QKk6j7qkPqCyb{Sv0 zvAlPgL7R0ON!}rye9?5UIE{Yk3ntqJjuGYXRx-kF@_v1?)Q8SIQhFoRd!(pt)9O4k zX)Y+HAa)JFNg0CyCzW;N{#uhNgniBoi+CmdYh0e^`~Iyfo44So{P;Vbihi|=lLx3B zG2F^{)zjByY0u1BQgr|G^U$Mm*Q^@;%r}!SpmC|;(~jws7!*g~x@f>Vcz+!IDnDV) zF}JqrbSE2oSQSbnM%#(sa{j~TG->|)Dnlj1+U{Er#?{kz?7q7Dc`)qw8t#^3 z@?*t@sUMc?d%L|4<6KZ_Zz#JQSGB$Rb@pl9&q&vNU~qFMtF6ljT#%Wf z)sqVf1y!$p3_O=F=oWJl^&SZMG0c{AwLg%B_8j080fZEF6$RE`}hZbL%f zNrAhA6ki`*@YI>*54XMlVah|IhhDLp|1Gz~>HB}H^9z>V`TkW%p^IIe`X5NV-Wbr1 z=RT}BeeS%*HFzKurS@T$U4N?j3>KNz?#43b!PwGA{|BPYg}`WRd^BX;3rW#`XEgrS zqpFy>TZ20LX{-i%kauOsBJcsvW#S`+ z`(ZldYlb}78@ETSS~KFgkAl=r-LsbmpJfkO{TxtH!;#eHdube!EuJK0k(f(_$>bKT zY?sWI^MpF#H`_`LZEX>~Va^F;S-dM&pnLD>B?Zw}a@Hbx176uoTR9JiNmfL)2FnX= z1Sbx_JQ4O`pSTDTv+R6hyyN_={R^xov@G)y3a?TA_u!mUx z$5C&=hiZLu-kxdJT{Goy40A*=gh1xLu*=hYeK&LOPL6AjK$vM`DF>cPnu%5!7_@#Ng9u|rS1NX}R2z@*umlzX?m$E-sex)P&r`%s`!?iedmi?{Q z!XP@=wU@0RkWJR-c-gMJW3^zdY6WIP`$_R%W+Ttq`wjci`Q_@`3pCW}Xyn{x8xh~a zb7zhBQY_K~a;;+Q?>K#tEsxExHM&_2kJCK!t>>o{qqGFpSWXrm;AeYf&BI_)<-3zH zq&)`s?n7OL@4`JtuOFOeH1-5Ka5!=ZqMlMsm0$+NV?5u3=VU6ZU$^u$+m#qt8OR=o z$#F$1zmI8}`B=i2=9l?(vdLd&!q;VKV*=MYO4I1@YuLZPj&2bGa0D(!hZOU+^5A4l z#sJW1rcjQ&pu34ad? z5mx_p=I&5x`QCsxt~W!BU${=|o|B=3K!!O0?mcqezdT2T&i~4K+`0x3;_=v&P(Mr( zN&^G>Y_+u70y}c0u@sqb2iKt<0tqI)TS`J;K*&o&1^PDztj~4szpwU=UGz9@N@soK zrp2XE60h&|s5k^VeA^4H6;ax~4p*HZe!{!Ze=nz||HR&-c5bAeO_%{izS!||caskY zA7h@y<#XYYQp>M>xwo~FfANs?ujE}_c6y4qlVS3%f8xJyslV+%>9EkT)XlNFsX9W- zeYzTzP;8u^ZDw{Y^4f~PR4&QxeiGMek~_*5ffDr`ld}Gg#D@|ZG6z-X$6;slfn0^g zd(`9l&dw8mDwzrx z+PXfy?2yDm8aw5V;*Y1F3MqfVLjri|whXp0*>z|&3S3GZ8nn>7%c0KnhJY~0ZISTV?lh%Zdjp1~E zKjd0s>NT?=vRWX^@%QL{FQzs_Pu%IgyXTz(SrPiPUu0)j_Q+NdzpE+>2;HUf*>c^p zUbA&fr*%f>TlK={p_xsQ)gGI3>lRJ?i{!S!=3`q=ef`??U~uO?Z!w?<)52uvn-xo~E#o-@#0oPjFVT~Zb>%_w&J9!S>%ZWgnnT^|zF2`~PHuCmqC|gg z*_EIdmT#?omu0;)t6l5+1*r75fFk=&vmtA@<=1&V%T|-kjS>>DIU+tPtQUW%l)|sR zb5R#Yg>s{$Dx8e!tscSZz2>OFa-;MrlA6SCe>)dZe!@r7JR@sk1DZ~({+(kjKM-sp zMM9-U#TH3n>`8b}NxvnJeOG8{91^OWaPu0t1fdG7oO1WHkEBT<@CJ9cP~xj(8m8g7 z(Abf~jDQxTSnr(PBwGH$Us&a2>T8UE77Fk3M=vBHkcefY^|Lm2gz~WGbUHoGM&~s8 zIjLDvOWTnEM`P>)Lb*T(&_AZ~N;2}vFjPwwIgYkX&-Z6g{3!?v8F$ucS(X0DoR?Rr zEweK4D`oxSVQ*tas7w6#+UdJ{7?CZaV;@(i^U!vLHS?&i9)V3|<8;haTJCZpC?)B1 zVP$wCHynfO+|)6u44v96mvU0sCy9gKzRPSP0FH~H4Eo;U(2=(PBtk+j46+MkBAc8} z`LX-}v9jiVLNZlA8$KuF(NCojK1D8W*uMIaLen@-JbL9I8m*}G3YIIcmbu&-vQAf% z2(U00<09cfQ{gp`TX8*ts3V2$VCBJPfY2Hc>O9gNm%*(xW+ce@Q0n9(S@b^_cS12t zZJn=1pHYu~o@{`9pkD@lj+!@}Kj9wiJ-X_?>O~rH3AkJFHVz>fW*2jB(Sg&VG4im$ z@m$1{Y^%R&k4(MKK^Xq*?Xn+q@zu1!Grhuf6M75{5Vj6LpdyP*rRqWFegj>o>=vIc zq=M5q|9Lk-p;=H)8vRcy!X%DGLsGRr8)I|ZOHq&V=5M!Q4o1(jkm1-i7%qPifv81+ zA-Hy7tj=xUI`q>J8b1$mVpoXNq@mZJgD~E-S=m`ge8_OqxHNBrTf@*X8ewjp|Aa0n z$cm%CAN_q7QQN?e1^`top92@jjXZ@BB}^9LD7o7P?=CgC@|iI|$T3CO%U;~`ne2z= z&%Jzo{iRN(|0kW%sDtqKBp+fZZs@kHPlG1}hxp+p1<%RH2o(-5AK8GC*@JIJ0YOL+ zeZr}79_;c<;6-Y5;9L#|^$PnmpC9-cM7!(~t+V>0Ks=fA>Djdf%9AhFgNQ-l!jXcN zpQ{VI^dr|sCj+IDp_{cIq-Pj0opT59IE`0l_aVk%K`C^1Xx1ov@Amv_D}ZFmVU5n{ zJ^V6i+*}TV@2`j?7|yIBxPd7MIF6`9Tg<=$quv5G zYJ%nrFvU)6{Go=4tkQ$kY>i7$un&?c+p!J)rj&yIPTb4Fki?8 z_kwubpPbl}4T}^wvS}~*W*OYlMKsUUS3`AMz19p+?Wg_E5UWDI!V)RlS8ZHINqzJV zurTv!f%=!FMmSYo9)CSHR8hXTT&k*mf`1u7m%ROkkew1%8s4O=2eKIGCEKf!~a z(Z*!MHGUXDIcIxBlt$XagIgdMOVoUSU2OA`p!xBFzOYP9mp4U-R9G8^qF4X)T|Zdv z2?he4Pe0_$tp11;KeS>9H=$AM16`uE=KLHKSyBQE16(ng&rd*D&DxjDMG0&6^TCc+? zn}sx=1RSyHTaDyxVy#aPU9|WFt?s91Ii-qVelhk;>nF_Oe(0JX>5iaxE}jNV46OdR|A*6+roP1zme0)?HkUt*!pl;Fbw`u z>^>%}UIyN$%8GFJU)l2SMC~r{5Sbq-)cDxhrjwRejW+gCKp7RMmP$4E? zAvr^(@}dlX0rW7#LV^ z$lnN%7%HyQC~c3L);)Il$F?c2MEYx@rXLJXy`Vv?a-b#|(s zl7;T^CBNIlX5gW?l(?W2c96QG{^?K1=q=zX-8-5n$Rb>4mr7yUBsv*sWtznA-XSP0 zIcj!UUY5D#2@D*Uc=*Sv*CO_fXZ=U~l4LtT8a+Mm#9dvSyH&M?`@=)pTrC+A0i~5& zAYV8zX!s}UsAB{S-ZUC?2WL%m#xbcEBv7{Yp^mO|MoYHdxbw!DZO|w1cSBq5x0aiS zKP4@CO|q3v_(e+ZWnD)E@TY2q2Ur)%##PVT1#z4w4hSq2H~7B?)aQVzjB8(-=vwlV zgWFfXH4yG>6BdW+XhZiMPdxn%NZC>W3lrrQ_ar^njJ9A7%XEq;7aT-x8F;ONJ(4|m zed^yJ$V+EW?e&4iqSI}2a(O!Vi+v}dW$TD{&*+6tzUr+n)kZZY+8{J~yTQfQg-83musU+X)^JZ_|LzuBhy`9PExqu!BhOGX-> z%Fi-(4CTvXtB#Pk*HeGDG#%^@g8qQ8XPC)*;lm@3yHB;{TS^tCOPi#VyBjisRw{*l z?nyot*hqB32eHKdR*@%ty_9%xZCXi=^0o3P#N2Hd%eBi z9{%liHB`FDMzi&e6e(JWIOTGgU8UgKeKvmC_^euMGwG^Fo_3^{{Sl&tiEIg*u$H9d zD;@DAnC#1|$aS_-Q?xmi$)I7{D3qQ=+#PD|th4iC){m`$-} zFM1jXQ!t7+TY-+WVEz%8ytLnFmMbSLKEVq2LSO%ID)A8hv1)ik>-h1}nv|lY(K|qJ z=^uMYlYk_SAGevnKD-51J*g93BtAaEP;!jGh|-=yd1ft{EIv)Gc=(_)^JcPi>7^)jQW5b`Ss?;-f9M)Jd!~ zsbBx&SKKL#h_z8@s!r}vI>;Om;o)pY?#tpEEkd9jOk*^uDLV;*C9pqMeH^~c%7xex zm6_X(A$%rz!-NTcZkeNDkrc|#`Pw+2n;x9{&hw=X`h zuinad%TSGIB~78UtUgQ1mB~O z(QUble Date: Wed, 13 Feb 2019 18:47:28 -0800 Subject: [PATCH 69/71] Fix author line Signed-off-by: Jacob Perron --- articles/actions.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/articles/actions.md b/articles/actions.md index 112a1bb8a..3f4fd1234 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -5,7 +5,7 @@ permalink: articles/actions.html abstract: Actions are one of the three core types of interaction between ROS nodes. This article specifies the requirements for actions, how they've changed from ROS 1, and how they're communicated. -author: '[Geoffrey Biggs](https://github.com/gbiggs)', '[Jacob Perron](https://github.com/jacobperron)', '[Shane Loretz](https://github.com/sloretz)' +author: '[Geoffrey Biggs](https://github.com/gbiggs) [Jacob Perron](https://github.com/jacobperron) [Shane Loretz](https://github.com/sloretz)' published: true --- From 1c98b9b7fbbeb5bde7cd36301c914e46016e1c0b Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 13 Feb 2019 18:51:15 -0800 Subject: [PATCH 70/71] Add third action interfaction example Signed-off-by: Jacob Perron --- articles/actions.md | 6 +++--- img/actions/interaction_example_2.png | Bin 0 -> 30542 bytes 2 files changed, 3 insertions(+), 3 deletions(-) create mode 100644 img/actions/interaction_example_2.png diff --git a/articles/actions.md b/articles/actions.md index 3f4fd1234..23496b53b 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -314,20 +314,20 @@ Following the goal request, the client makes an asynchronous request for the res The user defined method publishes feedback to the action client as it executes the goal. Ultimately, the user defined method populates a result message that is used as part of the result response. -![Goal Lifecycle Example 0](../img/actions/interaction_example_0.png) +![Action Interaction Example 0](../img/actions/interaction_example_0.png) #### Example 2 This example is almost identical to the first, but this time the action client requests for the goal to be canceled mid-execution. Note that the user defined method is allowed to perform any shutdown operations after the cancel request before returning with the cancellation result. -![Goal Lifecycle Example 1](../img/actions/interaction_example_1.png) +![Action Interaction Example 1](../img/actions/interaction_example_1.png) #### Example 3 Here is a more complex example involving multiple goals. -TODO +![Action Interaction Example 2](../img/actions/interaction_example_2.png) ### Topic and Service Name Examples diff --git a/img/actions/interaction_example_2.png b/img/actions/interaction_example_2.png new file mode 100644 index 0000000000000000000000000000000000000000..2441a89734d0f71d9097a587b2e58fb292697501 GIT binary patch literal 30542 zcmeGEr9yyr6AuD`5U8mt>OvsUT<~8c zE;jhf{M@xN1i}bWQ65%s{Ee2}WCg{Aib*4UG{zq~_kZ_AOZra;uv@Z#bXv+iEyZulxD?Fd(35 z*6(=Y$>x`_iOh-@4P!EOo}0gHu4Em@OIvQxi4XN}bW-_Jeoth&1B;q}x|Q-G9C>fPsswOe0*_wCGo z>yP5duzNQ8F+rMe|3C|$ich#VgMRWs{mf>r~V7@yh0LkLTs5tBGzkBO7HH z_@{awlw(Y+I%9uO>)I}*KPcH>9Ta+W3$7<_1|&5Q{SFS%E!XXJIrlfp*>|j`(a)@`8>~Lv@vGOCK19_X{j%?G zIG(ZhJy^3KlsPfqKV8jC3%dMmR?ZMN_>$uG>mw;8PnSu@>bGQC;_u~jp8cvU@L75L zq_285@OFx6;OX*8FMpFpG*Q|)yB`Ktt~J~1@S{LkRzq`%&qiQj-%0f;`3Atk+Pse^ zon=GW?!Q+EpB6fr3nl6iu;j?}FW;{4KHscP6SV0e$3>)nK0O>WOUqV@PIa8DdaEsS z+BW*xNQ~FiVJqzq0XZr$*?{ublLe-3*d*61^K3_2c~-fHMPt7TdxsG*C-i~IR}TRd zhJecS89}Eharcw?h-j>E`^`@!je^r(p9@9M`+j`-qcAyL#MWh{CZ!WJ#_!BDfV_X!%r*r&f@k;e_C1$tys^c zxF*)`^$uERVJc&nV2jM5vQB#YtNqODu7GTx1>#xn<3n|63e-hnPTZyS0@H4S^lV*E z_3jy;T&85--wnZsIC81J}F}ex)^>?Y&=n9P^QqhKV?_5q$PXlA+baQJNa2`Vvk3~$McZEWqLSc z1Jl3(sk<~Q>9vKjAFprnSRZNdPL&Dp?K`I=??vc?sr^51W-^cA$b(P%nz27E1xifn zs%p0z&--4{2x%m-YqovC9a_gU~X9T@w1FDUw;0RV-bDR5#tf>w>xvDy;;B=Wvwbzw|Bx-B_Nn}%B(!?@z z7%Mgj*bupN65Nf?8GN|n3of6nR^rt`I=G-wySjnc(Ti8-+bL=-)1K`Vk0N`Wb{E=L zB3WYZbke!M@;A#-B~goPhB4(;T!Y6ly1cU#l_Izw7OGwpc<(OM@#d=YH#{icacM~A zGw~$~SEWR)Nv7s|9}{45ULH+4ue9Rx3m9KN zC{DB)1sjqd6_UjeEFBiL2SKFw5$Gh0yyXFl)(&}z$^AW7LyC2M57qtqlAd4QWJXT* z{EyIXE(i0B9k8PO{R5KQQtrb_RBs7y-DUk+)VvKBoOSKIHDWs(a74x z3fHpP{RD!H@3r6-odXx4rrQF{ra7V1jvVynO6C{r+t{Drk7(zDpDWTue2E<0MI>{- zbsvyW!TVh0Frh1xU$XWk{P)mvBtE3&uHVtb69NuL+1)m>Jj?c%dA^4mFK*NVllt(d zq#Uset32#7Cji)hKARL1_HOc=5_fG&)1ri7sr&n!GXc;?vYb`|xhbZ;YV61ex)u)R zuy*TGXkUqk(pHqt`gS)*rtl5QUyT8EJ{P;4HrXulPrN@|Y{G!LC#iF` z!Qn;Fn2FbBi||?hBzrUYrgD_l1lz3?aR`l`^@A44*V4}8sDtK_h0hdM;=^|z^Oqf* z+_+o}w06tAR~WRes$HV_2u1^Cqx68l#Jai?SlHT0+(}`a-aB1`vP<#ztcS(-`-E(8 zJV4CRru$Okej8P^k;9L|hnBGYEUVMfImI(0R|?By=rj5#NL>SbYl`&u;IlFurLPY$NoWdbUO!W)tm) z(XbEuh9u@!>64TTZOTZYfP6Ntb<3{a22RXL+OX0tVeM8Hg_^Y(VCG{t&-`` z(5eAfofJ;a)q(}%hnMF9gwCDPS>4g5JPmCGp`UPqWErCd^6v!>sND6p{{73J*12ja zbt6C!hN$Vm9iPWoo@f3Nf8l*~4V;$s2Yn9`N%}d1tTrP?B4G%|ZafjKXkR=QDV#WA zZUK%#MM(K;yXl(G`CS<&Jtwe*8Z$X?x$@yx;h(iLWn8xlvQUM1H+?L2K0LrdhKgW# z%OP>@{-}7OeVS>dKO`M8M8C^SLWCNSId>SAF0zXBCjQ!~o^rg`I$KjPu}uF(4m((z;yW;lhJb~H0*V;#6_ktlW3sJ z@Gg%*3^v&JHF|w_W*u105IoL>g!EA>3-N6mu@S^^G1D&gbbELoG}XcPRc=Z`M)>Fx zdHHUliKh(f>djs{tugX>I7AsLq1XhZvSM|?yD9Duu!)Q&%5A)=nHXbe!w&weO?T8s zDSzGe{4;KGcD$WQj9N?gY(sggv-P&I7>m=zQxl$;{aLkZGk{ zJkI&P%wjZlE@CQ5ocMITU&yyL8b@D*PskJ%iC_M9h-E>1?Us`S=SV<=&5bUfEy)AQ z-j_L%idkVw;p%U_$%U=Eh<9&hIfJdY3MMUcrD=^Q~3?XBAY3OprrHE^9wVIyumqz#7w8T6X<(! zQF8>*mdR&;;Jzork-R!tWIGMPA`Fraww;RG-BQcObdnLR^jU8&C^T%8W(|Cm5(X)v zHdT=7eQ|Pw@!N$(16f*|F4J2qB$L_;22)}2H;In87}z)BKVuL{?H~=7-KMcW!hUhN{S7PKwg--> zH*T<^uW$JW_;sE7K~Ln4-=WS&sVHB*BtLS&@k2|@xr|W>lqXv1`Q5yyV=GDZ}-w6 zX)nXVNvqN|S3UO``qv^BaCTaEV3XRA|`Cp~6--XJ0vnXp@(!9q-Mh(t*FA_{h z-n1`5T3f$(mXnL=QvM^jXw0B~zBu}Ms*ijpDM&MF6u{_o))Kt0K}zuyejA@^b<&^p zrgQx!lLl7WTf>}gRG8(vBTeilMUHp=NUCF_y3RD7`)LSsDs^~5G?DSvX$Dp{O;4qC z_RcJt%y?#0DG^8LUFMNm>Yia9zL)3_R9rn+y}RLG!xpS~M&;~>tA-2m!W0LqDFfDy z(gNAD%5CpS^F%DR!7s0Sj;M`vUW)u&Yw%Baorr_*r?me~=!a?b&bIhBPFKPgR9y44$6+vHv#RKHtQOM|{H3p}2RiDCvtCNOKy%SmYFH#5^k(Qb*%f zFx~VjO5bX*;5-8Y<04RkeLBJ)^b~cK)-k4z}|7?6NmB^7*+UQB){Te!DI>vAh;G^9$g_ z0)IsLfb+8vE~m(|QM(i`kD$j5>+OxI$hoI7{VI(yV^nP2<{YP@45y+qHwt6h7Mp_58gWn{!+WlUE%e_Iby@i*2ZD7ZX@$^PNfMu>)iURj2JjZ ze6fb}HT1bt2xI_Jy3s7WJ zRWbQ@0Q{vJE#HV_rK(?9?`~lxKD;jH+<`ge{{J%c3VRT2m(=gQq$BTUdX1<}fOJN= zm~%#itA9XI{cI_mo~u>gCH&e0VMR z!M@D*;pL_F5Ou-vy+S3$VS!c>%x~5V1+@o@n2`YCxNH=g|l)t3P^R}A2A=mT2hc9 zx;v{nDp`O3puiG5gw%c0H#TJVh@L?4kUx%nvgQ2?wQB_ogazJ##K-*}T^Ri1Rl&<8 zU6{p)ELN`Zv&0!mVN%@h*~F=8-5-L({yi&bw!dbG*RS*NT0tl|m`?TYu;i+mx_J*_ z+|Xns!kh@s$yuO)o&);-g-CG;IK#XBpDRnENbJD~hS3OGTRAXB6M90h0Gc7gO~G%Z zI+wkr$S>zGHe&WmJsn+}NAMHI;5)o{GLiS{y2>$IbAsMObML$@G5qtChJvwCxzO$Ygk|=xkeZx{MW@{zq(&+cAU#T&-9HD_;Sk{2fkKT z8vhPj>i>7p{yS*%3@qxec?86!Ttc5tR()Ro_2pC0Eqm?1ABXYVf5-pOY54q7xb&1qXGW1<>)A_Jnw=J{3KPa2#+;sWV|7<;f&wZx_C#`Pl zYp=s><21-n8CK%&5egj71~s|N7Mn-8*z7WOn@|^FN?yoQQDeFH!rx`Z- z*A^JpmLG_iH$%REP$AOG)1V2RbZ(0zS$Sg>D}Y9{MpX_1xrk&z5J%nNZ#>C9Jz0$F zA9{bUf1y3PA5bHWG*QQ;)DLkokI%%{vO@bn&dqlG@li>}`bciHf3?Gepb%hULY{vN z_CX?(`lT|5D^M}Q{|0JLa$QpSToaasgk?5dRU zy&#~q&C|~0`#M|WYUK`s|I|FqwA6>6^xu}-^rqHrH~u5dKaHGY;0R-}=Nk|90ZL6n zXY_I}uC>MIFUZULEixUbht$kT`tLQX`PT5g z%eE-8{tzsDOcV$=oz4z_KLLZ;{wy-IioLtRS>d_)7^?FtBBnJv$RaJppGNziRis?@ z+wT|aZw|)r!f1UTLI14rbcGh01H5?q4H`kk7kE45{HDe{C^TYOJ^(X~3LnYW&V3|=mRdUAI=;PLy%Fvyxtg;;z+(dn_+sIU#m~)hKr^k7s9%UE3-0 zbaN4wSo5aQ9#@c#JcHgNVxdjEigItfzv zglqn0(Zf%#CrT|s{kLkjBYgm}>g~&vHQOTMeO#$3m*i^hN+SDgqC8h(yM7xB^RL zyHe!Ie=?Yn2T&ypw`Pfv^j2x9?O+CP0PGGp+KIpMDY#kTr0*oXUSq-&NmMIAfXrp7 z^RVy%iTS)tTP5J~Z2H8GuEPOWr>n56)pYmRwi-xxs)&7Ru6oK#itxGwp4P9=fA>7! zp`yf#z6!UI*>j{rJ6*QU$`tP#QMfg~86m+ZeSj9H3TbHruG*cBQM4DV+S19b@dEe< zRv{*V3R*kdNeUGB5X7@YlYg;aQ?dA?ttH(isd|9AmT zr>NBr(JeK`zZ>GFt*N_c2dLExaiR&An(i*!Z_i*K-Q;up&AjKsS7If%?ubo$=?(ToNgu>$b*;V!z*RSVP^Nm2Etssp}|mGM`=YB0%@qgz22yCb=qF!M=13Yo*3$#OYh%k1$Gg_GRD zxNryp*n)zITK9YdVN6e9Ahnmmn^hrd<)xIO8~M4Cyc#1>zLIjV~=3i~DBsMbvB;4rzIcHvRa9UQ`%m6db$ zo>WyAR%LEA$=5w;@1ERjN~&{g5}Vw5WKr#yvN*rCiNOvvYAAQ4DxJSwM~Gn5_?q`R zF%&P4r7Zt}y!tq>3jt*3_Q5({hjcpzX^_((^|eC+%_OkLPUWAAR|1bUus zQgjUg&8+619#w6^MEz|ZvBlqqf6PVQ-+i`ffkN_*D^@S&L{gc0xA=n`zcDIYkOM^9 zA0Dvf5wqr}xySQUM7qmA;JpGixleMtJ}G+gxAZ+mC{`}9Mm8Z+9jPh>3SA9A=XpZ5 zeblqmd8G>?W5!nE{Q=88$+{C>;3793W;&>hUOg@~52g{YR4h+~RC*bNKj%^@dm1O!6}>8||OI`SGgFp3q1qFEm>QE-ac&$bCiQTY@sV z*3tvFSfOkO>CD9t$>S+^&1gzqjW~Mgw&~*;zwJ$@re{C6p9X<_P=5=c{$!ewbHfj* zoo0*`P)-s8&N*ooc)HiAI)I=xz6FKH`J6*p(RrWgJuGzumQj&J6(17?o@4O@Z#g3SJf|D)OFFtEwTL|MJ zm~ZkFN3FV@Q<^HdX< zN49_i5kiII%s~*4D8W0&(_WdCe~YP;&P|Sl;&YIK0d)qYXi5>A9+W_OrD?gfTK)>p zpT3Xhe4Rq+8`<$zRfk7R33A+L$Dk^Wg$3%s~rWz+tEq$UVm za)hNf<0Mw73obFWBW`)VK|7V2A83-aRbTk<6J8g&V*WeNRG+o?5gGvg^^KVYIf7`+ z8eQ4q)-SS)G<;ZMYQndA4JTud#Ol}vrv0V;c7h5$N$+NowhT!l5 zUt>=&oXhJ!gHI%)?$v+ci1sC08R!>Y*$QkmTMniLfVx#;V-R=N0WhzKyC?30(i~at zd)*w-A_{kpL1be0;sy=#Pg18UpZygzqv9y1AP`y5a?g!qh!esIYkDCG6@xO9pcvO$ zf41?7lx)G>4#YJJmeDHDH%0{j0HGRUwN<=$$s=zZf;9j3f?$%yTKfNJ0dg0%fP3ag z>V1AJa!UKiB8AVSEju)Gcd=9b0`Ip5R~_1Bc`i4MP3szxyY;y}uEs&(Mn+(vx=1k` z40p;kdC)cTl*#f^=0}NmiSHjA#I@6p8Dz=?v|YaV68yZ(s*`YkFzD*L`DfJaM_SDg z9U2L@oHp0&$?qz^e}2ZI*1EgSTK1r;@%&H4;034#l@YvH(BkRQfnTk%}n)( zH4|-K>l}I*&rI9CGCEiAs!_H@mLgFhEWwOxsh@=@P!4R#mXhVkE@S>6T3G?1dNKpT zVLz`s`=pa0sB4B|<`-P{)jhU(_FJdFR?|Ct`CkxRw!6D9Pj84th zJA+1dIq-%ul-^BWfK?}vuQXkqsV~s9Q8P!$NzE>LhRiYC&UTn6U#MF6e5>@Ply~V) zw8LC-O#W1ym|I807XeV=p15<@V@*fx#@y#yRMbwqQ#9y8X`4$t$Aopx{eAZz4-%Q}Cvm zB-|P@D+u{XOYXf?flb%hctMTkw8n{E1#D_LjIz~m0~K)fy`rgiLUEiixa4pJ^qZkb zrk~%G^|tV(K?RqzY3}X`^rMU6J0K@0e*+6^vzx<5=H6=YUD7sm_qKFEav=Y(5emNa0!TC5OV`h$PIJF4dEy4K8nb9=jLTTVPCpdbRe-}feSQ$Ff66$Ifp5K$6Y1d z6Xvv#ChlY!uu(^cC<8~0zqHum0bSAQnd7lygYfXwBQakSJD=4|xUBnRVG^U01k&-2 z@DMJoBXWF4L695p92q=Gz$CVW&$Tj((BSu1prmwKm&4WZ%@5?@_>mrFJbXkK%<@t8 zPC+zid0iOFMNBz_RQ?Dk zbfR*XN$M3tNrSz%ZsDW6eY{VXQ$CBdpaU(#Sp(Wa%mq~tI7;XfOh!ysndH5=mmcv3 z3!nLEy@RNA99*9m-zVohmc=6SZK*a^Z&ZJ*ancP=3jqgo{T{fhx`?ned@8CoXC47# z7qBfE1|&{&#)by&8RxM=eGq}Em@>KU-?Y(KW4By+rXp(g5Gj1O^or={UmC^h;V~N9 z??gXT-VkV3R=x>Qd<9p>g|*E`47xb`wjFlimqy_r>Z#`%S$JJ7nb%xI~sd8{lbjE9E@*ZF>@<(w~gRyAI&omtBgI#zL>(Vk)r)uL)5dmcHtR;2VTJHK)<~XIFgA0kE?SKgjy(bV! z^&A63PImj{sBI#`Wi!F#1=~xFc&dF8__L_jGJmZ{_WAlTH?*Fp=EO(T>i!!KUT66z zrPtw6?YG28in*KMze5!6P0wjDG558XO^M^KbsAM7r7F)HHQh>=^UGMS_KnOG5+1n$cMR5~_Z|oQ zZ_n+Fl93!xL2K9Od*1q`ThM%Or#(h>K4+d>hmeGP;+j|&vjl<&NvFvwM@tdtgIeYV zk($FuiuqQS&v&W9D58EWz5BGnL1c|d`r%uQs;D^+vtE1vqUIuzO%DEurC`+>(ZTX7 zfjS#y0IQPAtjTw&YF?&uJgxWRQ5yZ(CGU>N>!Q&1?rv%G-R2h4G|06C^sWZV6UG*cR^cj1v1jHrQc$`F5Cc zXTihPnZ$B2&x?nk#bt1sYTLaq&^JxSM;+%)mUm`F7gS>^rF}q>kz58Uh)boHJt$F6 zHpY0V_%&x-N4+mB4DVIe{ zWfpHh%YxWQz^ZF(u68-8+T$|Qz>vbE_c(0Zn!zVnS#2_OgO+%&A9GjpsWX1WNA?On zoVj`}C(OAU(zmh~LfA-9sI@}C>GS>5Tuz)XJ1cSCpL~rjm2(YkSQyQCUJE5b{asNf z39Q@$>x|JKRjqsQRLXU^&R#l%wn>Y0Awd{64W@lfuX`BS;w!KjH#oycyf2k5H@u^X1 znd53IF*(XOjbvHnF9s)Pg#P<$DaHT#D<>zGI*!9E$aAsm4|+aFgShTpbOotahQpZ1 zq-U|38ZXP&>2Q%a=1XFh$Q0LFZ6IJe->3E3Z{>VKtRXFBzC~i*ae)>}*lL|1X z_`lb4#G^w*#(ds*jmeN0N6E1;ukgClP5#MEfFvG4V@bTim z%gKF=el^iWJ%<0ArdoxIDhzl(*?lATe{g&>|Z;B&ekCn%WHbD~wTl}^)-&$dPjlHL~yDlQ|=O#b7q6F^x+ z0|LdVYK^yoBZHA7EICtd+cORQAlK6XdY-;8I9Xpbf1{lYNcG+vzmTP!0rDGrdjB1H zbnx~Tjeg0wblY?vJBjKYzf0RERW5dD>8N^VFQ}{IX09A~w$6cuzv#d{4Xtk6kIWZ3pPX~aC;7P{x}HnMb0!d`W{gkRU;mfhuMdbK`+yp>PfuIg z24rfsH$@%noNDH=_3AtwE8LcQD&^sGi+|ZE*Zu6U0-g6E6E&_MBtW6GA7sjHFTVnb z+-JF`eQyNx>oF4X5QLnW<;3Fuh91KNhqn2ZV(17Uw(W=(5h^vKYNzD!A?f2OtByDZ z=UCY*Z!`G<04Xe!EucOgAd5~z$KJ@14&9s5zLgZ)HCW#;5gU!}bMif8l>heI5)gWG ze{?E}{qK@q03GielIHoBw~OOhLqKjh_GhYA&)6d~=&H8hK|!JfK$IHb z#A?nq2518DXa7j9dizUe{kDax-z80{fIp{!d_9WdVWYp#M7{^eJbQ`Yq&17BzV+k| zq_>=Emnnt(jvSy&5L=MkyO{u09c#yrTK6YvZy0Ij0b!t!gXKiZC)^?VJyZE*z5%Eb z^8h5xbDI9z>JEwmx86jJ8lo@VS>$1lv0AhK7=UQc=yriD6BrTkfx-3sOs6h@KwDLT zl$zpr`NtzOUdG1Rz;i1>dtk?FrFOd&4`C2ID7F8} z!1eO{Sgd;5GYzRXr1$e%$=g#Qg?|Qe>95(0IAwB77yo(7Ys$ju>pFXcgyy?1K+I-L8I&HijL#`=}^?&EZn#5PcJ35ih}(r#XnkVY;*aTe@{nd{ps+dHTm^s45EX3TJN_% z01cTf0NZE~pR9-zSl^U%$un_Ob=;%eWG#_cZ~|n$e=_#flGx#lB--EHn7O`TJA{1Y z3^Sd;kdZ@kL|~E?h!CRD5%x*h7fV{Ol7^$yoaQC~1uQ9`%5>kt@V9f4v`9M~7(6FE zYiU2vNJNsBqG4unx14eXX7qtPX2Dx;=FXSs&^fExDuR% z{A`ML36Os-AxRHjniMp1p5m#i39O2!4m{V< zTc*wGU&_y$sG77&UFbFAqoVbNKT_swjm3Spohq$*#`m_xB*?_4{6VU)0`%3%R$mg? zPTuQNbNtqGl%U+M3fPO)GARR8$0T;nEy3Zi2iQfc2kL*9|9>X>1*-QwdLRFTJY0t5 z_D%P!EhQ=wRym4jaf(okAbeOUk<5vl*3g{w1>jst1Kt|p^-0R(Db#UZlYum{Pn5Yi zClGzJo_L6>9zDNajQ>uIVn?<{IS!IUGa>6>;z=f2jI5Dv44jr{$H(N?qhdC1KPL>O6e!pI= zHz-Ges+6cL;IMAY7r^sy=PGe3h2-Az>sSod9nMzLL@P9vI!QEY`aW9TPz6OJjUz7$ zF4qm|{9hGZG-9-~er>j!w9fVSH=N%E98D~Uekc?umetz+`1ng9qz_aNoze3A9uybL zMGUoo0;0x+sF?R*Au2tdhzO}GHB&H)b&V#bK4=jctADZ2R_$ueHqh|uXtm^f=RM(a zrDUEZ0;Mm+w;H*>UpibsY45*KVL-k4FBD&gVhG0E6iIA<&GN348=K%JYqUdA;!)+X zv3Z-pfYiPQ8k53Rl^!E_rXZAAqhFufe=jj>n$CSV?n1ZTXb)sks7LSV5UkLbQ$*_P z;2@CCyyiFK)BJedUZxGaKQk%hEBOtX3?(6(W-Vk+sEw7v*a3_2B8}gaC(`7 z_2*qo5vp`iWxDHc%gTaN{q&mpKH0xsuPtAnMW5b@DWNn+a#T5&W5Xj(R`b6Xq*4bY zx_)JI<#SfctT47;dS3XyBQPVqvoJr#mm-(%X?_kRlJO?eS*U!D#43%(K^SlwxEmAw zEz~d~ixi_s^8i)VrTQ~&6_?!KZ=ghXPELek_Q^*s&$WbN`Kvaf%cv0A3rhlJ(yh9! z>AGm6J;2GRdVAT*(U+JnhQRb+7})6pA4gXO1f_vQH0=C$2tHpajLq1trt9MiIwBM` zMzrMX8^_;5qAF1ia#7U!)lSoWt>O5`#A?8VFS|oVS+u5`+aoCSh&g@gzpsFAPt}X# zvOHu`q#_rEH#nR%nyrNIYIyW#LT@TA9G`07K-lou8J*b{Ij85oz(W|4R?e_Xk(LIG zJ5Jg>797qBOGci@iX*_MOxTk2{+8R$wGP;16h5M+5yWGBI6q+Kw4x5GH&H;#&HR&` zk=QVb`t}o$R_ZcMeCST%NCQ!cy8lN;ojq?3QN`R9fb1V~i!a80yP1vHulLzM>N<IBRH1mbQj-UQ5X3KWzI%zc z(d3*)5Psv2=7QKy{H;n*!@xgzP-HOtpu}_z%!E^~dZyfI$4#As3wy)5f)W7qJD^WxhX$Q!D zUVcwu5ZcT?dH$V8w8viOafNM6Jui0wW@5r$`^xv$FMotmhq*2WOP}lHKO3yZ$}b-k zktB9USKG&Efk0D@&HOeLjZ5Bb2Ix6bZ8oZZVQ3g20L7JLM@cc|Loq5JECfAu8OI`E z{jdMroPsAnAB?f9p1NxPw~2A_MKv=Ge$hs+{)pz9tN%6Uwd^tVkX*Yvd+b0%EAspX zwk+CS*O|Y1Tqe3jf(>lfd7@^790Vd>_P|1cCf0?Y}cWWR)dSOeUlCb|;kVsEFxW%n%2 zD6rdlu_i;&dXn$H>{$bXQ5UxM0|b56(zhc=b$haB#_=S}Z<%`lslXOg3)IaPa>Cd2 z3)ajcUzFVIF2igs4tigW%I+Uiby?sfCq#}aM$pOHK(tSa_w*_~$I8It%66KTI2@53?{MSCDjNqA?gh)RyOB zeOdUeD+8o`oYvZjzWEPWi9LaI1EF*q=0Tt|EZ+HQzw@KY2UH{ai5z~WO{OGL+&ZAk zvC;LTTc_1ofT)kjMUiDlFbdg`A1N`}f$px07bc)V3zjpCin{^-5 z?9!->mL=iM@PPZczx;yr7#>;eJ zY1|)P<${`2>|opMAM_Oa6qmR@{GDP1g&!y-*4+-ZG}IwYy?e)i3REhRZVKuE&TV6L zhvM#|&yU%#dbb+Sog@^ZvTcE`vOq6C74#4O(t!}f&j&r5pIiA5vIbhCG(p`a$CNNx z@%?u#NliJdp{R$5G!~tcz=gIbw+(2PqJXH@k2j)@sqc-u?yKCgL6>$QLu=e02(>$% zeuA%nX+gO6wzKp%5N3V*b-9w}oEnUQvxSX$q!$1JV3=yt#a=Xxpmn4R(T+^kk7*O-oZet?vW+Hq}zf8=$^b<)F{o)?$zqVV8hGleXKc_w&FMYqG3sM<$NsW_JqR6i&6%=1|++3VmWw4Q|4$SyTw1{ zP;(%qll_=og?$tFFt;7FP~vv7lmzW<8l7yAmv)iymDYS@e@Q#sp_}c-Nl97Upqib2 z_`lQ|&$uK`T)5N+z{&lc`4~a?iIEZkdOob7Xx!XS@yOT$bP=)Y6K{P{J-+3dIcDnD zkK!@Z<;iahIPVeZMv{gTL5ViDycKEecq%|$b#Uj7_m-q_=$B_d1c51!A9OvRhq12w z`1FWhDCo++R<_b^m>H_s5!|kH5ve-?E@B4KVTkijw89W*Ts$E_A9#tP;hK#N&?xg7 zN0A4+nbAImnw0WJv(f^FQ)8|BYAWa;QcXQ9X}aRx<*<~H_B#>=nhHv}W;UFJHDtI5 zNJG}ikQ0?plZ?$i>M*IruT9lfuxiG?lFPw_ZBsTfqyN2BUuW1JxQ_oe)J@^2&jmxcbIHG-wKWN}O+ zP_J8W_O*laws#$L6|g8?aVpg=Ms_5I_0mV4~1YILC2MlSd}@u(8hqp!Kg zU;f416?OJUkAX?h{;4*L?l$^Qw_$)=mg@GrP(t7XK7aiX5J%iv$xCxW_)1ySKvG!W zhO#D4c`wE+kV=E{wiO}o$7luW6|O$3|AKzRzo0+;HKbT?!J7E#ZqU_fe%nx&7LRew z4t+h&^ZPEoFqDKE4_?K&_(9faQ&7GBgn@kob_W#6DZNB4%nrU|JT>c%11S5@z?K!oUVNU>TI!PEpeXL8*Sua zIaic8XS!}IREmcSAWvzo2X*h-nt-*fr~hUc|35R7m46Bh;!2FzOnifOAPE*_321LD zz^r#$MilJSS$C5*ebxTT@C?aoP}&UI%9z*f4?`N*%>TY7sqBBfX5H-iEG0cfC5p7k zZX`!-1>`b+d$B<@DTL0z-%9zEn@w{}6H&y1R&8gXZg_q0#TWDhGkP>15rFCyEVV0kPMt z-*!WF-6fzwIhUaH%exG;WX{e`4Tt&?`El7{|0Cu|r2S9Kv9V>9XbJb)nyQ7_9Y|Pp z+~6{rEix3^-wwK-bkX$%bSpt*A3O0M^#Gt@LzW&-`JfGHoa|K%Qke&~#Mf}3 z3r%HKdZ}91N$=Np0Zb0e1;U0L%~2zh@Qo4$S{}L-bOpLwGVc~*?E8-+76^k zi=i~Fq}5Lb)d?7P{k(D z94++Ddm(D2Uu>4VdG{9vuIV{{)5VBCXls5kPN3-543(3-JovusF82Yzv61bM_dn#I z@Q+`rkn>?epf?9jZ|fJmK?m0m3VrJQ5BDIq7$ez~uIV12yFB3^EjKTLl7>R(SGi5} z{{BsJY{$Q(a#3HWXZO`yl?8N;X&Zzmv9-I~N9b0u>Ls9^I2n6ND$Q$LqeIySgfVQc z$tHSDa_}9C1P(al?pDoWAL!j~dj>OzY@c)c*20VzU7}`zZTKml%d7e9gV?~B~#(r^9dyxiCnf`lGJ6P1*r!40xDInHF^JJ?2*=9}Y||o>M@!7iocsV2j5dyHKT!(|9sy*RbA4`5`Zygq09s9X ze&ViAjXt{x!VLrUnh6lza5&bof4v0X!{KN)DCns+T?8i1lnt^AKm|wrA_EJ~MJ-79ElpR8H=NC39^3IrL62=^{ttE*MMAfhjF4S#B!a8>ceh z-19BI?guhM?Cza)D$cU;#hV}Q3T}xN5fnw=lJtCo?#aWp&jo}FhK=k&H*m(1O=rkF zu6E*Wb^$H#QMn37x7;D-7A@uzkUI}L+rPe--m3CeEXSO~#Vu=!s-*+i)4&aYJSzJe zDRfwb(5xq!0s1^rXVU=jBDv?_$azz=v~Brj?!iA3HL}_@OHYm(L2<~N&bR>?wb4F^ zlzRq&CE+3Bj9vg&l8LLSUP%En-N$crGXaM}Op`~)@;y_y=jq;Z9^lC%V@N0l>pmWX z^lRL6nMm~=P~iq@A8Y6WP-{ewUYzddW&$CjE+k0_PmF}`t*GO#H{jzL%s9-a$+%SS z$X-;`l#wJI@oYGR(1|&vTL+>=v5P2?qd0*IjWU2Dlg^VxLlFQJgfM7{kyf~xngK6TF?#bXwi0i zidnWIe0O<2Z@`Gnxq+DGVZFefEkcs zl$$=k*}lINhXy3UH0J2Cf>kLxlpfT$%unlLUd**jdSMVNyrOV{m`5I#%0`?kfFG5p zuL-Cj41{pc8~{(E@x9*19jah#w1d?=5=)JUizC3`dOC%g%CV?497Wmr8m=Q02RXgTIF%daHxI}yURVXrugz>lL?26c$d`m-Rz z(l9gcV(vh&4TKGFdA`zJD-hE^(vZ(u3dXvOcf{Ix_)$l`2%9phV&JYi4}CKdEA7=M zRh@;q#s+O{HB@uq(fG`~)TTg0eLkJlHfunSq|wJ2o9}2jYrYlsymgj%7jB7#3|5&j zz3Kdc^~d9<7)Xl==p7^p%@ew^MG{x|R%rVQ$xmj#XAp5p#FSi)wh%oL$}aj)<+_XM zCd$CWHHc(&FS-?m*j<7~3U#j0_%^2}JuY4XwL`Skr2TM~hL2tr=546C#XJ^kX_)u- z&c8BmHsl=m(SUewh;v3w2JYR8A$APJ!JuW_b4oP`(`yJHkKotRAu0843^rrano5W= z5vml~mDswl*US$TDU|We+~1_(5cg|Ub=JrJZ3>b1j6omx9!1bGU_i}ejPjy8*qjN| z%OuVVNYbqiRUKy0vZvqK%POTpQtWh?O`O(DE|8% zEE;*k1tGdOTUiF~^@U(1{NXsVi%*TFXj7nHZ?xi&79bn(D@z||X+el9oe;hhxq2ZW!D!*1i#i35N~wEU;3# zNT*R6`m0ek!&;L&V48v$Ka*3|JB1f4+48^o^G1gdep{@|+ zn(mVufsng`U$X}t7H16D!LP|syftrVA$v_AaD#`vBkD`!|DT4Vpt}Z_MyT@#F_9!d zV$0{xfB%f4P*SE=W2-sB?XiktCR=LvR}6VvzE3x8D$ivC-#A?VS7^!orp{j6Z?D6w z7t@ZPLXPiL9(E|t40B#2p0H%4if>F)XUV26aFTp-kAM(nu9x6Yj-1t=7e zN5RWF0Tx<)J^^z5fO*Xe6U_upnLv?B>3}?J5IFN%GD_4 z?~ne`IA+eAbFS-py`HbvwbgTgDYRq3i#vshA+DRwF&`s#rd3C^$1~y&f$D#n|-QCw0ux_M0(TN)PN+^3du(YY?uL0?J!y4O^PwJ%p^^f8=lY9tA0Kg}44$6c71i$H z`!bX3)&KJkiox-hJj0=SM-KG1^@`P*eVa>GitwQeFFO5k=J(DcC^Vw4+Hi4&w}`v@5ovT(T~yLuVub#Sdc2hhIZ-`zoiPa-OaJSKxj*W-AYYp7P{_3i z0$jR7_PGB%s~|7#=+!m)mlv*5I~Fx8o#y_$jo4AI3VSfWlPHj-N7(>#obRZzzm{_q z=e%<5v2hKouWs148`{=QKdemU=6VAEagH?mV@U8OF$a0KN*+*9wVF@F(n_PsEjr{Q z+@1&=!prT22g>9e(Rq^5{lYIbnJQabFz)#f?x)}5?}a=1jfnG#DbRT5i_kC8lO6sXunQ->wh; zmbe#^a}L#JG!wTcm*YVb%)@6ac00gJ)X7YMhl1!fjVw{`vz+Tcro^J!c`C=vaDqK( ztB|E!Ps3plSM*hS!i4!w>gq*~>l05TsEiefZU_rYQSEFsDdPBDycc!CKg8W}+mFGr zH^a}l{O1|5)1LywB&KO{^0h;?RfL9d_EQI|Q3M!jbeR|^wa{nXHXz?!?>S*@(D>zT zqBffD341z*U{&q+*I(l6=PUt#=_)(*>4VV%p%}|``Se|}EZ^SxNjB1c0pI5_V&nHr z6P7p=IxOVTu{Bpeo!PvXLs>s)#Yx6%eu*oLhImVc zq-f$3?~q#^EB6W&%V@IdH$Uk}X^U3ou`xQ1v4zpEUHf^U))Dcs6c)kAxj6{wKRL;~ zpU?Pzypx%<#L_kgE?tUoufi#=;w&$aA6bbuQn9vUZGrmXxKEd$ifv4d2VBUs!KruL zLNYVcFJc7`;T6YSe(nBfjhj2r=v{I=lAnaI{cHXQ85S1tM>BZIRf84)aSVZEv!u zsIxp0)v_@YV~oC^7KVz+Zb7_2puQ1R0;jNNoh3ro8?8bjx0?N?rUF7DkazTWdTo)5 z|Mko1+^;Xzj9Y^OnZ$oq01uFvDeX-814Xmh@mb4^q+I3~>u#y`dk&H!BoUb>RPl!% z|DXf^Sreehq8rVxer}XNh(Z$`v)22qui>K9rUBuh`}UUU&U@Ed(5(ndeTq}8?(7?W z-(gn6O{o1D(7M_yjQeefct@ev)(1C~gX-%9*?)X!d6eG|ik9FnDT5tqi1>hSBpa%r z+Zo50p>(K`3vY^UfV9TG+wNvluKu=P>yNTMCj&G{p{ee@O8iX%>fy=04rBy;DMyvK z-nsqN^A-wz69_fer2XcHM5ab4ZQDqqYFgLjBDCn~eiDA(w2+6SaC6bZ?(C$&tRB-bb8?^7>|P$o}yJR?t-`k+ou z&Oc(8K0I_LDvI!cOdUQ7wE>J~aXNVzZ6%-*x$A-Au>r=i-@9z!We#InUo?1$}~ zwBbNZ7&nE_pNOHfDUGUEXZ|{NA9%a%%5uWalC){BQeP$%iFE#<Py0r5;pLk&M^ha@uDSwB|i`PVY>G}>xP@)OYOsHp|U1;xG zUZ8H*0_y(x-r`ao#w|ef07vO-7`tz- zPIeBPC~i@$a)p-U;9G?g3fJxzD(?IfNbZNSwUQJO-u9Y^`(kmscQ)b&>+n!(as@Ou z0kNl*7n@@HmOva}NGihbfGQ=ro_Swi{a7nxqL{|qZv7bg`mTb2Spw==k+V*xio7@HhD`mlR;YqFS>mkwT(8k{aS_eA4Cp3ONgJj%Q z8uX;v)pm^_-s z8wCP7FaWhmZx?p3B8?(j7VR zC{TL28IG!)10BMo@GKdeUCpu+yGYc`Or3truYj)S^t>H4o1#Tq)GQVCN3xHTjII(X zUK7R&tdD2sGHk@s&Bb(71v7>deLVly(6wO%E6?RB1b(N)BV*S$u%xVv?Da&JEu_Y1 zsQ9FYLbcRza`8{qRbZA&z4tMv0(7bBifIxC^O`nOqr`*YPlpEkjc9 z9$;~3EJSuDsPJ;JhclcY$b|*0hxg{&*^+HQ5D0lWb*CP?zh;md&8ZXk zYK+&!F|9I)G*2B8^CLg0eV{bZaf4OtA#_7_15n8?CNQ;gWxV-G&ZQ$EL(a7YkDU4# zrbvzoTztCbA!#>0GchA@{-=T4eb9QnwS9o)>tu~OWeUum zwC8xUQtcluTGr~}>VBlA>br}HQEz64sD~Re&ek;&WQ-~38U;Eqi4{BK-8nbEmQCLV z_A$4^#KMsz3CS1Q1n-$mD>e33bDSJ1pNrvu*%MEia<&(@vJNU9@oa|Pkl zm~UjZF2f};Yk@CWeeeEHSmGG_Usz(ZGgk&enH^5e&z9KzUM2&x#Uq zqFW}j;fWdZsW2L^k$8*B$E&e7#Q~#TV$RltT&IdEF-tNG7KBM1aAn%%>jFQ{)E|gn zZvJI3^0F-(6KX&lZ-(EU8Qpa(zxZfZ%w%&YNSYgl$o}qA53Nlu(kV)uI1|)7maoFE zd}%{fpp4XwH>v#3$VUF+4aZL7t4xoNkGNyoQvllz|CP2>q+bB*V?|BLdAO&iwE zH|6CV`7L9|eRKQwdmcHhB!Bn0{_y2Xkl;N)U5jeL;sS2@@A%IqYhiDx6Tw0IMf&`a zoN(Kw8#_IowSjY;G1MYlq|%Q)C!S^8`sjJ=3CNIS;+YMVA`ccopYJGkWN3E$1YX9y7e3UbV`UfkD}oIqtNKZ;(Ez=AQNr1XX04GI z!{iLe%^V&PtSrG)Lk@Dsd9<~`go2I-3^DR`?#~*bM?ynrqvX9C9oK5OsHrV2y|vMc zU-Q+}jL)G3kQed4s?rEG2_Bh@q9V>XNLtqhH-aFXbX1Ud3{^%la(>=K3*25`anB8} z`;=IcOuU8LCo#7Fcw`Pt6$-ghBgHHnsUW>isz>5^5$2N-C%ITH1#gCMm_jDkgZQLf zT$$dfA1}-_-R3D%6NE(;??O(_d`93w+dZ2A#a zg|`r}``Dj#s_&7@8_f+nDxHIreP}Z`=|PQ z;En~PwcIdTk03~V%de0!e?}Q3NSSKzr8D$_D(ukw(_nV^7>iW$NrZ zDa+nlLcH}&wVhg7d5_M#uz95(GajWJQ~-6inHXN|T}pbPyU?eL5U^!9CejLhu0S0=vP^{^n;n; zoAGh-tq+!~`mV$OM8cJSj`>=JGbi~O@<5;3BmDg{WGlvp28zKQxNG;~woXo50H7Bs zeD4MCJkMibd`q=XdeyzDj7#BIi}Exc|YyY=hU zs#+N7vfKkUakA{KG113k_HtB5kD_hC2I2WYFJ!81Z-xKEVHf5|+Us&aJA_VB0E4{6 z2AO7)?EC+Tfakt>ip&A+eM4^ET_2Qh7gh^E9>}VM*Bb42bPDgXX8MGfeWaM|r0op>rLz2>=hMTu!znH2Eut3adw3CxiSa7{J-kCaS*H8LX-}=$ zb&&&njr{(?;Ph~58b)_AoI@HCGrugj*tS2gLqZ-0_58F(>f0Ra0UnE^US_gP@b!` zHYGwA0p64lf;mSE-z}~?1ZE}GU747Q%!UmJ7jeJWxX2OVqC+Dn)9jAZkr6dpbz1m_0CT}vY z%YN|r^l!h66+^*FrQ32^pafV|iwz@$(1JRuAU`0qly=2dgvt+eHxNO#3wbwNXa51& z4A>vlV^u_X--YHN58Tq}#6X|x6W>J{MFaAbG>!lxr=+tJ%zq{L>LW8yTnS6q1x|%_5!i}WU_Lcc| zl#$Ufmc$>dPe&5gW$}HBGcZNT*@pTF!r@(bAc@SsFn$`Qe7~S?AFmJ$?KCCNMZb?! z_Z>7Xe^cw{bwv#r%-k~#2(l!VNNN^de0>gNjf_D+q8+?SYlgO-%;&{fuI5PzL6SoX zapV^czLd2y*7&COXxvLk=~S!0&24x>oG^Ib__K>y!%)d+T3SZ-g~RT~cm2)fpV zb?z^a&n%Bqf=^J#iGRZ^;H>Hr4@-q?#O~}Z@NuI(l`VIQ`6yV@Nrh{q>luE`VlWkR zlOTLaG0%_LF?_3A6bRfb0pDbPqu8_z=bbmUI@jmKcmG!h*K-PrN*oZ4jzdkydr6QDCw~i4StK6{fuoFSJ(CCcR0@&lgHvu zW-;5$S<=o4Z^P`{ucp!A|Kw!?(qb!q(FGbf{tfxOT~bEJT-YLg_*$ zZ&XFs0bY>;==oP4Pk_b4hw1k-N3!fg zI`vAGoRvrCNXRiA%&ji;!PiI$25P{G67KH!rK|Ot-zb;Q$8umYN)Fl259D^9Vyu|m z1AF<14iyi-Q3loLXabFe;n2+&p^YI-%V$$OU#qSq1iij!eYg4}$qS^U{Ezc;n1S7g z)@D-Pwgo7lN`CA=-ez$)jWQkO+3Kia9C&I%5N^F^gH_*VXqx`a(L=o9SV2Tjl_P)X zf;xFq#q*I~m^g~mBcvb%L-=#ThK<2s3|h3&y!)&0O*4v@ta$CD6XYPK!#K}HP$hn? z*w$MVqlBqeRf()gQsV1DGisTgkY`6nCpE|+|GqaRogI}+Mt1R6$YlUJWC2Ao^tSYVEMIfB>RQXD zY-{qJJGaJIGf(H#hzs|xH$zq@O~@>z1tW6Mt-!%qR{g{;L{16*HZMeeA@C#gx$#_P zi*sZ6yr6RWJ?5OrgU(xUYAMbn9zxf{N!d}4GLf|{>t@6*bE(@+je7D6>_lqxxV8}K9c+aqVKubxBX9| zK3dUM=|2sOuq!H;dzO)^8s+5A-61rPWXUi@Q-?pbhr)Nf_Ob1mU>hKkhA z{L^QVfEp4s|fz%Gij6P?<}YhmmvM&qYJDg zw6)M6FY++@l}#;<*;KvqM0$k8u%bUydpdQD^TPO%y2$p_XWlHt2Fbv4|1?MrO>?-W zaRngw6`M^9%)q_7Sov{Y4Hs2Aw*7K4wxD;7*R5}=4C$*uwxKw3K>^Z2oF1|;ef$O8 z_#LyK8w{t#kvig;Zh?wrp-3IzuC3ll%?TS3>oGH#A`5l5G&&SD9 z6vS#ImxjK~w!)fM2PdWQA-u34g!HgCy*{~=>S#D%bf!Uplbo5Kv?b%c5JUI?REE;_ z;yWRdWR;JqF{zJ9;xEUN@>0s+W){G=*Ji@spU{Z3k5#>=W-84F!q|UXGx#&#>F~dk zi#Jl{F^4b$#(WXKHU+x09&#e-ptnk;*+vFo4^+x&On$`L$LH9G@~YqCICtzjQyn>$ zrT%S=gVxm{u9;ytE()Y4fQo|D#TeyypR>!pk4^AFEEM$h zaOoI5zj4g*qeVw;pz~qo*$G(>5%N7v zOhNZvH6CdVoVtS!eGQDDJJ8<3A(WnDQIuV%Axr06Ua>O+Pa^D*6j13O#%0wupuwn9 z>m;XAZ`wt%ct>|69~bTvVH$--HlfWg_~Qd2*J8p-f@5Z3t&9Yev2AD3s^{q-{Zojf ze*z+zsUZF{;oT={zn6r98g&#shN1eFz)E*}eKN4;%KxAE56(Z`M-;{*i(f?PtK-iL zqVyHXQ+EIGR?;owDr+SYnXS$f2t=CH?m~-gm)6)X~vfzHk zBAcv5Z3M)yfkLgX9b~*#Hh`yPV5m^X1No@1Ik%6{grMeLDLwC6nYVhvhu1U5rS;{%SIyGDSoc4*tYnG*Tgzfb0R*YjFel7lj`t@)Y# z6DDDudilzqk$gB(MjZ#*d<3e+#rDBFJsOON5xZ}l}qE;|%&?Wl!q+H=lOK=vrIM9`%yG zt>JCrxrlHv*4CoF>FxpbD|>yqMyqdczu+60dI*DzIa0MeoEB-FABY@$^#s1QO5x_q zYG~$*J8Lm7&_6>-?8~(@x$b63?8|*Xq3=1H4b6fuYkyW2c>_O)j0#DEzmC7Hi9&{o zu=2>>$0o=RC-JsvOv1=<>F^KkSuvN9Ql>-GFj?-mNu-pqw17@=&m@5rkNk|hvjUof zi6ziF?=B)Gzfk3Pf*^uT=!35?XO{7@gB8$zn}KfuJ1+Q4rdO}E&{E6RWq8PzPO1{ z0uw-BNs z$V(A|u8oh(hox*LT)l>$4y4DIf$}%(i!PVb$=honR zl>VdfwXg47#rM!GsCfAA-hMlFv?q`<~SJf>s z1RKVS*Nj68BF0zT5WrvZdiW3S>kA+joHP1VFFZA4Ur|bNy4M!i*~65w#vg_XPI^tM z)ZmIHrV-F0XeD6ziPjhsO8sd%jz?f>1Le0Moq`k}Bc-9gAlTe9ItPlU?*%NIfD)uC zri0qw!D^V{HHZmZ4l!g{tGEj^6-&?>aVkE0_vKAj10FT=XO9sN?TJ*S=~nc6W^1{k zb*ez2ZrrL0MN(WTbFxANSyg&U7*1&CYu~8`8fX)+xr;4Ky=-JZ^zxl*Gg7ya!FDx( z723;)E!LaRgS|Bl$(ge?n$-%&9TYcNKTIC%U}ey0{Kln90S&}at}luqlKVMHfaGVu z%4GZVxcO(rN;O;$IEUuZ(+mRsfiqd{*R@#UBqw`?VdFQ-l>R;5 zhNqVh#u$4i+~Q{VsOQ zIz`41*(5Qi;`9_r%yC}66n8Ys%EMH3FNo4-LFI5PF|Q^Ii$*D=SQu6m4}f3!vAjif zj;@9a-2{Ck6)t0qHH}ZJi%+j;5oPsa+3J)L3p zWqB3%wS}RSepTE7Thgjq2hX4`LPUpbGEAKq`sKKzlwy8O^1P?lXU%VnmGW(+F!?HK z8t*%F6?ZLrKE#o6jVIm1R!QTV(f*%3vVJedRr@IAqVP4f{bohGmIJquYTn<2w<1FS zIUO+X=?HsuK-Gv!$?=4J{%uJ1uggMm}S^rf>5@h==%dp?j&vb!et1uW^ zGp;p(lt2^Tt$YCgy!p+jAz5tyvtM-+5^HG#MQx)>@4o?E?zZvS*QTeO#{+6b!L3r* zaSljytM3yw!bxB+K152l|6-v~J<$L5G}TmEnFwX0`&IE{p6&EhHJ(&PlvmtDBTSg1 zISEC$i}KG+9^{44j) zuHI(PUbN@V&+w(+3;gHUGncY=x8I$Sl&fkD%M-ew^lC1Z$-=0X{u6`@xK#Bw#*?HJ zpuW+cIr5`$Xdme?$PW!WZEPY2!yKGsvdk~#TGroRXb=(<+(*bJM~gr3SO~Dvy1^U6 z^Lv9q2V={{*uSv94dkg~>)^F~$L{3oOcV`ef9{}6T4aWb0ZHFQVr+#M`_ zf?pEppWOA;4GPN0D6ZQ(6RwlT-STSjr=Oc{$;g0ba+@`JqN}xKUHD>@Bw@ecOMipg zm2QT)-~I9y3=~%S951Chb83qvb``5W;&rBV5JP3yI7@omO?fv)_0u)|ixkjUCYS>0gz zL-u+u*UWW5=ey-m%4WeMfweUaF8*$5h|VX~-f{KBVlSYj4<#LpWKwK?`2>FS;x5Kz z=VoP&yZb?sb=mNu&Evc(!|Yvn%~Tg93T+iM=DwPWNqH(2cX9|R&+9x?7he0#hmCTp zqaiyNBwPxTbdVz~sre$K4Bj5|45*YCK$Ygoc&_IVyahYN>~Q zOeE{ROgEXIefB_pRmTYnpC_qphx8<2-RCk54+jZ_?IByen3I8>_bZIG-r5v9GA;?} z1RpoyQd$tc@2|EK6|!T(WsdoK%vQQey2tK`$Bcp<#vYuCf)9DzBrEm&4=xhqJ)2{; aNLYm42S|>3)hzb literal 0 HcmV?d00001 From f4b59fa2f87516b8b3c1050003cf49cc9ffd6fd4 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Thu, 14 Mar 2019 12:00:06 -0700 Subject: [PATCH 71/71] Fix typos, broken link, and rename goal events Signed-off-by: Jacob Perron --- articles/actions.md | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/articles/actions.md b/articles/actions.md index 23496b53b..8f9c1e658 100644 --- a/articles/actions.md +++ b/articles/actions.md @@ -24,7 +24,7 @@ Original Author: {{ page.author }} There are three forms of communication in ROS: topics, services, and actions. Topic publishers broadcast to multiple subscribers, but communication is one-way. Service clients send a request to a service server and get a response, but there is no information about the progress. -Similar to services, actions clients send a request to an action server in order to achieve some goal and will get a result. +Similar to services, action clients send a request to an action server in order to achieve some goal and will get a result. Unlike services, while the action is being peformed an action server sends progress feedback to the client. Actions are useful when a response may take a significant length of time. @@ -188,9 +188,9 @@ And three terminal states: State transitions triggered by the action server according to its designed behavior: - **execute** - Start execution of an accepted goal. -- **set_succeeded** - Notify that the goal completed successfully. -- **set_aborted** - Notify that an error was encountered during processing of the goal and it had to be aborted. -- **set_canceled** - Notify that canceling the goal completed successfully. +- **succeed** - Notify that the goal completed successfully. +- **abort** - Notify that an error was encountered during processing of the goal and it had to be aborted. +- **cancel** - Notify that canceling the goal completed successfully. State transitions triggered by the action client: @@ -201,7 +201,7 @@ A transition only occurs if the action server *accepts* the request to cancel th ## API -Proposed examples can be in the respository [examples](https://github.com/ros2/examples/tree/actions_proposal). +Usage examples can be found in the [examples](https://github.com/ros2/examples) repository. C++: @@ -227,7 +227,7 @@ In this section, they are descibed in detail. The purpose of this service is to send a goal to the action server. It is the first service called to begin an action, and is expected to return quickly. -The description of the goal in the request is user-define as part of the [Action Interface Definition](#action-interface-definition). +The description of the goal in the request is user-defined as part of the [Action Interface Definition](#action-interface-definition). The QoS settings of this service should be set so the client is guaranteed to receive a response or an action could be executed without a client being aware of it. @@ -308,7 +308,7 @@ Here are a couple of sequence diagrams depicting typical interactions between an #### Example 1 -In this example, the action client request a goal and gets a response from the server accepting the goal (synchronous). +In this example, the action client requests a goal and gets a response from the server accepting the goal (synchronous). Upon accepting the goal, the action server starts a user defined execution method for completing the goal. Following the goal request, the client makes an asynchronous request for the result. The user defined method publishes feedback to the action client as it executes the goal. @@ -318,7 +318,7 @@ Ultimately, the user defined method populates a result message that is used as p #### Example 2 -This example is almost identical to the first, but this time the action client requests for the goal to be canceled mid-execution. +This example is almost identical to the first, but this time the action client requests for the goal to be canceled mid-execution. Note that the user defined method is allowed to perform any shutdown operations after the cancel request before returning with the cancellation result. ![Action Interaction Example 1](../img/actions/interaction_example_1.png) @@ -398,7 +398,7 @@ These alternative approaches to actions in ROS 2 were considered. ### Actions in rmw An alternative to using services and topics is to implement actions in the rmw layer. -This would enable using middleware specific features better suited actions. +This would enable using middleware specific features better suited to actions. The default middleware in ROS 2 uses DDS, and there don't appear to be any DDS features better for actions than what are used for services and topics. Additionally implementing actions in the rmw implementations increases the complexity of writing an rmw implementation. For these reasons actions will be implemented at a higher level.