From 34b0fc8b7c1c9c60a2db960357f86b63ebdf319a Mon Sep 17 00:00:00 2001 From: knmcguire Date: Wed, 18 Oct 2023 14:42:10 +0200 Subject: [PATCH 001/162] add notify setpoint --- crazyflie/scripts/crazyflie_server.py | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/crazyflie/scripts/crazyflie_server.py b/crazyflie/scripts/crazyflie_server.py index ad8e299b4..b52bb6253 100755 --- a/crazyflie/scripts/crazyflie_server.py +++ b/crazyflie/scripts/crazyflie_server.py @@ -785,7 +785,15 @@ def _go_to_callback(self, request, response, uri="all"): return response def _notify_setpoints_stop_callback(self, request, response, uri="all"): - self.get_logger().info("Notify setpoint stop not yet implemented") + + self.get_logger().info(f"{uri}: Received notify setpoint stop") + + if uri == "all": + for link_uri in self.uris: + self.swarm._cfs[link_uri].cf.commander.send_notify_setpoint_stop() + else: + self.swarm._cfs[uri].cf.commander.send_notify_setpoint_stop() + return response def _upload_trajectory_callback(self, request, response, uri="all"): From 4b5cae6137e19827b7e9940edfe1570706f3fba2 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Wed, 18 Oct 2023 14:42:27 +0200 Subject: [PATCH 002/162] fix vel_mux issue --- crazyflie/scripts/vel_mux.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/crazyflie/scripts/vel_mux.py b/crazyflie/scripts/vel_mux.py index f1155ba1c..aab381cbb 100755 --- a/crazyflie/scripts/vel_mux.py +++ b/crazyflie/scripts/vel_mux.py @@ -12,7 +12,7 @@ from rclpy.node import Node from geometry_msgs.msg import Twist -from crazyflie_interfaces.srv import Takeoff, Land +from crazyflie_interfaces.srv import Takeoff, Land, NotifySetpointsStop from crazyflie_interfaces.msg import Hover import time @@ -39,6 +39,7 @@ def __init__(self): self.takeoff_client = self.create_client(Takeoff, robot_prefix + '/takeoff') self.publisher_hover = self.create_publisher(Hover, robot_prefix + '/cmd_hover', 10) self.land_client = self.create_client(Land, robot_prefix + '/land') + self.notify_client = self.create_client(NotifySetpointsStop, robot_prefix + '/notify_setpoints_stop') self.cf_has_taken_off = False self.takeoff_client.wait_for_service() @@ -72,6 +73,8 @@ def timer_callback(self): msg.z_distance = self.hover_height self.publisher_hover.publish(msg) else: + req = NotifySetpointsStop.Request() + self.notify_client.call_async(req) req = Land.Request() req.height = 0.1 req.duration = rclpy.duration.Duration(seconds=2.0).to_msg() @@ -80,7 +83,6 @@ def timer_callback(self): self.cf_has_taken_off = False self.received_first_cmd_vel = False - def main(args=None): rclpy.init(args=args) From 12e602b9917f889851a19a15fee250ee225d9588 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Wed, 18 Oct 2023 14:48:37 +0200 Subject: [PATCH 003/162] fix explaination example. Fixes #307 --- crazyflie_examples/launch/keyboard_velmux_launch.py | 2 +- docs2/tutorials.rst | 6 ++++-- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/crazyflie_examples/launch/keyboard_velmux_launch.py b/crazyflie_examples/launch/keyboard_velmux_launch.py index db7badac4..a6ad3f674 100644 --- a/crazyflie_examples/launch/keyboard_velmux_launch.py +++ b/crazyflie_examples/launch/keyboard_velmux_launch.py @@ -31,6 +31,6 @@ def generate_launch_description(): output='screen', parameters=[{"hover_height": 0.3}, {"incoming_twist_topic": "/cmd_vel"}, - {"robot_prefix": "/cf1"}] + {"robot_prefix": "/cf231"}] ), ]) diff --git a/docs2/tutorials.rst b/docs2/tutorials.rst index 58070bc67..a13e9a876 100644 --- a/docs2/tutorials.rst +++ b/docs2/tutorials.rst @@ -17,7 +17,7 @@ Teleoperation keyboard We have an example of the telop_twist_keyboard package working together with the crazyflie First, make sure that the crazyflies.yaml has the right URI and if you are using the `Flow deck `_ or `any other position system available `_ to the crazyflie. -set the controller to 1 (PID) +set the controller to 1 (PID). And if you have not already, install the teleop package for the keyboard. (replace DISTRO with humble or galactic): @@ -25,7 +25,9 @@ And if you have not already, install the teleop package for the keyboard. (repl sudo apt-get install ros-DISTRO-teleop-twist-keyboard -Then, run the following launch file to start up the crazyflie server (CFlib): +Then, first checkout keyboard_velmux_launch.py and make sure that the 'robot_prefix' of vel_mux matches your crazyflie ID in crazyfies.yaml ('cf231'). + +Then run the following launch file to start up the crazyflie server (CFlib): .. code-block:: bash From bb090e65239260dba80dde247af7404694627739 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Wed, 18 Oct 2023 21:54:27 +0200 Subject: [PATCH 004/162] crazyflie_py: fix flake8 and pep256 issues --- .github/workflows/ci-ros2.yml | 3 +- crazyflie_py/crazyflie_py/crazyflie.py | 253 ++++++++++++------- crazyflie_py/crazyflie_py/crazyswarm_py.py | 2 +- crazyflie_py/crazyflie_py/genericJoystick.py | 3 +- crazyflie_py/crazyflie_py/joystick.py | 5 +- crazyflie_py/crazyflie_py/keyboard.py | 2 +- crazyflie_py/crazyflie_py/linuxjsdev.py | 39 ++- crazyflie_py/crazyflie_py/uav_trajectory.py | 186 +++++++------- crazyflie_py/crazyflie_py/util.py | 23 +- crazyflie_py/test/test_copyright.py | 23 -- 10 files changed, 304 insertions(+), 235 deletions(-) delete mode 100644 crazyflie_py/test/test_copyright.py diff --git a/.github/workflows/ci-ros2.yml b/.github/workflows/ci-ros2.yml index dfb7ba1d6..5941c2c88 100644 --- a/.github/workflows/ci-ros2.yml +++ b/.github/workflows/ci-ros2.yml @@ -46,10 +46,11 @@ jobs: - name: build and test ROS 2 uses: ros-tooling/action-ros-ci@v0.3 with: - # TODO: removed crazyflie_interfaces since it causes some test failures package-name: | crazyflie crazyflie_examples + crazyflie_interfaces + crazyflie_py crazyflie_sim target-ros2-distro: ${{ matrix.ros_distribution }} vcs-repo-file-url: rosinstall \ No newline at end of file diff --git a/crazyflie_py/crazyflie_py/crazyflie.py b/crazyflie_py/crazyflie_py/crazyflie.py index 174877303..c679e6c62 100644 --- a/crazyflie_py/crazyflie_py/crazyflie.py +++ b/crazyflie_py/crazyflie_py/crazyflie.py @@ -19,12 +19,14 @@ import rclpy.node import rowan from std_srvs.srv import Empty -from geometry_msgs.msg import Point, Twist +from geometry_msgs.msg import Point from rcl_interfaces.srv import GetParameters, SetParameters, ListParameters, DescribeParameters from rcl_interfaces.msg import Parameter, ParameterValue, ParameterType -from crazyflie_interfaces.srv import Takeoff, Land, GoTo, UploadTrajectory, StartTrajectory, NotifySetpointsStop +from crazyflie_interfaces.srv import Takeoff, Land, GoTo, \ + UploadTrajectory, StartTrajectory, NotifySetpointsStop from crazyflie_interfaces.msg import TrajectoryPolynomialPiece, FullState, Position + def arrayToGeometryPoint(a): result = Point() result.x = a[0] @@ -32,19 +34,24 @@ def arrayToGeometryPoint(a): result.z = a[2] return result + class TimeHelper: - """Object containing all time-related functionality. + """ + Object containing all time-related functionality. This class mainly exists to support both real hardware and (potentially faster or slower than realtime) simulation with the same script. When running on real hardware, this class uses ROS time functions. The simulation equivalent does not depend on ROS. - Attributes: + Attributes + ---------- visualizer: No-op object conforming to the Visualizer API used in simulation scripts. Maintains the property that scripts should not know/care if they are running in simulation or not. + """ + def __init__(self, node): self.node = node # self.rosRate = None @@ -53,7 +60,7 @@ def __init__(self, node): # self.visualizer = visNull.VisNull() def time(self): - """Returns the current time in seconds.""" + """Return current time in seconds.""" return self.node.get_clock().now().nanoseconds / 1e9 def sleep(self, duration): @@ -64,7 +71,7 @@ def sleep(self, duration): rclpy.spin_once(self.node, timeout_sec=0) def sleepForRate(self, rateHz): - """Sleeps so that, if called in a loop, executes at specified rate.""" + """Sleep so that, if called in a loop, executes at specified rate.""" # Note: The following ROS 2 construct cannot easily be used, because in ROS 2 # there is no implicit threading anymore. Thus, the rosRate.sleep() call # is blocking. Instead, we simulate the rate behavior ourselves. @@ -80,21 +87,27 @@ def sleepForRate(self, rateHz): self.nextTime += 1.0 / rateHz def isShutdown(self): - """Returns true if the script should abort, e.g. from Ctrl-C.""" + """Return True if the script should abort, e.g. from Ctrl-C.""" return not rclpy.ok() class Crazyflie: - """Object representing a single robot. + """ + Object representing a single robot. The bulk of the module's functionality is contained in this class. """ def __init__(self, node, cfname, paramTypeDict): - """Constructor. + """ + Construct Crazyflie. Args: + ---- + node: ROS node reference cfname (string): Name of the robot names[ace] + paramTypeDict: dictionary of the parameter types + """ prefix = "/" + cfname self.prefix = prefix @@ -114,13 +127,17 @@ def __init__(self, node, cfname, paramTypeDict): # # self.stopService = rospy.ServiceProxy(prefix + "/stop", Stop) self.goToService = node.create_client(GoTo, prefix + "/go_to") self.goToService.wait_for_service() - self.uploadTrajectoryService = node.create_client(UploadTrajectory, prefix + "/upload_trajectory") + self.uploadTrajectoryService = node.create_client( + UploadTrajectory, prefix + "/upload_trajectory") self.uploadTrajectoryService.wait_for_service() - self.startTrajectoryService = node.create_client(StartTrajectory, prefix + "/start_trajectory") + self.startTrajectoryService = node.create_client( + StartTrajectory, prefix + "/start_trajectory") self.startTrajectoryService.wait_for_service() - self.notifySetpointsStopService = node.create_client(NotifySetpointsStop, prefix + "/notify_setpoints_stop") + self.notifySetpointsStopService = node.create_client( + NotifySetpointsStop, prefix + "/notify_setpoints_stop") self.notifySetpointsStopService.wait_for_service() - self.setParamsService = node.create_client(SetParameters, "/crazyflie_server/set_parameters") + self.setParamsService = node.create_client( + SetParameters, "/crazyflie_server/set_parameters") self.setParamsService.wait_for_service() # Query some settings @@ -148,20 +165,24 @@ def __init__(self, node, cfname, paramTypeDict): self.paramTypeDict = paramTypeDict - self.cmdFullStatePublisher = node.create_publisher(FullState, prefix + "/cmd_full_state", 1) + self.cmdFullStatePublisher = node.create_publisher( + FullState, prefix + "/cmd_full_state", 1) self.cmdFullStateMsg = FullState() self.cmdFullStateMsg.header.frame_id = "/world" - # self.cmdStopPublisher = rospy.Publisher(prefix + "/cmd_stop", std_msgs.msg.Empty, queue_size=1) + # self.cmdStopPublisher = rospy.Publisher( + # prefix + "/cmd_stop", std_msgs.msg.Empty, queue_size=1) - # self.cmdVelPublisher = rospy.Publisher(prefix + "/cmd_vel", geometry_msgs.msg.Twist, queue_size=1) + # self.cmdVelPublisher = rospy.Publisher( + # prefix + "/cmd_vel", geometry_msgs.msg.Twist, queue_size=1) - self.cmdPositionPublisher = node.create_publisher(Position, prefix + "/cmd_position", 1) + self.cmdPositionPublisher = node.create_publisher( + Position, prefix + "/cmd_position", 1) self.cmdPositionMsg = Position() self.cmdPositionMsg.header.frame_id = "/world" - - # self.cmdVelocityWorldPublisher = rospy.Publisher(prefix + "/cmd_velocity_world", VelocityWorld, queue_size=1) + # self.cmdVelocityWorldPublisher = rospy.Publisher( + # prefix + "/cmd_velocity_world", VelocityWorld, queue_size=1) # self.cmdVelocityWorldMsg = VelocityWorld() # self.cmdVelocityWorldMsg.header.seq = 0 # self.cmdVelocityWorldMsg.header.frame_id = "/world" @@ -202,7 +223,8 @@ def __init__(self, node, cfname, paramTypeDict): # of this list. With real hardware, this list is **ignored**, and # collision avoidance is checked with all other Crazyflies on the # same radio channel. - # ellipsoidRadii (array-like of float[3]): Radii of collision volume ellipsoid in meters. + # ellipsoidRadii (array-like of float[3]): Radii of collision volume + # ellipsoid in meters. # The Crazyflie's boundary for collision checking is a tall # ellipsoid. This accounts for the downwash effect: Due to the # fast-moving stream of air produced by the rotors, the safe @@ -224,13 +246,13 @@ def __init__(self, node, cfname, paramTypeDict): # }) # self.setParam("colAv/enable", 1) - # def disableCollisionAvoidance(self): # """Disables onboard collision avoidance.""" # self.setParam("colAv/enable", 0) def emergency(self): - """Emergency stop. Cuts power; causes future commands to be ignored. + """ + Emergency stop. Cuts power; causes future commands to be ignored. This command is useful if the operator determines that the control script is flawed, and that continuing to follow it will cause wrong/ @@ -244,15 +266,18 @@ def emergency(self): req = Empty.Request() self.emergencyService.call_async(req) - def takeoff(self, targetHeight, duration, groupMask = 0): - """Execute a takeoff - fly straight up, then hover indefinitely. + def takeoff(self, targetHeight, duration, groupMask=0): + """ + Execute a takeoff - fly straight up, then hover indefinitely. Asynchronous command; returns immediately. Args: + ---- targetHeight (float): The z-coordinate at which to hover. duration (float): How long until the height is reached. Seconds. groupMask (int): Group mask bits. See :meth:`setGroupMask()` doc. + """ req = Takeoff.Request() req.group_mask = groupMask @@ -260,18 +285,21 @@ def takeoff(self, targetHeight, duration, groupMask = 0): req.duration = rclpy.duration.Duration(seconds=duration).to_msg() self.takeoffService.call_async(req) - def land(self, targetHeight, duration, groupMask = 0): - """Execute a landing - fly straight down. User must cut power after. + def land(self, targetHeight, duration, groupMask=0): + """ + Execute a landing - fly straight down. User must cut power after. Asynchronous command; returns immediately. Args: + ---- targetHeight (float): The z-coordinate at which to land. Meters. Usually should be a few centimeters above the initial position to ensure that the controller does not try to penetrate the floor if the mocap coordinate origin is not perfect. duration (float): How long until the height is reached. Seconds. groupMask (int): Group mask bits. See :meth:`setGroupMask()` doc. + """ req = Land.Request() req.group_mask = groupMask @@ -291,8 +319,9 @@ def land(self, targetHeight, duration, groupMask = 0): # """ # self.stopService(groupMask) - def goTo(self, goal, yaw, duration, relative = False, groupMask = 0): - """Move smoothly to the goal, then hover indefinitely. + def goTo(self, goal, yaw, duration, relative=False, groupMask=0): + """ + Move smoothly to the goal, then hover indefinitely. Asynchronous command; returns immediately. @@ -315,6 +344,7 @@ def goTo(self, goal, yaw, duration, relative = False, groupMask = 0): controller to become unstable. Args: + ---- goal (iterable of 3 floats): The goal position. Meters. yaw (float): The goal yaw angle (heading). Radians. duration (float): How long until the goal is reached. Seconds. @@ -323,6 +353,7 @@ def goTo(self, goal, yaw, duration, relative = False, groupMask = 0): position is interpreted as absolute coordintates in the global reference frame. groupMask (int): Group mask bits. See :meth:`setGroupMask()` doc. + """ req = GoTo.Request() req.group_mask = groupMask @@ -333,24 +364,27 @@ def goTo(self, goal, yaw, duration, relative = False, groupMask = 0): self.goToService.call_async(req) def uploadTrajectory(self, trajectoryId, pieceOffset, trajectory): - """Uploads a piecewise polynomial trajectory for later execution. + """ + Upload a piecewise polynomial trajectory for later execution. See uav_trajectory.py for more information about piecewise polynomial trajectories. Args: + ---- trajectoryId (int): ID number of this trajectory. Multiple trajectories can be uploaded. TODO: what is the maximum ID? pieceOffset (int): TODO(whoenig): explain this. trajectory (:obj:`pycrazyswarm.uav_trajectory.Trajectory`): Trajectory object. + """ pieces = [] for poly in trajectory.polynomials: piece = TrajectoryPolynomialPiece() piece.duration = rclpy.duration.Duration(seconds=poly.duration).to_msg() - piece.poly_x = poly.px.p.tolist() - piece.poly_y = poly.py.p.tolist() - piece.poly_z = poly.pz.p.tolist() + piece.poly_x = poly.px.p.tolist() + piece.poly_y = poly.py.p.tolist() + piece.poly_z = poly.pz.p.tolist() piece.poly_yaw = poly.pyaw.p.tolist() pieces.append(piece) req = UploadTrajectory.Request() @@ -359,12 +393,16 @@ def uploadTrajectory(self, trajectoryId, pieceOffset, trajectory): req.pieces = pieces self.uploadTrajectoryService.call_async(req) - def startTrajectory(self, trajectoryId, timescale = 1.0, reverse = False, relative = True, groupMask = 0): - """Begins executing a previously uploaded trajectory. + def startTrajectory(self, trajectoryId, + timescale=1.0, reverse=False, + relative=True, groupMask=0): + """ + Begin executing a previously uploaded trajectory. Asynchronous command; returns immediately. Args: + ---- trajectoryId (int): ID number as given to :meth:`uploadTrajectory()`. timescale (float): Scales the trajectory duration by this factor. For example if timescale == 2.0, the trajectory will take twice @@ -374,6 +412,7 @@ def startTrajectory(self, trajectoryId, timescale = 1.0, reverse = False, relati is shifted such that it begins at the current position setpoint. This is usually the desired behavior. groupMask (int): Group mask bits. See :meth:`setGroupMask()` doc. + """ req = StartTrajectory.Request() req.group_mask = groupMask @@ -384,7 +423,8 @@ def startTrajectory(self, trajectoryId, timescale = 1.0, reverse = False, relati self.startTrajectoryService.call_async(req) def notifySetpointsStop(self, remainValidMillisecs=100, groupMask=0): - """Informs that streaming low-level setpoint packets are about to stop. + """ + Informs that streaming low-level setpoint packets are about to stop. Streaming setpoints are :meth:`cmdVelocityWorld`, :meth:`cmdFullState`, and so on. For safety purposes, they normally preempt onboard high-level @@ -403,10 +443,13 @@ def notifySetpointsStop(self, remainValidMillisecs=100, groupMask=0): streaming setpoint modes. Args: + ---- remainValidMillisecs (int): Number of milliseconds that the last streaming setpoint should be followed before reverting to the onboard-determined behavior. May be longer e.g. if one radio is controlling many robots. + groupMask (int): Group mask bits. See :meth:`setGroupMask()` doc. + """ req = NotifySetpointsStop.Request() req.remain_valid_millisecs = remainValidMillisecs @@ -425,8 +468,10 @@ def notifySetpointsStop(self, remainValidMillisecs=100, groupMask=0): # Returns: # position (np.array[3]): Current position. Meters. # """ - # self.tf.waitForTransform("/world", "/cf" + str(self.id), rospy.Time(0), rospy.Duration(10)) - # position, quaternion = self.tf.lookupTransform("/world", "/cf" + str(self.id), rospy.Time(0)) + # self.tf.waitForTransform( + # "/world", "/cf" + str(self.id), rospy.Time(0), rospy.Duration(10)) + # position, quaternion = self.tf.lookupTransform( + # "/world", "/cf" + str(self.id), rospy.Time(0)) # return np.array(position) # def getParam(self, name): @@ -451,13 +496,16 @@ def notifySetpointsStop(self, remainValidMillisecs=100, groupMask=0): # return rospy.get_param(self.prefix + "/" + name) def setParam(self, name, value): - """Changes the value of the given parameter. + """ + Change the value of the given parameter. See :meth:`getParam()` docs for overview of the parameter system. Args: + ---- name (str): The parameter's name. value (Any): The parameter's value. + """ param_name = self.prefix[1:] + ".params." + name param_type = self.paramTypeDict[name] @@ -482,7 +530,8 @@ def setParam(self, name, value): # self.updateParamsService(params.keys()) def cmdFullState(self, pos, vel, acc, yaw, omega): - """Sends a streaming full-state controller setpoint command. + """ + Send a streaming full-state controller setpoint command. The full-state setpoint is most useful for aggressive maneuvers where feedforward inputs for acceleration and angular velocity are critical @@ -497,31 +546,33 @@ def cmdFullState(self, pos, vel, acc, yaw, omega): :meth:`goTo()` after a streaming setpoint has been sent. Args: + ---- pos (array-like of float[3]): Position. Meters. vel (array-like of float[3]): Velocity. Meters / second. acc (array-like of float[3]): Acceleration. Meters / second^2. yaw (float): Yaw angle. Radians. omega (array-like of float[3]): Angular velocity in body frame. Radians / sec. + """ self.cmdFullStateMsg.header.stamp = self.node.get_clock().now().to_msg() - self.cmdFullStateMsg.pose.position.x = pos[0] - self.cmdFullStateMsg.pose.position.y = pos[1] - self.cmdFullStateMsg.pose.position.z = pos[2] - self.cmdFullStateMsg.twist.linear.x = vel[0] - self.cmdFullStateMsg.twist.linear.y = vel[1] - self.cmdFullStateMsg.twist.linear.z = vel[2] - self.cmdFullStateMsg.acc.x = acc[0] - self.cmdFullStateMsg.acc.y = acc[1] - self.cmdFullStateMsg.acc.z = acc[2] + self.cmdFullStateMsg.pose.position.x = pos[0] + self.cmdFullStateMsg.pose.position.y = pos[1] + self.cmdFullStateMsg.pose.position.z = pos[2] + self.cmdFullStateMsg.twist.linear.x = vel[0] + self.cmdFullStateMsg.twist.linear.y = vel[1] + self.cmdFullStateMsg.twist.linear.z = vel[2] + self.cmdFullStateMsg.acc.x = acc[0] + self.cmdFullStateMsg.acc.y = acc[1] + self.cmdFullStateMsg.acc.z = acc[2] q = rowan.from_euler(0, 0, yaw) self.cmdFullStateMsg.pose.orientation.w = q[0] self.cmdFullStateMsg.pose.orientation.x = q[1] self.cmdFullStateMsg.pose.orientation.y = q[2] self.cmdFullStateMsg.pose.orientation.z = q[3] - self.cmdFullStateMsg.twist.angular.x = omega[0] - self.cmdFullStateMsg.twist.angular.y = omega[1] - self.cmdFullStateMsg.twist.angular.z = omega[2] + self.cmdFullStateMsg.twist.angular.x = omega[0] + self.cmdFullStateMsg.twist.angular.y = omega[1] + self.cmdFullStateMsg.twist.angular.z = omega[2] self.cmdFullStatePublisher.publish(self.cmdFullStateMsg) # def cmdVelocityWorld(self, vel, yawRate): @@ -597,22 +648,26 @@ def cmdFullState(self, pos, vel, acc, yaw, omega): # msg.linear.z = thrust # self.cmdVelPublisher.publish(msg) - def cmdPosition(self, pos, yaw = 0.): - """Sends a streaming command of absolute position and yaw setpoint. + def cmdPosition(self, pos, yaw=0.): + """ + Send a streaming command of absolute position and yaw setpoint. Useful for slow maneuvers where a high-level planner determines the desired position, and the rest is left to the onboard controller. For more information on streaming setpoint commands, see the :meth:`cmdFullState()` documentation. + Args: + ---- pos (array-like of float[3]): Position. Meters. yaw (float): Yaw angle. Radians. + """ self.cmdPositionMsg.header.stamp = self.node.get_clock().now().to_msg() - self.cmdPositionMsg.x = pos[0] - self.cmdPositionMsg.y = pos[1] - self.cmdPositionMsg.z = pos[2] + self.cmdPositionMsg.x = pos[0] + self.cmdPositionMsg.y = pos[1] + self.cmdPositionMsg.z = pos[2] self.cmdPositionMsg.yaw = yaw self.cmdPositionPublisher.publish(self.cmdPositionMsg) @@ -641,19 +696,22 @@ def cmdPosition(self, pos, yaw = 0.): class CrazyflieServer(rclpy.node.Node): - """Object for broadcasting commands to all robots at once. + """ + Object for broadcasting commands to all robots at once. Also is the container for the individual :obj:`Crazyflie` objects. - Attributes: + Attributes + ---------- crazyfiles (List[Crazyflie]): List of one Crazyflie object per robot, as determined by the crazyflies.yaml config file. crazyfliesById (Dict[int, Crazyflie]): Index to the same Crazyflie objects by their ID number (last byte of radio address). + """ + def __init__(self): - """Initialize the server. Waits for all ROS services before returning. - """ + """Initialize the server. Waits for all ROS services before returning.""" super().__init__("CrazyflieAPI") self.emergencyService = self.create_client(Empty, "all/emergency") self.emergencyService.wait_for_service() @@ -666,10 +724,12 @@ def __init__(self): self.goToService.wait_for_service() self.startTrajectoryService = self.create_client(StartTrajectory, "all/start_trajectory") self.startTrajectoryService.wait_for_service() - self.setParamsService = self.create_client(SetParameters, "/crazyflie_server/set_parameters") + self.setParamsService = self.create_client( + SetParameters, "/crazyflie_server/set_parameters") self.setParamsService.wait_for_service() - self.cmdFullStatePublisher = self.create_publisher(FullState, "all/cmd_full_state", 1) + self.cmdFullStatePublisher = self.create_publisher( + FullState, "all/cmd_full_state", 1) self.cmdFullStateMsg = FullState() self.cmdFullStateMsg.header.frame_id = "/world" @@ -700,7 +760,8 @@ def __init__(self): break # Find the types for the parameters and store them - describeParametersService = self.create_client(DescribeParameters, "/crazyflie_server/describe_parameters") + describeParametersService = self.create_client( + DescribeParameters, "/crazyflie_server/describe_parameters") describeParametersService.wait_for_service() req = DescribeParameters.Request() req.names = params @@ -735,7 +796,8 @@ def __init__(self): self.crazyfliesById[cfid] = cf def emergency(self): - """Emergency stop. Cuts power; causes future commands to be ignored. + """ + Emergency stop. Cuts power; causes future commands to be ignored. This command is useful if the operator determines that the control script is flawed, and that continuing to follow it will cause wrong/ @@ -749,17 +811,20 @@ def emergency(self): req = Empty.Request() self.emergencyService.call_async(req) - def takeoff(self, targetHeight, duration, groupMask = 0): - """Broadcasted takeoff - fly straight up, then hover indefinitely. + def takeoff(self, targetHeight, duration, groupMask=0): + """ + Broadcasted takeoff - fly straight up, then hover indefinitely. Broadcast version of :meth:`Crazyflie.takeoff()`. All robots that match the groupMask take off at exactly the same time. Use for synchronized movement. Asynchronous command; returns immediately. Args: + ---- targetHeight (float): The z-coordinate at which to hover. duration (float): How long until the height is reached. Seconds. groupMask (int): Group mask bits. See :meth:`setGroupMask()` doc. + """ req = Takeoff.Request() req.group_mask = groupMask @@ -767,20 +832,23 @@ def takeoff(self, targetHeight, duration, groupMask = 0): req.duration = rclpy.duration.Duration(seconds=duration).to_msg() self.takeoffService.call_async(req) - def land(self, targetHeight, duration, groupMask = 0): - """Broadcasted landing - fly straight down. User must cut power after. + def land(self, targetHeight, duration, groupMask=0): + """ + Broadcasted landing - fly straight down. User must cut power after. Broadcast version of :meth:`Crazyflie.land()`. All robots that match the groupMask land at exactly the same time. Use for synchronized movement. Asynchronous command; returns immediately. Args: + ---- targetHeight (float): The z-coordinate at which to land. Meters. Usually should be a few centimeters above the initial position to ensure that the controller does not try to penetrate the floor if the mocap coordinate origin is not perfect. duration (float): How long until the height is reached. Seconds. groupMask (int): Group mask bits. See :meth:`Crazyflie.setGroupMask()` doc. + """ req = Land.Request() req.group_mask = groupMask @@ -788,8 +856,9 @@ def land(self, targetHeight, duration, groupMask = 0): req.duration = rclpy.duration.Duration(seconds=duration).to_msg() self.landService.call_async(req) - def goTo(self, goal, yaw, duration, groupMask = 0): - """Broadcasted goTo - Move smoothly to goal, then hover indefinitely. + def goTo(self, goal, yaw, duration, groupMask=0): + """ + Broadcasted goTo - Move smoothly to goal, then hover indefinitely. Broadcast version of :meth:`Crazyflie.goTo()`. All robots that match the groupMask start moving at exactly the same time. Use for synchronized @@ -803,10 +872,12 @@ def goTo(self, goal, yaw, duration, groupMask = 0): See docstring of :meth:`Crazyflie.goTo()` for additional details. Args: + ---- goal (iterable of 3 floats): The goal offset. Meters. yaw (float): The goal yaw angle (heading). Radians. duration (float): How long until the goal is reached. Seconds. groupMask (int): Group mask bits. See :meth:`Crazyflie.setGroupMask()` doc. + """ req = GoTo.Request() req.group_mask = groupMask @@ -816,13 +887,17 @@ def goTo(self, goal, yaw, duration, groupMask = 0): req.duration = rclpy.duration.Duration(seconds=duration).to_msg() self.goToService.call_async(req) - def startTrajectory(self, trajectoryId, timescale = 1.0, reverse = False, relative = True, groupMask = 0): - """Broadcasted - begins executing a previously uploaded trajectory. + def startTrajectory(self, trajectoryId, + timescale=1.0, reverse=False, + relative=True, groupMask=0): + """ + Broadcasted - begins executing a previously uploaded trajectory. Broadcast version of :meth:`Crazyflie.startTrajectory()`. Asynchronous command; returns immediately. Args: + ---- trajectoryId (int): ID number as given to :meth:`Crazyflie.uploadTrajectory()`. timescale (float): Scales the trajectory duration by this factor. For example if timescale == 2.0, the trajectory will take twice @@ -831,6 +906,7 @@ def startTrajectory(self, trajectoryId, timescale = 1.0, reverse = False, relati relative (bool): If true (default), the position of the trajectory is shifted such that it begins at the current position setpoint. groupMask (int): Group mask bits. See :meth:`Crazyflie.setGroupMask()` doc. + """ req = StartTrajectory.Request() req.group_mask = groupMask @@ -841,7 +917,7 @@ def startTrajectory(self, trajectoryId, timescale = 1.0, reverse = False, relati self.startTrajectoryService.call_async(req) def setParam(self, name, value): - """Broadcasted setParam. See Crazyflie.setParam() for details.""" + """Set parameter via broadcasts. See Crazyflie.setParam for details.""" param_name = "all.params." + name param_type = self.paramTypeDict[name] if param_type == ParameterType.PARAMETER_INTEGER: @@ -853,7 +929,8 @@ def setParam(self, name, value): self.setParamsService.call_async(req) def cmdFullState(self, pos, vel, acc, yaw, omega): - """Sends a streaming full-state controller setpoint command. + """ + Send a streaming full-state controller setpoint command. The full-state setpoint is most useful for aggressive maneuvers where feedforward inputs for acceleration and angular velocity are critical @@ -868,29 +945,31 @@ def cmdFullState(self, pos, vel, acc, yaw, omega): :meth:`goTo()` after a streaming setpoint has been sent. Args: + ---- pos (array-like of float[3]): Position. Meters. vel (array-like of float[3]): Velocity. Meters / second. acc (array-like of float[3]): Acceleration. Meters / second^2. yaw (float): Yaw angle. Radians. omega (array-like of float[3]): Angular velocity in body frame. Radians / sec. + """ self.cmdFullStateMsg.header.stamp = self.get_clock().now().to_msg() - self.cmdFullStateMsg.pose.position.x = pos[0] - self.cmdFullStateMsg.pose.position.y = pos[1] - self.cmdFullStateMsg.pose.position.z = pos[2] - self.cmdFullStateMsg.twist.linear.x = vel[0] - self.cmdFullStateMsg.twist.linear.y = vel[1] - self.cmdFullStateMsg.twist.linear.z = vel[2] - self.cmdFullStateMsg.acc.x = acc[0] - self.cmdFullStateMsg.acc.y = acc[1] - self.cmdFullStateMsg.acc.z = acc[2] + self.cmdFullStateMsg.pose.position.x = pos[0] + self.cmdFullStateMsg.pose.position.y = pos[1] + self.cmdFullStateMsg.pose.position.z = pos[2] + self.cmdFullStateMsg.twist.linear.x = vel[0] + self.cmdFullStateMsg.twist.linear.y = vel[1] + self.cmdFullStateMsg.twist.linear.z = vel[2] + self.cmdFullStateMsg.acc.x = acc[0] + self.cmdFullStateMsg.acc.y = acc[1] + self.cmdFullStateMsg.acc.z = acc[2] q = rowan.from_euler(0, 0, yaw) self.cmdFullStateMsg.pose.orientation.w = q[0] self.cmdFullStateMsg.pose.orientation.x = q[1] self.cmdFullStateMsg.pose.orientation.y = q[2] self.cmdFullStateMsg.pose.orientation.z = q[3] - self.cmdFullStateMsg.twist.angular.x = omega[0] - self.cmdFullStateMsg.twist.angular.y = omega[1] - self.cmdFullStateMsg.twist.angular.z = omega[2] - self.cmdFullStatePublisher.publish(self.cmdFullStateMsg) \ No newline at end of file + self.cmdFullStateMsg.twist.angular.x = omega[0] + self.cmdFullStateMsg.twist.angular.y = omega[1] + self.cmdFullStateMsg.twist.angular.z = omega[2] + self.cmdFullStatePublisher.publish(self.cmdFullStateMsg) diff --git a/crazyflie_py/crazyflie_py/crazyswarm_py.py b/crazyflie_py/crazyflie_py/crazyswarm_py.py index 2775080c4..959ac44a6 100644 --- a/crazyflie_py/crazyflie_py/crazyswarm_py.py +++ b/crazyflie_py/crazyflie_py/crazyswarm_py.py @@ -7,7 +7,7 @@ class Crazyswarm: def __init__(self): rclpy.init() - + self.allcfs = CrazyflieServer() self.timeHelper = TimeHelper(self.allcfs) diff --git a/crazyflie_py/crazyflie_py/genericJoystick.py b/crazyflie_py/crazyflie_py/genericJoystick.py index 2dbb08be3..32364b203 100644 --- a/crazyflie_py/crazyflie_py/genericJoystick.py +++ b/crazyflie_py/crazyflie_py/genericJoystick.py @@ -1,4 +1,3 @@ -import time import copy # import pyglet from . import keyboard @@ -20,6 +19,7 @@ # def on_joyhat_motion(joystick, hat_x, hat_y): # pass + class Joystick: def __init__(self, timeHelper): # joysticks = pyglet.input.get_joysticks() @@ -77,7 +77,6 @@ def waitUntilButtonPressed(self): while keyPoller.poll() is not None: self.timeHelper.sleep(0.01) - def checkIfAnyButtonIsPressed(self): if self.joyID is not None: state = self.js.read(self.joyID) diff --git a/crazyflie_py/crazyflie_py/joystick.py b/crazyflie_py/crazyflie_py/joystick.py index ba8207965..f6ae10500 100644 --- a/crazyflie_py/crazyflie_py/joystick.py +++ b/crazyflie_py/crazyflie_py/joystick.py @@ -2,6 +2,7 @@ import rospy from sensor_msgs.msg import Joy + class Joystick: def __init__(self): self.lastButtonState = 0 @@ -10,8 +11,8 @@ def __init__(self): def joyChanged(self, data): if (not self.buttonWasPressed and - data.buttons[5] == 1 and - self.lastButtonState == 0): + data.buttons[5] == 1 and + self.lastButtonState == 0): self.buttonWasPressed = True self.lastButtonState = data.buttons[5] diff --git a/crazyflie_py/crazyflie_py/keyboard.py b/crazyflie_py/crazyflie_py/keyboard.py index e5f788775..b4c92992f 100644 --- a/crazyflie_py/crazyflie_py/keyboard.py +++ b/crazyflie_py/crazyflie_py/keyboard.py @@ -20,7 +20,7 @@ def __exit__(self, type, value, traceback): termios.tcsetattr(self.fd, termios.TCSAFLUSH, self.old_term) def poll(self): - dr,dw,de = select.select([sys.stdin], [], [], 0) + dr, dw, de = select.select([sys.stdin], [], [], 0) if not dr == []: return sys.stdin.read(1) return None diff --git a/crazyflie_py/crazyflie_py/linuxjsdev.py b/crazyflie_py/crazyflie_py/linuxjsdev.py index ba5df731e..c9ebf50a3 100644 --- a/crazyflie_py/crazyflie_py/linuxjsdev.py +++ b/crazyflie_py/crazyflie_py/linuxjsdev.py @@ -23,8 +23,9 @@ # along with this program; if not, write to the Free Software Foundation, # Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. """ -Linux joystick driver using the Linux input_joystick subsystem. Requires sysfs -to be mounted on /sys and /dev/input/js* to be readable. +Linux joystick driver using the Linux input_joystick subsystem. + +Requires sysfs to be mounted on /sys and /dev/input/js* to be readable. This module is very linux specific but should work on any CPU platform """ @@ -67,9 +68,7 @@ class JEvent(object): - """ - Joystick event class. Encapsulate single joystick event. - """ + """Joystick event class. Encapsulate single joystick event.""" def __init__(self, evt_type, number, value): self.type = evt_type @@ -80,6 +79,7 @@ def __repr__(self): return "JEvent(type={}, number={}, value={})".format( self.type, self.number, self.value) + # Constants TYPE_BUTTON = 1 TYPE_AXIS = 2 @@ -123,7 +123,7 @@ def open(self): self.__initvalues() def close(self): - """Open the joystick device""" + """Open the joystick device.""" if not self._f: return @@ -133,21 +133,21 @@ def close(self): self._f = None def __initvalues(self): - """Read the buttons and axes initial values from the js device""" + """Read the buttons and axes initial values from the js device.""" for _ in range(len(self.axes) + len(self.buttons)): data = self._f.read(struct.calcsize(JS_EVENT_FMT)) jsdata = struct.unpack(JS_EVENT_FMT, data) self.__updatestate(jsdata) def __updatestate(self, jsdata): - """Update the internal absolute state of buttons and axes""" + """Update the internal absolute state of buttons and axes.""" if jsdata[JE_TYPE] & JS_EVENT_AXIS != 0: self.axes[jsdata[JE_NUMBER]] = jsdata[JE_VALUE] / 32768.0 elif jsdata[JE_TYPE] & JS_EVENT_BUTTON != 0: self.buttons[jsdata[JE_NUMBER]] = jsdata[JE_VALUE] def __decode_event(self, jsdata): - """ Decode a jsdev event into a dict """ + """Decode a jsdev event into a dict.""" # TODO: Add timestamp? if jsdata[JE_TYPE] & JS_EVENT_AXIS != 0: return JEvent(evt_type=TYPE_AXIS, @@ -159,7 +159,7 @@ def __decode_event(self, jsdata): value=jsdata[JE_VALUE] / 32768.0) def _read_all_events(self): - """Consume all the events queued up in the JS device""" + """Consume all the events queued up in the JS device.""" try: while True: data = self._f.read(struct.calcsize(JS_EVENT_FMT)) @@ -182,7 +182,7 @@ def _read_all_events(self): pass def read(self): - """ Returns a list of all joystick event since the last call """ + """Return a list of all joystick event since the last call.""" if not self._f: raise Exception("Joystick device not opened") @@ -192,9 +192,7 @@ def read(self): class Joystick(): - """ - Linux jsdev implementation of the Joystick class - """ + """Linux jsdev implementation of the Joystick class.""" def __init__(self): self.name = MODULE_NAME @@ -203,8 +201,9 @@ def __init__(self): def devices(self): """ - Returns a list containing an {"id": id, "name": name} dict for each - detected device. Result is cached once one or more devices are found. + Return a list containing an {"id": id, "name": name} dict for each detected device. + + Result is cached once one or more devices are found. """ if len(self._devices) == 0: syspaths = glob.glob("/sys/class/input/js*") @@ -219,15 +218,13 @@ def devices(self): return self._devices def open(self, device_id): - """ - Open the joystick device. The device_id is given by available_devices - """ + """Open the joystick device. The device_id is given by available_devices.""" self._js[device_id].open() def close(self, device_id): - """Open the joystick device""" + """Open the joystick device.""" self._js[device_id].close() def read(self, device_id): - """ Returns a list of all joystick event since the last call """ + """Return a list of all joystick event since the last call.""" return self._js[device_id].read() diff --git a/crazyflie_py/crazyflie_py/uav_trajectory.py b/crazyflie_py/crazyflie_py/uav_trajectory.py index 91939450a..b75af3585 100644 --- a/crazyflie_py/crazyflie_py/uav_trajectory.py +++ b/crazyflie_py/crazyflie_py/uav_trajectory.py @@ -2,108 +2,116 @@ import numpy as np + def normalize(v): - norm = np.linalg.norm(v) - assert norm > 0 - return v / norm + norm = np.linalg.norm(v) + assert norm > 0 + return v / norm class Polynomial: - def __init__(self, p): - self.p = p + def __init__(self, p): + self.p = p - # evaluate a polynomial using horner's rule - def eval(self, t): - assert t >= 0 - x = 0.0 - for i in range(0, len(self.p)): - x = x * t + self.p[len(self.p) - 1 - i] - return x + # evaluate a polynomial using horner's rule + def eval(self, t): + assert t >= 0 + x = 0.0 + for i in range(0, len(self.p)): + x = x * t + self.p[len(self.p) - 1 - i] + return x - # compute and return derivative - def derivative(self): - return Polynomial([(i+1) * self.p[i+1] for i in range(0, len(self.p) - 1)]) + # compute and return derivative + def derivative(self): + return Polynomial([(i+1) * self.p[i+1] for i in range(0, len(self.p) - 1)]) class TrajectoryOutput: - def __init__(self): - self.pos = None # position [m] - self.vel = None # velocity [m/s] - self.acc = None # acceleration [m/s^2] - self.omega = None # angular velocity [rad/s] - self.yaw = None # yaw angle [rad] + def __init__(self): + self.pos = None # position [m] + self.vel = None # velocity [m/s] + self.acc = None # acceleration [m/s^2] + self.omega = None # angular velocity [rad/s] + self.yaw = None # yaw angle [rad] # 4d single polynomial piece for x-y-z-yaw, includes duration. class Polynomial4D: - def __init__(self, duration, px, py, pz, pyaw): - self.duration = duration - self.px = Polynomial(px) - self.py = Polynomial(py) - self.pz = Polynomial(pz) - self.pyaw = Polynomial(pyaw) - - # compute and return derivative - def derivative(self): - return Polynomial4D( - self.duration, - self.px.derivative().p, - self.py.derivative().p, - self.pz.derivative().p, - self.pyaw.derivative().p) - - def eval(self, t): - result = TrajectoryOutput() - # flat variables - result.pos = np.array([self.px.eval(t), self.py.eval(t), self.pz.eval(t)]) - result.yaw = self.pyaw.eval(t) - - # 1st derivative - derivative = self.derivative() - result.vel = np.array([derivative.px.eval(t), derivative.py.eval(t), derivative.pz.eval(t)]) - dyaw = derivative.pyaw.eval(t) - - # 2nd derivative - derivative2 = derivative.derivative() - result.acc = np.array([derivative2.px.eval(t), derivative2.py.eval(t), derivative2.pz.eval(t)]) - - # 3rd derivative - derivative3 = derivative2.derivative() - jerk = np.array([derivative3.px.eval(t), derivative3.py.eval(t), derivative3.pz.eval(t)]) - - thrust = result.acc + np.array([0, 0, 9.81]) # add gravity - - z_body = normalize(thrust) - x_world = np.array([np.cos(result.yaw), np.sin(result.yaw), 0]) - y_body = normalize(np.cross(z_body, x_world)) - x_body = np.cross(y_body, z_body) - - jerk_orth_zbody = jerk - (np.dot(jerk, z_body) * z_body) - h_w = jerk_orth_zbody / np.linalg.norm(thrust) - - result.omega = np.array([-np.dot(h_w, y_body), np.dot(h_w, x_body), z_body[2] * dyaw]) - return result + def __init__(self, duration, px, py, pz, pyaw): + self.duration = duration + self.px = Polynomial(px) + self.py = Polynomial(py) + self.pz = Polynomial(pz) + self.pyaw = Polynomial(pyaw) + + # compute and return derivative + def derivative(self): + return Polynomial4D( + self.duration, + self.px.derivative().p, + self.py.derivative().p, + self.pz.derivative().p, + self.pyaw.derivative().p) + + def eval(self, t): + result = TrajectoryOutput() + # flat variables + result.pos = np.array([self.px.eval(t), self.py.eval(t), self.pz.eval(t)]) + result.yaw = self.pyaw.eval(t) + + # 1st derivative + derivative = self.derivative() + result.vel = np.array([derivative.px.eval(t), + derivative.py.eval(t), + derivative.pz.eval(t)]) + dyaw = derivative.pyaw.eval(t) + + # 2nd derivative + derivative2 = derivative.derivative() + result.acc = np.array([derivative2.px.eval(t), + derivative2.py.eval(t), + derivative2.pz.eval(t)]) + + # 3rd derivative + derivative3 = derivative2.derivative() + jerk = np.array([derivative3.px.eval(t), + derivative3.py.eval(t), + derivative3.pz.eval(t)]) + + thrust = result.acc + np.array([0, 0, 9.81]) # add gravity + + z_body = normalize(thrust) + x_world = np.array([np.cos(result.yaw), np.sin(result.yaw), 0]) + y_body = normalize(np.cross(z_body, x_world)) + x_body = np.cross(y_body, z_body) + + jerk_orth_zbody = jerk - (np.dot(jerk, z_body) * z_body) + h_w = jerk_orth_zbody / np.linalg.norm(thrust) + + result.omega = np.array([-np.dot(h_w, y_body), np.dot(h_w, x_body), z_body[2] * dyaw]) + return result class Trajectory: - def __init__(self): - self.polynomials = None - self.duration = None - - def n_pieces(self): - return len(self.polynomials) - - def loadcsv(self, filename): - data = np.loadtxt(filename, delimiter=",", skiprows=1, usecols=range(33)) - self.polynomials = [Polynomial4D(row[0], row[1:9], row[9:17], row[17:25], row[25:33]) for row in data] - self.duration = np.sum(data[:,0]) - - def eval(self, t): - assert t >= 0 - assert t <= self.duration - - current_t = 0.0 - for p in self.polynomials: - if t <= current_t + p.duration: - return p.eval(t - current_t) - current_t = current_t + p.duration + def __init__(self): + self.polynomials = None + self.duration = None + + def n_pieces(self): + return len(self.polynomials) + + def loadcsv(self, filename): + data = np.loadtxt(filename, delimiter=",", skiprows=1, usecols=range(33)) + self.polynomials = [Polynomial4D(row[0], row[1:9], + row[9:17], row[17:25], row[25:33]) for row in data] + self.duration = np.sum(data[:, 0]) + + def eval(self, t): + assert t >= 0 + assert t <= self.duration + + current_t = 0.0 + for p in self.polynomials: + if t <= current_t + p.duration: + return p.eval(t - current_t) + current_t = current_t + p.duration diff --git a/crazyflie_py/crazyflie_py/util.py b/crazyflie_py/crazyflie_py/util.py index e27dfaa74..602862b5b 100644 --- a/crazyflie_py/crazyflie_py/util.py +++ b/crazyflie_py/crazyflie_py/util.py @@ -6,15 +6,19 @@ def check_ellipsoid_collisions(positions, radii): - """Checks for collisions between a set of ellipsoids at given positions. + """ + Check for collisions between a set of ellipsoids at given positions. Args: + ---- positions (array float[n, 3]): The ellipsoid centers. radii (array float[3]): The radii of the axis-aligned ellipsoids. - Returns: + Returns + ------- colliding (array bool[n]): True at index i if the i'th ellipsoid intersects any of the other ellipsoids. + """ scaled = positions / radii[None, :] dists = sp.spatial.distance.pdist(scaled) @@ -27,33 +31,36 @@ def check_ellipsoid_collisions(positions, radii): def poisson_disk_sample(n, dim, mindist): - """Generates random points with guaranteed minimum pairwise distance. + """ + Generate random points with guaranteed minimum pairwise distance. Uses extremely naive and slow "dart throwing" algorithm. TODO(jpreiss): find/implement a library with a fast algorithm. Args: + ---- n (int): Number of points. dim (int): Dimensionality of points. mindist (float): Minimum Euclidean distance between any two points. - Returns: + Returns + ------- pts (array float[n, dim]): The sampled points. - """ + """ # Select hypercube volume such that n points will not pack it too tightly. # Note: Will be too sparse for dim >> 3, but reasonable for dim == 2 or 3. measure_ratio = 1.25 std = (measure_ratio * n) ** (1.0 / dim) * mindist + def sample(): return std * np.random.uniform(-0.5, 0.5, size=dim) # Sample the points using dart-throwing. - pts = sample()[None,:] + pts = sample()[None, :] while len(pts) < n: pt = sample() dists = np.linalg.norm(pts - pt, axis=1) if np.all(dists >= mindist): - pts = np.concatenate([pts, pt[None,:]], axis=0) + pts = np.concatenate([pts, pt[None, :]], axis=0) return pts - diff --git a/crazyflie_py/test/test_copyright.py b/crazyflie_py/test/test_copyright.py deleted file mode 100644 index cc8ff03f7..000000000 --- a/crazyflie_py/test/test_copyright.py +++ /dev/null @@ -1,23 +0,0 @@ -# Copyright 2015 Open Source Robotics Foundation, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from ament_copyright.main import main -import pytest - - -@pytest.mark.copyright -@pytest.mark.linter -def test_copyright(): - rc = main(argv=['.', 'test']) - assert rc == 0, 'Found errors' From 24bc57b90a7883511819317d7c572b1b146880a9 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Thu, 19 Oct 2023 07:17:05 +0200 Subject: [PATCH 005/162] CI: add rowan --- .github/workflows/ci-ros2.yml | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/.github/workflows/ci-ros2.yml b/.github/workflows/ci-ros2.yml index 5941c2c88..315d94ba1 100644 --- a/.github/workflows/ci-ros2.yml +++ b/.github/workflows/ci-ros2.yml @@ -42,6 +42,12 @@ jobs: sudo apt update sudo apt install -y libusb-1.0-0-dev + - name: install pip dependencies + # TODO: would be better to follow https://answers.ros.org/question/370666/how-to-declare-an-external-python-dependency-in-ros2/ + # but this requires some upstream changes + run: | + pip install rowan + - uses: actions/checkout@v2 - name: build and test ROS 2 uses: ros-tooling/action-ros-ci@v0.3 From 92664ff85c24698ab48867a89597afc7d44f97be Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Thu, 19 Oct 2023 11:20:35 +0200 Subject: [PATCH 006/162] fix more flake8 issues --- crazyflie_py/crazyflie_py/__init__.py | 2 +- crazyflie_py/crazyflie_py/crazyflie.py | 137 ++++++++++--------- crazyflie_py/crazyflie_py/crazyswarm_py.py | 3 +- crazyflie_py/crazyflie_py/genericJoystick.py | 10 +- crazyflie_py/crazyflie_py/joystick.py | 4 +- crazyflie_py/crazyflie_py/keyboard.py | 5 +- crazyflie_py/crazyflie_py/linuxjsdev.py | 46 +++---- crazyflie_py/crazyflie_py/uav_trajectory.py | 12 +- 8 files changed, 115 insertions(+), 104 deletions(-) diff --git a/crazyflie_py/crazyflie_py/__init__.py b/crazyflie_py/crazyflie_py/__init__.py index 6184517df..44fbd53e3 100644 --- a/crazyflie_py/crazyflie_py/__init__.py +++ b/crazyflie_py/crazyflie_py/__init__.py @@ -1,3 +1,3 @@ from .crazyswarm_py import Crazyswarm -__all__ = ["Crazyswarm"] +__all__ = ['Crazyswarm'] diff --git a/crazyflie_py/crazyflie_py/crazyflie.py b/crazyflie_py/crazyflie_py/crazyflie.py index c679e6c62..03055a8bc 100644 --- a/crazyflie_py/crazyflie_py/crazyflie.py +++ b/crazyflie_py/crazyflie_py/crazyflie.py @@ -1,9 +1,9 @@ #!/usr/bin/env python +from collections import defaultdict # import sys # import rospy -import numpy as np # import time # import tf_conversions # from std_srvs.srv import Empty @@ -13,18 +13,19 @@ # from tf import TransformListener # from .visualizer import visNull -from collections import defaultdict + +from crazyflie_interfaces.msg import FullState, Position, TrajectoryPolynomialPiece +from crazyflie_interfaces.srv import GoTo, Land,\ + NotifySetpointsStop, StartTrajectory, Takeoff, UploadTrajectory +from geometry_msgs.msg import Point +import numpy as np +from rcl_interfaces.msg import Parameter, ParameterType, ParameterValue +from rcl_interfaces.srv import DescribeParameters, GetParameters, ListParameters, SetParameters import rclpy import rclpy.node import rowan from std_srvs.srv import Empty -from geometry_msgs.msg import Point -from rcl_interfaces.srv import GetParameters, SetParameters, ListParameters, DescribeParameters -from rcl_interfaces.msg import Parameter, ParameterValue, ParameterType -from crazyflie_interfaces.srv import Takeoff, Land, GoTo, \ - UploadTrajectory, StartTrajectory, NotifySetpointsStop -from crazyflie_interfaces.msg import TrajectoryPolynomialPiece, FullState, Position def arrayToGeometryPoint(a): @@ -109,42 +110,42 @@ def __init__(self, node, cfname, paramTypeDict): paramTypeDict: dictionary of the parameter types """ - prefix = "/" + cfname + prefix = '/' + cfname self.prefix = prefix self.node = node # self.tf = tf - # rospy.wait_for_service(prefix + "/set_group_mask") - # self.setGroupMaskService = rospy.ServiceProxy(prefix + "/set_group_mask", SetGroupMask) - self.emergencyService = node.create_client(Empty, prefix + "/emergency") + # rospy.wait_for_service(prefix + '/set_group_mask') + # self.setGroupMaskService = rospy.ServiceProxy(prefix + '/set_group_mask', SetGroupMask) + self.emergencyService = node.create_client(Empty, prefix + '/emergency') self.emergencyService.wait_for_service() - self.takeoffService = node.create_client(Takeoff, prefix + "/takeoff") + self.takeoffService = node.create_client(Takeoff, prefix + '/takeoff') self.takeoffService.wait_for_service() - self.landService = node.create_client(Land, prefix + "/land") + self.landService = node.create_client(Land, prefix + '/land') self.landService.wait_for_service() - # # rospy.wait_for_service(prefix + "/stop") - # # self.stopService = rospy.ServiceProxy(prefix + "/stop", Stop) - self.goToService = node.create_client(GoTo, prefix + "/go_to") + # # rospy.wait_for_service(prefix + '/stop') + # # self.stopService = rospy.ServiceProxy(prefix + '/stop', Stop) + self.goToService = node.create_client(GoTo, prefix + '/go_to') self.goToService.wait_for_service() self.uploadTrajectoryService = node.create_client( - UploadTrajectory, prefix + "/upload_trajectory") + UploadTrajectory, prefix + '/upload_trajectory') self.uploadTrajectoryService.wait_for_service() self.startTrajectoryService = node.create_client( - StartTrajectory, prefix + "/start_trajectory") + StartTrajectory, prefix + '/start_trajectory') self.startTrajectoryService.wait_for_service() self.notifySetpointsStopService = node.create_client( - NotifySetpointsStop, prefix + "/notify_setpoints_stop") + NotifySetpointsStop, prefix + '/notify_setpoints_stop') self.notifySetpointsStopService.wait_for_service() self.setParamsService = node.create_client( - SetParameters, "/crazyflie_server/set_parameters") + SetParameters, '/crazyflie_server/set_parameters') self.setParamsService.wait_for_service() # Query some settings - getParamsService = node.create_client(GetParameters, "/crazyflie_server/get_parameters") + getParamsService = node.create_client(GetParameters, '/crazyflie_server/get_parameters') getParamsService.wait_for_service() req = GetParameters.Request() - req.names = ["robots.{}.initial_position".format(cfname), "robots.{}.uri".format(cfname)] + req.names = ['robots.{}.initial_position'.format(cfname), 'robots.{}.uri'.format(cfname)] future = getParamsService.call_async(req) while rclpy.ok(): rclpy.spin_once(node) @@ -166,26 +167,26 @@ def __init__(self, node, cfname, paramTypeDict): self.paramTypeDict = paramTypeDict self.cmdFullStatePublisher = node.create_publisher( - FullState, prefix + "/cmd_full_state", 1) + FullState, prefix + '/cmd_full_state', 1) self.cmdFullStateMsg = FullState() - self.cmdFullStateMsg.header.frame_id = "/world" + self.cmdFullStateMsg.header.frame_id = '/world' # self.cmdStopPublisher = rospy.Publisher( - # prefix + "/cmd_stop", std_msgs.msg.Empty, queue_size=1) + # prefix + '/cmd_stop', std_msgs.msg.Empty, queue_size=1) # self.cmdVelPublisher = rospy.Publisher( - # prefix + "/cmd_vel", geometry_msgs.msg.Twist, queue_size=1) + # prefix + '/cmd_vel', geometry_msgs.msg.Twist, queue_size=1) self.cmdPositionPublisher = node.create_publisher( - Position, prefix + "/cmd_position", 1) + Position, prefix + '/cmd_position', 1) self.cmdPositionMsg = Position() - self.cmdPositionMsg.header.frame_id = "/world" + self.cmdPositionMsg.header.frame_id = '/world' # self.cmdVelocityWorldPublisher = rospy.Publisher( - # prefix + "/cmd_velocity_world", VelocityWorld, queue_size=1) + # prefix + '/cmd_velocity_world', VelocityWorld, queue_size=1) # self.cmdVelocityWorldMsg = VelocityWorld() # self.cmdVelocityWorldMsg.header.seq = 0 - # self.cmdVelocityWorldMsg.header.frame_id = "/world" + # self.cmdVelocityWorldMsg.header.frame_id = '/world' # def setGroupMask(self, groupMask): # """Sets the group mask bits for this robot. @@ -193,7 +194,7 @@ def __init__(self, node, cfname, paramTypeDict): # The purpose of groups is to make it possible to trigger an action # (for example, executing a previously-uploaded trajectory) on a subset # of all robots without needing to send more than one radio packet. - # This is important to achieve tight, synchronized "choreography". + # This is important to achieve tight, synchronized 'choreography'. # Up to 8 groups may exist, corresponding to bits in the groupMask byte. # When a broadcast command is triggered on the :obj:`CrazyflieServer` object @@ -240,15 +241,15 @@ def __init__(self, node, cfname, paramTypeDict): # # Set radii before enabling to ensure collision avoidance never # # observes a wrong radius value. # self.setParams({ - # "colAv/ellipsoidX": float(ellipsoidRadii[0]), - # "colAv/ellipsoidY": float(ellipsoidRadii[1]), - # "colAv/ellipsoidZ": float(ellipsoidRadii[2]), + # 'colAv/ellipsoidX': float(ellipsoidRadii[0]), + # 'colAv/ellipsoidY': float(ellipsoidRadii[1]), + # 'colAv/ellipsoidZ': float(ellipsoidRadii[2]), # }) - # self.setParam("colAv/enable", 1) + # self.setParam('colAv/enable', 1) # def disableCollisionAvoidance(self): # """Disables onboard collision avoidance.""" - # self.setParam("colAv/enable", 0) + # self.setParam('colAv/enable', 0) def emergency(self): """ @@ -469,9 +470,9 @@ def notifySetpointsStop(self, remainValidMillisecs=100, groupMask=0): # position (np.array[3]): Current position. Meters. # """ # self.tf.waitForTransform( - # "/world", "/cf" + str(self.id), rospy.Time(0), rospy.Duration(10)) + # '/world', '/cf' + str(self.id), rospy.Time(0), rospy.Duration(10)) # position, quaternion = self.tf.lookupTransform( - # "/world", "/cf" + str(self.id), rospy.Time(0)) + # '/world', '/cf' + str(self.id), rospy.Time(0)) # return np.array(position) # def getParam(self, name): @@ -493,7 +494,7 @@ def notifySetpointsStop(self, remainValidMillisecs=100, groupMask=0): # Returns: # value (Any): The parameter's value. # """ - # return rospy.get_param(self.prefix + "/" + name) + # return rospy.get_param(self.prefix + '/' + name) def setParam(self, name, value): """ @@ -507,7 +508,7 @@ def setParam(self, name, value): value (Any): The parameter's value. """ - param_name = self.prefix[1:] + ".params." + name + param_name = self.prefix[1:] + '.params.' + name param_type = self.paramTypeDict[name] if param_type == ParameterType.PARAMETER_INTEGER: param_value = ParameterValue(type=param_type, integer_value=int(value)) @@ -526,7 +527,7 @@ def setParam(self, name, value): # params (Dict[str, Any]): Dict of parameter names/values. # """ # for name, value in params.items(): - # rospy.set_param(self.prefix + "/" + name, value) + # rospy.set_param(self.prefix + '/' + name, value) # self.updateParamsService(params.keys()) def cmdFullState(self, pos, vel, acc, yaw, omega): @@ -614,11 +615,11 @@ def cmdFullState(self, pos, vel, acc, yaw, omega): # self.cmdStopPublisher.publish(std_msgs.msg.Empty()) # def cmdVel(self, roll, pitch, yawrate, thrust): - # """Sends a streaming command of the "easy mode" manual control inputs. + # """Sends a streaming command of the 'easy mode' manual control inputs. # The (absolute roll & pitch, yaw rate, thrust) inputs are typically # used for manual flying by beginners or causal pilots, as opposed to the - # "acrobatic mode" inputs where roll and pitch rates are controlled + # 'acrobatic mode' inputs where roll and pitch rates are controlled # instead of absolute angles. This mode limits the possible maneuvers, # e.g. it is not possible to do a flip because the controller joystick # would need to rotate 360 degrees. @@ -678,7 +679,7 @@ def cmdPosition(self, pos, yaw=0.): # common to change the LED ring color many times during a flight, e.g. # as some kind of status indicator. This method makes it convenient. - # PRECONDITION: The param "ring/effect" must be set to 7 (solid color) + # PRECONDITION: The param 'ring/effect' must be set to 7 (solid color) # for this command to have any effect. The default mode uses the ring # color to indicate radio connection quality. @@ -690,9 +691,9 @@ def cmdPosition(self, pos, yaw=0.): # g (float): Green component of color, in range [0, 1]. # b (float): Blue component of color, in range [0, 1]. # """ - # self.setParam("ring/solidRed", int(r * 255)) - # self.setParam("ring/solidGreen", int(g * 255)) - # self.setParam("ring/solidBlue", int(b * 255)) + # self.setParam('ring/solidRed', int(r * 255)) + # self.setParam('ring/solidGreen', int(g * 255)) + # self.setParam('ring/solidBlue', int(b * 255)) class CrazyflieServer(rclpy.node.Node): @@ -712,37 +713,37 @@ class CrazyflieServer(rclpy.node.Node): def __init__(self): """Initialize the server. Waits for all ROS services before returning.""" - super().__init__("CrazyflieAPI") - self.emergencyService = self.create_client(Empty, "all/emergency") + super().__init__('CrazyflieAPI') + self.emergencyService = self.create_client(Empty, 'all/emergency') self.emergencyService.wait_for_service() - self.takeoffService = self.create_client(Takeoff, "all/takeoff") + self.takeoffService = self.create_client(Takeoff, 'all/takeoff') self.takeoffService.wait_for_service() - self.landService = self.create_client(Land, "all/land") + self.landService = self.create_client(Land, 'all/land') self.landService.wait_for_service() - self.goToService = self.create_client(GoTo, "all/go_to") + self.goToService = self.create_client(GoTo, 'all/go_to') self.goToService.wait_for_service() - self.startTrajectoryService = self.create_client(StartTrajectory, "all/start_trajectory") + self.startTrajectoryService = self.create_client(StartTrajectory, 'all/start_trajectory') self.startTrajectoryService.wait_for_service() self.setParamsService = self.create_client( - SetParameters, "/crazyflie_server/set_parameters") + SetParameters, '/crazyflie_server/set_parameters') self.setParamsService.wait_for_service() self.cmdFullStatePublisher = self.create_publisher( - FullState, "all/cmd_full_state", 1) + FullState, 'all/cmd_full_state', 1) self.cmdFullStateMsg = FullState() - self.cmdFullStateMsg.header.frame_id = "/world" + self.cmdFullStateMsg.header.frame_id = '/world' cfnames = [] for srv_name, srv_types in self.get_service_names_and_types(): - if "crazyflie_interfaces/srv/StartTrajectory" in srv_types: - # remove "/" and "/start_trajectory" + if 'crazyflie_interfaces/srv/StartTrajectory' in srv_types: + # remove '/' and '/start_trajectory' cfname = srv_name[1:-17] - if cfname != "all": + if cfname != 'all': cfnames.append(cfname) # Query all parameters - listParamsService = self.create_client(ListParameters, "/crazyflie_server/list_parameters") + listParamsService = self.create_client(ListParameters, '/crazyflie_server/list_parameters') listParamsService.wait_for_service() req = ListParameters.Request() req.depth = ListParameters.Request.DEPTH_RECURSIVE @@ -755,13 +756,13 @@ def __init__(self): # Filter the parameters that belong to this Crazyflie response = future.result() for p in response.result.names: - if ".params." in p: + if '.params.' in p: params.append(p) break # Find the types for the parameters and store them describeParametersService = self.create_client( - DescribeParameters, "/crazyflie_server/describe_parameters") + DescribeParameters, '/crazyflie_server/describe_parameters') describeParametersService.wait_for_service() req = DescribeParameters.Request() req.names = params @@ -773,7 +774,7 @@ def __init__(self): # Filter the parameters that belong to this Crazyflie response = future.result() for p, d in zip(params, response.descriptors): - idx = p.index(".params.") + idx = p.index('.params.') cf_name = p[0:idx] param_name = p[idx+8:] t = d.type @@ -782,11 +783,11 @@ def __init__(self): else: allParamTypeDicts[cf_name] = {param_name: t} break - self.paramTypeDict = allParamTypeDicts["all"] + self.paramTypeDict = allParamTypeDicts['all'] self.crazyflies = [] - self.crazyfliesById = dict() - self.crazyfliesByName = dict() + self.crazyfliesById = {} + self.crazyfliesByName = {} for cfname in cfnames: cf = Crazyflie(self, cfname, allParamTypeDicts[cfname]) self.crazyflies.append(cf) @@ -918,7 +919,7 @@ def startTrajectory(self, trajectoryId, def setParam(self, name, value): """Set parameter via broadcasts. See Crazyflie.setParam for details.""" - param_name = "all.params." + name + param_name = 'all.params.' + name param_type = self.paramTypeDict[name] if param_type == ParameterType.PARAMETER_INTEGER: param_value = ParameterValue(type=param_type, integer_value=int(value)) diff --git a/crazyflie_py/crazyflie_py/crazyswarm_py.py b/crazyflie_py/crazyflie_py/crazyswarm_py.py index 959ac44a6..ad3280639 100644 --- a/crazyflie_py/crazyflie_py/crazyswarm_py.py +++ b/crazyflie_py/crazyflie_py/crazyswarm_py.py @@ -1,10 +1,11 @@ import rclpy from . import genericJoystick -from .crazyflie import TimeHelper, CrazyflieServer +from .crazyflie import CrazyflieServer, TimeHelper class Crazyswarm: + def __init__(self): rclpy.init() diff --git a/crazyflie_py/crazyflie_py/genericJoystick.py b/crazyflie_py/crazyflie_py/genericJoystick.py index 32364b203..1fe1651a3 100644 --- a/crazyflie_py/crazyflie_py/genericJoystick.py +++ b/crazyflie_py/crazyflie_py/genericJoystick.py @@ -1,5 +1,6 @@ import copy # import pyglet + from . import keyboard # class JoyStickHandler: @@ -21,6 +22,7 @@ class Joystick: + def __init__(self, timeHelper): # joysticks = pyglet.input.get_joysticks() # joystick = joysticks[0] @@ -35,14 +37,14 @@ def __init__(self, timeHelper): self.js = linuxjsdev.Joystick() devices = self.js.devices() if len(devices) == 0: - print("Warning: No joystick found!") + print('Warning: No joystick found!') else: - ids = [dev["id"] for dev in devices] + ids = [dev['id'] for dev in devices] # For backwards compatibility, always choose device 0 if available. - self.joyID = 0 if 0 in ids else devices[0]["id"] + self.joyID = 0 if 0 in ids else devices[0]['id'] self.js.open(self.joyID) except ImportError: - print("Warning: Joystick only supported on Linux.") + print('Warning: Joystick only supported on Linux.') # def on_joybutton_press(joystick, button): # print(button) diff --git a/crazyflie_py/crazyflie_py/joystick.py b/crazyflie_py/crazyflie_py/joystick.py index f6ae10500..bdc1a096a 100644 --- a/crazyflie_py/crazyflie_py/joystick.py +++ b/crazyflie_py/crazyflie_py/joystick.py @@ -1,13 +1,15 @@ import time + import rospy from sensor_msgs.msg import Joy class Joystick: + def __init__(self): self.lastButtonState = 0 self.buttonWasPressed = False - rospy.Subscriber("/joy", Joy, self.joyChanged) + rospy.Subscriber('/joy', Joy, self.joyChanged) def joyChanged(self, data): if (not self.buttonWasPressed and diff --git a/crazyflie_py/crazyflie_py/keyboard.py b/crazyflie_py/crazyflie_py/keyboard.py index b4c92992f..d91cd1c25 100644 --- a/crazyflie_py/crazyflie_py/keyboard.py +++ b/crazyflie_py/crazyflie_py/keyboard.py @@ -1,9 +1,10 @@ -import sys import select +import sys import termios class KeyPoller(): + def __enter__(self): # Save the terminal settings self.fd = sys.stdin.fileno() @@ -16,7 +17,7 @@ def __enter__(self): return self - def __exit__(self, type, value, traceback): + def __exit__(self, type, value, traceback): # noqa A002 termios.tcsetattr(self.fd, termios.TCSAFLUSH, self.old_term) def poll(self): diff --git a/crazyflie_py/crazyflie_py/linuxjsdev.py b/crazyflie_py/crazyflie_py/linuxjsdev.py index c9ebf50a3..8bea8def8 100644 --- a/crazyflie_py/crazyflie_py/linuxjsdev.py +++ b/crazyflie_py/crazyflie_py/linuxjsdev.py @@ -37,19 +37,19 @@ import sys if not sys.platform.startswith('linux'): - raise ImportError("Only supported on Linux") + raise ImportError('Only supported on Linux') try: import fcntl except ImportError as e: - raise Exception("fcntl library probably not installed ({})".format(e)) + raise Exception('fcntl library probably not installed ({})'.format(e)) __author__ = 'Bitcraze AB' __all__ = ['Joystick'] logger = logging.getLogger(__name__) -JS_EVENT_FMT = "@IhBB" +JS_EVENT_FMT = '@IhBB' JE_TIME = 0 JE_VALUE = 1 JE_TYPE = 2 @@ -63,8 +63,8 @@ JSIOCGAXES = 0x80016a11 JSIOCGBUTTONS = 0x80016a12 -MODULE_MAIN = "Joystick" -MODULE_NAME = "linuxjsdev" +MODULE_MAIN = 'Joystick' +MODULE_NAME = 'linuxjsdev' class JEvent(object): @@ -76,7 +76,7 @@ def __init__(self, evt_type, number, value): self.value = value def __repr__(self): - return "JEvent(type={}, number={}, value={})".format( + return 'JEvent(type={}, number={}, value={})'.format( self.type, self.number, self.value) @@ -90,7 +90,7 @@ class _JS(): def __init__(self, num, name): self.num = num self.name = name - self._f_name = "/dev/input/js{}".format(num) + self._f_name = '/dev/input/js{}'.format(num) self._f = None self.opened = False @@ -98,12 +98,12 @@ def __init__(self, num, name): self.axes = [] self._prev_pressed = {} - def open(self): + def open(self): # noqa: A003 if self._f: - raise Exception("{} at {} is already " - "opened".format(self.name, self._f_name)) + raise Exception('{} at {} is already ' + 'opened'.format(self.name, self._f_name)) - self._f = open("/dev/input/js{}".format(self.num), "rb") + self._f = open('/dev/input/js{}'.format(self.num), 'rb') fcntl.fcntl(self._f.fileno(), fcntl.F_SETFL, os.O_NONBLOCK) # Get number of axis and button @@ -111,15 +111,15 @@ def open(self): if fcntl.ioctl(self._f.fileno(), JSIOCGAXES, val) != 0: self._f.close() self._f = None - raise Exception("Failed to read number of axes") + raise Exception('Failed to read number of axes') - self.axes = list(0 for i in range(val.value)) + self.axes = [0 for i in range(val.value)] if fcntl.ioctl(self._f.fileno(), JSIOCGBUTTONS, val) != 0: self._f.close() self._f = None - raise Exception("Failed to read number of axes") + raise Exception('Failed to read number of axes') - self.buttons = list(0 for i in range(val.value)) + self.buttons = [0 for i in range(val.value)] self.__initvalues() def close(self): @@ -127,7 +127,7 @@ def close(self): if not self._f: return - logger.info("Closed {} ({})".format(self.name, self.num)) + logger.info('Closed {} ({})'.format(self.name, self.num)) self._f.close() self._f = None @@ -170,7 +170,7 @@ def _read_all_events(self): logger.info(str(e)) self._f.close() self._f = None - raise IOError("Device has been disconnected") + raise IOError('Device has been disconnected') except TypeError: pass except ValueError: @@ -184,7 +184,7 @@ def _read_all_events(self): def read(self): """Return a list of all joystick event since the last call.""" if not self._f: - raise Exception("Joystick device not opened") + raise Exception('Joystick device not opened') self._read_all_events() @@ -201,23 +201,23 @@ def __init__(self): def devices(self): """ - Return a list containing an {"id": id, "name": name} dict for each detected device. + Return a list containing an {'id': id, 'name': name} dict for each detected device. Result is cached once one or more devices are found. """ if len(self._devices) == 0: - syspaths = glob.glob("/sys/class/input/js*") + syspaths = glob.glob('/sys/class/input/js*') for path in syspaths: device_id = int(os.path.basename(path)[2:]) - with open(path + "/device/name") as namefile: + with open(path + '/device/name') as namefile: name = namefile.read().strip() self._js[device_id] = _JS(device_id, name) - self._devices.append({"id": device_id, "name": name}) + self._devices.append({'id': device_id, 'name': name}) return self._devices - def open(self, device_id): + def open(self, device_id): # noqa: A003 """Open the joystick device. The device_id is given by available_devices.""" self._js[device_id].open() diff --git a/crazyflie_py/crazyflie_py/uav_trajectory.py b/crazyflie_py/crazyflie_py/uav_trajectory.py index b75af3585..39e0db1d2 100644 --- a/crazyflie_py/crazyflie_py/uav_trajectory.py +++ b/crazyflie_py/crazyflie_py/uav_trajectory.py @@ -10,11 +10,12 @@ def normalize(v): class Polynomial: + def __init__(self, p): self.p = p # evaluate a polynomial using horner's rule - def eval(self, t): + def eval(self, t): # noqa: A003 assert t >= 0 x = 0.0 for i in range(0, len(self.p)): @@ -27,6 +28,7 @@ def derivative(self): class TrajectoryOutput: + def __init__(self): self.pos = None # position [m] self.vel = None # velocity [m/s] @@ -37,6 +39,7 @@ def __init__(self): # 4d single polynomial piece for x-y-z-yaw, includes duration. class Polynomial4D: + def __init__(self, duration, px, py, pz, pyaw): self.duration = duration self.px = Polynomial(px) @@ -53,7 +56,7 @@ def derivative(self): self.pz.derivative().p, self.pyaw.derivative().p) - def eval(self, t): + def eval(self, t): # noqa: A003 result = TrajectoryOutput() # flat variables result.pos = np.array([self.px.eval(t), self.py.eval(t), self.pz.eval(t)]) @@ -93,6 +96,7 @@ def eval(self, t): class Trajectory: + def __init__(self): self.polynomials = None self.duration = None @@ -101,12 +105,12 @@ def n_pieces(self): return len(self.polynomials) def loadcsv(self, filename): - data = np.loadtxt(filename, delimiter=",", skiprows=1, usecols=range(33)) + data = np.loadtxt(filename, delimiter=',', skiprows=1, usecols=range(33)) self.polynomials = [Polynomial4D(row[0], row[1:9], row[9:17], row[17:25], row[25:33]) for row in data] self.duration = np.sum(data[:, 0]) - def eval(self, t): + def eval(self, t): # noqa: A003 assert t >= 0 assert t <= self.duration From a0a5d533c47326f018440002b376b3db6659aa94 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Thu, 19 Oct 2023 22:18:16 +0200 Subject: [PATCH 007/162] disable pep257 checks that are not applicable for us --- crazyflie_py/crazyflie_py/crazyflie.py | 20 +++++--------------- crazyflie_py/crazyflie_py/util.py | 8 ++------ crazyflie_py/test/test_pep257.py | 2 +- docs2/howto.rst | 13 ++++++++++++- 4 files changed, 20 insertions(+), 23 deletions(-) diff --git a/crazyflie_py/crazyflie_py/crazyflie.py b/crazyflie_py/crazyflie_py/crazyflie.py index 03055a8bc..025cac736 100644 --- a/crazyflie_py/crazyflie_py/crazyflie.py +++ b/crazyflie_py/crazyflie_py/crazyflie.py @@ -45,8 +45,7 @@ class TimeHelper: When running on real hardware, this class uses ROS time functions. The simulation equivalent does not depend on ROS. - Attributes - ---------- + Attributes: visualizer: No-op object conforming to the Visualizer API used in simulation scripts. Maintains the property that scripts should not know/care if they are running in simulation or not. @@ -104,10 +103,9 @@ def __init__(self, node, cfname, paramTypeDict): Construct Crazyflie. Args: - ---- - node: ROS node reference - cfname (string): Name of the robot names[ace] - paramTypeDict: dictionary of the parameter types + node: ROS node reference. + cfname (string): Name of the robot names[ace]. + paramTypeDict: dictionary of the parameter types. """ prefix = '/' + cfname @@ -345,7 +343,6 @@ def goTo(self, goal, yaw, duration, relative=False, groupMask=0): controller to become unstable. Args: - ---- goal (iterable of 3 floats): The goal position. Meters. yaw (float): The goal yaw angle (heading). Radians. duration (float): How long until the goal is reached. Seconds. @@ -444,7 +441,6 @@ def notifySetpointsStop(self, remainValidMillisecs=100, groupMask=0): streaming setpoint modes. Args: - ---- remainValidMillisecs (int): Number of milliseconds that the last streaming setpoint should be followed before reverting to the onboard-determined behavior. May be longer e.g. if one radio @@ -503,7 +499,6 @@ def setParam(self, name, value): See :meth:`getParam()` docs for overview of the parameter system. Args: - ---- name (str): The parameter's name. value (Any): The parameter's value. @@ -547,7 +542,6 @@ def cmdFullState(self, pos, vel, acc, yaw, omega): :meth:`goTo()` after a streaming setpoint has been sent. Args: - ---- pos (array-like of float[3]): Position. Meters. vel (array-like of float[3]): Velocity. Meters / second. acc (array-like of float[3]): Acceleration. Meters / second^2. @@ -702,8 +696,7 @@ class CrazyflieServer(rclpy.node.Node): Also is the container for the individual :obj:`Crazyflie` objects. - Attributes - ---------- + Attributes: crazyfiles (List[Crazyflie]): List of one Crazyflie object per robot, as determined by the crazyflies.yaml config file. crazyfliesById (Dict[int, Crazyflie]): Index to the same Crazyflie @@ -873,7 +866,6 @@ def goTo(self, goal, yaw, duration, groupMask=0): See docstring of :meth:`Crazyflie.goTo()` for additional details. Args: - ---- goal (iterable of 3 floats): The goal offset. Meters. yaw (float): The goal yaw angle (heading). Radians. duration (float): How long until the goal is reached. Seconds. @@ -898,7 +890,6 @@ def startTrajectory(self, trajectoryId, Asynchronous command; returns immediately. Args: - ---- trajectoryId (int): ID number as given to :meth:`Crazyflie.uploadTrajectory()`. timescale (float): Scales the trajectory duration by this factor. For example if timescale == 2.0, the trajectory will take twice @@ -946,7 +937,6 @@ def cmdFullState(self, pos, vel, acc, yaw, omega): :meth:`goTo()` after a streaming setpoint has been sent. Args: - ---- pos (array-like of float[3]): Position. Meters. vel (array-like of float[3]): Velocity. Meters / second. acc (array-like of float[3]): Acceleration. Meters / second^2. diff --git a/crazyflie_py/crazyflie_py/util.py b/crazyflie_py/crazyflie_py/util.py index 602862b5b..2c201ff9c 100644 --- a/crazyflie_py/crazyflie_py/util.py +++ b/crazyflie_py/crazyflie_py/util.py @@ -10,12 +10,10 @@ def check_ellipsoid_collisions(positions, radii): Check for collisions between a set of ellipsoids at given positions. Args: - ---- positions (array float[n, 3]): The ellipsoid centers. radii (array float[3]): The radii of the axis-aligned ellipsoids. - Returns - ------- + Returns: colliding (array bool[n]): True at index i if the i'th ellipsoid intersects any of the other ellipsoids. @@ -38,13 +36,11 @@ def poisson_disk_sample(n, dim, mindist): TODO(jpreiss): find/implement a library with a fast algorithm. Args: - ---- n (int): Number of points. dim (int): Dimensionality of points. mindist (float): Minimum Euclidean distance between any two points. - Returns - ------- + Returns: pts (array float[n, dim]): The sampled points. """ diff --git a/crazyflie_py/test/test_pep257.py b/crazyflie_py/test/test_pep257.py index b234a3840..bd90b5f8e 100644 --- a/crazyflie_py/test/test_pep257.py +++ b/crazyflie_py/test/test_pep257.py @@ -19,5 +19,5 @@ @pytest.mark.linter @pytest.mark.pep257 def test_pep257(): - rc = main(argv=['.', 'test']) + rc = main(argv=['.', 'test', '--add-ignore', 'D406', 'D407', 'D417']) assert rc == 0, 'Found code style errors / warnings' diff --git a/docs2/howto.rst b/docs2/howto.rst index abdeecc1c..7c214d872 100644 --- a/docs2/howto.rst +++ b/docs2/howto.rst @@ -90,4 +90,15 @@ To close the logblocks again, run: .. code-block:: bash ros2 service call /cf2/remove_logging crazyflie_interfaces/srv/RemoveLogging "{topic_name: 'topic_test'}" - ros2 service call /cf2/remove_logging crazyflie_interfaces/srv/RemoveLogging "{topic_name: 'pose'}" \ No newline at end of file + ros2 service call /cf2/remove_logging crazyflie_interfaces/srv/RemoveLogging "{topic_name: 'pose'}" + +Run Tests Locally +----------------- + +This requires some updated pip packages for testing, see https://docs.ros.org/en/humble/Installation/Alternatives/Ubuntu-Development-Setup.html, otherwise the reported failures will be inconsistent with CI. + +Then execute: + +``` +colcon test --event-handlers=console_cohesion+ --return-code-on-test-failure --packages-select crazyflie_py +``` From a3d5feaaad1142f41a64f2a9d134aac6ec19cd30 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Fri, 20 Oct 2023 21:05:59 +0200 Subject: [PATCH 008/162] crazyflie_sim: fix flake8 and pep256 issues --- crazyflie_sim/CMakeLists.txt | 16 ++ crazyflie_sim/crazyflie_sim/backend/none.py | 8 +- crazyflie_sim/crazyflie_sim/backend/np.py | 53 ++-- .../crazyflie_sim/crazyflie_server.py | 242 ++++++++++-------- crazyflie_sim/crazyflie_sim/crazyflie_sil.py | 103 +++++--- crazyflie_sim/crazyflie_sim/sim_data_types.py | 25 +- .../crazyflie_sim/visualization/blender.py | 146 ++++++----- .../crazyflie_sim/visualization/pdf.py | 96 +++---- .../visualization/record_states.py | 82 +++--- .../crazyflie_sim/visualization/rviz.py | 10 +- crazyflie_sim/package.xml | 1 + crazyflie_sim/test/test_copyright.py | 23 -- 12 files changed, 442 insertions(+), 363 deletions(-) delete mode 100644 crazyflie_sim/test/test_copyright.py diff --git a/crazyflie_sim/CMakeLists.txt b/crazyflie_sim/CMakeLists.txt index 61965fed1..e144c2c35 100644 --- a/crazyflie_sim/CMakeLists.txt +++ b/crazyflie_sim/CMakeLists.txt @@ -16,4 +16,20 @@ ament_python_install_package(${PROJECT_NAME} SCRIPTS_DESTINATION lib/${PROJECT_N # DESTINATION share/${PROJECT_NAME}/ # ) +if(BUILD_TESTING) + find_package(ament_cmake_pytest REQUIRED) + set(_pytest_tests + test/test_flake8.py + test/test_pep257.py + ) + foreach(_test_path ${_pytest_tests}) + get_filename_component(_test_name ${_test_path} NAME_WE) + ament_add_pytest_test(${_test_name} ${_test_path} + APPEND_ENV PYTHONPATH=${CMAKE_CURRENT_BINARY_DIR} + TIMEOUT 60 + WORKING_DIRECTORY ${CMAKE_SOURCE_DIR} + ) + endforeach() +endif() + ament_package() diff --git a/crazyflie_sim/crazyflie_sim/backend/none.py b/crazyflie_sim/crazyflie_sim/backend/none.py index c4bcf08a1..48b4c4bda 100644 --- a/crazyflie_sim/crazyflie_sim/backend/none.py +++ b/crazyflie_sim/crazyflie_sim/backend/none.py @@ -1,13 +1,14 @@ from __future__ import annotations from rclpy.node import Node -from rosgraph_msgs.msg import Clock from rclpy.time import Time -from ..sim_data_types import State, Action +from rosgraph_msgs.msg import Clock + +from ..sim_data_types import Action, State class Backend: - """Tracks the desired state perfectly (no physics simulation)""" + """Tracks the desired state perfectly (no physics simulation).""" def __init__(self, node: Node, names: list[str], states: list[State]): self.node = node @@ -33,4 +34,3 @@ def step(self, states_desired: list[State], actions: list[Action]) -> list[State def shutdown(self): pass - diff --git a/crazyflie_sim/crazyflie_sim/backend/np.py b/crazyflie_sim/crazyflie_sim/backend/np.py index eb2e43eb9..26e0c4cc3 100644 --- a/crazyflie_sim/crazyflie_sim/backend/np.py +++ b/crazyflie_sim/crazyflie_sim/backend/np.py @@ -1,16 +1,16 @@ from __future__ import annotations +import numpy as np from rclpy.node import Node -from rosgraph_msgs.msg import Clock from rclpy.time import Time -from ..sim_data_types import State, Action +from rosgraph_msgs.msg import Clock +import rowan +from ..sim_data_types import Action, State -import numpy as np -import rowan class Backend: - """Backend that uses newton-euler rigid-body dynamics implemented in numpy""" + """Backend that uses newton-euler rigid-body dynamics implemented in numpy.""" def __init__(self, node: Node, names: list[str], states: list[State]): self.node = node @@ -50,11 +50,11 @@ def shutdown(self): class Quadrotor: - """Basic rigid body quadrotor model (no drag) using numpy and rowan""" + """Basic rigid body quadrotor model (no drag) using numpy and rowan.""" def __init__(self, state): # parameters (Crazyflie 2.0 quadrotor) - self.mass = 0.034 # kg + self.mass = 0.034 # kg # self.J = np.array([ # [16.56,0.83,0.71], # [0.83,16.66,1.8], @@ -63,21 +63,21 @@ def __init__(self, state): self.J = np.array([16.571710e-6, 16.655602e-6, 29.261652e-6]) # Note: we assume here that our control is forces - arm_length = 0.046 # m + arm_length = 0.046 # m arm = 0.707106781 * arm_length - t2t = 0.006 # thrust-to-torque ratio + t2t = 0.006 # thrust-to-torque ratio self.B0 = np.array([ [1, 1, 1, 1], [-arm, -arm, arm, arm], [-arm, arm, arm, -arm], [-t2t, t2t, -t2t, t2t] ]) - self.g = 9.81 # not signed + self.g = 9.81 # not signed - if self.J.shape == (3,3): - self.inv_J = np.linalg.pinv(self.J) # full matrix -> pseudo inverse + if self.J.shape == (3, 3): + self.inv_J = np.linalg.pinv(self.J) # full matrix -> pseudo inverse else: - self.inv_J = 1 / self.J # diagonal matrix -> division + self.inv_J = 1 / self.J # diagonal matrix -> division self.state = state @@ -95,23 +95,28 @@ def rpm_to_force(rpm): # compute next state eta = np.dot(self.B0, force) - f_u = np.array([0,0,eta[0]]) - tau_u = np.array([eta[1],eta[2],eta[3]]) + f_u = np.array([0, 0, eta[0]]) + tau_u = np.array([eta[1], eta[2], eta[3]]) - # dynamics - # dot{p} = v + # dynamics + # dot{p} = v pos_next = self.state.pos + self.state.vel * dt - # mv = mg + R f_u - vel_next = self.state.vel + (np.array([0,0,-self.g]) + rowan.rotate(self.state.quat,f_u) / self.mass) * dt + # mv = mg + R f_u + vel_next = self.state.vel + ( + np.array([0, 0, -self.g]) + + rowan.rotate(self.state.quat, f_u) / self.mass) * dt # dot{R} = R S(w) # to integrate the dynamics, see # https://www.ashwinnarayan.com/post/how-to-integrate-quaternions/, and # https://arxiv.org/pdf/1604.08139.pdf - q_next = rowan.normalize(rowan.calculus.integrate(self.state.quat, self.state.omega, dt)) + q_next = rowan.normalize( + rowan.calculus.integrate( + self.state.quat, self.state.omega, dt)) - # mJ = Jw x w + tau_u - omega_next = self.state.omega + (self.inv_J * (np.cross(self.J * self.state.omega, self.state.omega) + tau_u)) * dt + # mJ = Jw x w + tau_u + omega_next = self.state.omega + ( + self.inv_J * (np.cross(self.J * self.state.omega, self.state.omega) + tau_u)) * dt self.state.pos = pos_next self.state.vel = vel_next @@ -121,5 +126,5 @@ def rpm_to_force(rpm): # if we fall below the ground, set velocities to 0 if self.state.pos[2] < 0: self.state.pos[2] = 0 - self.state.vel = [0,0,0] - self.state.omega = [0,0,0] + self.state.vel = [0, 0, 0] + self.state.omega = [0, 0, 0] diff --git a/crazyflie_sim/crazyflie_sim/crazyflie_server.py b/crazyflie_sim/crazyflie_sim/crazyflie_server.py index 0ba75f78f..8c3364e83 100755 --- a/crazyflie_sim/crazyflie_sim/crazyflie_server.py +++ b/crazyflie_sim/crazyflie_sim/crazyflie_server.py @@ -3,79 +3,84 @@ """ A crazyflie server for simulation. - 2022 - Wolfgang Hönig (TU Berlin) """ +from functools import partial +import importlib + +from crazyflie_interfaces.msg import FullState, Hover +from crazyflie_interfaces.srv import GoTo, Land, Takeoff +from crazyflie_interfaces.srv import NotifySetpointsStop, StartTrajectory, UploadTrajectory +from geometry_msgs.msg import Twist import rclpy from rclpy.node import Node import rowan -import importlib - -from crazyflie_interfaces.srv import Takeoff, Land, GoTo -from crazyflie_interfaces.srv import UploadTrajectory, StartTrajectory, NotifySetpointsStop -from crazyflie_interfaces.msg import Hover, FullState - from std_srvs.srv import Empty -from geometry_msgs.msg import Twist -from functools import partial # import BackendRviz from .backend_rviz # from .backend import * # from .backend.none import BackendNone from .crazyflie_sil import CrazyflieSIL, TrajectoryPolynomialPiece -from .sim_data_types import State, Action +from .sim_data_types import State class CrazyflieServer(Node): + def __init__(self): super().__init__( - "crazyflie_server", + 'crazyflie_server', allow_undeclared_parameters=True, automatically_declare_parameters_from_overrides=True, ) # Turn ROS parameters into a dictionary self._ros_parameters = self._param_to_dict(self._parameters) - self.cfs = dict() - - self.world_tf_name = "world" + self.cfs = {} + + self.world_tf_name = 'world' try: - self.world_tf_name = self._ros_parameters["world_tf_name"] + self.world_tf_name = self._ros_parameters['world_tf_name'] except KeyError: pass - robot_data = self._ros_parameters["robots"] + robot_data = self._ros_parameters['robots'] # Parse robots names = [] initial_states = [] for cfname in robot_data: - if robot_data[cfname]["enabled"]: - type_cf = robot_data[cfname]["type"] + if robot_data[cfname]['enabled']: + type_cf = robot_data[cfname]['type'] # do not include virtual objects - connection = self._ros_parameters['robot_types'][type_cf].get("connection", "crazyflie") - if connection == "crazyflie": + connection = self._ros_parameters['robot_types'][type_cf].get( + 'connection', 'crazyflie') + if connection == 'crazyflie': names.append(cfname) - pos = robot_data[cfname]["initial_position"] + pos = robot_data[cfname]['initial_position'] initial_states.append(State(pos)) # initialize backend by dynamically loading the module - backend_name = self._ros_parameters["sim"]["backend"] - module = importlib.import_module(".backend." + backend_name, package="crazyflie_sim") - class_ = getattr(module, "Backend") + backend_name = self._ros_parameters['sim']['backend'] + module = importlib.import_module('.backend.' + backend_name, package='crazyflie_sim') + class_ = getattr(module, 'Backend') self.backend = class_(self, names, initial_states) # initialize visualizations by dynamically loading the modules self.visualizations = [] - for vis_key in self._ros_parameters["sim"]["visualizations"]: - if self._ros_parameters["sim"]["visualizations"][vis_key]["enabled"]: - module = importlib.import_module(".visualization." + str(vis_key), package="crazyflie_sim") - class_ = getattr(module, "Visualization") - vis = class_(self, self._ros_parameters["sim"]["visualizations"][vis_key], names, initial_states) + for vis_key in self._ros_parameters['sim']['visualizations']: + if self._ros_parameters['sim']['visualizations'][vis_key]['enabled']: + module = importlib.import_module('.visualization.' + + str(vis_key), + package='crazyflie_sim') + class_ = getattr(module, 'Visualization') + vis = class_(self, + self._ros_parameters['sim']['visualizations'][vis_key], + names, + initial_states) self.visualizations.append(vis) - controller_name = backend_name = self._ros_parameters["sim"]["controller"] + controller_name = backend_name = self._ros_parameters['sim']['controller'] # create robot SIL objects for name, initial_state in zip(names, initial_states): @@ -86,51 +91,72 @@ def __init__(self): self.backend.time) # Create services for the entire swarm and each individual crazyflie - self.create_service(Empty, "all/emergency", self._emergency_callback) - self.create_service(Takeoff, "all/takeoff", self._takeoff_callback) - self.create_service(Land, "all/land", self._land_callback) - self.create_service(GoTo, "all/go_to", self._go_to_callback) - self.create_service(StartTrajectory, "all/start_trajectory", self._start_trajectory_callback) + self.create_service(Empty, 'all/emergency', self._emergency_callback) + self.create_service(Takeoff, 'all/takeoff', self._takeoff_callback) + self.create_service(Land, 'all/land', self._land_callback) + self.create_service(GoTo, 'all/go_to', self._go_to_callback) + self.create_service(StartTrajectory, + 'all/start_trajectory', + self._start_trajectory_callback) for name, _ in self.cfs.items(): self.create_service( - Empty, name + - "/emergency", partial(self._emergency_callback, name=name) + Empty, + name + '/emergency', + partial(self._emergency_callback, name=name) ) self.create_service( - Takeoff, name + - "/takeoff", partial(self._takeoff_callback, name=name) + Takeoff, + name + '/takeoff', + partial(self._takeoff_callback, name=name) ) self.create_service( - Land, name + "/land", partial(self._land_callback, name=name) + Land, + name + '/land', + partial(self._land_callback, name=name) ) self.create_service( - GoTo, name + "/go_to", partial(self._go_to_callback, name=name) + GoTo, + name + '/go_to', + partial(self._go_to_callback, name=name) ) self.create_service( - StartTrajectory, name + "/start_trajectory", partial(self._start_trajectory_callback, name=name) + StartTrajectory, + name + '/start_trajectory', + partial(self._start_trajectory_callback, name=name) ) self.create_service( - UploadTrajectory, name + "/upload_trajectory", partial(self._upload_trajectory_callback, name=name) + UploadTrajectory, + name + '/upload_trajectory', + partial(self._upload_trajectory_callback, name=name) ) self.create_service( - NotifySetpointsStop, name + "/notify_setpoints_stop", partial(self._notify_setpoints_stop_callback, name=name) + NotifySetpointsStop, + name + '/notify_setpoints_stop', + partial(self._notify_setpoints_stop_callback, name=name) ) self.create_subscription( - Twist, name + - "/cmd_vel_legacy", partial(self._cmd_vel_legacy_changed, name=name), 10 + Twist, + name + '/cmd_vel_legacy', + partial(self._cmd_vel_legacy_changed, name=name), + 10 ) self.create_subscription( - Hover, name + - "/cmd_hover", partial(self._cmd_hover_changed, name=name), 10 + Hover, + name + '/cmd_hover', + partial(self._cmd_hover_changed, name=name), + 10 ) self.create_subscription( - FullState, name + - "/cmd_full_state", partial(self._cmd_full_state_changed, name=name), 10 + FullState, + name + '/cmd_full_state', + partial(self._cmd_full_state_changed, name=name), + 10 ) # step as fast as possible - max_dt = 0.0 if "max_dt" not in self._ros_parameters["sim"] else self._ros_parameters["sim"]["max_dt"] + max_dt = 0.0 if 'max_dt' not in self._ros_parameters['sim'] \ + else self._ros_parameters['sim']['max_dt'] self.timer = self.create_timer(max_dt, self._timer_callback) self.is_shutdown = False @@ -147,7 +173,7 @@ def _timer_callback(self): states_desired = [cf.getSetpoint() for _, cf in self.cfs.items()] # execute the control loop - actions = [cf.executeController() for _, cf in self.cfs.items()] + actions = [cf.executeController() for _, cf in self.cfs.items()] # execute the physics simulator states_next = self.backend.step(states_desired, actions) @@ -160,9 +186,7 @@ def _timer_callback(self): vis.step(self.backend.time(), states_next, states_desired, actions) def _param_to_dict(self, param_ros): - """ - Turn ROS 2 parameters from the node into a dict - """ + """Turn ROS 2 parameters from the node into a dict.""" tree = {} for item in param_ros: t = tree @@ -173,58 +197,48 @@ def _param_to_dict(self, param_ros): t = t.setdefault(part, {}) return tree - def _emergency_callback(self, request, response, name="all"): - self.get_logger().info("emergency not yet implemented") + def _emergency_callback(self, request, response, name='all'): + self.get_logger().info('emergency not yet implemented') return response - def _takeoff_callback(self, request, response, name="all"): - """ - Service callback to take the crazyflie land to - a certain height in high level commander - """ - + def _takeoff_callback(self, request, response, name='all'): + """Service callback to takeoff the crazyflie.""" duration = float(request.duration.sec) + \ float(request.duration.nanosec / 1e9) self.get_logger().info( - f"takeoff(height={request.height} m," - + f"duration={duration} s," - + f"group_mask={request.group_mask}) {name}" + f'takeoff(height={request.height} m,' + + f'duration={duration} s,' + + f'group_mask={request.group_mask}) {name}' ) - cfs = self.cfs if name == "all" else {name: self.cfs[name]} + cfs = self.cfs if name == 'all' else {name: self.cfs[name]} for _, cf in cfs.items(): cf.takeoff(request.height, duration, request.group_mask) return response - def _land_callback(self, request, response, name="all"): - """ - Service callback to make the crazyflie land to - a certain height in high level commander - """ + def _land_callback(self, request, response, name='all'): + """Service callback to land the crazyflie.""" duration = float(request.duration.sec) + \ float(request.duration.nanosec / 1e9) self.get_logger().info( - f"land(height={request.height} m," - + f"duration={duration} s," - + f"group_mask={request.group_mask})" + f'land(height={request.height} m,' + + f'duration={duration} s,' + + f'group_mask={request.group_mask})' ) - cfs = self.cfs if name == "all" else {name: self.cfs[name]} + cfs = self.cfs if name == 'all' else {name: self.cfs[name]} for _, cf in cfs.items(): cf.land(request.height, duration, request.group_mask) return response - def _go_to_callback(self, request, response, name="all"): - """ - Service callback to have the crazyflie go to - a certain position in high level commander - """ + def _go_to_callback(self, request, response, name='all'): + """Service callback to have the crazyflie go to a position.""" duration = float(request.duration.sec) + \ float(request.duration.nanosec / 1e9) self.get_logger().info( - "go_to(position=%f,%f,%f m, yaw=%f rad, duration=%f s, relative=%d, group_mask=%d)" + 'go_to(position=%f,%f,%f m, yaw=%f rad, duration=%f s, relative=%d, group_mask=%d)' % ( request.goal.x, request.goal.y, @@ -235,21 +249,21 @@ def _go_to_callback(self, request, response, name="all"): request.group_mask, ) ) - cfs = self.cfs if name == "all" else {name: self.cfs[name]} + cfs = self.cfs if name == 'all' else {name: self.cfs[name]} for _, cf in cfs.items(): - cf.goTo([request.goal.x, request.goal.y, request.goal.z], + cf.goTo([request.goal.x, request.goal.y, request.goal.z], request.yaw, duration, request.relative, request.group_mask) - + return response - def _notify_setpoints_stop_callback(self, request, response, name="all"): - self.get_logger().info("Notify setpoint stop not yet implemented") + def _notify_setpoints_stop_callback(self, request, response, name='all'): + self.get_logger().info('Notify setpoint stop not yet implemented') return response - def _upload_trajectory_callback(self, request, response, name="all"): - self.get_logger().info("Upload trajectory(id=%d)" % (request.trajectory_id)) + def _upload_trajectory_callback(self, request, response, name='all'): + self.get_logger().info('Upload trajectory(id=%d)' % (request.trajectory_id)) - cfs = self.cfs if name == "all" else {name: self.cfs[name]} + cfs = self.cfs if name == 'all' else {name: self.cfs[name]} for _, cf in cfs.items(): pieces = [] for piece in request.pieces: @@ -259,14 +273,19 @@ def _upload_trajectory_callback(self, request, response, name="all"): poly_yaw = piece.poly_yaw duration = float(piece.duration.sec) + \ float(piece.duration.nanosec / 1e9) - pieces.append(TrajectoryPolynomialPiece(poly_x, poly_y, poly_z, poly_yaw, duration)) + pieces.append(TrajectoryPolynomialPiece( + poly_x, + poly_y, + poly_z, + poly_yaw, + duration)) cf.uploadTrajectory(request.trajectory_id, request.piece_offset, pieces) return response - - def _start_trajectory_callback(self, request, response, name="all"): + + def _start_trajectory_callback(self, request, response, name='all'): self.get_logger().info( - "start_trajectory(id=%d, timescale=%f, reverse=%d, relative=%d, group_mask=%d)" + 'start_trajectory(id=%d, timescale=%f, reverse=%d, relative=%d, group_mask=%d)' % ( request.trajectory_id, request.timescale, @@ -275,29 +294,38 @@ def _start_trajectory_callback(self, request, response, name="all"): request.group_mask, ) ) - cfs = self.cfs if name == "all" else {name: self.cfs[name]} + cfs = self.cfs if name == 'all' else {name: self.cfs[name]} for _, cf in cfs.items(): - cf.startTrajectory(request.trajectory_id, request.timescale, request.reversed, request.relative, request.group_mask) + cf.startTrajectory( + request.trajectory_id, + request.timescale, + request.reversed, + request.relative, + request.group_mask) return response - def _cmd_vel_legacy_changed(self, msg, name=""): + def _cmd_vel_legacy_changed(self, msg, name=''): """ - Topic update callback to control the attitude and thrust - of the crazyflie with teleop - """ - self.get_logger().info("cmd_vel_legacy not yet implemented") + Topic update callback. + Controls the attitude and thrust of the crazyflie with teleop. + """ + self.get_logger().info('cmd_vel_legacy not yet implemented') - def _cmd_hover_changed(self, msg, name=""): + def _cmd_hover_changed(self, msg, name=''): """ - Topic update callback to control the hover command - of the crazyflie from the velocity multiplexer (vel_mux) + Topic update callback for hover command. + + Used from the velocity multiplexer (vel_mux). """ - self.get_logger().info("cmd_hover not yet implemented") + self.get_logger().info('cmd_hover not yet implemented') def _cmd_full_state_changed(self, msg, name): - q = [msg.pose.orientation.w, msg.pose.orientation.x, msg.pose.orientation.y, msg.pose.orientation.z] + q = [msg.pose.orientation.w, + msg.pose.orientation.x, + msg.pose.orientation.y, + msg.pose.orientation.z] rpy = rowan.to_euler(q) self.cfs[name].cmdFullState( @@ -323,5 +351,5 @@ def main(args=None): crazyflie_server.destroy_node() -if __name__ == "__main__": +if __name__ == '__main__': main() diff --git a/crazyflie_sim/crazyflie_sim/crazyflie_sil.py b/crazyflie_sim/crazyflie_sim/crazyflie_sil.py index a4f9fe66b..cf904d746 100644 --- a/crazyflie_sim/crazyflie_sim/crazyflie_sil.py +++ b/crazyflie_sim/crazyflie_sim/crazyflie_sil.py @@ -1,21 +1,21 @@ #!/usr/bin/env python3 """ -Crazyflie Software-In-The-Loop Wrapper that uses the firmware Python bindings - +Crazyflie Software-In-The-Loop Wrapper that uses the firmware Python bindings. 2022 - Wolfgang Hönig (TU Berlin) """ from __future__ import annotations -import numpy as np - import cffirmware as firm +import numpy as np import rowan + from . import sim_data_types class TrajectoryPolynomialPiece: + def __init__(self, poly_x, poly_y, poly_z, poly_yaw, duration): self.poly_x = poly_x self.poly_y = poly_y @@ -23,6 +23,7 @@ def __init__(self, poly_x, poly_y, poly_z, poly_yaw, duration): self.poly_yaw = poly_yaw self.duration = duration + def copy_svec(v): return firm.mkvec(v.x, v.y, v.z) @@ -36,9 +37,7 @@ class CrazyflieSIL: MODE_LOW_POSITION = 3 MODE_LOW_VELOCITY = 4 - def __init__(self, name, initialPosition, controller_name, time_func): - # Core. self.name = name self.groupMask = 0 @@ -49,7 +48,7 @@ def __init__(self, name, initialPosition, controller_name, time_func): self.mode = CrazyflieSIL.MODE_IDLE self.planner = firm.planner() firm.plan_init(self.planner) - self.trajectories = dict() + self.trajectories = {} # previous state for HL commander self.cmdHl_pos = firm.mkvec(*initialPosition) @@ -68,7 +67,7 @@ def __init__(self, name, initialPosition, controller_name, time_func): self.state.velocity.y = 0 self.state.velocity.z = 0 self.state.attitude.roll = 0 - self.state.attitude.pitch = -0 # WARNING: this is in the legacy coordinate system + self.state.attitude.pitch = -0 # WARNING: this is in the legacy coordinate system self.state.attitude.yaw = 0 self.sensors = firm.sensorData_t() @@ -84,54 +83,65 @@ def __init__(self, name, initialPosition, controller_name, time_func): self.controller_name = controller_name # set up controller - if controller_name == "none": + if controller_name == 'none': self.controller = None - elif controller_name == "pid": + elif controller_name == 'pid': firm.controllerPidInit() self.controller = firm.controllerPid - elif controller_name == "mellinger": + elif controller_name == 'mellinger': self.mellinger_control = firm.controllerMellinger_t() firm.controllerMellingerInit(self.mellinger_control) self.controller = firm.controllerMellinger - elif controller_name == "brescianini": + elif controller_name == 'brescianini': firm.controllerBrescianiniInit() self.controller = firm.controllerBrescianini else: - raise ValueError("Unknown controller {}".format(controller_name)) + raise ValueError('Unknown controller {}'.format(controller_name)) def setGroupMask(self, groupMask): self.groupMask = groupMask - def takeoff(self, targetHeight, duration, groupMask = 0): + def takeoff(self, targetHeight, duration, groupMask=0): if self._isGroup(groupMask): self.mode = CrazyflieSIL.MODE_HIGH_POLY targetYaw = 0.0 - firm.plan_takeoff(self.planner, + firm.plan_takeoff( + self.planner, self.cmdHl_pos, - self.cmdHl_yaw, targetHeight, targetYaw, duration, self.time_func()) + self.cmdHl_yaw, + targetHeight, targetYaw, duration, self.time_func()) - def land(self, targetHeight, duration, groupMask = 0): + def land(self, targetHeight, duration, groupMask=0): if self._isGroup(groupMask): self.mode = CrazyflieSIL.MODE_HIGH_POLY targetYaw = 0.0 - firm.plan_land(self.planner, + firm.plan_land( + self.planner, self.cmdHl_pos, - self.cmdHl_yaw, targetHeight, targetYaw, duration, self.time_func()) + self.cmdHl_yaw, + targetHeight, targetYaw, duration, self.time_func()) # def stop(self, groupMask = 0): # if self._isGroup(groupMask): # self.mode = CrazyflieSIL.MODE_IDLE # firm.plan_stop(self.planner) - def goTo(self, goal, yaw, duration, relative = False, groupMask = 0): + def goTo(self, goal, yaw, duration, relative=False, groupMask=0): if self._isGroup(groupMask): if self.mode != CrazyflieSIL.MODE_HIGH_POLY: # We need to update to the latest firmware that has go_to_from. - raise ValueError("goTo from low-level modes not yet supported.") + raise ValueError('goTo from low-level modes not yet supported.') self.mode = CrazyflieSIL.MODE_HIGH_POLY - firm.plan_go_to(self.planner, relative, firm.mkvec(*goal), yaw, duration, self.time_func()) - - def uploadTrajectory(self, trajectoryId: int, pieceOffset: int, pieces: list[TrajectoryPolynomialPiece]): + firm.plan_go_to( + self.planner, + relative, + firm.mkvec(*goal), + yaw, duration, self.time_func()) + + def uploadTrajectory(self, + trajectoryId: int, + pieceOffset: int, + pieces: list[TrajectoryPolynomialPiece]): traj = firm.piecewise_traj() traj.t_begin = 0 traj.timescale = 1.0 @@ -148,7 +158,12 @@ def uploadTrajectory(self, trajectoryId: int, pieceOffset: int, pieces: list[Tra firm.poly4d_set(fwpiece, 3, coef, piece.poly_yaw[coef]) self.trajectories[trajectoryId] = traj - def startTrajectory(self, trajectoryId: int, timescale: float = 1.0, reverse: bool = False, relative: bool = True, groupMask: int = 0): + def startTrajectory(self, + trajectoryId: int, + timescale: float = 1.0, + reverse: bool = False, + relative: bool = True, + groupMask: int = 0): if self._isGroup(groupMask): self.mode = CrazyflieSIL.MODE_HIGH_POLY traj = self.trajectories[trajectoryId] @@ -185,7 +200,7 @@ def cmdFullState(self, pos, vel, acc, yaw, omega): self.setpoint.acceleration.x = acc[0] self.setpoint.acceleration.y = acc[1] self.setpoint.acceleration.z = acc[2] - + self.cmdHl_pos = copy_svec(self.setpoint.position) self.cmdHl_vel = copy_svec(self.setpoint.velocity) self.cmdHl_yaw = yaw @@ -282,18 +297,24 @@ def executeController(self): return None if self.mode != CrazyflieSIL.MODE_HIGH_POLY: - return sim_data_types.Action([0,0,0,0]) + return sim_data_types.Action([0, 0, 0, 0]) time_in_seconds = self.time_func() # ticks is essentially the time in milliseconds as an integer tick = int(time_in_seconds * 1000) - if self.controller_name != "mellinger": + if self.controller_name != 'mellinger': self.controller(self.control, self.setpoint, self.sensors, self.state, tick) else: - self.controller(self.mellinger_control, self.control, self.setpoint, self.sensors, self.state, tick) + self.controller( + self.mellinger_control, + self.control, + self.setpoint, + self.sensors, + self.state, + tick) return self._fwcontrol_to_sim_data_types_action() - # "private" methods + # 'private' methods def _isGroup(self, groupMask): return groupMask == 0 or (self.groupMask & groupMask) > 0 @@ -313,23 +334,29 @@ def pwm_to_rpm(pwm): def pwm_to_force(pwm): # polyfit using data and scripts from https://github.com/IMRCLab/crazyflie-system-id - p = [ 1.71479058e-09, 8.80284482e-05, -2.21152097e-01] + p = [1.71479058e-09, 8.80284482e-05, -2.21152097e-01] force_in_grams = np.polyval(p, pwm) force_in_newton = force_in_grams * 9.81 / 1000.0 return np.maximum(force_in_newton, 0) - return sim_data_types.Action([pwm_to_rpm(self.motors_thrust_pwm.motors.m1), - pwm_to_rpm(self.motors_thrust_pwm.motors.m2), - pwm_to_rpm(self.motors_thrust_pwm.motors.m3), - pwm_to_rpm(self.motors_thrust_pwm.motors.m4)]) - + return sim_data_types.Action( + [pwm_to_rpm(self.motors_thrust_pwm.motors.m1), + pwm_to_rpm(self.motors_thrust_pwm.motors.m2), + pwm_to_rpm(self.motors_thrust_pwm.motors.m3), + pwm_to_rpm(self.motors_thrust_pwm.motors.m4)]) @staticmethod def _fwsetpoint_to_sim_data_types_state(fwsetpoint): pos = np.array([fwsetpoint.position.x, fwsetpoint.position.y, fwsetpoint.position.z]) vel = np.array([fwsetpoint.velocity.x, fwsetpoint.velocity.y, fwsetpoint.velocity.z]) - acc = np.array([fwsetpoint.acceleration.x, fwsetpoint.acceleration.y, fwsetpoint.acceleration.z]) - omega = np.radians(np.array([fwsetpoint.attitudeRate.roll, fwsetpoint.attitudeRate.pitch, fwsetpoint.attitudeRate.yaw])) + acc = np.array([ + fwsetpoint.acceleration.x, + fwsetpoint.acceleration.y, + fwsetpoint.acceleration.z]) + omega = np.radians(np.array([ + fwsetpoint.attitudeRate.roll, + fwsetpoint.attitudeRate.pitch, + fwsetpoint.attitudeRate.yaw])) if fwsetpoint.mode.quat == firm.modeDisable: # compute rotation based on differential flatness diff --git a/crazyflie_sim/crazyflie_sim/sim_data_types.py b/crazyflie_sim/crazyflie_sim/sim_data_types.py index c5c484f49..8c1394001 100644 --- a/crazyflie_sim/crazyflie_sim/sim_data_types.py +++ b/crazyflie_sim/crazyflie_sim/sim_data_types.py @@ -1,8 +1,11 @@ import numpy as np + class State: - """Class that stores the state of a UAV as used in the simulator interface""" - def __init__(self, pos = np.zeros(3), vel = np.zeros(3), quat = np.array([1,0,0,0]), omega = np.zeros(3)): + """Class that stores the state of a UAV as used in the simulator interface.""" + + def __init__(self, pos=np.zeros(3), vel=np.zeros(3), + quat=np.array([1, 0, 0, 0]), omega=np.zeros(3)): # internally use one numpy array self._state = np.empty(13) self.pos = pos @@ -12,7 +15,7 @@ def __init__(self, pos = np.zeros(3), vel = np.zeros(3), quat = np.array([1,0,0, @property def pos(self): - """position [m; world frame]""" + """Position [m; world frame].""" return self._state[0:3] @pos.setter @@ -21,7 +24,7 @@ def pos(self, value): @property def vel(self): - """velocity [m/s; world frame]""" + """Velocity [m/s; world frame].""" return self._state[3:6] @vel.setter @@ -30,7 +33,7 @@ def vel(self, value): @property def quat(self): - """quaternion [qw, qx, qy, qz; body -> world]""" + """Quaternion [qw, qx, qy, qz; body -> world].""" return self._state[6:10] @quat.setter @@ -39,7 +42,7 @@ def quat(self, value): @property def omega(self): - """angular velocity [rad/s; body frame]""" + """Angular velocity [rad/s; body frame].""" return self._state[10:13] @omega.setter @@ -47,11 +50,13 @@ def omega(self, value): self._state[10:13] = value def __repr__(self) -> str: - return "State pos={}, vel={}, quat={}, omega={}".format(self.pos, self.vel, self.quat, self.omega) + return 'State pos={}, vel={}, quat={}, omega={}'.format( + self.pos, self.vel, self.quat, self.omega) class Action: - """Class that stores the action of a UAV as used in the simulator interface""" + """Class that stores the action of a UAV as used in the simulator interface.""" + def __init__(self, rpm): # internally use one numpy array self._action = np.empty(4) @@ -59,7 +64,7 @@ def __init__(self, rpm): @property def rpm(self): - """rotation per second [rpm]""" + """Rotation per second [rpm].""" return self._action @rpm.setter @@ -67,4 +72,4 @@ def rpm(self, value): self._action = value def __repr__(self) -> str: - return "Action rpm={}".format(self.rpm) + return 'Action rpm={}'.format(self.rpm) diff --git a/crazyflie_sim/crazyflie_sim/visualization/blender.py b/crazyflie_sim/crazyflie_sim/visualization/blender.py index ea876fd94..577687774 100755 --- a/crazyflie_sim/crazyflie_sim/visualization/blender.py +++ b/crazyflie_sim/crazyflie_sim/visualization/blender.py @@ -1,40 +1,43 @@ +import datetime +import os +from pathlib import Path + import bpy import numpy as np -import os -import datetime +from rclpy.node import Node import rowan as rw import yaml -from pathlib import Path -from rclpy.node import Node -from ..sim_data_types import State, Action -# rotation vectors are axis-angle format in "compact form", where +from ..sim_data_types import Action, State + + +# rotation vectors are axis-angle format in 'compact form', where # theta = norm(rvec) and axis = rvec / theta # they can be converted to a matrix using cv2. Rodrigues, see # https://docs.opencv.org/4.7.0/d9/d0c/group__calib3d.html#ga61585db663d9da06b68e70cfbf6a1eac def opencv2quat(rvec): angle = np.linalg.norm(rvec) if angle == 0: - q = np.array([1,0,0,0]) + q = np.array([1, 0, 0, 0]) else: axis = rvec.flatten() / angle q = rw.from_axis_angle(axis, angle) return q + class Visualization: def __init__(self, node: Node, params: dict, names: list[str], states: list[State]): self.node = node - ## blender + # blender # load environment world = bpy.context.scene.world world.use_nodes = True - background_paths = [""] - self.env = world.node_tree.nodes.new("ShaderNodeTexEnvironment") - if params["cycle_bg"]: + self.env = world.node_tree.nodes.new('ShaderNodeTexEnvironment') + if params['cycle_bg']: bg_paths = [] - p = Path(__file__).resolve().parent / "data/env" + p = Path(__file__).resolve().parent / 'data/env' print(p) for subdir, dirs, files in os.walk(p): bg_paths.extend([os.path.join(subdir, file) for file in files]) @@ -46,60 +49,64 @@ def __init__(self, node: Node, params: dict, names: list[str], states: list[Stat self.env.image = self.bg_imgs[self.bg_idx] else: self.cycle_bg = False - self.env.image = bpy.data.images.load(Path(__file__).resolve().parent / "data/env/env.jpg") + self.env.image = bpy.data.images.load( + Path(__file__).resolve().parent / 'data/env/env.jpg') node_tree = world.node_tree - node_tree.links.new(self.env.outputs["Color"], node_tree.nodes["Background"].inputs["Color"]) - - # import crazyflie object - bpy.ops.import_scene.obj(filepath=f"{Path(__file__).resolve().parent}/data/model/cf.obj", axis_forward="Y", axis_up="Z") - self.cf_default = bpy.data.objects["cf"] + node_tree.links.new( + self.env.outputs['Color'], + node_tree.nodes['Background'].inputs['Color']) + + # import crazyflie object + bpy.ops.import_scene.obj( + filepath=f'{Path(__file__).resolve().parent}/data/model/cf.obj', + axis_forward='Y', axis_up='Z') + self.cf_default = bpy.data.objects['cf'] # save scene self.scene = bpy.context.scene self.scene.render.resolution_x = 320 self.scene.render.resolution_y = 320 self.scene.render.pixel_aspect_x = 1.0 self.scene.render.pixel_aspect_y = 1.0 - self.scene.render.image_settings.file_format = "JPEG" - self.scene.unit_settings.length_unit = "METERS" - self.scene.unit_settings.system = "METRIC" + self.scene.render.image_settings.file_format = 'JPEG' + self.scene.unit_settings.length_unit = 'METERS' + self.scene.unit_settings.system = 'METRIC' self.scene.unit_settings.scale_length = 1.0 - #self.scene.render.threads = 2 # max CPU cores to use to render + # self.scene.render.threads = 2 # max CPU cores to use to render # remove default objects - bpy.data.objects.remove(bpy.data.objects["Cube"]) - bpy.data.objects.remove(bpy.data.objects["Light"]) + bpy.data.objects.remove(bpy.data.objects['Cube']) + bpy.data.objects.remove(bpy.data.objects['Light']) # create lamp - lamp_data = bpy.data.lights.new(name="Lamp", type="SUN") + lamp_data = bpy.data.lights.new(name='Lamp', type='SUN') lamp_data.energy = 1.5 lamp_data.angle = 0.19198621809482574 # 11 deg - self.lamp = bpy.data.objects.new(name="Lamp", object_data=lamp_data) + self.lamp = bpy.data.objects.new(name='Lamp', object_data=lamp_data) bpy.context.collection.objects.link(self.lamp) bpy.context.view_layer.objects.active = self.lamp # camera - self.camera = bpy.data.objects["Camera"] + self.camera = bpy.data.objects['Camera'] self.camera.data.lens = 0.7376461029052734 - self.camera.data.lens_unit = "FOV" - self.camera.data.sensor_fit = "AUTO" + self.camera.data.lens_unit = 'FOV' + self.camera.data.sensor_fit = 'AUTO' self.camera.data.sensor_width = 1.4 self.camera.data.sensor_height = 18 self.camera.data.angle = 1.518436431884765 # 87 deg self.camera.data.clip_start = 1.1e-6 # link camera to scene - self.cf_default.hide_render = False # set rotation mode to quaternion - self.cf_default.rotation_mode = "QUATERNION" - self.camera.rotation_mode = "QUATERNION" - self.lamp.rotation_mode = "QUATERNION" + self.cf_default.rotation_mode = 'QUATERNION' + self.camera.rotation_mode = 'QUATERNION' + self.lamp.rotation_mode = 'QUATERNION' - base = "simulation_results" - self.path = base + "/" + datetime.datetime.now().strftime("%Y-%m-%d_%H%M%S") + "/" - os.makedirs(self.path, exist_ok=True) + base = 'simulation_results' + self.path = base + '/' + datetime.datetime.now().strftime('%Y-%m-%d_%H%M%S') + '/' + os.makedirs(self.path, exist_ok=True) self.ts = [] self.frame = 0 - self.fps = params["fps"] # frames per second + self.fps = params['fps'] # frames per second self.names = names self.n = len(names) @@ -107,14 +114,13 @@ def __init__(self, node: Node, params: dict, names: list[str], states: list[Stat self.cam_state_filenames = [] # dictionary with (name, idx) pairs to later find corresponding cf - self.names_idx_map = dict() + self.names_idx_map = {} # init list self.cf_list = [self.cf_default] - self.cf_cameras = params["cf_cameras"] if "cf_cameras" in params else dict() + self.cf_cameras = params['cf_cameras'] if 'cf_cameras' in params else {} # matrix where rows are the constant transformation between camera and its cf # it should only be accessed if corresponding cf carries a camera self.Q_virt_cf_cam = np.zeros((self.n, 4)) - for idx, (name, state) in enumerate(zip(names, states)): self.names_idx_map[name] = idx @@ -128,38 +134,43 @@ def __init__(self, node: Node, params: dict, names: list[str], states: list[Stat # set positions self.cf_list[idx].location = np.array(state.pos) - self.tvecs = np.zeros((self.n, 3)) for name in names: - os.mkdir(self.path + "/" + name + "/") # create dir for every cf for saving images - csf = f"{self.path}/{name}/{name}.csv" - calibration_sf = f"{self.path}/{name}/calibration.yaml" + os.mkdir(self.path + '/' + name + '/') # create dir for every cf for saving images + csf = f'{self.path}/{name}/{name}.csv' + calibration_sf = f'{self.path}/{name}/calibration.yaml' # initialize /.csv self.state_filenames.append(csf) - ### self.cam_state_filenames.append(cam_sf) - with open(csf, "w") as file: - file.write("image_name,timestamp,x,y,z,qw,qx,qy,qz\n") + # self.cam_state_filenames.append(cam_sf) + with open(csf, 'w') as file: + file.write('image_name,timestamp,x,y,z,qw,qx,qy,qz\n') if name in self.cf_cameras: - calibration = self.cf_cameras[name]["calibration"] - calibration["dist_coeff"] = np.zeros(5).tolist() - calibration["camera_matrix"] = np.array([[170.0,0,160.0], [0,170.0,160.0],[0,0,1]]).tolist() - with open(calibration_sf, "w") as file: + calibration = self.cf_cameras[name]['calibration'] + calibration['dist_coeff'] = np.zeros(5).tolist() + calibration['camera_matrix'] = np.array([ + [170.0, 0, 160.0], + [0, 170.0, 160.0], + [0, 0, 1]]).tolist() + with open(calibration_sf, 'w') as file: yaml.dump(calibration, file) - rvec = np.array(calibration["rvec"]) if "rvec" in calibration else np.array([1.2092, -1.2092, 1.2092]) - tvec = np.array(calibration["tvec"]) if "tvec" in calibration else np.zeros(3) + rvec = np.array([1.2092, -1.2092, 1.2092]) + if 'rvec' in calibration: + rvec = np.array(calibration['rvec']) + tvec = np.array(calibration['tvec']) if 'tvec' in calibration else np.zeros(3) self.tvecs[self.names_idx_map[name]] = tvec q_real_camera_to_robot = rw.inverse(opencv2quat(rvec)) - q_virtual_camera_to_real_camera = rw.from_euler(np.pi, 0, 0, "xyz") - self.Q_virt_cf_cam[self.names_idx_map[name]] = rw.multiply(q_real_camera_to_robot, q_virtual_camera_to_real_camera) - + q_virtual_camera_to_real_camera = rw.from_euler(np.pi, 0, 0, 'xyz') + self.Q_virt_cf_cam[self.names_idx_map[name]] = rw.multiply( + q_real_camera_to_robot, + q_virtual_camera_to_real_camera) def step(self, t, states: list[State], states_desired: list[State], actions: list[Action]): self.ts.append(t) - # render and record `self.fps` frames per second + # render and record `self.fps` frames per second if t - self.frame / self.fps >= 1 / self.fps: self.frame += 1 # quaternion matrix - Q = np.zeros((self.n, 4)) + Q = np.zeros((self.n, 4)) # position matrix P = np.zeros((self.n, 3)) @@ -167,17 +178,20 @@ def step(self, t, states: list[State], states_desired: list[State], actions: lis for name, state in zip(self.names, states): idx = self.names_idx_map[name] Q[idx] = np.array(state.quat) - P[idx] = np.array(state.pos) + P[idx] = np.array(state.pos) # set rotations self.cf_list[idx].rotation_quaternion = Q[idx] # set positions self.cf_list[idx].location = P[idx] - # record states - image_name = f"{self.names[idx]}_{self.frame:05}.jpg" if name in self.cf_cameras else "None" # image capturing scene from cf's pov or None + # record states + # image capturing scene from cf's pov or None + image_name = None + if name in self.cf_cameras: + image_name = f'{self.names[idx]}_{self.frame:05}.jpg' # record cf's state in world frame - with open(self.state_filenames[idx], "a") as file: - file.write(f"{image_name},{t},{P[idx,0]},{P[idx,1]},{P[idx,2]},{Q[idx,0]},{Q[idx,1]},{Q[idx,2]},{Q[idx,3]}\n") + with open(self.state_filenames[idx], 'a') as file: + file.write(f'{image_name},{t},{P[idx,0]},{P[idx,1]},{P[idx,2]},{Q[idx,0]},{Q[idx,1]},{Q[idx,2]},{Q[idx,3]}\n') # noqa E501 # cycle background image if enabled if self.cycle_bg: @@ -199,12 +213,12 @@ def step(self, t, states: list[State], states_desired: list[State], actions: lis # hide corresponding cf for rendering self.cf_list[idx].hide_render = True # Render image - image_name = f"{name}_{self.frame:05}.jpg" # image capturing scene from cf's pov - self.scene.render.filepath = f"{self.path}/{name}/{image_name}" + image_name = f'{name}_{self.frame:05}.jpg' # image capturing scene from cf's pov + self.scene.render.filepath = f'{self.path}/{name}/{image_name}' bpy.ops.render.render(write_still=True) # show again after rendering self.cf_list[idx].hide_render = False def shutdown(self): - for idx in range(1,self.n): + for idx in range(1, self.n): bpy.data.objects.remove(self.cf_list[idx]) diff --git a/crazyflie_sim/crazyflie_sim/visualization/pdf.py b/crazyflie_sim/crazyflie_sim/visualization/pdf.py index bb789b296..d3b04507d 100644 --- a/crazyflie_sim/crazyflie_sim/visualization/pdf.py +++ b/crazyflie_sim/crazyflie_sim/visualization/pdf.py @@ -1,16 +1,18 @@ from __future__ import annotations -from rclpy.node import Node -from ..sim_data_types import State, Action - import copy + +from matplotlib.backends.backend_pdf import PdfPages +import matplotlib.pyplot as plt import numpy as np +from rclpy.node import Node import rowan -import matplotlib.pyplot as plt -from matplotlib.backends.backend_pdf import PdfPages + +from ..sim_data_types import Action, State + class Visualization: - """Plots current and desired states into a PDF""" + """Plots current and desired states into a PDF.""" def __init__(self, node: Node, params: dict, names: list[str], states: list[State]): self.node = node @@ -19,7 +21,7 @@ def __init__(self, node: Node, params: dict, names: list[str], states: list[Stat self.all_states = [] self.all_states_desired = [] self.all_actions = [] - self.filename = params["output_file"] + self.filename = params['output_file'] def step(self, t, states: list[State], states_desired: list[State], actions: list[Action]): self.ts.append(t) @@ -39,79 +41,79 @@ def shutdown(self): # position fig, axs = plt.subplots(3, 1, sharex=True) - axs[0].set_ylabel("px [m]") - axs[1].set_ylabel("py [m]") - axs[2].set_ylabel("pz [m]") - axs[-1].set_xlabel("Time [s]") + axs[0].set_ylabel('px [m]') + axs[1].set_ylabel('py [m]') + axs[2].set_ylabel('pz [m]') + axs[-1].set_xlabel('Time [s]') for d in range(3): - axs[d].plot(self.ts, cf_states[:,d], label="state") - axs[d].plot(self.ts, cf_states_desired[:,d], label="desired") + axs[d].plot(self.ts, cf_states[:, d], label='state') + axs[d].plot(self.ts, cf_states_desired[:, d], label='desired') axs[0].legend() pdf.savefig(fig) plt.close() # velocity fig, axs = plt.subplots(3, 1, sharex=True) - axs[0].set_ylabel("vx [m/s]") - axs[1].set_ylabel("vy [m/s]") - axs[2].set_ylabel("vz [m/s]") - axs[-1].set_xlabel("Time [s]") + axs[0].set_ylabel('vx [m/s]') + axs[1].set_ylabel('vy [m/s]') + axs[2].set_ylabel('vz [m/s]') + axs[-1].set_xlabel('Time [s]') for d in range(3): - axs[d].plot(self.ts, cf_states[:,3+d], label="state") - axs[d].plot(self.ts, cf_states_desired[:,3+d], label="desired") + axs[d].plot(self.ts, cf_states[:, 3+d], label='state') + axs[d].plot(self.ts, cf_states_desired[:, 3+d], label='desired') axs[0].legend() pdf.savefig(fig) plt.close() # orientation fig, axs = plt.subplots(3, 1, sharex=True) - axs[0].set_ylabel("roll [deg]") - axs[1].set_ylabel("pitch [deg]") - axs[2].set_ylabel("yaw [deg]") - axs[-1].set_xlabel("Time [s]") + axs[0].set_ylabel('roll [deg]') + axs[1].set_ylabel('pitch [deg]') + axs[2].set_ylabel('yaw [deg]') + axs[-1].set_xlabel('Time [s]') - rpy = np.degrees(rowan.to_euler(cf_states[:,6:10], convention='xyz')) - rpy_desired = np.degrees(rowan.to_euler(cf_states_desired[:,6:10], convention='xyz')) + rpy = np.degrees(rowan.to_euler(cf_states[:, 6:10], convention='xyz')) + rpy_desired = np.degrees( + rowan.to_euler(cf_states_desired[:, 6:10], convention='xyz')) for d in range(3): - axs[d].plot(self.ts, rpy[:,d], label="state") - axs[d].plot(self.ts, rpy_desired[:,d], label="desired") + axs[d].plot(self.ts, rpy[:, d], label='state') + axs[d].plot(self.ts, rpy_desired[:, d], label='desired') axs[0].legend() pdf.savefig(fig) plt.close() # omega fig, axs = plt.subplots(3, 1, sharex=True) - axs[0].set_ylabel("wx [deg/s]") - axs[1].set_ylabel("wy [deg/s]") - axs[2].set_ylabel("wz [deg/s]") - axs[-1].set_xlabel("Time [s]") + axs[0].set_ylabel('wx [deg/s]') + axs[1].set_ylabel('wy [deg/s]') + axs[2].set_ylabel('wz [deg/s]') + axs[-1].set_xlabel('Time [s]') for d in range(3): - axs[d].plot(self.ts, np.degrees(cf_states[:,10+d]), label="state") - axs[d].plot(self.ts, np.degrees(cf_states_desired[:,10+d]), label="desired") + axs[d].plot(self.ts, np.degrees(cf_states[:, 10+d]), label='state') + axs[d].plot(self.ts, np.degrees(cf_states_desired[:, 10+d]), label='desired') axs[0].legend() pdf.savefig(fig) plt.close() # actions fig, axs = plt.subplots(2, 2, sharex=True, sharey=True) - axs[0,0].set_ylabel("rpm") - axs[1,0].set_ylabel("rpm") - axs[1,0].set_xlabel("Time [s]") - axs[1,1].set_xlabel("Time [s]") - - axs[0,0].plot(self.ts, cf_actions[:,3], label="M4") - axs[0,0].set_title("M4") - axs[0,1].plot(self.ts, cf_actions[:,0], label="M1") - axs[0,1].set_title("M1") - axs[1,1].plot(self.ts, cf_actions[:,1], label="M2") - axs[1,1].set_title("M2") - axs[1,0].plot(self.ts, cf_actions[:,2], label="M3") - axs[1,0].set_title("M3") + axs[0, 0].set_ylabel('rpm') + axs[1, 0].set_ylabel('rpm') + axs[1, 0].set_xlabel('Time [s]') + axs[1, 1].set_xlabel('Time [s]') + + axs[0, 0].plot(self.ts, cf_actions[:, 3], label='M4') + axs[0, 0].set_title('M4') + axs[0, 1].plot(self.ts, cf_actions[:, 0], label='M1') + axs[0, 1].set_title('M1') + axs[1, 1].plot(self.ts, cf_actions[:, 1], label='M2') + axs[1, 1].set_title('M2') + axs[1, 0].plot(self.ts, cf_actions[:, 2], label='M3') + axs[1, 0].set_title('M3') pdf.savefig(fig) plt.close() - diff --git a/crazyflie_sim/crazyflie_sim/visualization/record_states.py b/crazyflie_sim/crazyflie_sim/visualization/record_states.py index 9734f1cd6..240bfae4d 100644 --- a/crazyflie_sim/crazyflie_sim/visualization/record_states.py +++ b/crazyflie_sim/crazyflie_sim/visualization/record_states.py @@ -1,50 +1,53 @@ from __future__ import annotations -import numpy as np -import os import datetime -from pathlib import Path +import os + +import numpy as np from rclpy.node import Node -from ..sim_data_types import State, Action + +from ..sim_data_types import Action, State class Visualization: - """Records states in given format file""" + """Records states in given format file.""" def __init__(self, node: Node, params: dict, names: list[str], states: list[State]): self.node = node self.names = names - self.outdir = params["output_dir"] if "output_dir" in params else "state_info" - self.outdir = self.outdir + "/" + datetime.datetime.now().strftime("%Y-%m-%d_%H%M%S") - os.makedirs(self.outdir, exist_ok=True) + self.outdir = params['output_dir'] if 'output_dir' in params else 'state_info' + self.outdir = self.outdir + '/' + datetime.datetime.now().strftime('%Y-%m-%d_%H%M%S') + os.makedirs(self.outdir, exist_ok=True) self.names_idx_map = {} - self.logging_time = params["logging_time"] if "logging_time" in params else 0.3 # how many seconds to leave between logs - self.last_log = -self.logging_time # timestamp of last log, initialized to -self.logging_time so log occurs at t=0 + # how many seconds to leave between logs + self.logging_time = params['logging_time'] if 'logging_time' in params else 0.3 + # timestamp of last log, initialized to -self.logging_time so log occurs at t=0 + self.last_log = -self.logging_time self.supported_formats = { - "csv": { - "log": self.__log_csv + 'csv': { + 'log': self.__log_csv }, - "np": { - "log": self.__log_np, - "shutdown": self.__shutdown_np + 'np': { + 'log': self.__log_np, + 'shutdown': self.__shutdown_np } - } - self.active_formats = [fmt for fmt in params["file_formats"]] + } + self.active_formats = params['file_formats'] for idx, name in enumerate(names): self.names_idx_map[name] = idx self.n = len(names) - if "csv" in self.active_formats: + if 'csv' in self.active_formats: for idx, name in enumerate(names): - os.makedirs(f"{self.outdir}/csv", exist_ok=True) - csf = f"{self.outdir}/csv/{name}.csv" + os.makedirs(f'{self.outdir}/csv', exist_ok=True) + csf = f'{self.outdir}/csv/{name}.csv' # initialize .csv - with open(csf, "w") as file: - file.write("timestamp,x,y,z,qw,qx,qy,qz\n") - self.ts = [] # list of timestamps - if "np" in self.active_formats: - os.makedirs(f"{self.outdir}/np", exist_ok=True) - self.Ps = [] # list of positions matrices (self.n x 3) - self.Qs = [] # list of quaternion matrices (self.n x 4) + with open(csf, 'w') as file: + file.write('timestamp,x,y,z,qw,qx,qy,qz\n') + self.ts = [] # list of timestamps + if 'np' in self.active_formats: + os.makedirs(f'{self.outdir}/np', exist_ok=True) + self.Ps = [] # list of positions matrices (self.n x 3) + self.Qs = [] # list of quaternion matrices (self.n x 4) def step(self, t, states: list[State], states_desired: list[State], actions: list[Action]): if t - self.last_log >= self.logging_time: @@ -52,32 +55,33 @@ def step(self, t, states: list[State], states_desired: list[State], actions: lis self.ts.append(t) P = np.zeros((self.n, 3)) Q = np.zeros((self.n, 4)) - for name, state in zip(self.names, states): - idx = self.names_idx_map[name] + for name, state in zip(self.names, states): + idx = self.names_idx_map[name] P[idx] = np.array(state.pos) Q[idx] = np.array(state.quat) for fmt in self.active_formats: - self.supported_formats[fmt]["log"](t, idx, P, Q) - + self.supported_formats[fmt]['log'](t, idx, P, Q) def __log_csv(self, t, idx: int, P: np.ndarray, Q: np.ndarray): - """ record states in csv file """ - with open(f"{self.outdir}/csv/{self.names[idx]}.csv", "a") as file: - file.write(f"{t},{P[idx,0]},{P[idx,1]},{P[idx,2]},{Q[idx,0]},{Q[idx,1]},{Q[idx,2]},{Q[idx,3]}\n") + """Record states in csv file.""" + with open(f'{self.outdir}/csv/{self.names[idx]}.csv', 'a') as file: + file.write(f'{t},{P[idx,0]},{P[idx,1]},{P[idx,2]},{Q[idx,0]},{Q[idx,1]},{Q[idx,2]},{Q[idx,3]}\n') # noqa E501 def __log_np(self, t, idx: int, P: np.ndarray, Q: np.ndarray): self.Ps.append(P) self.Qs.append(Q) - def __shutdown_np(self): P = np.array(self.Ps) Q = np.array(self.Qs) for idx, name in enumerate(self.names): - np.savez_compressed(f"{self.outdir}/np/{name}.npz", t=self.ts, pos=P[idx::self.n,idx,:], quat=Q[idx::self.n,idx,:]) + np.savez_compressed( + f'{self.outdir}/np/{name}.npz', + t=self.ts, + pos=P[idx::self.n, idx, :], + quat=Q[idx::self.n, idx, :]) def shutdown(self): for fmt in self.active_formats: - if "shutdown" in self.supported_formats[fmt]: - self.supported_formats[fmt]["shutdown"]() - + if 'shutdown' in self.supported_formats[fmt]: + self.supported_formats[fmt]['shutdown']() diff --git a/crazyflie_sim/crazyflie_sim/visualization/rviz.py b/crazyflie_sim/crazyflie_sim/visualization/rviz.py index 1c629ee66..c1ed92687 100644 --- a/crazyflie_sim/crazyflie_sim/visualization/rviz.py +++ b/crazyflie_sim/crazyflie_sim/visualization/rviz.py @@ -1,13 +1,14 @@ from __future__ import annotations from geometry_msgs.msg import TransformStamped -from tf2_ros import TransformBroadcaster from rclpy.node import Node -from ..sim_data_types import State, Action +from tf2_ros import TransformBroadcaster + +from ..sim_data_types import Action, State class Visualization: - """Publishes ROS 2 transforms of the states, so that they can be visualized in RVIZ""" + """Publishes ROS 2 transforms of the states, so that they can be visualized in RVIZ.""" def __init__(self, node: Node, params: dict, names: list[str], states: list[State]): self.node = node @@ -20,7 +21,7 @@ def step(self, t, states: list[State], states_desired: list[State], actions: lis for name, state in zip(self.names, states): msg = TransformStamped() msg.header.stamp = self.node.get_clock().now().to_msg() - msg.header.frame_id = "world" + msg.header.frame_id = 'world' msg.child_frame_id = name msg.transform.translation.x = state.pos[0] msg.transform.translation.y = state.pos[1] @@ -34,4 +35,3 @@ def step(self, t, states: list[State], states_desired: list[State], actions: lis def shutdown(self): pass - diff --git a/crazyflie_sim/package.xml b/crazyflie_sim/package.xml index dd1caa89f..0bdea17c3 100644 --- a/crazyflie_sim/package.xml +++ b/crazyflie_sim/package.xml @@ -17,6 +17,7 @@ ament_flake8 ament_pep257 python3-pytest + ament_cmake_pytest ament_cmake diff --git a/crazyflie_sim/test/test_copyright.py b/crazyflie_sim/test/test_copyright.py deleted file mode 100644 index cc8ff03f7..000000000 --- a/crazyflie_sim/test/test_copyright.py +++ /dev/null @@ -1,23 +0,0 @@ -# Copyright 2015 Open Source Robotics Foundation, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from ament_copyright.main import main -import pytest - - -@pytest.mark.copyright -@pytest.mark.linter -def test_copyright(): - rc = main(argv=['.', 'test']) - assert rc == 0, 'Found errors' From f08cfa337ed6633e56120959bf21fb5835a266a6 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Sat, 21 Oct 2023 22:29:51 +0200 Subject: [PATCH 009/162] crazyflie_examples: fix flake8 and pep256 issues --- crazyflie_examples/CMakeLists.txt | 16 ++++ .../crazyflie_examples/cmd_full_state.py | 11 ++- .../crazyflie_examples/figure8.py | 9 ++- .../crazyflie_examples/hello_world.py | 3 +- .../crazyflie_examples/multi_trajectory.py | 11 +-- .../crazyflie_examples/nice_hover.py | 9 ++- .../crazyflie_examples/set_param.py | 10 +-- .../launch/keyboard_velmux_launch.py | 10 ++- .../launch/multiranger_mapping_launch.py | 47 ++++++----- .../launch/multiranger_nav2_launch.py | 77 ++++++++++--------- crazyflie_examples/package.xml | 1 + crazyflie_examples/test/test_copyright.py | 23 ------ 12 files changed, 113 insertions(+), 114 deletions(-) delete mode 100644 crazyflie_examples/test/test_copyright.py diff --git a/crazyflie_examples/CMakeLists.txt b/crazyflie_examples/CMakeLists.txt index 9ea4389cd..0c70c94d2 100644 --- a/crazyflie_examples/CMakeLists.txt +++ b/crazyflie_examples/CMakeLists.txt @@ -16,4 +16,20 @@ install(DIRECTORY DESTINATION share/${PROJECT_NAME}/ ) +if(BUILD_TESTING) + find_package(ament_cmake_pytest REQUIRED) + set(_pytest_tests + test/test_flake8.py + test/test_pep257.py + ) + foreach(_test_path ${_pytest_tests}) + get_filename_component(_test_name ${_test_path} NAME_WE) + ament_add_pytest_test(${_test_name} ${_test_path} + APPEND_ENV PYTHONPATH=${CMAKE_CURRENT_BINARY_DIR} + TIMEOUT 60 + WORKING_DIRECTORY ${CMAKE_SOURCE_DIR} + ) + endforeach() +endif() + ament_package() diff --git a/crazyflie_examples/crazyflie_examples/cmd_full_state.py b/crazyflie_examples/crazyflie_examples/cmd_full_state.py index 93040f90b..4979e6461 100644 --- a/crazyflie_examples/crazyflie_examples/cmd_full_state.py +++ b/crazyflie_examples/crazyflie_examples/cmd_full_state.py @@ -1,10 +1,10 @@ #!/usr/bin/env python -import numpy as np from pathlib import Path -from crazyflie_py import * +from crazyflie_py import Crazyswarm from crazyflie_py.uav_trajectory import Trajectory +import numpy as np def executeTrajectory(timeHelper, cf, trajpath, rate=100, offset=np.zeros(3)): @@ -39,12 +39,15 @@ def main(): cf.takeoff(targetHeight=Z, duration=Z+1.0) timeHelper.sleep(Z+2.0) - executeTrajectory(timeHelper, cf, Path(__file__).parent / "data/figure8.csv", rate, offset=np.array([0, 0, 0.5])) + executeTrajectory(timeHelper, cf, + Path(__file__).parent / 'data/figure8.csv', + rate, + offset=np.array([0, 0, 0.5])) cf.notifySetpointsStop() cf.land(targetHeight=0.03, duration=Z+1.0) timeHelper.sleep(Z+2.0) -if __name__ == "__main__": +if __name__ == '__main__': main() diff --git a/crazyflie_examples/crazyflie_examples/figure8.py b/crazyflie_examples/crazyflie_examples/figure8.py index 58c768bc5..af75d2998 100644 --- a/crazyflie_examples/crazyflie_examples/figure8.py +++ b/crazyflie_examples/crazyflie_examples/figure8.py @@ -1,10 +1,11 @@ #!/usr/bin/env python -import numpy as np from pathlib import Path -from crazyflie_py import * +from crazyflie_py import Crazyswarm from crazyflie_py.uav_trajectory import Trajectory +import numpy as np + def main(): swarm = Crazyswarm() @@ -12,7 +13,7 @@ def main(): allcfs = swarm.allcfs traj1 = Trajectory() - traj1.loadcsv(Path(__file__).parent / "data/figure8.csv") + traj1.loadcsv(Path(__file__).parent / 'data/figure8.csv') TRIALS = 1 TIMESCALE = 1.0 @@ -36,5 +37,5 @@ def main(): timeHelper.sleep(3.0) -if __name__ == "__main__": +if __name__ == '__main__': main() diff --git a/crazyflie_examples/crazyflie_examples/hello_world.py b/crazyflie_examples/crazyflie_examples/hello_world.py index add21cb8c..20bae593e 100644 --- a/crazyflie_examples/crazyflie_examples/hello_world.py +++ b/crazyflie_examples/crazyflie_examples/hello_world.py @@ -1,6 +1,5 @@ """Takeoff-hover-land for one CF. Useful to validate hardware config.""" -# from pycrazyswarm import Crazyswarm from crazyflie_py import Crazyswarm @@ -19,5 +18,5 @@ def main(): timeHelper.sleep(TAKEOFF_DURATION) -if __name__ == "__main__": +if __name__ == '__main__': main() diff --git a/crazyflie_examples/crazyflie_examples/multi_trajectory.py b/crazyflie_examples/crazyflie_examples/multi_trajectory.py index a38b73139..57b5caa7d 100644 --- a/crazyflie_examples/crazyflie_examples/multi_trajectory.py +++ b/crazyflie_examples/crazyflie_examples/multi_trajectory.py @@ -1,21 +1,22 @@ #!/usr/bin/env python -import numpy as np from pathlib import Path -from crazyflie_py import * +from crazyflie_py import Crazyswarm from crazyflie_py.uav_trajectory import Trajectory +import numpy as np + def main(): swarm = Crazyswarm() timeHelper = swarm.timeHelper allcfs = swarm.allcfs trajs = [] - n = 2 # number of distinct trajectories + n = 2 # number of distinct trajectories for i in range(n): traj = Trajectory() - traj.loadcsv(Path(__file__).parent / f"data/multi_trajectory/traj{i}.csv") + traj.loadcsv(Path(__file__).parent / f'data/multi_trajectory/traj{i}.csv') trajs.append(traj) TRIALS = 1 @@ -38,5 +39,5 @@ def main(): timeHelper.sleep(3.0) -if __name__ == "__main__": +if __name__ == '__main__': main() diff --git a/crazyflie_examples/crazyflie_examples/nice_hover.py b/crazyflie_examples/crazyflie_examples/nice_hover.py index 43b83331d..b85647cdf 100644 --- a/crazyflie_examples/crazyflie_examples/nice_hover.py +++ b/crazyflie_examples/crazyflie_examples/nice_hover.py @@ -1,12 +1,12 @@ #!/usr/bin/env python +from crazyflie_py import Crazyswarm import numpy as np -from crazyflie_py import * def main(): Z = 1.0 - + swarm = Crazyswarm() timeHelper = swarm.timeHelper allcfs = swarm.allcfs @@ -17,11 +17,12 @@ def main(): pos = np.array(cf.initialPosition) + np.array([0, 0, Z]) cf.goTo(pos, 0, 1.0) - print("press button to continue...") + print('press button to continue...') swarm.input.waitUntilButtonPressed() allcfs.land(targetHeight=0.02, duration=1.0+Z) timeHelper.sleep(1.0+Z) -if __name__ == "__main__": + +if __name__ == '__main__': main() diff --git a/crazyflie_examples/crazyflie_examples/set_param.py b/crazyflie_examples/crazyflie_examples/set_param.py index 1e52cc6f2..69c49daf0 100644 --- a/crazyflie_examples/crazyflie_examples/set_param.py +++ b/crazyflie_examples/crazyflie_examples/set_param.py @@ -1,26 +1,24 @@ #!/usr/bin/env python -from crazyflie_py import * +from crazyflie_py import Crazyswarm def main(): - Z = 1.0 - swarm = Crazyswarm() timeHelper = swarm.timeHelper allcfs = swarm.allcfs # disable LED (one by one) for cf in allcfs.crazyflies: - cf.setParam("led.bitmask", 128) + cf.setParam('led.bitmask', 128) timeHelper.sleep(1.0) timeHelper.sleep(2.0) # enable LED (broadcast) - allcfs.setParam("led.bitmask", 0) + allcfs.setParam('led.bitmask', 0) timeHelper.sleep(5.0) -if __name__ == "__main__": +if __name__ == '__main__': main() diff --git a/crazyflie_examples/launch/keyboard_velmux_launch.py b/crazyflie_examples/launch/keyboard_velmux_launch.py index db7badac4..25d318a0b 100644 --- a/crazyflie_examples/launch/keyboard_velmux_launch.py +++ b/crazyflie_examples/launch/keyboard_velmux_launch.py @@ -1,8 +1,10 @@ import os -import yaml + from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch_ros.actions import Node +import yaml + def generate_launch_description(): # load crazyflies @@ -29,8 +31,8 @@ def generate_launch_description(): executable='vel_mux.py', name='vel_mux', output='screen', - parameters=[{"hover_height": 0.3}, - {"incoming_twist_topic": "/cmd_vel"}, - {"robot_prefix": "/cf1"}] + parameters=[{'hover_height': 0.3}, + {'incoming_twist_topic': '/cmd_vel'}, + {'robot_prefix': '/cf1'}] ), ]) diff --git a/crazyflie_examples/launch/multiranger_mapping_launch.py b/crazyflie_examples/launch/multiranger_mapping_launch.py index 7523caf77..7ff246f83 100644 --- a/crazyflie_examples/launch/multiranger_mapping_launch.py +++ b/crazyflie_examples/launch/multiranger_mapping_launch.py @@ -1,11 +1,10 @@ import os -import yaml + from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription from launch_ros.actions import Node -from launch.conditions import LaunchConfigurationEquals -from launch.launch_description_sources import PythonLaunchDescriptionSource +import yaml + def generate_launch_description(): # load crazyflies @@ -32,25 +31,25 @@ def generate_launch_description(): executable='vel_mux.py', name='vel_mux', output='screen', - parameters=[{"hover_height": 0.3}, - {"incoming_twist_topic": "/cmd_vel"}, - {"robot_prefix": "/cf1"}] + parameters=[{'hover_height': 0.3}, + {'incoming_twist_topic': '/cmd_vel'}, + {'robot_prefix': '/cf1'}] ), Node( - parameters=[ - {'odom_frame': 'odom'}, - {'map_frame': 'world'}, - {'base_frame': 'cf1'}, - {'scan_topic': '/cf1/scan'}, - {'use_scan_matching': False}, - {'max_laser_range': 3.5}, - {'resolution': 0.1}, - {'minimum_travel_distance': 0.01}, - {'minimum_travel_heading': 0.001}, - {'map_update_interval': 0.1} - ], - package='slam_toolbox', - executable='async_slam_toolbox_node', - name='slam_toolbox', - output='screen'), - ]) \ No newline at end of file + parameters=[ + {'odom_frame': 'odom'}, + {'map_frame': 'world'}, + {'base_frame': 'cf1'}, + {'scan_topic': '/cf1/scan'}, + {'use_scan_matching': False}, + {'max_laser_range': 3.5}, + {'resolution': 0.1}, + {'minimum_travel_distance': 0.01}, + {'minimum_travel_heading': 0.001}, + {'map_update_interval': 0.1} + ], + package='slam_toolbox', + executable='async_slam_toolbox_node', + name='slam_toolbox', + output='screen'), + ]) diff --git a/crazyflie_examples/launch/multiranger_nav2_launch.py b/crazyflie_examples/launch/multiranger_nav2_launch.py index e556277d3..9e1421325 100644 --- a/crazyflie_examples/launch/multiranger_nav2_launch.py +++ b/crazyflie_examples/launch/multiranger_nav2_launch.py @@ -1,11 +1,11 @@ import os -import yaml + from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription -from launch_ros.actions import Node -from launch.conditions import LaunchConfigurationEquals +from launch.actions import IncludeLaunchDescription from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch_ros.actions import Node +import yaml def generate_launch_description(): @@ -20,11 +20,10 @@ def generate_launch_description(): server_params = crazyflies - cf_examples_dir = get_package_share_directory("crazyflie_examples") + cf_examples_dir = get_package_share_directory('crazyflie_examples') bringup_dir = get_package_share_directory('nav2_bringup') bringup_launch_dir = os.path.join(bringup_dir, 'launch') - map_name = "map" - + map_name = 'map' return LaunchDescription([ Node( @@ -32,7 +31,7 @@ def generate_launch_description(): executable='crazyflie_server.py', name='crazyflie_server', output='screen', - parameters=[{"world_tf_name": 'map'}, + parameters=[{'world_tf_name': 'map'}, server_params], ), Node( @@ -40,44 +39,46 @@ def generate_launch_description(): executable='vel_mux.py', name='vel_mux', output='screen', - parameters=[{"hover_height": 0.3}, - {"incoming_twist_topic": "/cmd_vel"}, - {"robot_prefix": "/cf1"}] + parameters=[{'hover_height': 0.3}, + {'incoming_twist_topic': '/cmd_vel'}, + {'robot_prefix': '/cf1'}] ), Node( - parameters=[ - {'odom_frame': 'odom'}, - {'map_frame': 'map'}, - {'base_frame': 'cf1'}, - {'scan_topic': '/cf1/scan'}, - {'use_scan_matching': False}, - {'max_laser_range': 3.5}, - {'resolution': 0.1}, - {'minimum_travel_distance': 0.01}, - {'minimum_travel_heading': 0.001}, - {'map_update_interval': 0.1}, - {'mode': 'localization'}, - {"map_file_name": cf_examples_dir + "/data/" + map_name}, - {"map_start_pose": [0.0, 0.0, 0.0]} ], - package='slam_toolbox', - executable='async_slam_toolbox_node', - name='slam_toolbox', - output='screen'), + parameters=[ + {'odom_frame': 'odom'}, + {'map_frame': 'map'}, + {'base_frame': 'cf1'}, + {'scan_topic': '/cf1/scan'}, + {'use_scan_matching': False}, + {'max_laser_range': 3.5}, + {'resolution': 0.1}, + {'minimum_travel_distance': 0.01}, + {'minimum_travel_heading': 0.001}, + {'map_update_interval': 0.1}, + {'mode': 'localization'}, + {'map_file_name': cf_examples_dir + '/data/' + map_name}, + {'map_start_pose': [0.0, 0.0, 0.0]}], + package='slam_toolbox', + executable='async_slam_toolbox_node', + name='slam_toolbox', + output='screen'), IncludeLaunchDescription( PythonLaunchDescriptionSource( os.path.join(bringup_launch_dir, 'bringup_launch.py')), - launch_arguments={'slam': 'False', - 'use_sim_time': 'false', - 'map': cf_examples_dir + "/data/" + map_name + ".yaml", - 'params_file': os.path.join(cf_examples_dir, 'nav2_params.yaml'), - 'autostart': 'true', - 'use_composition': 'true', - 'transform_publish_period': '0.02' - }.items() + launch_arguments={ + 'slam': 'False', + 'use_sim_time': 'false', + 'map': cf_examples_dir + '/data/' + map_name + '.yaml', + 'params_file': os.path.join(cf_examples_dir, 'nav2_params.yaml'), + 'autostart': 'true', + 'use_composition': 'true', + 'transform_publish_period': '0.02' + }.items() ), IncludeLaunchDescription( PythonLaunchDescriptionSource( os.path.join(bringup_launch_dir, 'rviz_launch.py')), launch_arguments={ - 'rviz_config': os.path.join(bringup_dir, 'rviz', 'nav2_default_view.rviz')}.items()) + 'rviz_config': os.path.join( + bringup_dir, 'rviz', 'nav2_default_view.rviz')}.items()) ]) diff --git a/crazyflie_examples/package.xml b/crazyflie_examples/package.xml index 04015c337..1eba5101d 100644 --- a/crazyflie_examples/package.xml +++ b/crazyflie_examples/package.xml @@ -17,6 +17,7 @@ ament_flake8 ament_pep257 python3-pytest + ament_cmake_pytest ament_cmake diff --git a/crazyflie_examples/test/test_copyright.py b/crazyflie_examples/test/test_copyright.py deleted file mode 100644 index cc8ff03f7..000000000 --- a/crazyflie_examples/test/test_copyright.py +++ /dev/null @@ -1,23 +0,0 @@ -# Copyright 2015 Open Source Robotics Foundation, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from ament_copyright.main import main -import pytest - - -@pytest.mark.copyright -@pytest.mark.linter -def test_copyright(): - rc = main(argv=['.', 'test']) - assert rc == 0, 'Found errors' From 4bad810674d8c9f3a2dcb8562ea06c24dedb4237 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Wed, 1 Nov 2023 14:10:57 +0100 Subject: [PATCH 010/162] cpp backend: process all incoming radio messages Process all radio messages every millisecond. The behavior before was to process one message every 100 ms, which caused long delays for incoming messages (such as log topics). Fixes #300 --- crazyflie/deps/crazyflie_tools | 2 +- crazyflie/src/crazyflie_server.cpp | 9 +++++++-- 2 files changed, 8 insertions(+), 3 deletions(-) diff --git a/crazyflie/deps/crazyflie_tools b/crazyflie/deps/crazyflie_tools index f26165753..2e0ae6da8 160000 --- a/crazyflie/deps/crazyflie_tools +++ b/crazyflie/deps/crazyflie_tools @@ -1 +1 @@ -Subproject commit f26165753fb8cb527ca4f78f81b2db0a7c4c251f +Subproject commit 2e0ae6da886aff19bf93116c487e7c737fa3e417 diff --git a/crazyflie/src/crazyflie_server.cpp b/crazyflie/src/crazyflie_server.cpp index d0910f3b5..9594e2ee4 100644 --- a/crazyflie/src/crazyflie_server.cpp +++ b/crazyflie/src/crazyflie_server.cpp @@ -141,7 +141,11 @@ class CrazyflieROS subscription_cmd_position_ = node->create_subscription(name + "/cmd_position", rclcpp::SystemDefaultsQoS(), std::bind(&CrazyflieROS::cmd_position_changed, this, _1), sub_opt_cf_cmd); // spinning timer - spin_timer_ = node->create_wall_timer(std::chrono::milliseconds(100), std::bind(&CrazyflieROS::spin_once, this), callback_group_cf_srv); + // used to process all incoming radio messages + spin_timer_ = + node->create_wall_timer( + std::chrono::milliseconds(1), + std::bind(&CrazyflieROS::spin_once, this), callback_group_cf_srv); auto start = std::chrono::system_clock::now(); @@ -367,7 +371,8 @@ class CrazyflieROS void spin_once() { - cf_.spin_once(); + // process all packets from the receive queue + cf_.processAllPackets(); } std::string broadcastUri() const From b22d9881b300858b981adfbdfd1ecedf36c43c84 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Tue, 7 Nov 2023 11:26:27 +0100 Subject: [PATCH 011/162] server (cpp): continous unicast latency monitoring --- crazyflie/CMakeLists.txt | 1 + crazyflie/config/server.yaml | 2 + crazyflie/deps/crazyflie_tools | 2 +- crazyflie/src/crazyflie_server.cpp | 63 ++++++++++++++++++++++++------ 4 files changed, 56 insertions(+), 12 deletions(-) diff --git a/crazyflie/CMakeLists.txt b/crazyflie/CMakeLists.txt index ca4dc3764..8553b314d 100644 --- a/crazyflie/CMakeLists.txt +++ b/crazyflie/CMakeLists.txt @@ -85,6 +85,7 @@ ament_target_dependencies(crazyflie_server # Install C++ executables install(TARGETS # crazyflie_tools + comCheck scan listParams listLogVariables diff --git a/crazyflie/config/server.yaml b/crazyflie/config/server.yaml index d1ca14a8e..e0d8d6af6 100644 --- a/crazyflie/config/server.yaml +++ b/crazyflie/config/server.yaml @@ -4,6 +4,8 @@ frequency: 1.0 # report/run checks once per second motion_capture: warning_if_rate_outside: [80.0, 120.0] + communication: + max_unicast_latency: 10.0 # ms firmware_params: query_all_values_on_connect: False # simulation related diff --git a/crazyflie/deps/crazyflie_tools b/crazyflie/deps/crazyflie_tools index f26165753..65a8fcdf4 160000 --- a/crazyflie/deps/crazyflie_tools +++ b/crazyflie/deps/crazyflie_tools @@ -1 +1 @@ -Subproject commit f26165753fb8cb527ca4f78f81b2db0a7c4c251f +Subproject commit 65a8fcdf48762994dce277db506793cdcc9c7135 diff --git a/crazyflie/src/crazyflie_server.cpp b/crazyflie/src/crazyflie_server.cpp index d0910f3b5..8c7d9c3c8 100644 --- a/crazyflie/src/crazyflie_server.cpp +++ b/crazyflie/src/crazyflie_server.cpp @@ -119,6 +119,7 @@ class CrazyflieROS , name_(name) , node_(node) , tf_broadcaster_(node) + , last_on_latency_(std::chrono::steady_clock::now()) { auto sub_opt_cf_cmd = rclcpp::SubscriptionOptions(); sub_opt_cf_cmd.callback_group = callback_group_cf_cmd; @@ -143,6 +144,18 @@ class CrazyflieROS // spinning timer spin_timer_ = node->create_wall_timer(std::chrono::milliseconds(100), std::bind(&CrazyflieROS::spin_once, this), callback_group_cf_srv); + // link statistics + warning_freq_ = node->get_parameter("warnings.frequency").get_parameter_value().get(); + max_latency_ = node->get_parameter("warnings.communication.max_unicast_latency").get_parameter_value().get(); + + if (warning_freq_ >= 0.0) { + cf_.setLatencyCallback(std::bind(&CrazyflieROS::on_latency, this, std::placeholders::_1)); + link_statistics_timer_ = + node->create_wall_timer( + std::chrono::milliseconds((int)(1000.0/warning_freq_)), + std::bind(&CrazyflieROS::on_link_statistics_timer, this), callback_group_cf_srv); + + } auto start = std::chrono::system_clock::now(); @@ -679,6 +692,25 @@ class CrazyflieROS (*pub)->publish(msg); } + void on_link_statistics_timer() + { + cf_.triggerLatencyMeasurement(); + + auto now = std::chrono::steady_clock::now(); + std::chrono::duration elapsed = now - last_on_latency_; + if (elapsed.count() > 1.0 / warning_freq_) { + RCLCPP_WARN(logger_, "last latency update: %f s", elapsed.count()); + } + } + + void on_latency(uint64_t latency_in_us) + { + if (latency_in_us / 1000.0 > max_latency_) { + RCLCPP_WARN(logger_, "Latency: %f ms", latency_in_us / 1000.0); + } + last_on_latency_ = std::chrono::steady_clock::now(); + } + private: rclcpp::Logger logger_; CrazyflieLogger cf_logger_; @@ -715,7 +747,13 @@ class CrazyflieROS // multithreading rclcpp::CallbackGroup::SharedPtr callback_group_cf_; rclcpp::TimerBase::SharedPtr spin_timer_; - + + // link statistics + rclcpp::TimerBase::SharedPtr link_statistics_timer_; + std::chrono::time_point last_on_latency_; + float warning_freq_; + float max_latency_; + }; class CrazyflieServer : public rclcpp::Node @@ -767,6 +805,19 @@ class CrazyflieServer : public rclcpp::Node broadcasts_delay_between_repeats_ms_ = this->get_parameter("all.broadcasts.delay_between_repeats_ms").get_parameter_value().get(); mocap_enabled_ = false; + // Warnings + this->declare_parameter("warnings.frequency", 1.0); + float freq = this->get_parameter("warnings.frequency").get_parameter_value().get(); + if (freq >= 0.0) { + watchdog_timer_ = this->create_wall_timer(std::chrono::milliseconds((int)(1000.0/freq)), std::bind(&CrazyflieServer::on_watchdog_timer, this), callback_group_all_srv_); + } + this->declare_parameter("warnings.motion_capture.warning_if_rate_outside", std::vector({80.0, 120.0})); + auto rate_range = this->get_parameter("warnings.motion_capture.warning_if_rate_outside").get_parameter_value().get>(); + mocap_min_rate_ = rate_range[0]; + mocap_max_rate_ = rate_range[1]; + + this->declare_parameter("warnings.communication.max_unicast_latency", 10.0); + // load crazyflies from params auto node_parameters_iface = this->get_node_parameters_interface(); const std::map ¶meter_overrides = @@ -836,16 +887,6 @@ class CrazyflieServer : public rclcpp::Node param_subscriber_ = std::make_shared(this); cb_handle_ = param_subscriber_->add_parameter_event_callback(std::bind(&CrazyflieServer::on_parameter_event, this, _1)); - // Warnings - this->declare_parameter("warnings.frequency", 1.0); - float freq = this->get_parameter("warnings.frequency").get_parameter_value().get(); - if (freq >= 0.0) { - watchdog_timer_ = this->create_wall_timer(std::chrono::milliseconds((int)(1000.0/freq)), std::bind(&CrazyflieServer::on_watchdog_timer, this), callback_group_all_srv_); - } - this->declare_parameter("warnings.motion_capture.warning_if_rate_outside", std::vector({80.0, 120.0})); - auto rate_range = this->get_parameter("warnings.motion_capture.warning_if_rate_outside").get_parameter_value().get>(); - mocap_min_rate_ = rate_range[0]; - mocap_max_rate_ = rate_range[1]; } From 88eaa668a5b8425f4361be382520ed8c04ac7d1d Mon Sep 17 00:00:00 2001 From: Kimberly McGuire Date: Mon, 13 Nov 2023 13:49:58 +0100 Subject: [PATCH 012/162] Update crazyflie_server.py --- crazyflie/scripts/crazyflie_server.py | 22 ++++++++++++++++++++-- 1 file changed, 20 insertions(+), 2 deletions(-) diff --git a/crazyflie/scripts/crazyflie_server.py b/crazyflie/scripts/crazyflie_server.py index ad8e299b4..a95c06e0a 100755 --- a/crazyflie/scripts/crazyflie_server.py +++ b/crazyflie/scripts/crazyflie_server.py @@ -24,8 +24,7 @@ from crazyflie_interfaces.srv import Takeoff, Land, GoTo, RemoveLogging, AddLogging from crazyflie_interfaces.srv import UploadTrajectory, StartTrajectory, NotifySetpointsStop from rcl_interfaces.msg import ParameterDescriptor, SetParametersResult, ParameterType -from crazyflie_interfaces.msg import Hover -from crazyflie_interfaces.msg import LogDataGeneric +from crazyflie_interfaces.msg import Hover, LogDataGeneric, FullState from motion_capture_tracking_interfaces.msg import NamedPoseArray from std_srvs.srv import Empty @@ -246,6 +245,10 @@ def __init__(self): Hover, name + "/cmd_hover", partial(self._cmd_hover_changed, uri=uri), 10 ) + self.create_subscription( + Hover, name + + "/cmd_full_state", partial(self._cmd_full_state_changed, uri=uri), 10 + ) qos_profile = QoSProfile(reliability =QoSReliabilityPolicy.BEST_EFFORT, history=QoSHistoryPolicy.KEEP_LAST, depth=1, @@ -846,6 +849,21 @@ def _cmd_hover_changed(self, msg, uri=""): self.swarm._cfs[uri].cf.commander.send_hover_setpoint(vx, vy, yawrate, z) self.get_logger().info(f"{uri}: Received hover topic {vx} {vy} {yawrate} {z}") + def _cmd_full_state_changed(self, msg, uri=""): + """ + Topic update callback to full state cmd topic + """ + pos = [msg.pose.position.x, msg.pose.position.y, msg.pose.position.z] + vel = [msg.twist.linear.x, msg.twist.linear.y, msg.twist.linear.z] + acc = [msg.acc.x, msg.acc.y, msg.acc.z] + q = [msg.pose.orientation.x, msg.pose.orientation.y, msg.pose.orientation.z, msg.pose.orientation.w] + roll_rate = msg.twist.angular.x + pitch_rate = msg.twist.angular.y + yaw_rate = msg.twist.angular.z + + self.swarm._cfs[uri].cf.commander.send_hover_setpoint(pos, vel, acc, q, roll_rate, pitch_rate, yaw_rate) + self.get_logger().info(f"{uri}: Received full state topic {pose} {vel} {acc} {q}, {roll_rate}, {pitch_rate}, {yaw_rate}) + def _remove_logging(self, request, response, uri="all"): """ Service callback to remove logging blocks of the crazyflie From c849435d307649813e44f6ca2ef0fcf395290612 Mon Sep 17 00:00:00 2001 From: torobo Date: Tue, 14 Nov 2023 14:48:15 +0900 Subject: [PATCH 013/162] debug cmd_full_state cb --- crazyflie/scripts/crazyflie_server.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/crazyflie/scripts/crazyflie_server.py b/crazyflie/scripts/crazyflie_server.py index a95c06e0a..1b6018d72 100755 --- a/crazyflie/scripts/crazyflie_server.py +++ b/crazyflie/scripts/crazyflie_server.py @@ -246,7 +246,7 @@ def __init__(self): "/cmd_hover", partial(self._cmd_hover_changed, uri=uri), 10 ) self.create_subscription( - Hover, name + + FullState, name + "/cmd_full_state", partial(self._cmd_full_state_changed, uri=uri), 10 ) qos_profile = QoSProfile(reliability =QoSReliabilityPolicy.BEST_EFFORT, @@ -861,8 +861,8 @@ def _cmd_full_state_changed(self, msg, uri=""): pitch_rate = msg.twist.angular.y yaw_rate = msg.twist.angular.z - self.swarm._cfs[uri].cf.commander.send_hover_setpoint(pos, vel, acc, q, roll_rate, pitch_rate, yaw_rate) - self.get_logger().info(f"{uri}: Received full state topic {pose} {vel} {acc} {q}, {roll_rate}, {pitch_rate}, {yaw_rate}) + self.swarm._cfs[uri].cf.commander.send_full_state_setpoint(pos, vel, acc, q, roll_rate, pitch_rate, yaw_rate) + self.get_logger().info(f"{uri}: Received full state topic {pos} {vel} {acc} {q}, {roll_rate}, {pitch_rate}, {yaw_rate}") def _remove_logging(self, request, response, uri="all"): """ From 8319945e73f6fb6d82baa6eebb5e9b25dd42c0f7 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Thu, 16 Nov 2023 09:54:39 +0100 Subject: [PATCH 014/162] add support for downloadUSDLogfile --- crazyflie/CMakeLists.txt | 1 + crazyflie/deps/crazyflie_tools | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/crazyflie/CMakeLists.txt b/crazyflie/CMakeLists.txt index ca4dc3764..1b3479b5a 100644 --- a/crazyflie/CMakeLists.txt +++ b/crazyflie/CMakeLists.txt @@ -95,6 +95,7 @@ install(TARGETS console log setParam + downloadUSDLogfile # teleop crazyflie_server diff --git a/crazyflie/deps/crazyflie_tools b/crazyflie/deps/crazyflie_tools index 2e0ae6da8..c7f3b6c89 160000 --- a/crazyflie/deps/crazyflie_tools +++ b/crazyflie/deps/crazyflie_tools @@ -1 +1 @@ -Subproject commit 2e0ae6da886aff19bf93116c487e7c737fa3e417 +Subproject commit c7f3b6c895be149073758825383bdfd9d31f6679 From ae9815d46dc7dc7523ab0c33dd827c5b08aa8800 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Thu, 16 Nov 2023 10:43:02 +0100 Subject: [PATCH 015/162] sim: fix cmd_full_state example --- crazyflie_sim/crazyflie_sim/crazyflie_sil.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/crazyflie_sim/crazyflie_sim/crazyflie_sil.py b/crazyflie_sim/crazyflie_sim/crazyflie_sil.py index cf904d746..dc3018ad0 100644 --- a/crazyflie_sim/crazyflie_sim/crazyflie_sil.py +++ b/crazyflie_sim/crazyflie_sim/crazyflie_sil.py @@ -296,7 +296,7 @@ def executeController(self): if self.controller is None: return None - if self.mode != CrazyflieSIL.MODE_HIGH_POLY: + if self.mode == CrazyflieSIL.MODE_IDLE: return sim_data_types.Action([0, 0, 0, 0]) time_in_seconds = self.time_func() From a8a1625dfc28e4445e6afad036819ee172bbc980 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Thu, 16 Nov 2023 11:06:24 +0100 Subject: [PATCH 016/162] Add docs on collision avoidance and traj --- docs2/howto.rst | 37 ++++++++++++++++++++++++++++++++++--- 1 file changed, 34 insertions(+), 3 deletions(-) diff --git a/docs2/howto.rst b/docs2/howto.rst index 7c214d872..274f52374 100644 --- a/docs2/howto.rst +++ b/docs2/howto.rst @@ -99,6 +99,37 @@ This requires some updated pip packages for testing, see https://docs.ros.org/en Then execute: -``` -colcon test --event-handlers=console_cohesion+ --return-code-on-test-failure --packages-select crazyflie_py -``` +.. code-block:: bash + + colcon test --event-handlers=console_cohesion+ --return-code-on-test-failure --packages-select crazyflie_py + +Collision Avoidance +------------------- + +The official firmware has support for collision avoidance using the Buffered Voronoi Cell algorithm. +It requires the use of a motion capture system (so that the positions of other drones are known) and can be enabled +in the `crazyflies.yaml`: + +.. code-block:: yaml + + all: + firmware_params: + colAv: + enable: 1 + +or inside a Python script via: + +.. code-block:: python + + swarm = Crazyswarm() + allcfs = swarm.allcfs + allcfs.setParam("colAv.enable", 1) + +Note that the algorithm might require tuning of its hyperparameters. Documention can be found at https://github.com/bitcraze/crazyflie-firmware/blob/dbb9df1137f11d4e7e3771c56d25a7137b5b69cc/src/modules/src/collision_avoidance.c#L348-L428. + +Generate Trajectories +--------------------- + +Crazyswarm2 supports polynomial trajectories (8th order). These can be generated from waypoints, waypoint/time pairs, or optimization. Useful tools are available at https://github.com/whoenig/uav_trajectories, including scripts to visualize the resulting trajectories. + +For the multi-robot case, there is no easy to-use library, yet. One can use collision avoidance (see HowTo) or preplan trajectories using https://github.com/IMRCLab/db-CBS or https://github.com/mjdebord/smoothener/tree/cylinders. From e8808b989ef9053d7e998574310492c3fdaa550f Mon Sep 17 00:00:00 2001 From: Kimberly McGuire Date: Thu, 16 Nov 2023 13:27:13 +0100 Subject: [PATCH 017/162] add usb permission and update instructions Should fix #50 --- docs2/installation.rst | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/docs2/installation.rst b/docs2/installation.rst index 9cc72c428..404f9f20a 100644 --- a/docs2/installation.rst +++ b/docs2/installation.rst @@ -56,7 +56,11 @@ First Installation .. note:: symlink-install allows you to edit Python and config files without running `colcon build` every time. -5. Set up software-in-the-loop simulation (optional) +5. Set up USB permissions for crazyradio + + For the crazyradio, you need to setup usb rules in order to communicate with the Crazyflie. Find the instructions for that here `in Bitcraze's USB permission guide for Linux `_. + +6. Set up software-in-the-loop simulation (optional) This currently requires cloning the Crazyflie firmware and building the Python bindings manually. In a separate folder (not part of your ROS 2 workspace!), From 890e7ceb8e1b2c779ec78c64a3c1a3497eb04deb Mon Sep 17 00:00:00 2001 From: Kimberly McGuire Date: Thu, 16 Nov 2023 13:41:15 +0100 Subject: [PATCH 018/162] Update installation.rst --- docs2/installation.rst | 17 ++++++++++++++--- 1 file changed, 14 insertions(+), 3 deletions(-) diff --git a/docs2/installation.rst b/docs2/installation.rst index 404f9f20a..9ed2813d2 100644 --- a/docs2/installation.rst +++ b/docs2/installation.rst @@ -56,11 +56,22 @@ First Installation .. note:: symlink-install allows you to edit Python and config files without running `colcon build` every time. -5. Set up USB permissions for crazyradio +5. Set up Crazyradio For the crazyradio, you need to setup usb rules in order to communicate with the Crazyflie. Find the instructions for that here `in Bitcraze's USB permission guide for Linux `_. - -6. Set up software-in-the-loop simulation (optional) + + You will also need to update the crazyradio firmware to the latest development branch to be able to use all features. For Crazyradio PA (1), `follow these instructions `_. For Crazyradio 2, follow `these instuctions to build the firmware `_ and `these instuctions to flash it `_. + +6. Update the crazyflies + + If this is the first time handling crazyflies it is always good to start with `Bitcraze's getting started guide `_. + + You can update each crazyflie firmware to the latest release via `these instructions of the Bitcraze Crazyflie client `_ . + + While you are at it, make sure that each crazyflie have an unique radio address which you can change in `the client via these instructions `_ . + +7. Set up software-in-the-loop simulation (optional) This currently requires cloning the Crazyflie firmware and building the Python bindings manually. In a separate folder (not part of your ROS 2 workspace!), From 316eb23632586d13d8b735d0c5b27a0505bb13b4 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Thu, 16 Nov 2023 14:32:35 +0100 Subject: [PATCH 019/162] fix uppercase error and lost file --- crazyflie_examples/launch/multiranger_nav2_launch.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/crazyflie_examples/launch/multiranger_nav2_launch.py b/crazyflie_examples/launch/multiranger_nav2_launch.py index 9e1421325..33d834242 100644 --- a/crazyflie_examples/launch/multiranger_nav2_launch.py +++ b/crazyflie_examples/launch/multiranger_nav2_launch.py @@ -67,11 +67,11 @@ def generate_launch_description(): os.path.join(bringup_launch_dir, 'bringup_launch.py')), launch_arguments={ 'slam': 'False', - 'use_sim_time': 'false', + 'use_sim_time': 'False', 'map': cf_examples_dir + '/data/' + map_name + '.yaml', - 'params_file': os.path.join(cf_examples_dir, 'nav2_params.yaml'), - 'autostart': 'true', - 'use_composition': 'true', + 'params_file': os.path.join(cf_examples_dir, 'config/nav2_params.yaml'), + 'autostart': 'True', + 'use_composition': 'True', 'transform_publish_period': '0.02' }.items() ), From c111710eccbdbaf44f93e45edfae8535e40c0e31 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Thu, 16 Nov 2023 15:26:19 +0100 Subject: [PATCH 020/162] add simple mapper --- crazyflie_examples/CMakeLists.txt | 6 + .../launch/multiranger_simple_mapper.py | 46 +++++ crazyflie_examples/scripts/simple_mapper.py | 165 ++++++++++++++++++ 3 files changed, 217 insertions(+) create mode 100644 crazyflie_examples/launch/multiranger_simple_mapper.py create mode 100644 crazyflie_examples/scripts/simple_mapper.py diff --git a/crazyflie_examples/CMakeLists.txt b/crazyflie_examples/CMakeLists.txt index 0c70c94d2..68ed05566 100644 --- a/crazyflie_examples/CMakeLists.txt +++ b/crazyflie_examples/CMakeLists.txt @@ -32,4 +32,10 @@ if(BUILD_TESTING) endforeach() endif() +# Install Python executables +install(PROGRAMS + scripts/simple_mapper.py + DESTINATION lib/${PROJECT_NAME} +) + ament_package() diff --git a/crazyflie_examples/launch/multiranger_simple_mapper.py b/crazyflie_examples/launch/multiranger_simple_mapper.py new file mode 100644 index 000000000..1b7b56d3a --- /dev/null +++ b/crazyflie_examples/launch/multiranger_simple_mapper.py @@ -0,0 +1,46 @@ +import os + +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch_ros.actions import Node +import yaml + + +def generate_launch_description(): + # load crazyflies + crazyflies_yaml = os.path.join( + get_package_share_directory('crazyflie'), + 'config', + 'crazyflies.yaml') + + with open(crazyflies_yaml, 'r') as ymlfile: + crazyflies = yaml.safe_load(ymlfile) + + server_params = crazyflies + + cf_examples_dir = get_package_share_directory('crazyflie_examples') + bringup_dir = get_package_share_directory('nav2_bringup') + bringup_launch_dir = os.path.join(bringup_dir, 'launch') + map_name = 'map' + + return LaunchDescription([ + Node( + package='crazyflie', + executable='crazyflie_server.py', + name='crazyflie_server', + output='screen', + parameters=[{'world_tf_name': 'map'}, + server_params], + ), + Node( + package='crazyflie', + executable='vel_mux.py', + name='vel_mux', + output='screen', + parameters=[{'hover_height': 0.3}, + {'incoming_twist_topic': '/cmd_vel'}, + {'robot_prefix': '/cf231'}] + ) + ]) diff --git a/crazyflie_examples/scripts/simple_mapper.py b/crazyflie_examples/scripts/simple_mapper.py new file mode 100644 index 000000000..dc5f9791b --- /dev/null +++ b/crazyflie_examples/scripts/simple_mapper.py @@ -0,0 +1,165 @@ +""" This simple mapper is loosely based on both the bitcraze cflib point cloud example + https://github.com/bitcraze/crazyflie-lib-python/blob/master/examples/multiranger/multiranger_pointcloud.py + and the webots epuck simple mapper example: + https://github.com/cyberbotics/webots_ros2 + + Originally from https://github.com/knmcguire/crazyflie_ros2_experimental/ + """ + +import rclpy +from rclpy.node import Node +from rclpy.qos import DurabilityPolicy, HistoryPolicy, QoSProfile + +from nav_msgs.msg import Odometry +from sensor_msgs.msg import LaserScan +from nav_msgs.msg import OccupancyGrid +from geometry_msgs.msg import TransformStamped +from tf2_ros import StaticTransformBroadcaster + +import tf_transformations +import math +import numpy as np +from bresenham import bresenham + +GLOBAL_SIZE_X = 20.0 +GLOBAL_SIZE_Y = 20.0 +MAP_RES = 0.1 + +class SimpleMapper(Node): + def __init__(self): + super().__init__('simple_mapper') + self.odom_subscriber = self.create_subscription(Odometry, '/odom', self.odom_subcribe_callback, 10) + self.ranges_subscriber = self.create_subscription(LaserScan, '/scan', self.scan_subsribe_callback, 10) + self.position = [0.0, 0.0, 0.0] + self.angles = [0.0, 0.0, 0.0] + self.ranges = [0.0, 0.0, 0.0, 0.0] + self.range_max = 3.5 + + self.tfbr = StaticTransformBroadcaster(self) + t_map = TransformStamped() + t_map.header.stamp = self.get_clock().now().to_msg() + t_map.header.frame_id = 'map' + t_map.child_frame_id = 'odom' + t_map.transform.translation.x = 0.0 + t_map.transform.translation.y = 0.0 + t_map.transform.translation.z = 0.0 + self.tfbr.sendTransform(t_map) + + self.position_update = False + + self.map = [-1] * int(GLOBAL_SIZE_X / MAP_RES) * int(GLOBAL_SIZE_Y / MAP_RES) + self.map_publisher = self.create_publisher(OccupancyGrid, '/map', + qos_profile=QoSProfile( depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL, history=HistoryPolicy.KEEP_LAST,)) + + def odom_subcribe_callback(self, msg): + self.position[0] = msg.pose.pose.position.x + self.position[1] = msg.pose.pose.position.y + self.position[2] = msg.pose.pose.position.z + q = msg.pose.pose.orientation + euler = tf_transformations.euler_from_quaternion([q.x, q.y, q.z, q.w]) + self.angles[0] = euler[0] + self.angles[1] = euler[1] + self.angles[2] = euler[2] + self.position_update = True + + def scan_subsribe_callback(self, msg): + self.ranges = msg.ranges + self.range_max = msg.range_max + data = self.rotate_and_create_points() + + points_x = [] + points_y = [] + # + if self.position_update is False: + return + for i in range(len(data)): + point_x = int((data[i][0] - GLOBAL_SIZE_X / 2.0)/ MAP_RES ) + point_y = int((data[i][1] - GLOBAL_SIZE_Y / 2.0)/ MAP_RES ) + points_x.append(point_x) + points_y.append(point_y) + position_x_map = int((self.position[0] - GLOBAL_SIZE_X / 2.0)/ MAP_RES ) + position_y_map = int((self.position[1] - GLOBAL_SIZE_Y / 2.0)/ MAP_RES ) + for line_x, line_y in bresenham(position_x_map, position_y_map, point_x, point_y): + self.map[line_y * int(GLOBAL_SIZE_X / MAP_RES) + line_x] = 0 + self.map[point_y * int(GLOBAL_SIZE_X / MAP_RES) + point_x] = 100 + + msg = OccupancyGrid() + msg.header.stamp = self.get_clock().now().to_msg() + msg.header.frame_id = 'map' + msg.info.resolution = MAP_RES + msg.info.width = int(GLOBAL_SIZE_X / MAP_RES) + msg.info.height = int(GLOBAL_SIZE_Y / MAP_RES) + msg.info.origin.position.x = - GLOBAL_SIZE_X / 2.0 + msg.info.origin.position.y = - GLOBAL_SIZE_Y / 2.0 + msg.data = self.map + self.map_publisher.publish(msg) + + def rotate_and_create_points(self): + data = [] + o = self.position + roll = self.angles[0] + pitch = self.angles[1] + yaw = self.angles[2] + r_back = self.ranges[0] + r_left = self.ranges[1] + r_front = self.ranges[2] + r_right = self.ranges[3] + + if (r_left < self.range_max and r_left != 0.0): + left = [o[0], o[1] + r_left, o[2]] + data.append(self.rot(roll, pitch, yaw, o, left)) + + if (r_right < self.range_max and r_right != 0.0): + right = [o[0], o[1] - r_right, o[2]] + data.append(self.rot(roll, pitch, yaw, o, right)) + + if (r_front < self.range_max and r_front != 0.0): + front = [o[0] + r_front, o[1], o[2]] + data.append(self.rot(roll, pitch, yaw, o, front)) + + if (r_back < self.range_max and r_back != 0.0): + back = [o[0] - r_back, o[1], o[2]] + data.append(self.rot(roll, pitch, yaw, o, back)) + + return data + + def rot(self, roll, pitch, yaw, origin, point): + cosr = math.cos((roll)) + cosp = math.cos((pitch)) + cosy = math.cos((yaw)) + + sinr = math.sin((roll)) + sinp = math.sin((pitch)) + siny = math.sin((yaw)) + + roty = np.array([[cosy, -siny, 0], + [siny, cosy, 0], + [0, 0, 1]]) + + rotp = np.array([[cosp, 0, sinp], + [0, 1, 0], + [-sinp, 0, cosp]]) + + rotr = np.array([[1, 0, 0], + [0, cosr, -sinr], + [0, sinr, cosr]]) + + rotFirst = np.dot(rotr, rotp) + + rot = np.array(np.dot(rotFirst, roty)) + + tmp = np.subtract(point, origin) + tmp2 = np.dot(rot, tmp) + return np.add(tmp2, origin) + +def main(args=None): + + rclpy.init(args=args) + simple_mapper = SimpleMapper() + rclpy.spin(simple_mapper) + rclpy.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() \ No newline at end of file From ae7db66b37e73f27364d49bc0b7ff8de6ca45212 Mon Sep 17 00:00:00 2001 From: Kimberly McGuire Date: Thu, 16 Nov 2023 16:51:50 +0100 Subject: [PATCH 021/162] Delete pc_permissions.sh --- pc_permissions.sh | 15 --------------- 1 file changed, 15 deletions(-) delete mode 100755 pc_permissions.sh diff --git a/pc_permissions.sh b/pc_permissions.sh deleted file mode 100755 index 1b225474d..000000000 --- a/pc_permissions.sh +++ /dev/null @@ -1,15 +0,0 @@ -#!/bin/bash - -# Sets PC permissions - -sudo groupadd plugdev -sudo usermod -a -G plugdev $USER - -echo -e "# Crazyradio (normal operation) \nSUBSYSTEM==\"usb\", ATTRS{idVendor}==\"1915\", ATTRS{idProduct}==\"7777\", MODE=\"0664\", GROUP=\"plugdev\" \n# Bootloader \nSUBSYSTEM==\"usb\", ATTRS{idVendor}==\"1915\", ATTRS{idProduct}==\"0101\", MODE=\"0664\", GROUP=\"plugdev\"" | sudo tee /etc/udev/rules.d/99-crazyradio.rules - - -echo -e "SUBSYSTEM==\"usb\", ATTRS{idVendor}==\"0483\", ATTRS{idProduct}==\"5740\", MODE=\"0664\", GROUP=\"plugdev\"" | sudo tee /etc/udev/rules.d/99-crazyflie.rules - -sudo udevadm control --reload-rules && udevadm trigger - - From 7e3328cc9ed77e383ff0d7bc70ad51ab2cfa8642 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Thu, 16 Nov 2023 16:58:09 +0100 Subject: [PATCH 022/162] add internal link --- docs2/howto.rst | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/docs2/howto.rst b/docs2/howto.rst index 274f52374..7c0ed6bdf 100644 --- a/docs2/howto.rst +++ b/docs2/howto.rst @@ -103,6 +103,8 @@ Then execute: colcon test --event-handlers=console_cohesion+ --return-code-on-test-failure --packages-select crazyflie_py +.. _Collision Avoidance: + Collision Avoidance ------------------- @@ -132,4 +134,4 @@ Generate Trajectories Crazyswarm2 supports polynomial trajectories (8th order). These can be generated from waypoints, waypoint/time pairs, or optimization. Useful tools are available at https://github.com/whoenig/uav_trajectories, including scripts to visualize the resulting trajectories. -For the multi-robot case, there is no easy to-use library, yet. One can use collision avoidance (see HowTo) or preplan trajectories using https://github.com/IMRCLab/db-CBS or https://github.com/mjdebord/smoothener/tree/cylinders. +For the multi-robot case, there is no easy to-use library, yet. One can use collision avoidance (see :ref:`Collision Avoidance`) or preplan trajectories using https://github.com/IMRCLab/db-CBS or https://github.com/mjdebord/smoothener/tree/cylinders. From fed4474b12271857f6069c7cc2e6a57ebed24aab Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Thu, 16 Nov 2023 17:16:49 +0100 Subject: [PATCH 023/162] fix doc build --- docs2/installation.rst | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/docs2/installation.rst b/docs2/installation.rst index 9ed2813d2..325bb73f0 100644 --- a/docs2/installation.rst +++ b/docs2/installation.rst @@ -64,8 +64,7 @@ First Installation 6. Update the crazyflies - If this is the first time handling crazyflies it is always good to start with `Bitcraze's getting started guide `_. + If this is the first time handling crazyflies it is always good to start with `Bitcraze's getting started guide `_. You can update each crazyflie firmware to the latest release via `these instructions of the Bitcraze Crazyflie client `_ . From 94c61d4ecee4c5601f19f2da8fcb4c3c17a8e4ff Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Thu, 16 Nov 2023 17:22:28 +0100 Subject: [PATCH 024/162] Run docs CI on PRs; deploy only in main --- .github/workflows/ci-docs2.yml | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/.github/workflows/ci-docs2.yml b/.github/workflows/ci-docs2.yml index 3884a8f19..37521f765 100644 --- a/.github/workflows/ci-docs2.yml +++ b/.github/workflows/ci-docs2.yml @@ -1,8 +1,10 @@ -name: Docs deploy +name: Docs on: push: branches: [ main ] + pull_request: + branches: [ main ] jobs: build: @@ -33,6 +35,7 @@ jobs: touch docs2/_build/html/.nojekyll - name: Deploy + if: github.ref == 'refs/heads/main' uses: JamesIves/github-pages-deploy-action@v4 with: folder: docs2/_build/html # The folder the action should deploy. From 0ef00381c7a434a3f5d9a038c0c2faccdaa5e4b1 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Thu, 16 Nov 2023 17:38:08 +0100 Subject: [PATCH 025/162] fix flake8 errors --- crazyflie_examples/launch/keyboard_velmux_launch.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/crazyflie_examples/launch/keyboard_velmux_launch.py b/crazyflie_examples/launch/keyboard_velmux_launch.py index fa06c87ba..8fee2f797 100644 --- a/crazyflie_examples/launch/keyboard_velmux_launch.py +++ b/crazyflie_examples/launch/keyboard_velmux_launch.py @@ -31,8 +31,8 @@ def generate_launch_description(): executable='vel_mux.py', name='vel_mux', output='screen', - parameters=[{"hover_height": 0.3}, - {"incoming_twist_topic": "/cmd_vel"}, - {"robot_prefix": "/cf231"}] + parameters=[{'hover_height': 0.3}, + {'incoming_twist_topic': '/cmd_vel'}, + {'robot_prefix': '/cf231'}] ), ]) From 4d616a4897cf218ef42b2e6b18fcdab9c94779ce Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Fri, 17 Nov 2023 14:25:20 +0100 Subject: [PATCH 026/162] update submodule --- crazyflie/deps/crazyflie_tools | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/crazyflie/deps/crazyflie_tools b/crazyflie/deps/crazyflie_tools index c7f3b6c89..1efd3788f 160000 --- a/crazyflie/deps/crazyflie_tools +++ b/crazyflie/deps/crazyflie_tools @@ -1 +1 @@ -Subproject commit c7f3b6c895be149073758825383bdfd9d31f6679 +Subproject commit 1efd3788f5bf59e0fa3da2e4d2bc5cd7bee5b0fc From 487f7e7eeb03d3a9208177afde75b36f16a31502 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Mon, 20 Nov 2023 13:23:43 +0100 Subject: [PATCH 027/162] add trajectory cflib --- crazyflie/scripts/crazyflie_server.py | 70 ++++++++++++++++++++++++++- 1 file changed, 68 insertions(+), 2 deletions(-) diff --git a/crazyflie/scripts/crazyflie_server.py b/crazyflie/scripts/crazyflie_server.py index b52bb6253..a47c9c896 100755 --- a/crazyflie/scripts/crazyflie_server.py +++ b/crazyflie/scripts/crazyflie_server.py @@ -20,6 +20,8 @@ from cflib.crazyflie.swarm import CachedCfFactory from cflib.crazyflie.swarm import Swarm from cflib.crazyflie.log import LogConfig +from cflib.crazyflie.mem import MemoryElement +from cflib.crazyflie.mem import Poly4D from crazyflie_interfaces.srv import Takeoff, Land, GoTo, RemoveLogging, AddLogging from crazyflie_interfaces.srv import UploadTrajectory, StartTrajectory, NotifySetpointsStop @@ -797,11 +799,75 @@ def _notify_setpoints_stop_callback(self, request, response, uri="all"): return response def _upload_trajectory_callback(self, request, response, uri="all"): - self.get_logger().info("Notify trajectory not yet implemented") + + id = request.trajectory_id + offset = request.piece_offset + size = request.pieces.size() + total_duration = 0 + self.get_logger().info("upload_trajectory(id=%d,offset=%d, size=%d)"% ( + id, + offset, + size, + )) + + trajectory = [] + for i in range(size): + piece = request.pieces[i] + px = piece.poly_x + py = piece.poly_y + pz = piece.poly_z + pyaw = piece.poly_yaw + duration = request.duration.sec + trajectory.append(Poly4D(duration, px, py, pz, pyaw )) + total_duration = total_duration + duration + + if uri == "all": + upload_success_all = True + for link_uri in self.uris: + trajectory_mem = self.swarm._cfs[link_uri].cf.mem.get_mems(MemoryElement.TYPE_TRAJ)[id] + trajectory_mem.trajectory = trajectory + upload_result = trajectory_mem.write_data_sync() + if not upload_result: + self.get_logger().info(f"{link_uri}: Upload failed") + upload_success_all = False + else: + self.swarm._cfs[link_uri].cf.high_level_commander.define_trajectory(id, offset, len(trajectory)) + if upload_success_all is False: + response.success = False + return response + else: + trajectory_mem = self.swarm._cfs[uri].cf.mem.get_mems(MemoryElement.TYPE_TRAJ)[id] + trajectory_mem.trajectory = trajectory + upload_result = trajectory_mem.write_data_sync() + if not upload_result: + self.get_logger().info(f"{uri}: Upload failed") + response.success = False + return response + self.swarm._cfs[uri].cf.high_level_commander.define_trajectory(id, offset, len(trajectory)) + return response def _start_trajectory_callback(self, request, response, uri="all"): - self.get_logger().info("Start trajectory not yet implemented") + + id = request.trajectory_id + ts = request.timescale + rel = request.relative + rev = request.reversed + gm = request.group_mask + + self.get_logger().info("start_trajectory(id=%d,timescale=%f,relative=%d, reversed=%d, group_mask=%d)"% ( + id, + ts, + rel, + rev, + gm + )) + if uri == "all": + for link_uri in self.uris: + self.swarm._cfs[link_uri].cf.commander.start_trajectory(id, ts, rel, rev, gm) + else: + self.swarm._cfs[uri].cf.commander.start_trajectory(id, ts, rel, rev, gm) + return response def _poses_changed(self, msg): From 0a37e57049f1cd2cedd5089868108915bf664167 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Mon, 20 Nov 2023 13:55:41 +0100 Subject: [PATCH 028/162] fixed error messaging --- crazyflie/scripts/crazyflie_server.py | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/crazyflie/scripts/crazyflie_server.py b/crazyflie/scripts/crazyflie_server.py index a47c9c896..138dc6bf8 100755 --- a/crazyflie/scripts/crazyflie_server.py +++ b/crazyflie/scripts/crazyflie_server.py @@ -802,22 +802,22 @@ def _upload_trajectory_callback(self, request, response, uri="all"): id = request.trajectory_id offset = request.piece_offset - size = request.pieces.size() + lenght = len(request.pieces) total_duration = 0 - self.get_logger().info("upload_trajectory(id=%d,offset=%d, size=%d)"% ( + self.get_logger().info("upload_trajectory(id=%d,offset=%d, lenght=%d)"% ( id, offset, - size, + lenght, )) trajectory = [] - for i in range(size): + for i in range(lenght): piece = request.pieces[i] - px = piece.poly_x - py = piece.poly_y - pz = piece.poly_z - pyaw = piece.poly_yaw - duration = request.duration.sec + px = Poly4D.Poly(piece.poly_x) + py = Poly4D.Poly(piece.poly_y) + pz = Poly4D.Poly(piece.poly_z) + pyaw = Poly4D.Poly(piece.poly_yaw) + duration = piece.duration.sec trajectory.append(Poly4D(duration, px, py, pz, pyaw )) total_duration = total_duration + duration @@ -864,9 +864,9 @@ def _start_trajectory_callback(self, request, response, uri="all"): )) if uri == "all": for link_uri in self.uris: - self.swarm._cfs[link_uri].cf.commander.start_trajectory(id, ts, rel, rev, gm) + self.swarm._cfs[link_uri].cf.high_level_commander.start_trajectory(id, ts, rel, rev, gm) else: - self.swarm._cfs[uri].cf.commander.start_trajectory(id, ts, rel, rev, gm) + self.swarm._cfs[uri].cf.high_level_commander.start_trajectory(id, ts, rel, rev, gm) return response From fb11fa03fc79e766e8eacdfc2c3bcca97f8040bc Mon Sep 17 00:00:00 2001 From: knmcguire Date: Mon, 20 Nov 2023 14:00:06 +0100 Subject: [PATCH 029/162] add launch file --- .../multiranger_simple_mapper_launch.py | 44 +++++++++++++++++++ 1 file changed, 44 insertions(+) create mode 100644 crazyflie_examples/launch/multiranger_simple_mapper_launch.py diff --git a/crazyflie_examples/launch/multiranger_simple_mapper_launch.py b/crazyflie_examples/launch/multiranger_simple_mapper_launch.py new file mode 100644 index 000000000..f046d8996 --- /dev/null +++ b/crazyflie_examples/launch/multiranger_simple_mapper_launch.py @@ -0,0 +1,44 @@ +import os + +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch_ros.actions import Node +import yaml + + +def generate_launch_description(): + # load crazyflies + crazyflies_yaml = os.path.join( + get_package_share_directory('crazyflie'), + 'config', + 'crazyflies.yaml') + + with open(crazyflies_yaml, 'r') as ymlfile: + crazyflies = yaml.safe_load(ymlfile) + + server_params = crazyflies + + return LaunchDescription([ + Node( + package='crazyflie', + executable='crazyflie_server.py', + name='crazyflie_server', + output='screen', + parameters=[server_params], + ), + Node( + package='crazyflie', + executable='vel_mux.py', + name='vel_mux', + output='screen', + parameters=[{'hover_height': 0.3}, + {'incoming_twist_topic': '/cmd_vel'}, + {'robot_prefix': '/cf1'}] + ), + #Node( + # package='crazyflie_examples', + # executable='simple_mapper.py', + # name='simple mapper', + # output='screen' + #), + ]) From 8468108f4b75bc29ce47b6634362239f296b026a Mon Sep 17 00:00:00 2001 From: knmcguire Date: Mon, 20 Nov 2023 14:39:32 +0100 Subject: [PATCH 030/162] moved simple mapper to crazyflie scripts --- crazyflie/CMakeLists.txt | 1 + .../scripts/simple_mapper.py | 9 +++- crazyflie_examples/CMakeLists.txt | 6 --- .../launch/multiranger_simple_mapper.py | 46 ------------------- .../multiranger_simple_mapper_launch.py | 12 ++--- 5 files changed, 14 insertions(+), 60 deletions(-) rename {crazyflie_examples => crazyflie}/scripts/simple_mapper.py (95%) mode change 100644 => 100755 delete mode 100644 crazyflie_examples/launch/multiranger_simple_mapper.py diff --git a/crazyflie/CMakeLists.txt b/crazyflie/CMakeLists.txt index ca4dc3764..828cd9a44 100644 --- a/crazyflie/CMakeLists.txt +++ b/crazyflie/CMakeLists.txt @@ -106,6 +106,7 @@ install(PROGRAMS scripts/chooser.py scripts/vel_mux.py scripts/cfmult.py + scripts/simple_mapper.py DESTINATION lib/${PROJECT_NAME} ) diff --git a/crazyflie_examples/scripts/simple_mapper.py b/crazyflie/scripts/simple_mapper.py old mode 100644 new mode 100755 similarity index 95% rename from crazyflie_examples/scripts/simple_mapper.py rename to crazyflie/scripts/simple_mapper.py index dc5f9791b..967bd3d93 --- a/crazyflie_examples/scripts/simple_mapper.py +++ b/crazyflie/scripts/simple_mapper.py @@ -1,3 +1,5 @@ +#!/usr/bin/env python3 + """ This simple mapper is loosely based on both the bitcraze cflib point cloud example https://github.com/bitcraze/crazyflie-lib-python/blob/master/examples/multiranger/multiranger_pointcloud.py and the webots epuck simple mapper example: @@ -28,8 +30,8 @@ class SimpleMapper(Node): def __init__(self): super().__init__('simple_mapper') - self.odom_subscriber = self.create_subscription(Odometry, '/odom', self.odom_subcribe_callback, 10) - self.ranges_subscriber = self.create_subscription(LaserScan, '/scan', self.scan_subsribe_callback, 10) + self.odom_subscriber = self.create_subscription(Odometry, '/cf231/odom', self.odom_subcribe_callback, 10) + self.ranges_subscriber = self.create_subscription(LaserScan, '/cf231/scan', self.scan_subsribe_callback, 10) self.position = [0.0, 0.0, 0.0] self.angles = [0.0, 0.0, 0.0] self.ranges = [0.0, 0.0, 0.0, 0.0] @@ -51,6 +53,9 @@ def __init__(self): self.map_publisher = self.create_publisher(OccupancyGrid, '/map', qos_profile=QoSProfile( depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL, history=HistoryPolicy.KEEP_LAST,)) + self.get_logger().info(f"Simple mapper set for crazyflie"+ + f" using the odom and scan topic") + def odom_subcribe_callback(self, msg): self.position[0] = msg.pose.pose.position.x self.position[1] = msg.pose.pose.position.y diff --git a/crazyflie_examples/CMakeLists.txt b/crazyflie_examples/CMakeLists.txt index 68ed05566..0c70c94d2 100644 --- a/crazyflie_examples/CMakeLists.txt +++ b/crazyflie_examples/CMakeLists.txt @@ -32,10 +32,4 @@ if(BUILD_TESTING) endforeach() endif() -# Install Python executables -install(PROGRAMS - scripts/simple_mapper.py - DESTINATION lib/${PROJECT_NAME} -) - ament_package() diff --git a/crazyflie_examples/launch/multiranger_simple_mapper.py b/crazyflie_examples/launch/multiranger_simple_mapper.py deleted file mode 100644 index 1b7b56d3a..000000000 --- a/crazyflie_examples/launch/multiranger_simple_mapper.py +++ /dev/null @@ -1,46 +0,0 @@ -import os - -from ament_index_python.packages import get_package_share_directory -from launch import LaunchDescription -from launch.actions import IncludeLaunchDescription -from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch_ros.actions import Node -import yaml - - -def generate_launch_description(): - # load crazyflies - crazyflies_yaml = os.path.join( - get_package_share_directory('crazyflie'), - 'config', - 'crazyflies.yaml') - - with open(crazyflies_yaml, 'r') as ymlfile: - crazyflies = yaml.safe_load(ymlfile) - - server_params = crazyflies - - cf_examples_dir = get_package_share_directory('crazyflie_examples') - bringup_dir = get_package_share_directory('nav2_bringup') - bringup_launch_dir = os.path.join(bringup_dir, 'launch') - map_name = 'map' - - return LaunchDescription([ - Node( - package='crazyflie', - executable='crazyflie_server.py', - name='crazyflie_server', - output='screen', - parameters=[{'world_tf_name': 'map'}, - server_params], - ), - Node( - package='crazyflie', - executable='vel_mux.py', - name='vel_mux', - output='screen', - parameters=[{'hover_height': 0.3}, - {'incoming_twist_topic': '/cmd_vel'}, - {'robot_prefix': '/cf231'}] - ) - ]) diff --git a/crazyflie_examples/launch/multiranger_simple_mapper_launch.py b/crazyflie_examples/launch/multiranger_simple_mapper_launch.py index f046d8996..97fc12ba7 100644 --- a/crazyflie_examples/launch/multiranger_simple_mapper_launch.py +++ b/crazyflie_examples/launch/multiranger_simple_mapper_launch.py @@ -35,10 +35,10 @@ def generate_launch_description(): {'incoming_twist_topic': '/cmd_vel'}, {'robot_prefix': '/cf1'}] ), - #Node( - # package='crazyflie_examples', - # executable='simple_mapper.py', - # name='simple mapper', - # output='screen' - #), + Node( + package='crazyflie', + executable='simple_mapper.py', + name='simple_mapper', + output='screen' + ), ]) From 1c81737f10c4c8c65d88a2253dfc12acf138ca22 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Mon, 20 Nov 2023 14:49:33 +0100 Subject: [PATCH 031/162] add robot prefix parameters --- crazyflie/scripts/simple_mapper.py | 11 +++++++---- crazyflie/scripts/vel_mux.py | 2 +- crazyflie_examples/launch/keyboard_velmux_launch.py | 4 +++- .../launch/multiranger_simple_mapper_launch.py | 8 ++++++-- 4 files changed, 17 insertions(+), 8 deletions(-) diff --git a/crazyflie/scripts/simple_mapper.py b/crazyflie/scripts/simple_mapper.py index 967bd3d93..db7723850 100755 --- a/crazyflie/scripts/simple_mapper.py +++ b/crazyflie/scripts/simple_mapper.py @@ -30,8 +30,11 @@ class SimpleMapper(Node): def __init__(self): super().__init__('simple_mapper') - self.odom_subscriber = self.create_subscription(Odometry, '/cf231/odom', self.odom_subcribe_callback, 10) - self.ranges_subscriber = self.create_subscription(LaserScan, '/cf231/scan', self.scan_subsribe_callback, 10) + self.declare_parameter('robot_prefix', '/cf231') + robot_prefix = self.get_parameter('robot_prefix').value + + self.odom_subscriber = self.create_subscription(Odometry, robot_prefix + '/odom', self.odom_subcribe_callback, 10) + self.ranges_subscriber = self.create_subscription(LaserScan, robot_prefix + '/scan', self.scan_subsribe_callback, 10) self.position = [0.0, 0.0, 0.0] self.angles = [0.0, 0.0, 0.0] self.ranges = [0.0, 0.0, 0.0, 0.0] @@ -50,10 +53,10 @@ def __init__(self): self.position_update = False self.map = [-1] * int(GLOBAL_SIZE_X / MAP_RES) * int(GLOBAL_SIZE_Y / MAP_RES) - self.map_publisher = self.create_publisher(OccupancyGrid, '/map', + self.map_publisher = self.create_publisher(OccupancyGrid, robot_prefix + '/map', qos_profile=QoSProfile( depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL, history=HistoryPolicy.KEEP_LAST,)) - self.get_logger().info(f"Simple mapper set for crazyflie"+ + self.get_logger().info(f"Simple mapper set for crazyflie "+ robot_prefix + f" using the odom and scan topic") def odom_subcribe_callback(self, msg): diff --git a/crazyflie/scripts/vel_mux.py b/crazyflie/scripts/vel_mux.py index f1155ba1c..a9809f6c1 100755 --- a/crazyflie/scripts/vel_mux.py +++ b/crazyflie/scripts/vel_mux.py @@ -20,7 +20,7 @@ class VelMux(Node): def __init__(self): super().__init__('vel_mux') self.declare_parameter('hover_height', 0.5) - self.declare_parameter('robot_prefix', '/cf1') + self.declare_parameter('robot_prefix', '/cf231') self.declare_parameter('incoming_twist_topic', '/cmd_vel') self.hover_height = self.get_parameter('hover_height').value diff --git a/crazyflie_examples/launch/keyboard_velmux_launch.py b/crazyflie_examples/launch/keyboard_velmux_launch.py index 25d318a0b..241348aaa 100644 --- a/crazyflie_examples/launch/keyboard_velmux_launch.py +++ b/crazyflie_examples/launch/keyboard_velmux_launch.py @@ -18,6 +18,8 @@ def generate_launch_description(): server_params = crazyflies + crazyflie_name = '/cf231' + return LaunchDescription([ Node( package='crazyflie', @@ -33,6 +35,6 @@ def generate_launch_description(): output='screen', parameters=[{'hover_height': 0.3}, {'incoming_twist_topic': '/cmd_vel'}, - {'robot_prefix': '/cf1'}] + {'robot_prefix': crazyflie_name}] ), ]) diff --git a/crazyflie_examples/launch/multiranger_simple_mapper_launch.py b/crazyflie_examples/launch/multiranger_simple_mapper_launch.py index 97fc12ba7..0f850410b 100644 --- a/crazyflie_examples/launch/multiranger_simple_mapper_launch.py +++ b/crazyflie_examples/launch/multiranger_simple_mapper_launch.py @@ -18,6 +18,8 @@ def generate_launch_description(): server_params = crazyflies + crazyflie_name = '/cf231' + return LaunchDescription([ Node( package='crazyflie', @@ -33,12 +35,14 @@ def generate_launch_description(): output='screen', parameters=[{'hover_height': 0.3}, {'incoming_twist_topic': '/cmd_vel'}, - {'robot_prefix': '/cf1'}] + {'robot_prefix': crazyflie_name}] ), Node( package='crazyflie', executable='simple_mapper.py', name='simple_mapper', - output='screen' + output='screen', + parameters=[ + {'robot_prefix': crazyflie_name}] ), ]) From ed35c8c0fcf9524bcf9a45af325ee5f92d78a548 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Mon, 20 Nov 2023 14:52:13 +0100 Subject: [PATCH 032/162] revert velmux changes, will do later --- crazyflie/scripts/vel_mux.py | 2 +- crazyflie_examples/launch/keyboard_velmux_launch.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/crazyflie/scripts/vel_mux.py b/crazyflie/scripts/vel_mux.py index a9809f6c1..b89706ac5 100755 --- a/crazyflie/scripts/vel_mux.py +++ b/crazyflie/scripts/vel_mux.py @@ -20,7 +20,7 @@ class VelMux(Node): def __init__(self): super().__init__('vel_mux') self.declare_parameter('hover_height', 0.5) - self.declare_parameter('robot_prefix', '/cf231') + self.declare_parameter('robot_prefix', '/cf') self.declare_parameter('incoming_twist_topic', '/cmd_vel') self.hover_height = self.get_parameter('hover_height').value diff --git a/crazyflie_examples/launch/keyboard_velmux_launch.py b/crazyflie_examples/launch/keyboard_velmux_launch.py index 241348aaa..06b395ad4 100644 --- a/crazyflie_examples/launch/keyboard_velmux_launch.py +++ b/crazyflie_examples/launch/keyboard_velmux_launch.py @@ -35,6 +35,6 @@ def generate_launch_description(): output='screen', parameters=[{'hover_height': 0.3}, {'incoming_twist_topic': '/cmd_vel'}, - {'robot_prefix': crazyflie_name}] + {'robot_prefix': '/cf1'}] ), ]) From 7b1f1a3143498e5c55bfad0c318d02c9edcb82a0 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Tue, 21 Nov 2023 13:42:24 +0100 Subject: [PATCH 033/162] fixed duration issue --- crazyflie/scripts/crazyflie_server.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/crazyflie/scripts/crazyflie_server.py b/crazyflie/scripts/crazyflie_server.py index 138dc6bf8..7f569e0bd 100755 --- a/crazyflie/scripts/crazyflie_server.py +++ b/crazyflie/scripts/crazyflie_server.py @@ -817,7 +817,7 @@ def _upload_trajectory_callback(self, request, response, uri="all"): py = Poly4D.Poly(piece.poly_y) pz = Poly4D.Poly(piece.poly_z) pyaw = Poly4D.Poly(piece.poly_yaw) - duration = piece.duration.sec + duration = float(piece.duration.sec) + float(piece.duration.nanosec)/1e9 trajectory.append(Poly4D(duration, px, py, pz, pyaw )) total_duration = total_duration + duration From ca6152a8d71f78c228f56e7aba1dd39d8c41b079 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Tue, 21 Nov 2023 13:43:53 +0100 Subject: [PATCH 034/162] update overview --- docs2/overview.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs2/overview.rst b/docs2/overview.rst index 7383949ee..655afd9c6 100644 --- a/docs2/overview.rst +++ b/docs2/overview.rst @@ -87,7 +87,7 @@ Support functionality with backends +---------------------+---------+-----------+---------+ | - go_to | Yes | Yes | Yes | +---------------------+---------+-----------+---------+ -| - upload/start traj | Yes | No | Yes | +| - upload/start traj | Yes | Yes | Yes | +---------------------+---------+-----------+---------+ | Positioning System | +---------------------+---------+-----------+---------+ From 36cb38dc1f171a50fdb634121f6f9ea7a4f46201 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Tue, 21 Nov 2023 13:55:14 +0100 Subject: [PATCH 035/162] autopep8 format --- crazyflie/scripts/crazyflie_server.py | 186 +++++++++++++++----------- 1 file changed, 107 insertions(+), 79 deletions(-) diff --git a/crazyflie/scripts/crazyflie_server.py b/crazyflie/scripts/crazyflie_server.py index 7f569e0bd..448405256 100755 --- a/crazyflie/scripts/crazyflie_server.py +++ b/crazyflie/scripts/crazyflie_server.py @@ -54,6 +54,7 @@ "double": ParameterType.PARAMETER_DOUBLE, } + class CrazyflieServer(Node): def __init__(self): super().__init__( @@ -69,21 +70,21 @@ def __init__(self): self.cf_dict = {} self.uri_dict = {} self.type_dict = {} - + # Assign default topic types, variables and callbacks self.default_log_type = {"pose": PoseStamped, - "scan": LaserScan, - "odom": Odometry} + "scan": LaserScan, + "odom": Odometry} self.default_log_vars = {"pose": ['stateEstimate.x', 'stateEstimate.y', 'stateEstimate.z', - 'stabilizer.roll', 'stabilizer.pitch', 'stabilizer.yaw'], - "scan": ['range.front', 'range.left', 'range.back', 'range.right'], - "odom": ['stateEstimate.x', 'stateEstimate.y', 'stateEstimate.z', - 'stabilizer.yaw', 'stabilizer.roll', 'stabilizer.pitch', - 'kalman.statePX', 'kalman.statePY', 'kalman.statePZ', - 'gyro.z', 'gyro.x', 'gyro.y']} + 'stabilizer.roll', 'stabilizer.pitch', 'stabilizer.yaw'], + "scan": ['range.front', 'range.left', 'range.back', 'range.right'], + "odom": ['stateEstimate.x', 'stateEstimate.y', 'stateEstimate.z', + 'stabilizer.yaw', 'stabilizer.roll', 'stabilizer.pitch', + 'kalman.statePX', 'kalman.statePY', 'kalman.statePZ', + 'gyro.z', 'gyro.x', 'gyro.y']} self.default_log_fnc = {"pose": self._log_pose_data_callback, - "scan": self._log_scan_data_callback, - "odom": self._log_odom_data_callback} + "scan": self._log_scan_data_callback, + "odom": self._log_odom_data_callback} self.world_tf_name = "world" try: @@ -100,7 +101,8 @@ def __init__(self): if robot_data[crazyflie]["enabled"]: type_cf = robot_data[crazyflie]["type"] # do not include virtual objects - connection = self._ros_parameters['robot_types'][type_cf].get("connection", "crazyflie") + connection = self._ros_parameters['robot_types'][type_cf].get( + "connection", "crazyflie") if connection == "crazyflie": uri = robot_data[crazyflie]["uri"] self.uris.append(uri) @@ -153,7 +155,8 @@ def __init__(self): prefix = default_log_name topic_type = self.default_log_type[default_log_name] list_logvar = self.default_log_vars[default_log_name] - self._init_default_logblocks(prefix, link_uri, list_logvar, logging_enabled, topic_type) + self._init_default_logblocks( + prefix, link_uri, list_logvar, logging_enabled, topic_type) # Check for any custom_log topics custom_logging_enabled = False @@ -207,13 +210,14 @@ def __init__(self): self.get_logger().info("Check if you got the right URIs, if they are turned on" + " or if your script have proper access to a Crazyradio PA") exit() - + # Create services for the entire swarm and each individual crazyflie self.create_service(Empty, "all/emergency", self._emergency_callback) self.create_service(Takeoff, "all/takeoff", self._takeoff_callback) self.create_service(Land, "all/land", self._land_callback) self.create_service(GoTo, "all/go_to", self._go_to_callback) - self.create_service(StartTrajectory, "all/start_trajectory", self._start_trajectory_callback) + self.create_service( + StartTrajectory, "all/start_trajectory", self._start_trajectory_callback) for uri in self.cf_dict: name = self.cf_dict[uri] @@ -232,28 +236,35 @@ def __init__(self): GoTo, name + "/go_to", partial(self._go_to_callback, uri=uri) ) self.create_service( - StartTrajectory, name + "/start_trajectory", partial(self._start_trajectory_callback, uri=uri) + StartTrajectory, name + + "/start_trajectory", partial( + self._start_trajectory_callback, uri=uri) ) self.create_service( - UploadTrajectory, name + "/upload_trajectory", partial(self._upload_trajectory_callback, uri=uri) + UploadTrajectory, name + + "/upload_trajectory", partial( + self._upload_trajectory_callback, uri=uri) ) self.create_service( - NotifySetpointsStop, name + "/notify_setpoints_stop", partial(self._notify_setpoints_stop_callback, uri=uri) + NotifySetpointsStop, name + + "/notify_setpoints_stop", partial( + self._notify_setpoints_stop_callback, uri=uri) ) self.create_subscription( Twist, name + - "/cmd_vel_legacy", partial(self._cmd_vel_legacy_changed, uri=uri), 10 + "/cmd_vel_legacy", partial(self._cmd_vel_legacy_changed, + uri=uri), 10 ) self.create_subscription( Hover, name + "/cmd_hover", partial(self._cmd_hover_changed, uri=uri), 10 ) - qos_profile = QoSProfile(reliability =QoSReliabilityPolicy.BEST_EFFORT, - history=QoSHistoryPolicy.KEEP_LAST, - depth=1, - deadline = Duration(seconds=0, nanoseconds=1e9/100.0)) + qos_profile = QoSProfile(reliability=QoSReliabilityPolicy.BEST_EFFORT, + history=QoSHistoryPolicy.KEEP_LAST, + depth=1, + deadline=Duration(seconds=0, nanoseconds=1e9/100.0)) self.create_subscription( - NamedPoseArray, "/poses", + NamedPoseArray, "/poses", self._poses_changed, qos_profile ) @@ -263,7 +274,7 @@ def _init_default_logblocks(self, prefix, link_uri, list_logvar, global_logging_ """ cf_name = self.cf_dict[link_uri] cf_type = self.type_dict[link_uri] - + logging_enabled = False logging_freq = 10 try: @@ -293,8 +304,10 @@ def _init_default_logblocks(self, prefix, link_uri, list_logvar, global_logging_ else: lg.add_variable(logvar) - self.swarm._cfs[link_uri].logging[prefix + "_logging_enabled"] = logging_enabled - self.swarm._cfs[link_uri].logging[prefix + "_logging_freq"] = logging_freq + self.swarm._cfs[link_uri].logging[prefix + + "_logging_enabled"] = logging_enabled + self.swarm._cfs[link_uri].logging[prefix + + "_logging_freq"] = logging_freq self.swarm._cfs[link_uri].logging[prefix + "_log_config"] = lg if logging_enabled and global_logging_enabled: self.swarm._cfs[link_uri].logging[prefix + "_publisher"] = self.create_publisher( @@ -356,7 +369,7 @@ def _init_logging(self): if cf_handle.logging[prefix + "_logging_enabled"] and cf_handle.logging["enabled"]: callback_fnc = self.default_log_fnc[prefix] self._init_default_logging(prefix, link_uri, callback_fnc) - + # Start logging for costum logging blocks cf_handle.l_toc = cf.log.toc.toc if len(cf_handle.logging["custom_log_groups"]) != 0 and cf_handle.logging["enabled"]: @@ -408,11 +421,11 @@ def _init_default_logging(self, prefix, link_uri, callback_fnc): f"{link_uri} setup logging for {prefix} at freq {frequency}") except KeyError as e: self.get_logger().info(f'{link_uri}: Could not start log configuration,' - '{} not found in TOC'.format(str(e))) + '{} not found in TOC'.format(str(e))) except AttributeError: self.get_logger().info( f'{link_uri}: Could not add log config, bad configuration.') - + def _log_scan_data_callback(self, timestamp, data, logconf, uri): """ Once multiranger range is retrieved from the Crazyflie, @@ -431,7 +444,7 @@ def _log_scan_data_callback(self, timestamp, data, logconf, uri): if right_range > max_range: right_range = float("inf") if back_range > max_range: - back_range = float("inf") + back_range = float("inf") self.ranges = [back_range, right_range, front_range, left_range] msg = LaserScan() @@ -440,8 +453,8 @@ def _log_scan_data_callback(self, timestamp, data, logconf, uri): msg.range_min = 0.01 msg.range_max = 3.49 msg.ranges = self.ranges - msg.angle_min = -0.5 * 2* pi - msg.angle_max = 0.25 * 2 * pi + msg.angle_min = -0.5 * 2 * pi + msg.angle_max = 0.25 * 2 * pi msg.angle_increment = 1.0 * pi/2 self.swarm._cfs[uri].logging["scan_publisher"].publish(msg) @@ -572,10 +585,11 @@ def _init_parameters(self): for param in sorted(p_toc[group].keys()): name = group + "." + param - # Check the parameter type + # Check the parameter type elem = p_toc[group][param] type_cf_param = elem.ctype - parameter_descriptor = ParameterDescriptor(type=cf_log_to_ros_param[type_cf_param]) + parameter_descriptor = ParameterDescriptor( + type=cf_log_to_ros_param[type_cf_param]) # Check ros parameters if an parameter should be set # Parameter sets for individual robots has priority, @@ -586,11 +600,13 @@ def _init_parameters(self): except KeyError: pass try: - set_param_value = self._ros_parameters["robot_types"][self.cf_dict[link_uri]]["firmware_params"][group][param] + set_param_value = self._ros_parameters["robot_types"][self.cf_dict[link_uri] + ]["firmware_params"][group][param] except KeyError: pass try: - set_param_value = self._ros_parameters["robots"][self.cf_dict[link_uri]]["firmware_params"][group][param] + set_param_value = self._ros_parameters["robots"][self.cf_dict[link_uri] + ]["firmware_params"][group][param] except KeyError: pass @@ -637,7 +653,7 @@ def _init_parameters(self): descriptor=parameter_descriptor, ) - # Now all parameters are set + # Now all parameters are set set_param_all = True self.get_logger().info("All Crazyflies parameters are initialized") @@ -673,8 +689,8 @@ def _parameters_callback(self, params): try: for link_uri in self.uris: cf = self.swarm._cfs[link_uri].cf.param.set_value( - name_param, param.value - ) + name_param, param.value + ) self.get_logger().info( f" {link_uri}: {name_param} is set to {param.value}" ) @@ -682,9 +698,9 @@ def _parameters_callback(self, params): except Exception as e: self.get_logger().info(str(e)) return SetParametersResult(successful=False) - + return SetParametersResult(successful=False) - + def _emergency_callback(self, request, response, uri="all"): if uri == "all": for link_uri in self.uris: @@ -792,23 +808,23 @@ def _notify_setpoints_stop_callback(self, request, response, uri="all"): if uri == "all": for link_uri in self.uris: - self.swarm._cfs[link_uri].cf.commander.send_notify_setpoint_stop() + self.swarm._cfs[link_uri].cf.commander.send_notify_setpoint_stop() else: self.swarm._cfs[uri].cf.commander.send_notify_setpoint_stop() return response def _upload_trajectory_callback(self, request, response, uri="all"): - + id = request.trajectory_id offset = request.piece_offset lenght = len(request.pieces) total_duration = 0 - self.get_logger().info("upload_trajectory(id=%d,offset=%d, lenght=%d)"% ( - id, - offset, - lenght, - )) + self.get_logger().info("upload_trajectory(id=%d,offset=%d, lenght=%d)" % ( + id, + offset, + lenght, + )) trajectory = [] for i in range(lenght): @@ -817,59 +833,66 @@ def _upload_trajectory_callback(self, request, response, uri="all"): py = Poly4D.Poly(piece.poly_y) pz = Poly4D.Poly(piece.poly_z) pyaw = Poly4D.Poly(piece.poly_yaw) - duration = float(piece.duration.sec) + float(piece.duration.nanosec)/1e9 - trajectory.append(Poly4D(duration, px, py, pz, pyaw )) + duration = float(piece.duration.sec) + \ + float(piece.duration.nanosec)/1e9 + trajectory.append(Poly4D(duration, px, py, pz, pyaw)) total_duration = total_duration + duration - + if uri == "all": upload_success_all = True for link_uri in self.uris: - trajectory_mem = self.swarm._cfs[link_uri].cf.mem.get_mems(MemoryElement.TYPE_TRAJ)[id] + trajectory_mem = self.swarm._cfs[link_uri].cf.mem.get_mems( + MemoryElement.TYPE_TRAJ)[id] trajectory_mem.trajectory = trajectory upload_result = trajectory_mem.write_data_sync() if not upload_result: self.get_logger().info(f"{link_uri}: Upload failed") upload_success_all = False - else: - self.swarm._cfs[link_uri].cf.high_level_commander.define_trajectory(id, offset, len(trajectory)) + else: + self.swarm._cfs[link_uri].cf.high_level_commander.define_trajectory( + id, offset, len(trajectory)) if upload_success_all is False: response.success = False return response else: - trajectory_mem = self.swarm._cfs[uri].cf.mem.get_mems(MemoryElement.TYPE_TRAJ)[id] + trajectory_mem = self.swarm._cfs[uri].cf.mem.get_mems( + MemoryElement.TYPE_TRAJ)[id] trajectory_mem.trajectory = trajectory upload_result = trajectory_mem.write_data_sync() if not upload_result: self.get_logger().info(f"{uri}: Upload failed") response.success = False return response - self.swarm._cfs[uri].cf.high_level_commander.define_trajectory(id, offset, len(trajectory)) + self.swarm._cfs[uri].cf.high_level_commander.define_trajectory( + id, offset, len(trajectory)) return response - + def _start_trajectory_callback(self, request, response, uri="all"): - + id = request.trajectory_id ts = request.timescale rel = request.relative rev = request.reversed gm = request.group_mask - self.get_logger().info("start_trajectory(id=%d,timescale=%f,relative=%d, reversed=%d, group_mask=%d)"% ( - id, - ts, - rel, - rev, - gm - )) + self.get_logger().info("start_trajectory(id=%d,timescale=%f,relative=%d, reversed=%d, group_mask=%d)" % ( + id, + ts, + rel, + rev, + gm + )) if uri == "all": for link_uri in self.uris: - self.swarm._cfs[link_uri].cf.high_level_commander.start_trajectory(id, ts, rel, rev, gm) + self.swarm._cfs[link_uri].cf.high_level_commander.start_trajectory( + id, ts, rel, rev, gm) else: - self.swarm._cfs[uri].cf.high_level_commander.start_trajectory(id, ts, rel, rev, gm) + self.swarm._cfs[uri].cf.high_level_commander.start_trajectory( + id, ts, rel, rev, gm) return response - + def _poses_changed(self, msg): """ Topic update callback to the motion capture lib's @@ -887,7 +910,7 @@ def _poses_changed(self, msg): if name in self.uri_dict.keys(): uri = self.uri_dict[name] - #self.get_logger().info(f"{uri}: send extpos {x}, {y}, {z} to {name}") + # self.get_logger().info(f"{uri}: send extpos {x}, {y}, {z} to {name}") if isnan(quat.x): self.swarm._cfs[uri].cf.extpos.send_extpos( x, y, z) @@ -895,7 +918,6 @@ def _poses_changed(self, msg): self.swarm._cfs[uri].cf.extpos.send_extpose( x, y, z, quat.x, quat.y, quat.z, quat.w) - def _cmd_vel_legacy_changed(self, msg, uri=""): """ Topic update callback to control the attitude and thrust @@ -917,8 +939,10 @@ def _cmd_hover_changed(self, msg, uri=""): vy = msg.vy z = msg.z_distance yawrate = -1.0*degrees(msg.yaw_rate) - self.swarm._cfs[uri].cf.commander.send_hover_setpoint(vx, vy, yawrate, z) - self.get_logger().info(f"{uri}: Received hover topic {vx} {vy} {yawrate} {z}") + self.swarm._cfs[uri].cf.commander.send_hover_setpoint( + vx, vy, yawrate, z) + self.get_logger().info( + f"{uri}: Received hover topic {vx} {vy} {yawrate} {z}") def _remove_logging(self, request, response, uri="all"): """ @@ -968,8 +992,10 @@ def _add_logging(self, request, response, uri="all"): self.cf_dict[uri] + ".logs." + topic_name + ".frequency.", frequency) self.swarm._cfs[uri].logging[topic_name + "_publisher"] = self.create_publisher( self.default_log_type[topic_name], self.cf_dict[uri] + "/" + topic_name, 10) - self.swarm._cfs[uri].logging[topic_name + "_log_config"].period_in_ms = 1000 / frequency - self.swarm._cfs[uri].logging[topic_name + "_log_config"].start() + self.swarm._cfs[uri].logging[topic_name + + "_log_config"].period_in_ms = 1000 / frequency + self.swarm._cfs[uri].logging[topic_name + + "_log_config"].start() self.get_logger().info(f"{uri}: Add {topic_name} logging") except rclpy.exceptions.ParameterAlreadyDeclaredException: self.get_logger().info( @@ -988,7 +1014,7 @@ def _add_logging(self, request, response, uri="all"): lg_custom.add_variable(log_name) self.swarm._cfs[uri].logging["custom_log_publisher"][topic_name] = self.create_publisher( LogDataGeneric, self.cf_dict[uri] + "/" + topic_name, 10) - + self.swarm._cfs[uri].cf.log.add_config(lg_custom) lg_custom.data_received_cb.add_callback( @@ -1006,8 +1032,10 @@ def _add_logging(self, request, response, uri="all"): self.get_logger().info( f"{uri}: Failed to add {topic_name} logging") self.get_logger().info(str(e) + "is not in TOC") - self.undeclare_parameter(self.cf_dict[uri] + ".logs." + topic_name + ".frequency.") - self.undeclare_parameter(self.cf_dict[uri] + ".logs." + topic_name + ".vars.") + self.undeclare_parameter( + self.cf_dict[uri] + ".logs." + topic_name + ".frequency.") + self.undeclare_parameter( + self.cf_dict[uri] + ".logs." + topic_name + ".vars.") response.success = False return response except rclpy.exceptions.ParameterAlreadyDeclaredException: @@ -1018,7 +1046,7 @@ def _add_logging(self, request, response, uri="all"): response.success = True return response - + def main(args=None): From ff7ac0fadd3a4a2b42aeacdeb0969576e155d288 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Tue, 21 Nov 2023 13:57:30 +0100 Subject: [PATCH 036/162] fix doc --- docs2/overview.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs2/overview.rst b/docs2/overview.rst index 655afd9c6..7cb09506e 100644 --- a/docs2/overview.rst +++ b/docs2/overview.rst @@ -87,7 +87,7 @@ Support functionality with backends +---------------------+---------+-----------+---------+ | - go_to | Yes | Yes | Yes | +---------------------+---------+-----------+---------+ -| - upload/start traj | Yes | Yes | Yes | +| - upload/start traj | Yes | Yes | Yes | +---------------------+---------+-----------+---------+ | Positioning System | +---------------------+---------+-----------+---------+ From 098691d38e452e3808024937ab016ddf35ca3b4b Mon Sep 17 00:00:00 2001 From: knmcguire Date: Thu, 23 Nov 2023 14:49:15 +0100 Subject: [PATCH 037/162] fix mapping issue wrong order ranges --- crazyflie/scripts/simple_mapper.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/crazyflie/scripts/simple_mapper.py b/crazyflie/scripts/simple_mapper.py index db7723850..f0f316e78 100755 --- a/crazyflie/scripts/simple_mapper.py +++ b/crazyflie/scripts/simple_mapper.py @@ -109,9 +109,9 @@ def rotate_and_create_points(self): pitch = self.angles[1] yaw = self.angles[2] r_back = self.ranges[0] - r_left = self.ranges[1] + r_right = self.ranges[1] r_front = self.ranges[2] - r_right = self.ranges[3] + r_left = self.ranges[3] if (r_left < self.range_max and r_left != 0.0): left = [o[0], o[1] + r_left, o[2]] From 02b70523ad3890ab7ebd50a45da1fb5edb63696e Mon Sep 17 00:00:00 2001 From: knmcguire Date: Thu, 23 Nov 2023 14:52:21 +0100 Subject: [PATCH 038/162] change file name simple mapper --- crazyflie/CMakeLists.txt | 2 +- .../scripts/{simple_mapper.py => simple_mapper_multiranger.py} | 0 2 files changed, 1 insertion(+), 1 deletion(-) rename crazyflie/scripts/{simple_mapper.py => simple_mapper_multiranger.py} (100%) diff --git a/crazyflie/CMakeLists.txt b/crazyflie/CMakeLists.txt index 828cd9a44..e6bf91d0a 100644 --- a/crazyflie/CMakeLists.txt +++ b/crazyflie/CMakeLists.txt @@ -106,7 +106,7 @@ install(PROGRAMS scripts/chooser.py scripts/vel_mux.py scripts/cfmult.py - scripts/simple_mapper.py + scripts/simple_mapper_multiranger.py DESTINATION lib/${PROJECT_NAME} ) diff --git a/crazyflie/scripts/simple_mapper.py b/crazyflie/scripts/simple_mapper_multiranger.py similarity index 100% rename from crazyflie/scripts/simple_mapper.py rename to crazyflie/scripts/simple_mapper_multiranger.py From 2386488754be1c82f97bd9971171b65b273adae3 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Thu, 23 Nov 2023 14:54:09 +0100 Subject: [PATCH 039/162] simple mappr function name change --- crazyflie/scripts/simple_mapper_multiranger.py | 8 ++++---- .../launch/multiranger_simple_mapper_launch.py | 4 ++-- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/crazyflie/scripts/simple_mapper_multiranger.py b/crazyflie/scripts/simple_mapper_multiranger.py index f0f316e78..879f551ec 100755 --- a/crazyflie/scripts/simple_mapper_multiranger.py +++ b/crazyflie/scripts/simple_mapper_multiranger.py @@ -27,9 +27,9 @@ GLOBAL_SIZE_Y = 20.0 MAP_RES = 0.1 -class SimpleMapper(Node): +class SimpleMapperMultiranger(Node): def __init__(self): - super().__init__('simple_mapper') + super().__init__('simple_mapper_multiranger') self.declare_parameter('robot_prefix', '/cf231') robot_prefix = self.get_parameter('robot_prefix').value @@ -163,8 +163,8 @@ def rot(self, roll, pitch, yaw, origin, point): def main(args=None): rclpy.init(args=args) - simple_mapper = SimpleMapper() - rclpy.spin(simple_mapper) + simple_mapper_multiranger = SimpleMapperMultiranger() + rclpy.spin(simple_mapper_multiranger) rclpy.destroy_node() rclpy.shutdown() diff --git a/crazyflie_examples/launch/multiranger_simple_mapper_launch.py b/crazyflie_examples/launch/multiranger_simple_mapper_launch.py index 0f850410b..d8e4b4952 100644 --- a/crazyflie_examples/launch/multiranger_simple_mapper_launch.py +++ b/crazyflie_examples/launch/multiranger_simple_mapper_launch.py @@ -39,8 +39,8 @@ def generate_launch_description(): ), Node( package='crazyflie', - executable='simple_mapper.py', - name='simple_mapper', + executable='simple_mapper_multiranger.py', + name='simple_mapper_multiranger', output='screen', parameters=[ {'robot_prefix': crazyflie_name}] From 93668a3b53b2e597dacbf655bea924698f21bd87 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Thu, 23 Nov 2023 14:55:28 +0100 Subject: [PATCH 040/162] fix callback names typo --- crazyflie/scripts/simple_mapper_multiranger.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/crazyflie/scripts/simple_mapper_multiranger.py b/crazyflie/scripts/simple_mapper_multiranger.py index 879f551ec..afd4ef851 100755 --- a/crazyflie/scripts/simple_mapper_multiranger.py +++ b/crazyflie/scripts/simple_mapper_multiranger.py @@ -33,8 +33,8 @@ def __init__(self): self.declare_parameter('robot_prefix', '/cf231') robot_prefix = self.get_parameter('robot_prefix').value - self.odom_subscriber = self.create_subscription(Odometry, robot_prefix + '/odom', self.odom_subcribe_callback, 10) - self.ranges_subscriber = self.create_subscription(LaserScan, robot_prefix + '/scan', self.scan_subsribe_callback, 10) + self.odom_subscriber = self.create_subscription(Odometry, robot_prefix + '/odom', self.odom_subscribe_callback, 10) + self.ranges_subscriber = self.create_subscription(LaserScan, robot_prefix + '/scan', self.scan_subscribe_callback, 10) self.position = [0.0, 0.0, 0.0] self.angles = [0.0, 0.0, 0.0] self.ranges = [0.0, 0.0, 0.0, 0.0] @@ -59,7 +59,7 @@ def __init__(self): self.get_logger().info(f"Simple mapper set for crazyflie "+ robot_prefix + f" using the odom and scan topic") - def odom_subcribe_callback(self, msg): + def odom_subscribe_callback(self, msg): self.position[0] = msg.pose.pose.position.x self.position[1] = msg.pose.pose.position.y self.position[2] = msg.pose.pose.position.z @@ -70,7 +70,7 @@ def odom_subcribe_callback(self, msg): self.angles[2] = euler[2] self.position_update = True - def scan_subsribe_callback(self, msg): + def scan_subscribe_callback(self, msg): self.ranges = msg.ranges self.range_max = msg.range_max data = self.rotate_and_create_points() From b466f821667e401e6e2fef9e85e02f4895bd3bbb Mon Sep 17 00:00:00 2001 From: knmcguire Date: Thu, 23 Nov 2023 14:55:54 +0100 Subject: [PATCH 041/162] autopep8 --- .../scripts/simple_mapper_multiranger.py | 81 ++++++++++--------- 1 file changed, 44 insertions(+), 37 deletions(-) diff --git a/crazyflie/scripts/simple_mapper_multiranger.py b/crazyflie/scripts/simple_mapper_multiranger.py index afd4ef851..096b6126a 100755 --- a/crazyflie/scripts/simple_mapper_multiranger.py +++ b/crazyflie/scripts/simple_mapper_multiranger.py @@ -27,16 +27,19 @@ GLOBAL_SIZE_Y = 20.0 MAP_RES = 0.1 + class SimpleMapperMultiranger(Node): def __init__(self): super().__init__('simple_mapper_multiranger') self.declare_parameter('robot_prefix', '/cf231') - robot_prefix = self.get_parameter('robot_prefix').value - - self.odom_subscriber = self.create_subscription(Odometry, robot_prefix + '/odom', self.odom_subscribe_callback, 10) - self.ranges_subscriber = self.create_subscription(LaserScan, robot_prefix + '/scan', self.scan_subscribe_callback, 10) - self.position = [0.0, 0.0, 0.0] - self.angles = [0.0, 0.0, 0.0] + robot_prefix = self.get_parameter('robot_prefix').value + + self.odom_subscriber = self.create_subscription( + Odometry, robot_prefix + '/odom', self.odom_subscribe_callback, 10) + self.ranges_subscriber = self.create_subscription( + LaserScan, robot_prefix + '/scan', self.scan_subscribe_callback, 10) + self.position = [0.0, 0.0, 0.0] + self.angles = [0.0, 0.0, 0.0] self.ranges = [0.0, 0.0, 0.0, 0.0] self.range_max = 3.5 @@ -52,13 +55,14 @@ def __init__(self): self.position_update = False - self.map = [-1] * int(GLOBAL_SIZE_X / MAP_RES) * int(GLOBAL_SIZE_Y / MAP_RES) + self.map = [-1] * int(GLOBAL_SIZE_X / MAP_RES) * \ + int(GLOBAL_SIZE_Y / MAP_RES) self.map_publisher = self.create_publisher(OccupancyGrid, robot_prefix + '/map', - qos_profile=QoSProfile( depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL, history=HistoryPolicy.KEEP_LAST,)) + qos_profile=QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL, history=HistoryPolicy.KEEP_LAST,)) - self.get_logger().info(f"Simple mapper set for crazyflie "+ robot_prefix + + self.get_logger().info(f"Simple mapper set for crazyflie " + robot_prefix + f" using the odom and scan topic") - + def odom_subscribe_callback(self, msg): self.position[0] = msg.pose.pose.position.x self.position[1] = msg.pose.pose.position.y @@ -81,15 +85,17 @@ def scan_subscribe_callback(self, msg): if self.position_update is False: return for i in range(len(data)): - point_x = int((data[i][0] - GLOBAL_SIZE_X / 2.0)/ MAP_RES ) - point_y = int((data[i][1] - GLOBAL_SIZE_Y / 2.0)/ MAP_RES ) + point_x = int((data[i][0] - GLOBAL_SIZE_X / 2.0) / MAP_RES) + point_y = int((data[i][1] - GLOBAL_SIZE_Y / 2.0) / MAP_RES) points_x.append(point_x) points_y.append(point_y) - position_x_map = int((self.position[0] - GLOBAL_SIZE_X / 2.0)/ MAP_RES ) - position_y_map = int((self.position[1] - GLOBAL_SIZE_Y / 2.0)/ MAP_RES ) + position_x_map = int( + (self.position[0] - GLOBAL_SIZE_X / 2.0) / MAP_RES) + position_y_map = int( + (self.position[1] - GLOBAL_SIZE_Y / 2.0) / MAP_RES) for line_x, line_y in bresenham(position_x_map, position_y_map, point_x, point_y): - self.map[line_y * int(GLOBAL_SIZE_X / MAP_RES) + line_x] = 0 - self.map[point_y * int(GLOBAL_SIZE_X / MAP_RES) + point_x] = 100 + self.map[line_y * int(GLOBAL_SIZE_X / MAP_RES) + line_x] = 0 + self.map[point_y * int(GLOBAL_SIZE_X / MAP_RES) + point_x] = 100 msg = OccupancyGrid() msg.header.stamp = self.get_clock().now().to_msg() @@ -132,33 +138,34 @@ def rotate_and_create_points(self): return data def rot(self, roll, pitch, yaw, origin, point): - cosr = math.cos((roll)) - cosp = math.cos((pitch)) - cosy = math.cos((yaw)) + cosr = math.cos((roll)) + cosp = math.cos((pitch)) + cosy = math.cos((yaw)) + + sinr = math.sin((roll)) + sinp = math.sin((pitch)) + siny = math.sin((yaw)) - sinr = math.sin((roll)) - sinp = math.sin((pitch)) - siny = math.sin((yaw)) + roty = np.array([[cosy, -siny, 0], + [siny, cosy, 0], + [0, 0, 1]]) - roty = np.array([[cosy, -siny, 0], - [siny, cosy, 0], - [0, 0, 1]]) + rotp = np.array([[cosp, 0, sinp], + [0, 1, 0], + [-sinp, 0, cosp]]) - rotp = np.array([[cosp, 0, sinp], - [0, 1, 0], - [-sinp, 0, cosp]]) + rotr = np.array([[1, 0, 0], + [0, cosr, -sinr], + [0, sinr, cosr]]) - rotr = np.array([[1, 0, 0], - [0, cosr, -sinr], - [0, sinr, cosr]]) + rotFirst = np.dot(rotr, rotp) - rotFirst = np.dot(rotr, rotp) + rot = np.array(np.dot(rotFirst, roty)) - rot = np.array(np.dot(rotFirst, roty)) + tmp = np.subtract(point, origin) + tmp2 = np.dot(rot, tmp) + return np.add(tmp2, origin) - tmp = np.subtract(point, origin) - tmp2 = np.dot(rot, tmp) - return np.add(tmp2, origin) def main(args=None): @@ -170,4 +177,4 @@ def main(args=None): if __name__ == '__main__': - main() \ No newline at end of file + main() From 7019b14203a6bbb1012c53d0c1716da90d1dc3da Mon Sep 17 00:00:00 2001 From: knmcguire Date: Thu, 23 Nov 2023 14:56:20 +0100 Subject: [PATCH 042/162] revert change velmux --- crazyflie_examples/launch/keyboard_velmux_launch.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/crazyflie_examples/launch/keyboard_velmux_launch.py b/crazyflie_examples/launch/keyboard_velmux_launch.py index 06b395ad4..25d318a0b 100644 --- a/crazyflie_examples/launch/keyboard_velmux_launch.py +++ b/crazyflie_examples/launch/keyboard_velmux_launch.py @@ -18,8 +18,6 @@ def generate_launch_description(): server_params = crazyflies - crazyflie_name = '/cf231' - return LaunchDescription([ Node( package='crazyflie', From b20230ab4b69a6948ab63ee497d861affd350c89 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Thu, 23 Nov 2023 15:05:47 +0100 Subject: [PATCH 043/162] add doc about the example --- docs2/tutorials.rst | 38 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 38 insertions(+) diff --git a/docs2/tutorials.rst b/docs2/tutorials.rst index bb550ce1c..f56d62f75 100644 --- a/docs2/tutorials.rst +++ b/docs2/tutorials.rst @@ -87,6 +87,44 @@ Here you can see an example of 5 crazyflies with the Pose default topic enabled, +Mapping with simple mapper +-------------------------- + +If you have a crazyflie with a multiranger and flowdeck, you can try out some simple mapping. + +Make sure that the scan and odometry logging is enabled in crazyflies.yaml: + +.. code-block:: bash + + firmware_logging: + enabled: true + default_topics: + odom: + frequency: 10 # Hz + scan: + frequency: 10 # Hz + +and make sure that the pid controller and kalman filter is enabled: + +.. code-block:: bash + + firmware_params: + stabilizer: + estimator: 2 # 1: complementary, 2: kalman + controller: 1 # 1: PID, 2: mellinger + +If you are using a different name for your crazyflie, make sure to change the following in the example launch file (multiranger_simple_mapper_launch.py): + +.. code-block:: bash + crazyflie_name = '/cf231' + +Then start the simple mapper example launch file: + +.. code-block:: bash + ros2 launch crazyflie_examples multiranger_simple_mapper_launch.py + +And watch the mapping happening in rviz2 while controlling the crazyflie with the teleop node (see the sections above). + Mapping with the SLAM toolbox ----------------------------- From 99ccd67c875ece9fe4945dbacb89c196b2740bc5 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Thu, 23 Nov 2023 15:08:33 +0100 Subject: [PATCH 044/162] fix doc issues --- docs2/tutorials.rst | 2 ++ 1 file changed, 2 insertions(+) diff --git a/docs2/tutorials.rst b/docs2/tutorials.rst index f56d62f75..84281cc81 100644 --- a/docs2/tutorials.rst +++ b/docs2/tutorials.rst @@ -116,11 +116,13 @@ and make sure that the pid controller and kalman filter is enabled: If you are using a different name for your crazyflie, make sure to change the following in the example launch file (multiranger_simple_mapper_launch.py): .. code-block:: bash + crazyflie_name = '/cf231' Then start the simple mapper example launch file: .. code-block:: bash + ros2 launch crazyflie_examples multiranger_simple_mapper_launch.py And watch the mapping happening in rviz2 while controlling the crazyflie with the teleop node (see the sections above). From 9050b3790a13f51e4d44f37d804c012355659b9f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Wolfgang=20H=C3=B6nig?= Date: Fri, 1 Dec 2023 06:27:33 +0100 Subject: [PATCH 045/162] add system tests Add infrastructure for continuous integration tests that run on physical hardware (to be manually triggered via github actions; requires a custom github runner with access to the robot hardware). This initial change runs two of the example scripts and uploads a resulting PDF with the trajectory tracking results. Co-authored-by: JulienT hevenoz --- .github/workflows/systemtests.yml | 68 ++++++ systemtests/mcap_handler.py | 64 ++++++ systemtests/plotter_class.py | 343 ++++++++++++++++++++++++++++++ systemtests/run_test.py | 119 +++++++++++ 4 files changed, 594 insertions(+) create mode 100644 .github/workflows/systemtests.yml create mode 100644 systemtests/mcap_handler.py create mode 100644 systemtests/plotter_class.py create mode 100755 systemtests/run_test.py diff --git a/.github/workflows/systemtests.yml b/.github/workflows/systemtests.yml new file mode 100644 index 000000000..21588070b --- /dev/null +++ b/.github/workflows/systemtests.yml @@ -0,0 +1,68 @@ +name: System Tests + +on: + push: + branches: [ "feature_systemtests" ] + # manual trigger + workflow_dispatch: + +jobs: + build: + runs-on: self-hosted + steps: + - name: Create workspace + id: step1 + run: | + cd ros2_ws/src || mkdir -p ros2_ws/src + - name: Checkout motion capture package + id: step2 + run: | + cd ros2_ws/src + ls motion_capture_tracking || git clone --branch ros2 --recursive https://github.com/IMRCLab/motion_capture_tracking.git + - name: Checkout Crazyswarm2 + id: step3 + uses: actions/checkout@v4 + with: + path: ros2_ws/src/crazyswarm2 + submodules: 'recursive' + - name: Build workspace + id: step4 + run: | + source /opt/ros/humble/setup.bash + cd ros2_ws + colcon build --symlink-install + + - name: Flight test + id: step5 + run: | + cd ros2_ws + source /opt/ros/humble/setup.bash + . install/local_setup.bash + export ROS_LOCALHOST_ONLY=1 + python3 src/crazyswarm2/systemtests/run_test.py + + - name: Upload files + id: step6 + uses: actions/upload-artifact@v3 + with: + name: pdf_bagfiles_and_logs + path: | + ros2_ws/bagfiles + ros2_ws/results + ~/.ros/log + + + + + + # - name: build and test ROS 2 + # uses: ros-tooling/action-ros-ci@v0.3 + # with: + # package-name: | + # crazyflie + # crazyflie_examples + # crazyflie_interfaces + # crazyflie_py + # crazyflie_sim + # target-ros2-distro: humble + # vcs-repo-file-url: rosinstall \ No newline at end of file diff --git a/systemtests/mcap_handler.py b/systemtests/mcap_handler.py new file mode 100644 index 000000000..de15911c1 --- /dev/null +++ b/systemtests/mcap_handler.py @@ -0,0 +1,64 @@ +from pathlib import Path +from rclpy.serialization import deserialize_message +from rosidl_runtime_py.utilities import get_message +from std_msgs.msg import String +import rosbag2_py +import csv + +class McapHandler: + def __init__(self): + pass + + def read_messages(self, input_bag: str): + reader = rosbag2_py.SequentialReader() + reader.open( + rosbag2_py.StorageOptions(uri=input_bag, storage_id="mcap"), + rosbag2_py.ConverterOptions( + input_serialization_format="cdr", output_serialization_format="cdr" + ), + ) + topic_types = reader.get_all_topics_and_types() + + def typename(topic_name): + for topic_type in topic_types: + if topic_type.name == topic_name: + return topic_type.type + raise ValueError(f"topic {topic_name} not in bag") + + while reader.has_next(): + topic, data, timestamp = reader.read_next() + msg_type = get_message(typename(topic)) + msg = deserialize_message(data, msg_type) + yield topic, msg, timestamp + del reader + + def write_mcap_to_csv(self, inputbag:str, outputfile:str): + '''A method which translates an .mcap rosbag file format to a .csv file. + Only written to translate the /tf topic but could easily be extended to other topics''' + + try: + print("Translating .mcap to .csv") + f = open(outputfile, 'w+') + writer = csv.writer(f) + for topic, msg, timestamp in self.read_messages(inputbag): + writer.writerow([timestamp, msg.transforms[0].transform.translation.x, msg.transforms[0].transform.translation.y, msg.transforms[0].transform.translation.z]) + f.close() + except FileNotFoundError: + print(f"McapHandler : file {outputfile} not found") + exit(1) + + + + +if __name__ == "__main__": + + #command line utility + + from argparse import ArgumentParser, Namespace + parser = ArgumentParser(description="Translates the /tf topic of an .mcap rosbag file format to a .csv file") + parser.add_argument("inputbag", type=str, help="The .mcap rosbag file to be translated") + parser.add_argument("outputfile", type=str, help="Output csv file that has to be created/overwritten") + args:Namespace = parser.parse_args() + + translator = McapHandler() + translator.write_mcap_to_csv(args.inputbag,args.outputfile) diff --git a/systemtests/plotter_class.py b/systemtests/plotter_class.py new file mode 100644 index 000000000..beca43e33 --- /dev/null +++ b/systemtests/plotter_class.py @@ -0,0 +1,343 @@ +import matplotlib.pyplot as plt +import os +import sys +from matplotlib.backends.backend_pdf import PdfPages +import numpy as np +from crazyflie_py.uav_trajectory import Trajectory + + +class Plotter: + + def __init__(self): + self.params = {'experiment':'1','trajectory':'figure8.csv','motors':'standard motors(CF)', 'propellers':'standard propellers(CF)'} + self.bag_times = np.empty([0]) + self.bag_x = np.empty([0]) + self.bag_y = np.empty([0]) + self.bag_z = np.empty([0]) + self.ideal_traj_x = np.empty([0]) + self.ideal_traj_y = np.empty([0]) + self.ideal_traj_z = np.empty([0]) + self.euclidian_dist = np.empty([0]) + self.deviation = [] #list of all indexes where euclidian_distance(ideal - recorded) > EPSILON + + self.EPSILON = 0.05 # euclidian distance in [m] between ideal and recorded trajectory under which the drone has to stay to pass the test + self.DELAY_CONST_FIG8 = 4.75 #this is the delay constant which I found by adding up all the time.sleep() etc in the figure8.py file. This should be implemented better later + self.ALTITUDE_CONST_FIG8 = 1.0 #this is the altitude given for the takeoff in figure8.py. I should find a better solution than a symbolic constant ? + self.ALTITUDE_CONST_MULTITRAJ = 1 #takeoff altitude for traj0 in multi_trajectory.py + + def file_guard(self, pdf_path): + msg = None + if os.path.exists(pdf_path): + msg = input("file already exists, overwrite? [y/n]: ") + if msg == "n": + print("exiting...") + sys.exit(0) + elif msg == "y": + print("overwriting...") + os.remove(pdf_path) + else: + print("invalid msg...") + self.file_guard(pdf_path) + return + + + + def read_csv_and_set_arrays(self, ideal_csvfile, rosbag_csvfile): + '''Method that reads the csv data of the ideal test trajectory and of the actual recorded trajectory and initializes the attribute arrays''' + + #check which test we are plotting : figure8 or multi_trajectory + if("fig8" in rosbag_csvfile): + fig8 = True + print("Plotting fig8 test data") + else: + fig8 = False + print("Plotting multi_trajectory test data") + + #get ideal trajectory data + self.ideal_traj_csv = Trajectory() + try: + path_to_ideal_csv = os.path.join(os.path.dirname(os.path.abspath(__file__)),ideal_csvfile) + self.ideal_traj_csv.loadcsv(path_to_ideal_csv) + except FileNotFoundError: + print("Plotter : File not found " + path_to_ideal_csv) + exit(1) + + + #get rosbag data + rosbag_data = np.loadtxt(rosbag_csvfile, delimiter=",") + + self.bag_times = np.array(rosbag_data[:,0]) + self.bag_x = np.array(rosbag_data[:,1]) + self.bag_y = np.array(rosbag_data[:,2]) + self.bag_z = np.array(rosbag_data[:,3]) + + self.adjust_arrays() + bag_arrays_size = len(self.bag_times) + print("number of datapoints in self.bag_*: ",bag_arrays_size) + + #####calculate ideal trajectory points corresponding to the times of recorded points + + self.ideal_traj_x = np.empty([bag_arrays_size]) + self.ideal_traj_y = np.empty([bag_arrays_size]) + self.ideal_traj_z = np.empty([bag_arrays_size]) + self.euclidian_dist = np.empty([bag_arrays_size]) + + + no_match_in_idealcsv=[] + + for i in range(bag_arrays_size): + try: + pos = self.ideal_traj_csv.eval(self.bag_times[i] - self.DELAY_CONST_FIG8).pos + except AssertionError: + no_match_in_idealcsv.append(i) + pos = [0,0,0] #for all recorded datapoints who cannot be matched to a corresponding ideal position we assume the drone is on its ground start position (ie those datapoints are before takeoff or after landing) + + + self.ideal_traj_x[i], self.ideal_traj_y[i]= pos[0], pos[1] + if(fig8) : #special case : in fig8 test no altitude is given in the trajectory polynomials but is stays constant after takeoff in figure8.py + self.ideal_traj_z[i] = self.ALTITUDE_CONST_FIG8 + else : #for multi_trajectory test the altitude given in the trajectory polynomials is added to the takeoff altitude + self.ideal_traj_z[i] = self.ALTITUDE_CONST_MULTITRAJ + pos[2] + + self.euclidian_dist[i] = np.linalg.norm([self.ideal_traj_x[i]-self.bag_x[i], + self.ideal_traj_y[i]-self.bag_y[i], self.ideal_traj_z[i]-self.bag_z[i]]) + if self.euclidian_dist[i] > self.EPSILON: + self.deviation.append(i) + + self.no_match_warning(no_match_in_idealcsv) + + + def no_match_warning(self, unmatched_values:list): + ''' A method which prints a warning saying how many (if any) recorded datapoints could not be matched to an ideal datapoint''' + + no_match_arr = np.array(unmatched_values) + + if no_match_arr.size == 0: + return + + split_index_arr = [] + + for i in range(no_match_arr.size - 1): #find indexes which are not consecutive + if(no_match_arr[i+1] != no_match_arr[i]+1): + split_index_arr.append(i+1) + + banana_split = np.split(no_match_arr, split_index_arr) #split array into sub-array of consecutive indexes -> each sub-array is a timerange for which ideal positions weren't able to calculated + print(f"{len(no_match_arr)} recorded positions weren't able to be matched with a specified ideal position and were given the default (0,0,0) ideal position instead.") + print("Probable reason : their timestamp is before the start of the ideal trajectory or after its end.") + if len(banana_split)==2: + timerange1_start = self.bag_times[banana_split[0][0]] + timerange1_end= self.bag_times[banana_split[0][1]] + timerange2_start = self.bag_times[banana_split[1][0]] + timerange2_end = self.bag_times[banana_split[1][1]] + print(f"These datapoints correspond to the time ranges [{timerange1_start} , {timerange1_end}] and [{timerange2_start} , {timerange2_end}]") + + + + def adjust_arrays(self): + ''' Method that trims the self.bag_* attributes to get rid of the datapoints where the drone is immobile on the ground and makes self.bag_times start at 0 [s]''' + + print(f"rosbag initial length {(self.bag_times[-1]-self.bag_times[0]) * 10**-9}s") + + #find the takeoff time and landing times + ground_level = self.bag_z[0] + airborne = False + takeoff_index = None + landing_index = None + i=0 + for z_coord in self.bag_z: + if not(airborne) and z_coord > ground_level + ground_level*(0.1): #when altitude of the drone is 10% higher than the ground level, it started takeoff + takeoff_index = i + takeoff_time = self.bag_times[takeoff_index] + airborne = True + print(f"takeof time is {(takeoff_time-self.bag_times[0]) * 10**-9}") + if airborne and z_coord < ground_level + ground_level*(0.1): #find when it lands again + landing_index = i + landing_time = self.bag_times[landing_index] + print(f"landing time is {(landing_time-self.bag_times[0]) * 10**-9}") + break + i+=1 + + assert (takeoff_index != None) and (landing_index != None), "Plotter : couldn't find drone takeoff or landing" + + + ####get rid of datapoints before takeoff and after landing in bag_times, bag_x, bag_y, bag_y + + assert len(self.bag_times) == len(self.bag_x) == len(self.bag_y) == len(self.bag_z), "Plotter : self.bag_* aren't the same size before trimming" + index_arr = np.arange(len(self.bag_times)) + slicing_arr = np.delete(index_arr, index_arr[takeoff_index:landing_index+1]) #in our slicing array we take out all the indexes of when the drone is in flight so that it only contains the indexes of when the drone is on the ground + + #delete the datapoints where drone is on the ground + self.bag_times = np.delete(self.bag_times, slicing_arr) + self.bag_x = np.delete(self.bag_x, slicing_arr) + self.bag_y = np.delete(self.bag_y, slicing_arr) + self.bag_z = np.delete(self.bag_z, slicing_arr) + + assert len(self.bag_times) == len(self.bag_x) == len(self.bag_y) == len(self.bag_z), "Plotter : self.bag_* aren't the same size after trimming" + + #rewrite bag_times to start at 0 and be written in [s] instead of [ns] + bag_start_time = self.bag_times[0] + self.bag_times = (self.bag_times-bag_start_time) * (10**-9) + assert self.bag_times[0] == 0 + print(f"trimmed bag_times starts: {self.bag_times[0]}s and ends: {self.bag_times[-1]}, size: {len(self.bag_times)}") + + + + def create_figures(self, ideal_csvfile:str, rosbag_csvfile:str, pdfname:str): + '''Method that creates the pdf with the plots''' + + self.read_csv_and_set_arrays(ideal_csvfile,rosbag_csvfile) + + passed="failed" + if self.test_passed(): + passed = "passed" + + #create PDF to save figures + if(pdfname[-4:] != ".pdf"): + pdfname= pdfname + '.pdf' + + #check if user wants to overwrite the report file + self.file_guard(pdfname) + pdf_pages = PdfPages(pdfname) + + #create title page + if "figure8" in ideal_csvfile: + name = "Figure8" + elif "multi_trajectory" in ideal_csvfile: + name = "Multi_trajectory" + else: + name = "Unnamed test" + print("Plotter : test name not defined") + + text = f'{name} trajectory test' + title_text_settings = f'Settings:\n' + title_text_parameters = f'Parameters:\n' + for key, value in self.params.items(): + title_text_parameters += f" {key}: {value}\n" + title_text_results = f'Results: test {passed}\n' + f'max error : ' + + title_text = text + "\n" + title_text_settings + "\n" + title_text_parameters + "\n" + title_text_results + fig = plt.figure(figsize=(5,8)) + fig.text(0.1, 0.1, title_text, size=11) + + + pdf_pages.savefig(fig) + + + #create plots + fig, ax = plt.subplots() + ax.plot(self.bag_times, self.ideal_traj_x, label='Ideal trajectory', linestyle="--", linewidth=1, zorder=10) + ax.plot(self.bag_times, self.bag_x, label='Recorded trajectory') + ax.set_xlabel('time [s]') + ax.set_ylabel('x position [m]') + ax.set_title("Trajectory x") + + ax.grid(which='major', color='#DDDDDD', linewidth=0.8) + ax.grid(which='minor', color='#EEEEEE', linestyle=':', linewidth=0.5) + ax.minorticks_on() + fig.tight_layout(pad = 4) + fig.legend() + + pdf_pages.savefig(fig) + + fig2, ax2 = plt.subplots() + ax2.plot(self.bag_times, self.ideal_traj_y, label='Ideal trajectory', linestyle="--", linewidth=1, zorder=10) + ax2.plot(self.bag_times, self.bag_y, label='Recorded trajectory') + ax2.set_xlabel('time [s]') + ax2.set_ylabel('y position [m]') + ax2.set_title("Trajectory y") + ax2.grid(which='major', color='#DDDDDD', linewidth=0.8) + ax2.grid(which='minor', color='#EEEEEE', linestyle=':', linewidth=0.5) + ax2.minorticks_on() + fig2.tight_layout(pad = 4) + fig2.legend() + pdf_pages.savefig(fig2) + + + fig3, ax3 = plt.subplots() + ax3.plot(self.bag_times, self.ideal_traj_z, label='Ideal trajectory', linestyle="--", linewidth=1, zorder=10) + ax3.plot(self.bag_times, self.bag_z, label='Recorded trajectory') + ax3.set_xlabel('time [s]') + ax3.set_ylabel('z position [m]') + ax3.set_title("Trajectory z") + ax3.grid(which='major', color='#DDDDDD', linewidth=0.8) + ax3.grid(which='minor', color='#EEEEEE', linestyle=':', linewidth=0.5) + ax3.minorticks_on() + fig3.tight_layout(pad = 4) + fig3.legend() + pdf_pages.savefig(fig3) + + fig4, ax4 = plt.subplots() + ax4.plot(self.bag_times, self.euclidian_dist) + ax4.set_xlabel('time [s]') + ax4.set_ylabel('Euclidean distance [m]') + ax4.set_title('Deviation between ideal and recorded trajectories') + fig4.tight_layout(pad=4) + ax4.grid(which='major', color='#DDDDDD', linewidth=0.8) + ax4.grid(which='minor', color='#EEEEEE', linestyle=':', linewidth=0.5) + ax4.minorticks_on() + pdf_pages.savefig(fig4) + + + fig5,ax5 = plt.subplots() + ax5.plot(self.ideal_traj_x, self.ideal_traj_y, label='Ideal trajectory', linestyle="--", linewidth=1, zorder=10) + ax5.plot(self.bag_x, self.bag_y, label='Recorded trajectory') + ax5.set_xlabel('x [m]') + ax5.set_ylabel('y [m]') + ax5.set_title('2D visualization') + fig5.tight_layout(pad=4) + ax5.grid(which='major', color='#DDDDDD', linewidth=0.8) + ax5.grid(which='minor', color='#EEEEEE', linestyle=':', linewidth=0.5) + ax5.minorticks_on() + pdf_pages.savefig(fig5) + + + fig6 = plt.figure() + ax6 = fig6.add_subplot(projection="3d") + ax6.plot3D(self.ideal_traj_x,self.ideal_traj_y,self.ALTITUDE_CONST_FIG8, label='Ideal trajectory', linestyle="--", linewidth=1, zorder=10) + ax6.plot3D(self.bag_x,self.bag_y,self.bag_z, label='Recorded trajectory', linewidth=1) + ax6.grid(True) + ax6.set_title('3D visualization') + ax6.set_xlabel('x [m]') + ax6.set_ylabel('y [m]') + ax6.set_zlabel('z [m]') + plt.close(fig6) + plt.tight_layout(pad=4) + pdf_pages.savefig(fig6) + + + + pdf_pages.close() + + print("Results saved in " + pdfname) + + def test_passed(self) -> bool : + '''Returns True if the deviation between recorded and ideal trajectories of the drone always stayed lower + than EPSILON. Returns False otherwise ''' + + nb_dev_points = len(self.deviation) + + if nb_dev_points == 0: + print("Test passed") + return True + else: + print(f"The deviation between ideal and recorded trajectories is greater than {self.EPSILON}m for {nb_dev_points} " + f"datapoints, which corresponds to a duration of {nb_dev_points*0.01}s") + return False + +if __name__=="__main__": + + #command line utility + + from argparse import ArgumentParser, Namespace + parser = ArgumentParser(description="Creates a pdf plotting the recorded trajectory of a drone against its desired trajectory") + parser.add_argument("desired_trajectory", type=str, help=".csv file containing (time,x,y,z) of the ideal/desired drone trajectory") + parser.add_argument("recorded_trajectory", type=str, help=".csv file containing (time,x,y,z) of the recorded drone trajectory") + parser.add_argument("pdf", type=str, help="name of the pdf file you want to create/overwrite") + parser.add_argument("--open", help="Open the pdf directly after it is created", action="store_true") + args : Namespace = parser.parse_args() + + plotter = Plotter() + plotter.create_figures(args.desired_trajectory, args.recorded_trajectory, args.pdf) + if args.open: + import subprocess + subprocess.call(["xdg-open", args.pdf]) diff --git a/systemtests/run_test.py b/systemtests/run_test.py new file mode 100755 index 000000000..73cfa1406 --- /dev/null +++ b/systemtests/run_test.py @@ -0,0 +1,119 @@ +#!/usr/bin/env python3 +#!/usr/bin/env python3 +from subprocess import Popen, PIPE +import time +import os +import signal +from mcap_handler import McapHandler +from datetime import datetime +from plotter_class import Plotter +from pathlib import Path +import shutil +import atexit + + +class Waiter: + '''A helper class which sleeps the amount of seconds it is instanciated with. If the user interrupts with ^C during the waiting time (zB if the drone crashes), it will stop sleeping and continue + to the end of the program where all child processes are terminated correctly. All subsequent Waiter() calls will be ignored''' + wait=True + + def __init__(self, seconds): + if seconds > 0 : + self.sleep(seconds) + + def sleep(self, seconds): + start=time.time() + while Waiter.wait and time.time()<(start+seconds): + try: + time.sleep(1) + except KeyboardInterrupt: + Waiter.wait = False + +def record_start_and_terminate(testname:str, testduration:int, bagfolder:str): + '''Helper function that starts recording the /tf topic in a rosbag, starts the test, waits, closes the rosbag and terminate all processes + NB the testname must be the name of the crayzflie_examples executable (ie the CLI grammar "ros2 run crazyflie_examples testname" must be valid)''' + index = bagfolder.find("bag_") + bagname = bagfolder[index:] + + + src = "source " + bagfolder[:index-9] + "install/setup.bash" # -> "source /home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/install/setup.bash" + + command = f"{src} && ros2 bag record -s mcap -o {testname}_{bagname} /tf" + record_bag = Popen(command, shell=True, cwd=bagfolder, stderr=PIPE, stdout=True, + start_new_session=True, text=True, executable="/bin/bash") + + command = f"{src} && ros2 run crazyflie_examples {testname}" + start_flight_test = Popen(command, shell=True, stderr=True, stdout=True, + start_new_session=True, text=True, executable="/bin/bash") + + + Waiter(testduration) #wait x seconds for the crazyflie to fly the test + + os.killpg(os.getpgid(start_flight_test.pid), signal.SIGTERM) #kill flight test and all of its child processes + os.killpg(os.getpgid(record_bag.pid), signal.SIGTERM) #kill rosbag + + #if something went wrong with the bash command lines in Popen, print the error + if record_bag.stderr != None: + print(testname," record_bag stderr: ", record_bag.stderr.readlines()) + if start_flight_test.stderr != None: + print(testname," start_flight flight stderr: ", start_flight_test.stderr.readlines()) + + + +def translate_and_plot(testname:str, bagfolder:str): + '''Helper function that translates rosbag .mcap format to .csv, then uses that csv to plot a pdf ''' + index = bagfolder.find("bag_") + bagname = bagfolder[index:] + # NB : the mcap filename is almost the same as the folder name but has _0 at the end + inputbag = str(bagfolder) + f"/{testname}_{bagname}/{testname}_{bagname}_0.mcap" + output_csv = str(bagfolder) + f"/{testname}_{bagname}/{testname}_{bagname}_0.csv" + writer = McapHandler() + writer.write_mcap_to_csv(inputbag, output_csv) #translate bag from mcap to csv + output_pdf = str(path.parents[3].joinpath(f"results/Results_{testname}_"+ now +".pdf")) + rosbag_csv = output_csv + if "figure8" in testname: + test_file = "../crazyflie_examples/crazyflie_examples/data/figure8.csv" + elif "multi_trajectory" in testname: + test_file = "../crazyflie_examples/crazyflie_examples/data/multi_trajectory/traj0.csv" + else: + print("run_test.py : test file not defined") + plotter = Plotter() + plotter.create_figures(test_file, rosbag_csv, output_pdf) #plot the data + + +if __name__ == "__main__": + + path = Path(__file__) #Path(__file__) should be "/home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/src/crazyswarm2/systemtests/newsub.py" ; path.parents[0]=.../systemstests + + #delete results, logs and bags of previous experiments + shutil.rmtree(path.parents[3].joinpath("bagfiles")) + shutil.rmtree(path.parents[3].joinpath("results")) + shutil.rmtree(Path.home() / ".ros/log") + + + #create the folder where we will record the different bags and the folder where the results pdf will be saved + now = datetime.now().strftime('%d_%m_%Y-%H_%M_%S') + bagfolder = str((path.parents[3].joinpath(f"bagfiles/bag_" + now))) # /home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/bagfiles/bag_d_m_Y-H_M_S + os.makedirs(bagfolder) + os.makedirs(path.parents[3].joinpath("results")) # /home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/results + + + src = "source " + str(path.parents[3].joinpath("install/setup.bash")) # -> "source /home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/install/setup.bash" + command = f"{src} && ros2 launch crazyflie launch.py" + launch_crazyswarm = Popen(command, shell=True, stderr=True, stdout=True, text=True, + start_new_session=True, executable="/bin/bash") + + time.sleep(1) + print("f8") + record_start_and_terminate("figure8", 20, bagfolder) + print("multi") + record_start_and_terminate("multi_trajectory", 80, bagfolder) + + os.killpg(os.getpgid(launch_crazyswarm.pid), signal.SIGTERM) #kill crazyswarm and all of its child processes + + + #test done, now we create the results pdf + translate_and_plot("figure8", bagfolder) + translate_and_plot("multi_trajectory", bagfolder) + + exit(0) From 5bd08d8194ac97062a11645e79c3eeff3621c53e Mon Sep 17 00:00:00 2001 From: julienthevenoz <125280576+julienthevenoz@users.noreply.github.com> Date: Thu, 7 Dec 2023 21:47:58 +0100 Subject: [PATCH 046/162] Improve systemtests (#378) * clean processes automatically at exit; replaced custom Waiter class with Popen.wait() function * cleanup --- .github/workflows/systemtests.yml | 2 +- systemtests/run_test.py | 105 +++++++++++++++++------------- 2 files changed, 61 insertions(+), 46 deletions(-) diff --git a/.github/workflows/systemtests.yml b/.github/workflows/systemtests.yml index 21588070b..da29294a4 100644 --- a/.github/workflows/systemtests.yml +++ b/.github/workflows/systemtests.yml @@ -2,7 +2,7 @@ name: System Tests on: push: - branches: [ "feature_systemtests" ] + branches: [ "feature-systemtests-better" ] # manual trigger workflow_dispatch: diff --git a/systemtests/run_test.py b/systemtests/run_test.py index 73cfa1406..d5f80f554 100755 --- a/systemtests/run_test.py +++ b/systemtests/run_test.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 #!/usr/bin/env python3 -from subprocess import Popen, PIPE +from subprocess import Popen, PIPE, TimeoutExpired import time import os import signal @@ -12,45 +12,58 @@ import atexit -class Waiter: - '''A helper class which sleeps the amount of seconds it is instanciated with. If the user interrupts with ^C during the waiting time (zB if the drone crashes), it will stop sleeping and continue - to the end of the program where all child processes are terminated correctly. All subsequent Waiter() calls will be ignored''' - wait=True +def clean_process(process:Popen) -> int : + '''Kills process and its children on exit if they aren't already terminated (called with atexit). Returns 0 on success, 1 on failure''' + + if process.poll() == None: + group_id = os.getpgid(process.pid) + print(f"cleaning process {group_id}") + os.killpg(group_id, signal.SIGTERM) + time.sleep(0.01) #necessary delay before first poll + i=0 + while i < 10 and process.poll() == None: #in case the process termination is lazy and takes some time, we wait up to 0.5 sec per process + if process.poll() != None: + return 0 #if we have a returncode-> it terminated + time.sleep(0.05) #if not wait a bit longer + if(i == 9): + print(f"Process group {process} with groupID {group_id} didn't terminate correctly") + return 1 #after 0.5s we stop waiting and consider it did not terminate correctly + return 0 + else: + return 0 #process already terminated - def __init__(self, seconds): - if seconds > 0 : - self.sleep(seconds) - - def sleep(self, seconds): - start=time.time() - while Waiter.wait and time.time()<(start+seconds): - try: - time.sleep(1) - except KeyboardInterrupt: - Waiter.wait = False - -def record_start_and_terminate(testname:str, testduration:int, bagfolder:str): - '''Helper function that starts recording the /tf topic in a rosbag, starts the test, waits, closes the rosbag and terminate all processes + +def record_start_and_clean(testname:str, max_wait:int, bagfolder:str): + '''Starts recording the /tf topic in a rosbag, starts the test, waits, closes the rosbag and terminate all processes. max_wait is the max amount of time you want to wait + before forcefully terminating the test flight script (in case it never finishes correctly). NB the testname must be the name of the crayzflie_examples executable (ie the CLI grammar "ros2 run crazyflie_examples testname" must be valid)''' + index = bagfolder.find("bag_") bagname = bagfolder[index:] - - src = "source " + bagfolder[:index-9] + "install/setup.bash" # -> "source /home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/install/setup.bash" - - command = f"{src} && ros2 bag record -s mcap -o {testname}_{bagname} /tf" - record_bag = Popen(command, shell=True, cwd=bagfolder, stderr=PIPE, stdout=True, - start_new_session=True, text=True, executable="/bin/bash") - command = f"{src} && ros2 run crazyflie_examples {testname}" - start_flight_test = Popen(command, shell=True, stderr=True, stdout=True, - start_new_session=True, text=True, executable="/bin/bash") - + try: + command = f"{src} && ros2 bag record -s mcap -o {testname}_{bagname} /tf" + record_bag = Popen(command, shell=True, cwd=bagfolder, stderr=PIPE, stdout=True, + start_new_session=True, text=True, executable="/bin/bash") + atexit.register(clean_process, record_bag) + + command = f"{src} && ros2 run crazyflie_examples {testname}" + start_flight_test = Popen(command, shell=True, stderr=True, stdout=True, + start_new_session=True, text=True, executable="/bin/bash") + atexit.register(clean_process, start_flight_test) - Waiter(testduration) #wait x seconds for the crazyflie to fly the test + start_flight_test.wait(timeout=max_wait) #raise Timeoutexpired after max_wait seconds if start_flight_test didn't finish by itself + clean_process(start_flight_test) + clean_process(record_bag) - os.killpg(os.getpgid(start_flight_test.pid), signal.SIGTERM) #kill flight test and all of its child processes - os.killpg(os.getpgid(record_bag.pid), signal.SIGTERM) #kill rosbag + except TimeoutExpired: #if max_wait is exceeded + clean_process(start_flight_test) + clean_process(record_bag) + + except KeyboardInterrupt: #if drone crashes, user can ^C to skip the waiting + clean_process(start_flight_test) + clean_process(record_bag) #if something went wrong with the bash command lines in Popen, print the error if record_bag.stderr != None: @@ -59,9 +72,9 @@ def record_start_and_terminate(testname:str, testduration:int, bagfolder:str): print(testname," start_flight flight stderr: ", start_flight_test.stderr.readlines()) - def translate_and_plot(testname:str, bagfolder:str): - '''Helper function that translates rosbag .mcap format to .csv, then uses that csv to plot a pdf ''' + '''Translates rosbag .mcap format to .csv, then uses that csv to plot a pdf ''' + index = bagfolder.find("bag_") bagname = bagfolder[index:] # NB : the mcap filename is almost the same as the folder name but has _0 at the end @@ -81,15 +94,18 @@ def translate_and_plot(testname:str, bagfolder:str): plotter.create_figures(test_file, rosbag_csv, output_pdf) #plot the data + if __name__ == "__main__": - path = Path(__file__) #Path(__file__) should be "/home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/src/crazyswarm2/systemtests/newsub.py" ; path.parents[0]=.../systemstests + path = Path(__file__) #Path(__file__) in this case "/home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/src/crazyswarm2/systemtests/newsub.py" ; path.parents[0]=.../systemstests - #delete results, logs and bags of previous experiments - shutil.rmtree(path.parents[3].joinpath("bagfiles")) - shutil.rmtree(path.parents[3].joinpath("results")) - shutil.rmtree(Path.home() / ".ros/log") - + #delete results, logs and bags of previous experiments if they exist + if(Path(path.parents[3].joinpath("bagfiles")).exists()): + shutil.rmtree(path.parents[3].joinpath("bagfiles")) + if(Path(path.parents[3].joinpath("results")).exists()): + shutil.rmtree(path.parents[3].joinpath("results")) + if(Path(Path.home() / ".ros/log").exists()): + shutil.rmtree(Path.home() / ".ros/log") #create the folder where we will record the different bags and the folder where the results pdf will be saved now = datetime.now().strftime('%d_%m_%Y-%H_%M_%S') @@ -102,14 +118,13 @@ def translate_and_plot(testname:str, bagfolder:str): command = f"{src} && ros2 launch crazyflie launch.py" launch_crazyswarm = Popen(command, shell=True, stderr=True, stdout=True, text=True, start_new_session=True, executable="/bin/bash") + atexit.register(clean_process, launch_crazyswarm) #atexit helps us to make sure processes are cleaned even if script exits unexpectedly time.sleep(1) - print("f8") - record_start_and_terminate("figure8", 20, bagfolder) - print("multi") - record_start_and_terminate("multi_trajectory", 80, bagfolder) + record_start_and_clean("figure8", 20, bagfolder) + record_start_and_clean("multi_trajectory", 80, bagfolder) - os.killpg(os.getpgid(launch_crazyswarm.pid), signal.SIGTERM) #kill crazyswarm and all of its child processes + clean_process(launch_crazyswarm) #kill crazyswarm and all of its child processes #test done, now we create the results pdf From 455eceb5cba48333782a816e784458c72cf2aabf Mon Sep 17 00:00:00 2001 From: Kimberly McGuire Date: Wed, 13 Dec 2023 09:38:44 +0100 Subject: [PATCH 047/162] Update overview.rst --- docs2/overview.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs2/overview.rst b/docs2/overview.rst index 7cb09506e..c824081d2 100644 --- a/docs2/overview.rst +++ b/docs2/overview.rst @@ -75,7 +75,7 @@ Support functionality with backends +---------------------+---------+-----------+---------+ | Manual control | +---------------------+---------+-----------+---------+ -| - cmd_full_state | Yes | No | Yes | +| - cmd_full_state | Yes | Yes | Yes | +---------------------+---------+-----------+---------+ | - cmd_position | Yes | No | No | +---------------------+---------+-----------+---------+ From 963df7b71302e471cc075af3234e051f2968c923 Mon Sep 17 00:00:00 2001 From: HP99 Date: Wed, 13 Dec 2023 19:13:28 +0100 Subject: [PATCH 048/162] fix yaw conversion from quat in cmd_full_state in crazyflie_sim/crazyflie_server (#382) --- crazyflie_sim/crazyflie_sim/crazyflie_server.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/crazyflie_sim/crazyflie_sim/crazyflie_server.py b/crazyflie_sim/crazyflie_sim/crazyflie_server.py index 8c3364e83..0d05fede7 100755 --- a/crazyflie_sim/crazyflie_sim/crazyflie_server.py +++ b/crazyflie_sim/crazyflie_sim/crazyflie_server.py @@ -326,7 +326,7 @@ def _cmd_full_state_changed(self, msg, name): msg.pose.orientation.x, msg.pose.orientation.y, msg.pose.orientation.z] - rpy = rowan.to_euler(q) + rpy = rowan.to_euler(q, convention='xyz') self.cfs[name].cmdFullState( [msg.pose.position.x, msg.pose.position.y, msg.pose.position.z], From d446a09a56d81508b552b0e60bd9b94c69e49348 Mon Sep 17 00:00:00 2001 From: HP99 Date: Wed, 13 Dec 2023 19:22:39 +0100 Subject: [PATCH 049/162] fix quaternion integration equation in backend np (#383) * fix quaternion integration equation in backend np --- crazyflie_sim/crazyflie_sim/backend/np.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/crazyflie_sim/crazyflie_sim/backend/np.py b/crazyflie_sim/crazyflie_sim/backend/np.py index 26e0c4cc3..92d35528c 100644 --- a/crazyflie_sim/crazyflie_sim/backend/np.py +++ b/crazyflie_sim/crazyflie_sim/backend/np.py @@ -110,9 +110,11 @@ def rpm_to_force(rpm): # to integrate the dynamics, see # https://www.ashwinnarayan.com/post/how-to-integrate-quaternions/, and # https://arxiv.org/pdf/1604.08139.pdf + # Sec 4.5, https://arxiv.org/pdf/1711.02508.pdf + omega_global = rowan.rotate(self.state.quat, self.state.omega) q_next = rowan.normalize( rowan.calculus.integrate( - self.state.quat, self.state.omega, dt)) + self.state.quat, omega_global, dt)) # mJ = Jw x w + tau_u omega_next = self.state.omega + ( From 253a7aa54d9711a8605b672432f417d2eddb61ac Mon Sep 17 00:00:00 2001 From: Kimberly McGuire Date: Thu, 14 Dec 2023 09:49:22 +0100 Subject: [PATCH 050/162] remove logging --- crazyflie/scripts/crazyflie_server.py | 4 ---- 1 file changed, 4 deletions(-) diff --git a/crazyflie/scripts/crazyflie_server.py b/crazyflie/scripts/crazyflie_server.py index ea75853c0..ca44a9320 100755 --- a/crazyflie/scripts/crazyflie_server.py +++ b/crazyflie/scripts/crazyflie_server.py @@ -946,8 +946,6 @@ def _cmd_hover_changed(self, msg, uri=""): yawrate = -1.0*degrees(msg.yaw_rate) self.swarm._cfs[uri].cf.commander.send_hover_setpoint( vx, vy, yawrate, z) - self.get_logger().info( - f"{uri}: Received hover topic {vx} {vy} {yawrate} {z}") def _cmd_full_state_changed(self, msg, uri=""): """ @@ -960,9 +958,7 @@ def _cmd_full_state_changed(self, msg, uri=""): roll_rate = msg.twist.angular.x pitch_rate = msg.twist.angular.y yaw_rate = msg.twist.angular.z - self.swarm._cfs[uri].cf.commander.send_full_state_setpoint(pos, vel, acc, q, roll_rate, pitch_rate, yaw_rate) - self.get_logger().info(f"{uri}: Received full state topic {pos} {vel} {acc} {q}, {roll_rate}, {pitch_rate}, {yaw_rate}") def _remove_logging(self, request, response, uri="all"): """ From ba56210da49a9a1029baf2714c03ec17dc2677fe Mon Sep 17 00:00:00 2001 From: Kimberly McGuire Date: Thu, 14 Dec 2023 09:50:19 +0100 Subject: [PATCH 051/162] Update overview.rst --- docs2/overview.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs2/overview.rst b/docs2/overview.rst index c824081d2..014cfc93d 100644 --- a/docs2/overview.rst +++ b/docs2/overview.rst @@ -75,7 +75,7 @@ Support functionality with backends +---------------------+---------+-----------+---------+ | Manual control | +---------------------+---------+-----------+---------+ -| - cmd_full_state | Yes | Yes | Yes | +| - cmd_full_state | Yes | Yes | Yes | +---------------------+---------+-----------+---------+ | - cmd_position | Yes | No | No | +---------------------+---------+-----------+---------+ From 9db83605dc687c68f142f271536b4a380e823fb8 Mon Sep 17 00:00:00 2001 From: julienthevenoz <125280576+julienthevenoz@users.noreply.github.com> Date: Sun, 17 Dec 2023 21:09:59 +0100 Subject: [PATCH 052/162] Feature pytest (#386) * Python unittest integration * replaced run_test.py with test_flights.py ; changed the github action accordingly; corrected 0.3m x-offset in plotter for multi_trajectory (and other details) * Results folder uploaded even if step5 (flight_test) failed --- .github/workflows/systemtests.yml | 8 +- systemtests/plotter_class.py | 36 ++++--- systemtests/run_test.py | 134 ------------------------ systemtests/test_flights.py | 162 ++++++++++++++++++++++++++++++ 4 files changed, 190 insertions(+), 150 deletions(-) delete mode 100755 systemtests/run_test.py create mode 100644 systemtests/test_flights.py diff --git a/.github/workflows/systemtests.yml b/.github/workflows/systemtests.yml index da29294a4..045b64049 100644 --- a/.github/workflows/systemtests.yml +++ b/.github/workflows/systemtests.yml @@ -39,17 +39,17 @@ jobs: source /opt/ros/humble/setup.bash . install/local_setup.bash export ROS_LOCALHOST_ONLY=1 - python3 src/crazyswarm2/systemtests/run_test.py + python3 src/crazyswarm2/systemtests/test_flights.py - name: Upload files id: step6 + if: '!cancelled()' uses: actions/upload-artifact@v3 with: - name: pdf_bagfiles_and_logs + name: pdf_rosbags_and_logs path: | - ros2_ws/bagfiles ros2_ws/results - ~/.ros/log + diff --git a/systemtests/plotter_class.py b/systemtests/plotter_class.py index beca43e33..5655aedb6 100644 --- a/systemtests/plotter_class.py +++ b/systemtests/plotter_class.py @@ -4,6 +4,7 @@ from matplotlib.backends.backend_pdf import PdfPages import numpy as np from crazyflie_py.uav_trajectory import Trajectory +from pathlib import Path class Plotter: @@ -21,9 +22,10 @@ def __init__(self): self.deviation = [] #list of all indexes where euclidian_distance(ideal - recorded) > EPSILON self.EPSILON = 0.05 # euclidian distance in [m] between ideal and recorded trajectory under which the drone has to stay to pass the test - self.DELAY_CONST_FIG8 = 4.75 #this is the delay constant which I found by adding up all the time.sleep() etc in the figure8.py file. This should be implemented better later - self.ALTITUDE_CONST_FIG8 = 1.0 #this is the altitude given for the takeoff in figure8.py. I should find a better solution than a symbolic constant ? + self.DELAY_CONST_FIG8 = 4.75 #this is the delay constant which I found by adding up all the time.sleep() etc in the figure8.py file. This could be implemented better later ? + self.ALTITUDE_CONST_FIG8 = 1 #this is the altitude given for the takeoff in figure8.py. I should find a better solution than a symbolic constant ? self.ALTITUDE_CONST_MULTITRAJ = 1 #takeoff altitude for traj0 in multi_trajectory.py + self.X_OFFSET_CONST_MULTITRAJ = -0.3 #offest on the x axis between ideal and real trajectory. Reason: ideal trajectory (traj0.csv) starts with offset of 0.3m and CrazyflieServer.startTrajectory() is relative to start position def file_guard(self, pdf_path): msg = None @@ -45,18 +47,22 @@ def file_guard(self, pdf_path): def read_csv_and_set_arrays(self, ideal_csvfile, rosbag_csvfile): '''Method that reads the csv data of the ideal test trajectory and of the actual recorded trajectory and initializes the attribute arrays''' - #check which test we are plotting : figure8 or multi_trajectory - if("fig8" in rosbag_csvfile): - fig8 = True + #check which test we are plotting : figure8 or multi_trajectory or another one + if("figure8" in rosbag_csvfile): + fig8, m_t = True, False print("Plotting fig8 test data") - else: - fig8 = False + elif "multi_trajectory" in rosbag_csvfile: + fig8, m_t = False, True print("Plotting multi_trajectory test data") + else: + fig8, m_t = False, False + print("Plotting unspecified test data") #get ideal trajectory data self.ideal_traj_csv = Trajectory() try: path_to_ideal_csv = os.path.join(os.path.dirname(os.path.abspath(__file__)),ideal_csvfile) + print(path_to_ideal_csv) self.ideal_traj_csv.loadcsv(path_to_ideal_csv) except FileNotFoundError: print("Plotter : File not found " + path_to_ideal_csv) @@ -93,11 +99,15 @@ def read_csv_and_set_arrays(self, ideal_csvfile, rosbag_csvfile): pos = [0,0,0] #for all recorded datapoints who cannot be matched to a corresponding ideal position we assume the drone is on its ground start position (ie those datapoints are before takeoff or after landing) - self.ideal_traj_x[i], self.ideal_traj_y[i]= pos[0], pos[1] - if(fig8) : #special case : in fig8 test no altitude is given in the trajectory polynomials but is stays constant after takeoff in figure8.py - self.ideal_traj_z[i] = self.ALTITUDE_CONST_FIG8 - else : #for multi_trajectory test the altitude given in the trajectory polynomials is added to the takeoff altitude - self.ideal_traj_z[i] = self.ALTITUDE_CONST_MULTITRAJ + pos[2] + self.ideal_traj_x[i], self.ideal_traj_y[i], self.ideal_traj_z[i]= pos[0], pos[1], pos[2] + + #special cases + if fig8: + self.ideal_traj_z[i] = self.ALTITUDE_CONST_FIG8 #special case: in fig8 no altitude is given in the trajectory polynomials (idealcsv) but is fixed as the takeoff altitude in figure8.py + elif m_t: + self.ideal_traj_z[i] = pos[2] + self.ALTITUDE_CONST_MULTITRAJ #for multi_trajectory the altitude given in the trajectory polynomials is added to the fixed takeoff altitude specified in multi_trajectory.py + self.ideal_traj_x[i] = pos[0] + self.X_OFFSET_CONST_MULTITRAJ #the x-axis is offset by 0.3 m because ideal start position not being (0,0,0) + self.euclidian_dist[i] = np.linalg.norm([self.ideal_traj_x[i]-self.bag_x[i], self.ideal_traj_y[i]-self.bag_y[i], self.ideal_traj_z[i]-self.bag_z[i]]) @@ -341,3 +351,5 @@ def test_passed(self) -> bool : if args.open: import subprocess subprocess.call(["xdg-open", args.pdf]) + + diff --git a/systemtests/run_test.py b/systemtests/run_test.py deleted file mode 100755 index d5f80f554..000000000 --- a/systemtests/run_test.py +++ /dev/null @@ -1,134 +0,0 @@ -#!/usr/bin/env python3 -#!/usr/bin/env python3 -from subprocess import Popen, PIPE, TimeoutExpired -import time -import os -import signal -from mcap_handler import McapHandler -from datetime import datetime -from plotter_class import Plotter -from pathlib import Path -import shutil -import atexit - - -def clean_process(process:Popen) -> int : - '''Kills process and its children on exit if they aren't already terminated (called with atexit). Returns 0 on success, 1 on failure''' - - if process.poll() == None: - group_id = os.getpgid(process.pid) - print(f"cleaning process {group_id}") - os.killpg(group_id, signal.SIGTERM) - time.sleep(0.01) #necessary delay before first poll - i=0 - while i < 10 and process.poll() == None: #in case the process termination is lazy and takes some time, we wait up to 0.5 sec per process - if process.poll() != None: - return 0 #if we have a returncode-> it terminated - time.sleep(0.05) #if not wait a bit longer - if(i == 9): - print(f"Process group {process} with groupID {group_id} didn't terminate correctly") - return 1 #after 0.5s we stop waiting and consider it did not terminate correctly - return 0 - else: - return 0 #process already terminated - - -def record_start_and_clean(testname:str, max_wait:int, bagfolder:str): - '''Starts recording the /tf topic in a rosbag, starts the test, waits, closes the rosbag and terminate all processes. max_wait is the max amount of time you want to wait - before forcefully terminating the test flight script (in case it never finishes correctly). - NB the testname must be the name of the crayzflie_examples executable (ie the CLI grammar "ros2 run crazyflie_examples testname" must be valid)''' - - index = bagfolder.find("bag_") - bagname = bagfolder[index:] - src = "source " + bagfolder[:index-9] + "install/setup.bash" # -> "source /home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/install/setup.bash" - - try: - command = f"{src} && ros2 bag record -s mcap -o {testname}_{bagname} /tf" - record_bag = Popen(command, shell=True, cwd=bagfolder, stderr=PIPE, stdout=True, - start_new_session=True, text=True, executable="/bin/bash") - atexit.register(clean_process, record_bag) - - command = f"{src} && ros2 run crazyflie_examples {testname}" - start_flight_test = Popen(command, shell=True, stderr=True, stdout=True, - start_new_session=True, text=True, executable="/bin/bash") - atexit.register(clean_process, start_flight_test) - - start_flight_test.wait(timeout=max_wait) #raise Timeoutexpired after max_wait seconds if start_flight_test didn't finish by itself - clean_process(start_flight_test) - clean_process(record_bag) - - except TimeoutExpired: #if max_wait is exceeded - clean_process(start_flight_test) - clean_process(record_bag) - - except KeyboardInterrupt: #if drone crashes, user can ^C to skip the waiting - clean_process(start_flight_test) - clean_process(record_bag) - - #if something went wrong with the bash command lines in Popen, print the error - if record_bag.stderr != None: - print(testname," record_bag stderr: ", record_bag.stderr.readlines()) - if start_flight_test.stderr != None: - print(testname," start_flight flight stderr: ", start_flight_test.stderr.readlines()) - - -def translate_and_plot(testname:str, bagfolder:str): - '''Translates rosbag .mcap format to .csv, then uses that csv to plot a pdf ''' - - index = bagfolder.find("bag_") - bagname = bagfolder[index:] - # NB : the mcap filename is almost the same as the folder name but has _0 at the end - inputbag = str(bagfolder) + f"/{testname}_{bagname}/{testname}_{bagname}_0.mcap" - output_csv = str(bagfolder) + f"/{testname}_{bagname}/{testname}_{bagname}_0.csv" - writer = McapHandler() - writer.write_mcap_to_csv(inputbag, output_csv) #translate bag from mcap to csv - output_pdf = str(path.parents[3].joinpath(f"results/Results_{testname}_"+ now +".pdf")) - rosbag_csv = output_csv - if "figure8" in testname: - test_file = "../crazyflie_examples/crazyflie_examples/data/figure8.csv" - elif "multi_trajectory" in testname: - test_file = "../crazyflie_examples/crazyflie_examples/data/multi_trajectory/traj0.csv" - else: - print("run_test.py : test file not defined") - plotter = Plotter() - plotter.create_figures(test_file, rosbag_csv, output_pdf) #plot the data - - - -if __name__ == "__main__": - - path = Path(__file__) #Path(__file__) in this case "/home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/src/crazyswarm2/systemtests/newsub.py" ; path.parents[0]=.../systemstests - - #delete results, logs and bags of previous experiments if they exist - if(Path(path.parents[3].joinpath("bagfiles")).exists()): - shutil.rmtree(path.parents[3].joinpath("bagfiles")) - if(Path(path.parents[3].joinpath("results")).exists()): - shutil.rmtree(path.parents[3].joinpath("results")) - if(Path(Path.home() / ".ros/log").exists()): - shutil.rmtree(Path.home() / ".ros/log") - - #create the folder where we will record the different bags and the folder where the results pdf will be saved - now = datetime.now().strftime('%d_%m_%Y-%H_%M_%S') - bagfolder = str((path.parents[3].joinpath(f"bagfiles/bag_" + now))) # /home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/bagfiles/bag_d_m_Y-H_M_S - os.makedirs(bagfolder) - os.makedirs(path.parents[3].joinpath("results")) # /home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/results - - - src = "source " + str(path.parents[3].joinpath("install/setup.bash")) # -> "source /home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/install/setup.bash" - command = f"{src} && ros2 launch crazyflie launch.py" - launch_crazyswarm = Popen(command, shell=True, stderr=True, stdout=True, text=True, - start_new_session=True, executable="/bin/bash") - atexit.register(clean_process, launch_crazyswarm) #atexit helps us to make sure processes are cleaned even if script exits unexpectedly - - time.sleep(1) - record_start_and_clean("figure8", 20, bagfolder) - record_start_and_clean("multi_trajectory", 80, bagfolder) - - clean_process(launch_crazyswarm) #kill crazyswarm and all of its child processes - - - #test done, now we create the results pdf - translate_and_plot("figure8", bagfolder) - translate_and_plot("multi_trajectory", bagfolder) - - exit(0) diff --git a/systemtests/test_flights.py b/systemtests/test_flights.py new file mode 100644 index 000000000..cfd84f1c1 --- /dev/null +++ b/systemtests/test_flights.py @@ -0,0 +1,162 @@ +import unittest + +from pathlib import Path +import shutil +import os +from plotter_class import Plotter +from mcap_handler import McapHandler +from subprocess import Popen, PIPE, TimeoutExpired +import time +import signal +import atexit + +############################# + +def setUpModule(): + + path = Path(__file__) #Path(__file__) in this case "/home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/src/crazyswarm2/systemtests/test_flights.py" ; path.parents[0]=.../systemstests + + #delete results, logs and bags of previous experiments if they exist + if(Path(path.parents[3] / "results").exists()): + shutil.rmtree(path.parents[3] / "results") + + os.makedirs(path.parents[3] / "results") # /home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/results + +def tearDownModule(): + pass + + +def clean_process(process:Popen) -> int : + '''Kills process and its children on exit if they aren't already terminated (called with atexit). Returns 0 on termination, 1 if SIGKILL was needed''' + if process.poll() == None: + group_id = os.getpgid(process.pid) + print(f"cleaning process {group_id}") + os.killpg(group_id, signal.SIGTERM) + time.sleep(0.01) #necessary delay before first poll + i=0 + while i < 10 and process.poll() == None: #in case the process termination is lazy and takes some time, we wait up to 0.5 sec per process + if process.poll() != None: + return 0 #if we have a returncode-> it terminated + time.sleep(0.05) #if not wait a bit longer + if(i == 9): + os.killpg(group_id, signal.SIGKILL) + return 1 #after 0.5s we stop waiting, consider it did not terminate correctly and kill it + return 0 + else: + return 0 #process already terminated + + +class TestFlights(unittest.TestCase): + + def __init__(self, methodName: str = "runTest") -> None: + super().__init__(methodName) + self.test_file = None + self.launch_crazyswarm : Popen = None + self.ros2_ws = Path(__file__).parents[3] #/home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws + + def idFolderName(self): + return self.id().split(".")[-1] #returns the name of the test_function currently being run, for example "test_figure8" + + # runs once per test_ function + def setUp(self): + + if(Path(Path.home() / ".ros/log").exists()): #delete log files of the previous test + shutil.rmtree(Path.home() / ".ros/log") + self.test_file = None + + # launch server + src = "source " + str(Path(__file__).parents[3] / "install/setup.bash") # -> "source /home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/install/setup.bash" + command = f"{src} && ros2 launch crazyflie launch.py" + self.launch_crazyswarm = Popen(command, shell=True, stderr=True, stdout=PIPE, text=True, + start_new_session=True, executable="/bin/bash") + atexit.register(clean_process, self.launch_crazyswarm) #atexit helps us to make sure processes are cleaned even if script exits unexpectedly + time.sleep(1) + + + # runs once per test_ function + def tearDown(self) -> None: + clean_process(self.launch_crazyswarm) #kill crazyswarm_server and all of its child processes + + # copy .ros/log files to results folder + if Path(Path.home() / ".ros/log").exists(): + shutil.copytree(Path.home() / ".ros/log", Path(__file__).parents[3] / f"results/{self.idFolderName()}/roslogs") + + return super().tearDown() + + + + def record_start_and_clean(self, testname:str, max_wait:int): + '''Starts recording the /tf topic in a rosbag, starts the test, waits, closes the rosbag and terminate all processes. max_wait is the max amount of time you want to wait + before forcefully terminating the test flight script (in case it never finishes correctly). + NB the testname must be the name of the crayzflie_examples executable (ie the CLI grammar "ros2 run crazyflie_examples testname" must be valid)''' + + src = f"source {str(self.ros2_ws)}/install/setup.bash" + try: + command = f"{src} && ros2 bag record -s mcap -o test_{testname} /tf" + record_bag = Popen(command, shell=True, stderr=PIPE, stdout=True, text=True, + cwd= self.ros2_ws / "results/", start_new_session=True, executable="/bin/bash") + atexit.register(clean_process, record_bag) + + command = f"{src} && ros2 run crazyflie_examples {testname}" + start_flight_test = Popen(command, shell=True, stderr=True, stdout=True, + start_new_session=True, text=True, executable="/bin/bash") + atexit.register(clean_process, start_flight_test) + + start_flight_test.wait(timeout=max_wait) #raise Timeoutexpired after max_wait seconds if start_flight_test didn't finish by itself + clean_process(start_flight_test) + clean_process(record_bag) + + except TimeoutExpired: #if max_wait is exceeded + clean_process(start_flight_test) + clean_process(record_bag) + + except KeyboardInterrupt: #if drone crashes, user can ^C to skip the waiting + clean_process(start_flight_test) + clean_process(record_bag) + + #if something went wrong with the bash command lines in Popen, print the error + if record_bag.stderr != None: + print(testname," record_bag stderr: ", record_bag.stderr.readlines()) + if start_flight_test.stderr != None: + print(testname," start_flight flight stderr: ", start_flight_test.stderr.readlines()) + + + def translate_plot_and_check(self, testname:str) -> bool : + '''Translates rosbag .mcap format to .csv, then uses that csv to plot a pdf. Checks the deviation between ideal and real trajectories, i.e if the drone + successfully followed its given trajectory. Returns True if deviation < epsilon(defined in plotter_class.py) at every timestep, false if not. ''' + + # NB : the mcap filename is almost the same as the folder name but has _0 at the end + inputbag = f"{str(self.ros2_ws)}/results/test_{testname}/test_{testname}_0.mcap" + output_csv = f"{str(self.ros2_ws)}/results/test_{testname}/test_{testname}_0.csv" + + writer = McapHandler() + writer.write_mcap_to_csv(inputbag, output_csv) #translate bag from mcap to csv + output_pdf = f"{str(self.ros2_ws)}/results/test_{testname}/results_{testname}.pdf" + rosbag_csv = output_csv + + plotter = Plotter() + plotter.create_figures(self.test_file, rosbag_csv, output_pdf) #plot the data + return plotter.test_passed() + + + + def test_figure8(self): + self.test_file = "../crazyflie_examples/crazyflie_examples/data/figure8.csv" + # run test + self.record_start_and_clean("figure8", 20) + #create the plot etc + test_passed = self.translate_plot_and_check("figure8") + assert test_passed, "figure8 test failed : deviation larger than epsilon" + + def test_multi_trajectory(self): + self.test_file = "../crazyflie_examples/crazyflie_examples/data/multi_trajectory/traj0.csv" + self.record_start_and_clean("multi_trajectory", 80) + test_passed = self.translate_plot_and_check("multi_trajectory") + assert test_passed, "multitrajectory test failed : deviation larger than epsilon" + + + + +if __name__ == '__main__': + unittest.main() + From e954bc866c94116d7be87c4d60e6c2827ab89dbc Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Wed, 20 Dec 2023 06:50:53 +0100 Subject: [PATCH 053/162] Fix frequent crashes of figure8 example * Update crazyflie_cpp to upload trajectory pieces one-by-one (waiting for the result), similar to how we handle firmware communication issues for reading the various TOCs or parameters * Changing the Python layer to make uploadTrajectory a blocking call, i.e., waiting until the upload succeeded --- crazyflie/deps/crazyflie_tools | 2 +- crazyflie_py/crazyflie_py/crazyflie.py | 6 +++++- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/crazyflie/deps/crazyflie_tools b/crazyflie/deps/crazyflie_tools index 1efd3788f..fbd1f7306 160000 --- a/crazyflie/deps/crazyflie_tools +++ b/crazyflie/deps/crazyflie_tools @@ -1 +1 @@ -Subproject commit 1efd3788f5bf59e0fa3da2e4d2bc5cd7bee5b0fc +Subproject commit fbd1f730636f01632b3b99abd0fb2a0789a2d221 diff --git a/crazyflie_py/crazyflie_py/crazyflie.py b/crazyflie_py/crazyflie_py/crazyflie.py index 025cac736..da83edd48 100644 --- a/crazyflie_py/crazyflie_py/crazyflie.py +++ b/crazyflie_py/crazyflie_py/crazyflie.py @@ -389,7 +389,11 @@ def uploadTrajectory(self, trajectoryId, pieceOffset, trajectory): req.trajectory_id = trajectoryId req.piece_offset = pieceOffset req.pieces = pieces - self.uploadTrajectoryService.call_async(req) + future = self.uploadTrajectoryService.call_async(req) + while rclpy.ok(): + rclpy.spin_once(self.node) + if future.done(): + break def startTrajectory(self, trajectoryId, timescale=1.0, reverse=False, From ec7344cab6277fd2b01a24833005a89ea767c1ca Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Wolfgang=20H=C3=B6nig?= Date: Sun, 31 Dec 2023 21:41:24 +0100 Subject: [PATCH 054/162] crazyflie_py: add support for setting groupMask (#384) * crazyflie_py: add support for setting groupMask See https://github.com/IMRCLab/crazyswarm2/discussions/203 Only works with recent firmware versions. --- .../crazyflie_examples/group_mask.py | 27 +++++++++++ crazyflie_examples/setup.cfg | 1 + crazyflie_py/crazyflie_py/crazyflie.py | 48 +++++++++++-------- 3 files changed, 55 insertions(+), 21 deletions(-) create mode 100644 crazyflie_examples/crazyflie_examples/group_mask.py diff --git a/crazyflie_examples/crazyflie_examples/group_mask.py b/crazyflie_examples/crazyflie_examples/group_mask.py new file mode 100644 index 000000000..72ee8b2a9 --- /dev/null +++ b/crazyflie_examples/crazyflie_examples/group_mask.py @@ -0,0 +1,27 @@ +#!/usr/bin/env python + +from crazyflie_py import Crazyswarm + + +def main(): + swarm = Crazyswarm() + timeHelper = swarm.timeHelper + allcfs = swarm.allcfs + + # set group mask to enable group 1 and 4 (one by one) + for cf in allcfs.crazyflies: + cf.setGroupMask(0b00001001) + + print('Takeoff with a different mask (2) -> nothing should happen') + allcfs.takeoff(targetHeight=0.5, duration=3.0, groupMask=2) + timeHelper.sleep(3) + + print('Takeoff with correct mask (1) -> should work') + allcfs.takeoff(targetHeight=0.5, duration=3.0, groupMask=1) + timeHelper.sleep(3) + allcfs.land(targetHeight=0.02, duration=3.0) + timeHelper.sleep(3) + + +if __name__ == '__main__': + main() diff --git a/crazyflie_examples/setup.cfg b/crazyflie_examples/setup.cfg index 06e3a1c1a..b1b614c9e 100644 --- a/crazyflie_examples/setup.cfg +++ b/crazyflie_examples/setup.cfg @@ -3,6 +3,7 @@ console_scripts = hello_world = crazyflie_examples.hello_world:main nice_hover = crazyflie_examples.nice_hover:main figure8 = crazyflie_examples.figure8:main + group_mask = crazyflie_examples.group_mask:main multi_trajectory = crazyflie_examples.multi_trajectory:main cmd_full_state = crazyflie_examples.cmd_full_state:main set_param = crazyflie_examples.set_param:main diff --git a/crazyflie_py/crazyflie_py/crazyflie.py b/crazyflie_py/crazyflie_py/crazyflie.py index da83edd48..bbb7cbf2f 100644 --- a/crazyflie_py/crazyflie_py/crazyflie.py +++ b/crazyflie_py/crazyflie_py/crazyflie.py @@ -114,8 +114,6 @@ def __init__(self, node, cfname, paramTypeDict): # self.tf = tf - # rospy.wait_for_service(prefix + '/set_group_mask') - # self.setGroupMaskService = rospy.ServiceProxy(prefix + '/set_group_mask', SetGroupMask) self.emergencyService = node.create_client(Empty, prefix + '/emergency') self.emergencyService.wait_for_service() self.takeoffService = node.create_client(Takeoff, prefix + '/takeoff') @@ -186,29 +184,37 @@ def __init__(self, node, cfname, paramTypeDict): # self.cmdVelocityWorldMsg.header.seq = 0 # self.cmdVelocityWorldMsg.header.frame_id = '/world' - # def setGroupMask(self, groupMask): - # """Sets the group mask bits for this robot. + def setGroupMask(self, groupMask): + """ + Set the group mask bits for this robot. - # The purpose of groups is to make it possible to trigger an action - # (for example, executing a previously-uploaded trajectory) on a subset - # of all robots without needing to send more than one radio packet. - # This is important to achieve tight, synchronized 'choreography'. + The purpose of groups is to make it possible to trigger an action + (for example, executing a previously-uploaded trajectory) on a subset + of all robots without needing to send more than one radio packet. + This is important to achieve tight, synchronized 'choreography'. - # Up to 8 groups may exist, corresponding to bits in the groupMask byte. - # When a broadcast command is triggered on the :obj:`CrazyflieServer` object - # with a groupMask argument, the command only affects those robots whose - # groupMask has a nonzero bitwise-AND with the command's groupMask. - # A command with a groupMask of zero applies to all robots regardless of - # group membership. + Up to 8 groups may exist, corresponding to bits in the groupMask byte. + When a broadcast command is triggered on the :obj:`CrazyflieServer` object + with a groupMask argument, the command only affects those robots whose + groupMask has a nonzero bitwise-AND with the command's groupMask. + A command with a groupMask of zero applies to all robots regardless of + group membership. - # Some individual robot (not broadcast) commands also support groupMask, - # but it is not especially useful in that case. + Some individual robot (not broadcast) commands also support groupMask, + but it is not especially useful in that case. - # Args: - # groupMask (int): An 8-bit integer representing this robot's - # membership status in each of the <= 8 possible groups. - # """ - # self.setGroupMaskService(groupMask) + Args: + ---- + groupMask (int): An 8-bit integer representing this robot's + membership status in each of the <= 8 possible groups. + + """ + # Note that this requires a recent firmware; older firmware versions + # do not have such a parameter. + try: + self.setParam('hlCommander.groupmask', groupMask) + except KeyError: + self.node.get_logger().error('setGroupMask: Your firmware is too old - Please update.') # def enableCollisionAvoidance(self, others, ellipsoidRadii): # """Enables onboard collision avoidance. From 911293e062e1f9a122f4b8d2274a5e512e5d0ff7 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Wed, 10 Jan 2024 06:42:20 +0100 Subject: [PATCH 055/162] sim - vis - pdf: support multiple CFs The current implementation overrides the output pdf file for each UAV. This changes the implementation to write the data for all UAVs in one PDF. --- crazyflie_sim/crazyflie_sim/visualization/pdf.py | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/crazyflie_sim/crazyflie_sim/visualization/pdf.py b/crazyflie_sim/crazyflie_sim/visualization/pdf.py index d3b04507d..2ad0016af 100644 --- a/crazyflie_sim/crazyflie_sim/visualization/pdf.py +++ b/crazyflie_sim/crazyflie_sim/visualization/pdf.py @@ -30,17 +30,17 @@ def step(self, t, states: list[State], states_desired: list[State], actions: lis self.all_actions.append(copy.deepcopy(actions)) def shutdown(self): + with PdfPages(self.filename) as pdf: - for k, name in enumerate(self.names): + for k, name in enumerate(self.names): - cf_states = np.array([s[k]._state for s in self.all_states]) - cf_states_desired = np.array([s[k]._state for s in self.all_states_desired]) - cf_actions = np.array([s[k]._action for s in self.all_actions]) - - with PdfPages(self.filename) as pdf: + cf_states = np.array([s[k]._state for s in self.all_states]) + cf_states_desired = np.array([s[k]._state for s in self.all_states_desired]) + cf_actions = np.array([s[k]._action for s in self.all_actions]) # position fig, axs = plt.subplots(3, 1, sharex=True) + fig.suptitle(name + " position") axs[0].set_ylabel('px [m]') axs[1].set_ylabel('py [m]') axs[2].set_ylabel('pz [m]') @@ -55,6 +55,7 @@ def shutdown(self): # velocity fig, axs = plt.subplots(3, 1, sharex=True) + fig.suptitle(name + " velocity") axs[0].set_ylabel('vx [m/s]') axs[1].set_ylabel('vy [m/s]') axs[2].set_ylabel('vz [m/s]') @@ -69,6 +70,7 @@ def shutdown(self): # orientation fig, axs = plt.subplots(3, 1, sharex=True) + fig.suptitle(name + " orientation") axs[0].set_ylabel('roll [deg]') axs[1].set_ylabel('pitch [deg]') axs[2].set_ylabel('yaw [deg]') @@ -87,6 +89,7 @@ def shutdown(self): # omega fig, axs = plt.subplots(3, 1, sharex=True) + fig.suptitle(name + " angular velocity") axs[0].set_ylabel('wx [deg/s]') axs[1].set_ylabel('wy [deg/s]') axs[2].set_ylabel('wz [deg/s]') @@ -101,6 +104,7 @@ def shutdown(self): # actions fig, axs = plt.subplots(2, 2, sharex=True, sharey=True) + fig.suptitle(name + " motor actions") axs[0, 0].set_ylabel('rpm') axs[1, 0].set_ylabel('rpm') axs[1, 0].set_xlabel('Time [s]') From 57ee45737d23c7e08cbc8fc8dd6562c948e3a5d9 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Wed, 10 Jan 2024 06:50:09 +0100 Subject: [PATCH 056/162] fix flake8 issues --- crazyflie_sim/crazyflie_sim/visualization/pdf.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/crazyflie_sim/crazyflie_sim/visualization/pdf.py b/crazyflie_sim/crazyflie_sim/visualization/pdf.py index 2ad0016af..6f72ec751 100644 --- a/crazyflie_sim/crazyflie_sim/visualization/pdf.py +++ b/crazyflie_sim/crazyflie_sim/visualization/pdf.py @@ -40,7 +40,7 @@ def shutdown(self): # position fig, axs = plt.subplots(3, 1, sharex=True) - fig.suptitle(name + " position") + fig.suptitle(name + ' position') axs[0].set_ylabel('px [m]') axs[1].set_ylabel('py [m]') axs[2].set_ylabel('pz [m]') @@ -55,7 +55,7 @@ def shutdown(self): # velocity fig, axs = plt.subplots(3, 1, sharex=True) - fig.suptitle(name + " velocity") + fig.suptitle(name + ' velocity') axs[0].set_ylabel('vx [m/s]') axs[1].set_ylabel('vy [m/s]') axs[2].set_ylabel('vz [m/s]') @@ -70,7 +70,7 @@ def shutdown(self): # orientation fig, axs = plt.subplots(3, 1, sharex=True) - fig.suptitle(name + " orientation") + fig.suptitle(name + ' orientation') axs[0].set_ylabel('roll [deg]') axs[1].set_ylabel('pitch [deg]') axs[2].set_ylabel('yaw [deg]') @@ -89,7 +89,7 @@ def shutdown(self): # omega fig, axs = plt.subplots(3, 1, sharex=True) - fig.suptitle(name + " angular velocity") + fig.suptitle(name + ' angular velocity') axs[0].set_ylabel('wx [deg/s]') axs[1].set_ylabel('wy [deg/s]') axs[2].set_ylabel('wz [deg/s]') @@ -104,7 +104,7 @@ def shutdown(self): # actions fig, axs = plt.subplots(2, 2, sharex=True, sharey=True) - fig.suptitle(name + " motor actions") + fig.suptitle(name + ' motor actions') axs[0, 0].set_ylabel('rpm') axs[1, 0].set_ylabel('rpm') axs[1, 0].set_xlabel('Time [s]') From 51a12dd611247ecd42ff88ac4057c794fe03d8d8 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Wed, 10 Jan 2024 07:38:18 +0100 Subject: [PATCH 057/162] sim - backend - add neuralswarm Implements a new simulation backend "neuralswarm", that is based on the existing np backend but uses the NeuralSwarm2 interaction force prediction between UAVs in the system model. --- crazyflie_examples/crazyflie_examples/swap.py | 43 +++++ crazyflie_examples/setup.cfg | 1 + .../backend/data/neuralswarm2/phi_G.pth | Bin 0 -> 17207 bytes .../backend/data/neuralswarm2/phi_L.pth | Bin 0 -> 17399 bytes .../backend/data/neuralswarm2/phi_S.pth | Bin 0 -> 17399 bytes .../backend/data/neuralswarm2/rho_L.pth | Bin 0 -> 19383 bytes .../backend/data/neuralswarm2/rho_S.pth | Bin 0 -> 19383 bytes .../crazyflie_sim/backend/neuralswarm.py | 170 ++++++++++++++++++ crazyflie_sim/crazyflie_sim/backend/np.py | 6 +- 9 files changed, 217 insertions(+), 3 deletions(-) create mode 100644 crazyflie_examples/crazyflie_examples/swap.py create mode 100644 crazyflie_sim/crazyflie_sim/backend/data/neuralswarm2/phi_G.pth create mode 100644 crazyflie_sim/crazyflie_sim/backend/data/neuralswarm2/phi_L.pth create mode 100644 crazyflie_sim/crazyflie_sim/backend/data/neuralswarm2/phi_S.pth create mode 100644 crazyflie_sim/crazyflie_sim/backend/data/neuralswarm2/rho_L.pth create mode 100644 crazyflie_sim/crazyflie_sim/backend/data/neuralswarm2/rho_S.pth create mode 100644 crazyflie_sim/crazyflie_sim/backend/neuralswarm.py diff --git a/crazyflie_examples/crazyflie_examples/swap.py b/crazyflie_examples/crazyflie_examples/swap.py new file mode 100644 index 000000000..7f2f041fd --- /dev/null +++ b/crazyflie_examples/crazyflie_examples/swap.py @@ -0,0 +1,43 @@ +#!/usr/bin/env python + +from crazyflie_py import Crazyswarm +import numpy as np + + +def main(): + Id2 = 231 + Id1 = 5 + Pos1 = np.array([0.0, -0.2, 0.0]) + Pos2 = np.array([0.0, 0.2, 0.0]) + Height1 = 0.4 + Height2 = 0.5 + swapTime = 3 + + swarm = Crazyswarm() + timeHelper = swarm.timeHelper + allcfs = swarm.allcfs + + allcfs.takeoff(targetHeight=Height1, duration=3.0) + timeHelper.sleep(3.5) + + # go to initial positions + allcfs.crazyfliesById[Id1].goTo(Pos1 + np.array([0, 0, Height1]), 0, 3.0) + allcfs.crazyfliesById[Id2].goTo(Pos2 + np.array([0, 0, Height2]), 0, 3.0) + timeHelper.sleep(3.5) + + # swap 1 + allcfs.crazyfliesById[Id1].goTo(Pos2 + np.array([0, 0, Height1]), 0, swapTime) + allcfs.crazyfliesById[Id2].goTo(Pos1 + np.array([0, 0, Height2]), 0, swapTime) + timeHelper.sleep(swapTime + 1.5) + + # swap 2 + allcfs.crazyfliesById[Id1].goTo(Pos1 + np.array([0, 0, Height1]), 0, swapTime) + allcfs.crazyfliesById[Id2].goTo(Pos2 + np.array([0, 0, Height2]), 0, swapTime) + timeHelper.sleep(swapTime + 1.5) + + allcfs.land(targetHeight=0.02, duration=3.0) + timeHelper.sleep(3.5) + + +if __name__ == '__main__': + main() diff --git a/crazyflie_examples/setup.cfg b/crazyflie_examples/setup.cfg index b1b614c9e..0c0238812 100644 --- a/crazyflie_examples/setup.cfg +++ b/crazyflie_examples/setup.cfg @@ -7,3 +7,4 @@ console_scripts = multi_trajectory = crazyflie_examples.multi_trajectory:main cmd_full_state = crazyflie_examples.cmd_full_state:main set_param = crazyflie_examples.set_param:main + swap = crazyflie_examples.swap:main diff --git a/crazyflie_sim/crazyflie_sim/backend/data/neuralswarm2/phi_G.pth b/crazyflie_sim/crazyflie_sim/backend/data/neuralswarm2/phi_G.pth new file mode 100644 index 0000000000000000000000000000000000000000..855955e0a045a2a6393116682eb0f15ab029c923 GIT binary patch literal 17207 zcmb8X30zKH_dedJG$Tn=NQyL%y3g8?G$WakF)~DkTNw&Tr3oo2Nl{8tq=<(5tQ93h zhLCxPND)G2>VJEl_xpaI_j%v<_xt}&pZ)1`cKcjiXYaN5IqO<$A1@DS83_q_d5M2J z)FgUK_^n>BBw+1AQ-8l;Ka*9<0-YUIBz*tn2$x#0U}a$7!Ue$rD^~<5OkC~1aP>le zr+@{)3POqD-a<)39|bY=q6OwA>lOwqUJ@*nS`fTa3~MrXO>jV9kiy*63+Jy12=t#D zyl_R(%GGn%S||vm4Gn$d#8(B0Tly_tD3tm05(VeLm43mK|EyFH%KE5?+l;a@voITF zIm+77+S-W{zafsY6+@ca+1S|$b;Se?gN1|s0Ng4Z{F~sAKf&~Zg+slC`u`wk z`9B1Q{TrN}rLC2P1^8b%9;i+PF(j`$PPC|EesTWI_bf|h?0 zH2HT#YjZ2{4O^Jm2~GbbX!Z|+=D!JA{0U|mEVS|#TK|Kf)&CH*`8(X7BW+`2VPz(? z6%!mJ?m@fXcQfy^H&rQPdOa4-0A)K&DIPtGFmO`&h!byLvu@ZW35>Ec3 zW=+t16E6=r`GyYp>8r$M{=0bn*ZDg@LhfJYuc>&ZnE&qpJ3C7Mp31q(yU`F=lXEDwlh= z*B|}Q*s}{0Tfla8oZ#y=2Z|}k08IxcxO-v;o_H~qhCS#_7q@Lgee@+;#DK}tw`gIYiMm!zf@#S|1zQchAp43MRiwGoGwu2!y zei|^XLJe+`(S6Lx+Qd&6#geEck0nR>;{Mz9f=zd~sz~HGO z_GY*QEB@KcjMtpO5!sorRv{AnBFtfg%uzIcXNte1Z0LQSI`o;SgTuQv@*>-#_dNmjuB~lS=?!`ZEowne4}%5!lSnWZoHexW3^#+3S`2c>+IgD(y0lALXgsc6I@QV9; zuqErxa;e@oar@6UG!fg2=am7_T&hF!Wo2n#^(h#1bEjaV?-?vLs>UI|`eFUqk^I_) z{y6bi87XWu0zaJ(aPE5}RO?1F#n*=PQ{^$vjTh3mMRm9$I{@}(XJY8{KCGwL6O0>q z2ESxJz^#$%*b9pg!5radT<19nvI3>y+U_`>yJturf7L*q+?u;~HE7tAj$Lv}}kFV)6JCB2~&U+x_&bbfYzAVOqc|BRx{e0+E zy@&O_9tpz6zO4Q0FVG1~fTyo}uM=PJY5AEqceB z0byX41y+xW;i{69S@|jH}|- z@(Ho^+{{^Z_uU!Z5@uOpydr2Gggxav<5QF;n7y0j=+u)7i z2sBa1$C+uxQ29ie58QnhKfL*Y7pC7KWvz)|)w+XXyhedR!BEcV=W@z1Haudz+2hdPz7mD8|9T#xwZcM1c)2QfAMJ-r?A^Wf0i; z0sGhnQ9#rJJaE$&Lh|;oaS{diGwBz%a^px$%8kXd%Zw@Eh&J7wei8J$da?O)?~6x)H8QAs%A7f9ha;+IHKhcN1)L6&OBMVNe z-h_Hoda~5Z( zA9^1SjFQAzw$_|+N(FSC)8tNe+v2457*;309beBL!h%Nb0gwI4+_B51tnl$dTHWgo zEGk}%Pi*4(;x935t|e4?e;C8nFMWuEpphF9I+;FEEVu9Ec(!28Avk6e%PPxcs=j!g z$5)*XL=8>4to^n=6((+@DJNc{`(90^-#154cP0d8OW45H6Sp{pUOUNh`x=x={sFHx zFF?KeJ&?F*jKFHS*zONJ%y%j(>W9N@ldo{8${I$MY{loH z2YH+D{`|-K3SPxZ0urC9vbuvsd`9tHzDI96kgX|2jcs8daZrLn_YNlK^W8XNqdc7O zQlsi|hSW_Lk-mKAUBjQ^EmZ~LudC6S-QUs7L6ufr9mp*_m%`6o8wYm}4#r_uyRjud z3Ojf8qTGUf!NwEU*Lek$9O|k1V_7{ zLw9o*|K*efjtt0wtGj1lvQr4!c% zKVI4jefN%n(-)LDq5d3{98-wZPcK2nn_}+%gHPCQ{T-*SIw&ZcUJB40W`;`k|i%E-Unq)Ip#>I(#T}t3jem%y0J#Y}!*Infn z8R@~EL#z34`#k*Gb%}eie<;c)=}_l>9g4UwOYut&u$oEs4r5MFsj4-S#n%sN@VfRT zd|2&?QrEUI~t7uA5y$wmuTxR_4e7~GGc1Yh2UuUlv^J9m90H`1r9CE$08j$uG3F~dRCvHlte}P zvE&Jee(JK44|eSFfMYm3#F{NAI)F}7jze|eJ@_!ekFQ%2!ws|O!yl`W1h<@lZ1w_8 za@keNFSnGVlHz<&9RCE}F5x}fO$O1w6&7p$=db}sEGbbNdW z3Ex)pIYs%9a?p!{9Y@21mU5BNZ2_5Rn?y^3+>Gm3?{yGjbbc6X@Z6)~dOat7>83ng)?Bn)KaL0iODr}Zv0+M5yAhEpy zvcfyLnjsou;&SYiOEtTELx#@py2-u&-hjXICt-TwVp2+4k7Jr*nBT`@{z2aqw(iGQ zm>Q9Wa&8iIu(b>+;SLPSHlx>XGQjWfTHNXy4^hr@^7{o&EWC!kt&%w9A!gxNJ;1+Tan@NM%{Sb0K|U%tGMA94I7 zn2&vi`y;;Mt~B74_FRO08s{PPMJiObW%8U$62E%%Yff*%e9ZA414~tv>4T{)sIwFp zqyHKEFN=r#jjQp;geQ3V*9RP_Rsk-P%b_k<3N7aC#_F&MBFDXxaP0(D`dW9E-!okY zZZu{=QN=f`_R0k#)d;Thj7TstONEuT^StO{20VY<%3Ty)4i}IdO@iQ7*xsBhnjym|SZ}#_p3Db#lRz?;RL6iL z5p2ez-n4MdI?Rl`3&q+!apeuficyNp&`Y0nx^EF#`{&U?g`e<@$&y)340-)Xgmh~U z&iPF$tuOWfmvA|nUEB*dc;3S6NqeaJ)c{)IbPgqTZ+=`(t$sg$AxB-iv?-zyob)r_}b$qhhkwSe(QPSla+~lgtvIgy@$L9^W z^g(O!wA}!_X%#_l+hcioPL)~O{vyBVL)4P`4UDIEfW|c`Qp)ew2(s_HK~o}b6hi7lndZ{DzGn+5gjlgAx@@qmA=6~^`kzC+)q&+yK1A<1`0;7j{l zDn9ldX|4+dIgey%7E!EzLn21!G=bDj5%gZ03R8yYu`{>pQ7N+xlC_!GH8<_uNhYC-orLd z;)M)zxZ95s#*AZ9_tk0Nz;oEztVls+Irv1`mR&q0;8nGkl8k&0JmSK*;-;1+(^DNkFp&x5vwF8Vgj0EN&rn02ZXZxtp}*05ks6r;h(TU$b)T_(G1;mv-n8Gy!b z!ub=s9^(kiW^Ng`@bqeTyc~aozE1Ih@X&PJ^LQ7=OxeP5!~N9n`9D`hNo$q3R+OM&N;|R5aR=7; zW})lRlX$hCJt}=r7Wu^KgT)EcilH$9Si12vRKAPA30e)fZ_P94D13(SIZp(dA0XM? z6;m7DV#;1cw)pi9bo&{IQJUgs+x5qA;Ho7TTk;fB=4PPhcuDGY?hs7Ar9@Kk$OSh} zz%iZ&L}v_AFr)PgCa*Y;Lj<`v%rFHyqTWEdu_D>{$8%#;FTnj-6`0=WL+`G-b8YVr zP}umH^f1N^)ATY~QH%~N+bM(IbHa(&F2@(&r=nc5BU$!73SCvL5I_1R28ZY3VTb{~uqc)-=*OPa0EXCgCx3Nn(8I!^+$$QduY~Qhq|Gw0eU0)vu zfxD)mMeiusqka_Q)`W9o_xW=>d+oyvsat50HGnnr52cC6pMie0Ia@esC#+DHhKeh) z^l76d-RBSSOJBsW)MEqL>nXDIWAS>B@|jFEA1m169mk8+KK%h$N%zzP_xt47X0hS7pADE$5PEiYkk!3Nw^R!n0{p<0B-(7%{d*PyD96zo_39Z^yQ9^1S4eD3S z-BV?(NpcyxVfY3;RFoL1$)NdN33g)l9eAwNgw>A@QBfZRr}0-gy*BB(fYn;(9s3SEX5K);QH&|60rd@Tmho<(nXowBEJ z&`?6k|$tbCpDSVX=Y@ z5At|#)gTm3Qv>>-aplL^S<+5+A;6Ew|)$5_*nogCgN>{!;2V+#6txQzv{tx%xox_!*1A--D6uzATxyvW(y^e`*uk_f@`noCY(X13GP3;j4i7SAl6Br zC89Ni=LB%tACy?m;0io5*OHCCIS0=~s<4eahcjQfC4z%V)7Xs7xv*+x8m^*c^l0{3 znii=>3KOow={J(}dhJ^FocG0e){bQ_dNHR37xC0jHB24vk7}=yz;DP6xT0!+_1&qo zpuYh#vi!(5#g2wyTW|4E>wvxV(Prb+_fYGVaAuit0A|0K0@?%4qTBXZuF9<&jEahJ zt>z98`gefB0w=cgdNl9YZ!ezxXvjK(r_+kz(p+ZYD_oi{&qgb*WDTPTiVs!u(H9@% zgKtq_d*cpHpK~6R&DOG>qGbGHn#GFJcH`2N*D!DQQ%)_-0QT%Cmoe4X0 zuSKM#6b|weABje_PM}l!n{d{Rx7-z%&v@Zj9$lEzlg7T$M0ICZ+*vEf$|FaxE~ZB} z_0M5-{yeHw9>!*GuEezQjt9zTZRK_r0B-;m-umUCAaH>B#qeg7<)8U^8OP~fWFfz zj7ycHGhz9#NT&l6Kb-&r%lT|-ghbVJy@x1Q=g&J|e2J@PO~Ada&D{CzDQw`%zI<+q zD@unYTa9={^VQ*`Wd z8a&)-0u=^NxhK=CIF}u=TGdTqn z6=P`XT~}U0IusL2_aQAiEU+}sfPn)QS>HCX{w3SW{qCQo*Gjsx#NG3|{Ga-#-+$_# z|A}}yJNEfc{WCFH7w!*|r;`oJuxg7o?peMY%=?J2&?*`l`kH`Brf5M|t zNmcJO%&DZ)n#tWbK~tt20aBa7Tr&D#Nx&uYpU@XQ$~gA*97jEF7ozRuy>RxaC#i;C zglGCnY=4R}R=TNBghe^^?ur5nH#H_#)P`$<;%Mphfr6J_TUq=2(QNCbx$TYZ$`(r0(&*^2_X_#u~F;FJ7S2 zVr%YmXa_x5^q7C{JB95Tr2rkd?Rdd7h`xTSW4HE?5uM)9mud|~q?A%3j>|OR^WKv< zHN$J%Q5PH7IL?T6T{{LzXWp>6`z-hyspFVVXC#bM-YZIJ*+8MG0jNJ*j>!&=XBAbx zB>!>&+09$bUOq1p&oRcvWQWt{*6Y-U->JdYm3&P$kbkBX8*CE?nc`;;SDHgH)01(s zgc{y`aS!VSFYsDvIL=IbHkr=>A!W4SVtmwZ9y#bpP6j1r0K6QgC0E*Z30bv~sZY7=0#4aj5cL`Ml(EtiMZmUjNtAQ#p_eX5RaTZ>ByWU=E= z04tXFrio`Is8`ra{B&m}-M_V!*?acGX&p%YQx({o3u;yCidVBaGVT1((fKgF(wnBK zV|xQmL+;9MTw0TY50*zUJT@K5^B9DztL5Is zHL#njhoYy)Nls$ZeKhu1%hCs1k@~IAY~%J2radm1-5T4(WH0t7k$NoboL5;VL1s1xq z06wTBv%K!hcsczsjGbo1R5X8q*399QT`5)d`bro%=05~cJ3xCNKExw~zED^yg>0+A|%^VshDJ$YNF>r|Ulk z!B5RamjSwlDHETo1c z3mTEu3C@0ZAaYPJtaE;YS64Pb-j_O*|Fsaq7AM8cF#tp3xV>M<@?1A)G6l`k7VXG#>+4-7Ge)&#pTBrq52}?j?=ts_BO(e}SQD-M! zYp{7ccT*L3z>eZL!KCs6s@`!8yCrAP`{;X^Y#oWmq>DMV)H=$|lp!6n#bCGb7~U5S zA=%3v{QES6s>5L#%=V%M6)vhHt0f+wTKNJ_N{xozc0*x$-5U%TXT-k9KBC5=GI%L- zm`gu0f#eO#@urIuH%|Nv@UMRad%rtitNlk#uCp&jX2~!OiS-;kP@_Zh`k+*L0le); zs2TkN{5zze^lUiZSe1Zw^=7PMhA}s8J4$$P7DUnW{K2ADH*a>`N1u2*O9-!VqD{rQ^d?<_Wlwo3xRB77YJ~Q+xu3jiz z#jSQCcvuYwWrsmsqJ>z;8Y8-#QjhjGJmHYNG3!1i0cVdWkmBlLxN1xqcRUNI6) zzmSTSH|H>Jt+d0$RVofYW_IJOFkkl4b|kwI`y4yo7NgzrZ5UC|n+?r=0e+`5x%XWK zyvFJ_h(0wFG>r6VSovg{^f8$XhkN40spT-l6;N6$j-nI3&~RT@_GOngZTJ?=+NqLe z&68uNB{xIQm=$okgYmX0B9!blqz#Utmmig}v#T(+yCH5yykK z&SnSFlsQ+3BMVn27QVR$7pVKhUO7brTr3~L&buS&h`bqf@OpHAj3zDgnF_n+<>I-s z&J>d8F6!tV$fd4$#ksm4<-J-qL3-a>enIpPXe&&jmfJD#t_1Ag>I9>guQ@BZ_L5zn z>OwC!H9=T@yNGFR6{zH^z|QTdcxASvIQ|>UO;!B`TRCsKKd=h1Jpr3NGTDVOU2thy z7?$MCBKzR13WxaN?AwfSY=NEz<|$PO3dhS*tkOPy^6M(L;Hrv)>x%C%(9w&3CXQjh zG*V&remsQRnXR1v*imfpwOGcv#&bIaeMvf?H_3l(fv&JpdNqFlOIxYUtlQsFc4;Ym z@Rw$@ioe6ngrnTyd|z^0ejX33m*8!}cA!(o034fg4pKhru+`sWscqI5JTxZ)M7Tolpy@tRi5w1@taTer3rq$VOs1=Iuo~mT34!p zXp0qXc{-f6Ya#4$rRR2VTboG5os65P_bJYxg>PrdDCd<%`4L! zl^|AKat5oTTv+wQ!ThVpY3$;9W4seHkjj4e(vR24 zq`EL+vN4-K`!FZ>Y%12ieu~O*5^SMtHFl2k!o}&+S(th@`#4vbt@U{?dNsR{#(flW zzZxC*8A>+vIoO8h0!FG&dh0Q?>uYN+k zH5vS#wjFGC_;e;Avkybd-C1Gr6Id)E!0Xa;nRD7mXg=ge=bTrxw zA%zrs+nzn9!Jxt#(dI`_xIMQw>U?q+T)mXay{Xv^$zt6|>zNMf=WEe0`~eY|2wIaH z(B(m2vX33gP9Eql)-ILlwNEcvWxomeyK(3yZW(NT9qpbsgH!epO!U0RX;t?hMF+-0Pd5X-gjZ_t#}cW@Feoy?XHK8H@^t zM}dZmKV;A0*{&N@5iqzX?A|vPyJYv!*=;-7UcnNcb2!Zu25)0^1CFwB{&#pCZxi-_ zn+!K!D$qbK49z!>W6ej>Sj(bF=<&QB&L>Z%7QqBi^6kKggcMj6rOF~~@2S!XMj7b z-@L%g|kCtqFc!xRP$CaFHLfbZ$vYRi6p@<#QRU`DsikP3(Oh{!u%B& zIb4l~I5vU0(J;EzrADJaH)7(_RL<3QkytM!tn53LOBEWCX5J?-Kh=+ASS4d^WrO%V z(Gl-XGlGSo`_XZv0gbTROda`tOzP1oyteTtY}@n{UZ)RZ)%H`!^l?w-f5et{jEQ5D z8wXKk#c0?*tdVsVB||U%0N1@kj-?yx@m)Iuuvw!P#>ETRy#@jFJ|JGByfR=g=2zIV{wW5eV)PN8PwIfwco#Zv zc#)5rAPq93Es4bOXYb7~P}|y!^*k~GR($GBf$T00I~awt(m(JXI$I#@(o1Zzm!^U# zJt*t)W^C*=lC1|5YS^Se^F8g*=Fmyx#PNuqSLT4p)1AC=-#4J|hOBSPc=pq99YmiGgS7Axkn;(_M{=G_A}CbQEqRp%pR{E@ zGZS!`*&8gH9>ro;uExg19qhONAEtF(kfkd2|HbA1)&KuzcI|)h|39evGns}TFi}CD z#;=_P50`F(@|jb}KbnW$=j!-DXRKhfZ=zt>{-ro}K^T0?j75s=%|h5AsOxhWd^YED zQPFv#p&dZ3A3yWI`Rd*XdhPXFtN6d@6$byVSNv~2wX>t%f6^=duH)>Je~nrX7V{71 zi|}B!7bG@n<186nI{Us}Fvp=UD6f!Wk2m>&qR9eSHQ_x<_-S*KTR($@R~Rn8PY`;k z0>bMIY3+wAXmh*_SLTTGlpc=3(T6qZJ=+LVo1fx|cgk&7B$YTNpxGrm zn%M6&e*3f*C34+Fk*P;v*w_gIncaH)>vzg5J3<@w=A8dS-+J~!VfJtB=6Csj8^1sE zt^Y`X|1aZr=ery8FLq-?z6sfnL071;Rfjups*F@?Tj2c%ALgpPl1AN&#F)Q-*~i9#QUlUfVpQH?C&%c%CQQa8sJvEw)i+*m0VoJeI9ID__--@(sT0 zyyPY?odQ>f`8H~;<9xQUq73vyj?qDQ-t_b-o3bw6hal$A*%6u^lfBcTu-M^~p znp-`-`mW~SdC9!W{A4eOd$XpolEa7K%c)i-tUE%_RM*hKc0~vOiIW}L%Y#VmSbs8v z^VHFLg{e-sg$1D&;5+9VOIMPt(vnJ~IA0-cKX;k6^&X8iq7y7`Vg|jxb`Ba!Rs#8H zSIu#FKwnz+<5{m6^vviWT|FbuL|4SIc;}vML;8JorJs$%yTEMxIru6&J3xn)4+y}- z6Dn0rk1E(v=;rCcSblZ@YC@CTF zyZoQV`rqg8U-k$5|D3u0c_0h;{Yse8n^Ec2+dEr2CFnMp&%`t+?EdNeU>2P8+)&#(K|s!1v#G5nmR*$DeOqsJCG!?te0o1yV2^>hq4P?7M(QEFDS%-7bo3N_ugo z^RIxD+$>xca+y23>o81hX@=;SY*egVPSWEhv0!;g${D{E!v{*!E=y@zDv%It95{rM zAJpk&bosTyxfJobh!g2 zVjueMVh?KRGzWPXTllf$4eXBD%B5kbNMV#S!u@RiQf$j6FT8mSr1kx6^1HhsqCwh zEqikG3a4D4LrJqcz$$wsnY?_**?zsqd)MB8L78!wp0kC%gq-3R_(+g-G{>x~zw+T5 zWZ4M=8~7~y3MSfa!LeYSHtVMBQP^mBsJ8wSnchsj!e+(GbQuHV`*>m}!2D`B$ z$%yUqbAjP4icFHX#h2o|CCwTodR%0}LKN%plkF@#D}G0>_R3+W)UG3m{c-MA7tCx_ zXZ^B9u&JKu7(8?sc^taHC57~7!G$hlrmw=>LL1TjQZE)@?@ry~{E3X$)~s@(1O$v* zi%PZW_G>Bw;rOm7{9@V49wX5AkXPsdnUgm>j;G+r8-rKI$=)Dkt9M@A%BXI|W{}vi}iqZWv1{8w#Oa zq6>B=KY&eAC;5z+IBwdhW*DMZfYFlUF(Ks&EL6{A8z!r>^(LCQde~OTiGPSIFKvKO z+uN{BMTL1P9Oc)nD#K9kZWwhm6FoAkP>Pp_WoMnRCb>8Ge0aw{Z}uY7rw_2}(iE<% z^cmNoX98OmD^lT+9h7EZLEBdxl1tqhB$umcn|h#ilgBznf#{k-jvPyQ|-7s`20ql-7ggo8)i)Yg4^7bh1)Pu z>@Tmp`2=xVKQcd(%c)q}P|~ITO!Lzb+&oj3B}oQhuG$f%?vseU+g0iKA}ty@!HT|B z%CPNw5zI5ZK(#PZZP zvPVtoq>(p)N%m@k>9hC1qqX8WbuSlGV&>&q|rdPFw zBDx=O`7?r8Na0QH$MABjZ1jMzbvO7c{_b?ra{^fhe&fzXRlwZ=0(PO~8$PHRNssr) z!iLO!Sf1p-eEZb#55{h13eBb5)7o@=_d<$>eYgv4&&Lw?#uw98DX`;{RN-xyRfnHHbNB-TX0wnDS5Zac6UrWZ$iLKVfWp&X(KX+WE%Wea zKU@mARNc$iTdjf@FPV7WB#|5Fyc%LwSK&_c&1`?IB5M{(k>QAkIJ|K`zHQzH`is}I zg<8vab^Aip^01)Nw869`qz|{uH4f%Ymu0dmxAGsB#i2Ye#UAzXVkR5pm~DIu@UBt z_ShNVRmJg<7n4ZtO(mY_Sc+j+GP$Yl2Wi!AjuH=F#n;cqF*UjI^y7*X%xOs_4gExx zT;R{t;uSc*?N7i%s}Q>bXMlt08gAUuCf?0(7JWK$2?ECx`rj(25! zr@)Wu?71+9ODGP31B2tJX?Ql(H0zOTsRgfZun#Xv731;^3iQg~2De$dV|8#9T-5PF zv!JnD*o6oomRT_f##&^aP|YRq>i4fA|W1e#sMrE)gq8f z5K@R~0T=}x60BKQiSN!A{^9TRO@5^jt|TGxyZm>5M^$3%KYiPO>@Ie8bojeJ`*(ff z|8{Pv@Y~~R*uQwHl-RTWUA#ObfB*XDHv#^-+gR=QAO7X|`xgTKe)V5-YXJgon)X zoEID^FO=x-CzLb~kQYPG4z{&g7BX+n+(@BRaO7e!tX1HW$axDRZ^1^QB<^gizry|5PXU+)`O8@?dyw}3TGb6|SUMMe=3Fs-VuhK1 zJV^ZOXeX2n=q4@<4qGCW^T~=7b|32_;nUkkHc{BaN7hF&Q7E4>_ZKaNNTH&iP$}S- z+`qU5&6^n^>^WEbkLOCy{S(;E#@W`{#?j8k-cG1ISI(z*q)_EIzyzVHk7R;S?RT(V zkwSGpp~fGA+Wn89n*W5eb+LDGaUNu2YilRenkzS|ty`o}`xlk}#L>nAk* zgP{HY5bXC)II*yU#8@ta#01U61l?sLh33B#G*1-v7xNSowD=u!K%~&pPdM-og7&`? zwE8FF?*ttOIXl=0t$!zI^9MoOUj*%b2eXe9I`|14{~+k_KLnlr31{nKGh--oeGu#zE*NCa4}M zbpH)7K{)sqL66_ThC~WI{e(l8L)SlFZv{&7!5 zoAWYRW8i0z@zEYwy`)@VG4>3LUUPvRU1^B|Lum$I%<jU;?wl+7BwE;0E&T3~hJ1S#KGOmcpHs_J#c1X63F+3kjA@?)|wj_@=f^F8*F z^fhZ)O86+;)W;lKx-^N?w9%rv7ye{&oGebNcutl~S}#)H=)=D4Jk7ppnc~+*eS!jCx~+)n_@|)Sv-+hpv@UnNMu}7B`$ct{bztRLzc=q>=&q3`k;>BYw{5gTYrPF+J^f zWcj!YgWu-)2bc8upXc34NjaoI~tYFa`aOhG;YR02^i5 zLYVNlpxjlSO?QYQkHQq;o_;UV9fd65%5<1xD+BkpuY?d&BMiIHPQK0W&Mj0w3%Z#y zCON{0(gUC1vcC!KmwXV6Bo*m{A$PF!)Ll_?iV9qO{oeKVW*HiI>N<|Ccj0oinwT=9 z0MfmVRVmcR-~!ddFzaB5@#A_QSp}f-$ls(nvs`EJs){ZZs zDTcR1--b66y`2?MEjxf0i!9OX{%ktiq8UcTJ|ivr?qa4*UtAxpc~WH zIN?CN-;~To9tr?k*V9mUM3tVWCyBAbInb6D@;#p_VTypj+cq6)>hKm6pXt)*h+ulP zQ$UZcJ%`$o*4V^q7X}cV_c$x6nj11TpaTzYS z9fpWaJ=wbh7epgxn!(wjvtaF%)qJ|C62B9tN93#4aZ3$3(mCxqSt_N*vljm#$CMpm ziJ*%4FFl7X&As{cy;XueQVb{0umghvCp>I$hrb%W4iETC(Ew{dK4IW(UNG@IhHT#h zb2s1Q>z2B~+B7A;*z+VjxNHI{-sj2GYp=oaN&)S9W>zvehe}N6n5$+wA#l?X+evc&!Q^Kf1e(Z>%Qm2@_c2^}FOt(dDWgdD5_Flr(G| zn#iesYJ5Hc?#g| zVG0uI`s~P@t*&ziKOhf>pJa0reVDgoD3ez$BkR3J2~uMv;B$)tyql0*^=Y(==zP^!GTdYo ziP5se?n|DL8^evTqUj}Ddb!wDy0L=ER^2DF-o`VhuNTRkJ;oRvHGsHw-C-)$1uQ}D z7L(78CgH_>ap9vnV$<&onQ(IlaVY-Dl3itSk@s~$*6roTD@?sy3@p9T^uSp5>}fw7 zVd=wO&)3HL52fMB7+q{$kU^GieC|5+;zve9t)NbyvhG3?SlY4}RFp0P-6cVl)^5e3 zi}9|Ki`Vmc3zEn?|BLYXl?{Due++sL=|_7!>Om_dRjB4^MgD3@8CJYi!N}>WA*9`u zW;|Pm88O|seMF+bI4ljuXDou@ohH1(>IIxQ_YJ7uHR#;E1}CcNgWJ~euxP_k7;XFv zSF5S@5e)E;R%@>GFRKiK>!&@T#VjzRhs4;kXNMV0M;RW6u*ubr(8(H9*rQG;ztX-qBH z9l62=QP`UPY)wWy`#Q%R`vupqn8a&rK)yLhT~|XZ(*>?&S8d?Cju9?j>p~t)S0b@W z`t13v6GYJJ04v9zXP&1+dFUp4=xKLKka=ql&%QT-@6#MeJtt&ifsQ-hs+~ZbGM=Gj zdOc6>#bHUj4IS<`fgiBn!}m6J_0iE%7FH;URV}2UJq*B9!*FH`scV2Je!;jihW`b-b61Q~!5gpjJ|pUL)` zO~m#|CSPyAx{4-rLurimWFrxrNfJ?1k&Z}NXo`Nfd$h2N#ijOQI42bsaqRc zo%vaGZSe?VWwp4fB}ss;g+av3*g*6>7I0&eDo7hwRNYlp$6|$gHqSu?-E*}e_{R}) z=-N*bKe&kX8?TA3XM3TVz!E;5DvDQyOs*x=)}#_2?{93KXfm-_)yA~X0FGF2jU2vHNN)F(7mT}R0UsuUXsPZS7BR1w zRhlV7^Kxg@3su0z)oK{oC!MtloI&{E7&#Dc2H-|H3nqMZ#TiKkkn&WysxnU&Ui#?cuIk>X|K=Dw zk=P=jB@dWQ`$v|&rlv|tZadrdT@l;6hp}lxuMtPNB>2!gjcI=OfGq72$S;+o$0FtE z3+t0aKVc!fnc~W$Z$2V@KXpQ2z83BI&Wdi*QlkE`Bk2)kciJ>71(({&bE)W?%-A3m z?sgf{?M79ush%tNqB=b+Kf4|#tgr-?}d$rz@a2TZ(SJRnER2YbWZpJ>h2l zGtdGjuFCT9+J=SnI+=z^hr>$DqLJC1WY)GETCHWze|*lw z`sne{5|D@$PQ$s|*PU>CjSH3d_6|o`QGV?~I~tNi+^KV#EjzW1rhW;=N^byeq64)n zLq#$Bj_^`dWDUU`#JkI!>)ts?vL;D`h7)pW7{K4Rn9;UA?D)~%vjydm;UMj_Su__a zu=U#|h|wL76C0ZFQcQ1LSf3`^Z&?gE+XIM7gaZgi@8iMlqxeA4F}Qzb6+B-&4TK#l zsOHroxc5DVE{m2#o!BZ|d2|?`JbxNDwD`gLB<@4)CUt)Po;;M+oM*f21E9280v_2U z5uF7(Ko+>e=ZTb5mg=zZi*>MlTpCO>EP~tK^Rcd@8r}>@o&5oxCCR%_7I)n z^3=~qhN|>62d9c?(y8;p^=R95IPavugR0)3_TgBRkICT&p6HW%u?nQvdoR2leU?S< zbAV$CCFK3qJ+L<-5l+6=#wgE)kUww^Z@Bh>oETtAYkj-Zx2x+RAyEfqb5d#dv@m)q zn{q{0HyB^ElDO6;frmi>9FrKvm+OY{e8sbPB{l|z_TB;$Nl?|bT}MdKZXa;is7jj` zpTIB$b?9A@33ryAf`T37A$p;rp-YreCGV~&x!gSl`b zJ`-$59|u8T3vSt1OLE_(^AVBBAgj=g$~<@gk`9efw=SIdrv_4??0R}pV;rBd-ySyF zdcgIoad7DC9oRc!A~J#* zNco;kqShR_c1JY7GnaI^+o9uh6X;i_gYqqPr2exi z$u^B+GS7c775!uNY+Bq7)Kz>AQM`oyKwQoE;h`d5&S=e0qJYNP2Nr7 zIT9+k!Z#5|uP7tFWxZir+i<}?ji=0RMjPAzxF2D)3t7zNVQku-Y%)9B3=6wo6f7|^ z!LX^*MFzQ3e!Wwc1-&6|VUwWmvm$16SXn%lNkYFP@nlPjfSg+6fZkT6Y^RSbG!~kG zMXMzm?6n5PkUhjrK~41Oy%GkFlE#Ja_;Uu>PPc-NZ*uhEnCPk_uG%p2qa>e_v5s6D8H>Gp z>Cvvm-$1QEg6aku(K{Q{U|+Hc9}|^=&xcN8o6hMFruh+~k}5I#bYE_vl_k2_;|6h6 zk%r6yW8UT54dz_00K5K&VBn*z;H3RfRQzV zlJ>>!U0-10#XWFeaRR=|awKlaSKv_jWRNTMAt!M^#_j5Z+8Wk$r|WcVf^t@G>_|j! zQ`n~$dSGHc$2s}IYNGQ<4iCQ9gGG~L*wu3qSY9v!^=GKTr(3lw%d?W`C83D9tP;8V z)sZ)6s#(>yLD(rdjeYxkqAKi-BpeUxI#Fb80C~>#=+(WRBuS3Oh(rk-x%WP4UZF?G zn%g8&I!|!9y^{D>bdf5DIjlT*GwkUh`WapiFt2v1aD1s8{dE5Z1n&3(?K8CK&Z5CIw_Tn) z^!$X1w_dZ@wV{Fw=90AT!($wACyC$v`G83@tBPV@S(8p?&eg(|AaQjnByYY9x4OIG z*l-Pzxh+C6xeR>!0)D7Pp5I+V@mOU9Ul>@*)_iXkoW48@T1VKx$}TH7`RoM9X?=v3 z=M?C~t6Pcg=^Nx>!Uq2IZ9e$PHGxuD4_Y+Ci3-&`=-fRtfD(Y{;Sr$V@_Q&=? z?UWBt+}ocISfaumN_@$L#j1SDI(zgx@`}k^*a5SJ5-7V#8{Fz$VCsl&5Vh+KjPEMP z=B6M}$=b;MYEQeg2cCpit0ZaKfa|a-pdY<7$bl|!A3$ZsHR62dS(vLShpUbyin2%D z2Hn^F&@D5VXErFJl!hAkx=&?;$1dRu7T<Fi)wdzoOC?R8gmGfyUH=mYXs z%1L7ORyK2q<%u1(wd}-{{@{OU2a(_Mj6B`c!aVyOVp}<^nEYEWQ->rxk8!_pLQD~$}YpUj$*dM+67i9j1%cg{lwGv*= z51;M~u3-~gKd)JeU(eMDRw=vV(WB`Sv5>t=!Jyg}IR`-GS(JV*b?e8JrA9KwdXgW5Y?KK6k; zo7#IluTQ&yL#?M^jHCjuoPGn!3oo;0#yzR2ZwJ;b$bq2_J*aq>89&_J0WEht!D-ZX zVw(6_B&Ax-7UEzGRORHFp!|edNPissMGgx0tHMd+!R(rWEXt~`XUS??MDOa3u)=m3 zxS?py%pFb$K785A(iT;)K8^h`qx>=}-FJ*wW_J-u7DM(l?Pif-)@)V23QpX!h20)= znPdx%UfF}SY>hxrB!`>(*05c3PmtQO z!MIi<5_)gg3tHzMz>lC zZMtHg77w?v#k)n{S-;z9u<6@7$hSX>({=~)0@Vmy6OuqAD}A6{W*EQVPzL1FX-Lzq z27_Zy1RJU}n3D2+lDd39q>KA(Vo+~BFI*S0hfL=Z8>X|cYk=*ail9Moj>$Y$hQ}{U z;N*5aP%BcWi@vSLrjdJKvE&PsI1@`6ZVVz}?~UjwTSIzG{xdAv>q7@EFNgiwKd@|H zJc|i7$F9%W;{BIMD9%}qZ6=d>Tjp4dI}`}E$`WMP8Wa9e<0kCaxeqHp*wdM_cR>7l zLmYbj61f%J3DpUNJ3Y4Gn`{oUHTHwK+u29#mp#SbyW1#<-eU8OIR7_$%AkL>r~F|( z^763%hiUY0cGCarW|vY2jwzGo=J!0f?#(&a;Mz>gK$ot}h=5@x#-tC}qHeJgZOu#o zMi34?>vLPRspNz+Mg%kY;x<&T^bJr)kCGT1epm_4y1n2%YPZq+8z^g&c&eNOrw&PIT#VA!Jo@7p)*%3q`QBN=gu;Cev-Cvi`rex-)i8R_M!tXR#*+hcb7>EiYJAgW16_FstCXFc z*}1VU)NJZ*syr^8>l>}-3zG7=n{FbT`B>U*L&mI=^W$Z3s%JPqB4x`LP2Pw1Pfc=j zu=P7hf?uM*-5g_u&V=e^vaKtEcpvu^^sF1t4>{at1I~ESm=(SFzEi1880k)LukA*? z8;5bJo{Q+?<(qlcd+(D{QR7d>=qup8w-<<|KivfTh1>L#Jr*BdZI@CnqbA_EF}#-4}u3h@Y6h!4VETdW^B-tgzpEXZFtI z0lSsBlwP?}L_+Mh<35~*5f6ItvZacAE>nSBlJR_^@BmVOJzhIXpX(-XfNpbpGVcWw z_y|)YUYKJ87V`lrL$&GK5IJ1Ey*Ia2@DyDhnT>^t*@7RZ-0@?G9Y4J@4_}YS#v&>K z^%0u9Eb==$FenbMyHt{r8$VHAUJZ{-)Z$Xx_JiB-&FG?{B66Hw1kcZ0#UJnbL3${K!sE(c@9hC3vrA2*4|2zS6%Mz5Bn!9J_FI zIIKfzN1caH7xojM1O54xmH~YH%Kmh)oD23lau*!F>H#^fmkfGSlYK@p8^Ieu)OFbqoQ?g}}o;P6DHoKG4hDgZ7ZQ zK|;UV;iV(zn5l*l?VcBawc*>qPeYqtURMNPqCT-(7FURSh9<-sdQ$1$B{=)dTR5o7 zvD(jzu3esnp99rE-}VZ~ZdAgQk+zUGc`WS`w8F5DL#S>?2V82&0JWh?bZ*&N3?6h6 zAb`OKmt-7!IuZ2c#J0k=LG;>-a=h8E4JPGl@idoUm?eFj#5jL~@}Vy*3 z7U3$@15kZ-Ox22k%Jip-8SU8aN*$&r()@_E^x&{iyzak-hBQRMmTX&U|8#($s6&Y@ z3;YhN6gE)ZN8{+}{Fz|vBSjaacjIz>*5JB})9BZc)zDxygtM%nm;h;*?R%7KowLJ; z!~OZBpmlISN`p^r?#>6z*d*N5AD8V$oz)%ct@PuZle(J(Ylmunb3 z#TgaPF*l`vmAZN0vZD_4ZH_kjb+1LU?dCkAAcAUl6r<#lRd_QYny> zN^T78e8(YAI-M?koljp+wUkf(?+b;!7mwgpO)U_t z3*mZZQ?cslT(0<87yUB&a@un>`V^+J3Y`kP^7R$SwQdqvUl_){p9JIAh0(lE=sQgK zrVO(#WO7C0{h<9Oh_~!YCAuCZNILGI>w#phQKQCZZuubKmnPzb4O;Zo;}S@kY{3&1 zZFpDqY|uREExLQ#0`=8~(xbQ+4ZM<}WTrLrAMQkh7D(ZZw+U>#<~W$XbTWoy-1q#=_U{Xwjs()WV?^$(0q~8+qy4MjHJ8lRc+@l!uXT1XH94lI7`4V>e zj36^_?-wXi1Nz`iG`qU53yxU3!w*L@+S9lJo(K|fKzKNDSv-zfH@RZ+6-(N=s|5R8 zwWLea`hbV$2C$RwPB(9@M_Jjjs+@gmdVEt7lnNKYv}k)yv%*l_)`wP3-UZ5i77h>!2K2oNQy+AROcr}$w|(B|aH$hqy=3ss z^%#^WmZl3kdO`Q3@l>+kJ~%l{lVs)Yg?EZG=wL-{7j>z8K?!>Z%orgUd1*7sCB#9`QB9;e z%Ncv!N&xRmFTuub9gqI-f_>IYfyy< z%^ikah!srsbp|}Pmnc`C6>a+106#QFqmFDQ>pJ*pF)oQ zTpZS6PYif0j&5usT4*JG?vRlyC8gu}eWm)SDkHZ0h!#EsQF zY3-OVqL>p$SZnW5e8kk0s`Y|q)UuoiB`YTI4zD7C$(_q0-*X{6+~WhDFLB})g`;^i z^W}?d*7CrxZ9LKDJ4@WB&eeM+pmCr9zhZcdMZX#kLCur+p2Hrzzf>@Pd}t`NYv}XM ziHfvl%S{rvpf&Y>aePy+YMhmLMG!k|AL}TrAf~1X zZ1b7@xb0vtK2hF8o;jU~;|L+f7>Bdu^fE|3i{DYU%UUN{u*brwQj{<9S6*2Dy~7oI4sE zz>p>dULv23H65=7%RY4H_$YyYH`#^-<7=4Ns735&YERlZJOUEuTky*!^5oY#=i=2n zF)@k~62J0)Tj%`C{=@%z6#xI+fAG`a$yUF8M#xGt7Rr*?yVI4-;-eC_MXarQ^e%>3 z&biJ~ruAoan~cEkXczNnL)N)a78Mg6NUBk*U~1wkR^)5T4ptNiPV2m2pH7vFW{(Ue zdBH938FhKvU^C zw)&?VK5sF^PeWg5=DtVMx z-koXP&BrHg@uW1nt?IGXEz;xYVHO}C&gS(w@j}kWZNIsOkPUgl@C#&YSJS2At8rh^iU2LSvRvghf2D8>q z;j5a`aFEJ4_MjfPzmgPb4H}2{RF!$oC$T@7-YhUO+{M4vt75472{v%Z5*|H!mtbwZ zHF{0m!WSBsvk_YJpsu+JZJwFnqp<6&ban-neRd@d?LRTbX){|%7Vz@Ifn;h^HEzD0 z!tLG8FsY5JN!X(eoa{`m(mrtroW7>>rK?8attxBK86V5n$_C-7j8aCHTk?aQ{qaC- z7)_iXj1BkVVONF$_+PKZAIAV3gC66p_!c(7+lBjx*DiDAwg@ssd3>eoT^3v!$6oI= zH;|_ML1GbmmaeNDp^m%f5=c=$N2grR)h6s}3) z1=3scS?0?`{z=eAIzCkZS!cmdU)AMr5>Rk4rHls}+Yk+jCM?>WN zcJI0rjfmaMjoxr}N#$tOPnS@><5V^qoe?E6>=nd!AJ1b`w@6d-=htw?i_zrqM;Xuy zSHN>-lW=p(akLr~LmGM}a%sbd;D4|l&lP3xg7l24a)n%S;c^96KX6;HWA_1w6U^hI zXHG_=4UTy9zAoR}WXd8<9IGtgW^LoaIfimCVwZMwR(&9B~O@R*a~O=gT!*_tQ@GVQ4ZcG49LQLSP(y71q&iuGU+R9?1ZmuB0>k#@ zMcmoxFt>X@7`~jTg@<)&{EJQ!=sy1rH>xuD-V#S1Hv2tm7SC&;?+g(J)??F;Vm9OS zeVkI$3uQz4;_06?u>PznE8msLK8U{|lFu*Utx4Umz08}JZ94#2OW$ClwI!Dx-bzN< zdg0XTWqhjIP_%jR915x;`02(x{&47Mct19eU*WfKX+>XtHlz#nk{{!)w-eFFDIOCY zufgPfz2Nxvl+}2Gw zz0vT}dYZM1k$&m>iL!|gO^I3pZxj>3&?TIzOO=D#u&wwqCyaJjmO^2VMZ~-OAh6x} zu8ymlAiC@LvBS&d9Hv^t$5=RS<5Tff$jzF!+)vJnS+?pGiXrr3~s3IvZ=dZVF}| zk)diEPQoS=Lw3nARIpd}B5J-LMbuAqfL+rDbUFH+rOR9-bJjVrF)amE{S&(c6BQfS zC(9NVURuqLw`vL^w-u13`*d-N*%p@E8q4gKJz}PF_6vR}Hk4JqF0MPnAR3*f7UDAv4XnwR5frWn zz=v=3(CED%UzgD=Fbx_>O7>=m;{f!DL8~(F3hO6ITAIOI&Kw~S)V>|-wu%fiRl=Qqmz?;;ojD*@a*$BEN)T;7fWZpaoTL!u`w1l__E{$ZqtsU$5T(T84o66^mz+e$fd!Oy&X6sU>h7gWy9>g=!oMkdJ?@;m&u|L&td9ef001D7v1GQi&+(q zVP6h+L9v!Rew9?igCYItrEeEVn7fHU<>*{)_3{puYnDT~Z#v7ew1GIs27G;^7%i=w z`InvPsIs#k7&j)9FD_RFY2}u#b6TgN-Ag?#b!ZA(-gFX{-Z0`LdmdybEmL@MlNv~$ zO(EabiTL%$D!AQP4?Hgi@fYK6VSrmCe9C@>?tB>AZ&QzzxE+he>hjcxX*B2AGl9Hs zBTIbsQ?xQwmNzdhX0xyL){pT)Z(|IiPlwoez-2` zbq|L5-4<|(zFE+`#~!5{&Z5*v5n6tK1T#JY)m+`5+I0-&TZbjVHIGNM;o}Jq`{C0| zZ*#fBwNCQmKrVLB7(Uxagr3X@n?@T$ZS+o9@+1!J-CJN$OFpTeWeJLhdvP1{cu>iH zLWUhu;TCoeN$*1&Ns8zQO5Z7linL=Ow|xMwyKGD9tT#hgi62I_sFVI(+XU~mHiB!{ zI$oI|_7(n7fJ=Mz;#S79z;0d~%-q(C7r(g#7WWTAtw%5)C)1rscIx45sR{gx-b+z^ ze4IFLX$iM@dV`I8bq0(cy~4ejVt>S{C9I>@K9-rb0^{E7!<_-8g7gP5ydyA%XsH~= z*-zJTqT^27V+TRX%A-7bZY#U1H4;`VNaC^H7s$F%6YzBVN`9^|2Fn-iz~$YtxbI*E z9IbVqMLzfE?L-zkj(n>!%g(`mx1Y0=y@#>=$wGnYqBPzoa6P-fw4Mcc1aRdS-AHRl zPb@Uf;hRfyNN7_gdCT^JaK|GMJ4*6?-(KU!J-bo+)-*wkf(~qMn8&52h0`O71^C%G zjJK&xM6ahAD8C{{)c0aNRCaUaQL6;JC?o(pos{5FmloBIH|BdvU*qkuRoI+ZCaODD zO%yYCi5%{v3F^!n1>MG+5FO4nz?#e)mKoY9(y(wRoi>M9m_P&L#uqT1166FQ@;=tq z_o3jEYYJ1pqldSBpEIwh=j8UqUF=f)anZ+UJ;?j612vm>k|C>(h`!vt1HpYw`NiU8 zC~Qgsl{pFg!>Sd`+HoSj&L2!0Z{5ZMjlo>a_^2RkX*nidHN#k$fjFI;VB;nmt~oys zv%Y*ptE40Brk^Gr?o*AG-=~20o`raSV?VxryN0O#P&u5MB;IQY8iI#2f0BpV)4AKM zU^Xcg+46ofd3;|rZW%fcZe^}xK`VVAVMP_Ip6Q9Ft*goH{_k+^)L4xBQHFirErRxy zhcWNx2yS$tfk}HdvVynXd~LQD2Ca5N%lG0rj$CD(xm%z!C7fP<`&7{L>}J;kUv|>b z;_uqd6EpB=z-)R{Ap%5;2)WfP2L-!6GLP1fD%_WDeaYOcKcR?;;TIL8y1$W1FuAvloE_$mcc{8v9v1 ze;m-|T!=(A%L~GIQcp9t?3p#$3>M{ z>UiSHQ1z42KjW!o**G9e_QUMbLu{MMcX15gZob}YB6pp3n|Z&vz^uEOqjOYG9C5gX zL{>7UH(e6t3nn7}_<;?(okv#JP9RISNW<#e>)7ed`WXG#5hT9KVq;2>;KQ5xs^yIy zcz3Q58+++4k?^`l$dW6fxIigkc1wLfrS%bA7(WeJI2`M>QCX#IyB^e+L-ULL*v z%?{eKoxxZOd1%TThzfqw=*{_g?Bt|)EQK(PFO;YAs^d_QV!*Q(<@2pK^7*q(Zgf(B zG*6$d$Qm3Hv1#cCxa#8vU-vUiOWy7BHo^@0U$&>F<4Z{Gtqp<#?(v&Xg3o=G?z6-` z3BU4xlcCqY$nY!1`L_^aFAwE^%AgmM3C-g&*+7|xB2|wGxMsk6)K&ftJvKH%uWzfs zRZ@u-Px8Vqv7CjSGXj5e8Gcv%Jvn*vXFRJbflgWj`Sg_=(D{`yYctAZxA#rOgep1e z)O|a=2+d`&I<2C>j}|;5B9|n^ig3SA4|-zqW~_8G;43f&CLZ!4(cR-AJ-!3O9!pSd zxh?Q<-X*rv{}A-rq(*s7qyn+rzw&>R{omT}&-m{Dqy3%-nDUg5X5yGl9lke6 ziI3myMpNpv>4GDVnOrug}=BprFN5~>Q! zQ5$VIz30wnF4Li^v#P2xqfW7TGKX12@H)a*>;U5^OZqH1_hp-tg7DIpf7n0usNnuaD%f%b#Z&{54uy<<}qnmi~Fd!9Sn=t8b9*-<~`r zj=uiu)BlLC{wL61opSyTq@w@tKz}$E{S)Y~UJ-u>di<|Ie|q%%6X>toj(-Q*YxFOS z{@11ApFn>dpZ*TCap1oJ{do$)KY{)_Nc}ziOy>82?KObN^qUKlI+$M^@JIk17V;#P9Hr^y?&zU+I6Y sXMR(335jd&zZHvBU-s9r84_ED{C+PfzWDmc$o{&M7ytaK|9jp42cJU~i2wiq literal 0 HcmV?d00001 diff --git a/crazyflie_sim/crazyflie_sim/backend/data/neuralswarm2/phi_S.pth b/crazyflie_sim/crazyflie_sim/backend/data/neuralswarm2/phi_S.pth new file mode 100644 index 0000000000000000000000000000000000000000..ba8c848d21cc4fc0952c035c3fc824907d7b8db7 GIT binary patch literal 17399 zcmbWf2{=|=+c$2`Oi@y%q)|!cVV_GR6_PY64ak`2%Fvu4B%usxP)U>&kqqV9=ZQjt zq*m}yB)Hg6F%5T&{?+9h+2hF6XROVPM_ZYUHnX&_ zv^KR6$jp)yRr)T86!dV(ju6OBaS?OTbdgCE$hpY4h$jl?MNi=h6WU;`rr1|EVze-SkO z7s0{*gflS~ji!l(xs|zvV2Fs|7?}vc&_4+dO%x0h@e~mp{wJnkgkXe+VB}u}P5&fl z^dAsSt<6Q_XKXAO^(R5&zX*>0MbP9=Fw+QunTNpqFM?+OB53g+;6wy1O-w~^+EPSN zPc(v7zwp#uLBxv&|rfr0P^ANya1kL^=$o`2q+S=4wbXi%8M$k?~P(4C0<`2LG zf&DLn4u67;jSx6`2*yRO5jf3~6Uof{#eNaqzh;GC{2%f(VdyMTt(aiq8iDg4q8sJ6 zG+Z!+nh0 zU3$pY^stg#A`_9uEj!oG2L^WIcGZEXBa+pd?0j$bh$L21ZZMQ^fJewH25uG*^0PVYmcbBZ7j|t1v4Jh#kjSoGEMu`5tdY0lwmj)@; zmYWZ-D;so+I!pS|9m7nlIWUy<*xJYrN_yKRc*U~0y>D?JCn0{QKM4B{_OT0G=tsi* zWZGfV$4+cj14|h6Fy9mfoC3i!^R&I_ckEeyQ! z6`4}6DlQHsk<4T20Dk-6MaGWC!86?HF{H*5_#Byjt z=2knsWp=fzXAh&hTUF3_aXN3qHS=Qbow$vu*c~z`VCz)GYMp~uF!pm28$Y>~&5ayW zn>n!%)NT4vlT{ON^3iPKgAujsrUupCOpvD4-tyG>MuORY6Oc*b$lARjo^~%Ydvnb< z)!CLa2e_(%E!>s2rBsoXN6L*?u;i+$U9JBIx}&)pf61w%bMfO@5@KS%%Ks*(y8lT| z|Fy0;IrRU>mh-p$N4hJT63^ZQC3!KtbukhPf)`?9_YF?fdLLZ$3;}2FI(V??Db9aA zik*2c;AY%?j!L$l@lC}OEPvUGyLLXYb!t|mCi@%M;RR%`5P%&aJ*YS9O`0W+wEJuk zv?@j5m+wP4sVoa#vF{I%o~S{!6UAZun2m6wd>$x`y91{_PM~Bbe;5=dM`HWbpv`0< z-I1)Y`85t-{rwm35v>lt%KtVF8vkJ&{%Zqra!~tE19%SM64lHlJDf7E* z%wDww!`$Q~(v)^#PxNz{_kIU9R)5zY@A8gR_`QW9{=drq)(5qJ@56tuuucvt|LlWl z?hE{I%MAwT7&3*}0&Hyy0$)`{%KoOv((`oaOSe2r>*LQAwy8qUi&98ieFslf2UDMK zJ?Kub1yswI@lQJBXwsTiXquDC{~B-mt6%)wfAReP;5y{rxc;_7J2?#eC)d9T-d{hW z7JUGT%Y8YmxFfa)_nDIFo3miAe*mI$#kj`yIDSA`4lE2h0-Qu0US-eFqqhaQ`Q^i6 z-6Xhk`z5Z8o&nXPd(wl}6If!GgwHmNfp0cW$3y4vSTVc;A7rbuI4xJ`)5Diu@3tlf zlXWHqxXC>J8Svx3J+l<+FE`-X`MBd@cY$`eNi5(4`$1a2o0cXkG(5kJ6H=_@;E8S&i zD76o3wYBV~A05Cd9V$`qv;uA^PQp(w%OF+DkZD}-L4UmNItkSMN093%M^f*w;|KLi7H+ElgmfUZZ>dX;cdW{3Aq5C;ae+Pd1!MAvzuPKY`uY#W5$Y$m%^MRvYuoY3BEVOh2 zi>gSV{#WhjPW4VEc$rUUXO`gYo{D64Q4JGv4!_$=vs=DR8hAXo`s?Q#*djE#X4xT`XfGnKzVmgdCJB+>0xd`fuH~@V~ zl95lft$Z?$ul3evtL~*kmx&?uzLQ7RPbAp7A10i#QxTR%uBCw+l<2KQAf^1g1Re$7 zuta+(1cf63-D_UAF#w`QbWtYdd@ zpeeg?A(Cl0%TmI0MKW$Hq>7WRIQIQoT42#hKi=kI+@T!y(@C6(ANm6KEgr$S;T@=X z^&{5Y{tjt_CPS0QasGN+2S4q(1&uE>#^G~z;qHzPptHOUPhT=(-=AvHYt!CvYqBpc z+H)Ojhh4-?DzP9GSHiY~7a=Jt8TQYXrG;l4_-gAjm@`#@QmUkB%Jf5=PlP(nHN1{l ztwJ~%?|?~L^w^cn>dgDzSk}2Jfh>xy+s0phg!3vl^DUENc)_a~(C=e98+RgINzwvYWn_ z*{aLOF)w%)8+39FGyRxGRpYGKgvIS_`nH?!HdGJiuhypd=d1Xq-i_R_w)ODcy_(4? z=`%U2Has?4f*zD~!T2C@@w<`_TL6@n}4xdEegv5XTI5FIU7J8Hfvttts;@1y703|yfKWwIAh zXJsx7coG1XUT>K6m<*D0*I`R_7htcbQ1ECNYIo&iJbPHH%pQ*nr0tcd@IEq|J&Iq= z@9uqS%+?0$k($s{s*4_Yb`BRXoaEkv?eHHR7cH;S6pM)0WX5=Yc0SY&J+UgxpX2bUP zB+D6**l{x|-?SRM8(nxCV`Ucbr6+w(8pS$kH;(GI1F`;BF!K6a zvTC(pJ@w4#ORYXFmo>(wJ;wCYpQn^^Kep>(GoSQ*1loN`23;8oHc@2*EIP9?f4b*5 zQqH*t>Da~+`)kvzxV7wN>S$XSdlovnAM=~Osk5BAZeiWNDonDUOLxk1P`T+4q)YDQ zH$7^ko^Qn2yeC5Ts_Y909-M~WnKH1_Yp&>9#Fct3&1PQ)$%+E7{V{RlKoMS~2N8|7bw;Z2D z_amLxjWtgWm!a8_s(Vp_77HzjFIkWBho^(vSp^6kV$S)wCxVxH z5Biak4JtVgFq_N9<*Mo2VI}A}`)ZVZXc8-&v zub(%-eq}wDyh@twebtE#qZ{GX=gSzQei=>Kvl_9c@3!x-8&~%%#EQ&bq`dA8t$uO? zr$i^x1qXfGGe6FP=dxnpB6XSJJLTGh2Lg8WyfHOha^g4V3}Hj0<=BRjCNAt-3R|mz z+_*M*c4M=d@UY@>m}oz|w*I3ou?u4C{FgrT?wmFBdLvCH6=l>lU7q=@zK;g4qnYcu zb?n^dSuA2lEgseQfNgUNKyGp&Yd!M;WOGL_Lwd*6T<~Wb51$1GmwBk{D@mS%Yzh0m z##3Xv=-vAW_K_Xpx8C{&Uv+k%rg|@Cp?;1|+@A#=muEo!8-LarsKO@9?Z?EAp6AVS zx6t7zMYi8&FK8@2g1M3j*g2&GjEoF;+{xpeZwFxYb}!9yYUKko zkMSSHW@AH^QSFl@bJ)%Cg&Q*TOwy;4K@honKE*ZqC(EG(Z;j_;O^3rgnZPm%dhaH6C;|Q-aAWUvqP^fhaIYCG5vjUDi9Rs%Ed-_aOyX14Z={w3+vpaX3_FZs=_iY! zpL=zoZn8KNyfwu{cYQIJM3AJOjw zY8&K|{hDynHP7Y@zsz8xANHflW2UU%X(97fO1Cxc3}zRk=W{_O6CmWRE_I+4S&Tfz z)Msmx--`__Cacrd%Q>0MDy^U@YpO8U{WI)5B15$&>fp7z2TROt!K}LNY;ssD+lqibCxYLByJw>+)c{fI4) zDIZTG-l(#j`{$s4X%thRq=$E#fLW*o(SA8cxOmZKBW#5Hs;p2FHXqfbq>w5nLvzIB+8G|%bj%X6T z%`+oe;V8Oc(~1U9u7gUn4XqqHkeninS^LzV{OFQ(_^2@#FPw~nnZt%rS)@39n4?18 z4f?bq`#8j$yMzbhw&Lj961EA~x551qXF9n2CD(F)E0!Kjq2jSsOz`s%34)qPA}kOT z%I3lF_HC^1-j$TKv_C>~4EShSq5dH+_9*u=)~IN+*c>~W<)=f#U-rR>&jxIX!T^@M zvXFz?8Zc~dWXqmy}{dRRJaZyajS>d;T#v zJa8VeQ|s`MK#Oe4hSS@&A#`xF)?{vC61BlW9Q)Bv3|6&9GQUzq zTir{2S-FfOPVuaV!l0=bF{%&c%Lo|vvJz((^r-c`QpkEe)?@B-ov3WmQgjV3;?tk0 zGL4c_jBYC9qXq||q{S|q;Vr8;L>+B+qLS8u_U1a_e>Z?cb7;qrSr3JQ_>QwxL$=` zb-FmnHjclP2-H}(8LNVO)5h1$(6I0f_sbptBaZgkqaw1uh|2$FyZCqei^w4UFZ1>P zV1F6+;~)l}%;v>fD(QUuDy6})d{6PcA19*mhZa7j&6KH}D*~k)X)=G-hq`app|hGeeSe?FpQtck zWpko|?`Q*$ZHG|*?P&HqxQoB{(iAE`4k4!}jiBbEK`D((aIw3{cIQD*vReqh`k!p^ z>e?QWE#z1EzwZCP90LDC{|}t6g|c2-D8OI`9LSx9nGbtX5Ak(;M~eiwd060~X&N-{ zq8NWa_9r&?N#+w{HPNA>9s958$;Qa6=5L;rpcJPVYB^`b&0AE;`8m!98MSiAT%!v` zuO_44kGZ7$L6h8fSl9d)Aw zdoTQSN|_>DMsW`x_GYxK70(sdLb;rV?IU9|uu4%*f?t9KWVqh20!y!;J{v z$XnkL^1|$@1PbJ}OHcN$0^CrzOx zj#nY=ZaEg*5X0FX`s|kTC*kU)rjSv+6U0@=@jb38@y^$k;Isc&*wmH>wn-nMUTYdV z@a_|C$=Qz&jTOm?D)?7Bizfr{-ha)h}suz)X4 z8{FW+{>jLTW#Ea2^3dPwEFTgXg6j{g;AK7D^UKz!At(#E;knhgDbf>sx7eeOd;P z?!tW;7AU``jq`temjBQ=4fhWD#MMU5=X(d1g8cf!C{ulp@0fC!Gd%tk?xz^x@KQ6T zYBP}1+Bd2(Y*_GN5KEph89&c;;6gVy@E@%5aC9PLWl@%F z*wJobe3}Y9n+y(yC;NwY@)JdCt<2pJURSOqU3p_*pWvgNqN^C3K=HFS`P1q zn)ah`wp#_>N%kP0sO$XA_MPN$O&1Kb{lPK6RXDjc0B6r4x_9jYtY&vGg?)my=YD+l z-7@ZRmpFjo0qE|dfzvW~Q~RkM)b?1DJ#fq*m0|19zh(-zrQQXeHx6WtOEd6$w;Hcm zaS>I0`*95~8sKYG6I5N>3M)={f{V#_ocCiESzAn@AHh{96O%`hF$XAUNgIt_zily@Bb*TM< zc+Gu2_+^t78yTqqEH;)OZtKOu+a)pg>pIRjZ#DCHJ&4r@sA2a*Sr%cq3paeb&F5ce!zhbM;Hcma4rxy) zKVub{d-nx%{e^U^-XBN3B-HiUfM*9g^ZSEcVPy3AUmMJ{bB|NP2VT48HNN>5C1 z+Sg2)vG0&@vD6-v*T0SJXM6Eqqn`2;%rl7}??T#;&vi65!nJMBZ37Qf+lYG?^9^U) zIQc{Bwd-*g^)2tqUzwc-@u4E0({M%RFE$s=lx|bJ=sn%Ot^iF>FLE{RbK#t679LpJ zler)6!!AwC5H_6FVY@yXz_XK&xhKaPVbRx8tX7-NA9YxOyN-@vxd&Ingr&Zir~3_e z=veab>;Nn_u!FKma(LCawuT?k1?AQHtgps(=%aZ-SQNV!$8$ZH+u2q;d?JVD2M4f7 z%f9Txd8>InyM9CLoY zlY;h+ppv~+cw)2((&UeDIp6`W^>hl06xWB%_wRD?)rFjO^jJu_^BqiNocUQ^HSo|^ zhRrk4g$nsn)K0C0N805$Bly5)7QOm#cg+ot?dHKr20W zgI}FEl$i_InQ>ak%r;`V0A+N2(xYfpIK;g?n9BMF_ zxb=q6b^IljotOt&?~}=W-a**mRlrLg5psgByVQ3m@Eto*&`s?6`;}J9-AVbjwXShA*pMNPz0L!RaWew{h^NrwnlfxjY^DJVJMg@g7N5MoKj}Xxpw*Y!Y==81aDF50 zDcY$BLRuxyQ_$eq6 zoUXnW21Go9pI)UfVX_S!FrQ2djQX=@cJi!1qYs-oZ!?T(7Wpe)4u?Bac)q(nn75Ta z1VP!eAj&uhTYa_oyO&0@^K$!XSy8S{zzYLr|56>^Y#fg#d8@})EiyL;`$CF3(;0M1PM~)4F6R)HBectmZ_wa6-zDXAYiq^rEic6ew z&VJ#k=t&SUdMDRuc9ae{y(YS(2r^+~DO^UXcFF-;P|PyH2aYu)HGduSJEMs{y_-0t z+-%rA(;I`;(;%=xoE1pg;FCux@LIetX{{fOUj|okZPjADe;-ZAsU1#1!@k1&R9Tuk zXA-}pSQ;DHE-oo>2=3KAOSg|sWmeHs&^l8{{Zb34*I=HLHGa!qdNrBC{3p>A)kt*U z?P&h6Hl%`BKI(EkUfPn(zsZneceIS@eDB>@9Hhlwj#`1|42h(^$zYwv&|_aui)3W> zIc%1dX3E2RgN(^>=oO()g}c1yk@bE`^4LfIBQ-E)%m+FkxdA3>d$R8ft+2ZN1FSFV z4_=Z-X?N^;GU%;?mfM~R>u&6Z_yid^FsPc}tLX>b(S>wj#9PvPH=NeC>}3I=w;)!$ zoE)Y-h6RS{Q2($Q7FVC3S4&KB_huUybgBrizj}ceDl0%vJR5d|EyM}J7Z9|wKaG)# zhwzrZ%&OfV7WBGv>VZKjrG+PL4&0c8}-p=J45-bLRLPTx1?T3v6^fZQUA?)Mz`NbKW|m<3{2 zk7V1N>0_{6WET#}&9XT^G8Bq@BsjC3ZfGeX(h-tX$Spb^a@WP<6IFSR581&Vd?$lj zRyn~tzxTq7PjetjEg!nSI+9XLFr~jjykcmrfoGczjJ2=gFHTFT@$&g896GxKE0&DM zS9_(w&vVN0f&y3AAF$f?*|${GFg_w2Tos2#nff)~-Z~4HW+ZV7Cuc#OFbdbT7Q)0i z_IPJx7WV5ChR0SF<58pSC>y$-lX{#WjLH7S1=oG$>&`Ami-y-+hkH7=t@u3W6kUMR z1+Q&iFWkm6i3+Z?+zy&v{p9R+JjCVCmWq5xxmPj6P&RSWYXlfcMq4Gfw60lpL+z?~k-IQX73Y9&sG z!iyF-^PLgyy;{M^zKesXsUzXR8cVQAm<|=?@z~j^SF`v|3QiZ<1cFT;)pVYl4QVnd zJS+ccyD78~x<5PGuATf|7?>Lj*VqWSRMpMJzlnm7ZEbvY;ZWQjQUv!r zJF%b6XHNdoQaE|shV9&x%*&4d$|b)GhoxUQirTmbr@qp)J+NXYj>__)Lno$D?sjQb zUt)~sJgdy}8F^ht>>M)JZL&4$ASR4NqZ+i4Rh_1hrhieb^iEJP`xMllbSazV8 zK7PK6gUl{NV}4&eFZ%Y_W_S;z(=8$KsXYbD7zpe78qllKOzvCpQaHSJ78aP@=XMTx z$+?SFqLte~=y=}AADCqYsSXVDVu~?$h9~;4YT?R{oACHPDJ~WU(jA8uG-HZHE_y7x zNfXAoro!{q8SK!BA-sIT4Uln=Va2c2Y2JH*6ZA>FFo42(z?!jtij zXs@;b`pA!=nCZrBt8WDF-ESQ)^W`!goFR*a4ZGmxgenrq#L?u;4Y2ZQ6vcWT<0kqJ z;v^C(`1lxGj^!@}=`LB*+HQ!zal(t|KF zwRcl6rQ;>6-sFnP=U+gtRu>$#c^9Zv{J>)(UD74)8U{_8#QJ9rM5ru;L05HIXpAE+ zxa^6qr|g2B2M*ET`Ub8db2+bZO&uafUE?gZeE9?^50;fUjf&rm1JCMLpm4ktQ$1y9 z;qh|3^`(J_st|trTyKsuyaQL_SMUcWwex#4r18?e5H_txD9uk*$2KpK|M0N^me+`Z z_FO~mO2`eIzqN?}mbMVr6gAN)X94+6zsC39w*hO$6>t_VPhrKub@(dyJC|E)k5+9m z^s-?LW%_N$rGYZIwj-vdVc$DW&nlan{k0puJ#Hp{vlo=#q|BUk#)01LYvkm(2dlS+ zz!bMydiOI0bC0*flqI+Ma`Sh*UGFj6Qk6Hb{jwfwD;f#;r)IKq>Ge3GEE#_^9iwsG z-=HIGFI=_QjHgc4f_TMZXt}qQuUwfxGNw{^CZz>a3Z0n8lKr$jVFT*+Jd9%>jb~D! zw>j6%>*4fzjy$gr6s>qlx6g}wm?fFy|L6>;?Z3+L!`r|l=(4bO;&Z$<`T#eg@(Wxn zEfLw!hmp+zF^-Cw-k(|FOmCuge_WowX= zj$gKvkXU&JUT|wduWTm>X&gujJs1>vwsOOj3P3By2nBZa{7AiB&`Z7wL;O@|T+Kn8 zKEeYA`Z^0GV#ct(1L}F-Q~SAIDIqv%m=f(4A6cs#{F)jf!|9N38LxJpqwG1yVQOL* zEE}R&`zmcLEtQiB27DQs2Q zCT?ZdBCOjm2=~u#hU8o2nE7%T^Wns};U11Ou5=sj-EPD=#oWc1?@4&`n+8_+6kxdd zJm|Dbg>Qxfg$@}xxMxKM2AgT2s!JsQ^05^^TiO46OO@Wo3%WGP?)u8+7%bIIp zB{t_24)80V#X*0?9PX2;2cAAFgQ1eC(Cf}N=%sSSHgWJ}{%VTI{bxQD4oM#6r&A7C zyEbwuMm$$`*%}+}&4n4Ga=7ykKX8u=bMe!t7Ebz=3$Op_2OrgU4HoT_p&JD~ASq)E zf7!ATrL`nk=;PzG{FDvc`LvUpRptX0HPi8W=4Co=d`|fEau0Sox`h>6^Wn_@rl6|3w~W#MYRPf-ZWHW|i_*aw1o@(Y_W z(rdB7Zv&a@_JQ}eZK1?<895HD=lX9D*)_lJLi_Y^ewe~i%;S23>fm!c%!=UL*EsX; zX(REGt|&HYKp!Y=n~t3krPeDqeX`yD=_GH|7|buQiNnuh#d*b-Y5atuLzt$M4)ZoU zz-p&-T;4GhEK26U#35?XX(Hg_toLJ5++?^tMHaS?9f|F84q(BWQ0`Jc3#i+6lb28! zTa$G59BM@}?wxKWesLNibe@!j6G{%^^2k~ou<>Kf+ezEue8^X>vqK)fhi z@o>S0fk)8P+6pykCHlMygbP8(ps`*XCtN?sOS}j|m3w)h@;Q^YYMclK>r3Fk3`NXp z8UU;PBfuc=Fy45#2V)Zlg4Pui=wt2#Yk#=Hp0Uf|lZ7_I@}+1v>NEf2!x=7P!!>@` zOnZ1zIt?#f9*K3&Mxp!H?MTC(@>RE&@vjdma%IenOWL>vpL|-+JuAASQ`3__2f4S-r|0{zCLHDj4C7(LGd1-Y1VDBFkagmZ?~xRSDZl zENE|dB8-Yuf%F`E6xr4}i?ivrp(DERR$6~lnzb2&@`u2BO*4qMEaARaGOLo{t(bW= z_|G`!kOwoxG)2x8QTgBeE0+Hu-t^GJTo3`UZnModxR+7z08fym%Cw8fIM^>j>Z8_DRguG zC|>@f7X|ej1Oq>~!Gbqq$!0__U2Pst=RWqskPr!2_9GTcPe@bdG&i;q)YyByrTE77 zfo;XqePB55EVPLHT(?eTvm>LX^DTol$k?J-w3j6EwgHj!W0)_i7gJz6RXz#dgmv*9 z#fljE-4l!ZBPvhIgb9m%QL?%Zn>MVBT;$r(<;X~S+0y{k=GAkOK9}J2AqzgZU<$Rb zSkEo%u;TW-Q)b@PS**A)hdquximhu(AR}@Jm1{j_UG0jsngxDPdf$?6rrv^Q%VgOe zo82N^JOKv}EJTIF(ya4Q8h7zlJJsl)Z(XDY*wpR~7 zEL;OUhWe1+AQ$ejR0(bTu!l=v*0kW{P8fP(7Q0rkk{PW%k5}`S(plj>82ikdz9()% z|K}#`RG1Pi+8j&o4r@}9YBDY|+enW<7jk1(v5rZ8v|~~frVJl|cQ+se*L2|Sgnqp7 z$8~h7+8s=W9D#VdV|ecNLt#p8K1AL;0?+#^^P3mzGKU;@GB~!8jm0O>QndtI`YAId z?`@d7&VwyH&{q^c7|RNjb=m9}mszdpVe&td%^aWka_@Ja!mneV+wQo%80I+5VR_v- z*x)>dUCJn`Sw46pdl0yhEo_dZ%Aay}nadhcu`3$YHu*A}M~K-2PC+r%dlH@2Yk=()_hX$iYyvJ+SCj%C|+lws%odlNkLzj%l>#!rf%Jg%973No- zhsZE{$us?blh9x+f;;&ZWIeG-=%0aB9AIkZPSotm8gI zj?oVrua+vv_?`wyxf?NlKk0ZRXJ6ySZYUP=C*?QOmOB$L?OGR1n^(+#Ig`mQe2iu0n@w;~&jH7K?bwaM ztK(qG(ME{!e97}I-MC+(7if3RV9I;#IlcDt@O|1~)|uRwk?jK8VeLDxbcvBo@r7#E zoV*CNWxG&)16L z3s>)fH)qDP3@<5mf7fSRrmT!{mUc{kiw4bYs1sIx_hrY2_9e#;48`ZEu+RCsz|>O+ ziG38vXxd$rIUNdJ+g34^a3?a7?MA7mDd71+6O+Wg;+>obNOxI78)x+=%ke(^&5#hf zUwuTRgP#W7QTvcQ6H!7dn|DeuWG2VF=>0_jZ8Ta>u0;k+IXj4Qjasp;WCuU-Od4C3 ze+2tZ9RwM9yWn9B`RT{!E>6Id*DMVP3D}>YeP;x0%#$d?tF1s^kUn_MkM=ocijtK+Aw1+{ZOTtt8qn z!LWzbu>095&`V#(?K)fs7u1h}+bIcJ^JD|}INF;HcVEUT!#uI5y8_PJq{Cf@H+*@5 zo6VNB1^m-nRoLrR9ZVYNNz2R^V&$SlSUzM3yP=-SAM<>NQMRh&Ss4sr7j~0uqADhL zS~C9#EqXPf0LCjJyJ0p514arcFl`xLD8B&jYy7b8Vjf&Oc!LW%GX`S%bO8o!gPvPc zS-^BncJ7lMju;up?Y0y7-j@4ePLwtqGg#g3j_?F{Ra}RoHFor4j4^$!SE37Rr$Wzz z$<$MQBlM7bNEhYuS<*)DkB!Be4!1)i+#r6dHY!_#qJ(H;Hf)BnrKLgIOp=6Sl z2#(pau{tITI~7F15x3Qt?hIWVJ24iQT^@!-3omn80fS)c9DnxJWjRTkUxRgga&M5{EbsJw|a zh8i@&ZXx<~u0rwZp|<1vkKxFgLP&q-11)J@@IlrdzPp8Dm!>%E?ikCGM1KC|+*T-0 zJq-i9F2hqt8P@x20$VKD4knqR+<|rjnkkCiwN=lem?CMms4^0AE(b8{o2u-Hfgjg( zE0jVCL)r0ngP~0q`H4egQLDE+`3sXNaPxgo+1j7YU8@eaqHI~uv{a^TatL!ndqLYd zbKH>L3!2lPq0I5VguXjCE4+nQ-j8K%W2UfV$@zFda}e7Ya~u5S7DLFO9hiD}1^6tf zI}X>%(IC&6R(5Zs^s~-T8fr+lM0Tl=Ua_P&!G^hIr;73hT}kzldhM|IIqdA&P%^E& z52Ne{g2jb6)-SBdW^z(9>~UF)w=xXr>YHwx>hLU*I_*Nof6ibJM&{7?3AG$=vkS&a zO`!DsIHQ(iEK0$z5$}{-TRa2Nm?<)Sn)}gFq zekv^uy+oxw*RX?8O<1*m0o!(41z&8^gd(>L>ac8uj{8!zb1LqF<=bPla_TF%H~Ty2 z4#+rL_c^^7J6nW+P{ZGKqNmP1W~ zHO#Sl2SWoR7QAOLEfXL_PROSg)f3R~`Zap5?g}HC_S355>5x~>Q1Z+GR#kZpJ5NT! z3fqyG{^AfXxU9%jW6$uGp*LWW!WP{B<`{YXkYt9*A|L9*H!!Z-k0Wu??^fdYw?JaXq{dIqP-G9f9OBU zsp3G{ms=-+_?W&R`3zY<{o z3G{m==HG#qh|Wy-cSiq}LHbXi-_s=j4rC@e7UAE3{yUBHpFqFISNqmQ|9be>NgBVdf89_1A?RXam&W{2EfRg1U&m&M bZ5jLLZ*kGh-9=g?U%%SOi~V~3&u9M+bRv#O literal 0 HcmV?d00001 diff --git a/crazyflie_sim/crazyflie_sim/backend/data/neuralswarm2/rho_L.pth b/crazyflie_sim/crazyflie_sim/backend/data/neuralswarm2/rho_L.pth new file mode 100644 index 0000000000000000000000000000000000000000..a22dab4903176d22c32523947e366c9ec32e4750 GIT binary patch literal 19383 zcmbTdd036#_dZ^l2Wg@r6@?;|<~q+>hB9lAAw-4-nc_4XqR^a-Wh~NwB8gDvSvyiF zp+x3{WJ*O+k^FkSU+>TR_nEKj`+2Tw|8e$pp8MQupSAYhYwdfx&XkZ86O)w{`!A2O zn5x+F0588)AwH(w%Y&AiY*@2)$|NPRMgQT6=;!6Ne(hQxub@@y{R8D)0=#_!e7qf3 zc?HP}#f;p9;)V<4`=EWj#+iirtXk<8B<$xEw7w74WNC2FstGSJZR3}o$^Ad1xkJ2v9mNAXKQC; zXEDy!#@tLOy+ER`(`!SpP{v75B1kAZd#2b-!};*9Y%DE>8h$cP6QqNLntu~Cj23G3@$4fw_;1W1 zK|*ae;n05)H2<5R&VNC)wYIUawYIXgwH50AO;GQj1c&`aaQNR~`awbiH{pnX614a? zf+PPkoVi&aLo18EA+;8c`X@ode-SkLo8aibF~}!`c1? zCqA=p0PX(fXa6^(AV|o$3E`joEdS<*{}s^A+R}F1I7=&Q;rKp4@gU)Ze*i`aC;r86 z(%)bXK|)72;pE_O;gkh(eJ-WMuaW47#|>o+rHS7u=h5nT{eq7_k9WH zW4g#qdLS;Y4a4NTX>61!qqMo{IILU)yN*p}#rHKaUseTEV~p99-lLdtAq2-wS&!{b z4P;dq0n6|1=BA0(VQ*?QC+2BSS8cNKFMIc>38PN*jqYFVf3sKPzp?jU?lNVP+JBn5 z{xOdQI__rcMe9LlhZkGuH;}27MPR|a4r;!`vF?sLWPfKlt}hgkZP7s1G%FsXbr`g* zlxL5+ywP$>FG)Cm=7xQaW9h@UqwE@67JPR&#*dC#1_?>uR3;9dm zgVL;Mye@wRZju_)Ym$K5&2wO*#8#Gld@erKh{F06rtIwVM7HcgJWI+w_7D3h_RYHg ztNs6)9{vaWL^dQnx;WmjwH6npu&|w?D|t{d;i}*AfCGn2R3=2&^#Qik0ZY@WixNRr3GC1v!Wh(Tg(cZfUk3- z1^ZTBh1}hDV2O1PC&6ze6YZlQG~G>`Z{)+~9jhVX#u9S>n#V)c7!*iP!X|SucFJS! zKkT1u+~N9vwf|qy{Xf{>74S~*myf-_`1(}eLMZlE``>)b;=l2+f2}@KCYkVRZUcdmnUAP1{#U5wbgAPKPt_SSs54IrB-Nc!)rfi7V2fAo>nU+^% z@DYC`N+Q;@!~WJdXcODTYCOzv$w75CwI_Uf4Q) zCaqf}M#{M>nZtN*yl1zA**7MF$SQ(1v4zaUBMPV9Z-o0BFQG+L1p8ren5#@5%XY32 z@%J|L$NAITNd2)3t&`3`P%9!qOFLiA%d(mF+H{9EfQvI%Vfo#7mT5SMneEG?-NnVM z@LCEkTNR5VR>ojNzBd~aVULYwQP6NFkolWj1NkYb@UUGR_3kn9JgEt5wp5eOZzopw z`m-pqE0;CK#ZvXM12p@I8XCS0<7QJFYyR?C^iAl_lo!3=h94{B{dK&Vu4@&IS?$0S z8}31wS{Fapc@wOz7>f*yX{fO>w$8C+)w|C_>S=Q}IdlSjJ}b+n1ypmxnGvRD$z zBBXC{a$QH+Dmy7YH{%Sg=^BZbvbHn%13$RMON<~TeHu>EP{+Knwcz+64II83 zqUY8LMvbwRu!t<0&J{HC2+VN^Pxm5z)*%p97NQETu<7@of!(;AL|&-uex z(^N?FlMk{b6JPQM#e4AWJ_{)9{ldvK7vjmS&)|W94Er!@71P|%4|ONFP|5p~l(g^+ zd#b&I8H~%ovX7f^;zSiZ+Ps8a^3@&x;%N<(_Y>i}uvj)c<1ltUGh(yl6BtY=X0z1+ z<~-47Yln2=&L>T@#5j}PJTMgIB`L6H)3>pX(PPJ(78ml;V-G;|i#hy3^Jm;6!*eM6 zX*dQN zC;sMkI8Mg}Y2plIXONF(1szb`jX~EBqHM1wYEISS3Z5&{At^W9ylxMRy0{ubc2;rn zjhkWXDHE(6aEzX}9AtO81DH{nGrO>42Mh8)MH_=-VQLTqtI93l>10aUN&BeZf@5s| zEyPW6nqU=Z0*+o^i&GcuC&^8E*gwvYg^o=pn;*AW|=PDD+ zcOMQ34q>5Wj_+4G;EEtClunl97tXmx%g>!=OmiIU{^o@@ZWYoL`PFo0Y7v!3xpS(z zt8lNnHpXinz*9C3{3}y$F7wPV7FmgGbww;wO_RXg@5EV8W+AS4Yls0YquGy*Ih<%> zA^lYLg??#KSe7IN@y%(>t}~P^n0k)YDhUuu_CuU=B)ZQJ=QdT}N9SutQ9kM-%Xw#x z$L1(u_Sz8qiAI!Kql)4WZnMV&hET!pl`P-Qn1x24!q%**xPRGBrg1VBDRVJjutOVX zxmd7kFFj~yogBs1Tfn{!i-5URlPe-+CA5z`2hkMjE9NUxI z$oIZSNqB1t>nS=*Lph$!k$S@3R)(>vxE*Zpum+a2z?emRmSCl0oG=PTv%nh*a8B+w zT3vd9ei_S?=4=~Gbp2?bU#yQu-bCYx`lFOJb}$A``o*h+nW3ML3QN{^Wx=XBbQ3yh zbq|9}?Nixd)l_I6ACbg5gVon3nuz+Vj&BZ}3N`SE+(>W8J9K ze+5$t?$2(_-%S&X+vw=xspK3YhdV98*^wMAF1OW@JsEZhqZVw!f|SGTLtQKms0oG` zTN|9UNsq5Eb3*P&Dvi=fg}T1~^mv066T5zb-*xB_Ow3w=ViO}^%py6~uG=iwVs{Lt zd3AEE=nxBjbcIdsp1^8##o$%l3@n*WbSGJW)zXJpdWi}`=^@VZvpVak3qvi%bd+z3 zLHYGQXc(7Io^w3d+#mbd@fbB6toob_S{{vKmLDb$o5S=lssU%r@`H6zBQUdQ8sj^g zXzR`uELK5+MdU7qp~Lqv54Yn@~EU-Tq$a z5{4cZNN^~L^BEhA-=6QlxxYtYtWPkznz5H3{9-Z&%I7lU2wCQFHXaTJ_rpOZLlKSU zxd3Az)w!X@}N!rNf-u9!9uY6Eu+7UD;J4OlV<6zK6 zM?CUj6Sqm~99~>n0K2r;Vw9sMX6o2LXU}CeE^;rk@lzmu>rL#}i3F5wnu#B**AoBx zEnNAb#JaK`L*h>#mgck@A!#p6yP|`hQCa*oK{UJjr405Dz6RGW&cxau<$@c%-Q3RO zo8kR3BUUrb01ub+1J&3t=2_p&A8!u=m)8sM&Orlwu_he@d;D1Fj4)j5bXksOMG)KH$ZH4a}W64FU5z;#%u%jyzx9;7{c0VnK>o0d(5%~1%WYMOvtfkR|y5h6>+T+$VXLuqmt&4#9QwBl* zotv0-O91uHv7~PefviR#g~^qgtZ|&&mhY)w-dT@we%HrdoUB^oYy^hYDX zN@(Bc_~s^-pS(a{EXKnd&;6({G7^sUOQItmWtq;=0POx_#!}8s zU<*EIu_qh$F#E;s+=HLfMF*CRWTMi&Eaq1x+U$>pSqt@P$>STu?>G9@ zu?n-DRHtfL8e)v3SD{FjV%=C8E@>|0XP`9ZGUQPG{*JpcUwFJ-@VFzy&Zp9WZ@5em8 zEBqtB@;lk89-$~E_E-Dgavz)jn*03!1+6KQEdF0}pTAO}J3q|nd|oDt)vE*b<6ALd zY7K2t>f8GTMw8;JOnlSR#a*y$6@~ulfal|Lz+3$mhBcput=`}H5x$ModE5-|1;6Ew z9O?#^(+*C<^)YIEqoA9s!zH(!FwJTLSS*}~?fW!v>Uul$I^P0?hbIcY%^%IX7+9h4 z%e{iE`={xun-V;a&n|xRAzkpS{29McQVZG-ibMYKbKLRe#jM_KKPa!74+DkQ>Go7- zF7#P1uV$Kr;&03_wPma*!`hTDYcRzw6EEy)I>Wh-jDp+JJGhjC#k}T}SZY2$gBxBP zNB;M{;HSDVOwXypu(Qtavu(2|GyXWl&zvquef|+{RG;G}PWVdaRf=FiY6?)OG2C<* z$v$nYrA>!s!oUIpEVaz`zI#7pGE=^&w<>{YXx+*S`470(3Kd0RAhpnsn)>h_;Od*-g8wF_o}c+MWU6m}8@%dI2p-h6m;IUK&*{p8jJr_-_f z36xe}OgbAciI(Ra=eBBHr_7jol9GEPcxYY%e%plbu!p0OS+A-4^FW%Q770zO;z`x{ zGdOF;)7s|CpffOuOInyrT0eHX?9K-%dZTlu*3n z8~)UF;Jowpf|s2#+nH(uiEZDZSbr~fv)UYcqBZb{ZYW$T_F}?q>)67(YG~R0kZev5 zB1 z7xHVi!;q^HY-@`w{{Ewmzdp+_jb&EYFXay?e~-kYh98S(s;}Y({`gG=8;ZdG?rez2 z@n>+e~WUK%6yjJ{NJokZvA-&uzFE2%#$yG3@3R&@E}EAZ1C;euy<1)kmVt z2z}7&f0dhN5Jhe!Bk|=`2Z(Q0$3MRFK=-^FUT(Svlc!(8>)H))KxQ|L4;+DQ`wo%J z)d6s5dj)(P~63@{x;G$)MZIE%Ax@Xnb=tTA&x)3-QuksP^kP4w^-9+@Kz` zGdn~NeN}PKfkCX(Ljn)36Om|(8JccB2OA#l#I2eRVApvQcI72=AElM}7RA}vX7LK1 zsr{s+w)Y_ZBnnE#ijk7eR>pqp;FA*$fztTh5L-ExeU#FM%rXf)b#VtZznqW!pCiR% zFNtWyLuoqktX%X{-~x9PmNFSfNoJKl2%jIFK%yJ@o95ME604YzXtCbrrn2mFR^XVr683hZR1(J1g0 zJ=51IHuU}qu?Y)N{7^d#tJ=qlmKd|{q*{T3>nxmZpT@KY2eFPcX|`{lGH%_ri7f7# zBAeaG<>igycgJSZ z2|Meg(9HHCMA?VZ!TaJ|@x5EHUmD@oz=e#{)d9cj12LyVie@-mrIx%5vdBCMITl5b z+dl_p^fM&c03U(alsLiJ6mz;WK@L|ez0RFqxzJXa)A$PCurO zgY;vg$@ttxZm#$k+OkTGYdE$Xz9^aVxf@P%*)^-FaJ(1I8?g%>d#Ew1LtbQb(~2AD zC=SwtlPPmpJ*|_v50W=q=tH7DHJue>ff@oF=2DH-VEWRH35(*7bC5wL?lv8A0({F+J`;h(rqAIEZG4@$s6q8K(l9Z9`Quk$&L z59q}`SDLlw4wp4woU*f2>6-pcsJo;^X(z zC=_FNZdGw}W$h`#ApxHKxeL5UB-Es=fQ6^ypyHe>`MJ!7l&`t4r)(#+evRQb3VZ0& z#_NzOlf}Ou^pKA191P}JaUeOog;f2b`QJ0@DX4ofx%TRjiERYPei>6Z|RiI zKz!Kk1a)iVP)1IMttfj7cGl`pJohe^3JnEk7Uyv#<2ZcQc^>R-r$eQn25$4esb}Cb zcv7DU*Vn%w*^ztc()M%kdcjS2$dBeU3@0%M6$cjCtAHwgD(qRbF|M&l0!`;%{8w2U ze0RWzUfEuSt@Da$MS=_~@(Tym(Xwpf_cib(oG73#w|tiI0RFsw3jRG(Y-5}sy6)*9 ziD!t3-dm}}U^T27S4MYor}5I8chdVB2^OL=1s|rjkU&WWSD2S`D?Rp5cG*yr^9X`6 zw=5Xb`HUa-v>B2_)~vHL1hTjNf%s!W`XM(+wBg7p_S(}2=f>>BImw&hwuTDy9GJvM z1#d+c)zc6YH;6wtZZxJ%;ozd}9jv>2l&*5Bl(bBoIl8|BXNOhL^4PAgj#I|3Otrwm znL4;8{~n$RRN`$SUO}YyeW-0dM}89S$On%i-^($yW=jQ({?Q=%)Ghj$xAp%W%wDpY>4!k!X3lHojMY$%rdqo@GtLn1b zI>SUEJ4~T`)f%X*-H6*qEkHfpu^0=#;LQ(r*i$$Nt2T?{uOMA4-!coHnMk9*0Aql3Sc`ltsx}2n*A)d7D{dcG-bm9`@ zFGA3T8~A+uS|}Z{Kvddlfws=$NPXT5$UN8rinI{x7a5?)PK;*f#^OY~XujgK7Q3#$ z3*O|pp+}uDayrsjS|Wkx&869IK_P_fa>1Mdzqsi$ui5RnBY~-lZjhVvFig|c$2egk z|zJ~ zzBrejN;=|ODQODG{labd_6}q(IbzN{PuMZ`D7B3@WS7rf=juu|V8_xSoW+up@T=Sl zFPyE1jN|e=cudCWrm7HnB?nwW4zP`ua?DV349dAo2X~PKEe&3cc9GR!xL+A7HZOv& zr#$)czVXQ2kPR&_jPdx)yP)uJ4SYJAPQ(49NcD9LHO!6YgZ3NXYvVN1_RQy(gqq>S zBjNo0XaNSgzJTsFV^m(JiECc?Q~pg^=CuC?H(nwX*oad!DSR6Ht$YM)ZrhQ2Yd?CQ z@dM6JI!~GYPbi~eE7SE^!(`VCz$FIi%)7b+tZQY_)8jet4oTpDKnAl?j>AY-bGwG{ z8}Lm@3x5e1!Oi`YloCTjN)etq%%jq{JbvDUYjAl;4EtOugQ?eT@tpi_W-VXBYZU(E zk6gEc_Y>Pdq4hBwIB(2`IF>;0K~)?O9?I$~Wtsokq4bg^Vr`2ft=1YtLsxR#COSxm z0<}O<(w$Q42gCL72=?vHQt(}R4ipqiDdqYe_SpFj1iXDtd%lliBbyYMesnk8yB9*g zR04SSB2)S~PL0+~{z`#u;#k)4od*4QL^1`T?6kKY%lhfYTr>(ufvcqFVL<@WYP3?v zjCJKWKvU4B74d+ZRR#E55^F0 z4NQK$1y*#;!^`$-Y3tPI5LTAJB_z)QnMVQ;H;v^?8Xi-2m@0>c8sN2tvC41sS4n!n}n+`wFnAsKZNGzIWRhO zDe0BiVs~yNHDum`qFXcBQXeaH5gw%0wSZ9(BlyGxPvQ6JXwbS{il0{(!lz;ewZn8U zeAID1bCf#9oIXu2TKAG)uryBmIfTBB{s7<0BG|P6Rkk`KhQbUUKw8;n`dOgG3_fMT zoGmHD=AGikt25}Te!^#yJ!Id|p{lrg;4Z|{vmoS-f0;lg$~UO$<3;|qQVnH~8pMa* z6Xy=u+ft|0YijVVq(9#Vu;^K?+!qZErW+H@Pc>9yZ=4$_e~1_}Y`nsEm)CN>FSf($ zz8Dp7yU4%gAswDwPy1Sr&@#gmc;*vCsj=IEkMN+(Bc`x5;|f>*s~=PIilWXzM{vOI zb#S6_8$aX1Y(Zt18OiLLOx4lrSf_U@xj%B{i-*T^@_)+6@^>0#-5QIp24=$KN#~)l zr&)Bo>?L@^d$vZ9)|480|sGs%F-oW6k zmOZ~W!(TLKx(7?&KZJD*9YE zf0s2FP%;6gZkEKady@Gx#u}I-K8VkJv)<0F%8y-mZN+VoNTcaCepIul7Yuyj$b9`( zs7vu;3o?AE`c*pQPk&Fvligw0EH|8(WehGQvSjc39TJ@-=*0&!6a`jsYHjCWbWa0i z^vI%NSSMfUB&4);mL!rxCL3mp<{e|`-CTVv|74F!6?V*DBaff{W-`9|?T)rrzj1M9 zn>gh{A9nWc4tPI#Ha>o3zy$hZNNUDKFzA=S6&mD&_u5(-?!xG6zbjBZ&xwvqSO{em zrDU$0!b^UgON&;wlHAEcxOb+V;x3gDFZ+}qvOApyeU1U=(gjp6twGa_-Ki-ykL<7Q zpxzNY=_uMl`Nnz*FghoA*ucZ8gA#nm3nAHdR+0I}t9)F3IqzMp4Ef2GqJH0dcpq17 z8hdjLEZ0q@bg?YhW$+S%>eJbx!I${BA6wY(S|{qbnF+GLB1uwL7pomhsi^4)-7Pd= z7NZWccYAiQDphUH%3ci1Pc7g#wtCU)LNAfRQ7@A862p08rZKxkBiPEj(cJ4(qwvO& zPF{A0DYM&|$;DMDv5lYQU|aig%7_nTJso2Fi;;<3xGA?I;8|Z4@2( zpoF@qKcP;20iEs}gThBNAE5d1FO2u;P0(SL-N&CynDp579SivD`*zU{@4h{cn=VaoF`#r3$o_7hPDyH$h+bYMcavV) zUYP@R4P~OX-*>@d@D^G=r;wDZGx>R6+(C!C%&&Ca4%L12zza9ixT;_G=-Pru#H*?zQdR~t8D!(%c?7H5N;4v<=Twn)BnA(hq-U|;Pe zn78L+QVf@ecegH6e7X~tFi#vNyj5j`Li>Sha}2Z2jl-gXZt|UFK}-8|PU6!}kfEL; zbxxi~d801U5RC}#b?_7D{d0=D9yy81@l8uu=+#a+8r|;Dcl=FuXJ$XS~+klQG$D1-AM^& zO)z7oAsUREAPCqq04}#}#I<7%(4Q%eU>)sHWNH0~C#iFGnSP7dFt;7dFt-W5J8QFm zAYXQLMx*^K(8Wrb@367M3i?mfVr7=vu*}b~=&}AvobbMi2Fxmh#b1Z9n`Vl|<eb$BGlQl5*{T;aHvzJmA`9S)$P#B-l3|D03(eP_4WH`u*W>x)xwA<|v z9o)fhNIpvQMOvIr!BXh8-9SGKRC(_UF)*Wj7bq51!C9xzjm#;-RCUD#$j4ouPAq=AMR1rA>G9Bc>bC^ zb6f5K1;JDC$l3RN;0gimSh5_vWv1Y~jdF};tix%V^4QV(5gr=59CwNt!{}%S94TCa z{l8>Dba5DIR?MSYfm8XAyC?ec#&2+cfi;F1xMN#zIy@hdi~*@9ATZ$=tW&>7iSrTC zZz!PTIwQ=kFvPRI+U)UFM#DWnbLJ&kWR#~%Y^yfE_u>NRa+^T&ol^v2&X1|csTWSf zc~h111G=?JgEy2v4<~XCg6*+8+&+&gaGr7(B0|b|{%0^Z;af1BTi8nBee;@mH^Tf8;_A{kgXyJ|rA>6QpckpTQBRCemThuOSp|)T*)~LLIv%BL7@&($cU$23y z8};ek8E14%7iWV{2&td%QJ8S`C!M%=3hb+!!R@I6#vEwmT27mS_q0IL+;fO?oWHN{ zY_OH*FPU)$?Z;vFwj^j@q7QR+uVPCw9q~tO0attM5Z9sK0bj;U5{$~tgk2xBaCNd8 zTjw^1ZOyz&)hBxS{hKavj#6K^{Rf}Ho1zJvcH4#GOX=b8QIkWXby1|*cc#7tLwLaz z3v78`OLMmm<&y_yLtxbbnyXR39X%b(U9s8Hv+G4wFXoZ%}mN;ZSHZNsQS?8+6>bj;{Ui~9oqnUP3pT`XrY6v>3KY*%#BYE!H0aIE&^Lq^E(3l^2Tu;+i{lrBo}!ALOA2VJ{(P`?m`e{r2D89&HOzBY!P2}+vT-2(+R#!; zJAR$2kJv*AJI*>5?*fj!pyY9Yrq)YA=2|sr9)CiUPNq`)@p_rRYUvPkFL zNsQa~UhrN%j-Pg1gBxe2$nGvwg+=F`arU(sFq#c3nmp$g4^$hQFe?!)ZM&F z8*W-+#@QrTzc&GFBrZbxib?|88{BaHHfk&};KADpU#EYkuLGAr$>w;jHPjjQhSx)4 zvN2AX0WUg&Yji!ZMOLr zclre~S0M@={sv@h2tH3Lg1B^P*7WmY(e8;ECjWj4F-@j;T`vGVllODC@5RHdGz}*4@f3LX=-`t<19&dl z4>yf}0A_qy|@+62iS-KNqd14uRSA z-h#cxg(SYglcvwmL0)n_?p>2jzMq^}1!qN{2FB9Ko1U=6u>sbKrNfAX?MTXMv>`GY z&7LFpiw#2~KVx?4b_##%TQgr()=iI%Z^1VyQ(XTk5ni6ih54aMEa>oN`=8+%aBkyV z_BBnG6)Kj3VfR(^`!s__fVm*MA(>nALr9;E2b2DVX4ueItJEvM4%5rVQ{sv9oP7T{ zvaUHNh@AJ5Pi~3frzLQ3ddpB6t-S)q7RT|6Ht_s|uu^y-HJ#S!jODZo4)B5_je=Qw zL-=J94+v&-Q@`Ouq0(tL&FO!M{8#yq3ZCOrlFZ=z&VKO6Mx91Xya}@$>qOaZd*Fll zbz0OuiTF8j{F~ud`0Ub0km7le=XYPE-N)3J(54$k_SKATZB7v>_Zvc^u5QG|JMBc( zo7LH?w!U-Y52}3c+HOu@2Y5(PhD)3*f@>aMAZvmNm2Odk<1g~b@5~>;AjQczN=JZ( zL-e`2x{YweXenfc%CY)e9J8ME5!$+*gVK*tnnl(=}3N+w;TBddqvifg|3QGFBrm?1`~PU39L3r!5Fnt^X0>$0a4 zl$g@Ew~#);gI^n_hnEr`LHb)UfjCKnc7;E$Y_}RWG)d!C^$alZHDjQzL(L_cZ0US+ z_VAe@=t;Z+?&BMn({K?gy;C_$nMSVFs8w`ZESIIeOK@{CHEHDeRDRZoArNcu9+-?C z{FrczEX7SgW$8ttl7Vn#MXiNC$= z4?kEyVDRJ}+>k!aNmt&0MNg;FwYc5r`&0xOx6>hV?`QgYH--UHF49JAQ?JRx$7|`9qSvhpASw4jlHJp{5(nB1?~(l-ThS zJg=wl*RqDw!(;hmn{yhfY|_D4s)(}Nn z1Z%bQnV?StnW=Lhu3jC22?7(gsGl?YG}r~sPBX;?ajksYhe7E0F&pGgNu&APJG8~5 z7Aos!;srBt3R0Mc>cPKx-vjE1kEQH#Bd4QeF44e*@pI5VqlJ4C{FEFH$&mU?cN|iojOq`s zbG{Q(K+fhkE!!FbidULMs$Pr8>O(N~o|51;6-Wz&g&OGc(TYwQwNu_8Cp^+&KrI>L zQGequ7&pTZpRSN%J4zEt^#P+LzoTeXLMg=f>!Ylj8_gde!+h54=N4vG*>nDBkojje zgF|0P^x+J(jZDE=H;(cvBoyiBr6igweTS;sjObv~EcACs1huQbxG(CCP}QjbZp&8U zcAb5s%8KaZ-N~5sRU6Na{6!Cj3Nh{XOLE`398>q3LBie_upsOL=ThHAT(UBDwiUy0 zTThTKQwGx|LEPZk3MlhSjtzKtgLeG9%yqDtDADr`I=8#PG5w!htR>=&G9yeM$wU6u zF|=}oG&g&4f2_^5#v%n%Ol@ZTkd1w3vo=0>N9-sUnvSqFGX`oeRMC=waX7%F89qv< z(%>}{S#$SB!IfdZsK|5(M*ZSJZ`f8EsThvcZs~%!hDdy|{R>?Brp>FS__B&SQ#R(a*QP#9QYj`=DrgQ_x6U54lbnhMTw>LWP+wfUw*hk zmRY2bKMguAaIKVkQ2WG!wE1gd(f-Z%5Xs@h^ zla#LTkAjCV@6IF;TP&h8mJ+BvaSu&USco0@Gwrt@mtvpqHuEP>Ps3|xCy|S`KQ5C> z6FIJU3!Sgt5lh@oU)4_+k6Ps{YWVENugy2bu~#m@eYxova9bU(bXAejZfQQWJc^d> zxl8pWE;#k=34zFDIIL=mrE9;#vE{ZH1cpkoC+^+UYUU3MYTZzGwle-6RS04Q`P}3? z7wvoJY{zb8BOKo_fX)sb&3ioRtBWpq!97@41;?Lv(7@BXMW;O%i!#OxfqwhlX!&@g z^x_kAG}I2JOBPaAb1{^j(Z(Q!dwliV3*0)_XWR&pfV-|YiB@-6;*FraFy+TO%AeXz zk7QfzVrz$z;-vYM?P9|QN~*GjpOJ1YnU9BtFs ze3I-H3cRrhdfz3$pv_%0GVV3Vxa!c=;8vPoGzU6XC-YCHInvvZ6t1DKMsnC#7MjAJ z(692NBsn7iB9=d<%h9{wNB(oNoHK!sPq_&xHx*&9my2lQ!tuP^ylI?o!$7WL));z} zdj)o0d24sfTEy25xI<4aIfAEwB_&?ygq!=ub61_?M5Ag{;CoLKw48fRxq88nax|9H zUNoC_Svi7psu4n27>p?^>#KV{;R>|Aawn_yz?YfD{My!y(9xJAGK)RNmzBKa9fL>X z2n9wf%tm12XH%|QsUOZ5nQfo9!wjL~DSSUSo_*F_&7?1l;e0oUW5&h+C@r3ja5I)N zT$ixNMb3Tq#9l#tq%y0s*+fzXuz0x=hh{Z_3abAQqW{8<>YXq-c2t2{z_QUaTPS*9*31-tI%w} z7(a8)D+*m6OOm5v!RWFiw$!V$7K0Q~-lG7HK4RaMO*5*SJrA57NU*5e{diGUDjhM9 zf`a*eB=b%Y!t@=@0){cxyw5qb9W-` zz==Nvs1q!DHry|esIuG6o*84_tZ$?Z8pL#vP)qtP8VvB)5{Kxw|qcf%|(nqa6yYPvj@cwW#+O+<2kCIKh|#ApHOs* z4IuqLM(n6lI+>3i%7*NW<9p^zK<$@mkll8VUaP8*S!py(GE)&*+)1I5)C!8IDkIIw z6Di=LAC!62(TsiLXjD)VZMjjyKkIVgvfYD7Q|l}5akq$Xw9bH>xogSIqLlone<8j8 zku>({GgxkW4L<*_rAK}rC{eAQUOyQQW~Vy^Gp0~uABNpohz0v}ao?-Q zf*o4wRI}$eWGDTh_rV+Zvn$+ry|wp1v$Tg|4t*!NhU>hk;!&tOEDy`J#gO&^V=gRJ zjkSxN;}#rHhN`R$^wu|#Tah3Rn+_BK@7P3}PaFbim22GV6+3DBKrP@VMsoh9Zd~r~ zWX|x>SyK-U8|RVtOl?Z^Zlu?aYiQ3r zTTWZHjVpVv11DOu;H%UbTI#4oadp_IxpCt@eiCCB;-ACG34M1exA$v&}b=28rJveYZTG!%jZ5V%sz-QoPvWM zzu{$DC9(W_E3BJ|I5@crHb*I=YT*t_n>h{^)Qsm{PNmS3*Lo;5BN3MH^U$^79eCBm zqWz7>aA~j*j@YTO&U|m!limdzv4fzMlK z>e+6NgI3N*1ItKJ!Jxh~)YElb*ZsxZ@WDxBxL>`|yG}E`&iFjCI430lL z0p-u$Ch>RP^l5M)7{qF`wNrk==#(Z{q$9@soijl?TbJd(9m&K>ohf?86=ocFlKP!L z2fM!OW2~(`l|GbYoo|0}H$=f?2A0%pHVWr!`QyP|t3We681^g*U_E{w9R(AoDkoKG-= z;?6$q`RrL#w|OaEZjYc71w)`{>9XI7uVNKJ7Ori3IevUThWqx>Y%J-rQF*_DjwG+= zmYc7TU;T~vifjNA=PiTk-)_VzD;`70taU^+`3W4lFN60F`w)-8m$^oVmc00=J9a@y zG|l9KNnKep)Kr_{)QwGS26vmC+v7nte)cAJgkHeWv-Pk(d_KG5v=)L3)g(7d2hZkq zgQNK-R5NXm?HIsv{%q9GdyLqc^#xn_!faw&X3~6fG7RjmmyxRWWYWED0E>PPrH1`- zx-RuqviibNcI_rPIoWKqw|vmgZdTodF9-c;)vnv{%h#RQxzPzV{JHnmhGERe_lCrx z1Mue``?20bPfGImnp?j3w%*Wz>3+U&Onx0!y_3tWwN=71Z3@!A`+N5395soLisf>m zvLWuW19g=@vI~-H&>DQg?sd+Kj1;uMftX74m|RZQ#BU`&J0J4@U@970oclDPnor?w zWG2y%mjmryf*bCYVb@|G4DU&$VcnOY$|8etLnn2*5Sq8bkJSz@g1d!svfZX6 zx}eXoqc(&Tn@*$iEX&s{EhPS-O}JHi0tyzY$wg}pl+@b5vNVQOX!6;jExmX!umN{i z?qJ2Zni$@?2&=o)WGK)G`T!HDOOF7W-G{Gjaj@30Gx*+y9!Q8bz=sdh?Y>!MP}5$F z4=$}B{pO=~^MjQ%`@0Ob%=iOxwn(BgA>eyQ)ce{lWQM&k;HP44Y&4BT?^VPy zt8`>{Pzmk~%OeLHfxK~ijJ`E*H;{=bmF~R zy?9PD3f6#ksi(dH*BmOssE?Y6pM4RTJp2;1ouPO?c^>-a=fH%|gk8w5n4CxU{&)Uq z4x@F||4i9U65`|jPtA{5f$*GCSV4z*Tbc)-026vjl1vy}P9m}GL?zsCYf?jzG+OKq z33Q8e@b(mOw8W1h1&Jjb?jS4gjF=8`iASU$vCTpP@|+3eGI&TqVr7K{B%cZ7Qej9z z;`%RlkRNYhn*L}m--Q$;PGq`+RDLsno)nKsLE?;`JE(N!OdwYlR0)x XaAg=7-&2x2`L`*=C>de?KXd;A?Yat- literal 0 HcmV?d00001 diff --git a/crazyflie_sim/crazyflie_sim/backend/data/neuralswarm2/rho_S.pth b/crazyflie_sim/crazyflie_sim/backend/data/neuralswarm2/rho_S.pth new file mode 100644 index 0000000000000000000000000000000000000000..2d1bece6e1e0635385121ee1607a6d34be02fdd4 GIT binary patch literal 19383 zcmbTdc{G+^_dhOVo-$@gl#oav(|z_KNs1z=R8m5QBqV8)BqB-3oJb)lr4sII9}-2; zplFsjQ!VgQ6mY{i40Ojq5jLF0>aj= ziCh+KCKVxKXy_#__|{s%Cw&70B1HfGij-668sDgSe=kZ!4EK@~e8$FN(qwDP$(EMp zRu&eMBE-Bz1dD#*>mtNw>xe`}NX&H+axrvKPK=OrQFa-Y7$KD$^cOGbs0bO42wAVc z0{@HLieTTh5pqF-zZ@hQ^l!*!W>)5tEvHO2i;xczcQK5LQ1}Pnj))O1!*)a{{tc!S z6`|}Aq4Lj2&Hf`&)&B}-Hp#}^W{UX~3p0xdwIK1?_F_>HBmX97m>8ih;3*)e@i(Ss zRD_mC#HfD~H2a&N_J2j3Y(2@$+ENg|m1V@}zX|I6lc4Tj1jqahHa03k&m&^oKM9)u z2SNS+3MU|FG0DuzY_gekguy=v8vcvm_`eAn{f#*xD#F+!!sMR>&HpAi@qa-ypJHwq zVfr`0N&h4``7eTIe}kDvMOb)5O!+54i~k^K`QPEJC)-S!VrFG&9bxr1ob_LD!(0S6 z(B^M`wtqwNq9TY#1pJeq#ozqse+8UuZEb08W@ceF#WKQ905~iv!u}tCJ0hn3#n0hy zuxU{djvf)y*KLV#@{$y6nPsa3qJ00#iijEi*iO!dUV>Gjh?!d=X8mL9Mh8T$6=Xz& zi_5UJ|Jag(O%~z0C1Q5azpa=>%-Is*_U|j^5$;^&0kF+@&A;+rvJ#4e{B~h2a&&0Ib(bytQ|iCmhJd}avdLFuFiRK zZlW6vTI&MZhjf{#gB)F5m;t4hO6b~m9W%@I>7}PXv8&I37Ks)TmXeD#cNOXFk#peo z!-dqP*@Vh%{J~AlZ{l7`+Hyuc84%^;NF93}5nNYMzlc4g({mVo7qJf;CCXvs0!v61 zK0xHmSCeF|E;113M&%!5lEyp()E@VN`zv0d?<$?eg1h_I^?${y_CLh?ul#j#Q2H-N z*FVm&zD>K)qD+s8YL1{!d-lQ6&qvw!-AZ`fMw%*pFQhdAlJsbM72dvn0L-tAW|>Os z*pC;DbXkiY{iN&6@Ki2$Kbvvo!aG>lD~4}lfrYoJ;P2?m0qlgrSp@;sBowr!bgEs>~_#{_?X0$5UX})P?#Rlq}>+RX>(3EX#$g~Zb6?@sA2NT$&cx5VE zFAH<$jBfNWk729dSEJav87xPrna+{@O>Rigp?xOorjtaRx?!=vo} z%~kAHmoef;Yqr3qoJm_Jv8D(kJJahIQFoDSW1FxK9)A~!+bgVDjnx)dj0@@c%nwBM zRt~Jl&!de+99gz?AsxMY22DN_LVb_RvR^CDgTj7UhPAJm;g@9mxk>|_ppBgh5@Q8^ zd$3zrh2B~465nk31nM?sRLgScOVn`h)ed2dPIuI(unvO0#bc zr`ametaZ{-oR_|kW^L?Y87;v~;n;QRVKkhHw_YKR-6}Nl(q3AmHN#G+;u_4@e2(6p zYr*zjd52|B?U;x|8_LG7XLU~wkwAxP99bmE8rQAC&~u}i{g(6CS}ViIhb16Ub_G6} zf5vE=YCN~tg|JdRgj%VHvx1E( z%+pzjdW^7UJ;gEXmw?OR>H%DrKb7TvjG!)W)Tl=9NE-Ka8-%Csp<2!__!iR=>FBM` zsQ2a9_$axOU6eV`NR$% zz(=BwF#Du@u^6C+LVSf?pH&A z>s9=9w1s`%7>9l*wnJ*n9Qui?A|0cm_%5p=*}?GXY}<`29KFqg?P|9IgU#{mVz4Ys z4V;C}{beY-L5>FQs|S;aP@J9G$hlsT#%INr?7+&`WDiBqizF;yV-Q-Tab(fN?XW*n zmAx5p8ubpv(Fx+S>0$jxU{bUJ3vxfuw&J<8=4v_%n`4WyC&j60cpPdT-I)*-h%RaDIUViLJn~Y*hRK%G2hJ_r<(CF@==(+(ZBPfv!<+f%)FyCbUML;Pd;wOUgXrTCSxj?qADg;s zJyYHA7z%iqV0`%?cS|LUIV6U$W6p9k%J?+i2uPzglPOqdM4HPZ|pLKFLH70E6dm=V20+nKn( zB~8EONG-oaq44*17=7RuXvikxD!?0vyHf6?qe(rzE9rtpM_LIDfT=! zo|b+r#}`h=Sxf6lrZSKVL0i=5vW}_rRD=+9k{U;=7Z~GP!-;GhdON+LY~*~!>v~Mu~LC{d}+n^Pp5;p zLo$opG?Q(*afzigNisd6PSyO3>307j$TKf{21ky^u!tz?+s zc$A2>@Mvq_0U{cgjHw0-={sehIuq>J79$?!bsMrV3kZ8PSsdm++KCJ5Q~7hHesbRK z``G=kDm*TClD@dtg<JFwLb7-Zf^?zG-toT|J2&y_1KQynINiSxtSOPlY46godS_ z!twzv%Kd4C@}lKTM&uy7F1MD&8i+Nf>Itz7g>m%CJz07rc?%2;%F%heaQf_ODNzj` zfpWbjY{{Fz_OSW(?QGfs;YMAz1?;j_ zJe8U)%VsaFMycQkz^Bzam}A{#Zp5$*yq!3YT~9J0y<%@LWYbheX1mj$K^|N{m?Yl& zqR2ihuIDU|C@}x;2`tftz#ECx@YzCx?RYQ3rU-JP`eVoh`lxTS>Cw@TO0Y~C@J@S&HTog&5P zGg-#3Sc)G8#?s-MZd~^#7a+4Vz^L|J39K8?NZN^d9R(|~I&&@Hb(M_fL}24^A*zS_ZJEfm=DFi}>e zWrUY6T>#DJDyUJ`K;2``b0fYyfFt#$thVCir=Ibk1m9dKlJVL@z> zNd*Lb`VDJSlVMAiEe({9q<{4{6KisR#>of?{dN6c{hihS(BJ*5dv|g$|DXE1|0GuZ z55H&~x%rPCGw689C4mqo^w;%&aWMaH9Ly&DOOkMMF#Z3_VW-+Ax>fZdoLb&Py6#J| z;i@Z{gFyr63I(yz<&#uxA9s4%*_tlGUts?jV+4*pA|_dP(4bCOw!UZx`ql%Vv7(kcx9FpjpO^ zJu!`9Wr1-ld2uGY5VoJLDe0lFj!E0y8yO5qk3{~_f3CP2BKQB+fBu``^}qC=vU{e1 zp{)w-IJS)W?HENR%=5@zdlURDYHu4~S;?a89|L#$8`u8eEgF2_qd1Epr zZXE~rjc>rUDMIwy!Z>u$7>~vKlBs)F8YsP0rt6B1!26JgP}7xw?mxd^0nB7qXNbd5 zD#qT;UByJ^j)dQC*~I;@K4=WviNhr*O8DR4O&ME-Ar-0o+eV47+1(Lc#_z+Q;YXlz zY!WEW)u@^s-%vDAb30_qa+6Jt&%Z6OTXK$Y~BQMi(v~tfRX4_iYlm^kC`_J$!$yLA3K)Fi|R4OZo>@N6J`iKp-a)wZ*l!X4{7wy zc*`yH2}PYB38+`@jaTM0+EzSFg0vecc<7iv`c%&aC4YT165mN`te3IOI60irDn(al z?IhRagy_T*BjIJi4b~ytO7a48plaMqHeFYYdVL(rk`I@0v9Gq{Samztmwkj=5&Q}! zEn5lsUqYcIj)Peedx@v{L9ispFz~t#-8pp%JlqmTENp7w`MKw?qe~LTUrd5Gal7&3 z=4{A%N67{=1Ds+kOS3~PSW5MNa83OL^0!oA>hKaMji14uMP=aTHcxuNI1l?Ki&N#D zGtqbTZr1X;7&Th_v2J!c|H(yFS`cl`;xCs1bM|GoB2^$tVGLdi>LFjRD?=oI33;ZZ zNZ)U|2$$b&2Mf*#$Li<6PbF^*-qQ)=L{+K8QP+mtoP9*E`6%&pnMu`;8H4atInaLg z)OO>7J8=85G5RWa}u7?x`Z4Q&R)#C-h3ewbj~!aXzb#mG&2PC z*%{bS&`x5fET*De65QuT6^LE3p4sd$r02b2>F4lx(7)-)T>DON@5`cye5(SEutWS1 zq(Kd}?~^NvC*au{6F6RUffH421@BrJI`Ug8c3hi`kGLT2m~-yo@2h+kCmn9K?#nqILBVoEdF{R%I={fU#r`*kM2Ir9VHW-aWTt4XUyWkGMI+yyCOe;m zpyH7{<}K-uhn-%7vt1?O&8vq7xApk5?lG$Nr*ca@Hi%q-`%grdhM0z?}mM# zRojgUWnnPI(h+NxXfWeZYMjEV3{qP)6Z4OH!v(cOax(7%dXHHHt%>m@Z@Mn?#4zT4 zBmm2%Zsqd3#Od0KD}0|hzhV9Yd1_c1#N_6xP~DGH@%^SxP#n0EJ^JnocV{$`T@Guw zd$qg3GUE(;E2%_7J58a%>HxQ{KNsG&9fMYhbu3-)3k(K^vo*&RsEM-R|0mN5X6vS5 z$FzHpU77?{#~* zU0pY6e$z8ju~mwuNQ%+E)pp<}X+ysijOKI>Ho&=F9e6FS$*FG+V%v`HgsNV38sck2 zy@sS%*N>+SYQHmyRcR(H8aR!nao-@sJep~Xh0sImSCSJgEtv2olRI`!7iT%Uk#bQB z7LYOzwEX^X@jnvrLRu_L9bJGyj|@3ElLUOari`_Hab;I#X0Ua&Z^2f6H-FY8e` zT;}>n1AAMT&esdbgb#AP%t3P)p;L9)C2lqIGPGeKcGLKZtK%W_i6k6PRG~)V%2fMJ z1iW>~263l{{4w`hQBz%&_8mQEdqN=ro_}ltl4wHLZqeiJ+4k}C21TfRNj2m|s?i-b z!;ox{rupM<@n)GnCy6DVbQ%b;BPc@~FMq_hUMcu{LTW=$hZ8GO+fOQ5(h01VU~exM zgLd{37&EGv?SAtIQX|yZ0qGuYy}?vg;A9E;!>^Ol7rWr@X>};wvO{dV=^eM?|6g*#*U8qj;Vb1d8NK`wto0b?ohwJC`X}e?xNfC3R9!kBW z$9o#~)YjF<1zf}5PtzbL$C@admMrJSs-K^NW2yV3W=Ooh7hdZI+ED#6^!EG7Stf6?HQpjhPl)y)%lU=p zeNyQ!=>oK-#SLx;9ni%OfAT9kTXW zGP&8h+(&I$8d`D%KR*@>#7EC!qsh+H^<;6NqM-gZ$c`! zuYuwhif~pkgX#@6fl$~oNLc6xPmC@>d8v1og4B3|sU`k6m*8%;%p_1c_j6 zYB?ZEfA=K8z_V0-IQtFJQxEZ#bFy&9%Q{dBJBBSYZ$V#`1T`3tqF3?~!QHS7)|?Wi zsple~d0G(|-rNR~$)8EzE#Td|JsJw0^kHr0)H*6!Fn@_PT^H;+4?jCfo+{UeyKgKH5yFhqvi|vtiS-Nzn0)*5) zz>4-Qa62#_#;l)94Bqu{r$Z~r?Il4NKAvKow+yv^b`R!$+JRGi5-|4LMSAW;D%2hO z2)sTe8go0^) z8#UQ!@4e(tstU{KzsO}d9Od*EiPOb*g=lVu7%jdl%=0ka3j@{%AWL=?=ALW=nM1me z{Y)Lr!YYWE&0{cqtO~y0>QMY!0w_fPf~NinbjZViDj)8E<|~t+rLqP@L7IBL2>~Yw z5f(ne4(iezu=uGV`5HKxUBCzYV$;1ixaJ*9S)~PMq;kQqdmd)Z>9$SkNkEH-AHiQt zm|Y9gM{%8U`15=u_r%c=w@Jt|v%AA^h8&Mw-zv*$IQoThPH>2w(eZv9s;k#6!fJt?E2X6t(rZ zqI=)DzRc6yA>j^`o_vo}+bi&$=X}Q|nuLe*&T{unvf-n34jJ-@gllK>$%iqsG0h~6 z+cT6v6-Qkg!{f_UpF62GqpDyw7O3))?m6zT?Qc`w-Vt0mAzwVXV9+ytu1~3c}Cn{Y?r~ z-&%oA82c0CUn$XmeT^VjwFj=8Mf_5g#=U>~fwTTtL&wFNVMo^(rd=UM&HNI$`>V$~$cha~Pm7uui9jtjFPeM$ZxJ9?8z`|jp8A?PUb`EFJ zW*adqb}>sj)(=7H+SFAjg&Y3o71(av%ld@Ya$`o`2cKIMQ##c-GSJ7(_v2x&gAQn@ zIgtZDvavq=2}B3GveiFtf|T4i)_43G*J8aEyXLJW*VL8~!>huy>-jBsDd_WRAAbPr zzB^pyt9U3KDTgbL29n6(LbR!IfV>QDBVRut+*W=9n&V!8#YZ*zb)~MLcRK+gFYI8T zWG@=D1@Q-_W|B=>F}UE17(TF$$4jgTpM|NRlhP`3H+8qb8JUghk&-y(-Fw^TGj$+M zt`=R@=W$|3O0YS73;C0GjKntebHz{oa5fGlXq9^seM4rGF}Vtmc4`z9b|>Qkn+M#A z4`rlO?J8F^QiZ>9Y$}NMA0q)Doh7sdcuPJ)SI)i`F$2k83j4hK&*p!sHJSl?Go9yo|Ie%WWRu5Q8H zUTvx{`6;d}D&>ApHX*H{hSaCyGOT|h@U@CWsm^OzDrP7{UsRvP$BQ&U)Z{SVyXqAj zXn8>T#}1=&OFqL&-9ku@m!{g~7eKi69eC`y0d0xd5dT_^9?L%uAtTaY)V_HBwUF!3 zedz?+KN-cv{7$9~Mjvs`nLSY9ITgPxdfP}E85#uiX$%8Rd|5(SGHN&S-$5E`i0aB-RLiQ+G zs->r zVJjA4^nFSGq%&4*)(jrbkY7IMz@%QT0+>$+tQ!T`U$Ge<*Jq&@nGUwG zrF@6h(VWqN9_~cwcuseu0b2V=(3a5$z|XuF#5x7~-*GX1Cx0?sRhx@;2RU+n!XXU3 z8qPG$X7J9q>NZ?D+r^zxsR!lTK1@$!$fjx69Cp5G6y`5ALc{gmBzk%wPaR#N4(`kJfD%DuSZdzj4#l;NQ&(7k)iYbavOF)Dk(p2 zK*JuZQmMBgud2H6UZ|BX0ThV@!K@ zFf>=&5@VH*ETVfD&Htvw9JdLv#Pf&H{lR12lbneV`F;n~R@y;Xh(k&BB>CeaAT;^Pw4w7mgQ`*!J6I}I#Ko;+|~b#2OS+DU*8jtq`SbL6nXrz zUJYDOi^-%eAeknCt(9@;i@gUs}8^cz9)?09midtH0t!|9 zNn?8|SSLBiz=RBdGU6 zZ{~8X3U$)Qv1{g5u;~0HQh7BJ*6rPnGw-zNzkG<8mU+|)I~}`V(=-*6*8f>(?nR=3V9UG zXoueHjW{i;8|Epj=G`0{#?J8bx$cM^ATfIaZZ_WtnjT|V)ml4H_`Zp0F?*P#696WM zQXy=x0y^$g5Z4rOS|#u4*0SceC zqh2D${0pTTbWzx4P+sc{EA4dXX%~BF?l=L_N4-$(qdYTQY{2ASy5i`RQK&lpEqVn_ z!2Dl*WYJc28n|jEUV75Xts|c}V_y+=9%SfY*AvjHe4W$kPJqS2r}0l-I81%H4M&zF zvN6|_S<{wMX1=G2X}tFUg|nU93O7^q$=%92ieK0kRaBt2Qv+7I9zZq8S#(m0Jw!$U zdRXs-+_uS3lBI_~1^wmcbZ>a9F_&e`iiBX-z5K!(@lf_Gom?9c#pb?Kp!p9Haq?MD zra#7pyCt8=Y1=<#OV)3I1v|zupZZ(m=@Mh+n()2h$)a}R_GJW}o8-plyQC85Zz8l{ z^dERRCILh{c3}N&pBpy!@{T8a5zncx_T7we-7+|%!$J(H*z&h($J=>cmIZp z7&&_A^;iDzC7bb^?F=lM77G)8mZQSk&G_ASFKkqbBSL;3QMtw#gl1NONx?R>wfDg1 zm;ErMWD`d6S7ED%6_;~2jy!*p$4%G}26euw+$R6u+_ENbtaMDl^Io}dbK?ynn$X1k z+~xtY@_7)k^f*s2@PR5l2Y3s*_F%K=e)O9>2Bc@2Vdui-=vjP^dmL)RmE|qOvr_zj zcu(j2GV6rY1;&%$`oFxV|L%YN+q~}oqyKej`XR1W-j7+g-QdrvutkY@38wre9b`0C z;{$;%qg)rv`qFQp(1@vQY~E;obzuqy-OYl$jJY`T%{Wk&&mNIMXR9&TnfJ7+*u<$E;yo{PzC)7k2|qp@f^FkY`< z-ZL%-Wi%p5YKjqDA(~uV(*~Z*r!nO0q8;Rcwm@f^x{v$0`2Ze$n$8cJUJQft_;|6f z7;fI*!B;Mv#0DFFb8!jhv2KkBQ(BP*qxBw>(XW#+ecT27Htq_MoT&`Oi`HSdniMSA zcNJ$ge<#wMC_UFR1%geIu~;hu%Xcq97abKAVx?iz=O)@K=3|V?JM{dz z6Mjwn%-Ow4!JRX@IhD<^+#V}K{`X2l*z9=$17GBjD4}95gJ{AM@A2SYQ-eW=!eEVk zCcZR`!vzP=lDMshvHQ6ZjFLLb^(<-T<=;C5S&kQM#tvDLScwkq{((BM_%4le|Ln#P z``r+E{w^1kJwV#e{^U;E@Ci??nIs%|$)#OoPzdc@VrMuOuBj*cU;06j_A~rgv;hJh zIiid~8ti}dib#jQ~t@A>dvat)r(*a#j!k6=8@1Mz5vmN!p9H+owk z)7L!9z5?#9c{tp(FTl~s+Fba&eE3kV2(vS#fb+c!W;e?5%FKT5_u65&GPeU0=h#xy zAJK4aoGhAHCV+}n5>zV>XHV;=(uiv^P+uU%-S}7pPl7@z=cGYr&GDrB4{A~G<724* zv}Ujw`w%`4dO_suDzNdWgJJU@!jJC`bXY|mi7q$@W_@olc8RROyH9{Q&Wp*L#qv~k znHIe9-G;{NLdXg)5qfUfZF0*g7?!8UVSk7*wVODBx?Y|{4{z-wLs=#KiMvk0{474? z(L(f^`I>ipYdm^Nlt8xpJ@gWA{;AuARR;%o9RY91)=w$0c)1c@A?Go3ZaH}O*rWf~ zdhWKpK62w?aOFwMO42=XQE!OxS@`1fBxym}%8>dv9}eq4kW)p1;1fFnI#nn{H7jZk)$ z1NCfQ1vesh)0R(eprP>v+#mhKyj#|^USBsJ}nl<6j;-M8CrB{(HeSYVga{P z_bS+YA3&4h#c=-0b~rMp9V!mk(0yS`VDMKjd?5nupr{NI>RvL0(apxh-Nt;VumKxG(F)4^#Gl{yt z98Uu`*}%tb_Mly@O#jS10x|wl)MaWCob=y{U&bDUu25fyU*}90&ELUQWx0UT_U(AI zH6Au^nFLDP2Wn`|+hQH!Mu`wl{- z+HO+S6$6(HIJ~3thm(PWc&I5I&E;?7RNJwrlh_TjRI5O&z7l6{x({yUMerEYxP{@Iy_vwI2S`Z%VVHW!7u@sW@Z_Ke8R!&vP+=qK(3|rxTk{y2C5z$8omrr} z*A8tb7=SI9gID`&JU;FKoK{Ol&zM}&ImZBd_V2^a%Mwr+s)-9yTzS(Q_MpzaCHN|! z0o9IVbJm&`7`9+9v54M-3mQJ*NB!Ie)l1z1jcFA0H2@ZM*g}osQuuZ(3DzoS%GunN>iHe_h8!vBmtm_3q$)_#xifSVq{gMZEh~ zwGB!BT3ns!J}`N=2b_eiV#@MzEaN}5bz0bfO}p~=6LT#%iQHVg>94{2yi^e{Qa;Wb zc7%k*JCbZ?6VP6s3A$^G;d`Dxru{yRVru(9CQllKQk8L()^_-woJ5ulFUc5G^v`m_-``OH2nXE={T6M$A4rv^(BT5&k$H2w!U!f%L zC0N;>L8&-P8gpV49Tc2<2RA0c%FSl1q^<}T$B)57Z42SH!cS1N74-c3tFY#=I=kBG z%2o~IF|+!6?9br@+qp}Ju@$AdO!D1RT-%z)|2^s@&Kpd`hmjZXD^C}t1m0qoUmd5H zsEEg({NM^7&!DGO3gLm15=6b)K-S*>O*VOKXU~$hq31U_+I)Qx@ zZ6^h7ld8CtV~4T3@f3#d*I{-2b#T7*Bw3m#N@bSM#z_l&sV1C2g`fMe-{}$9Zas>d zFRGI3Zr?Z|_fD>|;Q`KD|BHl*tl`|^oDsu^V=^vh29YDE_*om2?s8|Xu3k)Op(1;} zGX^9Im*FAyg)H4Jid7m8%Blf%|UK>GK_k&7?%Co#i>2t07nh7LG-RM-G9FXRy*E?mE+V|Y@a|E z2v)+=Rf6Zlk@2+INP=ju)Q03Kp`e-NPCZ_3hwBzP^sDSv(4JHTJ`4LnGe8w~KA6YV zJmd3U9`|S04`)M!{cq$Mr{mZkgRnp$i+nnHnm>7O5!3zE$h#T%6HjYxBMwL6arlTi z@cODU_+GT-DpA9>zUnloSklj351q=E2QJ2QgTiElqBVG@$K&!}R^S#8#yVcSB@g>| zv(Il-@qX8AHs3IxymkAD52SD6yUF|6x>Z%^F**g>We($)KS@~p>H#(fZ2-RQIq;S{ zOWgDx*q%I@f(bO0$Q}3uQOi~M`j>^#x2F!R&$W?93**Tb^(B}itwz$SmO-*$hA3I~ zC_J4kj^FR6Hyldci{BD9L14i?_|~opdyU$#wpait2l0X!xOxoCd=jB z70d-??}0YWGNQ5jFx=Rg4s8aEGnQxt{{^E-(3}K(E9%p*ad`}yI1Gbx7tFBwcQt;v zF^Ybly&w4Zj^lwT0rYyOCG1Yuq}$df!3}qLDsjIDKxRIzygi@p-XKG_g|vdGeggO{ zy8`BgN5Fr`k%n7Op+VOuJ+OWyY_Kt*4=l~tk&oJf9_Rvw=Niy2>P~P~%$m$OPvE*h zZxlFRU~)47xFxT_vxMXBHS5qHnu6K-hr+bwO$vUnk^!m7wOp#)MTpsKgx@+=gSKGi zVA*dqBI=xvi^r|ua&}CHU8@UFHSh<maY>|Kpw%qzzQ#Sd z){8&wM48lsMsB_7LTC;f!np1@%pWf}ms>jUN(94hm2OOs?Z#If!%%rStczsnd-JS@U&k&9S)u@ULlDx%O_i$kxkV9daL5?{27 zWZZQ^E7c&5u5`uTU|&3x=tFY1+hE1fCD`y&nlsitgZ%~lL|MxTEoY7AH04gh@s}E) zolwdxzH}C4j2z%@#~bcj?kuo&en+GteL-~8CDboE2Ue9743(s?^0gX1llaPMcmCkl z9$3$XTU-Zci=*(qPvDv5no^sf0KCyq0JARKgF*L)T%g@#Ca$YMjZeOVJ5?PJws$7@ z6q!-8D1AC0wjKPR|ALq2X3)(}n)I&1M&PwakVczMF11sOE)h|p%c^bZVwpTHaI7Us zd!K^q1@m+<83{atx(PJ)cL$7k^B5Lv7~%$1^ys2zI@EUON_u{;G!!ePLSvLQ{gSwm zF23wa6B9nd(1*h~>Psmar>=p%q(sn(Q-KUYP0TdpA-riccs+PSt_)goo%0V6kM$SH zJ)xs093+Y9A@fmOuM$Mxjf2XsF_SdlW8`_!%iJpnU8)O8J(o$!Pc zk1m3BU^geE+<`t%=40BMo8;klQQT*BR-jeRB4Kd=?Yn&;Y`Y<+;oJ&mdk}}IB{V!= z(#u5(Y@TQBa@gBFmb`V*hl;vqIB~8i=efp?lX8dyqo2pPC>NsAzQa6)X=k_> zgOxAf!aa zxuEuT0}9#2HIM_DaIO9@8YBz{dAAYV&o8wYo_2xIwb>BWF-T%9+u+)m>zI(xik&xh zVW_}AuS#r37NLQj&y4Wy{y@wvDdA=|aiG`biT9`Jfp&cnC-I>UpA-*~qj{P5`k^oE zSyhNVlMAq0{R&4iV|hn^tb*>Y8= zCtx9omfuhAsBA~u(SF!}^dLX+z-jy#6@VYV?Ztp>foFHXjx!H@%ylTJl6)yo{K(Tm z#dU{C)@~j2y_s9ufdA0@y%mk5k)^h8^w8qnJti5}B)(Ec~a&9T?RM%z;`Y{@FY z8xR^W=RLtikBV^2*>hafMG`;BL~@+5?EDd=_MG9IiFPV*XK-7;45j!#ud?%K_XWiyBBsyNL$-+IS(FC$aFO5FT4l1AdUi4oEC! zk*l7Nk?pHd?3p)4%V*I3dlgK0t1tE*+r!#Y-$U_?$;|N4YOLRPjLB@Vfjf&uSp5ls zcPw!ldcXVgbY5M?wZDcqlX0a)J^dCu8CQm5;@7~DF;AgRR+$z(cVTUth3T9Xt6+=c zN%(rrii+);4~9S0=_sSs5OYM2vViNbylev;KQBppr+HH@LV_gkGN2PLwt%cuH}ops zgwBzV$cw^wT)B5T9FNY!QG)lRxXZS5pkxb-e0##yWV9Cj=+_3kU3zr$V*{!-N}xx7 z8%GcBno7^6FQe{~<>bBdR?gSGg4=kn6NA((;A<%(85*kOT8k%iZmY$J;IkxswOOFT|_D~Q!cFh-{akAI&EKC;r_FntBe{0YIgUE3hD*N1y>@gNC#UyciBT!Z7fI?!2n zg3Q&K#9uty4&PKA1!?DMbots0KI#{+N=uk`qjMjLZnXrVe0|Ix{)jV}q=2)!Pm%j+ z*PuA|9;cyHjakMWg6EScZ+(0TD%^8G+tf0`CEDWqeKEGK+oM6kqYUkXJ`-E%TU@`_ zO1fI80mkbmbNoZ6A*aNGitlt{Wz*NvFB*Jd0Ny#mEUhl#|R zDfF_{23V>)k@`P(rorbDfL$9$M)dE6GDQXn{q1C0?qr%)`<)AlmZuLz1i2s=4&_H{ zz}H9>bi1E{aOfzy3uaLF@eb7g@BnlNHezyVC#ZG?gKr^1ifRw84lt$tzgFW(RT2DQ zdKgBFX;NqLFF3iwnO+edLpLv;1HBUs=-TZ*H0DSnJeVr*`XARo$Hf}Z>3zl3pFIs@ zn#3tAQAJyc1hTE{8d2OAN1cL=aYKwW?UOmf9hp55n%zy|mCy)!TSAEwsagqN{Wa0h zMxDM`mjmwy+To;|7JX@Q3vWJ(f~ylE=@pw5@K{ZWa(A78x9~ZX8s34u^7=45O`fj5 zH=B*toI>Z7Po`$$bNB|PQj|LUhJdpZfW#e(^_ijD|mm@#+056*#TA;M5u%KR(e`o0;h?2(_6{5 zbZpNqy5hYAJzWL#OZj&USXu-zO>Jm-{5zR?>pAR{{0(tZhv3w^gP^+XGMuf8qbt9^ zf}W)%&?uOfoNSmx|MX9zX7QmgD{mF9I@ChaIy+&5u{F~=vH>q^uB2`kl)!%8Gu|1y zqol0O4kSX_VdK*={H}F(!Es3OoFSXEFQfK3v(biWxPeV!)mOs2kx1hpS6yquqOS^A`vUHYu!3?>z37 zt!1K0Wqk7)wOIXnJiGElh*<^iB%^k0 z)QXZV8y1*AvAlC@wz;5Ix*>6kR>MH|BZ5oVMk@TF_f1ycd&4Zz`*PoX$-C#1m%MZT zx%Yg(Ww1e?O*hXe<@l7hal88g_;~&>#N{`EZ{1<)DD&ZT;)ldqoAOW84?ZAE&am+j%E&ZWBIY&=7pbZS1p#9A$HTTstGIren=jz7oH5LrcY zA(He4j^Nqb^P!?^8Xf6{I9PU#)o$HEHu{^`UNr~bcRmWWnYDPa-Ga7;H=t+#QxMbo z6%K4HgtpQ9z!o2gN4EzFKe8I8S?&H@QxUGLZ%5D4v!pIB1G$=boYE!G^7Re8t#U1H zGp4h=FCnj=se%;y2}rO9iQ(1tP`R}lR%t&XY2B>Wz2z#}e%6wKfjXjc2VgS!6|kGv zVf~UWI23pjUEWVUlY6Z=s3?WX^OShU?uK99JpfZJ{rF6x5hh-!0|(a&<%0p<*}0PJ zGfeT8g>Qkepb;$d`f+%#AJg)b7=G#)Tr58duJL;@`Q$r&L#*b|Ytdq6p%Q&VyU>3E zKz+V|EZ=gFkBaYuV9Vzim(~n+oe`s7E5(`@^Lbjk6$JfJ+q7fF|2lsW+)e)D`OE!l z+|c0p0Uog#XxUXLeDaX2}8(}NbGi^5nf1|+@VMwE%pw%Qxf?F zb59XR%luK~Ah8LD6x6{qV>g3B#v^i&SnVbQMa%{YIe5rHV#%5mv@>QlP)I5#2Z{Av zQc$e+W{^nlCI^WRGNqv8*x5iKHzYYoydtHbo%&fpH(ZP4AaUwSL7L_N3KEvH93;-r zXh|L=XZ{14$@?s`N|iJ-Nf*w(c%}(XSVFro9>1RG3PmGB2#v)FwpR+PS-2|{VXSAF PBUHk(nq9*Dzvuo1`MbaF literal 0 HcmV?d00001 diff --git a/crazyflie_sim/crazyflie_sim/backend/neuralswarm.py b/crazyflie_sim/crazyflie_sim/backend/neuralswarm.py new file mode 100644 index 000000000..d3bea12d6 --- /dev/null +++ b/crazyflie_sim/crazyflie_sim/backend/neuralswarm.py @@ -0,0 +1,170 @@ +""" +This implementes interaction force prediction using NeuralSwarm(2). + +See https://github.com/aerorobotics/neural-swarm + +Logic copied from https://github.com/aerorobotics/neural-swarm/blob/master/planning/robots.py +""" + +from pathlib import Path + +import numpy as np +from rclpy.node import Node +from rclpy.time import Time +from rosgraph_msgs.msg import Clock +import torch +import torch.nn as nn +import torch.nn.functional as F + +from .np import Quadrotor +from ..sim_data_types import Action, State + + +# H is the dimension of the hidden state +class phi_Net(nn.Module): + + def __init__(self, inputdim=6, hiddendim=40): + super(phi_Net, self).__init__() + self.fc1 = nn.Linear(inputdim, 25) + self.fc2 = nn.Linear(25, 40) + self.fc3 = nn.Linear(40, 40) + self.fc4 = nn.Linear(40, hiddendim) + + def forward(self, x): + x = F.relu(self.fc1(x)) + x = F.relu(self.fc2(x)) + x = F.relu(self.fc3(x)) + x = self.fc4(x) + return x + + +class rho_Net(nn.Module): + + def __init__(self, hiddendim=40): + super(rho_Net, self).__init__() + self.fc1 = nn.Linear(hiddendim, 40) + self.fc2 = nn.Linear(40, 40) + self.fc3 = nn.Linear(40, 40) + self.fc4 = nn.Linear(40, 1) + + def forward(self, x): + x = F.relu(self.fc1(x)) + x = F.relu(self.fc2(x)) + x = F.relu(self.fc3(x)) + x = self.fc4(x) + return x + + +class NeuralSwarm: + + def __init__(self, model_folder): + self.H = 20 + self.rho_L_net = rho_Net(hiddendim=self.H) + self.phi_L_net = phi_Net(inputdim=6, hiddendim=self.H) # x,y,z,vx,vy,vz + self.rho_L_net.load_state_dict(torch.load('{}/rho_L.pth'.format(model_folder))) + self.phi_L_net.load_state_dict(torch.load('{}/phi_L.pth'.format(model_folder))) + self.rho_S_net = rho_Net(hiddendim=self.H) + self.phi_S_net = phi_Net(inputdim=6, hiddendim=self.H) # x,y,z,vx,vy,vz + self.rho_S_net.load_state_dict(torch.load('{}/rho_S.pth'.format(model_folder))) + self.phi_S_net.load_state_dict(torch.load('{}/phi_S.pth'.format(model_folder))) + self.phi_G_net = phi_Net(inputdim=4, hiddendim=self.H) # z,vx,vy,vz + self.phi_G_net.load_state_dict(torch.load('{}/phi_G.pth'.format(model_folder))) + + def compute_Fa(self, data_self, data_neighbors): + rho_input = torch.zeros(self.H) + cftype, x = data_self + for cftype_neighbor, x_neighbor in data_neighbors: + x_12 = torch.zeros(6) + x_12 = (x_neighbor - x).float() + if abs(x_12[0]) < 0.2 and abs(x_12[1]) < 0.2 and abs(x_12[3]) < 1.5: + if cftype_neighbor == 'small' or cftype_neighbor == 'small_powerful_motors': + rho_input += self.phi_S_net(x_12) + elif cftype_neighbor == 'large': + rho_input += self.phi_L_net(x_12) + else: + raise Exception('Unknown cftype!') + + # interaction with the ground + x_12 = torch.zeros(4) + x_12[0] = 0 - x[2] + x_12[1:4] = -x[3:6] + rho_input += self.phi_G_net(x_12) + + if cftype == 'small' or cftype == 'small_powerful_motors': + faz = self.rho_S_net(rho_input) + elif cftype == 'large': + faz = self.rho_L_net(rho_input) + else: + raise Exception('Unknown cftype!') + + return np.array([0, 0, faz[0].item()]) + + +class Backend: + """Backend that is based on the one defined in np.py.""" + + def __init__(self, node: Node, names: list[str], states: list[State]): + self.node = node + self.names = names + self.clock_publisher = node.create_publisher(Clock, 'clock', 10) + self.t = 0 + self.dt = 0.0005 + + self.uavs = [] + for state in states: + uav = Quadrotor(state) + self.uavs.append(uav) + self.neuralswarm = NeuralSwarm(Path(__file__).parent / 'data/neuralswarm2') + + def time(self) -> float: + return self.t + + def step(self, states_desired: list[State], actions: list[Action]) -> list[State]: + # advance the time + self.t += self.dt + + fa_data = [] + for uav in self.uavs: + fa_data.append(('small', torch.hstack( + (torch.tensor(uav.state.pos), torch.tensor(uav.state.vel))))) + + next_states = [] + for k, (uav, action) in enumerate(zip(self.uavs, actions)): + # estimate F_a + # print(k, fa_data[k], fa_data[0:k] + fa_data[k+1:]) + f_a = self.neuralswarm.compute_Fa(fa_data[k], fa_data[0:k] + fa_data[k+1:]) + # convert grams to Newtons + f_a = f_a / 1000 * 9.81 + # print(f_a) + uav.step(action, self.dt, f_a) + next_states.append(uav.state) + + # print(states_desired, actions, next_states) + # publish the current clock + clock_message = Clock() + clock_message.clock = Time(seconds=self.time()).to_msg() + self.clock_publisher.publish(clock_message) + + return next_states + + def shutdown(self): + pass + + +if __name__ == '__main__': + + # test case, see Fig 5g in NeuralSwarm2 paper + ns = NeuralSwarm(Path(__file__).parent / 'data/neuralswarm2') + + # x, y, z, vx, vy, vz + states = torch.tensor([ + [0, 0, 0.6, 0, 0, 0], + [0, -0.1, 0.5, 0, 0, 0], + [0, 0.1, 0.5, 0, 0, 0], + [0, 0, 0.3, 0, 0, 0], + ]) + + print(ns.compute_Fa(('small', states[3]), + [('small', states[0]), + ('small', states[1]), + ('small', states[2])])) diff --git a/crazyflie_sim/crazyflie_sim/backend/np.py b/crazyflie_sim/crazyflie_sim/backend/np.py index 92d35528c..fa3b6c2ef 100644 --- a/crazyflie_sim/crazyflie_sim/backend/np.py +++ b/crazyflie_sim/crazyflie_sim/backend/np.py @@ -81,7 +81,7 @@ def __init__(self, state): self.state = state - def step(self, action, dt): + def step(self, action, dt, f_a=np.zeros(3)): # convert RPM -> Force def rpm_to_force(rpm): @@ -101,10 +101,10 @@ def rpm_to_force(rpm): # dynamics # dot{p} = v pos_next = self.state.pos + self.state.vel * dt - # mv = mg + R f_u + # mv = mg + R f_u + f_a vel_next = self.state.vel + ( np.array([0, 0, -self.g]) + - rowan.rotate(self.state.quat, f_u) / self.mass) * dt + (rowan.rotate(self.state.quat, f_u) + f_a) / self.mass) * dt # dot{R} = R S(w) # to integrate the dynamics, see From 2fcdacf91c8a904ee85e4a30ff548375b952e733 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Wed, 10 Jan 2024 13:49:20 +0100 Subject: [PATCH 058/162] sim - visualization - rviz: use sim time Uses the simulation time rather than wall clock time for the published tf. Fixes #401. --- crazyflie_sim/crazyflie_sim/visualization/rviz.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/crazyflie_sim/crazyflie_sim/visualization/rviz.py b/crazyflie_sim/crazyflie_sim/visualization/rviz.py index c1ed92687..154144451 100644 --- a/crazyflie_sim/crazyflie_sim/visualization/rviz.py +++ b/crazyflie_sim/crazyflie_sim/visualization/rviz.py @@ -1,5 +1,7 @@ from __future__ import annotations +import math + from geometry_msgs.msg import TransformStamped from rclpy.node import Node from tf2_ros import TransformBroadcaster @@ -20,7 +22,8 @@ def step(self, t, states: list[State], states_desired: list[State], actions: lis msgs = [] for name, state in zip(self.names, states): msg = TransformStamped() - msg.header.stamp = self.node.get_clock().now().to_msg() + msg.header.stamp.sec = math.floor(t) + msg.header.stamp.nanosec = int((t - msg.header.stamp.sec) * 1e9) msg.header.frame_id = 'world' msg.child_frame_id = name msg.transform.translation.x = state.pos[0] From d71ee98ad6306dd6a9bd8da4c2aad38235618354 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Mon, 15 Jan 2024 14:58:39 +0100 Subject: [PATCH 059/162] crazyflie_server (cpp): add more connection statistics * Adds new types and topics to publish connection statistics for each connection * Adds a new warning if ack rate (for unicast) is low --- crazyflie/config/server.yaml | 2 + crazyflie/deps/crazyflie_tools | 2 +- crazyflie/src/crazyflie_server.cpp | 69 ++++++++++++++++++- crazyflie_interfaces/CMakeLists.txt | 2 + .../msg/ConnectionStatistics.msg | 6 ++ .../msg/ConnectionStatisticsArray.msg | 2 + 6 files changed, 79 insertions(+), 4 deletions(-) create mode 100644 crazyflie_interfaces/msg/ConnectionStatistics.msg create mode 100644 crazyflie_interfaces/msg/ConnectionStatisticsArray.msg diff --git a/crazyflie/config/server.yaml b/crazyflie/config/server.yaml index e0d8d6af6..6ec8a3989 100644 --- a/crazyflie/config/server.yaml +++ b/crazyflie/config/server.yaml @@ -6,6 +6,8 @@ warning_if_rate_outside: [80.0, 120.0] communication: max_unicast_latency: 10.0 # ms + min_unicast_ack_rate: 0.9 + publish_stats: false firmware_params: query_all_values_on_connect: False # simulation related diff --git a/crazyflie/deps/crazyflie_tools b/crazyflie/deps/crazyflie_tools index fbd1f7306..8cf7ee6b0 160000 --- a/crazyflie/deps/crazyflie_tools +++ b/crazyflie/deps/crazyflie_tools @@ -1 +1 @@ -Subproject commit fbd1f730636f01632b3b99abd0fb2a0789a2d221 +Subproject commit 8cf7ee6b0e91b78e428e167914c7a9a267e11ac2 diff --git a/crazyflie/src/crazyflie_server.cpp b/crazyflie/src/crazyflie_server.cpp index a76fdfc80..c49ac63c4 100644 --- a/crazyflie/src/crazyflie_server.cpp +++ b/crazyflie/src/crazyflie_server.cpp @@ -21,6 +21,7 @@ #include "crazyflie_interfaces/msg/full_state.hpp" #include "crazyflie_interfaces/msg/position.hpp" #include "crazyflie_interfaces/msg/log_data_generic.hpp" +#include "crazyflie_interfaces/msg/connection_statistics_array.hpp" using std::placeholders::_1; using std::placeholders::_2; @@ -151,6 +152,11 @@ class CrazyflieROS // link statistics warning_freq_ = node->get_parameter("warnings.frequency").get_parameter_value().get(); max_latency_ = node->get_parameter("warnings.communication.max_unicast_latency").get_parameter_value().get(); + min_ack_rate_ = node->get_parameter("warnings.communication.min_unicast_ack_rate").get_parameter_value().get(); + publish_stats_ = node->get_parameter("warnings.communication.publish_stats").get_parameter_value().get(); + if (publish_stats_) { + publisher_connection_stats_ = node->create_publisher(name + "/connection_statistics", 10); + } if (warning_freq_ >= 0.0) { cf_.setLatencyCallback(std::bind(&CrazyflieROS::on_latency, this, std::placeholders::_1)); @@ -706,12 +712,34 @@ class CrazyflieROS if (elapsed.count() > 1.0 / warning_freq_) { RCLCPP_WARN(logger_, "last latency update: %f s", elapsed.count()); } + + auto stats = cf_.connectionStatsDelta(); + float ack_rate = stats.sent_count / stats.ack_count; + if (ack_rate < min_ack_rate_) { + RCLCPP_WARN(logger_, "Ack rate: %.1f %%", ack_rate * 100); + } + + if (publish_stats_) { + crazyflie_interfaces::msg::ConnectionStatisticsArray msg; + msg.header.stamp = node_->get_clock()->now(); + msg.header.frame_id = "world"; + msg.stats.resize(1); + + msg.stats[0].uri = cf_.uri(); + msg.stats[0].sent_count = stats.sent_count; + msg.stats[0].sent_ping_count = stats.sent_ping_count; + msg.stats[0].receive_count = stats.receive_count; + msg.stats[0].enqueued_count = stats.enqueued_count; + msg.stats[0].ack_count = stats.ack_count; + + publisher_connection_stats_->publish(msg); + } } void on_latency(uint64_t latency_in_us) { if (latency_in_us / 1000.0 > max_latency_) { - RCLCPP_WARN(logger_, "Latency: %f ms", latency_in_us / 1000.0); + RCLCPP_WARN(logger_, "Latency: %.1f ms", latency_in_us / 1000.0); } last_on_latency_ = std::chrono::steady_clock::now(); } @@ -758,7 +786,9 @@ class CrazyflieROS std::chrono::time_point last_on_latency_; float warning_freq_; float max_latency_; - + float min_ack_rate_; + bool publish_stats_; + rclcpp::Publisher::SharedPtr publisher_connection_stats_; }; class CrazyflieServer : public rclcpp::Node @@ -822,6 +852,13 @@ class CrazyflieServer : public rclcpp::Node mocap_max_rate_ = rate_range[1]; this->declare_parameter("warnings.communication.max_unicast_latency", 10.0); + this->declare_parameter("warnings.communication.min_unicast_ack_rate", 0.9); + this->declare_parameter("warnings.communication.publish_stats", false); + + publish_stats_ = this->get_parameter("warnings.communication.publish_stats").get_parameter_value().get(); + if (publish_stats_) { + publisher_connection_stats_ = this->create_publisher("all/connection_statistics", 10); + } // load crazyflies from params auto node_parameters_iface = this->get_node_parameters_interface(); @@ -1160,7 +1197,7 @@ class CrazyflieServer : public rclcpp::Node mean_rate /= (mocap_data_received_timepoints_.size() - 1); if (num_rates_wrong > 0) { - RCLCPP_WARN(logger_, "Motion capture rate off (#: %d, Avg: %f)", num_rates_wrong, mean_rate); + RCLCPP_WARN(logger_, "Motion capture rate off (#: %d, Avg: %.1f)", num_rates_wrong, mean_rate); } } else if (mocap_enabled_) { // b) warn if no data was received @@ -1168,6 +1205,30 @@ class CrazyflieServer : public rclcpp::Node } mocap_data_received_timepoints_.clear(); + + if (publish_stats_) { + + crazyflie_interfaces::msg::ConnectionStatisticsArray msg; + msg.header.stamp = this->get_clock()->now(); + msg.header.frame_id = "world"; + msg.stats.resize(broadcaster_.size()); + + size_t i = 0; + for (auto &bc : broadcaster_) { + auto &cfbc = bc.second; + + auto stats = cfbc->connectionStatsDelta(); + + msg.stats[i].uri = cfbc->uri(); + msg.stats[i].sent_count = stats.sent_count; + msg.stats[i].sent_ping_count = stats.sent_ping_count; + msg.stats[i].receive_count = stats.receive_count; + msg.stats[i].enqueued_count = stats.enqueued_count; + msg.stats[i].ack_count = stats.ack_count; + ++i; + } + publisher_connection_stats_->publish(msg); + } } template @@ -1232,6 +1293,8 @@ class CrazyflieServer : public rclcpp::Node float mocap_min_rate_; float mocap_max_rate_; std::vector> mocap_data_received_timepoints_; + bool publish_stats_; + rclcpp::Publisher::SharedPtr publisher_connection_stats_; // multithreading rclcpp::CallbackGroup::SharedPtr callback_group_mocap_; diff --git a/crazyflie_interfaces/CMakeLists.txt b/crazyflie_interfaces/CMakeLists.txt index f5b8b6cc7..583e95fa1 100644 --- a/crazyflie_interfaces/CMakeLists.txt +++ b/crazyflie_interfaces/CMakeLists.txt @@ -18,6 +18,8 @@ find_package(std_msgs REQUIRED) find_package(rosidl_default_generators REQUIRED) rosidl_generate_interfaces(${PROJECT_NAME} + "msg/ConnectionStatistics.msg" + "msg/ConnectionStatisticsArray.msg" "msg/FullState.msg" "msg/LogDataGeneric.msg" "msg/Hover.msg" diff --git a/crazyflie_interfaces/msg/ConnectionStatistics.msg b/crazyflie_interfaces/msg/ConnectionStatistics.msg new file mode 100644 index 000000000..a28d08c1b --- /dev/null +++ b/crazyflie_interfaces/msg/ConnectionStatistics.msg @@ -0,0 +1,6 @@ +string uri +uint64 sent_count +uint64 sent_ping_count +uint64 receive_count +uint64 enqueued_count +uint64 ack_count diff --git a/crazyflie_interfaces/msg/ConnectionStatisticsArray.msg b/crazyflie_interfaces/msg/ConnectionStatisticsArray.msg new file mode 100644 index 000000000..8451db2ad --- /dev/null +++ b/crazyflie_interfaces/msg/ConnectionStatisticsArray.msg @@ -0,0 +1,2 @@ +std_msgs/Header header +ConnectionStatistics[] stats From 7be73c4a064547bf86609fa5725719e5c6597cdf Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Thu, 18 Jan 2024 14:28:52 +0100 Subject: [PATCH 060/162] add initial draft of dynobench backend --- .../crazyflie_sim/backend/dynobench.py | 108 ++++++++++++++++++ 1 file changed, 108 insertions(+) create mode 100644 crazyflie_sim/crazyflie_sim/backend/dynobench.py diff --git a/crazyflie_sim/crazyflie_sim/backend/dynobench.py b/crazyflie_sim/crazyflie_sim/backend/dynobench.py new file mode 100644 index 000000000..a6dbd379e --- /dev/null +++ b/crazyflie_sim/crazyflie_sim/backend/dynobench.py @@ -0,0 +1,108 @@ +from __future__ import annotations + +import numpy as np +from rclpy.node import Node +from rclpy.time import Time +import robot_python +from rosgraph_msgs.msg import Clock + +# import sys +# sys.path.append("/home/whoenig/projects/dynobench/build") + +from ..sim_data_types import Action, State + + +class Backend: + """Backend that uses newton-euler rigid-body dynamics implemented in numpy.""" + + def __init__(self, node: Node, names: list[str], states: list[State]): + self.node = node + self.names = names + self.clock_publisher = node.create_publisher(Clock, 'clock', 10) + self.t = 0 + self.dt = 0.0005 + + self.uavs = [] + for state in states: + uav = Quadrotor(state) + self.uavs.append(uav) + + def time(self) -> float: + return self.t + + def step(self, states_desired: list[State], actions: list[Action]) -> list[State]: + # advance the time + self.t += self.dt + + next_states = [] + + for uav, action in zip(self.uavs, actions): + uav.step(action, self.dt) + next_states.append(uav.state) + + # print(states_desired, actions, next_states) + # publish the current clock + clock_message = Clock() + clock_message.clock = Time(seconds=self.time()).to_msg() + self.clock_publisher.publish(clock_message) + + return next_states + + def shutdown(self): + pass + + +# convert RPM -> Force +def rpm_to_force(rpm): + # polyfit using data and scripts from https://github.com/IMRCLab/crazyflie-system-id + p = [2.55077341e-08, -4.92422570e-05, -1.51910248e-01] + force_in_grams = np.polyval(p, rpm) + force_in_newton = force_in_grams * 9.81 / 1000.0 + return np.maximum(force_in_newton, 0) + + +def sim_state2dynobench_state(state): + result = np.empty(13) + result[0:3] = state.pos + result[3:6] = state.quat[1:] + result[6] = state.quat[0] + result[7:10] = state.vel + result[10:13] = state.omega + return result + + +def dynobench_state2sim_state(state): + result = State() + result.pos = state[0:3] + result.quat = np.concatenate((state[6:7], state[3:6])) + result.vel = state[7:10] + result.omega = state[10:13] + return result + + +class Quadrotor: + """Basic rigid body quadrotor model (no drag) using numpy and rowan.""" + + def __init__(self, state): + self.uav = robot_python.robot_factory( + '/home/whoenig/projects/dynobench/models/quad3d_v0.yaml', [], []) + self.state = state + + def step(self, action, dt): + + # m: 0.034 + # max_f: 1.3 + force_in_newton = rpm_to_force(action.rpm) + normalized_force = force_in_newton / (1.3 * (0.034 / 4) * 9.81) + + xnext = np.zeros(13) + # print(sim_state2dynobench_state(self.state)) + print(normalized_force) + self.uav.step(xnext, sim_state2dynobench_state(self.state), normalized_force, dt) + self.state = dynobench_state2sim_state(xnext) + + # if we fall below the ground, set velocities to 0 + if self.state.pos[2] < 0: + self.state.pos[2] = 0 + self.state.vel = [0, 0, 0] + self.state.omega = [0, 0, 0] From e28a9f24478d5a34a873b5deb7cd62a701581fb5 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Thu, 18 Jan 2024 14:37:58 +0100 Subject: [PATCH 061/162] sim - backend - dynobench: cleanup --- .../backend/data/dynobench/crazyflie2.yaml | 15 +++++++++++++++ crazyflie_sim/crazyflie_sim/backend/dynobench.py | 6 ++---- 2 files changed, 17 insertions(+), 4 deletions(-) create mode 100644 crazyflie_sim/crazyflie_sim/backend/data/dynobench/crazyflie2.yaml diff --git a/crazyflie_sim/crazyflie_sim/backend/data/dynobench/crazyflie2.yaml b/crazyflie_sim/crazyflie_sim/backend/data/dynobench/crazyflie2.yaml new file mode 100644 index 000000000..34ffef628 --- /dev/null +++ b/crazyflie_sim/crazyflie_sim/backend/data/dynobench/crazyflie2.yaml @@ -0,0 +1,15 @@ +# distance_weights: [1. , .5, .2, .2 ] +distance_weights: [1., .5, .1, .05] +max_vel: 4 +max_angular_vel: 8 +max_acc: 25 # used for bounds on time +max_angular_acc: 20 # used for bounds on time +motor_control: true # True = controls are forces in the motors (False is NOT implemented) +m: 0.034 +max_f: 1.3 +arm_length: 0.046 +t2t: 0.006 # thrust-to-torque ratio +J_v: [16.571710e-6, 16.655602e-6, 29.261652e-6] # inertia matrix +dt: .01 +size: [.25] +dynamics: quad3d diff --git a/crazyflie_sim/crazyflie_sim/backend/dynobench.py b/crazyflie_sim/crazyflie_sim/backend/dynobench.py index a6dbd379e..0c092918c 100644 --- a/crazyflie_sim/crazyflie_sim/backend/dynobench.py +++ b/crazyflie_sim/crazyflie_sim/backend/dynobench.py @@ -1,4 +1,4 @@ -from __future__ import annotations +from pathlib import Path import numpy as np from rclpy.node import Node @@ -85,7 +85,7 @@ class Quadrotor: def __init__(self, state): self.uav = robot_python.robot_factory( - '/home/whoenig/projects/dynobench/models/quad3d_v0.yaml', [], []) + str((Path(__file__).parent / 'data/dynobench/crazyflie2.yaml').resolve()), [], []) self.state = state def step(self, action, dt): @@ -96,8 +96,6 @@ def step(self, action, dt): normalized_force = force_in_newton / (1.3 * (0.034 / 4) * 9.81) xnext = np.zeros(13) - # print(sim_state2dynobench_state(self.state)) - print(normalized_force) self.uav.step(xnext, sim_state2dynobench_state(self.state), normalized_force, dt) self.state = dynobench_state2sim_state(xnext) From f63e0b07f7ccac72b211677a2ecbcd306fa60dc1 Mon Sep 17 00:00:00 2001 From: Khaled Wahba <51020237+Khaledwahba1994@users.noreply.github.com> Date: Mon, 22 Jan 2024 21:18:57 +0100 Subject: [PATCH 062/162] backend sim: pinocchio (#408) * Add pinoccio backend for simulation --- .../backend/data/pinocchio/crazyflie2.urdf | 27 ++++ .../crazyflie_sim/backend/pinocchio.py | 118 ++++++++++++++++++ 2 files changed, 145 insertions(+) create mode 100644 crazyflie_sim/crazyflie_sim/backend/data/pinocchio/crazyflie2.urdf create mode 100644 crazyflie_sim/crazyflie_sim/backend/pinocchio.py diff --git a/crazyflie_sim/crazyflie_sim/backend/data/pinocchio/crazyflie2.urdf b/crazyflie_sim/crazyflie_sim/backend/data/pinocchio/crazyflie2.urdf new file mode 100644 index 000000000..d6f589ec9 --- /dev/null +++ b/crazyflie_sim/crazyflie_sim/backend/data/pinocchio/crazyflie2.urdf @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/crazyflie_sim/crazyflie_sim/backend/pinocchio.py b/crazyflie_sim/crazyflie_sim/backend/pinocchio.py new file mode 100644 index 000000000..77b066aa8 --- /dev/null +++ b/crazyflie_sim/crazyflie_sim/backend/pinocchio.py @@ -0,0 +1,118 @@ +from pathlib import Path + +import numpy as np +import pinocchio as pin +from rclpy.node import Node +from rclpy.time import Time +from rosgraph_msgs.msg import Clock + +from ..sim_data_types import Action, State + + +class Backend: + """Backend that uses pinocchio to simulate the rigid-body dynamics.""" + + def __init__(self, node: Node, names: list[str], states: list[State]): + self.node = node + self.names = names + self.clock_publisher = node.create_publisher(Clock, 'clock', 10) + self.t = 0 + self.dt = 0.0005 + + self.uavs = [] + for state in states: + uav = Quadrotor(state) + self.uavs.append(uav) + + def time(self) -> float: + return self.t + + def step(self, states_desired: list[State], actions: list[Action]) -> list[State]: + # advance the time + self.t += self.dt + + next_states = [] + + for uav, action in zip(self.uavs, actions): + uav.step(action, self.dt) + next_states.append(uav.state) + + # print(states_desired, actions, next_states) + # publish the current clock + clock_message = Clock() + clock_message.clock = Time(seconds=self.time()).to_msg() + self.clock_publisher.publish(clock_message) + + return next_states + + def shutdown(self): + pass + + +# convert RPM -> Force +def rpm_to_force(rpm): + # polyfit using data and scripts from https://github.com/IMRCLab/crazyflie-system-id + p = [2.55077341e-08, -4.92422570e-05, -1.51910248e-01] + force_in_grams = np.polyval(p, rpm) + force_in_newton = force_in_grams * 9.81 / 1000.0 + return np.maximum(force_in_newton, 0) + + +def pinocchio_state2sim_state(q, v): + result = State() + result.pos = q[0:3] + result.quat = np.concatenate((q[6:7], q[3:6])) + result.vel = v[0:3] + result.omega = v[3:6] + return result + + +def sim_state2pinocchio_state(state): + result = np.empty(13) + result[0:3] = state.pos + result[3:6] = state.quat[1:] + result[6] = state.quat[0] + result[7:10] = state.vel + result[10:13] = state.omega + q = result[0:7] # geometric states: x, y, z, qx, qy, qz, qw + v = result[7:] # velocities: vx, vy, vz, wx, wy, wz + return q, v + + +class Quadrotor: + """Basic rigid body quadrotor model (no drag) using numpy and rowan.""" + + def __init__(self, state): + arm_length = 0.046 # m + arm = 0.707106781 * arm_length + t2t = 0.006 # thrust-to-torque ratio + self.B0 = np.array([ + [1, 1, 1, 1], + [-arm, -arm, arm, arm], + [-arm, arm, arm, -arm], + [-t2t, t2t, -t2t, t2t] + ]) + self.uav, self.collision_model, self.visual_model = pin.buildModelsFromUrdf( + str((Path(__file__).parent / 'data/pinocchio/crazyflie2.urdf'))) + self.uavPinocchioData = self.uav.createData() + self.state = state + + def step(self, action, dt): + + # m: 0.034 + # max_f: 1.3 + force_in_newton = rpm_to_force(action.rpm) + eta = np.dot(self.B0, force_in_newton) + force_generalized = np.array([0., 0., eta[0], eta[1], eta[2], eta[3]]) + + q, v = sim_state2pinocchio_state(self.state) + a = pin.aba(self.uav, self.uavPinocchioData, q, v, force_generalized) + v_next = v + a*dt + q_next = pin.integrate(self.uav, q, v*dt) + self.state = pinocchio_state2sim_state(q_next, v_next) + + # if we fall below the ground, set velocities to 0 + if self.state.pos[2] < 0: + self.state.pos[2] = 0 + self.state.vel = [0, 0, 0] + self.state.omega = [0, 0, 0] From 5d8cbc43c1d2b876b7ee82e16ad4fe7468fc79f4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Wolfgang=20H=C3=B6nig?= Date: Sat, 27 Jan 2024 14:43:06 +0100 Subject: [PATCH 063/162] Add status topic (#406) Adding `//status` topic with battery information, supervisor information, and radio statistics * handling of overflow * add safeguard for older firmware versions * update submodule --- crazyflie/deps/crazyflie_tools | 2 +- crazyflie/src/crazyflie_server.cpp | 127 ++++++++++++++++++++++++++-- crazyflie_interfaces/CMakeLists.txt | 1 + crazyflie_interfaces/msg/Status.msg | 31 +++++++ 4 files changed, 153 insertions(+), 8 deletions(-) create mode 100644 crazyflie_interfaces/msg/Status.msg diff --git a/crazyflie/deps/crazyflie_tools b/crazyflie/deps/crazyflie_tools index 8cf7ee6b0..36ea3d401 160000 --- a/crazyflie/deps/crazyflie_tools +++ b/crazyflie/deps/crazyflie_tools @@ -1 +1 @@ -Subproject commit 8cf7ee6b0e91b78e428e167914c7a9a267e11ac2 +Subproject commit 36ea3d40161db8f580dbb8846789bc036a2ccedd diff --git a/crazyflie/src/crazyflie_server.cpp b/crazyflie/src/crazyflie_server.cpp index c49ac63c4..d79e307f7 100644 --- a/crazyflie/src/crazyflie_server.cpp +++ b/crazyflie/src/crazyflie_server.cpp @@ -20,6 +20,7 @@ #include "motion_capture_tracking_interfaces/msg/named_pose_array.hpp" #include "crazyflie_interfaces/msg/full_state.hpp" #include "crazyflie_interfaces/msg/position.hpp" +#include "crazyflie_interfaces/msg/status.hpp" #include "crazyflie_interfaces/msg/log_data_generic.hpp" #include "crazyflie_interfaces/msg/connection_statistics_array.hpp" @@ -102,6 +103,21 @@ class CrazyflieROS uint16_t right; } __attribute__((packed)); + struct logStatus { + // general status + uint16_t supervisorInfo; // supervisor.info + // battery related + // Note that using BQ-deck/Bolt one can actually have two batteries at the same time. + // vbat refers to the battery directly connected to the CF board and might not reflect + // the "external" battery on BQ/Bolt builds + uint16_t vbatMV; // pm.vbatMV + uint8_t pmState; // pm.state + // radio related + uint8_t rssi; // radio.rssi + uint16_t numRxBc; // radio.numRxBc + uint16_t numRxUc; // radio.numRxUc + } __attribute__((packed)); + public: CrazyflieROS( const std::string& link_uri, @@ -110,6 +126,7 @@ class CrazyflieROS rclcpp::Node* node, rclcpp::CallbackGroup::SharedPtr callback_group_cf_cmd, rclcpp::CallbackGroup::SharedPtr callback_group_cf_srv, + const CrazyflieBroadcaster* cfbc, bool enable_parameters = true) : logger_(rclcpp::get_logger(name)) , cf_logger_(logger_) @@ -121,6 +138,7 @@ class CrazyflieROS , node_(node) , tf_broadcaster_(node) , last_on_latency_(std::chrono::steady_clock::now()) + , cfbc_(cfbc) { auto sub_opt_cf_cmd = rclcpp::SubscriptionOptions(); sub_opt_cf_cmd.callback_group = callback_group_cf_cmd; @@ -355,6 +373,47 @@ class CrazyflieROS }, cb)); log_block_scan_->start(uint8_t(100.0f / (float)freq)); // this is in tens of milliseconds } + else if (i.first.find("default_topics.status") == 0) { + int freq = log_config_map["default_topics.status.frequency"].get(); + RCLCPP_INFO(logger_, "Logging to /status at %d Hz", freq); + + publisher_status_ = node->create_publisher(name + "/status", 10); + + std::function cb = std::bind(&CrazyflieROS::on_logging_status, this, std::placeholders::_1, std::placeholders::_2); + + std::list > logvars({ + // general status + {"supervisor", "info"}, + // battery related + {"pm", "vbatMV"}, + {"pm", "state"}, + // radio related + {"radio", "rssi"} + }); + + // check if this firmware version has radio.numRx{Bc,Uc} + status_has_radio_stats_ = false; + for (auto iter = cf_.logVariablesBegin(); iter != cf_.logVariablesEnd(); ++iter) { + auto entry = *iter; + if (entry.group == "radio" && entry.name == "numRxBc") { + logvars.push_back({"radio", "numRxBc"}); + logvars.push_back({"radio", "numRxUc"}); + status_has_radio_stats_ = true; + break; + } + } + + // older firmware -> use other 16-bit variables + if (!status_has_radio_stats_) { + RCLCPP_WARN(logger_, "Older firmware. status/num_rx_broadcast and status/num_rx_unicast are set to zero."); + logvars.push_back({"pm", "vbatMV"}); + logvars.push_back({"pm", "vbatMV"}); + } + + log_block_status_.reset(new LogBlock( + &cf_,logvars, cb)); + log_block_status_->start(uint8_t(100.0f / (float)freq)); // this is in tens of milliseconds + } else if (i.first.find("custom_topics") == 0 && i.first.rfind(".vars") != std::string::npos) { std::string topic_name = i.first.substr(14, i.first.size() - 14 - 5); @@ -690,6 +749,51 @@ class CrazyflieROS } } + void on_logging_status(uint32_t time_in_ms, const logStatus* data) { + if (publisher_status_) { + + crazyflie_interfaces::msg::Status msg; + msg.header.stamp = node_->get_clock()->now(); + msg.header.frame_id = name_; + msg.supervisor_info = data->supervisorInfo; + msg.battery_voltage = data->vbatMV / 1000.0f; + msg.pm_state = data->pmState; + msg.rssi = data->rssi; + if (status_has_radio_stats_) { + int32_t deltaRxBc = data->numRxBc - previous_numRxBc; + int32_t deltaRxUc = data->numRxUc - previous_numRxUc; + // handle overflow + if (deltaRxBc < 0) { + deltaRxBc += std::numeric_limits::max(); + } + if (deltaRxUc < 0) { + deltaRxUc += std::numeric_limits::max(); + } + msg.num_rx_broadcast = deltaRxBc; + msg.num_rx_unicast = deltaRxUc; + previous_numRxBc = data->numRxBc; + previous_numRxUc = data->numRxUc; + } else { + msg.num_rx_broadcast = 0; + msg.num_rx_unicast = 0; + } + + // connection sent stats (unicast) + const auto statsUc = cf_.connectionStats(); + size_t deltaTxUc = statsUc.sent_count - previous_stats_unicast_.sent_count; + msg.num_tx_unicast = deltaTxUc; + previous_stats_unicast_ = statsUc; + + // connection sent stats (broadcast) + const auto statsBc = cfbc_->connectionStats(); + size_t deltaTxBc = statsBc.sent_count - previous_stats_broadcast_.sent_count; + msg.num_tx_broadcast = deltaTxBc; + previous_stats_broadcast_ = statsBc; + + publisher_status_->publish(msg); + } + } + void on_logging_custom(uint32_t time_in_ms, const std::vector* values, void* userData) { auto pub = reinterpret_cast::SharedPtr*>(userData); @@ -774,6 +878,15 @@ class CrazyflieROS std::unique_ptr> log_block_scan_; rclcpp::Publisher::SharedPtr publisher_scan_; + std::unique_ptr> log_block_status_; + bool status_has_radio_stats_; + rclcpp::Publisher::SharedPtr publisher_status_; + uint16_t previous_numRxBc; + uint16_t previous_numRxUc; + bitcraze::crazyflieLinkCpp::Connection::Statistics previous_stats_unicast_; + bitcraze::crazyflieLinkCpp::Connection::Statistics previous_stats_broadcast_; + const CrazyflieBroadcaster* cfbc_; + std::list> log_blocks_generic_; std::list::SharedPtr> publishers_generic_; @@ -888,19 +1001,19 @@ class CrazyflieServer : public rclcpp::Node // if it is a Crazyflie, try to connect if (constr == "crazyflie") { std::string uri = parameter_overrides.at("robots." + name + ".uri").get(); + auto broadcastUri = Crazyflie::broadcastUriFromUnicastUri(uri); + if (broadcaster_.count(broadcastUri) == 0) { + broadcaster_.emplace(broadcastUri, std::make_unique(broadcastUri)); + } + crazyflies_.emplace(name, std::make_unique( uri, cf_type, name, this, callback_group_cf_cmd_, - callback_group_cf_srv_)); - - auto broadcastUri = crazyflies_[name]->broadcastUri(); - RCLCPP_INFO(logger_, "%s", broadcastUri.c_str()); - if (broadcaster_.count(broadcastUri) == 0) { - broadcaster_.emplace(broadcastUri, std::make_unique(broadcastUri)); - } + callback_group_cf_srv_, + broadcaster_.at(broadcastUri).get())); update_name_to_id_map(name, crazyflies_[name]->id()); } diff --git a/crazyflie_interfaces/CMakeLists.txt b/crazyflie_interfaces/CMakeLists.txt index 583e95fa1..0e92f4d09 100644 --- a/crazyflie_interfaces/CMakeLists.txt +++ b/crazyflie_interfaces/CMakeLists.txt @@ -25,6 +25,7 @@ rosidl_generate_interfaces(${PROJECT_NAME} "msg/Hover.msg" "msg/LogBlock.msg" "msg/Position.msg" + "msg/Status.msg" "msg/TrajectoryPolynomialPiece.msg" "msg/VelocityWorld.msg" "srv/GoTo.srv" diff --git a/crazyflie_interfaces/msg/Status.msg b/crazyflie_interfaces/msg/Status.msg new file mode 100644 index 000000000..bebd42a71 --- /dev/null +++ b/crazyflie_interfaces/msg/Status.msg @@ -0,0 +1,31 @@ + +# Constants +uint16 SUPERVISOR_INFO_CAN_BE_ARMED = 0 +uint16 SUPERVISOR_INFO_IS_ARMED = 2 +uint16 SUPERVISOR_INFO_AUTO_ARM = 4 +uint16 SUPERVISOR_INFO_CAN_FLY = 8 +uint16 SUPERVISOR_INFO_IS_FLYING = 16 +uint16 SUPERVISOR_INFO_IS_TUMBLED = 32 +uint16 SUPERVISOR_INFO_IS_LOCKED = 64 + +uint8 PM_STATE_BATTERY = 0 +uint8 PM_STATE_CHARGING = 1 +uint8 PM_STATE_CHARGED = 2 +uint8 PM_STATE_LOW_POWER = 3 +uint8 PM_STATE_SHUTDOWN = 4 + +std_msgs/Header header + +# general status +uint16 supervisor_info # Bitfield, see SUPERVISOR_INFO for individual bits + +# battery related +float32 battery_voltage # internal battery voltage [V] +uint8 pm_state # See PM_STATE_* for potential values + +# radio related +uint8 rssi # latest radio signal strength indicator [dBm] +uint32 num_rx_broadcast # number of received broadcast packets during the last period +uint32 num_tx_broadcast # number of broadcast packets sent during the last period +uint32 num_rx_unicast # number of received unicast packets during the last period +uint32 num_tx_unicast # number of unicast packets sent during the last period From 74839dcd661fd3904d00066597396eeb31fe0027 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Sat, 27 Jan 2024 14:52:54 +0100 Subject: [PATCH 064/162] docs: update warning to include shared user accounts --- docs2/conf.py | 2 +- docs2/usage.rst | 5 +++++ 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/docs2/conf.py b/docs2/conf.py index 63931d5d4..4acc270d1 100644 --- a/docs2/conf.py +++ b/docs2/conf.py @@ -62,7 +62,7 @@ # General information about the project. project = 'Crazyswarm2' -copyright = '2021-2022, Wolfgang Hönig (IMRClab), Kimberly McGuire (Bitcraze AB) and contributors' +copyright = '2021-2024, Wolfgang Hönig (TU Berlin), Kimberly McGuire (Bitcraze AB), and contributors' author = 'Wolfgang Hönig, Kimberly McGuire' # The version info for the project you're documenting, acts as replacement for diff --git a/docs2/usage.rst b/docs2/usage.rst index c35939ff7..d8278958b 100644 --- a/docs2/usage.rst +++ b/docs2/usage.rst @@ -19,6 +19,11 @@ Usage .. code-block:: bash export ROS_LOCALHOST_ONLY=1 + export ROS_DOMAIN_ID= + + The first environment variable restricts ROS to your local machine. The second is useful + if you have multiple user accounts on the same machine (e.g., a shared workstation computer). + In such case, each user should use a unique `domain ID `_. Configuration From 762672a6d4a78efca3613e24bfaf84ab75ce245e Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Sat, 27 Jan 2024 14:55:23 +0100 Subject: [PATCH 065/162] systemtests: use non-default domain id This should avoid interference with systemtests running on the same machine as flight tests --- .github/workflows/systemtests.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/systemtests.yml b/.github/workflows/systemtests.yml index 045b64049..1cae1631a 100644 --- a/.github/workflows/systemtests.yml +++ b/.github/workflows/systemtests.yml @@ -39,6 +39,7 @@ jobs: source /opt/ros/humble/setup.bash . install/local_setup.bash export ROS_LOCALHOST_ONLY=1 + export ROS_DOMAIN_ID=99 python3 src/crazyswarm2/systemtests/test_flights.py - name: Upload files From f861618803838173e7b7939c0d65fc4a8c192feb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Wolfgang=20H=C3=B6nig?= Date: Wed, 31 Jan 2024 13:38:45 +0100 Subject: [PATCH 066/162] Add robot_description support [cpp,cflib,sim] (#412) * add robot_description support in cpp, cflib and sim backends --- crazyflie/CMakeLists.txt | 3 +- crazyflie/config/config.rviz | 49 +- crazyflie/launch/launch.py | 9 + crazyflie/scripts/crazyflie_server.py | 11 + crazyflie/src/crazyflie_server.cpp | 14 + crazyflie/urdf/cf2_assembly_with_props.dae | 433 ++++++++++++++++++ crazyflie/urdf/crazyflie_description.urdf | 11 + .../crazyflie_sim/crazyflie_server.py | 12 + 8 files changed, 532 insertions(+), 10 deletions(-) create mode 100644 crazyflie/urdf/cf2_assembly_with_props.dae create mode 100644 crazyflie/urdf/crazyflie_description.urdf diff --git a/crazyflie/CMakeLists.txt b/crazyflie/CMakeLists.txt index ed6c31903..c8899cfbe 100644 --- a/crazyflie/CMakeLists.txt +++ b/crazyflie/CMakeLists.txt @@ -112,10 +112,11 @@ install(PROGRAMS DESTINATION lib/${PROJECT_NAME} ) -# Install launch and config files. +# Install launch, config, and urdf files. install(DIRECTORY launch config + urdf DESTINATION share/${PROJECT_NAME}/ ) diff --git a/crazyflie/config/config.rviz b/crazyflie/config/config.rviz index d19a5dc9a..9d1b49a9e 100644 --- a/crazyflie/config/config.rviz +++ b/crazyflie/config/config.rviz @@ -52,7 +52,7 @@ Visualization Manager: Frame Timeout: 15 Frames: All Enabled: true - test: + cf231: Value: true world: Value: true @@ -60,13 +60,44 @@ Visualization Manager: Name: TF Show Arrows: true Show Axes: true - Show Names: false + Show Names: true Tree: world: - test: + cf231: {} Update Interval: 0 Value: true + - Alpha: 1 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /cf231/robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + cf231: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Mass Properties: + Inertia: false + Mass: false + Name: CF231 + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true Enabled: true Global Options: Background Color: 48; 48; 48 @@ -113,25 +144,25 @@ Visualization Manager: Views: Current: Class: rviz_default_plugins/Orbit - Distance: 6.814720153808594 + Distance: 3.1647839546203613 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 0 - Y: 0 - Z: 0 + X: -0.028163839131593704 + Y: -0.049007341265678406 + Z: -0.025782346725463867 Focal Shape Fixed Size: true Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.665398120880127 + Pitch: 0.4847976565361023 Target Frame: Value: Orbit (rviz) - Yaw: 2.8785719871520996 + Yaw: 2.9185757637023926 Saved: ~ Window Geometry: Displays: diff --git a/crazyflie/launch/launch.py b/crazyflie/launch/launch.py index e71b9cf51..8a9290c11 100644 --- a/crazyflie/launch/launch.py +++ b/crazyflie/launch/launch.py @@ -30,6 +30,15 @@ def generate_launch_description(): server_params = [crazyflies] + [server_yaml_contents["/crazyflie_server"]["ros__parameters"]] + # robot description + urdf = os.path.join( + get_package_share_directory('crazyflie'), + 'urdf', + 'crazyflie_description.urdf') + with open(urdf, 'r') as f: + robot_desc = f.read() + server_params[1]["robot_description"] = robot_desc + # construct motion_capture_configuration motion_capture_yaml = os.path.join( get_package_share_directory('crazyflie'), diff --git a/crazyflie/scripts/crazyflie_server.py b/crazyflie/scripts/crazyflie_server.py index ca44a9320..fbbe8fe72 100755 --- a/crazyflie/scripts/crazyflie_server.py +++ b/crazyflie/scripts/crazyflie_server.py @@ -30,6 +30,7 @@ from motion_capture_tracking_interfaces.msg import NamedPoseArray from std_srvs.srv import Empty +from std_msgs.msg import String from geometry_msgs.msg import Twist from geometry_msgs.msg import PoseStamped, TransformStamped from sensor_msgs.msg import LaserScan @@ -220,6 +221,16 @@ def __init__(self): for uri in self.cf_dict: name = self.cf_dict[uri] + + pub = self.create_publisher(String, name + '/robot_description', + rclpy.qos.QoSProfile( + depth=1, + durability=rclpy.qos.QoSDurabilityPolicy.TRANSIENT_LOCAL)) + + msg = String() + msg.data = self._ros_parameters['robot_description'].replace("$NAME", name) + pub.publish(msg) + self.create_service( Empty, name + "/emergency", partial(self._emergency_callback, uri=uri) diff --git a/crazyflie/src/crazyflie_server.cpp b/crazyflie/src/crazyflie_server.cpp index d79e307f7..4a71e0245 100644 --- a/crazyflie/src/crazyflie_server.cpp +++ b/crazyflie/src/crazyflie_server.cpp @@ -12,6 +12,7 @@ #include "crazyflie_interfaces/srv/land.hpp" #include "crazyflie_interfaces/srv/go_to.hpp" #include "crazyflie_interfaces/srv/notify_setpoints_stop.hpp" +#include "std_msgs/msg/string.hpp" #include "geometry_msgs/msg/twist.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/transform_stamped.hpp" @@ -160,6 +161,15 @@ class CrazyflieROS subscription_cmd_full_state_ = node->create_subscription(name + "/cmd_full_state", rclcpp::SystemDefaultsQoS(), std::bind(&CrazyflieROS::cmd_full_state_changed, this, _1), sub_opt_cf_cmd); subscription_cmd_position_ = node->create_subscription(name + "/cmd_position", rclcpp::SystemDefaultsQoS(), std::bind(&CrazyflieROS::cmd_position_changed, this, _1), sub_opt_cf_cmd); + publisher_robot_description_ = node->create_publisher(name + "/robot_description", + rclcpp::QoS(1).transient_local()); + { + auto msg = std::make_unique(); + auto robot_desc = node->get_parameter("robot_description").get_parameter_value().get(); + msg->data = std::regex_replace(robot_desc, std::regex("\\$NAME"), name); + publisher_robot_description_->publish(std::move(msg)); + } + // spinning timer // used to process all incoming radio messages spin_timer_ = @@ -871,6 +881,8 @@ class CrazyflieROS rclcpp::Subscription::SharedPtr subscription_cmd_full_state_; rclcpp::Subscription::SharedPtr subscription_cmd_position_; + rclcpp::Publisher::SharedPtr publisher_robot_description_; + // logging std::unique_ptr> log_block_pose_; rclcpp::Publisher::SharedPtr publisher_pose_; @@ -953,6 +965,8 @@ class CrazyflieServer : public rclcpp::Node broadcasts_delay_between_repeats_ms_ = this->get_parameter("all.broadcasts.delay_between_repeats_ms").get_parameter_value().get(); mocap_enabled_ = false; + this->declare_parameter("robot_description", ""); + // Warnings this->declare_parameter("warnings.frequency", 1.0); float freq = this->get_parameter("warnings.frequency").get_parameter_value().get(); diff --git a/crazyflie/urdf/cf2_assembly_with_props.dae b/crazyflie/urdf/cf2_assembly_with_props.dae new file mode 100644 index 000000000..8e781721e --- /dev/null +++ b/crazyflie/urdf/cf2_assembly_with_props.dae @@ -0,0 +1,433 @@ + + + + + + Kimberly McGuire (Bitcraze AB) + Blender 3.1.2 commit date:2022-03-31, commit time:17:40, hash:cc66d1020c3b + + 2024-01-30T21:06:41 + 2024-01-30T21:06:41 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.009523815 0.009523815 0.009523815 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.1169535 0.1169535 0.1169535 1 + + + 0.8 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.3428556 0.3428556 0.3428556 1 + + + 0.6528497 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 0.5 + + + + + + + + + + + + + + + + + + + + + + + + + + -0.00999999 0.00999999 5e-4 -0.00999999 0.00999999 0.002499997 -0.00999999 0.01199996 0.002499997 -0.00999999 0.01199996 5e-4 0.00999999 0.01199996 0.002499997 0.00999999 0.01199996 5e-4 0.00999999 0.00999999 0.002499997 0.00999999 0.00999999 5e-4 -0.00999999 -0.00999999 5e-4 -0.00999999 -0.01199996 5e-4 -0.00999999 -0.01199996 0.002499997 -0.00999999 -0.00999999 0.002499997 0.00999999 -0.01199996 5e-4 0.00999999 -0.01199996 0.002499997 0.00999999 -0.00999999 5e-4 0.00999999 -0.00999999 0.002499997 -0.00999999 -0.01399999 -5e-4 -0.00999999 -0.01399999 5e-4 -0.00999999 0.01399999 5e-4 -0.00999999 0.01399999 -5e-4 0.00999999 0.01399999 5e-4 0.00999999 0.01399999 -5e-4 0.00999999 -0.01399999 5e-4 0.00999999 -0.01399999 -5e-4 -0.00109595 0.008999943 -5e-4 0.00109595 0.008999943 -5e-4 0.00109595 -0.008999943 -5e-4 -0.00109595 -0.008999943 -5e-4 -0.008095979 0.008999943 -5e-4 -0.008095979 -0.008999943 -5e-4 0.008095979 -0.008999943 -5e-4 0.008095979 0.008999943 -5e-4 -0.00109595 -0.008999943 5e-4 -0.008095979 -0.008999943 5e-4 -0.008095979 0.008999943 5e-4 -0.00109595 0.008999943 5e-4 0.00109595 0.008999943 5e-4 0.008095979 0.008999943 5e-4 0.008095979 -0.008999943 5e-4 0.00109595 -0.008999943 5e-4 + + + + + + + + + + -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 -1 0 0 1 0 0 1 0 0 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 0 2 0 3 0 3 1 2 1 4 1 3 1 4 1 5 1 5 2 4 2 6 2 5 2 6 2 7 2 7 3 6 3 1 3 7 3 1 3 0 3 3 4 5 4 7 4 3 4 7 4 0 4 4 5 2 5 1 5 4 5 1 5 6 5 8 0 9 0 10 0 8 0 10 0 11 0 9 3 12 3 13 3 9 3 13 3 10 3 12 2 14 2 15 2 12 2 15 2 13 2 14 1 8 1 11 1 14 1 11 1 15 1 9 4 8 4 14 4 9 4 14 4 12 4 13 5 15 5 11 5 13 5 11 5 10 5 16 0 17 0 18 0 16 0 18 0 19 0 19 1 18 1 20 1 19 1 20 1 21 1 21 2 20 2 22 2 21 2 22 2 23 2 23 3 22 3 17 3 23 3 17 3 16 3 24 6 25 6 26 6 24 4 26 4 27 4 16 4 19 4 28 4 16 4 28 4 29 4 24 4 28 4 19 4 23 4 16 4 29 4 27 5 26 5 30 5 23 4 29 4 27 4 24 4 19 4 21 4 31 4 25 4 24 4 23 4 27 4 30 4 31 4 24 4 21 4 23 4 30 4 31 4 21 7 23 7 31 7 32 5 33 5 17 5 20 5 18 5 34 5 35 5 36 5 37 5 20 5 34 5 35 5 32 5 17 5 22 5 38 5 39 5 32 5 20 8 35 8 37 8 38 5 32 5 22 5 20 9 37 9 38 9 22 5 20 5 38 5 34 5 18 5 17 5 34 10 17 10 33 10 36 11 35 11 32 11 36 5 32 5 39 5 27 1 29 1 33 1 27 1 33 1 32 1 33 2 29 2 28 2 33 2 28 2 34 2 34 3 28 3 24 3 34 3 24 3 35 3 24 0 27 0 32 0 24 0 32 0 35 0 30 1 26 1 39 1 30 1 39 1 38 1 31 0 30 0 38 0 31 12 38 12 37 12 36 3 25 3 31 3 36 3 31 3 37 3 39 13 26 13 25 13 39 14 25 14 36 14

+
+
+
+ + + + -0.008816301 2.5e-4 0.01445657 -0.009316325 2.5e-4 0.01445657 -0.009316325 -2.5e-4 0.01445657 -0.008816301 -2.5e-4 0.01445657 -0.008816301 -2.5e-4 -0.003543376 -0.009316325 -2.5e-4 -0.003543376 -0.009316325 2.5e-4 -0.003543376 -0.008816301 2.5e-4 -0.003543376 -0.006816327 2.5e-4 0.01445657 -0.00731635 2.5e-4 0.01445657 -0.00731635 -2.5e-4 0.01445657 -0.006816327 -2.5e-4 0.01445657 -0.006816327 -2.5e-4 -0.003543376 -0.00731635 -2.5e-4 -0.003543376 -0.00731635 2.5e-4 -0.003543376 -0.006816327 2.5e-4 -0.003543376 -0.004816353 2.5e-4 0.01445657 -0.005316317 2.5e-4 0.01445657 -0.005316317 -2.5e-4 0.01445657 -0.004816353 -2.5e-4 0.01445657 -0.004816353 -2.5e-4 -0.003543376 -0.005316317 -2.5e-4 -0.003543376 -0.005316317 2.5e-4 -0.003543376 -0.004816353 2.5e-4 -0.003543376 -0.002816319 2.5e-4 0.01445657 -0.003316342 2.5e-4 0.01445657 -0.003316342 -2.5e-4 0.01445657 -0.002816319 -2.5e-4 0.01445657 -0.002816319 -2.5e-4 -0.003543376 -0.003316342 -2.5e-4 -0.003543376 -0.003316342 2.5e-4 -0.003543376 -0.002816319 2.5e-4 -0.003543376 -8.16359e-4 2.5e-4 0.01445657 -0.001316308 2.5e-4 0.01445657 -0.001316308 -2.5e-4 0.01445657 -8.16359e-4 -2.5e-4 0.01445657 -8.16359e-4 -2.5e-4 -0.003543376 -0.001316308 -2.5e-4 -0.003543376 -0.001316308 2.5e-4 -0.003543376 -8.16359e-4 2.5e-4 -0.003543376 0.001183629 2.5e-4 0.01445657 6.8364e-4 2.5e-4 0.01445657 6.8364e-4 -2.5e-4 0.01445657 0.001183629 -2.5e-4 0.01445657 0.001183629 -2.5e-4 -0.003543376 6.8364e-4 -2.5e-4 -0.003543376 6.8364e-4 2.5e-4 -0.003543376 0.001183629 2.5e-4 -0.003543376 0.003183603 2.5e-4 0.01445657 0.002683639 2.5e-4 0.01445657 0.002683639 -2.5e-4 0.01445657 0.003183603 -2.5e-4 0.01445657 0.003183603 -2.5e-4 -0.003543376 0.002683639 -2.5e-4 -0.003543376 0.002683639 2.5e-4 -0.003543376 0.003183603 2.5e-4 -0.003543376 0.005183637 2.5e-4 0.01445657 0.004683613 2.5e-4 0.01445657 0.004683613 -2.5e-4 0.01445657 0.005183637 -2.5e-4 0.01445657 0.005183637 -2.5e-4 -0.003543376 0.004683613 -2.5e-4 -0.003543376 0.004683613 2.5e-4 -0.003543376 0.005183637 2.5e-4 -0.003543376 0.007183611 2.5e-4 0.01445657 0.006683588 2.5e-4 0.01445657 0.006683588 -2.5e-4 0.01445657 0.007183611 -2.5e-4 0.01445657 0.007183611 -2.5e-4 -0.003543376 0.006683588 -2.5e-4 -0.003543376 0.006683588 2.5e-4 -0.003543376 0.007183611 2.5e-4 -0.003543376 0.009183585 2.5e-4 0.01445657 0.008683621 2.5e-4 0.01445657 0.008683621 -2.5e-4 0.01445657 0.009183585 -2.5e-4 0.01445657 0.009183585 -2.5e-4 -0.003543376 0.008683621 -2.5e-4 -0.003543376 0.008683621 2.5e-4 -0.003543376 0.009183585 2.5e-4 -0.003543376 -0.00999999 -0.000999987 -10e-4 -0.00999999 -0.000999987 0.000999987 -0.00999999 0.000999987 0.000999987 -0.00999999 0.000999987 -10e-4 0.00999999 0.000999987 0.000999987 0.00999999 0.000999987 -10e-4 0.00999999 -0.000999987 0.000999987 0.00999999 -0.000999987 -10e-4 -0.008816301 -0.02224999 0.01445657 -0.009316325 -0.02224999 0.01445657 -0.009316325 -0.02174997 0.01445657 -0.008816301 -0.02174997 0.01445657 -0.008816301 -0.02174997 -0.003543376 -0.009316325 -0.02174997 -0.003543376 -0.009316325 -0.02224999 -0.003543376 -0.008816301 -0.02224999 -0.003543376 -0.006816327 -0.02224999 0.01445657 -0.00731635 -0.02224999 0.01445657 -0.00731635 -0.02174997 0.01445657 -0.006816327 -0.02174997 0.01445657 -0.006816327 -0.02174997 -0.003543376 -0.00731635 -0.02174997 -0.003543376 -0.00731635 -0.02224999 -0.003543376 -0.006816327 -0.02224999 -0.003543376 -0.004816353 -0.02224999 0.01445657 -0.005316317 -0.02224999 0.01445657 -0.005316317 -0.02174997 0.01445657 -0.004816353 -0.02174997 0.01445657 -0.004816353 -0.02174997 -0.003543376 -0.005316317 -0.02174997 -0.003543376 -0.005316317 -0.02224999 -0.003543376 -0.004816353 -0.02224999 -0.003543376 -0.002816319 -0.02224999 0.01445657 -0.003316342 -0.02224999 0.01445657 -0.003316342 -0.02174997 0.01445657 -0.002816319 -0.02174997 0.01445657 -0.002816319 -0.02174997 -0.003543376 -0.003316342 -0.02174997 -0.003543376 -0.003316342 -0.02224999 -0.003543376 -0.002816319 -0.02224999 -0.003543376 -8.16359e-4 -0.02224999 0.01445657 -0.001316308 -0.02224999 0.01445657 -0.001316308 -0.02174997 0.01445657 -8.16359e-4 -0.02174997 0.01445657 -8.16359e-4 -0.02174997 -0.003543376 -0.001316308 -0.02174997 -0.003543376 -0.001316308 -0.02224999 -0.003543376 -8.16359e-4 -0.02224999 -0.003543376 0.001183629 -0.02224999 0.01445657 6.8364e-4 -0.02224999 0.01445657 6.8364e-4 -0.02174997 0.01445657 0.001183629 -0.02174997 0.01445657 0.001183629 -0.02174997 -0.003543376 6.8364e-4 -0.02174997 -0.003543376 6.8364e-4 -0.02224999 -0.003543376 0.001183629 -0.02224999 -0.003543376 0.003183603 -0.02224999 0.01445657 0.002683639 -0.02224999 0.01445657 0.002683639 -0.02174997 0.01445657 0.003183603 -0.02174997 0.01445657 0.003183603 -0.02174997 -0.003543376 0.002683639 -0.02174997 -0.003543376 0.002683639 -0.02224999 -0.003543376 0.003183603 -0.02224999 -0.003543376 0.005183637 -0.02224999 0.01445657 0.004683613 -0.02224999 0.01445657 0.004683613 -0.02174997 0.01445657 0.005183637 -0.02174997 0.01445657 0.005183637 -0.02174997 -0.003543376 0.004683613 -0.02174997 -0.003543376 0.004683613 -0.02224999 -0.003543376 0.005183637 -0.02224999 -0.003543376 0.007183611 -0.02224999 0.01445657 0.006683588 -0.02224999 0.01445657 0.006683588 -0.02174997 0.01445657 0.007183611 -0.02174997 0.01445657 0.007183611 -0.02174997 -0.003543376 0.006683588 -0.02174997 -0.003543376 0.006683588 -0.02224999 -0.003543376 0.007183611 -0.02224999 -0.003543376 0.009183585 -0.02224999 0.01445657 0.008683621 -0.02224999 0.01445657 0.008683621 -0.02174997 0.01445657 0.009183585 -0.02174997 0.01445657 0.009183585 -0.02174997 -0.003543376 0.008683621 -0.02174997 -0.003543376 0.008683621 -0.02224999 -0.003543376 0.009183585 -0.02224999 -0.003543376 -0.00999999 -0.02099996 -10e-4 -0.00999999 -0.02099996 0.000999987 -0.00999999 -0.023 0.000999987 -0.00999999 -0.023 -10e-4 0.00999999 -0.023 0.000999987 0.00999999 -0.023 -10e-4 0.00999999 -0.02099996 0.000999987 0.00999999 -0.02099996 -10e-4 + + + + + + + + + + 0 0 1 0 -1 0 -1 0 0 0 0 -1 1 0 0 0 1 0 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 0 2 0 3 0 4 1 3 1 2 1 4 1 2 1 5 1 5 2 2 2 1 2 5 2 1 2 6 2 6 3 7 3 4 3 6 3 4 3 5 3 7 4 0 4 3 4 7 4 3 4 4 4 6 5 1 5 0 5 6 5 0 5 7 5 8 0 9 0 10 0 8 0 10 0 11 0 12 1 11 1 10 1 12 1 10 1 13 1 13 2 10 2 9 2 13 2 9 2 14 2 14 3 15 3 12 3 14 3 12 3 13 3 15 4 8 4 11 4 15 4 11 4 12 4 14 5 9 5 8 5 14 5 8 5 15 5 16 0 17 0 18 0 16 0 18 0 19 0 20 1 19 1 18 1 20 1 18 1 21 1 21 2 18 2 17 2 21 2 17 2 22 2 22 3 23 3 20 3 22 3 20 3 21 3 23 4 16 4 19 4 23 4 19 4 20 4 22 5 17 5 16 5 22 5 16 5 23 5 24 0 25 0 26 0 24 0 26 0 27 0 28 1 27 1 26 1 28 1 26 1 29 1 29 2 26 2 25 2 29 2 25 2 30 2 30 3 31 3 28 3 30 3 28 3 29 3 31 4 24 4 27 4 31 4 27 4 28 4 30 5 25 5 24 5 30 5 24 5 31 5 32 0 33 0 34 0 32 0 34 0 35 0 36 1 35 1 34 1 36 1 34 1 37 1 37 2 34 2 33 2 37 2 33 2 38 2 38 3 39 3 36 3 38 3 36 3 37 3 39 4 32 4 35 4 39 4 35 4 36 4 38 5 33 5 32 5 38 5 32 5 39 5 40 0 41 0 42 0 40 0 42 0 43 0 44 1 43 1 42 1 44 1 42 1 45 1 45 2 42 2 41 2 45 2 41 2 46 2 46 3 47 3 44 3 46 3 44 3 45 3 47 4 40 4 43 4 47 4 43 4 44 4 46 5 41 5 40 5 46 5 40 5 47 5 48 0 49 0 50 0 48 0 50 0 51 0 52 1 51 1 50 1 52 1 50 1 53 1 53 2 50 2 49 2 53 2 49 2 54 2 54 3 55 3 52 3 54 3 52 3 53 3 55 4 48 4 51 4 55 4 51 4 52 4 54 5 49 5 48 5 54 5 48 5 55 5 56 0 57 0 58 0 56 0 58 0 59 0 60 1 59 1 58 1 60 1 58 1 61 1 61 2 58 2 57 2 61 2 57 2 62 2 62 3 63 3 60 3 62 3 60 3 61 3 63 4 56 4 59 4 63 4 59 4 60 4 62 5 57 5 56 5 62 5 56 5 63 5 64 0 65 0 66 0 64 0 66 0 67 0 68 1 67 1 66 1 68 1 66 1 69 1 69 2 66 2 65 2 69 2 65 2 70 2 70 3 71 3 68 3 70 3 68 3 69 3 71 4 64 4 67 4 71 4 67 4 68 4 70 5 65 5 64 5 70 5 64 5 71 5 72 0 73 0 74 0 72 0 74 0 75 0 76 1 75 1 74 1 76 1 74 1 77 1 77 2 74 2 73 2 77 2 73 2 78 2 78 3 79 3 76 3 78 3 76 3 77 3 79 4 72 4 75 4 79 4 75 4 76 4 78 5 73 5 72 5 78 5 72 5 79 5 80 2 81 2 82 2 80 2 82 2 83 2 83 5 82 5 84 5 83 5 84 5 85 5 85 4 84 4 86 4 85 4 86 4 87 4 87 1 86 1 81 1 87 1 81 1 80 1 83 3 85 3 87 3 83 3 87 3 80 3 84 0 82 0 81 0 84 0 81 0 86 0 88 0 90 0 89 0 88 0 91 0 90 0 92 5 90 5 91 5 92 5 93 5 90 5 93 2 89 2 90 2 93 2 94 2 89 2 94 3 92 3 95 3 94 3 93 3 92 3 95 4 91 4 88 4 95 4 92 4 91 4 94 1 88 1 89 1 94 1 95 1 88 1 96 0 98 0 97 0 96 0 99 0 98 0 100 5 98 5 99 5 100 5 101 5 98 5 101 2 97 2 98 2 101 2 102 2 97 2 102 3 100 3 103 3 102 3 101 3 100 3 103 4 99 4 96 4 103 4 100 4 99 4 102 1 96 1 97 1 102 1 103 1 96 1 104 0 106 0 105 0 104 0 107 0 106 0 108 5 106 5 107 5 108 5 109 5 106 5 109 2 105 2 106 2 109 2 110 2 105 2 110 3 108 3 111 3 110 3 109 3 108 3 111 4 107 4 104 4 111 4 108 4 107 4 110 1 104 1 105 1 110 1 111 1 104 1 112 0 114 0 113 0 112 0 115 0 114 0 116 5 114 5 115 5 116 5 117 5 114 5 117 2 113 2 114 2 117 2 118 2 113 2 118 3 116 3 119 3 118 3 117 3 116 3 119 4 115 4 112 4 119 4 116 4 115 4 118 1 112 1 113 1 118 1 119 1 112 1 120 0 122 0 121 0 120 0 123 0 122 0 124 5 122 5 123 5 124 5 125 5 122 5 125 2 121 2 122 2 125 2 126 2 121 2 126 3 124 3 127 3 126 3 125 3 124 3 127 4 123 4 120 4 127 4 124 4 123 4 126 1 120 1 121 1 126 1 127 1 120 1 128 0 130 0 129 0 128 0 131 0 130 0 132 5 130 5 131 5 132 5 133 5 130 5 133 2 129 2 130 2 133 2 134 2 129 2 134 3 132 3 135 3 134 3 133 3 132 3 135 4 131 4 128 4 135 4 132 4 131 4 134 1 128 1 129 1 134 1 135 1 128 1 136 0 138 0 137 0 136 0 139 0 138 0 140 5 138 5 139 5 140 5 141 5 138 5 141 2 137 2 138 2 141 2 142 2 137 2 142 3 140 3 143 3 142 3 141 3 140 3 143 4 139 4 136 4 143 4 140 4 139 4 142 1 136 1 137 1 142 1 143 1 136 1 144 0 146 0 145 0 144 0 147 0 146 0 148 5 146 5 147 5 148 5 149 5 146 5 149 2 145 2 146 2 149 2 150 2 145 2 150 3 148 3 151 3 150 3 149 3 148 3 151 4 147 4 144 4 151 4 148 4 147 4 150 1 144 1 145 1 150 1 151 1 144 1 152 0 154 0 153 0 152 0 155 0 154 0 156 5 154 5 155 5 156 5 157 5 154 5 157 2 153 2 154 2 157 2 158 2 153 2 158 3 156 3 159 3 158 3 157 3 156 3 159 4 155 4 152 4 159 4 156 4 155 4 158 1 152 1 153 1 158 1 159 1 152 1 160 0 162 0 161 0 160 0 163 0 162 0 164 5 162 5 163 5 164 5 165 5 162 5 165 2 161 2 162 2 165 2 166 2 161 2 166 3 164 3 167 3 166 3 165 3 164 3 167 4 163 4 160 4 167 4 164 4 163 4 166 1 160 1 161 1 166 1 167 1 160 1 168 2 170 2 169 2 168 2 171 2 170 2 171 1 172 1 170 1 171 1 173 1 172 1 173 4 174 4 172 4 173 4 175 4 174 4 175 5 169 5 174 5 175 5 168 5 169 5 171 3 175 3 173 3 171 3 168 3 175 3 172 0 169 0 170 0 172 0 174 0 169 0

+
+
+
+ + + + 0.01091998 -0.008999943 -0.001559972 0.01091998 -0.008999943 0.001559972 -0.01091998 -0.008999943 0.001559972 -0.01091998 -0.008999943 -0.001559972 0.01399999 0.007019996 -0.001559972 0.01399999 0.007019996 0.001559972 0.01399999 -0.007019996 0.001559972 0.01399999 -0.007019996 -0.001559972 0.01091998 0.007019996 0.001999974 -0.01091998 0.007019996 0.001999974 -0.01091998 -0.007019996 0.001999974 0.01091998 -0.007019996 0.001999974 -0.01399999 -0.007019996 -0.001559972 -0.01399999 -0.007019996 0.001559972 -0.01399999 0.007019996 0.001559972 -0.01399999 0.007019996 -0.001559972 -0.01091998 0.008999943 -0.001559972 -0.01091998 0.008999943 0.001559972 0.01091998 0.008999943 0.001559972 0.01091998 0.008999943 -0.001559972 -0.01091998 -0.007019996 -0.001999974 -0.01091998 0.007019996 -0.001999974 0.01091998 -0.007019996 -0.001999974 0.01091998 0.007019996 -0.001999974 + + + + + + + + + + 0 -1 0 1 0 0 0 0 1 -1 0 0 0 1 0 -0.1381187 -0.2148514 -0.966831 -0.1381187 -0.2148514 0.966831 -0.1381187 0.2148514 -0.966831 -0.1381187 0.2148514 0.966831 0.1381187 -0.2148514 -0.966831 0.1381187 -0.2148514 0.966831 0.1381187 0.2148514 -0.966831 0.1381187 0.2148514 0.966831 -0.1414214 0 -0.9899496 -0.5407575 -0.8411786 0 -0.5407578 -0.8411785 0 -0.1414214 0 0.9899496 -0.5407575 0.8411786 0 -0.5407578 0.8411785 0 0 0.2169303 -0.9761872 0 0.2169306 -0.9761871 0 0.2169303 0.9761872 0 0.2169306 0.9761871 0.5407578 0.8411785 0 0.5407575 0.8411786 0 0.1414214 0 -0.9899496 0.1414214 0 0.9899496 0.5407575 -0.8411786 0 0.5407578 -0.8411785 0 0 -0.2169303 -0.9761872 0 -0.2169306 -0.9761871 0 -0.2169303 0.9761872 0 -0.2169306 0.9761871 0 0 -1 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 0 2 0 3 0 4 1 5 1 6 1 4 1 6 1 7 1 8 2 9 2 10 2 8 2 10 2 11 2 12 3 13 3 14 3 12 3 14 3 15 3 16 4 17 4 18 4 16 4 18 4 19 4 20 5 3 5 12 5 2 6 10 6 13 6 21 7 15 7 16 7 9 8 17 8 14 8 22 9 7 9 0 9 11 10 1 10 6 10 23 11 19 11 4 11 8 12 5 12 18 12 21 13 20 13 12 13 21 13 12 13 15 13 3 14 2 14 13 14 3 15 13 15 12 15 10 16 9 16 14 16 10 16 14 16 13 16 17 17 16 17 15 17 17 18 15 18 14 18 23 19 21 19 16 19 23 20 16 20 19 20 9 21 8 21 18 21 9 22 18 22 17 22 5 23 4 23 19 23 5 24 19 24 18 24 22 25 23 25 4 25 22 25 4 25 7 25 8 26 11 26 6 26 8 26 6 26 5 26 1 27 0 27 7 27 1 28 7 28 6 28 20 29 22 29 0 29 20 30 0 30 3 30 11 31 10 31 2 31 11 32 2 32 1 32 21 33 23 33 22 33 21 33 22 33 20 33

+
+
+
+ + + + 0.01349288 0.003098845 0.001246988 0.002614974 0.01389831 0.001246988 0.002614974 0.01389831 -0.001246988 0.01349288 0.003098845 -0.001246988 0.0288853 0.02750301 0.001246988 0.0288853 0.02750301 -0.001246988 0.0269072 0.02946692 -0.001246988 0.0269072 0.02946692 0.001246988 0.01658421 0.01987266 0.001246988 0.01658421 0.01987266 -0.001246988 0.01936602 0.01711088 0.001246988 0.01936602 0.01711088 -0.001246988 0.01064378 0.01584881 -0.001246988 0.01538521 0.01114153 -0.001246988 0.01538521 0.01114153 0.001246988 0.01064378 0.01584881 0.001246988 -0.01349288 0.003098845 0.001246988 -0.01349288 0.003098845 -0.001246988 -0.002614974 0.01389831 -0.001246988 -0.002614974 0.01389831 0.001246988 -0.0288853 0.02750301 0.001246988 -0.0269072 0.02946692 0.001246988 -0.0269072 0.02946692 -0.001246988 -0.0288853 0.02750301 -0.001246988 -0.01658421 0.01987266 0.001246988 -0.01658421 0.01987266 -0.001246988 -0.01936602 0.01711088 0.001246988 -0.01936602 0.01711088 -0.001246988 -0.01064378 0.01584881 -0.001246988 -0.01538521 0.01114153 -0.001246988 -0.01538521 0.01114153 0.001246988 -0.01064378 0.01584881 0.001246988 0.01349288 -0.003098845 0.001246988 0.01349288 -0.003098845 -0.001246988 0.002614974 -0.01389831 -0.001246988 0.002614974 -0.01389831 0.001246988 0.0288853 -0.02750301 0.001246988 0.0269072 -0.02946692 0.001246988 0.0269072 -0.02946692 -0.001246988 0.0288853 -0.02750301 -0.001246988 0.01658421 -0.01987266 0.001246988 0.01658421 -0.01987266 -0.001246988 0.01936602 -0.01711088 0.001246988 0.01936602 -0.01711088 -0.001246988 0.01064378 -0.01584881 -0.001246988 0.01538521 -0.01114153 -0.001246988 0.01538521 -0.01114153 0.001246988 0.01064378 -0.01584881 0.001246988 -0.01349288 -0.003098845 0.001246988 -0.002614974 -0.01389831 0.001246988 -0.002614974 -0.01389831 -0.001246988 -0.01349288 -0.003098845 -0.001246988 -0.0288853 -0.02750301 0.001246988 -0.0288853 -0.02750301 -0.001246988 -0.0269072 -0.02946692 -0.001246988 -0.0269072 -0.02946692 0.001246988 -0.01658421 -0.01987266 0.001246988 -0.01658421 -0.01987266 -0.001246988 -0.01936602 -0.01711088 0.001246988 -0.01936602 -0.01711088 -0.001246988 -0.01064378 -0.01584881 -0.001246988 -0.01538521 -0.01114153 -0.001246988 -0.01538521 -0.01114153 0.001246988 -0.01064378 -0.01584881 0.001246988 -0.01551216 0.004768252 0.001246988 -0.0129494 0.006718754 0.001246988 -0.008020222 0.0102784 0.001246988 -0.003097176 0.01383805 0.001246988 -0.003097176 0.01383805 -0.001246988 -0.01551216 0.004768252 -0.001246988 0.006261169 0.0102784 0.001246988 0.006261169 0.0102784 -0.001246988 0.002675712 0.01383805 -0.001246988 0.002675712 0.01383805 0.001246988 0.01824802 0.001543164 0.001246988 0.01824802 0 0.001246988 0.01824802 0 -0.001246988 0.01824802 0.001543164 -0.001246988 -0.01551216 0 0.001246988 -0.01551216 0 -0.001246988 -0.01551216 0.001327097 0.001246988 -0.01551216 0.001327097 -0.001246988 0.0134322 0.003159105 0.001246988 0.0134322 0.003159105 -0.001246988 0.009846687 0.006718754 -0.001246988 0.009846687 0.006718754 0.001246988 -0.008020222 -0.0102784 0.001246988 -0.0129494 -0.006718754 0.001246988 -0.01551216 -0.004768252 0.001246988 -0.01551216 -0.004768252 -0.001246988 -0.003097176 -0.01383805 -0.001246988 -0.003097176 -0.01383805 0.001246988 0.006261169 -0.0102784 0.001246988 0.002675712 -0.01383805 0.001246988 0.002675712 -0.01383805 -0.001246988 0.006261169 -0.0102784 -0.001246988 0.01824802 -0.001543164 0.001246988 0.01824802 -0.001543164 -0.001246988 -0.01551216 -0.001327097 0.001246988 -0.01551216 -0.001327097 -0.001246988 0.0134322 -0.003159105 0.001246988 0.009846687 -0.006718754 0.001246988 0.009846687 -0.006718754 -0.001246988 0.0134322 -0.003159105 -0.001246988 -0.00999999 0.00999999 0.001311063 -0.00999999 0.01199996 0.001311063 -0.00999999 0.01199996 0.003311097 -0.00999999 0.00999999 0.003311097 0.00999999 0.01199996 0.001311063 0.00999999 0.01199996 0.003311097 0.00999999 0.00999999 0.001311063 0.00999999 0.00999999 0.003311097 -0.00999999 -0.00999999 0.001311063 -0.00999999 -0.00999999 0.003311097 -0.00999999 -0.01199996 0.003311097 -0.00999999 -0.01199996 0.001311063 0.00999999 -0.01199996 0.003311097 0.00999999 -0.01199996 0.001311063 0.00999999 -0.00999999 0.003311097 0.00999999 -0.00999999 0.001311063 -0.01551216 0.004768252 0.001246988 -0.0129494 0.006718754 0.001246988 -0.008020222 0.0102784 0.001246988 -0.01551216 0.004768252 -0.001246988 0.006261169 0.0102784 0.001246988 0.006261169 0.0102784 -0.001246988 0.01824802 0.001543164 0.001246988 0.01824802 0 0.001246988 0.01824802 0 -0.001246988 0.01824802 0.001543164 -0.001246988 -0.01551216 0 0.001246988 -0.01551216 0 -0.001246988 -0.01551216 0.001327097 0.001246988 -0.01551216 0.001327097 -0.001246988 0.0134322 0.003159105 0.001246988 0.0134322 0.003159105 -0.001246988 0.009846687 0.006718754 -0.001246988 0.009846687 0.006718754 0.001246988 -0.008020222 -0.0102784 0.001246988 -0.0129494 -0.006718754 0.001246988 -0.01551216 -0.004768252 0.001246988 -0.01551216 -0.004768252 -0.001246988 -0.003097176 -0.01383805 -0.001246988 -0.003097176 -0.01383805 0.001246988 0.006261169 -0.0102784 0.001246988 0.002675712 -0.01383805 0.001246988 0.002675712 -0.01383805 -0.001246988 0.006261169 -0.0102784 -0.001246988 0.01824802 -0.001543164 0.001246988 0.01824802 -0.001543164 -0.001246988 -0.01551216 -0.001327097 0.001246988 -0.01551216 -0.001327097 -0.001246988 0.0134322 -0.003159105 0.001246988 0.009846687 -0.006718754 0.001246988 0.009846687 -0.006718754 -0.001246988 0.0134322 -0.003159105 -0.001246988 -0.00999999 0.00999999 0.001311063 -0.00999999 0.00999999 0.003311097 -0.00999999 0.01199996 0.003311097 0.00999999 0.01199996 0.003311097 0.00999999 0.00999999 0.003311097 0.00999999 0.00999999 0.001311063 -0.00999999 -0.00999999 0.001311063 -0.00999999 -0.01199996 0.001311063 -0.00999999 -0.01199996 0.003311097 -0.00999999 -0.00999999 0.003311097 0.00999999 -0.01199996 0.001311063 0.00999999 -0.01199996 0.003311097 0.00999999 -0.00999999 0.001311063 0.00999999 -0.00999999 0.003311097 + + + + + + + + + + -0.7045438 -0.7096605 0 -0.7045438 -0.7096605 0 0.7045443 0.70966 0 0.7045433 0.7096611 0 -0.6807795 0.7324885 0 -0.6807794 0.7324886 0 0 0 1 0 0 1 0.7373957 -0.6754611 0 0.7373957 -0.675461 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.8319734 -0.5548156 0 0.8319732 -0.5548159 0 0 0 1 0 0 1 -0.5608213 0.827937 0 -0.5608218 0.8279366 0 -0.2360691 0.9717363 0 -0.236069 0.9717363 0 0 0 1 0 0 1 0.9734192 -0.229031 0 0.9734191 -0.2290314 0 0 0 -1 0.7045438 -0.7096605 0 0.7045439 -0.7096605 0 -0.7045432 0.7096611 0 -0.7045443 0.7096601 0 0.6807794 0.7324886 0 0.6807794 0.7324885 0 0 0 1 0 0 1 -0.7373958 -0.6754609 0 -0.7373957 -0.6754611 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.8319733 -0.5548158 0 -0.831973 -0.5548161 0 0 0 1 0 0 1 0.5608217 0.8279367 0 0.5608213 0.827937 0 0.2360689 0.9717363 0 0 0 1 0 0 1 -0.9734192 -0.2290311 0 -0.9734191 -0.2290314 0 0 0 -1 0 0 -1 -0.7045438 0.7096605 0 0.7045429 -0.7096614 0 0.704544 -0.7096604 0 -0.6807792 -0.7324887 0 -0.6807792 -0.7324886 0 0 0 1 0 0 1 0.7373957 0.6754611 0 0.7373955 0.6754612 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.8319733 0.5548158 0 0.8319734 0.5548156 0 0 0 1 0 0 1 -0.5608217 -0.8279367 0 -0.5608213 -0.827937 0 -0.2360693 -0.9717363 0 -0.2360693 -0.9717363 0 0 0 1 0 0 1 0.9734191 0.2290314 0 0.9734192 0.2290311 0 0 0 -1 0.7045438 0.7096605 0 0.7045438 0.7096605 0 -0.7045439 -0.7096604 0 0.6807792 -0.7324886 0 0.6807791 -0.7324888 0 0 0 1 0 0 1 -0.7373958 0.6754609 0 -0.7373956 0.6754612 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.8319734 0.5548156 0 -0.8319731 0.5548161 0 0 0 1 0 0 1 0.5608215 -0.8279368 0 0.5608215 -0.8279367 0 0.2360691 -0.9717363 0 0.236069 -0.9717363 0 -0.973419 0.2290314 0 -0.9734191 0.2290311 0 -3.70063e-6 1.16742e-6 -1 -0.5859354 0.8103578 0 -0.589901 0.8074757 0 -0.5923686 0.8054254 -0.01973915 0.7045438 0.7096606 0 1 0 0 0 -1 0 0 0 1 0 0 -1 0.7045436 0.7096607 0 0 0 1 0 0 1 -1 0 0 -1 -1.10705e-6 0 0 0 -1 0 0 1 0 0 1 0.3181167 0.9480516 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 -1.01069e-6 0.7045438 0.7096605 0 0.704544 0.7096604 0 -9.25141e-7 -1.1674e-6 -1 -0.589901 -0.8074756 0 -0.5859354 -0.8103578 4.80206e-7 -0.5923684 -0.8054255 -0.01973885 0.7045437 -0.7096606 0 0.7045438 -0.7096605 0 1 1.10391e-6 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0.7045435 -0.7096607 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0.3181167 -0.9480516 0 0 0 -1 0 0 -1 0 0 -1 -1.85029e-6 0 -1 -0.5859355 0.8103576 0 -0.5899011 0.8074756 0 -0.5923686 0.8054254 -0.01973855 0.7045439 0.7096605 0 0 0 1 0 0 -1 0 0 1 -1 -2.19824e-6 0 -1 1.09118e-6 0 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 -1 -2.7754e-6 -1.16739e-6 -1 -0.5899009 -0.8074757 0 -0.5859354 -0.8103578 4.80206e-7 -0.5923684 -0.8054254 -0.01973885 0.7045438 -0.7096606 0 0.7045438 -0.7096605 0 0 0 -1 0.7045436 -0.7096608 0 0.7045437 -0.7096607 0 0 0 1 0 0 -1 0 0 1 0 0 1 0.3181168 -0.9480515 0 0 0 -1 0 0 -1 0 0 -1 0.7045437 -0.7096607 0 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 1 2 1 3 1 4 2 5 2 6 2 4 3 6 3 7 3 8 4 7 4 6 4 8 5 6 5 9 5 10 6 4 6 7 6 10 7 7 7 8 7 11 8 5 8 4 8 11 9 4 9 10 9 9 10 6 10 5 10 9 11 5 11 11 11 12 12 9 12 11 12 12 13 11 13 13 13 13 14 11 14 10 14 13 15 10 15 14 15 14 16 10 16 8 16 14 17 8 17 15 17 15 18 8 18 9 18 15 19 9 19 12 19 1 20 15 20 12 20 1 21 12 21 2 21 0 22 14 22 15 22 0 23 15 23 1 23 3 24 13 24 14 24 3 25 14 25 0 25 2 26 12 26 13 26 2 26 13 26 3 26 16 27 17 27 18 27 16 28 18 28 19 28 20 29 21 29 22 29 20 30 22 30 23 30 24 31 25 31 22 31 24 32 22 32 21 32 26 33 24 33 21 33 26 34 21 34 20 34 27 35 26 35 20 35 27 36 20 36 23 36 25 37 27 37 23 37 25 38 23 38 22 38 28 39 29 39 27 39 28 40 27 40 25 40 29 41 30 41 26 41 29 42 26 42 27 42 30 43 31 43 24 43 30 44 24 44 26 44 31 45 28 45 25 45 31 46 25 46 24 46 19 47 18 47 28 47 19 47 28 47 31 47 16 48 19 48 31 48 16 49 31 49 30 49 17 50 16 50 30 50 17 51 30 51 29 51 18 52 17 52 29 52 18 53 29 53 28 53 32 54 33 54 34 54 32 54 34 54 35 54 36 55 37 55 38 55 36 56 38 56 39 56 40 57 41 57 38 57 40 58 38 58 37 58 42 59 40 59 37 59 42 60 37 60 36 60 43 61 42 61 36 61 43 62 36 62 39 62 41 63 43 63 39 63 41 64 39 64 38 64 44 65 45 65 43 65 44 66 43 66 41 66 45 67 46 67 42 67 45 68 42 68 43 68 46 69 47 69 40 69 46 70 40 70 42 70 47 71 44 71 41 71 47 72 41 72 40 72 35 73 34 73 44 73 35 74 44 74 47 74 32 75 35 75 47 75 32 76 47 76 46 76 33 77 32 77 46 77 33 78 46 78 45 78 34 26 33 26 45 26 34 79 45 79 44 79 48 80 49 80 50 80 48 81 50 81 51 81 52 82 53 82 54 82 52 82 54 82 55 82 56 83 55 83 54 83 56 84 54 84 57 84 58 85 52 85 55 85 58 86 55 86 56 86 59 87 53 87 52 87 59 88 52 88 58 88 57 89 54 89 53 89 57 90 53 90 59 90 60 91 57 91 59 91 60 92 59 92 61 92 61 93 59 93 58 93 61 94 58 94 62 94 62 95 58 95 56 95 62 96 56 96 63 96 63 97 56 97 57 97 63 98 57 98 60 98 49 99 63 99 60 99 49 100 60 100 50 100 48 49 62 49 63 49 48 23 63 23 49 23 51 101 61 101 62 101 51 102 62 102 48 102 50 79 60 79 61 79 50 26 61 26 51 26 64 103 65 103 66 103 66 104 67 104 68 104 68 105 69 105 64 105 66 106 68 106 64 106 70 81 71 81 72 81 70 107 72 107 73 107 74 108 75 108 76 108 74 108 76 108 77 108 75 109 78 109 79 109 75 109 79 109 76 109 80 110 78 110 75 110 80 16 75 16 74 16 77 26 76 26 79 26 77 111 79 111 81 111 82 107 83 107 84 107 82 112 84 112 85 112 64 113 82 113 85 113 64 114 85 114 65 114 65 16 85 16 70 16 65 16 70 16 66 16 80 115 64 115 69 115 80 115 69 115 81 115 78 115 80 115 81 115 78 116 81 116 79 116 83 117 77 117 81 117 83 26 81 26 69 26 64 118 80 118 74 118 64 119 74 119 82 119 82 120 74 120 77 120 82 120 77 120 83 120 84 121 83 121 69 121 69 122 68 122 72 122 71 123 84 123 69 123 69 124 72 124 71 124 66 16 70 16 73 16 66 16 73 16 67 16 67 125 73 125 72 125 67 126 72 126 68 126 85 127 84 127 71 127 85 128 71 128 70 128 86 129 87 129 88 129 88 130 89 130 90 130 90 131 91 131 86 131 88 132 90 132 86 132 92 133 93 133 94 133 92 134 94 134 95 134 96 135 97 135 76 135 96 108 76 108 75 108 98 136 96 136 75 136 98 137 75 137 78 137 97 138 99 138 79 138 97 139 79 139 76 139 100 140 101 140 102 140 100 140 102 140 103 140 88 141 87 141 101 141 88 142 101 142 100 142 87 16 86 16 92 16 87 16 92 16 101 16 98 115 99 115 89 115 98 115 89 115 88 115 78 115 79 115 99 115 78 115 99 115 98 115 103 143 89 143 99 143 103 144 99 144 97 144 88 145 100 145 96 145 88 146 96 146 98 146 100 147 103 147 97 147 100 147 97 147 96 147 89 148 103 148 102 148 95 26 94 26 90 26 89 149 102 149 95 149 95 150 90 150 89 150 86 16 91 16 93 16 86 16 93 16 92 16 91 109 90 109 94 109 91 109 94 109 93 109 101 134 92 134 95 134 101 133 95 133 102 133 104 108 105 108 106 108 104 108 106 108 107 108 105 109 108 109 109 109 105 109 109 109 106 109 108 115 110 115 111 115 108 115 111 115 109 115 110 125 104 125 107 125 110 125 107 125 111 125 105 16 104 16 110 16 105 16 110 16 108 16 109 26 111 26 107 26 109 26 107 26 106 26 112 108 113 108 114 108 112 108 114 108 115 108 115 125 114 125 116 125 115 125 116 125 117 125 117 115 116 115 118 115 117 115 118 115 119 115 119 109 118 109 113 109 119 109 113 109 112 109 115 16 117 16 119 16 115 16 119 16 112 16 116 26 114 26 113 26 116 26 113 26 118 26 120 151 121 151 122 151 122 152 67 152 68 152 68 153 123 153 120 153 122 154 68 154 120 154 124 128 125 128 72 128 124 155 72 155 73 155 126 108 127 108 128 108 126 108 128 108 129 108 127 109 130 109 131 109 127 109 131 109 128 109 132 156 130 156 127 156 132 16 127 16 126 16 129 26 128 26 131 26 129 157 131 157 133 157 134 107 135 107 136 107 134 112 136 112 137 112 120 158 134 158 137 158 120 16 137 16 121 16 121 16 137 16 124 16 121 16 124 16 122 16 132 115 120 115 123 115 132 115 123 115 133 115 130 159 132 159 133 159 130 160 133 160 131 160 135 161 129 161 133 161 135 26 133 26 123 26 120 162 132 162 126 162 120 16 126 16 134 16 134 120 126 120 129 120 134 120 129 120 135 120 136 163 135 163 123 163 123 26 68 26 72 26 125 164 136 164 123 164 123 165 72 165 125 165 122 16 124 16 73 16 122 16 73 16 67 16 137 107 136 107 125 107 137 155 125 155 124 155 138 166 139 166 140 166 140 167 141 167 142 167 142 168 143 168 138 168 140 169 142 169 138 169 144 170 145 170 146 170 144 171 146 171 147 171 148 108 149 108 128 108 148 108 128 108 127 108 150 16 148 16 127 16 150 16 127 16 130 16 149 172 151 172 131 172 149 26 131 26 128 26 152 173 153 173 154 173 152 174 154 174 155 174 140 141 139 141 153 141 140 175 153 175 152 175 139 16 138 16 144 16 139 16 144 16 153 16 150 115 151 115 141 115 150 115 141 115 140 115 130 115 131 115 151 115 130 115 151 115 150 115 155 26 141 26 151 26 155 176 151 176 149 176 140 177 152 177 148 177 140 178 148 178 150 178 152 179 155 179 149 179 152 179 149 179 148 179 141 180 155 180 154 180 147 26 146 26 142 26 141 181 154 181 147 181 147 182 142 182 141 182 138 16 143 16 145 16 138 16 145 16 144 16 143 109 142 109 146 109 143 109 146 109 145 109 153 27 144 27 147 27 153 183 147 183 154 183 156 115 157 115 158 115 156 115 158 115 105 115 105 125 158 125 159 125 105 125 159 125 108 125 108 108 159 108 160 108 108 108 160 108 161 108 161 109 160 109 157 109 161 109 157 109 156 109 105 26 108 26 161 26 105 26 161 26 156 26 159 16 158 16 157 16 159 16 157 16 160 16 162 115 163 115 164 115 162 115 164 115 165 115 163 109 166 109 167 109 163 109 167 109 164 109 166 108 168 108 169 108 166 108 169 108 167 108 168 125 162 125 165 125 168 125 165 125 169 125 163 26 162 26 168 26 163 26 168 26 166 26 167 16 169 16 165 16 167 16 165 16 164 16

+
+
+
+ + + + 0 0.003999948 -0.007499992 0 0.003999948 0.007499992 0.001530706 0.003695487 -0.007499992 0.001530706 0.003695487 0.007499992 0.002828419 0.002828419 -0.007499992 0.002828419 0.002828419 0.007499992 0.003695487 0.001530706 -0.007499992 0.003695487 0.001530706 0.007499992 0.003999948 0 -0.007499992 0.003999948 0 0.007499992 0.003695487 -0.001530706 -0.007499992 0.003695487 -0.001530706 0.007499992 0.002828419 -0.002828419 -0.007499992 0.002828419 -0.002828419 0.007499992 0.001530706 -0.003695487 -0.007499992 0.001530706 -0.003695487 0.007499992 0 -0.003999948 -0.007499992 0 -0.003999948 0.007499992 -0.001530706 -0.003695487 -0.007499992 -0.001530706 -0.003695487 0.007499992 -0.002828419 -0.002828419 -0.007499992 -0.002828419 -0.002828419 0.007499992 -0.003695487 -0.001530706 -0.007499992 -0.003695487 -0.001530706 0.007499992 -0.003999948 0 -0.007499992 -0.003999948 0 0.007499992 -0.003695487 0.001530706 -0.007499992 -0.003695487 0.001530706 0.007499992 -0.002828419 0.002828419 -0.007499992 -0.002828419 0.002828419 0.007499992 -0.001530706 0.003695487 -0.007499992 -0.001530706 0.003695487 0.007499992 -0.08789849 0.003999948 -0.007499992 -0.08789849 0.003999948 0.007499992 -0.08942919 0.003695487 -0.007499992 -0.08942919 0.003695487 0.007499992 -0.09072691 0.002828419 -0.007499992 -0.09072691 0.002828419 0.007499992 -0.09159398 0.001530706 -0.007499992 -0.09159398 0.001530706 0.007499992 -0.0918985 0 -0.007499992 -0.0918985 0 0.007499992 -0.09159398 -0.001530706 -0.007499992 -0.09159398 -0.001530706 0.007499992 -0.09072691 -0.002828419 -0.007499992 -0.09072691 -0.002828419 0.007499992 -0.08942919 -0.003695487 -0.007499992 -0.08942919 -0.003695487 0.007499992 -0.08789849 -0.003999948 -0.007499992 -0.08789849 -0.003999948 0.007499992 -0.08636772 -0.003695487 -0.007499992 -0.08636772 -0.003695487 0.007499992 -0.08507007 -0.002828419 -0.007499992 -0.08507007 -0.002828419 0.007499992 -0.08420294 -0.001530706 -0.007499992 -0.08420294 -0.001530706 0.007499992 -0.08389848 0 -0.007499992 -0.08389848 0 0.007499992 -0.08420294 0.001530706 -0.007499992 -0.08420294 0.001530706 0.007499992 -0.08507007 0.002828419 -0.007499992 -0.08507007 0.002828419 0.007499992 -0.08636772 0.003695487 -0.007499992 -0.08636772 0.003695487 0.007499992 0 -0.0918985 -0.007499992 0 -0.0918985 0.007499992 0.001530706 -0.09159398 -0.007499992 0.001530706 -0.09159398 0.007499992 0.002828419 -0.09072691 -0.007499992 0.002828419 -0.09072691 0.007499992 0.003695487 -0.08942919 -0.007499992 0.003695487 -0.08942919 0.007499992 0.003999948 -0.08789849 -0.007499992 0.003999948 -0.08789849 0.007499992 0.003695487 -0.08636772 -0.007499992 0.003695487 -0.08636772 0.007499992 0.002828419 -0.08507007 -0.007499992 0.002828419 -0.08507007 0.007499992 0.001530706 -0.08420294 -0.007499992 0.001530706 -0.08420294 0.007499992 0 -0.08389848 -0.007499992 0 -0.08389848 0.007499992 -0.001530706 -0.08420294 -0.007499992 -0.001530706 -0.08420294 0.007499992 -0.002828419 -0.08507007 -0.007499992 -0.002828419 -0.08507007 0.007499992 -0.003695487 -0.08636772 -0.007499992 -0.003695487 -0.08636772 0.007499992 -0.003999948 -0.08789849 -0.007499992 -0.003999948 -0.08789849 0.007499992 -0.003695487 -0.08942919 -0.007499992 -0.003695487 -0.08942919 0.007499992 -0.002828419 -0.09072691 -0.007499992 -0.002828419 -0.09072691 0.007499992 -0.001530706 -0.09159398 -0.007499992 -0.001530706 -0.09159398 0.007499992 -0.08789849 -0.0918985 -0.007499992 -0.08789849 -0.0918985 0.007499992 -0.08942919 -0.09159398 -0.007499992 -0.08942919 -0.09159398 0.007499992 -0.09072691 -0.09072691 -0.007499992 -0.09072691 -0.09072691 0.007499992 -0.09159398 -0.08942919 -0.007499992 -0.09159398 -0.08942919 0.007499992 -0.09189844 -0.08789849 -0.007499992 -0.09189844 -0.08789849 0.007499992 -0.09159398 -0.08636772 -0.007499992 -0.09159398 -0.08636772 0.007499992 -0.09072691 -0.08507007 -0.007499992 -0.09072691 -0.08507007 0.007499992 -0.08942919 -0.08420294 -0.007499992 -0.08942919 -0.08420294 0.007499992 -0.08789849 -0.08389848 -0.007499992 -0.08789849 -0.08389848 0.007499992 -0.08636772 -0.08420294 -0.007499992 -0.08636772 -0.08420294 0.007499992 -0.08507001 -0.08507007 -0.007499992 -0.08507001 -0.08507007 0.007499992 -0.08420294 -0.08636772 -0.007499992 -0.08420294 -0.08636772 0.007499992 -0.08389848 -0.08789849 -0.007499992 -0.08389848 -0.08789849 0.007499992 -0.08420294 -0.08942919 -0.007499992 -0.08420294 -0.08942919 0.007499992 -0.08507001 -0.09072691 -0.007499992 -0.08507001 -0.09072691 0.007499992 -0.08636772 -0.09159398 -0.007499992 -0.08636772 -0.09159398 0.007499992 + + + + + + + + + + 0.1950904 0.9807854 0 0.5555704 0.8314697 0 0.8314695 0.5555704 0 0.9807853 0.1950905 0 0.9807854 -0.1950903 0 0.8314695 -0.5555704 0 0.5555704 -0.8314697 0 0.1950903 -0.9807854 0 -0.1950904 -0.9807853 0 -0.5555703 -0.8314696 0 -0.8314693 -0.5555707 0 -0.9807853 -0.1950905 0 -0.9807854 0.1950902 0 -0.8314696 0.5555703 0 0 0 1 -0.5555704 0.8314695 0 -0.1950902 0.9807853 0 3.21555e-7 0 -1 -0.1950899 0.9807854 0 -0.5555716 0.8314688 0 -0.8314738 0.5555639 0 -0.9807836 0.1950989 0 -0.9807875 -0.1950799 0 -0.8314647 -0.5555776 0 -0.5555716 -0.8314688 0 -0.1950899 -0.9807854 0 0.1950899 -0.9807854 0 0.555576 -0.8314658 0 0.8314738 -0.5555641 0 0.9807856 -0.1950893 0 0.9807856 0.1950893 0 0.8314645 0.555578 0 -3.21555e-7 0 1 0.5555672 0.8314718 0 0.1950898 0.9807854 0 0 0 -1 0.1950909 -0.9807853 0 0.5555703 -0.8314696 0 0.831469 -0.5555712 0 0.9807854 -0.1950899 0 0.9807854 0.1950899 0 0.8314687 0.5555716 0 0.5555704 0.8314695 0 0.1950908 0.9807852 0 -0.195091 0.9807852 0 -0.5555705 0.8314695 0 -0.8314687 0.5555716 0 -0.9807854 0.1950899 0 -0.9807854 -0.1950899 0 -0.8314692 -0.555571 0 -2.27374e-7 0 1 -0.5555703 -0.8314696 0 -0.1950909 -0.9807853 0 0 0 -1 -0.1950859 -0.9807862 0 -0.5555715 -0.8314688 0 -0.83147 -0.5555697 0 -0.9807856 -0.1950891 0 -0.9807873 0.1950803 0 -0.8314655 0.5555766 0 -0.5555762 0.8314658 0 -0.1950859 0.9807862 0 0.1950859 0.9807862 0 0.5555715 0.8314688 0 0.8314746 0.5555627 0 0.9807856 0.1950891 0 0.9807835 -0.1950995 0 0.83147 -0.5555697 0 -5.48928e-7 0 1 0.5555669 -0.8314719 0 0.1950859 -0.9807862 0 0.8314697 0.5555703 0 0.9807853 0.1950902 0 0.5555704 -0.8314695 0 -0.8314696 -0.5555703 0 -0.9807854 -0.1950902 0 -0.9807852 0.1950908 0 1.95137e-6 0 1 1.95137e-6 0 1 -1.95137e-6 0 1 -0.5555704 0.8314696 0 -1.95137e-6 0 -1 -3.90274e-6 0 -1 1.95137e-6 0 -1 1.95137e-6 0 -1 3.90274e-6 0 -1 -4.54747e-7 0 -1 -0.1950899 0.9807854 0 -0.5555715 0.8314688 0 -0.8314647 0.5555778 0 -0.9807875 0.1950798 0 -0.9807836 -0.1950989 0 -0.8314738 -0.5555639 0 -0.1950899 -0.9807854 0 0.1950899 -0.9807854 0 0.5555669 -0.831472 0 0.8314646 -0.5555779 0 0.8314736 0.5555643 0 9.75681e-7 0 1 -7.41687e-7 0 1 9.75679e-7 0 1 -9.75679e-7 0 1 4.54747e-7 0 1 0.5555763 0.8314656 0 0.1950898 0.9807854 0 7.41687e-7 0 -1 -1.95136e-6 0 -1 -1.48338e-6 0 -1 1.95136e-6 0 -1 -2.27374e-7 0 -1 0.195091 -0.9807853 0 0.8314689 -0.5555714 0 0.9807854 -0.1950899 0 0.9807855 0.1950896 0 0.8314689 0.5555712 0 0.1950908 0.9807852 0 -0.195091 0.9807852 0 -0.5555704 0.8314697 0 -0.8314689 0.5555712 0 -0.9807854 0.1950899 0 -0.9807853 -0.1950902 0 -0.8314691 -0.555571 0 -1.95136e-6 0 1 -1.95133e-6 0 1 -4.87839e-7 0 1 1.95133e-6 0 1 1.95136e-6 0 1 -0.5555702 -0.8314698 0 -0.195091 -0.9807853 0 -1.95142e-6 0 -1 1.95142e-6 0 -1 9.75709e-7 0 -1 -0.5555762 -0.8314658 0 -0.8314655 -0.5555766 0 -0.9807875 -0.1950795 0 -0.83147 0.5555697 0 0.5555669 0.8314719 0 0.83147 0.5555697 0 0.9807837 0.1950986 0 0.8314746 -0.5555627 0 0.5555715 -0.8314688 0 9.75724e-7 0 -1 -1.95132e-6 0 -1 -9.75633e-7 0 -1 + + + + + + + + + + 1 1 0.9375 0.5 1 0.5 0.9375 1 0.875 0.5 0.9375 0.5 0.875 1 0.8125 0.5 0.875 0.5 0.8125 1 0.75 0.5 0.8125 0.5 0.75 1 0.6875 0.5 0.75 0.5 0.6875 1 0.625 0.5 0.6875 0.5 0.625 1 0.5625 0.5 0.625 0.5 0.5625 1 0.5 0.5 0.5625 0.5 0.5 1 0.4375 0.5 0.5 0.5 0.4375 1 0.375 0.5 0.4375 0.5 0.375 1 0.3125 0.5 0.375 0.5 0.3125 1 0.25 0.5 0.3125 0.5 0.25 1 0.1875 0.5 0.25 0.5 0.1875 1 0.125 0.5 0.1875 0.5 0.08029437 0.08029437 0.4197056 0.08029437 0.4197056 0.4197056 0.125 1 0.0625 0.5 0.125 0.5 0.0625 1 0 0.5 0.0625 0.5 0.5282689 0.341844 0.658156 0.4717311 0.841844 0.02826887 0.9375 0.5 1 1 1 0.5 0.875 0.5 0.9375 1 0.9375 0.5 0.8125 0.5 0.875 1 0.875 0.5 0.75 0.5 0.8125 1 0.8125 0.5 0.6875 0.5 0.75 1 0.75 0.5 0.625 0.5 0.6875 1 0.6875 0.5 0.5625 0.5 0.625 1 0.625 0.5 0.5 0.5 0.5625 1 0.5625 0.5 0.4375 0.5 0.5 1 0.5 0.5 0.375 0.5 0.4375 1 0.4375 0.5 0.3125 0.5 0.375 1 0.375 0.5 0.25 0.5 0.3125 1 0.3125 0.5 0.1875 0.5 0.25 1 0.25 0.5 0.125 0.5 0.1875 1 0.1875 0.5 0.08029431 0.4197056 0.25 0.49 0.25 0.00999999 0.0625 0.5 0.125 1 0.125 0.5 0 0.5 0.0625 1 0.0625 0.5 0.5282689 0.341844 0.658156 0.02826887 0.9717311 0.1581559 0.9375 0.5 1 1 1 0.5 0.875 0.5 0.9375 1 0.9375 0.5 0.8125 0.5 0.875 1 0.875 0.5 0.75 0.5 0.8125 1 0.8125 0.5 0.6875 0.5 0.75 1 0.75 0.5 0.625 0.5 0.6875 1 0.6875 0.5 0.5625 0.5 0.625 1 0.625 0.5 0.5 0.5 0.5625 1 0.5625 0.5 0.4375 0.5 0.5 1 0.5 0.5 0.375 0.5 0.4375 1 0.4375 0.5 0.3125 0.5 0.375 1 0.375 0.5 0.25 0.5 0.3125 1 0.3125 0.5 0.1875 0.5 0.25 1 0.25 0.5 0.125 0.5 0.1875 1 0.1875 0.5 0.08029437 0.08029437 0.00999999 0.25 0.25 0.49 0.0625 0.5 0.125 1 0.125 0.5 0 0.5 0.0625 1 0.0625 0.5 0.841844 0.02826887 0.9717311 0.1581559 0.841844 0.4717311 1 1 0.9375 0.5 1 0.5 0.9375 1 0.875 0.5 0.9375 0.5 0.875 1 0.8125 0.5 0.875 0.5 0.8125 1 0.75 0.5 0.8125 0.5 0.75 1 0.6875 0.5 0.75 0.5 0.6875 1 0.625 0.5 0.6875 0.5 0.625 1 0.5625 0.5 0.625 0.5 0.5625 1 0.5 0.5 0.5625 0.5 0.5 1 0.4375 0.5 0.5 0.5 0.4375 1 0.375 0.5 0.4375 0.5 0.375 1 0.3125 0.5 0.375 0.5 0.3125 1 0.25 0.5 0.3125 0.5 0.25 1 0.1875 0.5 0.25 0.5 0.1875 1 0.125 0.5 0.1875 0.5 0.4197056 0.08029437 0.49 0.25 0.4197056 0.4197056 0.125 1 0.0625 0.5 0.125 0.5 0.0625 1 0 0.5 0.0625 0.5 0.9717311 0.341844 0.841844 0.02826887 0.5282689 0.1581559 1 1 0.9375 1 0.9375 0.5 0.9375 1 0.875 1 0.875 0.5 0.875 1 0.8125 1 0.8125 0.5 0.8125 1 0.75 1 0.75 0.5 0.75 1 0.6875 1 0.6875 0.5 0.6875 1 0.625 1 0.625 0.5 0.625 1 0.5625 1 0.5625 0.5 0.5625 1 0.5 1 0.5 0.5 0.5 1 0.4375 1 0.4375 0.5 0.4375 1 0.375 1 0.375 0.5 0.375 1 0.3125 1 0.3125 0.5 0.3125 1 0.25 1 0.25 0.5 0.25 1 0.1875 1 0.1875 0.5 0.1875 1 0.125 1 0.125 0.5 0.4197056 0.4197056 0.341844 0.4717311 0.25 0.49 0.25 0.49 0.1581559 0.4717311 0.08029431 0.4197056 0.08029431 0.4197056 0.02826893 0.341844 0.00999999 0.25 0.00999999 0.25 0.02826887 0.1581559 0.08029437 0.08029437 0.08029437 0.08029437 0.1581559 0.02826887 0.4197056 0.08029437 0.1581559 0.02826887 0.25 0.00999999 0.4197056 0.08029437 0.25 0.00999999 0.341844 0.02826887 0.4197056 0.08029437 0.4197056 0.08029437 0.4717311 0.1581559 0.49 0.25 0.49 0.25 0.4717311 0.341844 0.4197056 0.08029437 0.4717311 0.341844 0.4197056 0.4197056 0.4197056 0.08029437 0.4197056 0.4197056 0.25 0.49 0.08029437 0.08029437 0.25 0.49 0.08029431 0.4197056 0.08029437 0.08029437 0.08029431 0.4197056 0.00999999 0.25 0.08029437 0.08029437 0.125 1 0.0625 1 0.0625 0.5 0.0625 1 0 1 0 0.5 0.658156 0.4717311 0.75 0.49 0.841844 0.4717311 0.841844 0.4717311 0.9197056 0.4197056 0.9717311 0.341844 0.9717311 0.341844 0.99 0.25 0.9717311 0.1581559 0.9717311 0.1581559 0.9197056 0.08029437 0.9717311 0.341844 0.9197056 0.08029437 0.841844 0.02826887 0.9717311 0.341844 0.841844 0.02826887 0.75 0.00999999 0.658156 0.02826887 0.658156 0.02826887 0.5802944 0.08029437 0.5282689 0.1581559 0.5282689 0.1581559 0.51 0.25 0.5282689 0.341844 0.5282689 0.341844 0.5802944 0.4197056 0.658156 0.4717311 0.658156 0.4717311 0.841844 0.4717311 0.841844 0.02826887 0.841844 0.4717311 0.9717311 0.341844 0.841844 0.02826887 0.841844 0.02826887 0.658156 0.02826887 0.5282689 0.1581559 0.5282689 0.1581559 0.5282689 0.341844 0.841844 0.02826887 0.9375 0.5 0.9375 1 1 1 0.875 0.5 0.875 1 0.9375 1 0.8125 0.5 0.8125 1 0.875 1 0.75 0.5 0.75 1 0.8125 1 0.6875 0.5 0.6875 1 0.75 1 0.625 0.5 0.625 1 0.6875 1 0.5625 0.5 0.5625 1 0.625 1 0.5 0.5 0.5 1 0.5625 1 0.4375 0.5 0.4375 1 0.5 1 0.375 0.5 0.375 1 0.4375 1 0.3125 0.5 0.3125 1 0.375 1 0.25 0.5 0.25 1 0.3125 1 0.1875 0.5 0.1875 1 0.25 1 0.125 0.5 0.125 1 0.1875 1 0.25 0.49 0.341844 0.4717311 0.4197056 0.4197056 0.4197056 0.4197056 0.4717311 0.341844 0.49 0.25 0.49 0.25 0.4717311 0.1581559 0.25 0.00999999 0.4717311 0.1581559 0.4197056 0.08029437 0.25 0.00999999 0.4197056 0.08029437 0.341844 0.02826887 0.25 0.00999999 0.25 0.00999999 0.1581559 0.02826887 0.08029437 0.08029437 0.08029437 0.08029437 0.02826887 0.1581559 0.00999999 0.25 0.00999999 0.25 0.02826893 0.341844 0.08029431 0.4197056 0.08029431 0.4197056 0.1581559 0.4717311 0.25 0.49 0.25 0.49 0.4197056 0.4197056 0.25 0.00999999 0.4197056 0.4197056 0.49 0.25 0.25 0.00999999 0.25 0.00999999 0.08029437 0.08029437 0.00999999 0.25 0.00999999 0.25 0.08029431 0.4197056 0.25 0.00999999 0.0625 0.5 0.0625 1 0.125 1 0 0.5 0 1 0.0625 1 0.841844 0.4717311 0.75 0.49 0.658156 0.4717311 0.658156 0.4717311 0.5802944 0.4197056 0.841844 0.4717311 0.5802944 0.4197056 0.5282689 0.341844 0.841844 0.4717311 0.5282689 0.341844 0.51 0.25 0.5282689 0.1581559 0.5282689 0.1581559 0.5802944 0.08029437 0.5282689 0.341844 0.5802944 0.08029437 0.658156 0.02826887 0.5282689 0.341844 0.658156 0.02826887 0.75 0.00999999 0.9717311 0.1581559 0.75 0.00999999 0.841844 0.02826887 0.9717311 0.1581559 0.841844 0.02826887 0.9197056 0.08029437 0.9717311 0.1581559 0.9717311 0.1581559 0.99 0.25 0.9717311 0.341844 0.9717311 0.341844 0.9197056 0.4197056 0.9717311 0.1581559 0.9197056 0.4197056 0.841844 0.4717311 0.9717311 0.1581559 0.841844 0.4717311 0.5282689 0.341844 0.9717311 0.1581559 0.9375 0.5 0.9375 1 1 1 0.875 0.5 0.875 1 0.9375 1 0.8125 0.5 0.8125 1 0.875 1 0.75 0.5 0.75 1 0.8125 1 0.6875 0.5 0.6875 1 0.75 1 0.625 0.5 0.625 1 0.6875 1 0.5625 0.5 0.5625 1 0.625 1 0.5 0.5 0.5 1 0.5625 1 0.4375 0.5 0.4375 1 0.5 1 0.375 0.5 0.375 1 0.4375 1 0.3125 0.5 0.3125 1 0.375 1 0.25 0.5 0.25 1 0.3125 1 0.1875 0.5 0.1875 1 0.25 1 0.125 0.5 0.125 1 0.1875 1 0.25 0.49 0.341844 0.4717311 0.49 0.25 0.341844 0.4717311 0.4197056 0.4197056 0.49 0.25 0.4197056 0.4197056 0.4717311 0.341844 0.49 0.25 0.49 0.25 0.4717311 0.1581559 0.4197056 0.08029437 0.4197056 0.08029437 0.341844 0.02826887 0.25 0.00999999 0.25 0.00999999 0.1581559 0.02826887 0.08029437 0.08029437 0.08029437 0.08029437 0.02826887 0.1581559 0.00999999 0.25 0.00999999 0.25 0.02826893 0.341844 0.08029431 0.4197056 0.08029431 0.4197056 0.1581559 0.4717311 0.00999999 0.25 0.1581559 0.4717311 0.25 0.49 0.00999999 0.25 0.49 0.25 0.4197056 0.08029437 0.25 0.49 0.4197056 0.08029437 0.25 0.00999999 0.25 0.49 0.25 0.00999999 0.08029437 0.08029437 0.25 0.49 0.0625 0.5 0.0625 1 0.125 1 0 0.5 0 1 0.0625 1 0.841844 0.4717311 0.75 0.49 0.658156 0.4717311 0.658156 0.4717311 0.5802944 0.4197056 0.5282689 0.341844 0.5282689 0.341844 0.51 0.25 0.5282689 0.1581559 0.5282689 0.1581559 0.5802944 0.08029437 0.5282689 0.341844 0.5802944 0.08029437 0.658156 0.02826887 0.5282689 0.341844 0.658156 0.02826887 0.75 0.00999999 0.841844 0.02826887 0.841844 0.02826887 0.9197056 0.08029437 0.9717311 0.1581559 0.9717311 0.1581559 0.99 0.25 0.841844 0.4717311 0.99 0.25 0.9717311 0.341844 0.841844 0.4717311 0.9717311 0.341844 0.9197056 0.4197056 0.841844 0.4717311 0.841844 0.4717311 0.658156 0.4717311 0.658156 0.02826887 0.658156 0.4717311 0.5282689 0.341844 0.658156 0.02826887 0.658156 0.02826887 0.841844 0.02826887 0.841844 0.4717311 1 1 0.9375 1 0.9375 0.5 0.9375 1 0.875 1 0.875 0.5 0.875 1 0.8125 1 0.8125 0.5 0.8125 1 0.75 1 0.75 0.5 0.75 1 0.6875 1 0.6875 0.5 0.6875 1 0.625 1 0.625 0.5 0.625 1 0.5625 1 0.5625 0.5 0.5625 1 0.5 1 0.5 0.5 0.5 1 0.4375 1 0.4375 0.5 0.4375 1 0.375 1 0.375 0.5 0.375 1 0.3125 1 0.3125 0.5 0.3125 1 0.25 1 0.25 0.5 0.25 1 0.1875 1 0.1875 0.5 0.1875 1 0.125 1 0.125 0.5 0.4197056 0.4197056 0.341844 0.4717311 0.25 0.49 0.25 0.49 0.1581559 0.4717311 0.08029431 0.4197056 0.08029431 0.4197056 0.02826893 0.341844 0.00999999 0.25 0.00999999 0.25 0.02826887 0.1581559 0.08029431 0.4197056 0.02826887 0.1581559 0.08029437 0.08029437 0.08029431 0.4197056 0.08029437 0.08029437 0.1581559 0.02826887 0.25 0.00999999 0.25 0.00999999 0.341844 0.02826887 0.4197056 0.08029437 0.4197056 0.08029437 0.4717311 0.1581559 0.49 0.25 0.49 0.25 0.4717311 0.341844 0.4197056 0.4197056 0.4197056 0.4197056 0.25 0.49 0.08029437 0.08029437 0.25 0.49 0.08029431 0.4197056 0.08029437 0.08029437 0.08029437 0.08029437 0.25 0.00999999 0.4197056 0.4197056 0.25 0.00999999 0.4197056 0.08029437 0.4197056 0.4197056 0.125 1 0.0625 1 0.0625 0.5 0.0625 1 0 1 0 0.5 0.658156 0.4717311 0.75 0.49 0.9717311 0.341844 0.75 0.49 0.841844 0.4717311 0.9717311 0.341844 0.841844 0.4717311 0.9197056 0.4197056 0.9717311 0.341844 0.9717311 0.341844 0.99 0.25 0.841844 0.02826887 0.99 0.25 0.9717311 0.1581559 0.841844 0.02826887 0.9717311 0.1581559 0.9197056 0.08029437 0.841844 0.02826887 0.841844 0.02826887 0.75 0.00999999 0.5282689 0.1581559 0.75 0.00999999 0.658156 0.02826887 0.5282689 0.1581559 0.658156 0.02826887 0.5802944 0.08029437 0.5282689 0.1581559 0.5282689 0.1581559 0.51 0.25 0.5282689 0.341844 0.5282689 0.341844 0.5802944 0.4197056 0.658156 0.4717311 0.5282689 0.1581559 0.5282689 0.341844 0.658156 0.4717311 0.658156 0.4717311 0.9717311 0.341844 0.5282689 0.1581559 + + + + + + + + + + + + + + +

1 0 0 2 0 1 0 0 2 3 1 3 4 1 4 2 1 5 5 2 6 6 2 7 4 2 8 7 3 9 8 3 10 6 3 11 9 4 12 10 4 13 8 4 14 11 5 15 12 5 16 10 5 17 13 6 18 14 6 19 12 6 20 15 7 21 16 7 22 14 7 23 17 8 24 18 8 25 16 8 26 19 9 27 20 9 28 18 9 29 21 10 30 22 10 31 20 10 32 23 11 33 24 11 34 22 11 35 25 12 36 26 12 37 24 12 38 27 13 39 28 13 40 26 13 41 21 14 42 13 14 43 5 14 44 29 15 45 30 15 46 28 15 47 31 16 48 0 16 49 30 16 50 26 17 51 30 17 52 14 17 53 34 18 54 33 18 55 32 18 56 36 19 57 35 19 58 34 19 59 38 20 60 37 20 61 36 20 62 40 21 63 39 21 64 38 21 65 42 22 66 41 22 67 40 22 68 44 23 69 43 23 70 42 23 71 46 24 72 45 24 73 44 24 74 48 25 75 47 25 76 46 25 77 50 26 78 49 26 79 48 26 80 52 27 81 51 27 82 50 27 83 54 28 84 53 28 85 52 28 86 56 29 87 55 29 88 54 29 89 58 30 90 57 30 91 56 30 92 60 31 93 59 31 94 58 31 95 61 32 96 33 32 97 49 32 98 62 33 99 61 33 100 60 33 101 32 34 102 63 34 103 62 34 104 58 35 105 50 35 106 42 35 107 66 36 108 65 36 109 64 36 110 68 37 111 67 37 112 66 37 113 70 38 114 69 38 115 68 38 116 72 39 117 71 39 118 70 39 119 74 40 120 73 40 121 72 40 122 76 41 123 75 41 124 74 41 125 78 42 126 77 42 127 76 42 128 80 43 129 79 43 130 78 43 131 82 44 132 81 44 133 80 44 134 84 45 135 83 45 136 82 45 137 86 46 138 85 46 139 84 46 140 88 47 141 87 47 142 86 47 143 90 48 144 89 48 145 88 48 146 92 49 147 91 49 148 90 49 149 85 50 150 89 50 151 65 50 152 94 51 153 93 51 154 92 51 155 64 52 156 95 52 157 94 52 158 78 53 159 74 53 160 66 53 161 97 54 162 98 54 163 96 54 164 99 55 165 100 55 166 98 55 167 101 56 168 102 56 169 100 56 170 103 57 171 104 57 172 102 57 173 105 58 174 106 58 175 104 58 176 107 59 177 108 59 178 106 59 179 109 60 180 110 60 181 108 60 182 111 61 183 112 61 184 110 61 185 113 62 186 114 62 187 112 62 188 115 63 189 116 63 190 114 63 191 117 64 192 118 64 193 116 64 194 119 65 195 120 65 196 118 65 197 121 66 198 122 66 199 120 66 200 123 67 201 124 67 202 122 67 203 109 68 204 105 68 205 101 68 206 125 69 207 126 69 208 124 69 209 127 70 210 96 70 211 126 70 212 102 53 213 110 53 214 118 53 215 1 0 216 3 0 217 2 0 218 3 1 219 5 1 220 4 1 221 5 71 222 7 71 223 6 71 224 7 72 225 9 72 226 8 72 227 9 4 228 11 4 229 10 4 230 11 5 231 13 5 232 12 5 233 13 73 234 15 73 235 14 73 236 15 7 237 17 7 238 16 7 239 17 8 240 19 8 241 18 8 242 19 51 243 21 51 244 20 51 245 21 74 246 23 74 247 22 74 248 23 75 249 25 75 250 24 75 251 25 76 252 27 76 253 26 76 254 27 13 255 29 13 256 28 13 257 5 14 258 3 14 259 1 14 260 1 14 261 31 14 262 29 14 263 29 77 264 27 77 265 25 77 266 25 78 267 23 78 268 21 78 269 21 14 270 19 14 271 13 14 272 19 14 273 17 14 274 13 14 275 17 14 276 15 14 277 13 14 278 13 79 279 11 79 280 9 79 281 9 14 282 7 14 283 13 14 284 7 14 285 5 14 286 13 14 287 5 14 288 1 14 289 21 14 290 1 14 291 29 14 292 21 14 293 29 14 294 25 14 295 21 14 296 29 80 297 31 80 298 30 80 299 31 16 300 1 16 301 0 16 302 30 53 303 0 53 304 2 53 305 2 81 306 4 81 307 6 81 308 6 82 309 8 82 310 10 82 311 10 53 312 12 53 313 6 53 314 12 53 315 14 53 316 6 53 317 14 53 318 16 53 319 18 53 320 18 83 321 20 83 322 22 83 323 22 84 324 24 84 325 26 84 326 26 85 327 28 85 328 30 85 329 30 53 330 2 53 331 14 53 332 2 53 333 6 53 334 14 53 335 14 53 336 18 53 337 22 53 338 22 86 339 26 86 340 14 86 341 34 87 342 35 87 343 33 87 344 36 88 345 37 88 346 35 88 347 38 89 348 39 89 349 37 89 350 40 90 351 41 90 352 39 90 353 42 91 354 43 91 355 41 91 356 44 92 357 45 92 358 43 92 359 46 55 360 47 55 361 45 55 362 48 93 363 49 93 364 47 93 365 50 94 366 51 94 367 49 94 368 52 95 369 53 95 370 51 95 371 54 96 372 55 96 373 53 96 374 56 29 375 57 29 376 55 29 377 58 30 378 59 30 379 57 30 380 60 97 381 61 97 382 59 97 383 33 98 384 35 98 385 37 98 386 37 14 387 39 14 388 41 14 389 41 99 390 43 99 391 49 99 392 43 14 393 45 14 394 49 14 395 45 100 396 47 100 397 49 100 398 49 101 399 51 101 400 53 101 401 53 14 402 55 14 403 57 14 404 57 14 405 59 14 406 61 14 407 61 14 408 63 14 409 33 14 410 33 14 411 37 14 412 49 14 413 37 14 414 41 14 415 49 14 416 49 14 417 53 14 418 57 14 419 57 102 420 61 102 421 49 102 422 62 103 423 63 103 424 61 103 425 32 104 426 33 104 427 63 104 428 34 53 429 32 53 430 62 53 431 62 53 432 60 53 433 34 53 434 60 105 435 58 105 436 34 105 437 58 106 438 56 106 439 54 106 440 54 53 441 52 53 442 58 53 443 52 107 444 50 107 445 58 107 446 50 53 447 48 53 448 42 53 449 48 53 450 46 53 451 42 53 452 46 53 453 44 53 454 42 53 455 42 108 456 40 108 457 38 108 458 38 53 459 36 53 460 42 53 461 36 53 462 34 53 463 42 53 464 34 109 465 58 109 466 42 109 467 66 110 468 67 110 469 65 110 470 68 6 471 69 6 472 67 6 473 70 111 474 71 111 475 69 111 476 72 112 477 73 112 478 71 112 479 74 113 480 75 113 481 73 113 482 76 114 483 77 114 484 75 114 485 78 1 486 79 1 487 77 1 488 80 115 489 81 115 490 79 115 491 82 116 492 83 116 493 81 116 494 84 117 495 85 117 496 83 117 497 86 118 498 87 118 499 85 118 500 88 119 501 89 119 502 87 119 503 90 120 504 91 120 505 89 120 506 92 121 507 93 121 508 91 121 509 65 14 510 67 14 511 73 14 512 67 14 513 69 14 514 73 14 515 69 122 516 71 122 517 73 122 518 73 123 519 75 123 520 77 123 521 77 124 522 79 124 523 81 124 524 81 14 525 83 14 526 85 14 527 85 125 528 87 125 529 89 125 530 89 126 531 91 126 532 93 126 533 93 14 534 95 14 535 89 14 536 95 14 537 65 14 538 89 14 539 73 102 540 77 102 541 65 102 542 77 14 543 81 14 544 65 14 545 81 14 546 85 14 547 65 14 548 94 127 549 95 127 550 93 127 551 64 128 552 65 128 553 95 128 554 66 53 555 64 53 556 94 53 557 94 129 558 92 129 559 90 129 560 90 53 561 88 53 562 86 53 563 86 53 564 84 53 565 90 53 566 84 53 567 82 53 568 90 53 569 82 53 570 80 53 571 78 53 572 78 130 573 76 130 574 74 130 575 74 53 576 72 53 577 66 53 578 72 53 579 70 53 580 66 53 581 70 131 582 68 131 583 66 131 584 66 53 585 94 53 586 82 53 587 94 53 588 90 53 589 82 53 590 82 53 591 78 53 592 66 53 593 97 54 594 99 54 595 98 54 596 99 132 597 101 132 598 100 132 599 101 133 600 103 133 601 102 133 602 103 134 603 105 134 604 104 134 605 105 47 606 107 47 607 106 47 608 107 135 609 109 135 610 108 135 611 109 88 612 111 88 613 110 88 614 111 61 615 113 61 616 112 61 617 113 62 618 115 62 619 114 62 620 115 136 621 117 136 622 116 136 623 117 137 624 119 137 625 118 137 626 119 138 627 121 138 628 120 138 629 121 39 630 123 39 631 122 39 632 123 139 633 125 139 634 124 139 635 101 14 636 99 14 637 97 14 638 97 14 639 127 14 640 125 14 641 125 14 642 123 14 643 121 14 644 121 14 645 119 14 646 125 14 647 119 14 648 117 14 649 125 14 650 117 14 651 115 14 652 113 14 653 113 14 654 111 14 655 109 14 656 109 14 657 107 14 658 105 14 659 105 14 660 103 14 661 101 14 662 101 14 663 97 14 664 117 14 665 97 14 666 125 14 667 117 14 668 117 14 669 113 14 670 101 14 671 113 14 672 109 14 673 101 14 674 125 140 675 127 140 676 126 140 677 127 70 678 97 70 679 96 70 680 126 53 681 96 53 682 102 53 683 96 53 684 98 53 685 102 53 686 98 53 687 100 53 688 102 53 689 102 53 690 104 53 691 110 53 692 104 53 693 106 53 694 110 53 695 106 141 696 108 141 697 110 141 698 110 53 699 112 53 700 118 53 701 112 53 702 114 53 703 118 53 704 114 53 705 116 53 706 118 53 707 118 142 708 120 142 709 122 142 710 122 143 711 124 143 712 126 143 713 118 53 714 122 53 715 126 53 716 126 53 717 102 53 718 118 53 719

+
+
+
+ + + + 0.005317986 0.00486803 0.003593802 0.004800558 0.004358887 0.004319727 0.002978742 0.002566218 0.004319727 0.002978742 0.002566218 -0.005680263 0.005317986 0.00486803 -0.005680263 0.004953145 0.00523889 0.003593802 0.004953145 0.00523889 -0.005680263 0.002613842 0.002937018 -0.005680263 0.002613842 0.002937018 0.004319727 0.004435718 0.004729688 0.004319727 0.004017651 0.003588497 -0.01271951 0.005317986 0.00486803 -0.01089519 0.002978742 0.002566218 -0.01271951 0.003652751 0.003959298 -0.01271951 0.002613842 0.002937018 -0.01271951 0.004953145 0.00523889 -0.01089519 -0.004823744 0.005358219 0.003593802 -0.004318952 0.004836559 0.004319727 -0.002541422 0.002999961 0.004319727 -0.002541422 0.002999961 -0.005680263 -0.004823744 0.005358219 -0.005680263 -0.005197584 0.004996418 0.003593802 -0.005197584 0.004996418 -0.005680263 -0.002915203 0.002638161 -0.005680263 -0.002915203 0.002638161 0.004319727 -0.004692733 0.004474759 0.004319727 -0.003555059 0.004047274 -0.01271951 -0.004823744 0.005358219 -0.01089519 -0.002541422 0.002999961 -0.01271951 -0.003928899 0.003685474 -0.01271951 -0.002915203 0.002638161 -0.01271951 -0.005197584 0.004996418 -0.01089519 0.002129197 -0.02311611 0.003208577 0.001975595 -0.02311611 0.003463387 0.001409769 -0.02311611 0.003463387 0.001409769 -0.02311611 0.003119826 0.001999974 -0.02311611 0.003119826 -0.002499997 -0.02311611 2.79243e-5 -0.002499997 -0.02311611 0.003103077 -0.002499997 -0.01974391 0.003103077 -0.002499997 -0.01974391 2.79243e-5 0.002499997 -0.01974391 2.79243e-5 0.002499997 -0.01974391 0.003103077 0.002499997 -0.02311611 0.003103077 0.002499997 -0.02311611 2.79243e-5 0.001409769 -0.01974391 0.003463387 -0.001409769 -0.01974391 0.003463387 -0.001409769 -0.02311611 0.003463387 0.001409769 -0.006255149 0.003463387 -0.001409769 -0.006255149 0.003463387 -0.001409769 -0.009627342 0.003463387 0.001409769 -0.009627342 0.003463387 0.001409769 -0.01299953 0.003463387 -0.001409769 -0.01299953 0.003463387 -0.001409769 -0.01637172 0.003463387 0.001409769 -0.01637172 0.003463387 0.002217113 -0.002882957 0.003183543 0.002499997 -0.002882957 0.003103077 0.002499997 -0.002882957 2.79243e-5 0.002217113 -0.002882957 2.79243e-5 0.002499997 -0.009627342 2.79243e-5 0.002499997 -0.009627342 0.003103077 0.002499997 -0.01299953 0.003103077 0.002499997 -0.01299953 2.79243e-5 0.002499997 -0.01637172 0.003103077 0.002499997 -0.01637172 2.79243e-5 -0.002499997 -0.006255149 2.79243e-5 -0.002499997 -0.006255149 0.003103077 -0.002499997 -0.002882957 0.003103077 -0.002499997 -0.002882957 2.79243e-5 0.002499997 -0.006255149 2.79243e-5 0.002499997 -0.006255149 0.003103077 -0.002499997 -0.009627342 2.79243e-5 -0.002499997 -0.009627342 0.003103077 -0.002499997 -0.01299953 2.79243e-5 -0.002499997 -0.01299953 0.003103077 -0.002499997 -0.01637172 2.79243e-5 -0.002499997 -0.01637172 0.003103077 0.001975595 -0.006255149 0.003463387 0.001975595 -0.009627342 0.003463387 0.001975595 -0.01299953 0.003463387 0.001975595 -0.01637172 0.003463387 0.001975595 -0.01974391 0.003463387 -0.001975595 -0.02311611 0.003463387 -0.002129197 -0.02311611 0.003208577 -0.001999974 -0.02311611 0.003119826 -0.001409769 -0.02311611 0.003119826 -0.001975595 -0.01637172 0.003463387 -0.001975595 -0.01974391 0.003463387 -0.001975595 -0.01299953 0.003463387 -0.001975595 -0.009627342 0.003463387 -0.001975595 -0.006255149 0.003463387 -0.001999974 -0.003028035 0.003119826 -0.001999974 -0.006255149 0.003119826 -0.001999974 -0.006255149 2.79243e-5 -0.001999974 -0.003028035 2.79243e-5 0.001999974 -0.01974391 2.79243e-5 0.001999974 -0.02311611 2.79243e-5 0.001999974 -0.01974391 0.003119826 -0.001409769 -0.01974391 0.003119826 -0.001999974 -0.01974391 0.003119826 0.001409769 -0.01974391 0.003119826 0.001409769 -0.006255149 0.003119826 0.001409769 -0.009627342 0.003119826 -0.001409769 -0.009627342 0.003119826 -0.001409769 -0.006255149 0.003119826 0.001409769 -0.01299953 0.003119826 0.001409769 -0.01637172 0.003119826 -0.001409769 -0.01637172 0.003119826 -0.001409769 -0.01299953 0.003119826 0.001999974 -0.003028035 0.003119826 0.001999974 -0.006255149 0.003119826 0.001409769 -0.003419578 0.003119826 0.001415908 -0.003418326 0.003119826 0.001999974 -0.009627342 0.003119826 0.001999974 -0.01299953 0.003119826 0.001999974 -0.01637172 0.003119826 -0.001409769 -0.003419578 0.003119826 -0.001415908 -0.003418326 0.003119826 -0.001999974 -0.009627342 0.003119826 -0.001999974 -0.01299953 0.003119826 -0.001999974 -0.01637172 0.003119826 0.001999974 -0.006255149 2.79243e-5 0.001999974 -0.003028035 2.79243e-5 0.001999974 -0.009627342 2.79243e-5 0.001999974 -0.01299953 2.79243e-5 0.001999974 -0.01637172 2.79243e-5 -0.001999974 -0.02311611 2.79243e-5 -0.001999974 -0.01974391 2.79243e-5 -0.001999974 -0.01637172 2.79243e-5 -0.001999974 -0.01299953 2.79243e-5 -0.001999974 -0.009627342 2.79243e-5 0.001415908 -0.003418326 0.003463387 0.001409769 -0.003419578 0.003463387 0.001975595 -0.003044307 0.003463387 -0.001415908 -0.003418326 0.003463387 -0.001975595 -0.003044307 0.003463387 -0.001409769 -0.003419578 0.003463387 -0.002217113 -0.002882957 2.79243e-5 -0.002217113 -0.002882957 0.003183603 -0.002217113 -0.002882957 0.003297388 0.002217113 -0.002882957 0.003297388 -0.003361761 -0.002167582 -0.005680263 -0.003361761 -0.002167582 0.004319727 -0.003935337 -7.16104e-4 0.004319727 -0.003935337 -7.16104e-4 -0.005680263 -0.003909826 8.4441e-4 0.004319727 -0.003909826 8.4441e-4 -0.005680263 -0.003289043 0.00227636 0.004319727 -0.003289043 0.00227636 -0.005680263 -0.002167582 0.003361761 0.004319727 -0.002167582 0.003361761 -0.005680263 -7.16104e-4 0.003935337 0.004319727 -7.16104e-4 0.003935337 -0.005680263 8.4441e-4 0.003909826 0.004319727 8.4441e-4 0.003909826 -0.005680263 0.00227636 0.003289043 0.004319727 0.00227636 0.003289043 -0.005680263 0.003361761 0.002167582 0.004319727 0.003361761 0.002167582 -0.005680263 0.003935337 7.16104e-4 0.004319727 0.003935337 7.16104e-4 -0.005680263 0.003909826 -8.4441e-4 0.004319727 0.003909826 -8.4441e-4 -0.005680263 0.003289043 -0.00227636 0.004319727 0.003289043 -0.00227636 -0.005680263 0.002167582 -0.003361761 0.004319727 0.002167582 -0.003361761 -0.005680263 7.16103e-4 -0.003935337 0.004319727 7.16103e-4 -0.003935337 -0.005680263 -8.44409e-4 -0.003909826 0.004319727 -8.44409e-4 -0.003909826 -0.005680263 -0.00227636 -0.003289043 0.004319727 -0.00227636 -0.003289043 -0.005680263 -0.002991139 -0.001928627 0.004319727 -0.003501534 -6.37161e-4 0.004319727 -0.003478825 7.51323e-4 0.004319727 -0.002926468 0.002025365 0.004319727 -0.001928627 0.002991139 0.004319727 -6.37161e-4 0.003501534 0.004319727 7.51323e-4 0.003478825 0.004319727 0.002025365 0.002926468 0.004319727 0.002991139 0.001928627 0.004319727 0.003501534 6.37161e-4 0.004319727 0.003478825 -7.51322e-4 0.004319727 0.002926468 -0.002025365 0.004319727 0.001928627 -0.002991139 0.004319727 6.3716e-4 -0.003501534 0.004319727 -7.51322e-4 -0.003478825 0.004319727 -0.002025365 -0.002926468 0.004319727 -7.51322e-4 -0.003478825 -0.00413084 -0.002025365 -0.002926468 -0.00413084 -0.002999961 0 -0.00413084 -0.0028764 6.21222e-4 -0.00413084 -0.003478825 7.51323e-4 -0.00413084 -0.003501534 -6.37161e-4 -0.00413084 -0.002991139 -0.001928627 -0.00413084 6.3716e-4 -0.003501534 -0.00413084 0.001928627 -0.002991139 -0.00413084 0.002926468 -0.002025365 -0.00413084 0.003478825 -7.51322e-4 -0.00413084 0.0028764 -6.21221e-4 -0.00413084 0.002771615 -0.001148045 -0.00413084 0.002121269 -0.002121269 -0.00413084 -0.002771615 -0.001148045 -0.00413084 0.001148045 -0.002771615 -0.00413084 -0.002121269 -0.002121269 -0.00413084 -0.001148045 -0.002771615 -0.00413084 0 -0.002999961 -0.00413084 0.002999961 0 -0.00413084 0.003501534 6.37161e-4 -0.00413084 0.002991139 0.001928627 -0.00413084 0.002025365 0.002926468 -0.00413084 7.51323e-4 0.003478825 -0.00413084 -6.37161e-4 0.003501534 -0.00413084 -0.001928627 0.002991139 -0.00413084 -0.002926468 0.002025365 -0.00413084 -0.002771615 0.001148045 -0.00413084 -0.002121269 0.002121269 -0.00413084 0.002771615 0.001148045 -0.00413084 -0.001148045 0.002771615 -0.00413084 0.002121269 0.002121269 -0.00413084 0.001148045 0.002771615 -0.00413084 0 0.002999961 -0.00413084 -0.001674652 -0.00241971 -0.005680263 0.001674652 0.00241971 -0.005680263 0.001148045 0.002771615 -0.005680263 -0.002121269 -0.002121269 -0.005680263 -0.002771615 -0.001148045 -0.005680263 0 0.002999961 -0.005680263 -0.001148045 0.002771615 -0.005680263 -0.002999961 0 -0.005680263 -0.002121269 0.002121269 -0.005680263 -0.002771615 0.001148045 -0.005680263 0.002121269 0.002121269 -0.005680263 -0.001148045 -0.002771615 -0.005680263 0 -0.002999961 -0.005680263 0.002771615 0.001148045 -0.005680263 0.001148045 -0.002771615 -0.005680263 0.002999961 0 -0.005680263 0.002771615 -0.001148045 -0.005680263 0.002121269 -0.002121269 -0.005680263 -0.04870867 -0.04915863 0.003593802 -0.04819953 -0.0486412 0.004319727 -0.0464068 -0.04681938 0.004319727 -0.0464068 -0.04681938 -0.005680263 -0.04870867 -0.04915863 -0.005680263 -0.04907947 -0.04879373 0.003593802 -0.04907947 -0.04879373 -0.005680263 -0.04677766 -0.04645448 -0.005680263 -0.04677766 -0.04645448 0.004319727 -0.04857033 -0.0482763 0.004319727 -0.04742914 -0.04785829 -0.01271951 -0.04870867 -0.04915863 -0.01089519 -0.0464068 -0.04681938 -0.01271951 -0.04779994 -0.04749339 -0.01271951 -0.04677766 -0.04645448 -0.01271951 -0.04907947 -0.04879373 -0.01089519 -0.04919886 -0.03901678 0.003593802 -0.0486772 -0.03952163 0.004319727 -0.04684054 -0.04129916 0.004319727 -0.04684054 -0.04129916 -0.005680263 -0.04919886 -0.03901678 -0.005680263 -0.048837 -0.03864294 0.003593802 -0.048837 -0.03864294 -0.005680263 -0.04647874 -0.04092532 -0.005680263 -0.04647874 -0.04092532 0.004319727 -0.0483154 -0.03914779 0.004319727 -0.04788792 -0.04028552 -0.01271951 -0.04919886 -0.03901678 -0.01089519 -0.04684054 -0.04129916 -0.01271951 -0.04752612 -0.03991168 -0.01271951 -0.04647874 -0.04092532 -0.01271951 -0.048837 -0.03864294 -0.01089519 -0.02072447 -0.04596984 0.003208577 -0.02072447 -0.04581624 0.003463327 -0.02072447 -0.04525035 0.003463327 -0.02072447 -0.04525035 0.003119826 -0.02072447 -0.04584062 0.003119826 -0.02072447 -0.04134058 2.79233e-5 -0.02072447 -0.04134058 0.003103077 -0.02409666 -0.04134058 0.003103077 -0.02409666 -0.04134058 2.79233e-5 -0.02409666 -0.04634058 2.79233e-5 -0.02409666 -0.04634058 0.003103077 -0.02072447 -0.04634058 0.003103077 -0.02072447 -0.04634058 2.79233e-5 -0.02409666 -0.04525035 0.003463327 -0.02409666 -0.04243081 0.003463327 -0.02072447 -0.04243081 0.003463327 -0.03758543 -0.04525035 0.003463327 -0.03758543 -0.04243081 0.003463327 -0.03421324 -0.04243081 0.003463327 -0.03421324 -0.04525035 0.003463327 -0.03084105 -0.04525035 0.003463327 -0.03084105 -0.04243081 0.003463327 -0.02746886 -0.04243081 0.003463327 -0.02746886 -0.04525035 0.003463327 -0.04095762 -0.04605776 0.003183543 -0.04095762 -0.04634058 0.003103077 -0.04095762 -0.04634058 2.79233e-5 -0.04095762 -0.04605776 2.79233e-5 -0.03421324 -0.04634058 2.79233e-5 -0.03421324 -0.04634058 0.003103077 -0.03084105 -0.04634058 0.003103077 -0.03084105 -0.04634058 2.79233e-5 -0.02746886 -0.04634058 0.003103077 -0.02746886 -0.04634058 2.79233e-5 -0.03758543 -0.04134058 2.79233e-5 -0.03758543 -0.04134058 0.003103077 -0.04095762 -0.04134058 0.003103077 -0.04095762 -0.04134058 2.79233e-5 -0.03758543 -0.04634058 2.79233e-5 -0.03758543 -0.04634058 0.003103077 -0.03421324 -0.04134058 2.79233e-5 -0.03421324 -0.04134058 0.003103077 -0.03084105 -0.04134058 2.79233e-5 -0.03084105 -0.04134058 0.003103077 -0.02746886 -0.04134058 2.79233e-5 -0.02746886 -0.04134058 0.003103077 -0.03758543 -0.04581624 0.003463327 -0.03421324 -0.04581624 0.003463327 -0.03084105 -0.04581624 0.003463327 -0.02746886 -0.04581624 0.003463327 -0.02409666 -0.04581624 0.003463327 -0.02072447 -0.04186493 0.003463327 -0.02072447 -0.04171139 0.003208577 -0.02072447 -0.04184061 0.003119826 -0.02072447 -0.04243081 0.003119826 -0.02746886 -0.04186493 0.003463327 -0.02409666 -0.04186493 0.003463327 -0.03084105 -0.04186493 0.003463327 -0.03421324 -0.04186493 0.003463327 -0.03758543 -0.04186493 0.003463327 -0.04081249 -0.04184061 0.003119826 -0.03758543 -0.04184061 0.003119826 -0.03758543 -0.04184061 2.79233e-5 -0.04081249 -0.04184061 2.79233e-5 -0.02409666 -0.04584062 2.79233e-5 -0.02072447 -0.04584062 2.79233e-5 -0.02409666 -0.04584062 0.003119826 -0.02409666 -0.04243081 0.003119826 -0.02409666 -0.04184061 0.003119826 -0.02409666 -0.04525035 0.003119826 -0.03758543 -0.04525035 0.003119826 -0.03421324 -0.04525035 0.003119826 -0.03421324 -0.04243081 0.003119826 -0.03758543 -0.04243081 0.003119826 -0.03084105 -0.04525035 0.003119826 -0.02746886 -0.04525035 0.003119826 -0.02746886 -0.04243081 0.003119826 -0.03084105 -0.04243081 0.003119826 -0.04081249 -0.04584062 0.003119826 -0.03758543 -0.04584062 0.003119826 -0.040421 -0.04525035 0.003119826 -0.04042226 -0.04525655 0.003119826 -0.03421324 -0.04584062 0.003119826 -0.03084105 -0.04584062 0.003119826 -0.02746886 -0.04584062 0.003119826 -0.040421 -0.04243081 0.003119826 -0.04042226 -0.04242467 0.003119826 -0.03421324 -0.04184061 0.003119826 -0.03084105 -0.04184061 0.003119826 -0.02746886 -0.04184061 0.003119826 -0.03758543 -0.04584062 2.79233e-5 -0.04081249 -0.04584062 2.79233e-5 -0.03421324 -0.04584062 2.79233e-5 -0.03084105 -0.04584062 2.79233e-5 -0.02746886 -0.04584062 2.79233e-5 -0.02072447 -0.04184061 2.79233e-5 -0.02409666 -0.04184061 2.79233e-5 -0.02746886 -0.04184061 2.79233e-5 -0.03084105 -0.04184061 2.79233e-5 -0.03421324 -0.04184061 2.79233e-5 -0.04042226 -0.04525655 0.003463327 -0.040421 -0.04525035 0.003463327 -0.04079622 -0.04581624 0.003463327 -0.04042226 -0.04242467 0.003463327 -0.04079622 -0.04186493 0.003463327 -0.040421 -0.04243081 0.003463327 -0.04095762 -0.04162341 2.79233e-5 -0.04095762 -0.04162341 0.003183543 -0.04095762 -0.04162341 0.003297388 -0.04095762 -0.04605776 0.003297388 -0.041673 -0.04047882 -0.005680263 -0.041673 -0.04047882 0.004319727 -0.04312449 -0.03990525 0.004319727 -0.04312449 -0.03990525 -0.005680263 -0.044685 -0.03993076 0.004319727 -0.044685 -0.03993076 -0.005680263 -0.04611694 -0.04055148 0.004319727 -0.04611694 -0.04055148 -0.005680263 -0.04720234 -0.041673 0.004319727 -0.04720234 -0.041673 -0.005680263 -0.04777598 -0.04312449 0.004319727 -0.04777598 -0.04312449 -0.005680263 -0.04775047 -0.044685 0.004319727 -0.04775047 -0.044685 -0.005680263 -0.04712969 -0.04611694 0.004319727 -0.04712969 -0.04611694 -0.005680263 -0.04600816 -0.04720234 0.004319727 -0.04600816 -0.04720234 -0.005680263 -0.04455667 -0.04777598 0.004319727 -0.04455667 -0.04777598 -0.005680263 -0.04299616 -0.04775047 0.004319727 -0.04299616 -0.04775047 -0.005680263 -0.04156422 -0.04712969 0.004319727 -0.04156422 -0.04712969 -0.005680263 -0.04047882 -0.04600816 0.004319727 -0.04047882 -0.04600816 -0.005680263 -0.03990525 -0.04455667 0.004319727 -0.03990525 -0.04455667 -0.005680263 -0.03993076 -0.04299616 0.004319727 -0.03993076 -0.04299616 -0.005680263 -0.04055148 -0.04156422 0.004319727 -0.04055148 -0.04156422 -0.005680263 -0.04191195 -0.04084944 0.004319727 -0.04320341 -0.04033905 0.004319727 -0.0445919 -0.04036176 0.004319727 -0.04586601 -0.04091411 0.004319727 -0.04683178 -0.04191195 0.004319727 -0.04734212 -0.04320341 0.004319727 -0.04731941 -0.0445919 0.004319727 -0.04676711 -0.04586601 0.004319727 -0.04576921 -0.04683178 0.004319727 -0.04447776 -0.04734212 0.004319727 -0.04308927 -0.04731941 0.004319727 -0.04181516 -0.04676711 0.004319727 -0.04084944 -0.04576921 0.004319727 -0.04033905 -0.04447776 0.004319727 -0.04036176 -0.04308927 0.004319727 -0.04091411 -0.04181516 0.004319727 -0.04036176 -0.04308927 -0.00413084 -0.04091411 -0.04181516 -0.00413084 -0.04384058 -0.04084062 -0.00413084 -0.04446184 -0.04096418 -0.00413084 -0.0445919 -0.04036176 -0.00413084 -0.04320341 -0.04033905 -0.00413084 -0.04191195 -0.04084944 -0.00413084 -0.04033905 -0.04447776 -0.00413084 -0.04084944 -0.04576921 -0.00413084 -0.04181516 -0.04676711 -0.00413084 -0.04308927 -0.04731941 -0.00413084 -0.04321938 -0.04671704 -0.00413084 -0.04269254 -0.04661226 -0.00413084 -0.04171925 -0.04596191 -0.00413084 -0.04269254 -0.04106897 -0.00413084 -0.04106897 -0.04498863 -0.00413084 -0.04171925 -0.04171925 -0.00413084 -0.04106897 -0.04269254 -0.00413084 -0.04084062 -0.04384058 -0.00413084 -0.04384058 -0.0468406 -0.00413084 -0.04447776 -0.04734212 -0.00413084 -0.04576921 -0.04683178 -0.00413084 -0.04676711 -0.04586601 -0.00413084 -0.04731941 -0.0445919 -0.00413084 -0.04734212 -0.04320341 -0.00413084 -0.04683178 -0.04191195 -0.00413084 -0.04586601 -0.04091411 -0.00413084 -0.04498863 -0.04106897 -0.00413084 -0.04596191 -0.04171925 -0.00413084 -0.04498863 -0.04661226 -0.00413084 -0.04661226 -0.04269254 -0.00413084 -0.04596191 -0.04596191 -0.00413084 -0.04661226 -0.04498863 -0.00413084 -0.0468406 -0.04384058 -0.00413084 -0.04142087 -0.04216587 -0.005680263 -0.04626035 -0.04551529 -0.005680263 -0.04661226 -0.04498863 -0.005680263 -0.04171925 -0.04171925 -0.005680263 -0.04269254 -0.04106897 -0.005680263 -0.0468406 -0.04384058 -0.005680263 -0.04661226 -0.04269254 -0.005680263 -0.04384058 -0.04084062 -0.005680263 -0.04596191 -0.04171925 -0.005680263 -0.04498863 -0.04106897 -0.005680263 -0.04596191 -0.04596191 -0.005680263 -0.04106897 -0.04269254 -0.005680263 -0.04084062 -0.04384058 -0.005680263 -0.04498863 -0.04661226 -0.005680263 -0.04106897 -0.04498863 -0.005680263 -0.04384058 -0.0468406 -0.005680263 -0.04269254 -0.04661226 -0.005680263 -0.04171925 -0.04596191 -0.005680263 0.04870867 -0.03852254 0.003593802 0.04819953 -0.03903996 0.004319727 0.0464068 -0.04086178 0.004319727 0.0464068 -0.04086178 -0.005680263 0.04870867 -0.03852254 -0.005680263 0.04907947 -0.03888744 0.003593802 0.04907947 -0.03888744 -0.005680263 0.04677766 -0.04122668 -0.005680263 0.04677766 -0.04122668 0.004319727 0.04857033 -0.03940486 0.004319727 0.04742914 -0.03982287 -0.01271951 0.04870867 -0.03852254 -0.01089519 0.0464068 -0.04086178 -0.01271951 0.04779994 -0.04018777 -0.01271951 0.04677766 -0.04122668 -0.01271951 0.04907947 -0.03888744 -0.01089519 0.04919886 -0.04866439 0.003593802 0.0486772 -0.04815953 0.004319727 0.04684054 -0.046382 0.004319727 0.04684054 -0.046382 -0.005680263 0.04919886 -0.04866439 -0.005680263 0.048837 -0.04903823 0.003593802 0.048837 -0.04903823 -0.005680263 0.04647874 -0.04675585 -0.005680263 0.04647874 -0.04675585 0.004319727 0.0483154 -0.04853338 0.004319727 0.04788792 -0.04739564 -0.01271951 0.04919886 -0.04866439 -0.01089519 0.04684054 -0.046382 -0.01271951 0.04752612 -0.04776948 -0.01271951 0.04647874 -0.04675585 -0.01271951 0.048837 -0.04903823 -0.01089519 0.02072447 -0.04171139 0.003208577 0.02072447 -0.04186493 0.003463327 0.02072447 -0.04243081 0.003463327 0.02072447 -0.04243081 0.003119826 0.02072447 -0.04184061 0.003119826 0.02072447 -0.04634058 2.79233e-5 0.02072447 -0.04634058 0.003103077 0.02409666 -0.04634058 0.003103077 0.02409666 -0.04634058 2.79233e-5 0.02409666 -0.04134058 2.79233e-5 0.02409666 -0.04134058 0.003103077 0.02072447 -0.04134058 0.003103077 0.02072447 -0.04134058 2.79233e-5 0.02409666 -0.04243081 0.003463327 0.02409666 -0.04525035 0.003463327 0.02072447 -0.04525035 0.003463327 0.03758543 -0.04243081 0.003463327 0.03758543 -0.04525035 0.003463327 0.03421324 -0.04525035 0.003463327 0.03421324 -0.04243081 0.003463327 0.03084105 -0.04243081 0.003463327 0.03084105 -0.04525035 0.003463327 0.02746886 -0.04525035 0.003463327 0.02746886 -0.04243081 0.003463327 0.04095762 -0.04162341 0.003183543 0.04095762 -0.04134058 0.003103077 0.04095762 -0.04134058 2.79233e-5 0.04095762 -0.04162341 2.79233e-5 0.03421324 -0.04134058 2.79233e-5 0.03421324 -0.04134058 0.003103077 0.03084105 -0.04134058 0.003103077 0.03084105 -0.04134058 2.79233e-5 0.02746886 -0.04134058 0.003103077 0.02746886 -0.04134058 2.79233e-5 0.03758543 -0.04634058 2.79233e-5 0.03758543 -0.04634058 0.003103077 0.04095762 -0.04634058 0.003103077 0.04095762 -0.04634058 2.79233e-5 0.03758543 -0.04134058 2.79233e-5 0.03758543 -0.04134058 0.003103077 0.03421324 -0.04634058 2.79233e-5 0.03421324 -0.04634058 0.003103077 0.03084105 -0.04634058 2.79233e-5 0.03084105 -0.04634058 0.003103077 0.02746886 -0.04634058 2.79233e-5 0.02746886 -0.04634058 0.003103077 0.03758543 -0.04186493 0.003463327 0.03421324 -0.04186493 0.003463327 0.03084105 -0.04186493 0.003463327 0.02746886 -0.04186493 0.003463327 0.02409666 -0.04186493 0.003463327 0.02072447 -0.04581624 0.003463327 0.02072447 -0.04596984 0.003208577 0.02072447 -0.04584062 0.003119826 0.02072447 -0.04525035 0.003119826 0.02746886 -0.04581624 0.003463327 0.02409666 -0.04581624 0.003463327 0.03084105 -0.04581624 0.003463327 0.03421324 -0.04581624 0.003463327 0.03758543 -0.04581624 0.003463327 0.04081249 -0.04584062 0.003119826 0.03758543 -0.04584062 0.003119826 0.03758543 -0.04584062 2.79233e-5 0.04081249 -0.04584062 2.79233e-5 0.02409666 -0.04184061 2.79233e-5 0.02072447 -0.04184061 2.79233e-5 0.02409666 -0.04184061 0.003119826 0.02409666 -0.04525035 0.003119826 0.02409666 -0.04584062 0.003119826 0.02409666 -0.04243081 0.003119826 0.03758543 -0.04243081 0.003119826 0.03421324 -0.04243081 0.003119826 0.03421324 -0.04525035 0.003119826 0.03758543 -0.04525035 0.003119826 0.03084105 -0.04243081 0.003119826 0.02746886 -0.04243081 0.003119826 0.02746886 -0.04525035 0.003119826 0.03084105 -0.04525035 0.003119826 0.04081249 -0.04184061 0.003119826 0.03758543 -0.04184061 0.003119826 0.040421 -0.04243081 0.003119826 0.04042226 -0.04242467 0.003119826 0.03421324 -0.04184061 0.003119826 0.03084105 -0.04184061 0.003119826 0.02746886 -0.04184061 0.003119826 0.040421 -0.04525035 0.003119826 0.04042226 -0.04525655 0.003119826 0.03421324 -0.04584062 0.003119826 0.03084105 -0.04584062 0.003119826 0.02746886 -0.04584062 0.003119826 0.03758543 -0.04184061 2.79233e-5 0.04081249 -0.04184061 2.79233e-5 0.03421324 -0.04184061 2.79233e-5 0.03084105 -0.04184061 2.79233e-5 0.02746886 -0.04184061 2.79233e-5 0.02072447 -0.04584062 2.79233e-5 0.02409666 -0.04584062 2.79233e-5 0.02746886 -0.04584062 2.79233e-5 0.03084105 -0.04584062 2.79233e-5 0.03421324 -0.04584062 2.79233e-5 0.04042226 -0.04242467 0.003463327 0.040421 -0.04243081 0.003463327 0.04079622 -0.04186493 0.003463327 0.04042226 -0.04525655 0.003463327 0.04079622 -0.04581624 0.003463327 0.040421 -0.04525035 0.003463327 0.04095762 -0.04605776 2.79233e-5 0.04095762 -0.04605776 0.003183543 0.04095762 -0.04605776 0.003297388 0.04095762 -0.04162341 0.003297388 0.041673 -0.04720234 -0.005680263 0.041673 -0.04720234 0.004319727 0.04312449 -0.04777598 0.004319727 0.04312449 -0.04777598 -0.005680263 0.044685 -0.04775047 0.004319727 0.044685 -0.04775047 -0.005680263 0.04611694 -0.04712969 0.004319727 0.04611694 -0.04712969 -0.005680263 0.04720234 -0.04600816 0.004319727 0.04720234 -0.04600816 -0.005680263 0.04777598 -0.04455667 0.004319727 0.04777598 -0.04455667 -0.005680263 0.04775047 -0.04299616 0.004319727 0.04775047 -0.04299616 -0.005680263 0.04712969 -0.04156422 0.004319727 0.04712969 -0.04156422 -0.005680263 0.04600816 -0.04047882 0.004319727 0.04600816 -0.04047882 -0.005680263 0.04455667 -0.03990525 0.004319727 0.04455667 -0.03990525 -0.005680263 0.04299616 -0.03993076 0.004319727 0.04299616 -0.03993076 -0.005680263 0.04156422 -0.04055148 0.004319727 0.04156422 -0.04055148 -0.005680263 0.04047882 -0.041673 0.004319727 0.04047882 -0.041673 -0.005680263 0.03990525 -0.04312449 0.004319727 0.03990525 -0.04312449 -0.005680263 0.03993076 -0.044685 0.004319727 0.03993076 -0.044685 -0.005680263 0.04055148 -0.04611694 0.004319727 0.04055148 -0.04611694 -0.005680263 0.04191195 -0.04683178 0.004319727 0.04320341 -0.04734212 0.004319727 0.0445919 -0.04731941 0.004319727 0.04586601 -0.04676711 0.004319727 0.04683178 -0.04576921 0.004319727 0.04734212 -0.04447776 0.004319727 0.04731941 -0.04308927 0.004319727 0.04676711 -0.04181516 0.004319727 0.04576921 -0.04084944 0.004319727 0.04447776 -0.04033905 0.004319727 0.04308927 -0.04036176 0.004319727 0.04181516 -0.04091411 0.004319727 0.04084944 -0.04191195 0.004319727 0.04033905 -0.04320341 0.004319727 0.04036176 -0.0445919 0.004319727 0.04091411 -0.04586601 0.004319727 0.04036176 -0.0445919 -0.00413084 0.04091411 -0.04586601 -0.00413084 0.04384058 -0.0468406 -0.00413084 0.04446184 -0.04671704 -0.00413084 0.0445919 -0.04731941 -0.00413084 0.04320341 -0.04734212 -0.00413084 0.04191195 -0.04683178 -0.00413084 0.04033905 -0.04320341 -0.00413084 0.04084944 -0.04191195 -0.00413084 0.04181516 -0.04091411 -0.00413084 0.04308927 -0.04036176 -0.00413084 0.04321938 -0.04096418 -0.00413084 0.04269254 -0.04106897 -0.00413084 0.04171925 -0.04171925 -0.00413084 0.04269254 -0.04661226 -0.00413084 0.04106897 -0.04269254 -0.00413084 0.04171925 -0.04596191 -0.00413084 0.04106897 -0.04498863 -0.00413084 0.04084062 -0.04384058 -0.00413084 0.04384058 -0.04084062 -0.00413084 0.04447776 -0.04033905 -0.00413084 0.04576921 -0.04084944 -0.00413084 0.04676711 -0.04181516 -0.00413084 0.04731941 -0.04308927 -0.00413084 0.04734212 -0.04447776 -0.00413084 0.04683178 -0.04576921 -0.00413084 0.04586601 -0.04676711 -0.00413084 0.04498863 -0.04661226 -0.00413084 0.04596191 -0.04596191 -0.00413084 0.04498863 -0.04106897 -0.00413084 0.04661226 -0.04498863 -0.00413084 0.04596191 -0.04171925 -0.00413084 0.04661226 -0.04269254 -0.00413084 0.0468406 -0.04384058 -0.00413084 0.04142087 -0.04551529 -0.005680263 0.04626035 -0.04216587 -0.005680263 0.04661226 -0.04269254 -0.005680263 0.04171925 -0.04596191 -0.005680263 0.04269254 -0.04661226 -0.005680263 0.0468406 -0.04384058 -0.005680263 0.04661226 -0.04498863 -0.005680263 0.04384058 -0.0468406 -0.005680263 0.04596191 -0.04596191 -0.005680263 0.04498863 -0.04661226 -0.005680263 0.04596191 -0.04171925 -0.005680263 0.04106897 -0.04498863 -0.005680263 0.04084062 -0.04384058 -0.005680263 0.04498863 -0.04106897 -0.005680263 0.04106897 -0.04269254 -0.005680263 0.04384058 -0.04084062 -0.005680263 0.04269254 -0.04106897 -0.005680263 0.04171925 -0.04171925 -0.005680263 -0.005317986 -0.09254932 0.003593802 -0.004800558 -0.09204012 0.004319727 -0.002978742 -0.09024745 0.004319727 -0.002978742 -0.09024745 -0.005680263 -0.005317986 -0.09254932 -0.005680263 -0.004953145 -0.09292012 0.003593802 -0.004953145 -0.09292012 -0.005680263 -0.002613842 -0.09061825 -0.005680263 -0.002613842 -0.09061825 0.004319727 -0.004435718 -0.09241098 0.004319727 -0.004017651 -0.09126973 -0.01271951 -0.005317986 -0.09254932 -0.01089519 -0.002978742 -0.09024745 -0.01271951 -0.003652751 -0.09164059 -0.01271951 -0.002613842 -0.09061825 -0.01271951 -0.004953145 -0.09292012 -0.01089519 0.004823744 -0.09303945 0.003593802 0.004318952 -0.09251785 0.004319727 0.002541422 -0.09068119 0.004319727 0.002541422 -0.09068119 -0.005680263 0.004823744 -0.09303945 -0.005680263 0.005197584 -0.09267765 0.003593802 0.005197584 -0.09267765 -0.005680263 0.002915263 -0.09031939 -0.005680263 0.002915263 -0.09031939 0.004319727 0.004692733 -0.09215605 0.004319727 0.003555059 -0.09172856 -0.01271951 0.004823744 -0.09303945 -0.01089519 0.002541422 -0.09068119 -0.01271951 0.003928899 -0.09136676 -0.01271951 0.002915263 -0.09031939 -0.01271951 0.005197584 -0.09267765 -0.01089519 -0.002129197 -0.06456512 0.003208577 -0.001975595 -0.06456512 0.003463327 -0.001409769 -0.06456512 0.003463327 -0.001409769 -0.06456512 0.003119826 -0.001999974 -0.06456512 0.003119826 0.002499997 -0.06456512 2.79224e-5 0.002499997 -0.06456512 0.003103077 0.002499997 -0.06793731 0.003103077 0.002499997 -0.06793731 2.79224e-5 -0.002499997 -0.06793731 2.79224e-5 -0.002499997 -0.06793731 0.003103077 -0.002499997 -0.06456512 0.003103077 -0.002499997 -0.06456512 2.79224e-5 -0.001409769 -0.06793731 0.003463327 0.001409769 -0.06793731 0.003463327 0.001409769 -0.06456512 0.003463327 -0.001409769 -0.08142608 0.003463327 0.001409769 -0.08142608 0.003463327 0.001409769 -0.07805389 0.003463327 -0.001409769 -0.07805389 0.003463327 -0.001409769 -0.07468169 0.003463327 0.001409769 -0.07468169 0.003463327 0.001409769 -0.0713095 0.003463327 -0.001409769 -0.0713095 0.003463327 -0.002217173 -0.08479827 0.003183543 -0.002499997 -0.08479827 0.003103077 -0.002499997 -0.08479827 2.79224e-5 -0.002217173 -0.08479827 2.79224e-5 -0.002499997 -0.07805389 2.79224e-5 -0.002499997 -0.07805389 0.003103077 -0.002499997 -0.07468169 0.003103077 -0.002499997 -0.07468169 2.79224e-5 -0.002499997 -0.0713095 0.003103077 -0.002499997 -0.0713095 2.79224e-5 0.002499997 -0.08142608 2.79224e-5 0.002499997 -0.08142608 0.003103077 0.002499997 -0.08479827 0.003103077 0.002499997 -0.08479827 2.79224e-5 -0.002499997 -0.08142608 2.79224e-5 -0.002499997 -0.08142608 0.003103077 0.002499997 -0.07805389 2.79224e-5 0.002499997 -0.07805389 0.003103077 0.002499997 -0.07468169 2.79224e-5 0.002499997 -0.07468169 0.003103077 0.002499997 -0.0713095 2.79224e-5 0.002499997 -0.0713095 0.003103077 -0.001975595 -0.08142608 0.003463327 -0.001975595 -0.07805389 0.003463327 -0.001975595 -0.07468169 0.003463327 -0.001975595 -0.0713095 0.003463327 -0.001975595 -0.06793731 0.003463327 0.001975595 -0.06456512 0.003463327 0.002129197 -0.06456512 0.003208577 0.001999974 -0.06456512 0.003119826 0.001409769 -0.06456512 0.003119826 0.001975595 -0.0713095 0.003463327 0.001975595 -0.06793731 0.003463327 0.001975595 -0.07468169 0.003463327 0.001975595 -0.07805389 0.003463327 0.001975595 -0.08142608 0.003463327 0.001999974 -0.08465313 0.003119826 0.001999974 -0.08142608 0.003119826 0.001999974 -0.08142608 2.79224e-5 0.001999974 -0.08465313 2.79224e-5 -0.001999974 -0.06793731 2.79224e-5 -0.001999974 -0.06456512 2.79224e-5 -0.001999974 -0.06793731 0.003119826 0.001409769 -0.06793731 0.003119826 0.001999974 -0.06793731 0.003119826 -0.001409769 -0.06793731 0.003119826 -0.001409769 -0.08142608 0.003119826 -0.001409769 -0.07805389 0.003119826 0.001409769 -0.07805389 0.003119826 0.001409769 -0.08142608 0.003119826 -0.001409769 -0.07468169 0.003119826 -0.001409769 -0.0713095 0.003119826 0.001409769 -0.0713095 0.003119826 0.001409769 -0.07468169 0.003119826 -0.001999974 -0.08465313 0.003119826 -0.001999974 -0.08142608 0.003119826 -0.001409769 -0.08426165 0.003119826 -0.001415908 -0.08426284 0.003119826 -0.001999974 -0.07805389 0.003119826 -0.001999974 -0.07468169 0.003119826 -0.001999974 -0.0713095 0.003119826 0.001409769 -0.08426165 0.003119826 0.001415908 -0.08426284 0.003119826 0.001999974 -0.07805389 0.003119826 0.001999974 -0.07468169 0.003119826 0.001999974 -0.0713095 0.003119826 -0.001999974 -0.08142608 2.79224e-5 -0.001999974 -0.08465313 2.79224e-5 -0.001999974 -0.07805389 2.79224e-5 -0.001999974 -0.07468169 2.79224e-5 -0.001999974 -0.0713095 2.79224e-5 0.001999974 -0.06456512 2.79224e-5 0.001999974 -0.06793731 2.79224e-5 0.001999974 -0.0713095 2.79224e-5 0.001999974 -0.07468169 2.79224e-5 0.001999974 -0.07805389 2.79224e-5 -0.001415908 -0.08426284 0.003463327 -0.001409769 -0.08426165 0.003463327 -0.001975595 -0.08463686 0.003463327 0.001415908 -0.08426284 0.003463327 0.001975595 -0.08463686 0.003463327 0.001409769 -0.08426165 0.003463327 0.002217113 -0.08479827 2.79224e-5 0.002217113 -0.08479827 0.003183543 0.002217113 -0.08479827 0.003297388 -0.002217173 -0.08479827 0.003297388 0.003361761 -0.08551365 -0.005680263 0.003361761 -0.08551365 0.004319727 0.003935337 -0.08696514 0.004319727 0.003935337 -0.08696514 -0.005680263 0.003909826 -0.08852565 0.004319727 0.003909826 -0.08852565 -0.005680263 0.003289043 -0.08995759 0.004319727 0.003289043 -0.08995759 -0.005680263 0.002167582 -0.09104299 0.004319727 0.002167582 -0.09104299 -0.005680263 7.16105e-4 -0.09161663 0.004319727 7.16105e-4 -0.09161663 -0.005680263 -8.44412e-4 -0.09159106 0.004319727 -8.44412e-4 -0.09159106 -0.005680263 -0.00227636 -0.09097033 0.004319727 -0.00227636 -0.09097033 -0.005680263 -0.003361761 -0.08984881 0.004319727 -0.003361761 -0.08984881 -0.005680263 -0.003935337 -0.08839732 0.004319727 -0.003935337 -0.08839732 -0.005680263 -0.003909826 -0.08683681 0.004319727 -0.003909826 -0.08683681 -0.005680263 -0.003289043 -0.08540487 0.004319727 -0.003289043 -0.08540487 -0.005680263 -0.002167582 -0.08431947 0.004319727 -0.002167582 -0.08431947 -0.005680263 -7.16105e-4 -0.08374583 0.004319727 -7.16105e-4 -0.08374583 -0.005680263 8.44408e-4 -0.08377134 0.004319727 8.44408e-4 -0.08377134 -0.005680263 0.00227636 -0.08439213 0.004319727 0.00227636 -0.08439213 -0.005680263 0.002991139 -0.0857526 0.004319727 0.003501534 -0.08704406 0.004319727 0.003478825 -0.08843255 0.004319727 0.002926468 -0.08970665 0.004319727 0.001928627 -0.09067237 0.004319727 6.37162e-4 -0.09118276 0.004319727 -7.51324e-4 -0.09116005 0.004319727 -0.002025425 -0.09060776 0.004319727 -0.002991139 -0.08960986 0.004319727 -0.003501534 -0.0883184 0.004319727 -0.003478825 -0.08692991 0.004319727 -0.002926468 -0.0856558 0.004319727 -0.001928627 -0.08469003 0.004319727 -6.37159e-4 -0.08417969 0.004319727 7.51324e-4 -0.0842024 0.004319727 0.002025425 -0.0847547 0.004319727 7.51324e-4 -0.0842024 -0.00413084 0.002025425 -0.0847547 -0.00413084 0.002999961 -0.08768123 -0.00413084 0.0028764 -0.08830243 -0.00413084 0.003478825 -0.08843255 -0.00413084 0.003501534 -0.08704406 -0.00413084 0.002991139 -0.0857526 -0.00413084 -6.37159e-4 -0.08417969 -0.00413084 -0.001928627 -0.08469003 -0.00413084 -0.002926468 -0.0856558 -0.00413084 -0.003478825 -0.08692991 -0.00413084 -0.0028764 -0.08706003 -0.00413084 -0.002771615 -0.08653318 -0.00413084 -0.002121269 -0.0855599 -0.00413084 0.002771615 -0.08653318 -0.00413084 -0.001148045 -0.08490961 -0.00413084 0.002121269 -0.0855599 -0.00413084 0.001148045 -0.08490961 -0.00413084 0 -0.08468121 -0.00413084 -0.002999961 -0.08768123 -0.00413084 -0.003501534 -0.0883184 -0.00413084 -0.002991139 -0.08960986 -0.00413084 -0.002025425 -0.09060776 -0.00413084 -7.51324e-4 -0.09116005 -0.00413084 6.37162e-4 -0.09118276 -0.00413084 0.001928627 -0.09067237 -0.00413084 0.002926468 -0.08970665 -0.00413084 0.002771615 -0.08882927 -0.00413084 0.002121269 -0.08980256 -0.00413084 -0.002771615 -0.08882927 -0.00413084 0.001148045 -0.09045284 -0.00413084 -0.002121269 -0.08980256 -0.00413084 -0.001148045 -0.09045284 -0.00413084 0 -0.09068125 -0.00413084 0.001674652 -0.08526146 -0.005680263 -0.001674652 -0.09010094 -0.005680263 -0.001148045 -0.09045284 -0.005680263 0.002121269 -0.0855599 -0.005680263 0.002771615 -0.08653318 -0.005680263 0 -0.09068125 -0.005680263 0.001148045 -0.09045284 -0.005680263 0.002999961 -0.08768123 -0.005680263 0.002121269 -0.08980256 -0.005680263 0.002771615 -0.08882927 -0.005680263 -0.002121269 -0.08980256 -0.005680263 0.001148045 -0.08490961 -0.005680263 0 -0.08468121 -0.005680263 -0.002771615 -0.08882927 -0.005680263 -0.001148045 -0.08490961 -0.005680263 -0.002999961 -0.08768123 -0.005680263 -0.002771615 -0.08653318 -0.005680263 -0.002121269 -0.0855599 -0.005680263 + + + + + + + + + + 0.7013857 -0.712782 -4.90183e-7 0.7013856 -0.7127822 0 0.7013857 -0.712782 0 -0.7013856 0.7127821 0 -0.7013856 0.712782 0 -0.7013857 0.7127819 0 0.712782 0.7013857 0 0.7127824 0.7013853 0 0.701386 -0.7127817 0 0.7013857 -0.712782 0 0.7013853 -0.7127824 0 -0.7013857 0.712782 0 -0.7013857 0.712782 0 -0.7127825 -0.7013853 0 -0.712782 -0.7013857 0 0 0 -1 0.5040131 0.495955 -0.7071065 0.5040118 0.4959551 -0.7071073 0.7127831 0.7013846 0 0.7127822 0.7013854 0 0.5040128 0.4959534 0.7071079 0.5040138 0.4959544 0.7071064 0 0 1 1.70996e-7 0 1 0.7185755 0.6954489 -4.90183e-7 0.7185751 0.6954494 0 0.7185753 0.6954492 0 -0.7185752 -0.6954492 0 -0.7185752 -0.6954494 0 -0.7185751 -0.6954494 0 -0.6954478 0.7185766 0 -0.6954493 0.7185752 0 0.7185752 0.6954494 0 0.7185753 0.6954492 0 -0.7185751 -0.6954494 0 -0.7185754 -0.6954491 0 -0.7185751 -0.6954494 1.76021e-7 0.6954499 -0.7185747 0 0.6954489 -0.7185757 0 2.39887e-6 0 -1 -1.19943e-6 0 -1 -0.491756 0.5081108 -0.7071064 -0.4917582 0.5081082 -0.7071067 -0.6954489 0.7185757 0 -0.6954481 0.7185765 0 -0.4917567 0.5081105 0.7071062 -0.4917556 0.5081106 0.707107 -1.70996e-7 0 1 0 -1 1.26179e-5 0 -1 0 6.6104e-6 -1 -1.87907e-5 -1 0 0 1 -7.01628e-7 -3.02851e-7 1 -3.50814e-7 0 1.91311e-7 0 1 0 1 0 1 0 1.51425e-7 1 0 0 1 0 -1.51425e-7 1 1.75407e-7 -1.51425e-7 1 0 -3.02851e-7 -1 0 0 1 0 1.51425e-7 -1 1.75407e-7 -1.51425e-7 -1 0 -1.51425e-7 0 -1 6.30892e-6 0 -1 -3.4709e-5 0 0 1 -9.53226e-7 0 1 -4.3228e-7 0 1 1 -1.82302e-7 0 1 -2.73454e-7 0 -1 1.74458e-7 0 -1 0 0 -3.84519e-7 0 -1 3.63647e-5 0 -1 4.12282e-7 0 -1 -9.13896e-7 0 -1 4.37606e-7 0 -1 -2.41265e-7 0 -1 2.48112e-5 0 -1 9.13897e-7 0 -1 -1.77951e-7 0 -1 5.57993e-7 0 -1 -1 -1.82302e-7 0 -1 3.48915e-7 2.25909e-7 -1 0 0 -1 -3.48915e-7 0 -1 0 2.25909e-7 -1 0 -1.50606e-7 -1 3.48915e-7 0 -1 0 -1.50606e-7 1 0 -1.50606e-7 1 -1.74458e-7 0 1 0 1.50606e-7 1 2.61686e-7 -1.50606e-7 1 0 1.50606e-7 1 0 0 -1.04161e-4 0 1 -2.86813e-7 0 1 1 -1.75407e-7 0 0 0 -1 0 0 -1 -2.05466e-5 0 1 -5.0237e-6 -1 0 1.44137e-5 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 -1.96265e-7 0 1 0 0 -3.3031e-7 1 0 -3.3031e-7 1 0 -6.6062e-7 1 0 -6.6062e-7 1 0 0 -1 -2.32458e-5 -8.57603e-6 -1 2.3246e-5 -0.5663009 1.02645e-6 0.8241986 -0.5663006 0 0.8241988 -0.5663008 0 0.8241987 0.5663009 -3.17949e-7 0.8241986 0.5663 -4.23932e-7 0.8241993 -0.5663006 1.58975e-7 0.8241989 -0.5663008 0 0.8241987 -0.5663006 0 0.8241989 -0.5663003 0 0.824199 -0.5663007 0 0.8241987 -0.5663002 0 0.8241991 -0.5663003 0 0.8241991 -0.5663006 0 0.8241989 0.5662989 -1.20828e-7 0.8242 0.5663 0 0.8241991 0.5663019 -2.45611e-7 0.824198 0.5663002 0 0.8241991 0.5663006 0 0.8241989 0.5663006 0 0.8241989 0.5663001 0 0.8241992 0.5663002 0 0.8241991 0.5662998 0 0.8241994 0.5663006 1.58975e-7 0.8241989 0.5662993 0 0.8241998 -0.5555694 0.8314703 0 -0.5555698 0.83147 0 -0.555571 0.8314692 -2.03536e-6 -0.55557 0.8314698 0 -0.5555703 0.8314697 0 -0.5555699 0.8314698 -3.3805e-6 -0.1951152 0.9807804 0 0.195197 0.9807642 0 0.1951962 0.9807642 0 0.5555705 0.8314694 0 0.555571 0.8314692 0 0.5555695 0.8314701 0 0.5555721 0.8314684 0 0.5555698 0.83147 -9.83177e-7 0.5555709 0.8314692 -2.48229e-6 -0.930014 -0.367524 0 -0.9300139 -0.3675245 0 -0.9998663 0.01635259 0 -0.9174984 0.3977398 0 -0.9174985 0.3977394 0 -0.6954492 0.7185752 0 -0.3675243 0.9300139 0 -0.3675245 0.9300138 0 0.01635265 0.9998663 0 0.01635265 0.9998663 0 0.3977396 0.9174984 0 0.3977397 0.9174984 0 0.930014 0.3675242 0 0.9300139 0.3675246 0 0.9998663 -0.01635259 0 0.9998663 -0.01635211 0 0.9174985 -0.3977394 0 0.9174983 -0.3977398 0 0.6954492 -0.7185752 0 0.3675244 -0.9300139 0 0.3675245 -0.9300138 0 -0.01635265 -0.9998664 0 -0.01635265 -0.9998664 0 -0.3977397 -0.9174984 0 -0.3977397 -0.9174984 0 -0.7185753 -0.6954492 0 -0.7185752 -0.6954493 0 2.83943e-7 0 1 -1.34742e-6 0 1 1.89296e-7 0 1 -3.7859e-7 0 1 -1.13577e-6 0 1 6.7371e-7 0 1 1.26321e-7 0 1 3.78591e-7 0 1 1.23042e-6 0 1 -1.89295e-7 0 1 7.57181e-7 0 1 -1.34742e-6 0 1 -3.7859e-7 0 1 -1.26321e-7 0 1 0.3977401 0.9174982 0 0.39774 0.9174983 0 8.73836e-7 0 1 2.46486e-6 0 1 -6.16215e-7 0 1 6.16216e-7 0 1 -1.98391e-6 0 1 4.22733e-6 0 1 6.30456e-7 0 1 3.00637e-7 0 1 -2.34646e-7 0 1 2.91279e-7 0 1 6.16215e-7 0 1 -1.23243e-6 0 1 -4.22732e-6 0 1 9.91959e-7 0 1 1.20255e-6 0 1 3.51968e-7 0 1 -3.00637e-7 0 1 -0.7185752 -0.6954493 0 -0.7185754 -0.6954491 0 0.9300138 0.3675247 0 0.930014 0.3675245 0 0.7185752 0.6954492 0 0.7185753 0.6954492 0 -0.9300138 -0.3675245 0 -0.9300138 -0.3675245 0 0.9998663 -0.01635235 0 0.9998664 -0.01635265 0 -0.9998664 0.01635235 0 -0.9998664 0.01635235 0 0.9174982 -0.3977398 0 0.9174982 -0.3977401 0 -0.9174984 0.3977396 0 0.6954491 -0.7185754 0 0.6954494 -0.7185752 0 -0.6954491 0.7185754 0 0.3675246 -0.9300138 0 0.3675246 -0.9300139 0 -0.3675245 0.9300138 0 -0.3675245 0.930014 0 -0.01635229 -0.9998663 0 0.01635229 0.9998663 0 -0.3977401 -0.9174982 0 -0.3977398 -0.9174982 0 -5.61982e-7 0 -1 9.75682e-7 0 -1 0 0 -1 -5.61982e-7 0 -1 1.84636e-6 0 -1 5.81742e-7 0 -1 2.29691e-7 0 -1 -1.83753e-7 0 -1 -1.55716e-6 0 -1 2.13564e-6 0 -1 1.06782e-6 0 -1 -7.78582e-7 0 -1 1.95137e-6 0 -1 9.75684e-7 0 -1 6.79168e-7 0 -1 7.78582e-7 0 -1 0 0 -1 -1.83752e-7 0 -1 3.67505e-7 0 -1 -1.59723e-6 0 -1 -0.1950901 -0.9807854 0 -0.1950902 -0.9807853 0 -0.5555704 -0.8314695 0 -0.5555704 -0.8314695 0 -0.5555701 -0.8314697 0 -0.8314696 -0.5555703 0 -0.8314699 -0.55557 0 -0.9807853 -0.1950905 0 -0.9807853 -0.1950906 0 -0.9807853 0.1950906 0 -0.9807854 0.1950899 0 -0.9807854 0.1950904 -1.88245e-7 -0.8314696 0.5555703 0 -0.8314698 0.5555701 0 -0.5555704 0.8314695 0 -0.5555704 0.8314695 0 -0.1950901 0.9807854 0 -0.1950899 0.9807854 0 0.1950902 0.9807853 0 0.1950901 0.9807854 0 0.5555704 0.8314695 0 0.5555707 0.8314693 0 0.5555698 0.83147 0 0.8314696 0.5555703 0 0.8314693 0.5555709 0 0.9807854 0.1950901 0 0.9807853 -0.1950905 0 0.9807853 -0.1950902 0 0.9807854 -0.1950898 -2.21972e-7 0.8314698 -0.5555702 0 0.8314698 -0.55557 0 0.5555704 -0.8314697 0 0.5555704 -0.8314695 0 0.1950899 -0.9807854 0 0.19509 -0.9807854 0 0.7127842 -0.7013834 0 0.7127819 -0.7013857 0 0.7127828 -0.7013849 0 -0.7127833 0.7013843 0 -0.7127836 0.7013841 0 -0.7127807 0.701387 3.99133e-7 -0.7013818 -0.7127858 0 -0.7013878 -0.7127799 0 0.7127835 -0.7013842 0 0.7127824 -0.7013853 0 0.7127807 -0.7013871 7.09159e-7 -0.7127846 0.7013831 0 -0.7127819 0.7013859 0 -0.7127814 0.7013863 -9.38778e-7 0.7013827 0.712785 0 0.7013906 0.7127771 0 -1.19945e-6 0 -1 -0.4959464 -0.5040152 -0.707111 -0.4959524 -0.5040099 -0.7071105 -0.7013871 -0.7127806 0 -0.7013764 -0.712791 0 -0.4959497 -0.5040273 0.7071 -0.4959513 -0.5040145 0.707108 6.8398e-7 0 1 -0.6954489 -0.7185757 0 -0.6954488 -0.7185758 0 -0.6954491 -0.7185755 0 0.69545 0.7185745 0 0.6954479 0.7185766 0 0.6954531 0.7185716 7.98274e-7 -0.7185749 0.6954497 0 -0.7185688 0.6954559 0 -0.6954453 -0.7185791 0 -0.6954485 -0.7185759 0 -0.6954512 -0.7185734 0 0.6954511 0.7185735 0 0.6954486 0.7185759 0 0.6954494 0.7185751 0 0.7185823 -0.695442 0 0.7185743 -0.6954502 0 1.19943e-6 0 -1 -0.5081086 0.4917579 -0.7071067 -0.5081101 0.4917587 -0.7071051 -0.718569 0.6954557 0 -0.7185797 0.6954446 0 -0.5081138 0.4917591 0.7071021 -0.5081086 0.4917545 0.707109 1.36796e-6 0 1 -8.54984e-7 0 1 1 0 -7.3115e-6 1 0 1.13572e-5 1.10471e-6 -1 0 1.10471e-6 -1 0 0 0 1 0 0 1 0 -1 -1.91965e-7 0 0 -1 0 0 -1 5.86466e-7 0 -1 0 1 3.69571e-7 0 0 -1 -5.66917e-6 0 1 -1 -1.01901e-6 0 1 -5.58369e-6 0 1 0 5.85603e-7 1.10471e-6 -1 0 1.10471e-6 -1 0 -1 1.87787e-6 0 -1 2.82485e-5 0 1 0 -1.24816e-5 -1 -2.82488e-5 0 -1.6423e-5 0.5662661 0.8242226 0 0.5663031 0.8241971 0 0.5663009 0.8241987 0 -0.5662971 0.8242012 6.69537e-7 -0.5663037 0.8241968 0 0.5662974 0.8242011 0 0.5663034 0.8241969 0 0.5663037 0.8241968 0 0.5662968 0.8242015 0 -0.5663089 0.8241931 0 -0.5662968 0.8242015 3.92974e-7 -0.5662972 0.8242012 0 -0.5662974 0.8242011 1 8.19451e-6 0 -0.8314558 0.5555908 0 -0.8314718 0.555567 0 -0.8314681 0.5555726 -2.44244e-5 -0.8314711 0.5555682 0 -0.8314747 0.5555629 0 -0.8314654 0.5555768 0 -0.9805393 0.1963231 0 -0.9810232 0.1938903 0 -0.9805394 -0.1963225 0 -0.9810231 -0.1938909 0 -0.8314718 -0.555567 0 -0.8314515 -0.5555974 0 -0.8314532 -0.5555949 0 -0.8314667 -0.5555747 0 -0.8314673 -0.5555739 0 -0.8314737 -0.5555644 -9.9293e-6 0.367525 0.9300137 0 0.3675262 0.9300132 0 -0.01635259 0.9998663 0 -0.3977403 0.9174981 0 -0.7185757 0.6954488 0 -0.930013 0.3675268 0 -0.9998664 -0.0163502 0 -0.9998663 -0.01635766 0 -0.9174993 -0.3977373 0 -0.9174979 -0.3977405 0 -0.6954489 -0.7185755 0 -0.367525 -0.9300137 0 -0.3675262 -0.9300132 0 0.01635265 -0.9998663 0 0.3977376 -0.9174993 0 0.3977403 -0.9174981 0 0.7185757 -0.6954488 0 0.930013 -0.3675268 0 0.9998664 0.01635026 0 0.9998663 0.01635396 0 0.9174983 0.3977397 0 0.6954489 0.7185755 0 -3.78597e-7 0 1 1.47371e-7 0 1 -5.67882e-7 0 1 0 0 1 1.51435e-6 0 1 3.78588e-7 0 1 -1.34745e-6 0 1 3.78594e-7 0 1 -1.47374e-7 0 1 7.57176e-7 0 1 -1.51437e-6 0 1 1.34743e-6 0 1 -3.78591e-7 0 1 1.34742e-6 0 1 -0.9174966 -0.3977438 0 -0.9175001 -0.3977354 0 1.23244e-6 0 1 -1.23244e-6 0 1 -3.43467e-7 0 1 0 0 1 1.26091e-6 0 1 4.72845e-7 0 1 -1.23244e-6 0 1 3.43467e-7 0 1 0 0 1 -1.26091e-6 0 1 -4.7284e-7 0 1 0.6954481 0.7185763 0 -0.3675239 -0.9300142 0 -0.6954481 -0.7185763 0 0.3675239 0.9300142 0 0.01635068 -0.9998664 0 0.01635056 -0.9998664 0 -0.01635062 0.9998664 0 -0.01635062 0.9998664 0 0.3977404 -0.9174981 0 0.3977404 -0.9174981 0 -0.3977404 0.9174981 0 -0.3977404 0.9174981 0 0.7185762 -0.6954483 0 0.7185762 -0.6954482 0 -0.7185762 0.6954483 0 -0.7185738 0.6954509 0 0.9300128 -0.3675273 0 0.9300146 -0.367523 0 -0.9300148 0.367522 0 -0.9300148 0.3675221 0 0.9998664 0.01635354 0 0.9998664 0.0163486 0 -0.9998663 -0.0163536 0 -0.9998664 -0.01634865 0 0.9174966 0.3977438 0 0.9175001 0.3977354 0 0 0 -1 9.23191e-7 0 -1 -1.94646e-7 0 -1 -1.95137e-6 0 -1 7.78579e-7 0 -1 -1.99653e-7 0 -1 9.99089e-7 0 -1 0.9807851 0.1950918 0 0.9807866 0.195084 0 0.8314734 0.5555646 0 0.8314704 0.5555693 0 0.8314692 0.555571 6.5567e-6 0.55557 0.8314699 0 0.5555662 0.8314723 0 0.1950894 0.9807856 0 0.1950893 0.9807856 0 -0.195091 0.9807852 0 -0.1950938 0.9807847 0 -0.1950855 0.9807863 3.7069e-6 -0.55557 0.8314699 0 -0.5555662 0.8314723 0 -0.8314698 0.5555702 0 -0.8314698 0.5555699 0 -0.9807851 0.1950918 0 -0.9807866 0.195084 0 -0.9807866 -0.195084 0 -0.9807851 -0.1950918 0 -0.8314698 -0.5555702 0 -0.831469 -0.5555712 0 -0.8314705 -0.5555691 3.70696e-6 -0.55557 -0.8314699 0 -0.1950893 -0.9807856 0 -0.1950894 -0.9807856 0 0.1950879 -0.9807858 0 0.1950883 -0.9807857 0 0.1950904 -0.9807853 0 0.55557 -0.8314699 0 0.8314735 -0.5555644 0 0.9807866 -0.195084 0 0.9807851 -0.1950918 0 -0.7127842 0.7013834 0 -0.7127819 0.7013857 0 -0.7127828 0.7013849 0 0.7127833 -0.7013843 0 0.7127836 -0.7013841 0 0.7127807 -0.701387 1.59653e-6 0.7013818 0.7127858 0 0.7013878 0.7127799 0 -0.7127835 0.7013842 0 -0.7127824 0.7013853 0 -0.7127807 0.7013871 0 0.7127846 -0.7013831 0 0.7127819 -0.7013859 0 0.7127814 -0.7013863 -9.38778e-7 -0.7013827 -0.712785 0 -0.7013906 -0.7127771 0 1.19944e-6 0 -1 0.4959502 0.5040191 -0.7071056 0.4959539 0.5040113 -0.7071085 0.7013871 0.7127806 0 0.7013764 0.712791 0 0.4959521 0.5040298 0.7070966 0.4959513 0.5040145 0.707108 -6.83984e-7 0 1 0.6954489 0.7185757 7.84291e-6 0.6954488 0.7185758 0 0.6954491 0.7185755 0 -0.69545 -0.7185745 0 -0.6954479 -0.7185766 0 -0.6954531 -0.7185716 0 0.7185749 -0.6954497 0 0.7185688 -0.6954559 0 0.6954453 0.7185791 0 0.6954485 0.7185759 0 0.6954512 0.7185734 -7.09161e-7 -0.6954511 -0.7185735 0 -0.6954486 -0.7185759 0 -0.6954494 -0.7185751 9.38781e-7 -0.7185823 0.695442 0 -0.7185743 0.6954502 0 -1.19943e-6 0 -1 0.5081086 -0.4917579 -0.7071067 0.5081111 -0.4917597 -0.7071037 0.718569 -0.6954557 0 0.7185797 -0.6954446 0 0.5081114 -0.4917567 0.7071055 0.5081086 -0.4917545 0.707109 -1.36797e-6 0 1 8.54986e-7 0 1 -1 0 -7.3115e-6 -1 0 1.13572e-5 -1.10471e-6 1 -2.80651e-6 -1.10471e-6 1 0 0 0 1 0 1 1.98813e-6 0 -1 2.79132e-6 0 0 -1 -5.8634e-7 0 -1 0 -1 9.92594e-7 0 0 -1 5.66795e-6 0 1 1 1.01901e-6 0 -1 5.58369e-6 0 -1 0 5.85603e-7 -1.10471e-6 1 0 -1.10471e-6 1 0 1 -1.87787e-6 0 1 -2.82485e-5 0 -1 0 -1.24816e-5 1 2.82488e-5 0 1.6423e-5 -0.5662661 0.8242226 0 -0.5663009 0.8241987 -6.69529e-7 0.5662974 0.8242011 0 0.5663089 0.8241931 -3.92974e-7 0.5662972 0.8242012 -1 -8.19451e-6 0 0.8314558 -0.5555908 0 0.8314718 -0.555567 0 0.8314681 -0.5555726 -3.25658e-5 0.8314711 -0.5555682 0 0.8314747 -0.5555629 0 0.8314654 -0.5555768 0 0.9805393 -0.1963231 0 0.9810232 -0.1938903 0 0.9805394 0.1963225 0 0.9810231 0.1938909 0 0.8314718 0.555567 0 0.8314515 0.5555974 0 0.8314532 0.5555949 0 0.8314667 0.5555747 0 0.8314673 0.5555739 0 0.8314737 0.5555644 -9.9293e-6 0.01635259 -0.9998663 0 0.9998664 0.0163502 0 0.9998663 0.01635766 0 0.9174993 0.3977373 0 0.9174979 0.3977405 0 -0.01635265 0.9998663 0 -0.3977376 0.9174993 0 -0.9998664 -0.01635026 0 -0.9998663 -0.01635396 0 -0.9174983 -0.3977397 0 -1.47371e-7 0 1 5.67886e-7 0 1 0 0 1 1.47374e-7 0 1 -7.57181e-7 0 1 -1.34743e-6 0 1 3.43471e-7 0 1 -3.43463e-7 0 1 4.7284e-7 0 1 -0.01635068 0.9998664 0 -0.01635056 0.9998664 0 0.01635062 -0.9998664 0 0.01635062 -0.9998664 0 -0.7185762 0.6954482 0 0.7185738 -0.6954509 0 -0.9300128 0.3675273 0 -0.9300146 0.367523 0 0.9300148 -0.367522 0 0.9300148 -0.3675221 0 -0.9998664 -0.01635354 0 -0.9998664 -0.0163486 0 0.9998663 0.0163536 0 0.9998664 0.01634865 0 0 0 -1 -9.2317e-7 0 -1 1.94646e-7 0 -1 1.95137e-6 0 -1 -7.78579e-7 0 -1 1.99652e-7 0 -1 -9.99089e-7 0 -1 -0.8314734 -0.5555646 0 -0.8314704 -0.5555693 0 -0.8314692 -0.555571 4.37113e-6 -0.5555662 -0.8314723 0 0.195091 -0.9807852 0 0.1950938 -0.9807847 0 0.1950855 -0.9807863 0 0.5555662 -0.8314723 0 0.8314698 -0.5555699 0 0.8314698 0.5555702 0 0.831469 0.5555712 0 0.8314705 0.5555691 5.56044e-6 -0.1950879 0.9807858 0 -0.1950883 0.9807857 0 -0.1950904 0.9807853 0 -0.8314735 0.5555644 0 -0.7013851 0.7127826 -1.56859e-5 -0.7013856 0.7127821 0 -0.7013855 0.7127822 0 0.7013839 -0.7127838 0 0.7013843 -0.7127835 0 0.7013829 -0.7127847 -1.59654e-6 -0.7127801 -0.7013877 0 -0.7013856 0.7127822 0 -0.7013856 0.712782 2.83665e-6 0.7013841 -0.7127836 0 0.701384 -0.7127837 0 0.7013837 -0.712784 0 0.7127836 0.701384 0 -0.5040076 -0.4959549 -0.7071104 -0.5040181 -0.4959505 -0.7071061 -0.7127806 -0.7013871 0 -0.7127798 -0.701388 0 -0.5039986 -0.4959433 0.7071249 -0.5040261 -0.4959602 0.7070934 -0.718575 -0.6954495 0 -0.7185746 -0.69545 0 -0.7185745 -0.69545 0 0.7185745 0.69545 0 0.7185747 0.6954498 0 0.7185744 0.6954502 7.9827e-7 0.6954474 -0.7185771 0 0.6954481 -0.7185764 0 -0.7185764 -0.6954481 0 -0.7185725 -0.695452 0 0.7185726 0.695452 0 0.7185755 0.695449 0 -0.6954475 0.718577 0 -0.6954481 0.7185764 0 0.4917559 -0.5081093 -0.7071076 0.4917549 -0.5081096 -0.7071081 0.6954478 -0.7185767 0 0.6954476 -0.7185768 0 0.4917593 -0.5081132 0.7071024 0.4917588 -0.5081139 0.7071022 -1.70995e-7 0 1 0 1 5.04712e-5 -1 1.05244e-6 0 -1 1.05244e-6 0 0 1 3.78536e-5 4.85978e-5 0 -1 -4.12284e-7 0 -1 3.61898e-7 0 -1 -4.66855e-5 0 -1 0 0 -1 1.66236e-6 0 1 0 0 -1 -1 1.07946e-6 0 -1 1.07946e-6 0 0 1 -4.64914e-5 0 1 -2.3246e-5 0.5663058 -1.5397e-5 0.8241953 0.5662984 0 0.8242003 0.5663009 0 0.8241987 -0.5663021 0 0.8241978 -0.5662997 6.35898e-7 0.8241994 0.5663006 0 0.8241989 0.566299 0 0.8241999 0.5663 0 0.8241993 -0.5662988 0 0.8242001 -0.5662984 0 0.8242003 -0.5663031 4.421e-7 0.8241972 -0.5663 0 0.8241993 -0.566299 0 0.8241999 0 1 -8.1945e-6 0.5555825 -0.8314615 0 0.5555688 -0.8314707 0 0.5555754 -0.8314662 -3.25657e-5 0.5555819 -0.8314617 0 0.5555734 -0.8314676 0 0.5555776 -0.8314648 0 0.1945151 -0.9808996 0 0.1945252 -0.9808976 0 -0.1945151 -0.9808996 0 -0.1945252 -0.9808976 0 -0.5555688 -0.8314707 0 -0.5555887 -0.8314573 0 -0.5555695 -0.8314702 0 -0.5555887 -0.8314573 0 -0.5555762 -0.8314657 0 -0.5555846 -0.8314599 -3.97166e-5 0.9300134 0.3675255 0 0.9300134 0.367526 0 0.9998663 -0.01635301 0 0.9998664 -0.01635253 0 0.9174984 -0.3977397 0 0.9174983 -0.3977397 0 0.6954502 -0.7185744 0 0.3675256 -0.9300134 0 0.3675256 -0.9300135 0 -0.01635497 -0.9998663 0 -0.3977398 -0.9174984 0 -0.3977398 -0.9174984 0 -0.7185756 -0.6954489 0 -0.7185757 -0.6954488 0 -0.9300134 -0.3675255 0 -0.9300134 -0.367526 0 -0.9998663 0.01635307 0 -0.9998663 0.01635265 0 -0.917499 0.397738 0 -0.9174991 0.397738 0 -0.6954502 0.7185744 0 -0.3675256 0.9300134 0 -0.3675256 0.9300135 0 0.01635503 0.9998663 0 0.3977389 0.9174987 0 0.3977389 0.9174987 0 0.7185756 0.6954489 0 0.7185757 0.6954488 0 1.89293e-7 0 1 1.34743e-6 0 1 1.34742e-6 0 1 7.57181e-7 0 1 -1.34742e-6 0 1 1.13574e-6 0 1 3.78578e-7 0 1 -1.34739e-6 0 1 0 0 1 -1.89295e-7 0 1 -1.13575e-6 0 1 -3.78574e-7 0 1 1.34739e-6 0 1 0 0 1 -0.3977428 -0.917497 0 -0.3977428 -0.917497 0 2.91278e-7 0 1 1.23243e-6 0 1 -6.16213e-7 0 1 -6.30447e-7 0 1 6.30466e-7 0 1 3.00643e-7 0 1 2.34648e-7 0 1 -2.91272e-7 0 1 6.16237e-7 0 1 2.11366e-6 0 1 6.3046e-7 0 1 -3.00643e-7 0 1 -2.34641e-7 0 1 0.7185757 0.6954488 0 0.7185757 0.6954488 0 -0.9300144 -0.3675231 0 -0.7185757 -0.6954488 0 -0.7185757 -0.6954488 0 0.9300144 0.3675231 0 -0.9998664 0.0163508 0 -0.9998664 0.0163505 0 0.9998664 -0.0163508 0 0.9998664 -0.0163505 0 -0.917498 0.3977406 0 -0.9174981 0.3977404 0 0.917498 -0.3977406 0 0.9174981 -0.3977404 0 -0.6954474 0.7185771 0 -0.6954473 0.7185772 0 0.6954473 -0.7185772 0 -0.3675263 0.9300132 0 -0.3675264 0.9300131 0 0.3675253 -0.9300135 0 0.3675254 -0.9300135 0 0.01634788 0.9998664 0 -0.01634794 -0.9998664 0 0.3977428 0.917497 0 0.3977428 0.917497 0 -5.6198e-7 0 -1 -1.95137e-6 0 -1 9.75663e-7 0 -1 1.8294e-7 0 -1 -9.23177e-7 0 -1 2.29693e-7 0 -1 2.13558e-6 0 -1 1.06782e-6 0 -1 -7.78586e-7 0 -1 4.87832e-7 0 -1 6.79178e-7 0 -1 -2.66953e-7 0 -1 7.78583e-7 0 -1 0 0 -1 -3.99301e-7 0 -1 -4.99544e-7 0 -1 0.1950896 0.9807855 0 0.5555679 0.8314712 0 0.5555739 0.8314672 0 0.5555611 0.8314758 0 0.8314721 0.5555665 0 0.831472 0.5555666 0 0.9807853 0.1950905 0 0.9807854 0.19509 0 0.9807853 -0.1950905 0 0.9807853 -0.1950909 0 0.9807856 -0.1950892 1.85348e-6 0.8314723 -0.5555663 0 0.8314719 -0.5555669 0 0.5555681 -0.8314712 0 0.5555679 -0.8314712 0 0.1950896 -0.9807855 0 -0.1950896 -0.9807855 0 -0.5555681 -0.8314712 0 -0.5555608 -0.831476 0 -0.5555739 -0.8314672 -7.41388e-6 -0.8314701 -0.5555697 0 -0.8314703 -0.5555693 0 -0.9807855 -0.1950892 0 -0.9807857 -0.1950887 0 -0.9807857 0.1950887 0 -0.9807856 0.1950892 0 -0.9807856 0.1950894 2.18557e-6 -0.8314701 0.5555697 0 -0.8314703 0.5555693 0 -0.5555679 0.8314712 0 -0.5555681 0.8314712 0 -0.1950896 0.9807855 0 + + + + + + + + + + + + + + +

0 0 1 0 2 0 2 1 3 1 4 1 2 2 4 2 0 2 5 3 6 3 7 3 7 4 8 4 9 4 7 5 9 5 5 5 6 6 5 6 0 6 6 7 0 7 4 7 10 8 11 8 4 8 4 9 3 9 12 9 4 10 12 10 10 10 13 3 14 3 7 3 7 11 6 11 15 11 7 12 15 12 13 12 3 13 7 13 14 13 3 14 14 14 12 14 12 15 14 15 13 15 12 15 13 15 10 15 15 16 11 16 10 16 15 17 10 17 13 17 6 18 4 18 11 18 6 19 11 19 15 19 0 20 5 20 9 20 0 21 9 21 1 21 8 22 2 22 1 22 8 23 1 23 9 23 16 24 17 24 18 24 18 25 19 25 20 25 18 26 20 26 16 26 21 27 22 27 23 27 23 28 24 28 25 28 23 29 25 29 21 29 22 30 21 30 16 30 22 31 16 31 20 31 26 32 27 32 20 32 20 32 19 32 28 32 20 33 28 33 26 33 29 34 30 34 23 34 23 35 22 35 31 35 23 36 31 36 29 36 19 37 23 37 30 37 19 38 30 38 28 38 28 39 30 39 29 39 28 40 29 40 26 40 31 41 27 41 26 41 31 42 26 42 29 42 22 43 20 43 27 43 22 44 27 44 31 44 16 45 21 45 25 45 16 46 25 46 17 46 24 22 18 22 17 22 24 47 17 47 25 47 32 48 33 48 34 48 34 49 35 49 36 49 34 50 36 50 32 50 37 51 38 51 39 51 37 51 39 51 40 51 41 52 42 52 43 52 41 53 43 53 44 53 45 22 46 22 47 22 45 22 47 22 34 22 48 22 49 22 50 22 48 22 50 22 51 22 52 54 53 54 54 54 52 22 54 22 55 22 56 55 57 55 58 55 56 55 58 55 59 55 60 56 61 56 62 56 60 57 62 57 63 57 63 57 62 57 64 57 63 58 64 58 65 58 65 59 64 59 42 59 65 60 42 60 41 60 66 61 67 61 68 61 66 51 68 51 69 51 70 57 71 57 61 57 70 62 61 62 60 62 72 63 73 63 67 63 72 51 67 51 66 51 74 51 75 51 73 51 74 64 73 64 72 64 76 51 77 51 75 51 76 51 75 51 74 51 40 51 39 51 77 51 40 51 77 51 76 51 78 22 48 22 51 22 78 22 51 22 79 22 79 22 51 22 52 22 79 22 52 22 80 22 80 22 52 22 55 22 80 22 55 22 81 22 81 22 55 22 45 22 81 22 45 22 82 22 47 65 83 65 84 65 84 66 85 66 86 66 84 49 86 49 47 49 54 22 87 22 88 22 54 67 88 67 46 67 53 68 89 68 87 68 53 22 87 22 54 22 50 22 90 22 89 22 50 69 89 69 53 69 49 22 91 22 90 22 49 22 90 22 50 22 92 70 93 70 94 70 92 71 94 71 95 71 96 72 97 72 36 72 96 73 36 73 98 73 99 15 86 15 85 15 99 15 85 15 100 15 98 15 36 15 35 15 98 15 35 15 101 15 101 15 35 15 86 15 101 15 86 15 99 15 102 15 103 15 104 15 102 15 104 15 105 15 106 15 107 15 108 15 106 15 108 15 109 15 110 74 111 74 102 74 102 75 112 75 113 75 102 76 113 76 110 76 111 15 114 15 103 15 111 77 103 77 102 77 114 15 115 15 106 15 114 15 106 15 103 15 115 15 116 15 107 15 115 15 107 15 106 15 116 15 98 15 101 15 116 15 101 15 107 15 117 78 105 78 93 78 93 79 92 79 118 79 93 80 118 80 117 80 105 15 104 15 119 15 105 81 119 81 93 81 104 82 109 82 120 82 104 15 120 15 119 15 109 15 108 15 121 15 109 15 121 15 120 15 108 83 99 83 100 83 108 15 100 15 121 15 122 84 111 84 110 84 122 51 110 51 123 51 122 85 124 85 114 85 122 86 114 86 111 86 124 87 125 87 115 87 124 88 115 88 114 88 125 89 126 89 116 89 125 90 116 90 115 90 126 51 96 51 98 51 126 91 98 91 116 91 127 57 128 57 100 57 127 57 100 57 85 57 128 92 129 92 121 92 128 93 121 93 100 93 129 94 130 94 120 94 129 95 120 95 121 95 130 57 131 57 119 57 130 96 119 96 120 96 131 97 94 97 93 97 131 57 93 57 119 57 37 15 40 15 128 15 37 15 128 15 127 15 46 22 88 22 83 22 46 22 83 22 47 22 82 22 45 22 34 22 82 22 34 22 33 22 132 98 133 98 48 98 48 22 78 22 134 22 48 99 134 99 132 99 58 57 57 57 71 57 58 100 71 100 70 100 59 15 58 15 70 15 70 101 122 101 123 101 70 102 123 102 59 102 135 22 136 22 91 22 91 22 49 22 137 22 91 103 137 103 135 103 138 55 69 55 68 55 138 55 68 55 139 55 44 104 43 104 32 104 32 105 36 105 97 105 32 49 97 49 44 49 34 49 47 49 86 49 34 49 86 49 35 49 95 106 94 106 66 106 66 15 69 15 138 15 66 107 138 107 95 107 72 108 66 108 94 108 72 15 94 15 131 15 74 109 72 109 131 109 74 15 131 15 130 15 76 15 74 15 130 15 76 15 130 15 129 15 40 15 76 15 129 15 40 15 129 15 128 15 41 15 44 15 97 15 41 15 97 15 96 15 65 15 41 15 96 15 65 15 96 15 126 15 63 15 65 15 126 15 63 15 126 15 125 15 60 110 63 110 125 110 60 111 125 111 124 111 70 112 60 112 124 112 70 15 124 15 122 15 112 51 102 51 48 51 112 51 48 51 133 51 52 51 51 51 103 51 52 51 103 51 106 51 45 51 55 51 107 51 45 51 107 51 101 51 137 113 49 113 105 113 137 57 105 57 117 57 50 114 53 114 109 114 50 115 109 115 104 115 54 57 46 57 99 57 54 57 99 57 108 57 49 55 48 55 102 55 49 55 102 55 105 55 51 49 50 49 104 49 51 49 104 49 103 49 53 116 52 116 106 116 53 117 106 117 109 117 55 49 54 49 108 49 55 49 108 49 107 49 46 118 45 118 101 118 46 119 101 119 99 119 83 120 38 120 84 120 68 55 140 55 139 55 43 121 33 121 32 121 141 55 57 55 56 55 136 122 140 122 68 122 68 123 67 123 91 123 68 124 91 124 136 124 82 125 33 125 43 125 82 126 43 126 42 126 83 127 88 127 39 127 83 128 39 128 38 128 88 129 87 129 77 129 88 130 77 130 39 130 87 131 89 131 75 131 87 130 75 130 77 130 89 129 90 129 73 129 89 132 73 132 75 132 90 133 91 133 67 133 90 134 67 134 73 134 141 135 134 135 78 135 78 136 71 136 57 136 78 137 57 137 141 137 78 138 79 138 61 138 78 139 61 139 71 139 79 140 80 140 62 140 79 141 62 141 61 141 80 142 81 142 64 142 80 143 64 143 62 143 81 144 82 144 42 144 81 145 42 145 64 145 84 49 38 49 37 49 37 49 127 49 85 49 37 49 85 49 84 49 59 146 123 146 110 146 110 147 113 147 132 147 132 148 134 148 141 148 56 149 59 149 110 149 132 150 141 150 56 150 110 151 132 151 56 151 133 152 132 152 113 152 133 152 113 152 112 152 117 153 118 153 135 153 117 154 135 154 137 154 135 155 118 155 92 155 92 156 95 156 138 156 139 157 140 157 136 157 92 158 138 158 139 158 136 159 135 159 92 159 92 160 139 160 136 160 142 161 143 161 144 161 142 162 144 162 145 162 145 163 144 163 146 163 145 163 146 163 147 163 147 164 146 164 148 164 147 165 148 165 149 165 149 31 148 31 150 31 149 166 150 166 151 166 151 167 150 167 152 167 151 168 152 168 153 168 153 169 152 169 154 169 153 170 154 170 155 170 155 171 154 171 156 171 155 172 156 172 157 172 157 32 156 32 158 32 157 32 158 32 159 32 159 173 158 173 160 173 159 174 160 174 161 174 161 175 160 175 162 175 161 176 162 176 163 176 163 177 162 177 164 177 163 178 164 178 165 178 165 179 164 179 166 179 165 179 166 179 167 179 167 180 166 180 168 180 167 181 168 181 169 181 169 182 168 182 170 182 169 183 170 183 171 183 171 184 170 184 172 184 171 185 172 185 173 185 173 186 172 186 143 186 173 187 143 187 142 187 174 188 175 188 144 188 174 189 144 189 143 189 175 190 176 190 146 190 175 22 146 22 144 22 176 191 177 191 148 191 176 22 148 22 146 22 177 192 178 192 150 192 177 22 150 22 148 22 178 22 179 22 152 22 178 193 152 193 150 193 179 22 180 22 154 22 179 194 154 194 152 194 180 195 181 195 156 195 180 22 156 22 154 22 181 22 182 22 158 22 181 22 158 22 156 22 182 196 183 196 160 196 182 22 160 22 158 22 183 197 184 197 162 197 183 22 162 22 160 22 184 198 185 198 164 198 184 199 164 199 162 199 185 200 186 200 166 200 185 22 166 22 164 22 186 191 187 191 168 191 186 22 168 22 166 22 187 22 188 22 170 22 187 201 170 201 168 201 188 22 189 22 172 22 188 22 172 22 170 22 189 22 174 22 143 22 189 22 143 22 172 22 189 202 188 202 190 202 189 203 190 203 191 203 192 204 193 204 194 204 194 205 195 205 196 205 196 206 191 206 190 206 190 207 197 207 198 207 198 22 199 22 200 22 200 22 201 22 202 22 200 22 202 22 203 22 192 208 194 208 196 208 204 209 192 209 196 209 198 22 200 22 203 22 198 210 203 210 205 210 206 210 204 210 196 210 207 211 206 211 196 211 190 212 198 212 205 212 190 22 205 22 208 22 207 22 196 22 190 22 190 22 208 22 207 22 209 213 201 213 200 213 200 22 210 22 211 22 211 214 212 214 213 214 213 22 214 22 215 22 215 215 216 215 194 215 194 22 193 22 217 22 194 22 217 22 218 22 209 22 200 22 211 22 219 216 209 216 211 216 215 217 194 217 218 217 215 22 218 22 220 22 221 22 219 22 211 22 222 218 221 218 211 218 213 219 215 219 220 219 213 220 220 220 223 220 222 22 211 22 213 22 213 22 223 22 222 22 182 221 181 221 212 221 182 222 212 222 211 222 175 223 174 223 196 223 175 224 196 224 195 224 174 225 189 225 191 225 174 226 191 226 196 226 183 227 182 227 211 227 183 228 211 228 210 228 176 229 175 229 195 229 176 230 195 230 194 230 184 231 183 231 210 231 184 232 210 232 200 232 177 233 176 233 194 233 177 234 194 234 216 234 185 235 184 235 200 235 185 235 200 235 199 235 178 236 177 236 216 236 178 237 216 237 215 237 186 166 185 166 199 166 186 238 199 238 198 238 179 239 178 239 215 239 179 240 215 240 214 240 187 241 186 241 198 241 187 242 198 242 197 242 180 243 179 243 214 243 180 243 214 243 213 243 188 244 187 244 197 244 188 244 197 244 190 244 181 245 180 245 213 245 181 246 213 246 212 246 224 247 173 247 142 247 142 15 145 15 147 15 147 248 149 248 151 248 151 249 153 249 155 249 155 250 157 250 225 250 155 251 225 251 226 251 227 252 224 252 142 252 228 253 227 253 142 253 155 254 226 254 229 254 155 15 229 15 230 15 228 255 142 255 147 255 231 256 228 256 147 256 151 15 155 15 230 15 151 15 230 15 232 15 233 15 231 15 147 15 151 257 232 257 233 257 147 258 151 258 233 258 234 15 225 15 157 15 157 15 159 15 161 15 161 259 163 259 165 259 165 260 167 260 169 260 169 15 171 15 173 15 173 261 224 261 235 261 173 15 235 15 236 15 234 262 157 262 161 262 237 15 234 15 161 15 169 263 173 263 236 263 169 264 236 264 238 264 239 265 237 265 161 265 240 15 239 15 161 15 165 15 169 15 238 15 165 15 238 15 241 15 240 266 161 266 165 266 165 15 241 15 240 15 229 267 226 267 222 267 229 268 222 268 223 268 234 269 221 269 222 269 222 270 226 270 225 270 222 271 225 271 234 271 221 272 234 272 237 272 221 273 237 273 219 273 237 274 239 274 209 274 237 275 209 275 219 275 209 276 239 276 240 276 240 277 202 277 201 277 240 278 201 278 209 278 241 279 203 279 202 279 241 280 202 280 240 280 238 281 205 281 203 281 238 282 203 282 241 282 236 283 208 283 205 283 236 284 205 284 238 284 235 285 207 285 208 285 235 286 208 286 236 286 206 287 207 287 235 287 224 288 227 288 206 288 235 289 224 289 206 289 228 290 204 290 206 290 228 291 206 291 227 291 231 292 192 292 204 292 231 292 204 292 228 292 231 293 233 293 217 293 193 294 192 294 231 294 217 295 193 295 231 295 218 296 217 296 233 296 218 297 233 297 232 297 218 298 232 298 230 298 218 299 230 299 220 299 230 300 229 300 223 300 230 301 223 301 220 301 242 302 244 302 243 302 244 303 246 303 245 303 244 304 242 304 246 304 247 305 249 305 248 305 249 306 251 306 250 306 249 307 247 307 251 307 248 308 242 308 247 308 248 309 246 309 242 309 252 310 246 310 253 310 246 311 254 311 245 311 246 312 252 312 254 312 255 313 249 313 256 313 249 314 257 314 248 314 249 315 255 315 257 315 245 316 256 316 249 316 245 317 254 317 256 317 254 15 255 15 256 15 254 318 252 318 255 318 257 319 252 319 253 319 257 320 255 320 252 320 248 321 253 321 246 321 248 322 257 322 253 322 242 323 251 323 247 323 242 324 243 324 251 324 250 22 243 22 244 22 250 325 251 325 243 325 258 326 260 326 259 326 260 327 262 327 261 327 260 328 258 328 262 328 263 329 265 329 264 329 265 330 267 330 266 330 265 331 263 331 267 331 264 332 258 332 263 332 264 333 262 333 258 333 268 334 262 334 269 334 262 335 270 335 261 335 262 336 268 336 270 336 271 337 265 337 272 337 265 338 273 338 264 338 265 339 271 339 273 339 261 340 272 340 265 340 261 341 270 341 272 341 270 15 271 15 272 15 270 342 268 342 271 342 273 343 268 343 269 343 273 344 271 344 268 344 264 345 269 345 262 345 264 346 273 346 269 346 258 347 267 347 263 347 258 348 259 348 267 348 266 349 259 349 260 349 266 350 267 350 259 350 274 351 276 351 275 351 276 57 278 57 277 57 276 352 274 352 278 352 279 55 281 55 280 55 279 55 282 55 281 55 283 353 285 353 284 353 283 354 286 354 285 354 287 355 289 355 288 355 287 22 276 22 289 22 290 22 292 22 291 22 290 22 293 22 292 22 294 356 296 356 295 356 294 22 297 22 296 22 298 51 300 51 299 51 298 51 301 51 300 51 302 49 304 49 303 49 302 49 305 49 304 49 305 49 306 49 304 49 305 49 307 49 306 49 307 49 284 49 306 49 307 357 283 357 284 357 308 55 310 55 309 55 308 55 311 55 310 55 312 49 303 49 313 49 312 49 302 49 303 49 314 55 309 55 315 55 314 55 308 55 309 55 316 55 315 55 317 55 316 55 314 55 315 55 318 55 317 55 319 55 318 55 316 55 317 55 282 55 319 55 281 55 282 55 318 55 319 55 320 22 293 22 290 22 320 22 321 22 293 22 321 22 294 22 293 22 321 22 322 22 294 22 322 22 297 22 294 22 322 22 323 22 297 22 323 22 287 22 297 22 323 22 324 22 287 22 289 57 326 57 325 57 326 57 328 57 327 57 326 57 289 57 328 57 296 22 330 22 329 22 296 22 288 22 330 22 295 22 329 22 331 22 295 22 296 22 329 22 292 22 331 22 332 22 292 22 295 22 331 22 291 22 332 22 333 22 291 22 292 22 332 22 334 49 336 49 335 49 334 49 337 49 336 49 338 55 278 55 339 55 338 55 340 55 278 55 341 15 327 15 328 15 341 15 342 15 327 15 340 15 277 15 278 15 340 15 343 15 277 15 343 15 328 15 277 15 343 358 341 358 328 358 344 15 346 15 345 15 344 15 347 15 346 15 348 15 350 15 349 15 348 359 351 359 350 359 352 15 344 15 353 15 344 15 355 15 354 15 344 15 352 15 355 15 353 15 345 15 356 15 353 15 344 15 345 15 356 15 348 15 357 15 356 15 345 15 348 15 357 15 349 15 358 15 357 15 348 15 349 15 358 15 343 15 340 15 358 15 349 15 343 15 359 15 335 15 347 15 335 15 360 15 334 15 335 360 359 360 360 360 347 15 361 15 346 15 347 15 335 15 361 15 346 15 362 15 351 15 346 15 361 15 362 15 351 15 363 15 350 15 351 15 362 15 363 15 350 15 342 15 341 15 350 15 363 15 342 15 364 55 352 55 353 55 364 55 365 55 352 55 364 55 356 55 366 55 364 55 353 55 356 55 366 55 357 55 367 55 366 55 356 55 357 55 367 55 358 55 368 55 367 55 357 55 358 55 368 361 340 361 338 361 368 55 358 55 340 55 369 49 342 49 370 49 369 49 327 49 342 49 370 49 363 49 371 49 370 49 342 49 363 49 371 49 362 49 372 49 371 49 363 49 362 49 372 49 361 49 373 49 372 49 362 49 361 49 373 49 335 49 336 49 373 49 361 49 335 49 279 15 370 15 282 15 279 15 369 15 370 15 288 22 325 22 330 22 288 22 289 22 325 22 324 22 276 22 287 22 324 22 275 22 276 22 374 22 290 22 375 22 290 22 376 22 320 22 290 22 374 22 376 22 300 49 313 49 299 49 300 49 312 49 313 49 301 15 312 15 300 15 312 15 365 15 364 15 312 362 301 362 365 362 377 22 333 22 378 22 333 22 379 22 291 22 333 363 377 363 379 363 380 51 310 51 311 51 380 364 381 364 310 364 286 365 274 365 285 365 274 57 339 57 278 57 274 366 286 366 339 366 276 57 328 57 289 57 276 57 277 57 328 57 337 15 308 15 336 15 308 15 380 15 311 15 308 15 337 15 380 15 314 15 336 15 308 15 314 15 373 15 336 15 316 15 373 15 314 15 316 15 372 15 373 15 318 15 372 15 316 15 318 15 371 15 372 15 282 15 371 15 318 15 282 15 370 15 371 15 283 15 339 15 286 15 283 15 338 15 339 15 307 15 338 15 283 15 307 15 368 15 338 15 305 15 368 15 307 15 305 15 367 15 368 15 302 15 367 15 305 15 302 15 366 15 367 15 312 15 366 15 302 15 312 15 364 15 366 15 354 55 290 55 344 55 354 55 375 55 290 55 294 55 345 55 293 55 294 55 348 55 345 55 287 55 349 55 297 55 287 55 343 55 349 55 379 49 347 49 291 49 379 49 359 49 347 49 292 367 351 367 295 367 292 368 346 368 351 368 296 49 341 49 288 49 296 49 350 49 341 49 291 51 344 51 290 51 291 51 347 51 344 51 293 57 346 57 292 57 293 57 345 57 346 57 295 51 348 51 294 51 295 51 351 51 348 51 297 57 350 57 296 57 297 57 349 57 350 57 288 51 343 51 287 51 288 369 341 369 343 369 325 57 326 57 280 57 310 370 381 370 382 370 285 371 274 371 275 371 383 372 298 372 299 372 378 373 310 373 382 373 310 374 333 374 309 374 310 375 378 375 333 375 324 376 285 376 275 376 324 377 284 377 285 377 325 378 281 378 330 378 325 379 280 379 281 379 330 378 319 378 329 378 330 380 281 380 319 380 329 381 317 381 331 381 329 380 319 380 317 380 331 378 315 378 332 378 331 380 317 380 315 380 332 378 309 378 333 378 332 380 315 380 309 380 383 382 320 382 376 382 320 383 299 383 313 383 320 384 383 384 299 384 320 385 303 385 321 385 320 385 313 385 303 385 321 385 304 385 322 385 321 385 303 385 304 385 322 385 306 385 323 385 322 383 304 383 306 383 323 385 284 385 324 385 323 385 306 385 284 385 326 57 279 57 280 57 279 57 327 57 369 57 279 386 326 386 327 386 301 387 352 387 365 387 352 388 374 388 355 388 374 389 383 389 376 389 298 390 352 390 301 390 374 391 298 391 383 391 352 392 298 392 374 392 375 393 355 393 374 393 375 394 354 394 355 394 359 395 377 395 360 395 359 396 379 396 377 396 377 397 334 397 360 397 334 398 380 398 337 398 381 399 378 399 382 399 334 400 381 400 380 400 378 401 334 401 377 401 334 402 378 402 381 402 384 403 386 403 385 403 384 404 387 404 386 404 387 405 388 405 386 405 387 405 389 405 388 405 389 406 390 406 388 406 389 406 391 406 390 406 391 407 392 407 390 407 391 407 393 407 392 407 393 408 394 408 392 408 393 408 395 408 394 408 395 409 396 409 394 409 395 410 397 410 396 410 397 411 398 411 396 411 397 412 399 412 398 412 399 413 400 413 398 413 399 413 401 413 400 413 401 414 402 414 400 414 401 415 403 415 402 415 403 416 404 416 402 416 403 416 405 416 404 416 405 417 406 417 404 417 405 418 407 418 406 418 407 419 408 419 406 419 407 419 409 419 408 419 409 420 410 420 408 420 409 420 411 420 410 420 411 421 412 421 410 421 411 422 413 422 412 422 413 423 414 423 412 423 413 423 415 423 414 423 415 424 385 424 414 424 415 424 384 424 385 424 416 425 386 425 417 425 416 22 385 22 386 22 417 22 388 22 418 22 417 426 386 426 388 426 418 22 390 22 419 22 418 22 388 22 390 22 419 22 392 22 420 22 419 22 390 22 392 22 420 427 394 427 421 427 420 22 392 22 394 22 421 428 396 428 422 428 421 22 394 22 396 22 422 429 398 429 423 429 422 22 396 22 398 22 423 430 400 430 424 430 423 431 398 431 400 431 424 432 402 432 425 432 424 22 400 22 402 22 425 22 404 22 426 22 425 433 402 433 404 433 426 22 406 22 427 22 426 22 404 22 406 22 427 22 408 22 428 22 427 22 406 22 408 22 428 22 410 22 429 22 428 22 408 22 410 22 429 434 412 434 430 434 429 22 410 22 412 22 430 435 414 435 431 435 430 436 412 436 414 436 431 437 385 437 416 437 431 438 414 438 385 438 431 439 432 439 430 439 431 440 433 440 432 440 434 22 436 22 435 22 436 22 438 22 437 22 438 441 432 441 433 441 432 442 440 442 439 442 440 22 442 22 441 22 442 443 444 443 443 443 442 22 445 22 444 22 434 22 438 22 436 22 446 444 438 444 434 444 440 22 445 22 442 22 440 445 447 445 445 445 448 446 438 446 446 446 449 22 438 22 448 22 432 22 447 22 440 22 432 22 450 22 447 22 449 22 432 22 438 22 432 22 449 22 450 22 451 22 442 22 443 22 442 22 453 22 452 22 453 447 455 447 454 447 455 22 457 22 456 22 457 22 436 22 458 22 436 448 459 448 435 448 436 22 460 22 459 22 451 22 453 22 442 22 461 449 453 449 451 449 457 22 460 22 436 22 457 450 462 450 460 450 463 451 453 451 461 451 464 22 453 22 463 22 455 22 462 22 457 22 455 22 465 22 462 22 464 22 455 22 453 22 455 22 464 22 465 22 424 452 454 452 423 452 424 452 453 452 454 452 417 453 438 453 416 453 417 453 437 453 438 453 416 454 433 454 431 454 416 454 438 454 433 454 425 455 453 455 424 455 425 455 452 455 453 455 418 456 437 456 417 456 418 457 436 457 437 457 426 458 452 458 425 458 426 459 442 459 452 459 419 460 436 460 418 460 419 461 458 461 436 461 427 462 442 462 426 462 427 463 441 463 442 463 420 464 458 464 419 464 420 465 457 465 458 465 428 466 441 466 427 466 428 467 440 467 441 467 421 468 457 468 420 468 421 469 456 469 457 469 429 470 440 470 428 470 429 471 439 471 440 471 422 472 456 472 421 472 422 473 455 473 456 473 430 474 439 474 429 474 430 475 432 475 439 475 423 476 455 476 422 476 423 477 454 477 455 477 466 15 384 15 415 15 384 478 389 478 387 478 389 15 393 15 391 15 393 15 397 15 395 15 397 15 467 15 399 15 397 479 468 479 467 479 469 15 384 15 466 15 470 15 384 15 469 15 397 15 471 15 468 15 397 15 472 15 471 15 470 15 389 15 384 15 473 15 389 15 470 15 393 15 472 15 397 15 393 15 474 15 472 15 475 15 389 15 473 15 393 15 475 15 474 15 389 480 475 480 393 480 476 15 399 15 467 15 399 15 403 15 401 15 403 15 407 15 405 15 407 15 411 15 409 15 411 481 415 481 413 481 415 15 477 15 466 15 415 15 478 15 477 15 476 15 403 15 399 15 479 15 403 15 476 15 411 482 478 482 415 482 411 15 480 15 478 15 481 15 403 15 479 15 482 15 403 15 481 15 407 483 480 483 411 483 407 484 483 484 480 484 482 15 407 15 403 15 407 15 482 15 483 15 471 485 464 485 468 485 471 486 465 486 464 486 476 487 464 487 463 487 464 488 467 488 468 488 464 489 476 489 467 489 463 490 479 490 476 490 463 491 461 491 479 491 479 492 451 492 481 492 479 493 461 493 451 493 451 494 482 494 481 494 482 495 443 495 444 495 482 496 451 496 443 496 483 497 444 497 445 497 483 498 482 498 444 498 480 499 445 499 447 499 480 500 483 500 445 500 478 501 447 501 450 501 478 502 480 502 447 502 477 503 450 503 449 503 477 504 478 504 450 504 448 505 477 505 449 505 466 506 448 506 469 506 477 507 448 507 466 507 470 508 448 508 446 508 470 508 469 508 448 508 473 509 446 509 434 509 473 510 470 510 446 510 473 511 459 511 475 511 435 512 473 512 434 512 459 513 473 513 435 513 460 514 475 514 459 514 460 514 474 514 475 514 460 515 472 515 474 515 460 296 462 296 472 296 472 516 465 516 471 516 472 517 462 517 465 517 484 518 486 518 485 518 486 519 488 519 487 519 486 520 484 520 488 520 489 521 491 521 490 521 491 522 493 522 492 522 491 523 489 523 493 523 490 524 484 524 489 524 490 525 488 525 484 525 494 526 488 526 495 526 488 527 496 527 487 527 488 528 494 528 496 528 497 529 491 529 498 529 491 530 499 530 490 530 491 531 497 531 499 531 487 532 498 532 491 532 487 533 496 533 498 533 496 15 497 15 498 15 496 534 494 534 497 534 499 535 494 535 495 535 499 536 497 536 494 536 490 537 495 537 488 537 490 538 499 538 495 538 484 539 493 539 489 539 484 540 485 540 493 540 492 22 485 22 486 22 492 541 493 541 485 541 500 542 502 542 501 542 502 543 504 543 503 543 502 544 500 544 504 544 505 545 507 545 506 545 507 546 509 546 508 546 507 547 505 547 509 547 506 548 500 548 505 548 506 549 504 549 500 549 510 550 504 550 511 550 504 551 512 551 503 551 504 552 510 552 512 552 513 553 507 553 514 553 507 554 515 554 506 554 507 555 513 555 515 555 503 556 514 556 507 556 503 557 512 557 514 557 512 15 513 15 514 15 512 558 510 558 513 558 515 559 510 559 511 559 515 560 513 560 510 560 506 561 511 561 504 561 506 562 515 562 511 562 500 563 509 563 505 563 500 564 501 564 509 564 508 565 501 565 502 565 508 566 509 566 501 566 516 567 518 567 517 567 518 51 520 51 519 51 518 568 516 568 520 568 521 49 523 49 522 49 521 49 524 49 523 49 525 569 527 569 526 569 525 570 528 570 527 570 529 571 531 571 530 571 529 22 518 22 531 22 532 22 534 22 533 22 532 22 535 22 534 22 536 355 538 355 537 355 536 22 539 22 538 22 540 57 542 57 541 57 540 57 543 57 542 57 544 55 546 55 545 55 544 55 547 55 546 55 547 55 548 55 546 55 547 55 549 55 548 55 549 55 526 55 548 55 549 572 525 572 526 572 550 49 552 49 551 49 550 49 553 49 552 49 554 55 545 55 555 55 554 55 544 55 545 55 556 49 551 49 557 49 556 49 550 49 551 49 558 49 557 49 559 49 558 49 556 49 557 49 560 49 559 49 561 49 560 49 558 49 559 49 524 49 561 49 523 49 524 49 560 49 561 49 562 22 535 22 532 22 562 22 563 22 535 22 563 22 536 22 535 22 563 22 564 22 536 22 564 22 539 22 536 22 564 22 565 22 539 22 565 22 529 22 539 22 565 22 566 22 529 22 531 51 568 51 567 51 568 51 570 51 569 51 568 51 531 51 570 51 538 22 572 22 571 22 538 22 530 22 572 22 537 22 571 22 573 22 537 22 538 22 571 22 534 22 573 22 574 22 534 22 537 22 573 22 533 22 574 22 575 22 533 22 534 22 574 22 576 55 578 55 577 55 576 55 579 55 578 55 580 49 520 49 581 49 580 573 582 573 520 573 583 15 569 15 570 15 583 15 584 15 569 15 582 15 519 15 520 15 582 15 585 15 519 15 585 15 570 15 519 15 585 574 583 574 570 574 586 15 588 15 587 15 586 15 589 15 588 15 590 15 592 15 591 15 590 358 593 358 592 358 594 15 586 15 595 15 586 15 597 15 596 15 586 15 594 15 597 15 595 15 587 15 598 15 595 15 586 15 587 15 598 15 590 15 599 15 598 15 587 15 590 15 599 15 591 15 600 15 599 15 590 15 591 15 600 15 585 15 582 15 600 15 591 15 585 15 601 15 577 15 589 15 577 15 602 15 576 15 577 575 601 575 602 575 589 15 603 15 588 15 589 15 577 15 603 15 588 15 604 15 593 15 588 15 603 15 604 15 593 15 605 15 592 15 593 15 604 15 605 15 592 15 584 15 583 15 592 15 605 15 584 15 606 49 594 49 595 49 606 49 607 49 594 49 606 49 598 49 608 49 606 49 595 49 598 49 608 49 599 49 609 49 608 49 598 49 599 49 609 49 600 49 610 49 609 49 599 49 600 49 610 576 582 576 580 576 610 49 600 49 582 49 611 55 584 55 612 55 611 55 569 55 584 55 612 55 605 55 613 55 612 55 584 55 605 55 613 55 604 55 614 55 613 55 605 55 604 55 614 55 603 55 615 55 614 55 604 55 603 55 615 55 577 55 578 55 615 55 603 55 577 55 521 15 612 15 524 15 521 15 611 15 612 15 530 22 567 22 572 22 530 22 531 22 567 22 566 22 518 22 529 22 566 22 517 22 518 22 616 22 532 22 617 22 532 22 618 22 562 22 532 22 616 22 618 22 542 55 555 55 541 55 542 55 554 55 555 55 543 15 554 15 542 15 554 15 607 15 606 15 554 577 543 577 607 577 619 22 575 22 620 22 575 22 621 22 533 22 575 578 619 578 621 578 622 57 552 57 553 57 622 579 623 579 552 579 528 580 516 580 527 580 516 51 581 51 520 51 516 581 528 581 581 581 518 51 570 51 531 51 518 51 519 51 570 51 579 15 550 15 578 15 550 15 622 15 553 15 550 15 579 15 622 15 556 15 578 15 550 15 556 15 615 15 578 15 558 15 615 15 556 15 558 15 614 15 615 15 560 15 614 15 558 15 560 15 613 15 614 15 524 15 613 15 560 15 524 15 612 15 613 15 525 15 581 15 528 15 525 15 580 15 581 15 549 15 580 15 525 15 549 15 610 15 580 15 547 15 610 15 549 15 547 15 609 15 610 15 544 15 609 15 547 15 544 15 608 15 609 15 554 15 608 15 544 15 554 15 606 15 608 15 596 49 532 49 586 49 596 49 617 49 532 49 536 49 587 49 535 49 536 49 590 49 587 49 529 49 591 49 539 49 529 49 585 49 591 49 621 55 589 55 533 55 621 55 601 55 589 55 534 582 593 582 537 582 534 583 588 583 593 583 538 55 583 55 530 55 538 55 592 55 583 55 533 57 586 57 532 57 533 57 589 57 586 57 535 51 588 51 534 51 535 51 587 51 588 51 537 57 590 57 536 57 537 57 593 57 590 57 539 51 592 51 538 51 539 51 591 51 592 51 530 57 585 57 529 57 530 584 583 584 585 584 567 51 568 51 522 51 552 585 623 585 624 585 527 586 516 586 517 586 625 587 540 587 541 587 620 588 552 588 624 588 552 383 575 383 551 383 552 589 620 589 575 589 566 379 527 379 517 379 566 590 526 590 527 590 567 385 523 385 572 385 567 376 522 376 523 376 572 385 561 385 571 385 572 385 523 385 561 385 571 383 559 383 573 383 571 385 561 385 559 385 573 385 557 385 574 385 573 385 559 385 557 385 574 385 551 385 575 385 574 385 557 385 551 385 625 591 562 591 618 591 562 374 541 374 555 374 562 592 625 592 541 592 562 378 545 378 563 378 562 380 555 380 545 380 563 378 546 378 564 378 563 380 545 380 546 380 564 378 548 378 565 378 564 374 546 374 548 374 565 378 526 378 566 378 565 380 548 380 526 380 568 51 521 51 522 51 521 51 569 51 611 51 521 593 568 593 569 593 543 594 594 594 607 594 594 595 616 595 597 595 616 596 625 596 618 596 540 597 594 597 543 597 616 598 540 598 625 598 594 599 540 599 616 599 617 600 597 600 616 600 617 601 596 601 597 601 601 602 619 602 602 602 601 603 621 603 619 603 619 604 576 604 602 604 576 605 622 605 579 605 623 606 620 606 624 606 576 607 623 607 622 607 620 608 576 608 619 608 576 609 620 609 623 609 626 414 628 414 627 414 626 415 629 415 628 415 629 610 630 610 628 610 629 610 631 610 630 610 631 418 632 418 630 418 631 418 633 418 632 418 633 419 634 419 632 419 633 419 635 419 634 419 635 420 636 420 634 420 635 420 637 420 636 420 637 611 638 611 636 611 637 612 639 612 638 612 639 613 640 613 638 613 639 614 641 614 640 614 641 424 642 424 640 424 641 424 643 424 642 424 643 403 644 403 642 403 643 404 645 404 644 404 645 615 646 615 644 615 645 615 647 615 646 615 647 616 648 616 646 616 647 406 649 406 648 406 649 407 650 407 648 407 649 407 651 407 650 407 651 408 652 408 650 408 651 408 653 408 652 408 653 617 654 617 652 617 653 618 655 618 654 618 655 619 656 619 654 619 655 619 657 619 656 619 657 413 627 413 656 413 657 413 626 413 627 413 658 432 628 432 659 432 658 22 627 22 628 22 659 22 630 22 660 22 659 620 628 620 630 620 660 22 632 22 661 22 660 22 630 22 632 22 661 22 634 22 662 22 661 22 632 22 634 22 662 621 636 621 663 621 662 22 634 22 636 22 663 622 638 622 664 622 663 22 636 22 638 22 664 435 640 435 665 435 664 22 638 22 640 22 665 437 642 437 666 437 665 438 640 438 642 438 666 425 644 425 667 425 666 22 642 22 644 22 667 22 646 22 668 22 667 623 644 623 646 623 668 22 648 22 669 22 668 22 646 22 648 22 669 22 650 22 670 22 669 22 648 22 650 22 670 22 652 22 671 22 670 22 650 22 652 22 671 624 654 624 672 624 671 22 652 22 654 22 672 429 656 429 673 429 672 625 654 625 656 625 673 430 627 430 658 430 673 431 656 431 627 431 673 476 674 476 672 476 673 477 675 477 674 477 676 22 678 22 677 22 678 22 680 22 679 22 680 447 674 447 675 447 674 441 682 441 681 441 682 22 684 22 683 22 684 626 686 626 685 626 684 22 687 22 686 22 676 22 680 22 678 22 688 449 680 449 676 449 682 22 687 22 684 22 682 450 689 450 687 450 690 451 680 451 688 451 691 22 680 22 690 22 674 22 689 22 682 22 674 22 692 22 689 22 691 22 674 22 680 22 674 22 691 22 692 22 693 22 684 22 685 22 684 22 695 22 694 22 695 441 697 441 696 441 697 22 699 22 698 22 699 22 678 22 700 22 678 627 701 627 677 627 678 22 702 22 701 22 693 22 695 22 684 22 703 444 695 444 693 444 699 22 702 22 678 22 699 445 704 445 702 445 705 628 695 628 703 628 706 22 695 22 705 22 697 22 704 22 699 22 697 22 707 22 704 22 706 22 697 22 695 22 697 22 706 22 707 22 666 454 696 454 665 454 666 454 695 454 696 454 659 455 680 455 658 455 659 455 679 455 680 455 658 452 675 452 673 452 658 452 680 452 675 452 667 453 695 453 666 453 667 453 694 453 695 453 660 629 679 629 659 629 660 630 678 630 679 630 668 631 694 631 667 631 668 632 684 632 694 632 661 462 678 462 660 462 661 463 700 463 678 463 669 460 684 460 668 460 669 461 683 461 684 461 662 466 700 466 661 466 662 633 699 633 700 633 670 464 683 464 669 464 670 634 682 634 683 634 663 635 699 635 662 635 663 636 698 636 699 636 671 637 682 637 670 637 671 638 681 638 682 638 664 639 698 639 663 639 664 640 697 640 698 640 672 641 681 641 671 641 672 642 674 642 681 642 665 439 697 439 664 439 665 440 696 440 697 440 708 15 626 15 657 15 626 643 631 643 629 643 631 15 635 15 633 15 635 15 639 15 637 15 639 15 709 15 641 15 639 644 710 644 709 644 711 15 626 15 708 15 712 15 626 15 711 15 639 15 713 15 710 15 639 15 714 15 713 15 712 15 631 15 626 15 715 15 631 15 712 15 635 15 714 15 639 15 635 15 716 15 714 15 717 15 631 15 715 15 635 15 717 15 716 15 631 645 717 645 635 645 718 15 641 15 709 15 641 15 645 15 643 15 645 15 649 15 647 15 649 15 653 15 651 15 653 646 657 646 655 646 657 15 719 15 708 15 657 15 720 15 719 15 718 15 645 15 641 15 721 15 645 15 718 15 653 647 720 647 657 647 653 15 722 15 720 15 723 15 645 15 721 15 724 15 645 15 723 15 649 648 722 648 653 648 649 649 725 649 722 649 724 15 649 15 645 15 649 15 724 15 725 15 713 504 706 504 710 504 713 503 707 503 706 503 718 650 706 650 705 650 706 651 709 651 710 651 706 652 718 652 709 652 705 508 721 508 718 508 705 653 703 653 721 653 721 510 693 510 723 510 721 509 703 509 693 509 693 654 724 654 723 654 724 655 685 655 686 655 724 656 693 656 685 656 725 514 686 514 687 514 725 657 724 657 686 657 722 296 687 296 689 296 722 658 725 658 687 658 720 517 689 517 692 517 720 516 722 516 689 516 719 486 692 486 691 486 719 485 720 485 692 485 690 659 719 659 691 659 708 660 690 660 711 660 719 661 690 661 708 661 712 490 690 490 688 490 712 490 711 490 690 490 715 493 688 493 676 493 715 492 712 492 688 492 715 662 701 662 717 662 677 663 715 663 676 663 701 664 715 664 677 664 702 497 717 497 701 497 702 497 716 497 717 497 702 665 714 665 716 665 702 499 704 499 714 499 714 502 707 502 713 502 714 501 704 501 707 501 726 666 727 666 728 666 728 667 729 667 730 667 728 668 730 668 726 668 731 669 732 669 733 669 733 670 734 670 735 670 733 671 735 671 731 671 732 672 731 672 726 672 732 672 726 672 730 672 736 11 737 11 730 11 730 673 729 673 738 673 730 674 738 674 736 674 739 675 740 675 733 675 733 676 732 676 741 676 733 677 741 677 739 677 729 678 733 678 740 678 729 678 740 678 738 678 738 15 740 15 739 15 738 15 739 15 736 15 741 679 737 679 736 679 741 680 736 680 739 680 732 681 730 681 737 681 732 682 737 682 741 682 726 683 731 683 735 683 726 684 735 684 727 684 734 22 728 22 727 22 734 22 727 22 735 22 742 685 743 685 744 685 744 686 745 686 746 686 744 687 746 687 742 687 747 688 748 688 749 688 749 689 750 689 751 689 749 690 751 690 747 690 748 691 747 691 742 691 748 692 742 692 746 692 752 693 753 693 746 693 746 686 745 686 754 686 746 694 754 694 752 694 755 695 756 695 749 695 749 689 748 689 757 689 749 696 757 696 755 696 745 697 749 697 756 697 745 698 756 698 754 698 754 15 756 15 755 15 754 15 755 15 752 15 757 699 753 699 752 699 757 700 752 700 755 700 748 701 746 701 753 701 748 702 753 702 757 702 742 703 747 703 751 703 742 704 751 704 743 704 750 22 744 22 743 22 750 705 743 705 751 705 758 706 759 706 760 706 760 55 761 55 762 55 760 55 762 55 758 55 763 57 764 57 765 57 763 57 765 57 766 57 767 707 768 707 769 707 767 708 769 708 770 708 771 22 772 22 773 22 771 22 773 22 760 22 774 22 775 22 776 22 774 22 776 22 777 22 778 22 779 22 780 22 778 22 780 22 781 22 782 49 783 49 784 49 782 49 784 49 785 49 786 51 787 51 788 51 786 51 788 51 789 51 789 51 788 51 790 51 789 51 790 51 791 51 791 51 790 51 768 51 791 51 768 51 767 51 792 57 793 57 794 57 792 57 794 57 795 57 796 51 797 51 787 51 796 51 787 51 786 51 798 57 799 57 793 57 798 57 793 57 792 57 800 57 801 57 799 57 800 57 799 57 798 57 802 57 803 57 801 57 802 57 801 57 800 57 766 57 765 57 803 57 766 57 803 57 802 57 804 22 774 22 777 22 804 22 777 22 805 22 805 22 777 22 778 22 805 22 778 22 806 22 806 22 778 22 781 22 806 22 781 22 807 22 807 22 781 22 771 22 807 22 771 22 808 22 773 709 809 709 810 709 810 55 811 55 812 55 810 55 812 55 773 55 780 22 813 22 814 22 780 22 814 22 772 22 779 22 815 22 813 22 779 22 813 22 780 22 776 22 816 22 815 22 776 22 815 22 779 22 775 22 817 22 816 22 775 22 816 22 776 22 818 51 819 51 820 51 818 51 820 51 821 51 822 57 823 57 762 57 822 57 762 57 824 57 825 15 812 15 811 15 825 15 811 15 826 15 824 15 762 15 761 15 824 15 761 15 827 15 827 15 761 15 812 15 827 15 812 15 825 15 828 15 829 15 830 15 828 15 830 15 831 15 832 15 833 15 834 15 832 15 834 15 835 15 836 15 837 15 828 15 828 710 838 710 839 710 828 711 839 711 836 711 837 15 840 15 829 15 837 15 829 15 828 15 840 15 841 15 832 15 840 15 832 15 829 15 841 15 842 15 833 15 841 15 833 15 832 15 842 15 824 15 827 15 842 15 827 15 833 15 843 15 831 15 819 15 819 712 818 712 844 712 819 713 844 713 843 713 831 15 830 15 845 15 831 15 845 15 819 15 830 15 835 15 846 15 830 15 846 15 845 15 835 15 834 15 847 15 835 15 847 15 846 15 834 15 825 15 826 15 834 15 826 15 847 15 848 57 837 57 836 57 848 57 836 57 849 57 848 57 850 57 840 57 848 57 840 57 837 57 850 57 851 57 841 57 850 57 841 57 840 57 851 57 852 57 842 57 851 57 842 57 841 57 852 57 822 57 824 57 852 57 824 57 842 57 853 51 854 51 826 51 853 51 826 51 811 51 854 51 855 51 847 51 854 51 847 51 826 51 855 51 856 51 846 51 855 51 846 51 847 51 856 51 857 51 845 51 856 51 845 51 846 51 857 51 820 51 819 51 857 51 819 51 845 51 763 15 766 15 854 15 763 15 854 15 853 15 772 22 814 22 809 22 772 22 809 22 773 22 808 22 771 22 760 22 808 22 760 22 759 22 858 22 859 22 774 22 774 22 804 22 860 22 774 22 860 22 858 22 784 51 783 51 797 51 784 51 797 51 796 51 785 15 784 15 796 15 796 15 848 15 849 15 796 714 849 714 785 714 861 22 862 22 817 22 817 22 775 22 863 22 817 715 863 715 861 715 864 49 795 49 794 49 864 49 794 49 865 49 770 55 769 55 758 55 758 55 762 55 823 55 758 55 823 55 770 55 760 55 773 55 812 55 760 55 812 55 761 55 821 15 820 15 792 15 792 15 795 15 864 15 792 716 864 716 821 716 798 15 792 15 820 15 798 15 820 15 857 15 800 15 798 15 857 15 800 15 857 15 856 15 802 15 800 15 856 15 802 15 856 15 855 15 766 15 802 15 855 15 766 15 855 15 854 15 767 15 770 15 823 15 767 15 823 15 822 15 791 15 767 15 822 15 791 15 822 15 852 15 789 15 791 15 852 15 789 15 852 15 851 15 786 15 789 15 851 15 786 15 851 15 850 15 796 15 786 15 850 15 796 15 850 15 848 15 838 57 828 57 774 57 838 57 774 57 859 57 778 57 777 57 829 57 778 57 829 57 832 57 771 57 781 57 833 57 771 57 833 57 827 57 863 51 775 51 831 51 863 51 831 51 843 51 776 717 779 717 835 717 776 718 835 718 830 718 780 51 772 51 825 51 780 51 825 51 834 51 775 49 774 49 828 49 775 49 828 49 831 49 777 55 776 55 830 55 777 55 830 55 829 55 779 49 778 49 832 49 779 49 832 49 835 49 781 55 780 55 834 55 781 55 834 55 833 55 772 49 771 49 827 49 772 49 827 49 825 49 809 719 764 719 810 719 794 49 866 49 865 49 769 720 759 720 758 720 867 49 783 49 782 49 862 721 866 721 794 721 794 722 793 722 817 722 794 723 817 723 862 723 808 724 759 724 769 724 808 725 769 725 768 725 809 726 814 726 765 726 809 722 765 722 764 722 814 727 813 727 803 727 814 728 803 728 765 728 813 726 815 726 801 726 813 728 801 728 803 728 815 726 816 726 799 726 815 722 799 722 801 722 816 726 817 726 793 726 816 728 793 728 799 728 867 729 860 729 804 729 804 730 797 730 783 730 804 731 783 731 867 731 804 129 805 129 787 129 804 732 787 732 797 732 805 733 806 733 788 733 805 732 788 732 787 732 806 129 807 129 790 129 806 732 790 732 788 732 807 129 808 129 768 129 807 730 768 730 790 730 810 55 764 55 763 55 763 55 853 55 811 55 763 734 811 734 810 734 785 735 849 735 836 735 836 736 839 736 858 736 858 737 860 737 867 737 782 738 785 738 836 738 858 739 867 739 782 739 836 740 858 740 782 740 859 741 858 741 839 741 859 742 839 742 838 742 843 743 844 743 861 743 843 744 861 744 863 744 861 745 844 745 818 745 818 746 821 746 864 746 865 747 866 747 862 747 818 748 864 748 865 748 862 749 861 749 818 749 818 750 865 750 862 750 868 751 869 751 870 751 868 752 870 752 871 752 871 753 870 753 872 753 871 754 872 754 873 754 873 755 872 755 874 755 873 756 874 756 875 756 875 757 874 757 876 757 875 757 876 757 877 757 877 758 876 758 878 758 877 759 878 759 879 759 879 760 878 760 880 760 879 760 880 760 881 760 881 761 880 761 882 761 881 762 882 762 883 762 883 763 882 763 884 763 883 764 884 764 885 764 885 765 884 765 886 765 885 766 886 766 887 766 887 767 886 767 888 767 887 768 888 768 889 768 889 769 888 769 890 769 889 770 890 770 891 770 891 771 890 771 892 771 891 771 892 771 893 771 893 772 892 772 894 772 893 773 894 773 895 773 895 774 894 774 896 774 895 774 896 774 897 774 897 775 896 775 898 775 897 776 898 776 899 776 899 777 898 777 869 777 899 778 869 778 868 778 900 779 901 779 870 779 900 780 870 780 869 780 901 437 902 437 872 437 901 781 872 781 870 781 902 782 903 782 874 782 902 783 874 783 872 783 903 784 904 784 876 784 903 22 876 22 874 22 904 785 905 785 878 785 904 786 878 786 876 786 905 22 906 22 880 22 905 787 880 787 878 787 906 22 907 22 882 22 906 22 882 22 880 22 907 22 908 22 884 22 907 22 884 22 882 22 908 788 909 788 886 788 908 783 886 783 884 783 909 428 910 428 888 428 909 22 888 22 886 22 910 624 911 624 890 624 910 22 890 22 888 22 911 789 912 789 892 789 911 22 892 22 890 22 912 790 913 790 894 790 912 791 894 791 892 791 913 22 914 22 896 22 913 792 896 792 894 792 914 22 915 22 898 22 914 22 898 22 896 22 915 22 900 22 869 22 915 22 869 22 898 22 915 793 914 793 916 793 915 794 916 794 917 794 918 795 919 795 920 795 920 796 921 796 922 796 922 22 917 22 916 22 916 797 923 797 924 797 924 22 925 22 926 22 926 22 927 22 928 22 926 22 928 22 929 22 918 22 920 22 922 22 930 22 918 22 922 22 924 22 926 22 929 22 924 798 929 798 931 798 932 799 930 799 922 799 933 800 932 800 922 800 916 801 924 801 931 801 916 22 931 22 934 22 933 22 922 22 916 22 916 22 934 22 933 22 935 802 927 802 926 802 926 442 936 442 937 442 937 22 938 22 939 22 939 803 940 803 941 803 941 22 942 22 920 22 920 22 919 22 943 22 920 804 943 804 944 804 935 22 926 22 937 22 945 22 935 22 937 22 941 22 920 22 944 22 941 805 944 805 946 805 947 22 945 22 937 22 948 806 947 806 937 806 939 807 941 807 946 807 939 22 946 22 949 22 948 22 937 22 939 22 939 22 949 22 948 22 908 808 907 808 938 808 908 809 938 809 937 809 901 810 900 810 922 810 901 810 922 810 921 810 900 811 915 811 917 811 900 812 917 812 922 812 909 813 908 813 937 813 909 813 937 813 936 813 902 814 901 814 921 814 902 815 921 815 920 815 910 816 909 816 936 816 910 817 936 817 926 817 903 818 902 818 920 818 903 819 920 819 942 819 911 820 910 820 926 820 911 821 926 821 925 821 904 822 903 822 942 822 904 823 942 823 941 823 912 691 911 691 925 691 912 824 925 824 924 824 905 825 904 825 941 825 905 826 941 826 940 826 913 827 912 827 924 827 913 828 924 828 923 828 906 829 905 829 940 829 906 829 940 829 939 829 914 830 913 830 923 830 914 830 923 830 916 830 907 831 906 831 939 831 907 832 939 832 938 832 950 833 899 833 868 833 868 834 871 834 873 834 873 835 875 835 877 835 877 836 879 836 881 836 881 15 883 15 951 15 881 837 951 837 952 837 953 15 950 15 868 15 954 838 953 838 868 838 881 15 952 15 955 15 881 15 955 15 956 15 954 15 868 15 873 15 957 839 954 839 873 839 877 15 881 15 956 15 877 15 956 15 958 15 959 15 957 15 873 15 877 840 958 840 959 840 873 841 877 841 959 841 960 15 951 15 883 15 883 15 885 15 887 15 887 15 889 15 891 15 891 15 893 15 895 15 895 842 897 842 899 842 899 843 950 843 961 843 899 844 961 844 962 844 960 845 883 845 887 845 963 15 960 15 887 15 895 846 899 846 962 846 895 15 962 15 964 15 965 15 963 15 887 15 966 15 965 15 887 15 891 847 895 847 964 847 891 848 964 848 967 848 966 15 887 15 891 15 891 15 967 15 966 15 955 849 952 849 948 849 955 849 948 849 949 849 960 850 947 850 948 850 948 851 952 851 951 851 948 852 951 852 960 852 947 853 960 853 963 853 947 854 963 854 945 854 963 855 965 855 935 855 963 856 935 856 945 856 935 857 965 857 966 857 966 858 928 858 927 858 966 859 927 859 935 859 967 860 929 860 928 860 967 861 928 861 966 861 964 862 931 862 929 862 964 863 929 863 967 863 962 864 934 864 931 864 962 864 931 864 964 864 961 865 933 865 934 865 961 865 934 865 962 865 932 866 933 866 961 866 950 867 953 867 932 867 961 868 950 868 932 868 954 869 930 869 932 869 954 870 932 870 953 870 957 871 918 871 930 871 957 872 930 872 954 872 957 873 959 873 943 873 919 874 918 874 957 874 943 875 919 875 957 875 944 876 943 876 959 876 944 877 959 877 958 877 944 878 958 878 956 878 944 879 956 879 946 879 956 880 955 880 949 880 956 880 949 880 946 880

+
+
+
+ + + + 0 -0.001999974 -0.001999974 0 -0.001999974 0.001421093 -7.65367e-4 -0.001847743 0.00131154 -7.65367e-4 -0.001847743 -0.001999974 -0.001414179 -0.001414179 9.99604e-4 -0.001414179 -0.001414179 -0.001999974 -0.001847743 -7.65367e-4 5.32729e-4 -0.001847743 -7.65367e-4 -0.001999974 -0.001999974 0 -1.79885e-5 -0.001999974 0 -0.001999974 -0.001847743 7.65367e-4 -5.68705e-4 -0.001847743 7.65367e-4 -0.001999974 -0.001414179 0.001414179 -0.001035571 -0.001414179 0.001414179 -0.001999974 -7.65367e-4 0.001847743 -0.001347482 -7.65367e-4 0.001847743 -0.001999974 0 0.001999974 -0.001457035 0 0.001999974 -0.001999974 7.65367e-4 0.001847743 -0.001999974 0 0.001999974 0.001999974 7.65367e-4 0.001847743 0.001999974 0.001414179 0.001414179 0.001999974 0.001414179 0.001414179 -0.001999974 0.001847743 7.65367e-4 0.001999974 0.001847743 7.65367e-4 -0.001999974 0.001999974 0 0.001999974 0.001999974 0 -0.001999974 0.001847743 -7.65367e-4 0.001999974 0.001847743 -7.65367e-4 -0.001999974 0.001414179 -0.001414179 0.001999974 0.001414179 -0.001414179 -0.001999974 -0.001414179 -0.001414179 0.001999974 -7.65367e-4 -0.001847743 0.001999974 0 -0.001999974 0.001999974 7.65367e-4 -0.001847743 0.001999974 -7.65367e-4 0.001847743 0.001999974 -0.001414179 0.001414179 0.001999974 -0.001847743 7.65367e-4 0.001999974 -0.001999974 0 0.001999974 -0.001847743 -7.65367e-4 0.001999974 7.65367e-4 -0.001847743 -0.001999974 7.65367e-4 -0.001847743 -0.001347482 0 -0.001999974 -0.001457035 0.01653528 -0.004334032 -9.65724e-4 0.02133989 -0.003939688 -4.56432e-4 0.001847743 7.65367e-4 5.32729e-4 0.001999974 0 -1.79885e-5 0.02345544 -4.78913e-4 0.001098155 0.0231958 7.50976e-4 0.001266658 0.001414179 0.001414179 9.99604e-4 0.02240127 0.002166092 0.001186668 7.65366e-4 0.001847743 0.00131154 0.02022266 0.003809988 0.001138865 0.001847743 -7.65367e-4 -5.68705e-4 0.02341061 -0.002114474 5.80571e-4 0 0.001999974 0.001421093 0.01448982 0.004217267 0.001118838 0.001414179 -0.001414179 -0.001035571 0.02314895 -0.003187358 1.38679e-4 0 0 0 -7.65368e-4 0.001847743 -0.001347482 0 0.001999974 -0.001457035 -0.01653528 0.004334032 -9.65724e-4 -0.02133989 0.003939688 -4.56432e-4 -0.001847743 -7.65367e-4 5.32729e-4 -0.001999974 0 -1.79885e-5 -0.02345544 4.78909e-4 0.001098155 -0.0231958 -7.50979e-4 0.001266658 -0.001414179 -0.001414179 9.99604e-4 -0.02240127 -0.002166092 0.001186668 -7.65366e-4 -0.001847743 0.00131154 -0.02022266 -0.003809988 0.001138865 -0.001847743 7.65367e-4 -5.68705e-4 -0.02341061 0.002114474 5.80571e-4 -0.01448982 -0.004217267 0.001118838 -0.001414179 0.001414179 -0.001035571 -0.02314895 0.003187358 1.38679e-4 8.03577e-4 -0.001669585 -0.001813113 0.02138286 -0.003702402 -8.94434e-4 0.01657199 -0.004173696 -0.001437842 3.67138e-5 -0.001839578 -0.001929223 0.001862168 8.94353e-4 4.98801e-5 0.02321308 8.96381e-4 7.88594e-4 0.02348321 -2.90873e-4 6.35759e-4 0.002027451 1.872e-4 -4.80802e-4 0.001414418 0.001484632 5.04594e-4 0.02240705 0.002253592 6.94454e-4 7.59125e-4 0.001859784 8.11758e-4 0.02021872 0.003864169 6.41829e-4 0.02344667 -0.001904726 1.28149e-4 0.001884579 -5.53324e-4 -0.001019954 -6.9277e-6 0.001999497 9.21166e-4 0.01448291 0.00421679 6.18956e-4 0.001456499 -0.001178562 -0.001474499 0.02318966 -0.002962052 -3.05808e-4 0 0 -5e-4 -8.03577e-4 0.001669585 -0.001813113 -0.02138286 0.003702402 -8.94434e-4 -0.01657199 0.004173696 -0.001437842 -3.67141e-5 0.001839578 -0.001929223 -0.001862168 -8.94354e-4 4.98801e-5 -0.02321308 -8.96385e-4 7.88594e-4 -0.02348321 2.90869e-4 6.35759e-4 -0.002027451 -1.87201e-4 -4.80802e-4 -0.001414418 -0.001484632 5.04594e-4 -0.02240705 -0.002253592 6.94454e-4 -7.59125e-4 -0.001859784 8.11758e-4 -0.02021872 -0.003864169 6.41829e-4 -0.02344667 0.001904726 1.28149e-4 -0.001884579 5.53324e-4 -0.001019954 6.928e-6 -0.001999497 9.21166e-4 -0.01448291 -0.00421679 6.18956e-4 -0.001456499 0.001178562 -0.001474499 -0.02318966 0.002962052 -3.05808e-4 -8.03577e-4 0.001669585 -0.001813113 -3.6714e-5 0.001839578 -0.001929223 -0.02318966 0.002962052 -3.05808e-4 -0.0408982 -0.04467964 -0.001999974 -0.0408982 -0.04467964 0.001421093 -0.04108291 -0.04392147 0.00131154 -0.04108291 -0.04392147 -0.001999974 -0.04154372 -0.04329168 9.99604e-4 -0.04154372 -0.04329168 -0.001999974 -0.04221045 -0.04288619 5.32729e-4 -0.04221045 -0.04288619 -0.001999974 -0.04298162 -0.04276669 -1.79885e-5 -0.04298162 -0.04276669 -0.001999974 -0.04373979 -0.0429514 -5.68705e-4 -0.04373979 -0.0429514 -0.001999974 -0.04436957 -0.0434122 -0.001035571 -0.04436957 -0.0434122 -0.001999974 -0.04477506 -0.04407894 -0.001347482 -0.04477506 -0.04407894 -0.001999974 -0.04489457 -0.04485011 -0.001457035 -0.04489457 -0.04485011 -0.001999974 -0.04470986 -0.04560828 -0.001999974 -0.04489457 -0.04485011 0.001999974 -0.04470986 -0.04560828 0.001999974 -0.04424905 -0.04623806 0.001999974 -0.04424905 -0.04623806 -0.001999974 -0.04358232 -0.04664355 0.001999974 -0.04358232 -0.04664355 -0.001999974 -0.04281115 -0.04676306 0.001999974 -0.04281115 -0.04676306 -0.001999974 -0.04205298 -0.04657834 0.001999974 -0.04205298 -0.04657834 -0.001999974 -0.0414232 -0.04611754 0.001999974 -0.0414232 -0.04611754 -0.001999974 -0.04154372 -0.04329168 0.001999974 -0.04108291 -0.04392147 0.001999974 -0.0408982 -0.04467964 0.001999974 -0.04101771 -0.0454508 0.001999974 -0.04477506 -0.04407894 0.001999974 -0.04436957 -0.0434122 0.001999974 -0.04373979 -0.0429514 0.001999974 -0.04298162 -0.04276669 0.001999974 -0.04221045 -0.04288619 0.001999974 -0.04101771 -0.0454508 -0.001999974 -0.04101771 -0.0454508 -0.001347482 -0.0408982 -0.04467964 -0.001457035 -0.03786164 -0.06110048 -9.65724e-4 -0.038051 -0.06591755 -4.56432e-4 -0.04358232 -0.04664355 5.32729e-4 -0.04281115 -0.04676306 -1.79885e-5 -0.04141849 -0.06817865 0.001098155 -0.04265832 -0.06797164 0.001266658 -0.04424905 -0.04623806 9.99604e-4 -0.044106 -0.06723815 0.001186668 -0.04470986 -0.04560828 0.00131154 -0.04584127 -0.06513154 0.001138865 -0.04205298 -0.04657834 -5.68705e-4 -0.03978627 -0.06806421 5.80571e-4 -0.04489457 -0.04485011 0.001421093 -0.04649245 -0.0594213 0.001118838 -0.0414232 -0.04611754 -0.001035571 -0.03872555 -0.06775707 1.38679e-4 -0.04289638 -0.04476487 0 -0.04477506 -0.04407894 -0.001347482 -0.04489457 -0.04485011 -0.001457035 -0.04793113 -0.02842926 -9.65724e-4 -0.04774183 -0.0236122 -4.56432e-4 -0.04221045 -0.04288619 5.32729e-4 -0.04298162 -0.04276669 -1.79885e-5 -0.04437434 -0.02135109 0.001098155 -0.04313451 -0.02155816 0.001266658 -0.04154372 -0.04329168 9.99604e-4 -0.04168677 -0.02229166 0.001186668 -0.04108291 -0.04392147 0.00131154 -0.03995156 -0.0243982 0.001138865 -0.04373979 -0.0429514 -5.68705e-4 -0.0460065 -0.02146559 5.80571e-4 -0.03930032 -0.03010851 0.001118838 -0.04436957 -0.0434122 -0.001035571 -0.04706722 -0.02177274 1.38679e-4 -0.04119402 -0.04549658 -0.001813113 -0.0382862 -0.06597059 -8.94434e-4 -0.03802031 -0.06114399 -0.001437842 -0.04105687 -0.04472315 -0.001929223 -0.04371058 -0.04666352 4.98801e-5 -0.04280287 -0.06799513 7.88594e-4 -0.04160517 -0.06821441 6.35759e-4 -0.04299706 -0.04679846 -4.80802e-4 -0.04431945 -0.04624134 5.04594e-4 -0.0441932 -0.06724768 6.94454e-4 -0.04472219 -0.04560256 8.11758e-4 -0.04589551 -0.06512993 6.41829e-4 -0.03999429 -0.06810909 1.28149e-4 -0.04226326 -0.04662424 -0.001019954 -0.04489439 -0.04484313 9.21166e-4 -0.04649227 -0.05941432 6.18956e-4 -0.04165679 -0.04616987 -0.001474499 -0.03894889 -0.06780731 -3.05808e-4 -0.04289638 -0.04476487 -5e-4 -0.04459875 -0.04403316 -0.001813113 -0.04750657 -0.02355915 -8.94434e-4 -0.04777246 -0.02838575 -0.001437842 -0.0447359 -0.04480659 -0.001929223 -0.04208219 -0.04286623 4.98801e-5 -0.04298996 -0.02153462 7.88594e-4 -0.0441876 -0.02131533 6.35759e-4 -0.04279577 -0.04273128 -4.80802e-4 -0.04147338 -0.0432884 5.04594e-4 -0.04159963 -0.02228212 6.94454e-4 -0.04107064 -0.04392719 8.11758e-4 -0.03989726 -0.02439987 6.41829e-4 -0.04579848 -0.02142065 1.28149e-4 -0.04352951 -0.04290556 -0.001019954 -0.04089838 -0.04468661 9.21166e-4 -0.0393005 -0.03011542 6.18956e-4 -0.04413598 -0.04335993 -0.001474499 -0.04684388 -0.02172249 -3.05808e-4 -0.04459875 -0.04403316 -0.001813113 -0.0447359 -0.04480659 -0.001929223 -0.04684388 -0.02172249 -3.05808e-4 0.04276669 -0.04298162 -0.001999974 0.04276669 -0.04298162 0.001421093 0.0429514 -0.04373979 0.00131154 0.0429514 -0.04373979 -0.001999974 0.0434122 -0.04436957 9.99604e-4 0.0434122 -0.04436957 -0.001999974 0.04407894 -0.04477506 5.32729e-4 0.04407894 -0.04477506 -0.001999974 0.04485011 -0.04489457 -1.79885e-5 0.04485011 -0.04489457 -0.001999974 0.04560828 -0.04470986 -5.68705e-4 0.04560828 -0.04470986 -0.001999974 0.04623806 -0.04424905 -0.001035571 0.04623806 -0.04424905 -0.001999974 0.04664355 -0.04358232 -0.001347482 0.04664355 -0.04358232 -0.001999974 0.04676306 -0.04281115 -0.001457035 0.04676306 -0.04281115 -0.001999974 0.04657834 -0.04205298 -0.001999974 0.04676306 -0.04281115 0.001999974 0.04657834 -0.04205298 0.001999974 0.04611754 -0.0414232 0.001999974 0.04611754 -0.0414232 -0.001999974 0.0454508 -0.04101771 0.001999974 0.0454508 -0.04101771 -0.001999974 0.04467964 -0.0408982 0.001999974 0.04467964 -0.0408982 -0.001999974 0.04392147 -0.04108291 0.001999974 0.04392147 -0.04108291 -0.001999974 0.04329168 -0.04154372 0.001999974 0.04329168 -0.04154372 -0.001999974 0.0434122 -0.04436957 0.001999974 0.0429514 -0.04373979 0.001999974 0.04276669 -0.04298162 0.001999974 0.04288619 -0.04221045 0.001999974 0.04664355 -0.04358232 0.001999974 0.04623806 -0.04424905 0.001999974 0.04560828 -0.04470986 0.001999974 0.04485011 -0.04489457 0.001999974 0.04407894 -0.04477506 0.001999974 0.04288619 -0.04221045 -0.001999974 0.04288619 -0.04221045 -0.001347482 0.04276669 -0.04298162 -0.001457035 0.03973013 -0.02656078 -9.65724e-4 0.03991949 -0.02174371 -4.56432e-4 0.0454508 -0.04101771 5.32729e-4 0.04467964 -0.0408982 -1.79885e-5 0.04328697 -0.01948261 0.001098155 0.04452681 -0.01968967 0.001266658 0.04611754 -0.0414232 9.99604e-4 0.04597449 -0.02042317 0.001186668 0.04657834 -0.04205298 0.00131154 0.04770976 -0.02252972 0.001138865 0.04392147 -0.04108291 -5.68705e-4 0.04165476 -0.01959711 5.80571e-4 0.04676306 -0.04281115 0.001421093 0.04836094 -0.02824002 0.001118838 0.04329168 -0.04154372 -0.001035571 0.04059404 -0.01990425 1.38679e-4 0.04476487 -0.04289638 0 0.04664355 -0.04358232 -0.001347482 0.04676306 -0.04281115 -0.001457035 0.04979962 -0.05923199 -9.65724e-4 0.04961031 -0.06404906 -4.56432e-4 0.04407894 -0.04477506 5.32729e-4 0.04485011 -0.04489457 -1.79885e-5 0.04624283 -0.06631016 0.001098155 0.04500299 -0.06610316 0.001266658 0.0434122 -0.04436957 9.99604e-4 0.04355525 -0.06536966 0.001186668 0.0429514 -0.04373979 0.00131154 0.04182004 -0.06326305 0.001138865 0.04560828 -0.04470986 -5.68705e-4 0.04787498 -0.06619572 5.80571e-4 0.0411688 -0.05755281 0.001118838 0.04623806 -0.04424905 -0.001035571 0.04893571 -0.06588858 1.38679e-4 0.0430625 -0.04216468 -0.001813113 0.04015469 -0.02169066 -8.94434e-4 0.03988879 -0.02651727 -0.001437842 0.04292535 -0.04293811 -0.001929223 0.04557907 -0.04099774 4.98801e-5 0.04467135 -0.01966613 7.88594e-4 0.04347366 -0.01944684 6.35759e-4 0.04486554 -0.04086279 -4.80802e-4 0.04618793 -0.04141992 5.04594e-4 0.04606169 -0.02041363 6.94454e-4 0.04659068 -0.0420587 8.11758e-4 0.047764 -0.02253139 6.41829e-4 0.04186278 -0.01955217 1.28149e-4 0.04413175 -0.04103708 -0.001019954 0.04676288 -0.04281812 9.21166e-4 0.04836076 -0.02824693 6.18956e-4 0.04352527 -0.04149144 -0.001474499 0.04081737 -0.019854 -3.05808e-4 0.04476487 -0.04289638 -5e-4 0.04646724 -0.04362809 -0.001813113 0.04937505 -0.06410211 -8.94434e-4 0.04964095 -0.0592755 -0.001437842 0.04660439 -0.04285466 -0.001929223 0.04395067 -0.04479503 4.98801e-5 0.04485845 -0.06612664 7.88594e-4 0.04605609 -0.06634593 6.35759e-4 0.04466426 -0.04492998 -4.80802e-4 0.04334187 -0.04437285 5.04594e-4 0.04346811 -0.0653792 6.94454e-4 0.04293912 -0.04373407 8.11758e-4 0.04176574 -0.06326144 6.41829e-4 0.04766696 -0.0662406 1.28149e-4 0.04539799 -0.04475575 -0.001019954 0.04276686 -0.04297465 9.21166e-4 0.04116898 -0.05754584 6.18956e-4 0.04600447 -0.04430139 -0.001474499 0.04871237 -0.06593883 -3.05808e-4 0.04646724 -0.04362809 -0.001813113 0.04660439 -0.04285466 -0.001929223 0.04871237 -0.06593883 -3.05808e-4 0.001868486 -0.08566129 -0.001999974 0.001868486 -0.08566129 0.001421093 0.00263381 -0.08581358 0.00131154 0.00263381 -0.08581358 -0.001999974 0.003282666 -0.08624708 9.99604e-4 0.003282666 -0.08624708 -0.001999974 0.00371623 -0.08689594 5.32729e-4 0.00371623 -0.08689594 -0.001999974 0.00386846 -0.08766132 -1.79885e-5 0.00386846 -0.08766132 -0.001999974 0.00371623 -0.0884267 -5.68705e-4 0.00371623 -0.0884267 -0.001999974 0.003282666 -0.0890755 -0.001035571 0.003282666 -0.0890755 -0.001999974 0.00263381 -0.08950906 -0.001347482 0.00263381 -0.08950906 -0.001999974 0.001868486 -0.0896613 -0.001457035 0.001868486 -0.0896613 -0.001999974 0.001103103 -0.08950906 -0.001999974 0.001868486 -0.0896613 0.001999974 0.001103103 -0.08950906 0.001999974 4.54273e-4 -0.0890755 0.001999974 4.54273e-4 -0.0890755 -0.001999974 2.07275e-5 -0.0884267 0.001999974 2.07275e-5 -0.0884267 -0.001999974 -1.31514e-4 -0.08766132 0.001999974 -1.31514e-4 -0.08766132 -0.001999974 2.07275e-5 -0.08689594 0.001999974 2.07275e-5 -0.08689594 -0.001999974 4.54273e-4 -0.08624708 0.001999974 4.54273e-4 -0.08624708 -0.001999974 0.003282666 -0.08624708 0.001999974 0.00263381 -0.08581358 0.001999974 0.001868486 -0.08566129 0.001999974 0.001103103 -0.08581358 0.001999974 0.00263381 -0.08950906 0.001999974 0.003282666 -0.0890755 0.001999974 0.00371623 -0.0884267 0.001999974 0.00386846 -0.08766132 0.001999974 0.00371623 -0.08689594 0.001999974 0.001103103 -0.08581358 -0.001999974 0.001103103 -0.08581358 -0.001347482 0.001868486 -0.08566129 -0.001457035 -0.01466679 -0.08332723 -9.65724e-4 -0.0194714 -0.08372163 -4.56432e-4 2.07275e-5 -0.0884267 5.32729e-4 -1.31514e-4 -0.08766132 -1.79885e-5 -0.02158695 -0.0871824 0.001098155 -0.02132731 -0.08841228 0.001266658 4.54273e-4 -0.0890755 9.99604e-4 -0.02053278 -0.08982741 0.001186668 0.001103103 -0.08950906 0.00131154 -0.01835417 -0.09147131 0.001138865 2.07275e-5 -0.08689594 -5.68705e-4 -0.02154213 -0.08554679 5.80571e-4 0.001868486 -0.0896613 0.001421093 -0.01262134 -0.09187865 0.001118838 4.54273e-4 -0.08624708 -0.001035571 -0.02128046 -0.08447396 1.38679e-4 0.001868486 -0.08766132 0 0.00263381 -0.08950906 -0.001347482 0.001868486 -0.0896613 -0.001457035 0.01840376 -0.09199541 -9.65724e-4 0.02320837 -0.09160101 -4.56432e-4 0.00371623 -0.08689594 5.32729e-4 0.00386846 -0.08766132 -1.79885e-5 0.02532392 -0.08814024 0.001098155 0.02506428 -0.0869103 0.001266658 0.003282666 -0.08624708 9.99604e-4 0.02426975 -0.08549523 0.001186668 0.00263381 -0.08581358 0.00131154 0.02209115 -0.08385127 0.001138865 0.00371623 -0.0884267 -5.68705e-4 0.0252791 -0.0897758 5.80571e-4 0.01635831 -0.08344399 0.001118838 0.003282666 -0.0890755 -0.001035571 0.02501744 -0.09084868 1.38679e-4 0.001064896 -0.08599168 -0.001813113 -0.01951438 -0.08395886 -8.94434e-4 -0.01470351 -0.08348762 -0.001437842 0.001831769 -0.08582168 -0.001929223 6.26221e-6 -0.08855569 4.98801e-5 -0.02134466 -0.08855772 7.88594e-4 -0.02161473 -0.08737045 6.35759e-4 -1.58966e-4 -0.08784854 -4.80802e-4 4.54016e-4 -0.08914595 5.04594e-4 -0.02053856 -0.08991491 6.94454e-4 0.001109361 -0.08952111 8.11758e-4 -0.01835024 -0.09152549 6.41829e-4 -0.02157819 -0.08575659 1.28149e-4 -1.6138e-5 -0.08710801 -0.001019954 0.0018754 -0.08966082 9.21166e-4 -0.01261442 -0.09187811 6.18956e-4 4.11976e-4 -0.0864827 -0.001474499 -0.02132117 -0.08469927 -3.05808e-4 0.001868486 -0.08766132 -5e-4 0.002672016 -0.08933097 -0.001813113 0.02325135 -0.09136372 -8.94434e-4 0.01844048 -0.09183502 -0.001437842 0.001905143 -0.08950096 -0.001929223 0.003730654 -0.08676695 4.98801e-5 0.02508163 -0.08676493 7.88594e-4 0.0253517 -0.08795219 6.35759e-4 0.003895938 -0.0874741 -4.80802e-4 0.003282904 -0.08617669 5.04594e-4 0.02427554 -0.08540773 6.94454e-4 0.002627611 -0.08580148 8.11758e-4 0.02208721 -0.08379715 6.41829e-4 0.02531516 -0.08956605 1.28149e-4 0.003753066 -0.08821463 -0.001019954 0.001861512 -0.08566182 9.21166e-4 0.0163514 -0.08344447 6.18956e-4 0.003324985 -0.08883988 -0.001474499 0.02505815 -0.09062337 -3.05808e-4 0.002672016 -0.08933097 -0.001813113 0.001905143 -0.08950096 -0.001929223 0.02505815 -0.09062337 -3.05808e-4 + + + + + + + + + + 0 -0.7462026 -0.665719 0.08095937 -0.9950895 0.05694371 -0.3826833 -0.9238796 0 -0.2855594 -0.6894015 -0.6657189 -0.6894015 -0.2855596 -0.6657187 -1 -2.17625e-7 0 -0.7462024 -1.22696e-7 -0.6657192 -0.9238796 0.3826835 0 -0.6894016 0.2855592 -0.6657187 -0.2855595 0.6894013 -0.6657189 -0.3826836 0.9238795 0 0 1 0 0 0.7462027 -0.6657189 0 0.7462028 0.6657188 0.2855593 0.6894014 0.6657189 0.7462024 2.09306e-7 -0.6657193 0.7462027 0 0.6657188 0.6894013 -0.2855595 0.6657189 0 -0.7462027 0.6657189 0.2855592 -0.6894014 0.665719 0.5276449 -0.5276449 0.665719 0.689402 0.2855592 0.6657183 0.5276449 0.5276451 0.665719 -0.5276449 -0.5276451 0.665719 -0.5276449 0.5276448 0.6657191 -0.7462028 0 0.6657188 -0.5276454 -0.5276448 -0.6657187 0.2855593 0.6894015 -0.6657189 0.6894013 0.2855597 -0.6657189 0.6894015 -0.2855592 -0.6657189 0.2855596 -0.6894013 -0.6657189 -0.7071067 -0.707107 0 -0.2855594 -0.6894015 0.6657189 -0.707107 0.7071067 0 -0.6894018 0.2855592 0.6657186 -0.9238794 -0.3826838 0 -0.6894017 -0.2855594 0.6657186 -0.2855592 0.6894014 0.665719 -0.3748962 -0.7816502 0.4984736 0.6311947 0.1767534 0.7552164 0.5248991 0.4826806 0.7010709 -0.1582986 -0.7873222 0.5958736 0.2573913 0.6935871 0.67282 -0.7081931 -0.4253229 0.5635272 -0.7082605 -0.1986545 0.6774241 0.6699832 -0.3351253 0.6624301 -0.817855 0.0142318 0.5752485 -0.02832227 0.7650859 0.6433052 -0.5823978 0.01877319 0.8126872 -0.357304 0.2884959 0.8883153 0.1679158 -0.9497295 0.2642319 0.5648971 -0.7122579 0.4166294 0.41309 -0.5338768 0.7377888 0.9653253 0.1375148 0.2218936 0.07708626 0.9719986 0.2219831 -0.1679159 0.9497294 0.2642319 0.5878704 0.6405184 0.49411 0.7081931 0.4253231 0.5635272 -0.6717817 0.1170585 0.7314416 -0.6311947 -0.1767534 0.7552163 0.374896 0.7816503 0.4984737 0.7082605 0.1986545 0.6774241 -0.8025102 0.3241897 0.500878 0.1582985 0.7873218 0.5958741 -0.2573911 -0.6935855 0.6728217 0.5823978 -0.01877266 0.8126872 -0.7079404 0.6868429 0.1645214 -0.227101 0.8081443 -0.5434408 0.04681378 -0.4709634 -0.8809098 -0.7987827 0.1411343 -0.584831 -0.6431276 0.2793524 -0.7129861 0.7421983 0.3454436 -0.5742912 0.783652 0.2218073 -0.580251 -0.6109308 0.4729923 -0.6348559 -0.6039934 0.01654142 -0.7968177 0.5849545 0.5077975 -0.6324319 -0.384606 -0.37048 -0.845472 0.2669962 0.7314997 -0.6273924 0.772009 0.1294873 -0.6222823 -0.863177 0.02027082 -0.5044946 -0.03747242 0.6877762 -0.7249551 -0.4273026 0.7637783 -0.4837924 0.2818456 -0.3080278 -0.9086704 0.2271012 -0.8081442 -0.5434409 -0.2334834 0.02328401 -0.972082 -0.02981293 0.340254 -0.9398608 0.7987845 -0.1411336 -0.5848289 0.6431276 -0.2793523 -0.7129862 -0.7421985 -0.3454434 -0.5742911 -0.7836518 -0.2218074 -0.5802511 0.6039935 -0.0165416 -0.7968176 -0.5849545 -0.5077975 -0.6324318 0.2584314 -0.7192381 -0.6449108 -0.667337 0.2068901 -0.7154424 0.3683512 -0.6397519 -0.6745628 -0.7687523 -0.1133454 -0.6294226 -0.8743168 -0.2032756 0.4407372 0.6717818 -0.1170586 0.7314414 -0.05454945 -0.9115495 0.4075561 0.3846062 0.3704797 -0.845472 0.6109308 -0.472992 -0.6348561 -0.5248991 -0.482681 0.7010706 0.02832239 -0.7650857 0.6433054 -0.2669953 -0.7314993 -0.6273933 0.03747254 -0.6877762 -0.724955 -0.5276448 0.527645 -0.665719 0.5276448 0.5276451 -0.6657189 0.5276453 -0.5276447 -0.6657188 -0.5878705 -0.6405183 0.4941098 -0.5396548 0.6347205 -0.5530848 0.6673443 -0.2068942 -0.7154344 0.2271012 -0.8081443 -0.5434408 0.7987844 -0.1411337 -0.584829 0.863176 -0.02027118 -0.5044961 -0.6673444 0.206894 -0.7154344 0.7455248 0.03179866 -0.6657189 0.906734 0.4217031 0 0.9976353 -0.03848809 0.05694246 0.676608 0.3146756 -0.6657184 0.2559248 0.7009432 -0.6657185 -0.0317952 0.7455247 -0.6657192 -0.04261016 0.9990919 0 -0.3146753 0.6766077 -0.6657188 -0.4217045 0.9067333 0 -0.7009429 0.2559249 -0.6657187 -0.9990918 -0.04261201 0 -0.9393478 0.3429663 0 -0.745525 -0.03179585 -0.6657188 -0.6766076 -0.3146756 0.6657188 -0.7455248 -0.03179281 0.6657193 0.03179609 -0.7455247 -0.6657192 0.3146747 -0.676608 0.6657187 0.0317955 -0.7455248 0.6657191 0.745525 0.03179413 0.665719 0.5496467 -0.5046846 0.6657192 0.7009418 -0.2559272 0.665719 -0.5046818 -0.5496491 0.6657193 -0.2559243 -0.7009434 0.6657186 0.504682 0.5496488 0.6657193 -0.5496481 0.5046825 0.6657196 -0.03179591 0.7455247 0.6657192 0.5046839 0.549647 -0.6657195 -0.6766074 -0.3146761 -0.6657187 -0.2559258 -0.7009428 -0.6657187 0.314677 -0.6766068 -0.6657189 0.700944 -0.2559227 -0.6657186 0.6763354 0.7365938 0 0.6766076 0.3146761 0.6657186 -0.7365952 0.6763339 0 -0.314675 0.676608 0.6657186 0.3429685 0.9393469 0 0.2559235 0.7009438 0.6657184 -0.7009431 0.2559249 0.6657186 0.7649651 0.4078625 0.4984744 -0.459876 -0.5449901 0.7010705 -0.1496988 -0.6381551 0.7552141 0.7798629 0.1917027 0.5958725 -0.681987 -0.2867105 0.6728231 0.3947595 0.7256764 0.5635235 0.3633663 -0.6550991 0.6624275 0.1682943 0.716083 0.6774232 -0.04906916 0.8165074 0.5752459 -0.765596 -0.004304528 0.6433073 -0.04357326 0.5810694 0.8126868 0.9560213 -0.1272945 0.2642339 -0.3034556 0.344686 0.8883165 0.7356837 -0.5340338 0.4166263 0.5509896 -0.3899658 0.7377922 -0.9678309 -0.1184346 0.2219837 -0.09625303 -0.9703084 0.2218946 -0.9560213 0.1273009 0.2642307 -0.6148878 -0.6146292 0.4941093 -0.1455783 0.6661823 0.7314425 -0.3947584 -0.725676 0.5635249 0.1496996 0.6381526 0.7552161 -0.7649654 -0.407863 0.4984735 -0.3580898 0.7879662 0.5008803 -0.1682934 -0.7160825 0.6774241 0.6819889 0.2867107 0.6728211 -0.7798627 -0.1917032 0.5958728 -0.716387 0.678029 0.1645187 0.0435726 -0.5810685 0.8126874 -0.8170879 0.1924597 -0.5434396 -0.175049 0.792034 -0.5848421 0.4725317 -0.02670288 -0.8809091 -0.3065029 0.630638 -0.712988 -0.1882129 -0.7923859 -0.5802591 -0.3135039 -0.7562432 -0.5742923 -0.4985941 0.5902202 -0.6348577 -0.04226207 0.602741 -0.796817 -0.482411 -0.60606 -0.6324326 0.3537545 0.4000416 -0.8454729 -0.7194592 -0.2979241 -0.6273913 -0.09648007 -0.7768225 -0.6222849 -0.05703401 0.8615258 -0.5045002 -0.6887509 0.008130908 -0.7249525 -0.7812932 0.39437 -0.4837904 0.3197576 -0.2684645 -0.9086704 0.8170879 -0.1924601 -0.5434395 -0.3412169 0.01528608 -0.9398603 -0.03320986 0.2322808 -0.9720817 0.1750516 -0.7920293 -0.5848476 0.3065037 -0.6306387 -0.712987 0.1882125 0.7923927 -0.58025 0.3135063 0.7562432 -0.5742909 0.04226112 -0.6027407 -0.7968172 0.4824105 0.6060616 -0.6324313 0.7295984 -0.22755 -0.6449087 -0.235139 0.657912 -0.715445 0.6548674 -0.3407562 -0.6745621 0.08048552 0.7728857 -0.6294202 0.1658352 0.8821812 0.4407438 0.1455777 -0.6661909 0.7314348 0.9083966 0.09334158 0.4075574 -0.3537541 -0.4000416 -0.8454732 0.4985966 -0.5902203 -0.6348556 0.4598743 0.5449897 0.701072 0.7655984 0.004303276 0.6433045 0.6887478 -0.008132696 -0.7249554 0.7194588 0.2979215 -0.6273929 -0.5496482 0.5046826 -0.6657195 -0.504683 -0.5496483 -0.6657191 0.5496493 -0.5046815 -0.6657193 0.6148877 0.6146301 0.4941083 -0.6571398 0.512119 -0.5530837 0.2351419 -0.657922 -0.7154348 0.05703675 -0.8615267 -0.5044986 -0.2351435 0.657919 -0.715437 -0.7455248 -0.03179848 -0.6657189 -0.906734 -0.4217032 0 -0.9976354 0.03848469 0.05694341 -0.6766065 -0.3146781 -0.6657187 -0.2559248 -0.7009432 -0.6657185 0.03179579 -0.7455246 -0.6657192 0.04261058 -0.9990918 0 0.3146759 -0.6766076 -0.6657187 0.4217039 -0.9067336 0 0.7009436 -0.255924 -0.6657184 0.9990918 0.04261124 0 0.9393488 -0.3429638 0 0.7455245 0.03179579 -0.6657194 0.6766064 0.3146775 0.6657192 0.7455248 0.03179281 0.6657193 -0.03179615 0.7455246 -0.6657192 -0.3146754 0.6766078 0.6657186 -0.03179633 0.7455247 0.6657192 -0.7455248 -0.03179454 0.665719 -0.5496484 0.5046824 0.6657195 -0.7009429 0.2559248 0.6657188 0.5046803 0.5496507 0.6657191 0.2559241 0.7009434 0.6657186 -0.5046829 -0.5496482 0.6657192 0.5496463 -0.5046849 0.6657193 0.03179556 -0.7455247 0.6657191 -0.5046815 -0.5496497 -0.6657191 0.6766088 0.3146734 -0.6657186 0.2559241 0.7009435 -0.6657185 -0.3146755 0.6766077 -0.6657187 -0.700944 0.2559227 -0.6657186 -0.6763349 -0.7365944 0 -0.6766079 -0.3146745 0.6657189 0.7365942 -0.676335 0 0.3146744 -0.6766083 0.6657186 -0.3429695 -0.9393466 0 -0.2559258 -0.7009428 0.6657187 0.7009417 -0.2559276 0.665719 -0.764965 -0.4078633 0.4984737 0.4598755 0.5449894 0.7010715 0.1496992 0.6381525 0.7552164 -0.7798621 -0.1917039 0.5958732 0.681988 0.2867115 0.6728216 -0.3947595 -0.7256749 0.5635256 -0.3633685 0.6550941 0.6624312 -0.1682949 -0.7160849 0.677421 0.04906517 -0.8165042 0.5752508 0.765596 0.00430423 0.6433073 0.04357218 -0.5810691 0.812687 -0.9560216 0.127295 0.2642325 0.3034564 -0.3446887 0.8883152 -0.7356817 0.5340346 0.4166288 -0.5509892 0.3899695 0.7377905 0.9678309 0.1184343 0.2219837 0.0962544 0.9703086 0.2218928 0.9560208 -0.1272993 0.2642333 0.6148896 0.6146296 0.4941064 0.1455783 -0.6661955 0.7314305 0.3947587 0.7256748 0.563526 -0.1496989 -0.6381545 0.7552147 0.7649644 0.4078623 0.4984756 0.3580877 -0.7879719 0.5008729 0.1682946 0.7160839 0.6774223 -0.6819881 -0.2867103 0.6728221 0.7798626 0.191703 0.5958727 0.7163875 -0.6780288 0.1645177 -0.04357349 0.5810688 0.8126873 0.8170869 -0.1924606 -0.543441 0.1750447 -0.7920413 -0.5848334 -0.472532 0.02670228 -0.8809089 0.3065026 -0.6306371 -0.7129888 0.1882129 0.7923938 -0.5802484 0.3135059 0.7562437 -0.5742905 0.4985944 -0.5902203 -0.6348572 0.04226189 -0.6027392 -0.7968183 0.4824109 0.6060609 -0.6324318 -0.3537521 -0.4000453 -0.8454722 0.7194578 0.2979224 -0.6273937 0.09647488 0.7768262 -0.6222811 0.05703181 -0.8615217 -0.5045075 0.6887508 -0.008131206 -0.7249526 0.7812935 -0.3943697 -0.4837903 -0.3197572 0.2684646 -0.9086706 -0.8170876 0.1924616 -0.5434395 0.3412169 -0.01528638 -0.9398604 0.03321045 -0.2322807 -0.9720817 -0.1750495 0.792033 -0.5848432 -0.3065018 0.6306356 -0.7129905 -0.1882119 -0.7923818 -0.5802651 -0.313505 -0.7562438 -0.574291 -0.04226082 0.6027417 -0.7968164 -0.4824106 -0.6060609 -0.632432 -0.7295985 0.22755 -0.6449086 0.2351387 -0.6579131 -0.7154441 -0.6548658 0.3407555 -0.674564 -0.08048909 -0.7728805 -0.6294261 -0.1658367 -0.8821825 0.4407408 -0.145578 0.6661812 0.7314436 -0.9083964 -0.09334224 0.4075578 0.3537537 0.4000431 -0.8454726 -0.4985963 0.5902209 -0.6348551 -0.4598749 -0.5449903 0.7010712 -0.7655987 -0.004303872 0.6433042 -0.688747 0.008132338 -0.7249562 -0.7194598 -0.2979237 -0.6273908 0.5496483 -0.5046825 -0.6657195 0.5046837 0.5496472 -0.6657195 -0.549648 0.5046826 -0.6657196 -0.6148885 -0.6146296 0.4941079 0.657138 -0.5121173 -0.5530872 -0.2351421 0.657922 -0.7154347 -0.05703562 0.8615291 -0.5044946 0.2351422 -0.6579188 -0.7154377 -3.10351e-7 0.7462036 -0.6657178 -0.08096092 0.9950889 0.05695182 0.3826845 0.9238792 0 0.2855598 0.6894004 -0.6657196 0.6894008 0.2855597 -0.6657193 1 1.54151e-6 0 0.7462028 1.52108e-6 -0.6657188 0.923879 -0.3826848 0 0.6894016 -0.2855603 -0.6657183 0.28556 -0.6894021 -0.6657179 0.3826839 -0.9238794 0 0 -1 0 0 -0.7462019 -0.6657198 0 -0.7462019 0.6657198 -0.2855598 -0.6894021 0.665718 -0.7462027 0 -0.6657189 -0.7462028 0 0.6657187 -0.6894011 0.2855591 0.6657193 -3.60873e-7 0.7462036 0.665718 -0.2855589 0.6894004 0.6657202 -0.5276443 0.5276465 0.6657183 -0.689401 -0.285561 0.6657186 -0.5276447 -0.527644 0.6657199 0.5276448 0.5276455 0.6657186 0.5276448 -0.5276439 0.6657199 0.7462028 1.56618e-6 0.6657188 0.5276442 0.5276459 -0.6657187 -0.2855599 -0.6894021 -0.665718 -0.6894011 -0.285561 -0.6657185 -0.6894015 0.285559 -0.665719 -0.2855592 0.6894005 -0.6657199 0.7071064 0.7071072 0 0.2855596 0.6894004 0.6657198 0.7071072 -0.7071065 0 0.6894012 -0.2855603 0.6657187 0.9238795 0.3826836 0 0.689401 0.2855598 0.6657192 0.2855601 -0.689402 0.665718 0.3748966 0.781649 0.498475 -0.6311954 -0.1767513 0.7552161 -0.5248981 -0.4826796 0.7010725 0.1582983 0.7873291 0.5958645 -0.2573927 -0.6935856 0.672821 0.7081932 0.4253179 0.5635309 0.7082578 0.1986523 0.6774277 -0.6699869 0.3351221 0.662428 0.8179191 -0.01422673 0.5751573 0.0283221 -0.7650799 0.6433123 0.582392 -0.01877611 0.8126913 0.3573055 -0.288505 0.8883117 -0.167915 0.9497284 0.2642359 -0.5648927 0.7122582 0.4166351 -0.4130837 0.5338729 0.7377951 -0.9653531 -0.1374804 0.2217944 -0.07708686 -0.9719977 0.2219867 0.167918 -0.9497307 0.2642259 -0.5878692 -0.6405211 0.4941079 -0.7081959 -0.4253249 0.5635223 0.6717795 -0.1170623 0.7314429 0.6311936 0.1767559 0.7552165 -0.3748962 -0.7816454 0.498481 -0.7082607 -0.1986582 0.6774228 0.8025099 -0.3241881 0.5008794 -0.1583018 -0.7873246 0.5958697 0.2573919 0.6935891 0.6728177 -0.5823986 0.01877582 0.8126866 0.7079401 -0.6868436 0.1645199 0.2270929 -0.8081509 -0.5434345 -0.04681378 0.4709674 -0.8809076 0.7987381 -0.1411775 -0.5848817 0.6431273 -0.2793527 -0.7129862 -0.742201 -0.3454418 -0.5742889 -0.7836484 -0.2218055 -0.5802565 0.6109306 -0.4729927 -0.6348558 0.6039939 -0.01653212 -0.7968176 -0.5849552 -0.5077995 -0.6324295 0.3846091 0.3704743 -0.8454731 -0.2669942 -0.7315006 -0.6273923 -0.7720052 -0.1294935 -0.6222857 0.8631245 -0.02027738 -0.5045839 0.03747326 -0.6877831 -0.7249485 0.4273028 -0.7637795 -0.4837906 -0.2818462 0.308034 -0.9086682 -0.2271057 0.8081416 -0.543443 0.2334829 -0.02328026 -0.9720821 0.02981233 -0.340258 -0.9398595 -0.7987309 0.1411525 -0.5848974 -0.6431262 0.2793472 -0.7129895 0.7421988 0.3454467 -0.5742887 0.7836537 0.2218036 -0.5802502 -0.6039999 0.01653999 -0.7968128 0.5849588 0.5078008 -0.6324253 -0.2584329 0.7192396 -0.6449084 0.667337 -0.2068899 -0.7154424 -0.3683511 0.6397474 -0.6745671 0.7687532 0.1133442 -0.6294216 0.8743509 0.2032626 0.4406754 -0.6717849 0.1170606 0.7314382 0.05455005 0.9115486 0.4075579 -0.3845989 -0.3704783 -0.8454759 -0.6109272 0.4729974 -0.6348554 0.5248938 0.4826764 0.7010778 -0.02832227 0.7650817 0.6433103 0.2669939 0.7314968 -0.6273969 -0.03747266 0.6877813 -0.7249501 0.5276443 -0.5276443 -0.6657201 -0.5276443 -0.5276442 -0.6657201 -0.5276439 0.5276466 -0.6657185 0.5878688 0.64052 0.4941098 0.5396559 -0.6347213 -0.5530827 -0.6673502 0.2068974 -0.715428 -0.8631843 0.02027374 -0.5044817 0.667343 -0.206893 -0.715436 + + + + + + + + + + + + + + +

0 0 1 1 2 2 0 0 2 2 3 3 7 4 8 5 9 6 9 6 10 7 11 8 15 9 14 10 16 11 15 9 16 11 17 12 16 11 19 13 20 14 26 15 25 16 27 17 33 18 34 19 29 20 29 20 27 17 25 16 25 16 23 21 21 22 21 22 20 14 19 13 31 23 33 18 29 20 21 22 19 13 36 24 36 24 38 25 31 23 21 22 36 24 31 23 34 19 1 1 0 0 3 3 5 26 7 4 15 9 17 12 18 27 24 28 26 15 28 29 40 30 3 3 7 4 15 9 18 27 24 28 4 31 2 2 32 32 12 33 10 7 37 34 12 33 37 34 36 24 6 35 4 31 31 23 6 35 31 23 39 36 8 5 39 36 38 25 2 2 1 1 33 18 2 2 33 18 32 32 16 11 14 10 35 37 10 7 8 5 38 25 49 38 48 39 50 40 51 41 49 38 50 40 51 41 50 40 52 42 46 43 53 44 54 45 55 46 52 42 56 47 57 48 41 49 44 50 57 48 44 50 58 51 53 44 57 48 58 51 53 44 58 51 54 45 60 52 61 53 62 54 60 52 62 54 63 55 64 56 65 57 66 58 64 56 66 58 67 59 68 60 64 56 67 59 65 57 72 61 73 62 1 1 70 63 71 64 72 61 75 65 76 66 77 67 79 68 80 69 81 70 82 71 83 72 81 70 83 72 84 73 85 74 86 75 82 71 85 74 82 71 81 70 87 76 88 77 86 75 84 73 83 72 89 78 91 79 92 80 88 77 93 81 78 82 77 67 96 83 97 84 98 85 96 83 98 85 99 86 100 87 101 88 102 89 104 90 105 91 101 88 104 90 101 88 100 87 112 92 113 93 97 84 112 92 97 84 96 83 109 94 108 95 113 93 109 94 113 93 112 92 41 49 93 81 77 67 51 41 55 46 91 79 51 41 91 79 87 76 42 96 77 67 80 69 53 44 46 43 84 73 52 42 50 40 86 75 52 42 86 75 88 77 50 40 48 39 82 71 50 40 82 71 86 75 48 39 47 97 83 72 44 50 43 98 79 68 47 97 54 45 89 78 47 97 89 78 83 72 43 98 42 96 80 69 55 46 92 80 91 79 68 60 70 63 106 99 64 56 68 60 104 90 60 52 112 92 96 83 65 57 100 87 103 100 61 53 60 52 96 83 61 53 96 83 99 86 72 61 65 57 103 100 72 61 103 100 109 94 73 62 76 66 113 93 73 62 113 93 108 95 69 101 67 59 101 88 76 66 97 84 113 93 74 102 107 103 111 104 63 55 62 54 98 85 66 58 108 95 102 89 62 54 61 53 99 86 62 54 99 86 98 85 3 3 2 2 4 31 3 3 4 31 5 26 5 26 4 31 6 35 5 26 6 35 7 4 7 4 6 35 8 5 9 6 8 5 10 7 11 8 10 7 12 33 11 8 12 33 13 105 13 105 12 33 14 10 13 105 14 10 15 9 18 27 17 12 16 11 16 11 20 14 18 27 18 27 20 14 21 22 18 27 21 22 22 106 22 106 21 22 23 21 22 106 23 21 24 28 24 28 23 21 25 16 24 28 25 16 26 15 26 15 27 17 28 29 28 29 27 17 29 20 28 29 29 20 30 107 31 23 32 32 33 18 19 13 35 37 36 24 36 24 37 34 38 25 38 25 39 36 31 23 29 20 25 16 21 22 31 23 29 20 21 22 30 107 29 20 34 19 30 107 34 19 40 30 0 0 40 30 34 19 34 19 33 18 1 1 40 30 0 0 3 3 7 4 9 6 11 8 11 8 13 105 15 9 18 27 22 106 24 28 28 29 30 107 40 30 7 4 11 8 15 9 24 28 28 29 40 30 40 30 7 4 15 9 15 9 24 28 40 30 4 31 32 32 31 23 14 10 12 33 36 24 14 10 36 24 35 37 8 5 6 35 39 36 16 11 35 37 19 13 10 7 38 25 37 34 41 49 42 96 43 98 41 49 43 98 44 50 45 108 46 43 47 97 45 108 47 97 48 39 49 38 45 108 48 39 46 43 54 45 47 97 55 46 51 41 52 42 77 67 78 82 79 68 87 76 86 75 85 74 84 73 89 78 90 109 91 79 88 77 87 76 93 81 94 110 78 82 90 109 89 78 94 110 90 109 94 110 93 81 49 38 51 41 87 76 49 38 87 76 85 74 57 48 53 44 90 109 57 48 90 109 93 81 45 108 49 38 85 74 45 108 85 74 81 70 41 49 57 48 93 81 46 43 45 108 81 70 46 43 81 70 84 73 42 96 41 49 77 67 53 44 84 73 90 109 54 45 58 51 94 110 54 45 94 110 89 78 58 51 44 50 78 82 58 51 78 82 94 110 48 39 83 72 82 71 56 47 52 42 88 77 56 47 88 77 92 80 44 50 79 68 78 82 43 98 80 69 79 68 55 46 56 47 92 80 68 60 67 59 69 101 70 63 68 60 69 101 70 63 69 101 71 64 65 57 73 62 66 58 1 1 71 64 74 102 75 65 60 52 63 55 75 65 63 55 76 66 72 61 76 66 73 62 114 111 97 84 98 85 114 111 98 85 115 112 100 87 102 89 103 100 106 99 107 103 105 91 106 99 105 91 104 90 103 100 102 89 108 95 103 100 108 95 109 94 110 113 111 104 107 103 110 113 107 103 106 99 112 92 116 114 97 84 112 92 97 84 114 111 109 94 108 95 116 114 109 94 116 114 112 92 68 60 106 99 104 90 75 65 72 61 109 94 75 65 109 94 112 92 64 56 104 90 100 87 60 52 75 65 112 92 60 52 112 92 114 111 65 57 64 56 100 87 70 63 1 1 110 113 70 63 110 113 106 99 61 53 60 52 114 111 61 53 114 111 115 112 71 64 69 101 105 91 71 64 105 91 107 103 73 62 76 66 116 114 73 62 116 114 108 95 69 101 101 88 105 91 76 66 63 55 97 84 76 66 97 84 116 114 67 59 66 58 102 89 67 59 102 89 101 88 74 102 71 64 107 103 63 55 98 85 97 84 66 58 73 62 108 95 62 54 61 53 115 112 62 54 115 112 98 85 1 1 74 102 111 104 1 1 111 104 110 113 117 115 119 116 118 117 117 115 120 118 119 116 124 119 126 120 125 121 126 120 128 122 127 123 132 124 133 125 131 126 132 124 134 127 133 125 133 125 137 128 136 129 143 130 144 131 142 132 150 133 146 134 151 135 146 134 142 132 144 131 142 132 138 136 140 137 138 136 136 129 137 128 148 138 146 134 150 133 138 136 153 139 136 129 153 139 148 138 155 140 138 136 148 138 153 139 151 135 117 115 118 117 120 118 124 119 122 141 132 124 135 142 134 127 141 143 145 144 143 130 157 145 124 119 120 118 132 124 141 143 135 142 121 146 149 147 119 116 129 148 154 149 127 123 129 148 153 139 154 149 123 150 148 138 121 146 123 150 156 151 148 138 125 121 155 140 156 151 119 116 150 133 118 117 119 116 149 147 150 133 133 125 152 152 131 126 127 123 155 140 125 121 166 153 167 154 165 155 168 156 167 154 166 153 168 156 169 157 167 154 163 158 171 159 170 160 172 161 173 162 169 157 174 163 161 164 158 165 174 163 175 166 161 164 170 160 175 166 174 163 170 160 171 159 175 166 177 167 179 168 178 169 177 167 180 170 179 168 181 171 183 172 182 173 181 171 184 174 183 172 185 175 184 174 181 171 182 173 190 176 189 177 118 117 188 178 187 179 189 177 193 180 192 181 194 182 197 183 196 184 198 185 200 186 199 187 198 185 201 188 200 186 202 189 199 187 203 190 202 189 198 185 199 187 204 191 203 190 205 192 201 188 206 193 200 186 208 194 205 192 209 195 210 196 194 182 195 197 213 198 215 199 214 200 213 198 216 201 215 199 217 202 219 203 218 204 221 205 218 204 222 206 221 205 217 202 218 204 229 207 214 200 230 208 229 207 213 198 214 200 226 209 230 208 225 210 226 209 229 207 230 208 158 165 194 182 210 196 168 156 208 194 172 161 168 156 204 191 208 194 159 211 197 183 194 182 170 160 201 188 163 158 169 157 203 190 167 154 169 157 205 192 203 190 167 154 199 187 165 155 167 154 203 190 199 187 165 155 200 186 164 212 161 164 196 184 160 213 164 212 206 193 171 159 164 212 200 186 206 193 160 213 197 183 159 211 172 161 208 194 209 195 185 175 223 214 187 179 181 171 221 205 185 175 177 167 213 198 229 207 182 173 220 215 217 202 178 169 213 198 177 167 178 169 216 201 213 198 189 177 220 215 182 173 189 177 226 209 220 215 190 176 230 208 193 180 190 176 225 210 230 208 186 216 218 204 184 174 193 180 230 208 214 200 191 217 228 218 224 219 180 170 215 199 179 168 183 172 219 203 225 210 179 168 216 201 178 169 179 168 215 199 216 201 120 118 121 146 119 116 120 118 122 141 121 146 122 141 123 150 121 146 122 141 124 119 123 150 124 119 125 121 123 150 126 120 127 123 125 121 128 122 129 148 127 123 128 122 130 220 129 148 130 220 131 126 129 148 130 220 132 124 131 126 135 142 133 125 134 127 133 125 135 142 137 128 135 142 138 136 137 128 135 142 139 221 138 136 139 221 140 137 138 136 139 221 141 143 140 137 141 143 142 132 140 137 141 143 143 130 142 132 143 130 145 144 144 131 145 144 146 134 144 131 145 144 147 222 146 134 148 138 150 133 149 147 136 129 153 139 152 152 153 139 155 140 154 149 155 140 148 138 156 151 146 134 138 136 142 132 148 138 138 136 146 134 147 222 151 135 146 134 147 222 157 145 151 135 117 115 151 135 157 145 151 135 118 117 150 133 157 145 120 118 117 115 124 119 128 122 126 120 128 122 132 124 130 220 135 142 141 143 139 221 145 144 157 145 147 222 124 119 132 124 128 122 141 143 157 145 145 144 157 145 132 124 124 119 132 124 157 145 141 143 121 146 148 138 149 147 131 126 153 139 129 148 131 126 152 152 153 139 125 121 156 151 123 150 133 125 136 129 152 152 127 123 154 149 155 140 158 165 160 213 159 211 158 165 161 164 160 213 162 223 164 212 163 158 162 223 165 155 164 212 166 153 165 155 162 223 163 158 164 212 171 159 172 161 169 157 168 156 194 182 196 184 195 197 204 191 202 189 203 190 201 188 207 224 206 193 208 194 204 191 205 192 210 196 195 197 211 225 207 224 211 225 206 193 207 224 210 196 211 225 166 153 204 191 168 156 166 153 202 189 204 191 174 163 207 224 170 160 174 163 210 196 207 224 162 223 202 189 166 153 162 223 198 185 202 189 158 165 210 196 174 163 163 158 198 185 162 223 163 158 201 188 198 185 159 211 194 182 158 165 170 160 207 224 201 188 171 159 211 225 175 166 171 159 206 193 211 225 175 166 195 197 161 164 175 166 211 225 195 197 165 155 199 187 200 186 173 162 205 192 169 157 173 162 209 195 205 192 161 164 195 197 196 184 160 213 196 184 197 183 172 161 209 195 173 162 185 175 186 216 184 174 187 179 186 216 185 175 187 179 188 178 186 216 182 173 183 172 190 176 118 117 191 217 188 178 192 181 180 170 177 167 192 181 193 180 180 170 189 177 190 176 193 180 231 198 215 199 214 200 231 198 232 201 215 199 217 202 220 215 219 203 223 214 222 206 224 219 223 214 221 205 222 206 220 215 225 210 219 203 220 215 226 209 225 210 227 226 224 219 228 218 227 226 223 214 224 219 229 207 214 200 233 227 229 207 231 198 214 200 226 209 233 227 225 210 226 209 229 207 233 227 185 175 221 205 223 214 192 181 226 209 189 177 192 181 229 207 226 209 181 171 217 202 221 205 177 167 229 207 192 181 177 167 231 198 229 207 182 173 217 202 181 171 187 179 227 226 118 117 187 179 223 214 227 226 178 169 231 198 177 167 178 169 232 201 231 198 188 178 222 206 186 216 188 178 224 219 222 206 190 176 233 227 193 180 190 176 225 210 233 227 186 216 222 206 218 204 193 180 214 200 180 170 193 180 233 227 214 200 184 174 219 203 183 172 184 174 218 204 219 203 191 217 224 219 188 178 180 170 214 200 215 199 183 172 225 210 190 176 179 168 232 201 178 169 179 168 215 199 232 201 118 117 228 218 191 217 118 117 227 226 228 218 234 228 236 229 235 230 234 228 237 231 236 229 241 232 243 233 242 234 243 233 245 235 244 236 249 237 250 238 248 239 249 237 251 240 250 238 250 238 254 241 253 242 260 243 261 244 259 245 267 246 263 247 268 248 263 247 259 245 261 244 259 245 255 249 257 250 255 249 253 242 254 241 265 251 263 247 267 246 255 249 270 252 253 242 270 252 265 251 272 253 255 249 265 251 270 252 268 248 234 228 235 230 237 231 241 232 239 254 249 237 252 255 251 240 258 256 262 257 260 243 274 258 241 232 237 231 249 237 258 256 252 255 238 259 266 260 236 229 246 261 271 262 244 236 246 261 270 252 271 262 240 263 265 251 238 259 240 263 273 264 265 251 242 234 272 253 273 264 236 229 267 246 235 230 236 229 266 260 267 246 250 238 269 265 248 239 244 236 272 253 242 234 283 266 284 267 282 268 285 269 284 267 283 266 285 269 286 270 284 267 280 271 288 272 287 273 289 274 290 275 286 270 291 276 278 277 275 278 291 276 292 279 278 277 287 273 292 279 291 276 287 273 288 272 292 279 294 280 296 281 295 282 294 280 297 283 296 281 298 284 300 285 299 286 298 284 301 287 300 285 302 288 301 287 298 284 299 286 307 289 306 290 235 230 305 291 304 292 306 290 310 293 309 294 311 295 314 296 313 297 315 298 317 299 316 300 315 298 318 301 317 299 319 302 316 300 320 303 319 302 315 298 316 300 321 304 320 303 322 305 318 301 323 306 317 299 325 307 322 305 326 308 327 309 311 295 312 310 330 311 332 312 331 313 330 311 333 314 332 312 334 315 336 316 335 317 338 318 335 317 339 319 338 318 334 315 335 317 346 320 331 313 347 321 346 320 330 311 331 313 343 322 347 321 342 323 343 322 346 320 347 321 275 278 311 295 327 309 285 269 325 307 289 274 285 269 321 304 325 307 276 324 314 296 311 295 287 273 318 301 280 271 286 270 320 303 284 267 286 270 322 305 320 303 284 267 316 300 282 268 284 267 320 303 316 300 282 268 317 299 281 325 278 277 313 297 277 326 281 325 323 306 288 272 281 325 317 299 323 306 277 326 314 296 276 324 289 274 325 307 326 308 302 288 340 327 304 292 298 284 338 318 302 288 294 280 330 311 346 320 299 286 337 328 334 315 295 282 330 311 294 280 295 282 333 314 330 311 306 290 337 328 299 286 306 290 343 322 337 328 307 289 347 321 310 293 307 289 342 323 347 321 303 329 335 317 301 287 310 293 347 321 331 313 308 330 345 331 341 332 297 283 332 312 296 281 300 285 336 316 342 323 296 281 333 314 295 282 296 281 332 312 333 314 237 231 238 259 236 229 237 231 239 254 238 259 239 254 240 263 238 259 239 254 241 232 240 263 241 232 242 234 240 263 243 233 244 236 242 234 245 235 246 261 244 236 245 235 247 333 246 261 247 333 248 239 246 261 247 333 249 237 248 239 252 255 250 238 251 240 250 238 252 255 254 241 252 255 255 249 254 241 252 255 256 334 255 249 256 334 257 250 255 249 256 334 258 256 257 250 258 256 259 245 257 250 258 256 260 243 259 245 260 243 262 257 261 244 262 257 263 247 261 244 262 257 264 335 263 247 265 251 267 246 266 260 253 242 270 252 269 265 270 252 272 253 271 262 272 253 265 251 273 264 263 247 255 249 259 245 265 251 255 249 263 247 264 335 268 248 263 247 264 335 274 258 268 248 234 228 268 248 274 258 268 248 235 230 267 246 274 258 237 231 234 228 241 232 245 235 243 233 245 235 249 237 247 333 252 255 258 256 256 334 262 257 274 258 264 335 241 232 249 237 245 235 258 256 274 258 262 257 274 258 249 237 241 232 249 237 274 258 258 256 238 259 265 251 266 260 248 239 270 252 246 261 248 239 269 265 270 252 242 234 273 264 240 263 250 238 253 242 269 265 244 236 271 262 272 253 275 278 277 326 276 324 275 278 278 277 277 326 279 336 281 325 280 271 279 336 282 268 281 325 283 266 282 268 279 336 280 271 281 325 288 272 289 274 286 270 285 269 311 295 313 297 312 310 321 304 319 302 320 303 318 301 324 337 323 306 325 307 321 304 322 305 327 309 312 310 328 338 324 337 328 338 323 306 324 337 327 309 328 338 283 266 321 304 285 269 283 266 319 302 321 304 291 276 324 337 287 273 291 276 327 309 324 337 279 336 319 302 283 266 279 336 315 298 319 302 275 278 327 309 291 276 280 271 315 298 279 336 280 271 318 301 315 298 276 324 311 295 275 278 287 273 324 337 318 301 288 272 328 338 292 279 288 272 323 306 328 338 292 279 312 310 278 277 292 279 328 338 312 310 282 268 316 300 317 299 290 275 322 305 286 270 290 275 326 308 322 305 278 277 312 310 313 297 277 326 313 297 314 296 289 274 326 308 290 275 302 288 303 329 301 287 304 292 303 329 302 288 304 292 305 291 303 329 299 286 300 285 307 289 235 230 308 330 305 291 309 294 297 283 294 280 309 294 310 293 297 283 306 290 307 289 310 293 348 311 332 312 331 313 348 311 349 314 332 312 334 315 337 328 336 316 340 327 339 319 341 332 340 327 338 318 339 319 337 328 342 323 336 316 337 328 343 322 342 323 344 339 341 332 345 331 344 339 340 327 341 332 346 320 331 313 350 340 346 320 348 311 331 313 343 322 350 340 342 323 343 322 346 320 350 340 302 288 338 318 340 327 309 294 343 322 306 290 309 294 346 320 343 322 298 284 334 315 338 318 294 280 346 320 309 294 294 280 348 311 346 320 299 286 334 315 298 284 304 292 344 339 235 230 304 292 340 327 344 339 295 282 348 311 294 280 295 282 349 314 348 311 305 291 339 319 303 329 305 291 341 332 339 319 307 289 350 340 310 293 307 289 342 323 350 340 303 329 339 319 335 317 310 293 331 313 297 283 310 293 350 340 331 313 301 287 336 316 300 285 301 287 335 317 336 316 308 330 341 332 305 291 297 283 331 313 332 312 300 285 342 323 307 289 296 281 349 314 295 282 296 281 332 312 349 314 235 230 345 331 308 330 235 230 344 339 345 331 351 341 352 342 353 343 351 341 353 343 354 344 358 345 359 346 360 347 360 347 361 348 362 349 366 350 365 351 367 352 366 350 367 352 368 353 367 352 370 354 371 355 377 356 376 357 378 358 384 359 385 360 380 361 380 361 378 358 376 357 376 357 374 362 372 363 372 363 371 355 370 354 382 364 384 359 380 361 372 363 370 354 387 365 387 365 389 366 382 364 372 363 387 365 382 364 385 360 352 342 351 341 354 344 356 367 358 345 366 350 368 353 369 368 375 369 377 356 379 370 391 371 354 344 358 345 366 350 369 368 375 369 355 372 353 343 383 373 363 374 361 348 388 375 363 374 388 375 387 365 357 376 355 372 382 364 357 376 382 364 390 377 359 346 390 377 389 366 353 343 352 342 384 359 353 343 384 359 383 373 367 352 365 351 386 378 361 348 359 346 389 366 400 379 399 380 401 381 402 382 400 379 401 381 402 382 401 381 403 383 397 384 404 385 405 386 406 387 403 383 407 388 408 389 392 390 395 391 408 389 395 391 409 392 404 385 408 389 409 392 404 385 409 392 405 386 411 393 412 394 413 395 411 393 413 395 414 396 415 397 416 398 417 399 415 397 417 399 418 400 419 401 415 397 418 400 416 398 423 402 424 403 352 342 421 404 422 405 423 402 426 406 427 407 428 408 430 409 431 410 432 411 433 412 434 413 432 411 434 413 435 414 436 415 437 416 433 412 436 415 433 412 432 411 438 417 439 418 437 416 435 414 434 413 440 419 442 420 443 421 439 418 444 422 429 423 428 408 447 424 448 425 449 426 447 424 449 426 450 427 451 428 452 429 453 430 455 431 456 432 452 429 455 431 452 429 451 428 463 433 464 434 448 425 463 433 448 425 447 424 460 435 459 436 464 434 460 435 464 434 463 433 392 390 444 422 428 408 402 382 406 387 442 420 402 382 442 420 438 417 393 437 428 408 431 410 404 385 397 384 435 414 403 383 401 381 437 416 403 383 437 416 439 418 401 381 399 380 433 412 401 381 433 412 437 416 399 380 398 438 434 413 395 391 394 439 430 409 398 438 405 386 440 419 398 438 440 419 434 413 394 439 393 437 431 410 406 387 443 421 442 420 419 401 421 404 457 440 415 397 419 401 455 431 411 393 463 433 447 424 416 398 451 428 454 441 412 394 411 393 447 424 412 394 447 424 450 427 423 402 416 398 454 441 423 402 454 441 460 435 424 403 427 407 464 434 424 403 464 434 459 436 420 442 418 400 452 429 427 407 448 425 464 434 425 443 458 444 462 445 414 396 413 395 449 426 417 399 459 436 453 430 413 395 412 394 450 427 413 395 450 427 449 426 354 344 353 343 355 372 354 344 355 372 356 367 356 367 355 372 357 376 356 367 357 376 358 345 358 345 357 376 359 346 360 347 359 346 361 348 362 349 361 348 363 374 362 349 363 374 364 446 364 446 363 374 365 351 364 446 365 351 366 350 369 368 368 353 367 352 367 352 371 355 369 368 369 368 371 355 372 363 369 368 372 363 373 447 373 447 372 363 374 362 373 447 374 362 375 369 375 369 374 362 376 357 375 369 376 357 377 356 377 356 378 358 379 370 379 370 378 358 380 361 379 370 380 361 381 448 382 364 383 373 384 359 370 354 386 378 387 365 387 365 388 375 389 366 389 366 390 377 382 364 380 361 376 357 372 363 382 364 380 361 372 363 381 448 380 361 385 360 381 448 385 360 391 371 351 341 391 371 385 360 385 360 384 359 352 342 391 371 351 341 354 344 358 345 360 347 362 349 362 349 364 446 366 350 369 368 373 447 375 369 379 370 381 448 391 371 358 345 362 349 366 350 375 369 379 370 391 371 391 371 358 345 366 350 366 350 375 369 391 371 355 372 383 373 382 364 365 351 363 374 387 365 365 351 387 365 386 378 359 346 357 376 390 377 367 352 386 378 370 354 361 348 389 366 388 375 392 390 393 437 394 439 392 390 394 439 395 391 396 449 397 384 398 438 396 449 398 438 399 380 400 379 396 449 399 380 397 384 405 386 398 438 406 387 402 382 403 383 428 408 429 423 430 409 438 417 437 416 436 415 435 414 440 419 441 450 442 420 439 418 438 417 444 422 445 451 429 423 441 450 440 419 445 451 441 450 445 451 444 422 400 379 402 382 438 417 400 379 438 417 436 415 408 389 404 385 441 450 408 389 441 450 444 422 396 449 400 379 436 415 396 449 436 415 432 411 392 390 408 389 444 422 397 384 396 449 432 411 397 384 432 411 435 414 393 437 392 390 428 408 404 385 435 414 441 450 405 386 409 392 445 451 405 386 445 451 440 419 409 392 395 391 429 423 409 392 429 423 445 451 399 380 434 413 433 412 407 388 403 383 439 418 407 388 439 418 443 421 395 391 430 409 429 423 394 439 431 410 430 409 406 387 407 388 443 421 419 401 418 400 420 442 421 404 419 401 420 442 421 404 420 442 422 405 416 398 424 403 417 399 352 342 422 405 425 443 426 406 411 393 414 396 426 406 414 396 427 407 423 402 427 407 424 403 465 424 448 425 449 426 465 424 449 426 466 427 451 428 453 430 454 441 457 440 458 444 456 432 457 440 456 432 455 431 454 441 453 430 459 436 454 441 459 436 460 435 461 452 462 445 458 444 461 452 458 444 457 440 463 433 467 453 448 425 463 433 448 425 465 424 460 435 459 436 467 453 460 435 467 453 463 433 419 401 457 440 455 431 426 406 423 402 460 435 426 406 460 435 463 433 415 397 455 431 451 428 411 393 426 406 463 433 411 393 463 433 465 424 416 398 415 397 451 428 421 404 352 342 461 452 421 404 461 452 457 440 412 394 411 393 465 424 412 394 465 424 466 427 422 405 420 442 456 432 422 405 456 432 458 444 424 403 427 407 467 453 424 403 467 453 459 436 420 442 452 429 456 432 427 407 414 396 448 425 427 407 448 425 467 453 418 400 417 399 453 430 418 400 453 430 452 429 425 443 422 405 458 444 414 396 449 426 448 425 417 399 424 403 459 436 413 395 412 394 466 427 413 395 466 427 449 426 352 342 425 443 462 445 352 342 462 445 461 452

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0.025 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0.011 0 0 1 0.014 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1.229657 0.02 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0.015 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + 0.705359 0 0 0.031 0 0.705359 0 0.031 0 0 0.705359 0.014 0 0 0 1 + + + + + + + + + + + + 0.7071068 0.7071068 0 0.031 -0.7071068 0.7071068 0 0.031 0 0 1 0.014 0 0 0 1 + + + + + + + + + + 0.6918778 0.7220147 0 0.031 -0.7220147 0.6918778 0 0.031 0 0 1 0.022 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/crazyflie/urdf/crazyflie_description.urdf b/crazyflie/urdf/crazyflie_description.urdf new file mode 100644 index 000000000..88a68e5c0 --- /dev/null +++ b/crazyflie/urdf/crazyflie_description.urdf @@ -0,0 +1,11 @@ + + + + + + + + + + + \ No newline at end of file diff --git a/crazyflie_sim/crazyflie_sim/crazyflie_server.py b/crazyflie_sim/crazyflie_sim/crazyflie_server.py index 0d05fede7..13bf4ae2e 100755 --- a/crazyflie_sim/crazyflie_sim/crazyflie_server.py +++ b/crazyflie_sim/crazyflie_sim/crazyflie_server.py @@ -16,6 +16,7 @@ import rclpy from rclpy.node import Node import rowan +from std_msgs.msg import String from std_srvs.srv import Empty @@ -100,6 +101,17 @@ def __init__(self): self._start_trajectory_callback) for name, _ in self.cfs.items(): + pub = self.create_publisher( + String, + name + '/robot_description', + rclpy.qos.QoSProfile( + depth=1, + durability=rclpy.qos.QoSDurabilityPolicy.TRANSIENT_LOCAL)) + + msg = String() + msg.data = self._ros_parameters['robot_description'].replace('$NAME', name) + pub.publish(msg) + self.create_service( Empty, name + '/emergency', From 14bdc226541dfab1a3ec1284a7c59ea24034863f Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Thu, 1 Feb 2024 16:03:45 +0100 Subject: [PATCH 067/162] server cpp: add new communication warnings * unicast_receive_rate measures the end-to-end rate of received unicast packets over sent unicast packets * broadcast_receive_rate measures the end-to-end rate of received broadcast packets over sent unicast packets Warnings if this is larger than 1 or smaller than a user-defined threshold. --- crazyflie/config/crazyflies.yaml | 2 ++ crazyflie/config/server.yaml | 2 ++ crazyflie/src/crazyflie_server.cpp | 27 +++++++++++++++++++++++++++ 3 files changed, 31 insertions(+) diff --git a/crazyflie/config/crazyflies.yaml b/crazyflie/config/crazyflies.yaml index e136fcd8b..adefcbfd1 100644 --- a/crazyflie/config/crazyflies.yaml +++ b/crazyflie/config/crazyflies.yaml @@ -77,6 +77,8 @@ all: # remove to disable default topic pose: frequency: 10 # Hz + status: + frequency: 1 # Hz #custom_topics: # topic_name1: # frequency: 10 # Hz diff --git a/crazyflie/config/server.yaml b/crazyflie/config/server.yaml index 6ec8a3989..59a3ebcb5 100644 --- a/crazyflie/config/server.yaml +++ b/crazyflie/config/server.yaml @@ -7,6 +7,8 @@ communication: max_unicast_latency: 10.0 # ms min_unicast_ack_rate: 0.9 + min_unicast_receive_rate: 0.9 # requires status topic to be enabled + min_broadcast_receive_rate: 0.9 # requires status topic to be enabled publish_stats: false firmware_params: query_all_values_on_connect: False diff --git a/crazyflie/src/crazyflie_server.cpp b/crazyflie/src/crazyflie_server.cpp index 4a71e0245..1dfe1de98 100644 --- a/crazyflie/src/crazyflie_server.cpp +++ b/crazyflie/src/crazyflie_server.cpp @@ -181,6 +181,8 @@ class CrazyflieROS warning_freq_ = node->get_parameter("warnings.frequency").get_parameter_value().get(); max_latency_ = node->get_parameter("warnings.communication.max_unicast_latency").get_parameter_value().get(); min_ack_rate_ = node->get_parameter("warnings.communication.min_unicast_ack_rate").get_parameter_value().get(); + min_unicast_receive_rate_ = node->get_parameter("warnings.communication.min_unicast_receive_rate").get_parameter_value().get(); + min_broadcast_receive_rate_ = node->get_parameter("warnings.communication.min_broadcast_receive_rate").get_parameter_value().get(); publish_stats_ = node->get_parameter("warnings.communication.publish_stats").get_parameter_value().get(); if (publish_stats_) { publisher_connection_stats_ = node->create_publisher(name + "/connection_statistics", 10); @@ -801,6 +803,27 @@ class CrazyflieROS previous_stats_broadcast_ = statsBc; publisher_status_->publish(msg); + + // warnings + if (msg.num_rx_unicast > msg.num_tx_unicast) { + RCLCPP_WARN(logger_, "Unexpected number of unicast packets. Sent: %d. Received: %d", msg.num_tx_unicast, msg.num_rx_unicast); + } + if (msg.num_tx_unicast > 0) { + float unicast_receive_rate = msg.num_rx_unicast / (float)msg.num_tx_unicast; + if (unicast_receive_rate < min_unicast_receive_rate_) { + RCLCPP_WARN(logger_, "Low unicast receive rate (%.2f < %.2f). Sent: %d. Received: %d", unicast_receive_rate, min_unicast_receive_rate_, msg.num_tx_unicast, msg.num_rx_unicast); + } + } + + if (msg.num_rx_broadcast > msg.num_tx_broadcast) { + RCLCPP_WARN(logger_, "Unexpected number of broadcast packets. Sent: %d. Received: %d", msg.num_tx_broadcast, msg.num_rx_broadcast); + } + if (msg.num_tx_broadcast > 0) { + float broadcast_receive_rate = msg.num_rx_broadcast / (float)msg.num_tx_broadcast; + if (broadcast_receive_rate < min_broadcast_receive_rate_) { + RCLCPP_WARN(logger_, "Low broadcast receive rate (%.2f < %.2f). Sent: %d. Received: %d", broadcast_receive_rate, min_broadcast_receive_rate_, msg.num_tx_broadcast, msg.num_rx_broadcast); + } + } } } @@ -912,6 +935,8 @@ class CrazyflieROS float warning_freq_; float max_latency_; float min_ack_rate_; + float min_unicast_receive_rate_; + float min_broadcast_receive_rate_; bool publish_stats_; rclcpp::Publisher::SharedPtr publisher_connection_stats_; }; @@ -980,6 +1005,8 @@ class CrazyflieServer : public rclcpp::Node this->declare_parameter("warnings.communication.max_unicast_latency", 10.0); this->declare_parameter("warnings.communication.min_unicast_ack_rate", 0.9); + this->declare_parameter("warnings.communication.min_unicast_receive_rate", 0.9); + this->declare_parameter("warnings.communication.min_broadcast_receive_rate", 0.9); this->declare_parameter("warnings.communication.publish_stats", false); publish_stats_ = this->get_parameter("warnings.communication.publish_stats").get_parameter_value().get(); From 19f40f5ef1b5439faac6233e5ad1e50696d0e036 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Thu, 1 Feb 2024 21:55:38 +0100 Subject: [PATCH 068/162] add initial gui draft --- crazyflie/CMakeLists.txt | 1 + crazyflie/scripts/gui.py | 145 ++++++++++++++++++++++++++++++++ crazyflie/urdf/cf2_assembly.stl | Bin 0 -> 166184 bytes 3 files changed, 146 insertions(+) create mode 100755 crazyflie/scripts/gui.py create mode 100644 crazyflie/urdf/cf2_assembly.stl diff --git a/crazyflie/CMakeLists.txt b/crazyflie/CMakeLists.txt index c8899cfbe..66e1e4ae1 100644 --- a/crazyflie/CMakeLists.txt +++ b/crazyflie/CMakeLists.txt @@ -109,6 +109,7 @@ install(PROGRAMS scripts/vel_mux.py scripts/cfmult.py scripts/simple_mapper_multiranger.py + scripts/gui.py DESTINATION lib/${PROJECT_NAME} ) diff --git a/crazyflie/scripts/gui.py b/crazyflie/scripts/gui.py new file mode 100755 index 000000000..3941d8c77 --- /dev/null +++ b/crazyflie/scripts/gui.py @@ -0,0 +1,145 @@ +#!/usr/bin/env python3 + +import math +import threading +from pathlib import Path + +import rclpy +from geometry_msgs.msg import Pose, Twist +from rcl_interfaces.msg import Log +from rclpy.executors import ExternalShutdownException +from rclpy.node import Node + +from tf2_ros import TransformException +from tf2_ros.buffer import Buffer +from tf2_ros.transform_listener import TransformListener + +from nicegui import Client, app, events, ui, ui_run + + +class NiceGuiNode(Node): + + def __init__(self) -> None: + super().__init__('nicegui') + + # find all crazyflies + self.cfnames = [] + for srv_name, srv_types in self.get_service_names_and_types(): + if 'crazyflie_interfaces/srv/StartTrajectory' in srv_types: + # remove '/' and '/start_trajectory' + cfname = srv_name[1:-17] + if cfname != 'all': + self.cfnames.append(cfname) + + print(self.cfnames) + self.cfs = [] + + self.tf_buffer = Buffer() + self.tf_listener = TransformListener(self.tf_buffer, self) + + + + + self.cmd_vel_publisher = self.create_publisher(Twist, 'cmd_vel', 1) + self.sub_log = self.create_subscription(Log, 'rosout', self.on_rosout, 1) + + self.logs = dict() + + with Client.auto_index_client: + # with ui.row().classes('w-full h-full no-wrap'): + # self.log = ui.log().classes('w-full h-full no-wrap') + + + + + with ui.row().classes('items-stretch'): + # with ui.card().classes('w-44 text-center items-center'): + # ui.label('Data').classes('text-2xl') + # ui.label('linear velocity').classes('text-xs mb-[-1.8em]') + # slider_props = 'readonly selection-color=transparent' + # self.linear = ui.slider(min=-1, max=1, step=0.05, value=0).props(slider_props) + # ui.label('angular velocity').classes('text-xs mb-[-1.8em]') + # self.angular = ui.slider(min=-1, max=1, step=0.05, value=0).props(slider_props) + # ui.label('position').classes('text-xs mb-[-1.4em]') + # self.position = ui.label('---') + with ui.card().classes('w-full h-full'): + ui.label('Visualization').classes('text-2xl') + with ui.scene(800, 600, on_click=self.on_vis_click) as scene: + for name in self.cfnames: + robot = scene.stl('/urdf/cf2_assembly.stl').scale(1.0).material('#ff0000').with_name(name) + self.cfs.append(robot) + # with scene.group() as self.robot_3d: + # prism = [[-0.5, -0.5], [0.5, -0.5], [0.75, 0], [0.5, 0.5], [-0.5, 0.5]] + # self.robot_object = scene.extrusion(prism, 0.4).material('#4488ff', 0.5) + + with ui.row().classes('w-full h-full'): + with ui.tabs().classes('w-full') as tabs: + self.tabs = [] + for name in ["all"] + self.cfnames: + self.tabs.append(ui.tab(name)) + with ui.tab_panels(tabs, value=self.tabs[0]).classes('w-full') as self.tabpanels: + for name, tab in zip(["all"] + self.cfnames, self.tabs): + with ui.tab_panel(tab): + self.logs[name] = ui.log().classes('w-full h-full no-wrap') + ui.label("Battery Voltage: ") + ui.button("Reboot") + + # Call on_timer function + self.timer = self.create_timer(0.1, self.on_timer) + + def send_speed(self, x: float, y: float) -> None: + msg = Twist() + msg.linear.x = x + msg.angular.z = -y + self.linear.value = x + self.angular.value = y + self.cmd_vel_publisher.publish(msg) + + def on_rosout(self, msg: Log) -> None: + if msg.name in self.logs: + self.logs[msg.name].push(msg.msg) + + def on_timer(self) -> None: + for name, robot in zip(self.cfnames, self.cfs): + t = self.tf_buffer.lookup_transform( + "world", + name, + rclpy.time.Time()) + pos = t.transform.translation + robot.move(pos.x, pos.y, pos.z) + + def on_vis_click(self, e: events.SceneClickEventArguments): + hit = e.hits[0] + name = hit.object_name or hit.object_id + ui.notify(f'You clicked on the {name}') + if name == 'ground': + self.tabpanels.value = 'all' + else: + self.tabpanels.value = name + + + + # def handle_pose(self, msg: Pose) -> None: + # self.position.text = f'x: {msg.position.x:.2f}, y: {msg.position.y:.2f}' + # self.robot_3d.move(msg.position.x, msg.position.y) + # self.robot_3d.rotate(0, 0, 2 * math.atan2(msg.orientation.z, msg.orientation.w)) + + +def main() -> None: + # NOTE: This function is defined as the ROS entry point in setup.py, but it's empty to enable NiceGUI auto-reloading + pass + + +def ros_main() -> None: + rclpy.init() + node = NiceGuiNode() + try: + rclpy.spin(node) + except ExternalShutdownException: + pass + + +app.add_static_files("/urdf", "/home/whoenig/projects/crazyflie/crazyswarm2/src/crazyswarm2/crazyflie/urdf/") +app.on_startup(lambda: threading.Thread(target=ros_main).start()) +ui_run.APP_IMPORT_STRING = f'{__name__}:app' # ROS2 uses a non-standard module name, so we need to specify it here +ui.run(uvicorn_reload_dirs=str(Path(__file__).parent.resolve()), favicon='🤖') diff --git a/crazyflie/urdf/cf2_assembly.stl b/crazyflie/urdf/cf2_assembly.stl new file mode 100644 index 0000000000000000000000000000000000000000..02772d31eee4006fef671357ff447daf0f273ffa GIT binary patch literal 166184 zcmce<3EY;`_6EF5MaE;E=iyKx6w&=Ww<$t~lHpLKOc|n#8S2%5qRhfUsYvFdB=tPc zEg~eE%#|XU8mJJW@4D`Nujjq?`@VJj&-Z=${r-RJJbPVxtv#*1_uA`TZ;NX$zpUGp z=bgLL`Q0wNbf?2FIj_sP=XKlrfPEV8)7bql|9)E^sP;{g z_k8@(=zvDISCe4~ua)sTSCLqW>Q36)S4~E8Wv6|jb3eE#ZLOkBwnsEx**3m-oek6R zxNeghqCIarFhv*_HL>5lR`=XGpoz6ZOB7-9sD-_Db&q$r<)RX?CWF$gO-hF?U$v@dVs$AOX|2h* z6_~qive|yc#_bD-Wb4CdB3|y$aQx?3E2N#nY)@>qe>Y@dL1ue_vz?k??xwUyRJOe$ zu6X>>g3UzqXhCLv8C}WGb{H4yGI^v|FQfY=HxxLps0n6efwPjd)#UrC&fOcuBeF49 zE~6>K5WXFlC9%yCfX5mtVX~lXC;bmCwVkQO% zoW<}E$nha`Uw3l(ircc<4;@qVjOc9FCR&dr=18*HrZikhyE<=zG zwX$|_mMB8GOt#l5v!ZG5YKbC@_Pr}IQtQK+!4i{4+GbC6#Fu;YD0GV-PEUQ4_G(+$ zXRlc)eclCY6+S(G&&X>vd)4O2zppqkzVd}BqqOAO-;N!>-76hauC5vFWt7(1GI?dp z3F$i55|c+RqrHsok8hcr-uQ%grxGkw((dqf?QTp%?OA}*MxDI zJkGbjhA0 zf6w%^#5Lb=uUY8{kiC0Z{BTM;m+iIb{-GsCTRXOSrDJxI$@cT4-`B1wTWBTh1=7?+ zWn%P@24vw;kgM|6m=ol_CU#XdB;QUceY z>P{}A*$zWk%MIoCT5GLxSvx!;+d0$TrOjwl|HO3ua8}y9GTI}SV?0jF?glj>$YsA* z(<<#No1;2+O-9&P*1LvKE|XCmq4nzQ)A?ro#Q*xe)>^AvDlg?s`-zl|0i_$w){>^S z*79)Yv@usMqpckw0;0-0Cux&m<4;{yk1#IN&}0zheHqq^RmQb=CPsT1YT;@^RPAZ!u9m%)z1UT5!h6e2_>=NY_)FY`2jM2%HMMw2gVS zol|eZj$B+()WMGj?JfTo|7B|}K#!6=7u-n zpdG&DbF-UpRfKA2?eGZJ?*El{=k)et2x?+&s-~5l08)f z^LWh&M8aTV0j>L}-a3Y#vwZ-2kCnJPp_?pp0=*}JwL|2u*`8jeR*8LWf)8kf?3JpLQPWUwZWcr)9bX-RDiSYor!5S6opSpKVu zFs%$x+44zMZo=9>)^8@ykH^+kZo-C8F4NW{s@{ZcE-Auj-}0(A;i?F7nGBEc?dJcl zNNg@u<*GX79>c!U61BT#6TOV8H(|~=mZ&_f$+-oO@09wGtIE)NZ61g103zMbZB`o> zd(_arcdg}B5z3|eRk_uvwbl|v811!E>tn5@bfd{-8hS*wpQkd6iwNa1+P7oEsjI&U z!+w-+!kBNXxd~fIHU{ZQR?jHT{oilG-LN~i$4&Us>?Uk7v|hc7c&`Dx&I$XOEv)H$ z#oo1BxO4x%-h|8hV71-3e6OXZ95t>%(&4I*G2-bvPz4m)Gt?@lkHs*%;UvI)DL+iC!>1E(1Y_G4W z*V%5{YIk)sO(Xs{yw}!r|Mb0Ei3t&AoylcdDZomS`-@*Mw1J#@8yWS%AR8HW)U0dJFp>$HiU1- zQbeTG|GrV$azn6QLn!SLSq#f+5#+L(Jfc#sFiKBl7{a%_h8ULg45wUKTt@o4bIlN? zcg`B3^jNQ zji96M_PcKfqCaDa{wzn$WpNT|k1}$^qD|8XQ^v5Q<6&Hsu3ScYt*qUg?HZ-0T&9&r zVD2V}ze-zf2wNiA5 z$n0*~j?6Bl2<0-`wcz}bh9 zH07PrJD?;JtEt2R*N8))#MST z7gv-?XT7Go${_9BYagDLocLt@w6EIlxHOvh$kM3I`NJZk7hIA=XFk6;y0g}bsKG5I zAcg?Zy9R`E8O@rUTl8k@Jh zb|pWxQW=U45r2-`BzX(-mslMGYX{ed(SDYkw7fhXiLL{ymt49E0<998ujI0pleV7r zGVT!>Hfk)f(Ijo-?-3@2mciP=64kI~t%y*qR1=l$++ADTkZjs^|Ma|TtzEied|3wV zhspCJ*uTyGrJ-Bgkgg~jgU?z$U0&O|&OPF1ARb)h6ZVhIC7o9u zF%^h|*MK0G)#MS6K%@0C3ukkQ_R2<+HqmI0I2H95GrOy{)^t}(?GcUdTNK@V-#)od zp6pp(QS8wXix1C@t=lcCvsWp4boP{HW&qfc->=_`G>xltJda+QIHp zcUu#jS6gq~Ja^}+6QYLw#{zNR6OZRMn{sz;-^%ciJ>s{EZNv^oZtI-b23P3!y zd}isU-v*TCzT7@;n^|PeU0P6%J9~H4yZh$mPiYffyxt2y410ZQX|0LOcDul%P?yTvves_vHS%y}i6xo4C+^Yf>nRlDu(%C~-T@BDj@bqx{1b;6-#=D;oPs~mLT!T8V4t)NaXxC9Ka^oklcW-^NR{r-1gK}RSa$|r{ zu0uAvBs#j=VL8q*=SH+xkl$|VTltMHIX<@a%(V8z++{Ja5MJIjyJP_}^u~l*JL2Zgp zUEecVzr)(O-Q1tihu^&%ZMIvB+*$kG9J%hV1oCjwduK_0pW)Ns-gT zU2(;g6AC9z>6r{2QZILbtDUQL*|_MvQAgxv9`SHAY~5D^dCpzlyjT9#kM_!U{q~AP z_0@K4@J{nw%Vj4;XMeyI)$7*hiZd>Lv{=!qM>2Fyo!r=wb#hm<9Ut9tW0PFp#;-=t zd^$Fe=UkVi)AENtb6ftNch5??N2{X7PcDvHjvf(B9o#sVU)eUAedRNejuTFnE$%7p zIjM2!=muSrB|~fFZr!|IjwATah=-ylMz_onvGAp_(NR;I=Qx^p2VU!r(h(CHl$v79 z6`@?eomeM#RI55UKjshjTT%SI&Vb@~81rkkT^!BBDUxIUz+Ui&ZhlyfW8Pr*tD;ie zBIn24y}4CxmqBfE9Kp8#TokqZ`j2!3`{X-C^*%c!#}QOCw0dVr>6GEqO9hOeB9u#I zJGb-fsijdL^)G$8&)Lbcr&dOf4z8DDU+q)>_UQa&$K{Sc`aeN0IQP-gX{8&Vxvg{= zdRGzJSK1@aZNAo!(t;+fN~-u*=?>qP zW_~%i^hMWG0)%p@Z0B0OaC7eS4ZFt=Y|<&O_FTt59P=|Lo|c?4v3|0s-sR18SJS;j z=bLj6tvn^^(Ruyk&}W`6C_=e(6~ON^e`Ws3?ychicix}3a{~8s)g-hGKX0~v@=5bk z^`vc+a}HOTCbiN)Jiz_+51<;om=!R{nq*YoFbG<<-upQ=!E#t!X`B27nrm76oQS)OS_$V)_;{OS&Rxxuf4(%hq&xD9b#~6ZeqZm1d!O21=Q{7R zXS{BgLz70wcFAeIy1$0jXGPrx@$mX_()svi0YbS#tv>tY@MKKOjgo68k0_}oI{x99 zkNtkz_|y8w#TUPG&mlVd)WYc;gH1f{hPc_Ld*?4+)V82Ir=2EwI@|M!#nIpezeKdh z&h38R)p5t8`;_+VF{r5ftD@Cn;J)>rn~R@p*gcts6{V*PU3cL+?{js_c+n->B}4l! zD(dd67U%jievDk#Iyt{becQ(+OM16T+C4HdZ!NES-VJ3OH-BYmVfWTa|2ysv5Xu$W z-MuznKOWWm)MU^3y@OkdY8Yzu@we;6*LFBHX}!;f&GiHjaETprZcg9Y$sIeji}Mp_ z6!iR|=LEG~&UJsMcGCK%GvoZ?*#Sbi)IK`*=%B7i$2|t-*V(vPzTN5PMmuiNJje67 zo{-eeV+60hE&sy>o#IDNDwb3ewbUxlx&6*OB6+s!?#cdjmW;b+-rdn@bGOg&?ELVm z3!`_Z?VIC%e%8Xfqbok!KF596xg$T`CLViN^LQ!Npq?Q0{Hc4QbB*dXNG_}&$Mer< zmeaGLwl>@cZ~f%(_`Q}J#e?4+QPO&K#)M_#7ABoK?av4pl>lm!=S1vY146ls_A=f=t1sHIed@*05~EqK z`F*^M5kO4cxjI6*jP^3-!&CbqJZtnyX^GLPjLcu^Wqb?7^qLUDrQR>+4n)sRufg|f z_h{B@wAbp=llRX*h?PsNw8Us4LZ4-))gYA1XfNZW<-N+@T3dsx*Va5~+uKP~7yDOH z_DrzEW*=#r#~uNXaM{1BCAOl-W$V!+_7$zP#MU{vR9n-C|E-9vh2*j^AgwbdL}*=# z4iWu#YF`=)n?OI>WbDh)9?ScK{g>3&Y8T6{zcyPxt+Rv+d zfOvWh2y$6X9`PY&;rDCsI&*inUhs%l!TodgN~U{})@#3e#P!(Ehp)jSOfDNukEq{a zVCk5ddzIdVKT+?_Hru)P=}iW&WZT_U8ua4crAhE7DnhyRMuvFcR~MCvZx%|kb~_>F zsByH|TD{lmjm)_|Pu40eoG_^PCH#qsP%gbEI(Ku61*QAnf2(v5{E4Tk6J-&B?#kW^VqF3y%rBYIE`| z<~kl>J9?hhJ*hafMXCP3mKPPFTw(8?dRX7mfxBNBAAjyPdG+I)h2wcwwM9%(t-hrt z=Uow>QhVwHxWL#<{vyfUeK{!RJ1=k8HbgmQ)6+Oazg z&RssLYyAAr!vY_fwkg!=m~W3sCU@E{{%Q8@MO~>XFO<>z>Xyl2mu?sLxP4K8P_EE_ zby!~)&+XkRe(2$mfsah>imn^Hv3$E;GP}d6@kU)gY_4OV^=eN$w@=^N@v5ELCAA-( zQP8!mZ!9{;oa->Tc06tQnaL$nW(Nr6(s_(KPWL{gvwL(*+THMGN$XWR7_N`cuDPxB z`~{to&u~9igmS4o_;(kyiU0HEhDoD?-pQ#YQxBAS*qrM*_K5hJQM<%vA3Q6kuVHGV zbj{<<{LCZbi@WX~ZvY>FB9u!#Q_gL1SN-I^Qj_F^Jr@RkIJIipCVU?SAK9DmkqyWF zT=xw1iz(W<@8BaF4IkN(9`^=5GSx8D>YIBP6)wGRpCaEmZKvmMp#Bo|qd3?0lK1kn zcYHs8Bi=dfbXWD>A0m1@yR>l84$l_&&KV%YKNG$#JwLHm{;63F^3P+(v9lrHIn`^V zUJ+zN9PxN@_Pci%`OaxOGIt!USA8|k?Yews{A|J1mCnQ~nR*@7 zpA>lU+&*u++{!B_M6L0Hr5;oDcO&3l#3`e?6G z1>U?=x@x7~FT7@)@?&ZK!skjGVn0_zz!i8P&%gD#+{+g~n&T_kKN~EKR^GET;wzbY z>$FXHuN~dLw0XagrK>w#5FnIG+lQ#ISyM~*Ki^7WvaoUtUzppsfu@@T|l7=8xR{%H-9K+vIh9 z=*-ubE%oG013IrCKl;G)1w|;Ajt%mV{|)a31KVGpJhj2H;xl+xQ(LP$fUbGxCM~=nS#@jO z(y4e?Q-pHq>T+&>yc^Wnxm`TF_v+sbbRIi**yP&Dr_0Zb_pS17pj?5KaBsYSRWhbU z-~7r;-p{G-`c|MCI=Ah0ee#F(=or6_lZ@JP-3{~&!MP8wxh?-CUK-|~xcZj{)e!f= zMJFVe7dDBX!fT)I$h!BbeROWOuiGRSez{@X=)iY!icl_XlXDM`Jt8@4)Gomp?)sOEfHHin~B%`g>w}P<19jfmkpzL@1Z8N9U%&$Ivv3ZaZtor3Id5=tDZ|`Nf61 zve;w$-FwyCN2kS$M)=5OD^Y~fJa@s<49~~n%wO{6vc&~@J;?RuBTEZw.JVoK$ z4j;0`AuHG2wN|8W_Cy=a^9o+W;ZIzWd02Y4sGZ)v$W?!So%9An?}zToXUF0n?)v9~FBE37+ zWhj@nR(k>8>i=s~^NYsNyRcOjhpZZE`$DZ$#x}?Qnfe5%iOLHR%BAvb_N=)biqM*z zD`MXMl6jrA-%WSU5~H*AQC6%Xu~kGao%tq@zn9rTR3yPn%;uHO#OjC-vXNqmjWcN* z+3E;u2TKC2vNc~Fp<1at8*`87i8rrzPx0PbYa#Dy)(ad1qrGLAfOj1Dc+>Ym>v!I9 zY;6-^v|s1DwB0{{cMS+bE5eWYbMWn+lD*ejYw5Ez4O6YM8A@%PLmYB!amb1=S`l8x z*RVYN5`trCGme(bXmTmqxeZ}OKQb#?gRMzbujL`EyZYlS%E#Nv=` z<)|GbmyN8qiHJjvEe=`xJ!nT}wY{a@^u9%fI}wNcDemXCYT1jA%|5c&Ad5X7x%lv+ z#Uwk|75DQ~5QqE#?&mgtI2#n9H96M}_wx&~IAleP9B@SO@GSON(RkbT5vC9BD$lvIm(9#qAP#xIvF&5C zYMi^ZrtDj^*kfC1zIV6A{d_ybA-{(ExgzTS^Pr-|9xK|p3lPP+AL5X^A&OP?RfN{$ z+yS`JKZH2s^KheAgtlDK&OLDUz|tJVA{^3GCi#=8};zjXp@NdK+FUGrptpl#X==p03yJfM*Hpl$D>WFuPNr*%K3hxF1 zVzWyMEwk8TMW=DdC5uD0wau9r2|{ba2>{XRpEiFsKLoQxr62M}--5*+>niZ?22Bx% zoZ#I+tv=481&cinE!^gaB>#2RqxpL=f?C&E4-P17ki{OG?c(gg9#H#^(!moNb9*keUIH+Rxjxm^*5{3N1SH|Vf-agQtx zS?k?=w-!Zl7{aSkYLuh&^A9IOOj!=GSezxbQ_5hunDg zs|raLd;IWT7ZoffnH$qq#ci@UDFM840> z){o~Q4!QN~y~}4q?svM*b$@j3W%x@LArASwJ-5v3ey3|N+-oPpUozs>y7|Z79hp;v zt|&!g?jijBTiy@*3@1J8uk zrPkovwGS;?OtN!_e!NZmF5-}%M+~Iy!fI|3qpMp0? zYdP14%23(P9goQV(TGD%u%Z;9c308PF|vOK;*ifn9J21`s+DT%+%0(LdM-{757 z5o(DPjc)<)&N&`&$PXb7Sy<-35z7?y&Igg2f&W zUv*)@Vv?QvH@*dU6LH9AjUHUm)1>Zw;mNX2y$10B#38S9X0x202X!CRUcie9UM(#S zS?kg<*SX-_dY>MiOh+7Y4)2_bP^}d0+(6t=TW3+lwsLq!)-_?j`TfO8`Yhb_o zQ#j&~OBRQ0C5lkm-|i5HoJbsU>JcQD&LyMyyUzj93jIZ`tc3Q;P6H`ge2dNvKs;P$ zctBEwc!%u1%p1L-y$=9!$jMffamZz@3_%%2dj#T;6N^K(5^|Z}hg|l%M<5P4u{dNa zQH0VS@eVv{zhzOyR&UCc`AErSzk9?KAbws0qAJ?C*6@|Qx(44X5q3lNGVVuw`>-qy z*-FS|H*9j*?;e4e@Dh8N<6$L=P}(EN>Hk#(eo@=Q$z|)mI>KfNOKet>wt4Iknwdhm zY~7K|R+LAWPV@*Xm)Q?;nO&)l(EhRUCzqWpt0S~tMQBaVEyOny%pySTtb{#kCvw(n zzk3<~4N(>C+)J=-D>MJDjX_l|lgHojg#r*8BkusUvJy%+G*9h;p?);DO zHF%w~9hqF#a=$wx4mq(nWV0pdj+4ET5ux(%Wf=CSN!fmGBgI|V=u}4L5%yY5LtcY= zh(n$Rf1>p$TdubkTOX9|+_}hWa0TL!=}%OI-og}}#v$h|4%tSEE!10>Ss#DOxD0s> zW+M)HKKzM_(7U0cojVzM4L(I2a#O@1+dANwD?)3+-5F6~_ahGZIYfo2bgehM4<3ZP z29swDEzN~L(Z+-JL+{bHHvKvANqpnJ)}+Sy!{A%eyT0C1LvPf4L^{nw9P%$0920oe z)F-F+XnbXgxTSiFp386QPb=EcU^K&v2hlY?A&vRDQeubRel~~ic}Nj3bh)9@6Ufk9P(87eH5Yc z6z$yY{2~`|$glm}wxDCK?Fh%?Y(ydLaCnQ-uV*eVDnff#(awE(Xy1Gb#3A=W9I{zU zS^(A1ESx{@{^t7Te?lB`e?%cELffHe=MKkr!o!d1lb?3OprX!E)k?KRR2brxO6T2_ zKO1pNicoK@q7i$()8OL25r_N~;+AyPs#dBkZuE#knt(XueLuausOv*zsBC;2j&G6o zLmYDb+ZF`~^@mU5r=%={_o_}s;MVUJyY=3A{M6~;*ifn9J0QQ z>DpG?h3GbXi#!~0$VZ*Ac$^~C1EpwuKZxj^0f<9>645)_Le*WZ9bWt3BYOruvd^mc z$dpU{WoaC8!Z_rM5QnUGSG7`Yor{rg=@G;s^PSUneeMS8I|=xx2VC z-Z^c3aK};qjLJjAme048cX;R26N~z1?9AYA!k;4F($BB=&wq$_PDQBKNYOX}AbZjm zh(kUTuaIor6p|$6w{+kkxyt?<%3k zYub=G`Mz!Dmf9f>SrO_$UanB9dr$c>zr~{GN{eq%w~j0wg%f}xv`vb}*EM)6x)pClv)Axe z)Cg}y7L)wHycHo1IloyJhpesDdc&3@XHDMXkQJf6X+`7P4F4rko?jyAde#xtUVxt( zUn1>@IOJE(-zKl?L*?lzaPBmGiL@AT$h+bMpa|7U(eT#dyP{(ehkP>jbG-xTJXQ^z z+X>$lZHGAI;VXs(9(t9bvi}#K{^9r%>1)IxzxB!OflptxQf-~P5&3<#M;!7;GcIec zHc{u8+A-(GBfrn_h(m6RceMZ^uNjK|d)^ItBfrnH>n$se+b4}fE=LRK+74~|C&=$J zq+i|A;)!V-av7nkNYTzs?^8RD5Qp5SfB0^o^EI@hr{nvmDTqTp4d)WIwYnx0jaPkS z1hP0})mJsqHw4VYYx|TgL>%&0ILWAVeJcoegQfVQ>I1wqtcR0~B2*Ja zpInSMsZ050K&_Ww%kl<8KaBnEeKIZ3 zvu|Zy9DV`HF=4%oTBeO8m;LS$m0mLVsk8B53FCvg%aLY$Fs-#mNN(IT%cgN@y(+I# z0=>@4bqg{L^XABU`Hd>?YhK1J%PKP{E0?xbdm)s;uY|aRu`X?gwl74e3`Q{X&P=q* zb8h~>?kUGQE0@Z%+2h;MX16OXKSQiC6rnXCLI|F_PqO%S?RV3iqiM8XACmDT&4M0utc@8HD4W} z>qF(KhIl{6i_9B%Bcv>AA@6EdFUP=WZy6AWTw<;XBCOx(ld-i;gwcMTe+I<8H6RSF z2tVc}yks;)W);e?*3xHb8j{OsYMaI(Gaqs_grODTWn}q~({|X5qa`z%T#80+Ls&QD zLyoDH_KD3UB8>L)D$9pl4Pj_Sc&&bdg?lfvi8g=K4wB18*4xBQVBNmW?5_5^w!>&| zsW->{ynFVYu&pTeBC{6mGrn(uIo9~Cb)jyzg3nvq?UMIO$KZbcV3rS=mXotV5n7XT z?QuWPW%qNNaYT$j4&?|KLda^)$`Stp}t4=5|yREGi zKd*Y=e%>&U)-XQ=ED^<+96S_s;?r$~@ou2Afw|&7*fT0J52W>o-v=+kyTJu`H+VP8hfI6L7UDD+ z*lmK&Fu8_p^$ zDKMMvHOPVd#R%e)42-|tvpKHMy? zL4kR4ktyWYW%(=NVd;|PLpH><$bsCY?y>^&ODY->DaePs;(nh^mpL*Jhg@JjWUZGO zRyyu?bAg$4%lVK?mJitws-dEtI~ZP^^)oLH^NDnJwTsNZsr53C!iPsZTwpFm_$=X* zxeGp-?(oT|?i(Tpa;s%06_^`0Y)2hP zkl#TbGqrhr`N%9E^08n4k&d8p^+Ims`kx(A z^doq}i6?`@R$4p{*vpS@%fMqp)+66&LMki-mKYg&4@^5Cgf{n876{yRh0?W?OmlzTO4@cLDwbufgm1diko>U2v~v>>HTf%IAUB=tbG?{!9dn%v@D#xZFbzI{Z{P#a8K-k8v~UCP z`q~1ouZ%<1lkh*019|9zUkbFr;jXp^-Z@V^x=(%y;*fPuRV$%2;adPi_K!n`@p+s1 ze8_fY&~>is5pNTCgIphPkhKT+e8{#tGouIMkc-@-)Dj^ZJKi9l#T(=@yg^#axjs~e zo^bFoipc)w5ZV70;*b@gc308PH9$V(mk`-M`=fF`}{Mkpuav&$cgee|-SCk*7@Cx9Iot9KHpZfNuf5$F~4_n$*27JXv0b$o?3S{gYZY z%jtPg_d)Fi=JK~Rxi19J=*Uc!3fhUvP`#Dq6npZ z+)|bgIlb3fz2wpvZohlPez-x-T!ZJ1YemuMUBqkiFDbDdc0#5MJr&#U{;q~NOUWW10 zTWhm~B{nNb+dTFN$)+1Cm#sT;*^2TA{JlGiluh%haj#{GSqaj%&OJi4(*CjWCzqWp zLj?Z5TAESLTCNDK$+;b2-7J>VO4y@zB4@q!yO;5hd_7<#ics1kK8AmHUgqDmF{sLA z^7uPqKY-x;We->h>oPP?_eOge(pQ1+)yA3i8p6wfPrsZ&+4`L&Hfp48G|LF{gwT2Dxl5c*N-JuOjmA-Kk};bw@56o3e~@th22HmRK*4)?UX~TlLzH_N}i-^E%th zk7}iDa!wP!9~bx@HYI3iqKn_qRaV^ z^Og^pFI8-z-oniK_`v;WE)!|^q#3`=T1dF#X&L_rYI~5BYxNH5iIGWE%t854}g*+VtndTkwthe)z`y$SfbS zc?b2D8hWD`>C`KWbW-1fdhzrgjZ7hkTlyLK6IUT_Nj(M33VYzwOA7S1gtye@FZa)% z+J9teCh{TcJyYeWKLBx-h(dZ4QApF_DN;|0>b?_lBR8wnvfw>M^$}Av5#OKJe$D4Y zHcgZ()Czu|Jp4W-`h8S)m8WRl4ZS3CGlxL=Dt zr3JlwK4e=Ts+DRB|1RQ|#+`Rl=?BCu>8w_7t)k&uLfld}#4Wvme8{?LRV&*KyoEar zQAn>L3hCroJ|D8J50#;^@e+q`k&E~idF8D>AF?5IRw^11DfkxoIed%U%Euw6@eH&w z>K9XOF&_9%cnrQ1e)0Pc(tOC~BhwyLdHDN-_)hp8{=K3nd_H7*QPQ~-zOlUUPVM+$ z{Jo-w-u3yA4WaW@(at5vhujI#J7*($N9)q{q4p6Yi0GXOh~DXj=p999y#d-yLO$eA z5Q}r$AwD0n`N-6hrk*Keu173RU&P{UaiGtKT*_X?bZx8ca;^owMZOQ;A|IROLpFqZ zpcIX0T;xN(0ns}@BMwmuJ$7Kfa!5AHb3ZD{@(m50CEhkVGNBHz-7 zc<0m;i~48m%;0arKfOLRzb*1Dy@Pj7MX1k8(a3d=>`8Ybd(wrK`H)i|nd+|SzvqqR zNaRDl71?^)XZeurjYYk6>Sw~~HOr)P5;Ezi_f+3iLXX#%_)6$2d?oZVz7kS|dQugQ z*?vf`($UDh(<{q|Y`#$Sa)nwA!godM;k%+G*w0mW^*|~bnN^Xk=SO7g;Vao5$cOyr zJxdFGB~#tii-%i0zC`*8Un2d26M!PLO^SBzApf^B^B=C^t%zAqFaCe=R+PhA(SG=L zX=#zC;>;IAmSVI)d5@*qxCNIgc-qhTsIC z>qE!G&e#3~a2WC-uXp|x@vK#i0)%?Z6^#ru_^zmk?}|oZKi4~eddyYBaz5nP@*$gt zUS+7Z|BFvQ!k0)(@g-94k9|I5vsbE>YKvKde8{)s?~I=HR+ls%vc)9o9JAYme^;A} z{61SEzt1ySK4e4a7%2Mhc{jMN{q;$&4VLBB+S}(twrBxe+o5eQBEQea$nVpCn$L%9 z2wg>rc5WQLk7|kUqYfJsz8mO#4XtP`d>?fo-VG)q4q0ujt_elsyKQ6yYH(EF(iNBb ze8{%&|0tgi z*&;;L4(gtW*bjVzbsfIJ+BwUIYzWm|(axQRZ?JB{H(0fEJ|D8}mO38c&e;fGR6U3< zss`aCqb*e3^$h{G9r=)-L}sHc_UjV7X6Sh6IQ>1Z8HhtpzuM}yFpWblpBZ!q(DOq% zA9Bom$htap-67gm4*x zzdN_-q}K7h@ZQlU^A6%4%^UR=WSJ#0+9OUu{iV$Np(WH}J$$=Q>uj_~WciR&8La=K zEDqUdo{%W(qbw%5oDaDgLb;6gGMEO-H%yJGAskQZ^(S%l-x0k zLpGWSa$8I?d&vG(#MZmyx&)pU_8n=)3U|n2lG98G=Ce$*Y+8xdtMZTwsWKBntR?KT zE?Mj`BY)4xVvWT#B%P2`Ae*hfwd!DAF^)J-nH>abRAf|oJ+b20#^4Iu4XcL z3p1KygXkTf-8fx?HU{)r*xJ^0?hzLPfoxN&MUcyC@`x-Sa{69tEu;rB&`@S5GVtSF zt=}&Gg|{XI>$Ts#jNLIquFou-%|7}+mCJtj2`B%qY5!z%N#~VEY>W)b)67z< zt<4bRvYI?1%ZHrymCYsEE47J6d&EH4-G?%}t7BlgvrR^O#2Ltke0~;(Y&L^q&hM+u zufYt4jkB0!=W64A{^btu=ifsdvdty7T+t!oBizp)%i@p~pUvUhy-X+M5JTddUASM;}^Is5$JRSFQ zvt*pRwz|0E@Oy5HNyc3b_w!8=hdcxKb44f@zhp1RB)bO?#kvsLbh{#oRdrW%i1_ic zA^BqvhkP||^omffu;p1k=9;d$TQUor#cRNJ;@w~@;*j6W@*x{Sxh_X;uXmg2Ub0l&jTTC+ls&1`PZ^R)lz`KDWl#Ac7+4&KFxfSmQ zA7p<=QP;MjL&W>Yhx|_SXG;SyOH>n``TY89Mi!HdzcF%k-_m*0hn8BN*}1$sS3Mye ziQLF`XTa$dk>m#i+Yg^!8jmPeX3{W( za;a=&r-T=0|11vqapXg`IArEau-Idj=iC{{hx{hukh{_+Bl>DPHb!pbld_m(+@0ZJ zc>{6CJ>g+t=9ckU95OQ@^v`0CRUUFDES*-`9&yOmAyW1R=k0q z#~==QA>xpGARqEqSse1c$boFJ$GAroCS)!_Y$3N&K2M<;dk2u;V)5ya_K6- zj`P*Z(pJdcy6Ud`^LGB^ey*B?mf<_(L;f6b$h{}`4)#9X6LsAnpC$Yyd*km%b#7eF zhn()Iy4Qwla2)(4P5Rd@wR^9e4>?6BSGb}sL=5Bu$i@2EWvKDzCig-d@*hVw3lPc`YIQ%NCNIYu%g8A{ zAF^qp;~$QBmJd0xe8?PY?on#tbdDj*CSG3~Ar84V;*fRcw9_O{XN{0ez+#edZpS<4 z$B09ok2qxAUlpwu1Gm%{Z_ZtdIOIdN?v!R*urq_MyKtQ!gEzsrT+vV6#fP_EGKzKeXw%MgcL z@qX{%mJ(kIAPS1wg+HfCy8n2eq5LLWlvd?a8=UTJWoH5~;H$*<AJIlJAZ2;s8T(#aC+`T~TysN+0 z8W-zQE~CASLvXJ>vj)$daaBFTJ9h_ekPp=0xzqKbs{lDg(Q4-Tr60sfDBWn@)%3KC zbE5bFjEe~6GTOHz%ZD6z4XPsSChXr*vwXi$gXp)}>rVdl}y%dTxvDeH^lu z7|nXk@8e}m0^)k)uBBGS#k!QsXfFeCoC)GNVu zR)Y1~-tJ`>KYf-qmsn!6kF?Epj}Y%*;1{*ELM~g69?|Zn$~+TVV(Xk-s%@oC)XG{& zE*k^VHW$2%N=(>tMTdxEcWIv=0-Hsoaj_STX1#Vg_cA^N;{F;C%4M`4j~1AP$7cRr z>vxtYm(gBE4v3T1;1MR5)x>ib{%*#y%BW(ii!zKWrN!ol2pa=(+1QY_(Ig$_L)H?T z8RW7V;}L^@D#xBDHCYC7=}M~{Ka6=|Yl2)h9;CH>&i$ufUGvZ<+78t))ar=FW6SxF zRl3RxWmM`_5qP#$UMRy5jKJ0sl^4oDhK<-VY}h(b&vrWIvYN~JkkkFcWN>G(@u1(w zXg{yAe8{UskjrZFh;=XvhpoZu%-z{~!6UMK$f*poC3-?8m;LS$*I_?@VhtW)a@lBl z#2(0pd^!HU+7F0Bwq9h*ZMIXM-l^~fDDoP#MI7=B_!AYOT) z(MFA}HS0rvqTa}mO&56$j(BZQZXW!Jicl`SCzkUX=MUZ(IH|uqQV|V9P;ys z3R6w=KB)5W7pIU9`QL~`9-QSvCWVd|WllaDcPsAa&f^SLh{pyVhZ>i@Z z(y24zkeegpqWTl`zO4Q^M0q1_X%FO2{GM@3;#JdI>cPm3+$@VphKB`FNS*Lk*>}wH zA)8lC@BJ#xg+9`*WUN+z^k@9av(R!Vvn^=@Dw4YXdL2@|A5~|rK?to_J3o2 zX7)GM6`@?}(MjWw2z7rmeIOH>X4oY9b`KrtHq4PM@ zYQIKT#xI|HQ|Yu0dz5sBD_7{P?Xc_MVpqf=_dp!7u3FVF)M^-_kgh@;^2iTwPv7DB z8qSrf@#`gw@_vwhdgYNnn1zp?v#-ek~xliz&a9`vdy#LeL0YbTS9wQ><+CKSX z5r=&0jXoc;y$Puu4A)09@z)&@SyMzDa=VM~PV*s~-Bk@kt#Zh>G%WkO zuX+Mde+lzLnjgiv&yjCw0^*Q6;GNS>_f_xxAp&v8(N$R-vLci#d|jF_u~%sl;*dvT z$FZ{^SCqb5saM3gn~`tnfb8$S+K$W}N9$EzjdQyq-_mV}Ltce^2>PVRD^P=2g$ivmklYMi8$nI@M>wN3EDyB(l-4)Z!CFa>lubPjRl|KEz-2JP~oo>M>Q1m%g_+*Kz2aeEXB<=3hh{vLci#^rY^F+&k?M zhkRp}583>ms+D@bU`yKmnE!6!bNOBI_YG8Evw~ovojuU_)luO&^Tuc8YQvQP~Z$%C8R&;3=d#t|2|K+XdAiNd*h_|8@Yj`VC zdC2>LZR0JRL-+HeFP!Iww}ArAQ>#3AeY(3!8Y z@veq1krv=DBAk%rLuRBC*PwERT1~@uMJ>+1DZlr*dz9=Bz!QLKqH`K=UONxYy^X(b zaL4jtfrnl-3}yV^efnGBOQhQ8ZWm9Vdwby1R}Dk0K0$t;J72G#jGfe_x!OdvT{_$fYpPcf{^94mHmyXTf^KS3}^7{-#9P-qLTjtf)s%_UbkJlyS_t~#s-TWz2 zM&=ZuT)MiPTMO?7yCDvF)5}-?ZlLoRe-Yu`+Hps`8(d!H-9Wk2N+9%$*4Wo-5^}&!>_%qG#M`qV^3WDOM_~NZ0yK7v;c9) zZ;ki)kS!`i_dd0c_Or$|x(tsrdqC}cL8ia6x{ExH7+8M^m{Ti_${ti#$uVAcGr|@}(&=R8?J+^LSHIa7i{na3p%V^5RIdPpj5oE;l7)|N1 zU9RiDSEX7R&3cD!uu<-t>8m0yV=Ex$W(X}Yn(Y|YckA4k5v$TR;hVU1>qKaID#N%~ zmvWgruNAp}tY4>~S`ndKVLQG6;$I)FRSltBM*DWGjry&3Z?3g@?wD(Sk19HiJH)tV zzS_3A(H=2HdRI$yJd9>d@BsjUzDo9JUus$tf?O&)MU;DYVcpGhM~z#RYGwUKgwbBB zFEAc8^{(}m_8Z%T{iD7g^WJV{6Rpb-Ar1J-I9e>Z#F_$GCmCfZsX8@4<|Tnxni zy~mCJy-tWwE|rH{5oY3qKUY5!*>5V(BVJzvf?BDz&UJ!T*PK0W{91LJ##R?sj&YIJ z)rELCAZkw^H-6VD2<1{sgdJye{c=WY8-uDgDn!V5#EMWZm4`^DUwX!G|J1i|Wsfdn zcDUK)&bem09Cd%DyUQKhW9uB{eSEyj-BE9&ly)u$M8lu^rt4fwNDl-Td)I0rjrj^h z=VjFq%4M{-K0qXw{?a#{yY1dy8MUhLS{coHr=Gqtx^5#cFO`v;zRV-E#AvqT>K9f< z2j1e_l(r)|Y(?Mbg`Ey~$+%dra+y4@)gcS}Mr=KM*-D5onp|N!R)2ufE$v>oNqnR5tQJ{@%C1 znZlM^3t6wCjrJ|C4+Q#awFq)qO&-Cz{lAJtOSIllt8d>srJNT>5y}0ee?gE-wZ&hr>za#x zhgPrDX&PHyTocAcT2~ihov+A6M*o-bnT+kBhrW|0{0Qz0~hu?$hcUqa;faHjMVxJ+~wrxgIjKn zHvQ*?k@bC#`jT>u?Rg&t&EEZXmxBYSA=pI?PX9K|F0sRl-v`IxTts9i%;Oc{NL<_-_Wz{71GAd z|Aq+V(mt$2Fdx}PU(Ab+9WX7ei~r^SX1$NqDMhdS>%AIeC_=f&&Hr6ptF5Pvi&k9! zR9eFSZiW9%t`nEtA6?#Z#D7637r9RY%F8$$XNBR}2%fXmZ_)4z=SJ5p8W6ob{`V+) zV@^5-M*H5K1Md1ju@7oOkjsA0#sl2nWOMi0r)Eaqje0p9bJE{~<~YB<^MvT|hQqTl z=bYl)q6|eSm(gAZEL$0&B}P-m9uGbnJuvjnOa^9Qs#QD?AiNCKN=p=> z^Eh1}sm<*R8H!LYozwV>o@g~%p7!oN(d1~S1HMV6-wS$Y&};|Cg=6B^hr=32?^Z)7 zm(kVR!8$32B}TJe9h=l%rE3tYwyALupVH!QaF2;N0OTvczcCYc+WpI)cVkRVzby z8QE@-YNgiFXx3{rc^RuiD3{S*23L~*R}tT_*H_VQM|r!XmMFA7ZRf4BQ$~PLt_4G; zMK=_^C9?YY--=jE6rpwuUT2Y^2<6IeRf=Xdsma1=i6TM^x0%RLgmT?`$5T;*XZ+3( zwnIx4q5BGAQbmR$lxtzVK~b+=ZO2)F*Ju;uJvZ+ytkB+BhBX zWPsZQxSs~#MpDXK5tT4(@c^Cs}ha!|qW&8bu_Jq=InlU%pebq1NIIpwId(kt;e-+Svo$DS| z6M|g!yGN)^T({w%X!4&uQwwM3L~W$VKuRy1;UD@r(TIqO)$ zdCU1rTD5iVl`ZBqWBaSNZ5tDxn|rLvKMMrMg> zQs<3n(b*4F|?a+F4t>~N%+o1^MQhA7h{CwlGRvcrFHD`v- zSG9Kd-r$y-%Cd z%B8X~9w%>IZn@U0tBA9OW94O3_HRX^2<1|FVLP;5UA3Go9INUw6ro%y58qVFEYW(^ zs)d$X+o1^MQhA}D!PX%6C8Mc(xX$NdkE)y9QjLoU}LClK_qupL^j ztw+i*+G_>wgty_?=hmm;LUwVn0z1wX$8GGHjM8 z{nrrWvYI@Ct!C@ryZ^V*TJHwgnxKquCeqJesP%E}W>ou!J8Af}= zEXY_FcaYT~$ffd-E%eVOWt&)&Kan!5cS!>=`OYz{pC=hbD3^`7M|kcO5u1(TSzT`| zdJDrh?s7L!gmT$=jx|+EfL5{I`)nU1mz^0sVtu(AC_=f^I~>Ze^A78>(-LVrmv|YK zn2Nw>ss4a(Ui&4w@$dJm%_YtO@NA_nt7QjL^EwI+H8h4NjWzb$KQ#Lb+6SW#4kl?PS4zXK%8a^JE|rbH8HP1T>p*Fb!?)W3K3=v~J%UD;eM>R?ORGhY z%W9&h*tyPF<2PhBQ9bcS6A`{NL~Auoo~q|9gO=!B&1gS@^p(tqjK_L!-LxhIxlEo% zOab?{nf1|Cq$|~EZ?Dz^H*8jFuWCY&%YOHWTTj?BT_3!$*!h#v%?^?deU?*K#^rgX zB{l{`Snv9Fbo_Ap8WGB+vJnHh-zTPF6^SC0OV8TQU9ex}c&Kexbcj$Hicl`yOOPcEc4X7+ z{$V>ZZHDd0N_*R$d23U=sWMMtcNLmF69+2|+IV-6PQQ*!MA_Ek*?a@p@5ftHu=26nGyy?SOe`mZ6#Wi@%k49H-AQ7h{c%CLE*v`26j zvcFb`AeYtT5fd?jh#^Z`u5-y+OBqI&Wt3kUYC@39elN?28K*|AbPR0vQHIfF8Rd4= zgdmswUY1dAhs{yeYdxxTSw^`XH6h4lzn5i{+hJqNdToX)?GZR-#Jm}?XT57D3q7|roi(t0%J65nrywJOjIqfTFWbIE zgx)#y+?BrY@_wGS!%o7i*G}O?+wWe+XX{QWonL24e(E1>Vm%exNrq_E*15@br<69S zHzhyp&o;4^=$o*fgPq%@-jvc)b*JQ?tb$N3m5p!QQUB+V^B@p<^U{`UkKl`3)IS=C zsZ|ilr7!%>jRp6^K)nHkj-cK-?JU85bM8JM-UH&*DhTD$@yB0F1EL7Tb3kal`buV} z8ZYB=AVvZ)qY6T~R9@OwCG=IEeWms4E18|nyo|dc;}al?RS?Rh@{madh-ZL!1qiKI zU&-v0SzU%AluP9~*BZ0rpBVQZkfHVJEYUd@j)x+YOXXp0qYZmP&J&Pf>wq&{@6LMj zPG#gV<|U4~me`4dt<}{91lrILGA^!yP%f2??^u9X1Q`!hLFnr{&p{TKW5M=v1e zS3xM3YKXrj1jMsIj0QsM)z^1B&-oF&7>HMam{J9yTq@7GcYzoR1m~63tFP}Gm*X5} zdmgjB#M!P0s2ceu5*>42<1|F-Y?3?7w!gX!*y*N?N8zK2-8}fP(O$-aH;&F1GK7|x zcZgg@b5BHGP9P>^2rbd|5zgITfhbndiaU#OsfJ#w6VZ;BYmi|Gu1BN&9`!P0l-AG= z>K-Egh&GJ3{-kZ%S9(6zHW}@;>b~oS@vh&k9ziav$s-ng)HZ%IzhNpv&$Z_3A(zp< zcmErLTvn4uu%9}hzc{b7E~6>K{0v^J7lC*xLuiT791q*u{oLJZ^Xua=B`?ED*zZPj zJi^`ib;!67V?wR0UP?EF%J3sN1Bins9-Y7Pr`}_ECl*?!@(W#8hS48J; zRsJ>uhz>O&gllm|dl~Ef+&4mWzn38;#zh(IzhQrDn6+aeqWbMC2;*X1%4M{d@g;h8 zt9citGPJ~K%HUXx?Ph)TA`rXQfKV=@y^M1(7Q5EpKb4^+MyGv+u}D5$J8Q=fAii9u zI)Wo+Tt<5tr=VxAYE($)m6jMy861n`n_8KS&OoeJ146ls_A>Zw#(OLL*Bn}6G-Yrs zK3nIP?AtyfR{l^Op0j80`>EQXAkoyo`nf%Q=x zAzU0iBD@T&j{?7bVLPX;$>yPt zH@an$yZ^-_6i z=biiU_ZL^X6LE9$_r&^z3j8+ z4)!wC&LhTa=-TDpRfKY>JlGHEE3Nk_j78s{*G=1@c0SZf5z3|V@Dg`u<#=el9E*MD z*7JQOJ3}}giqPFatG>*ZK% z`mWzI)Xs-}r3mFxdHAb{haFdLht|un*s|TCbZx7hcW%E=Mwi>62<1|F$TJ~pQ0wJb zOziemDnspj*bYS~m&ywfS}(_<+mZ9U4A~jd^-*rQBFxTneW<)phStlmplu;S?L7X* z$k4UZ5yZP%tO(^&d7%ugcMFUKZ3|_nov%bth9ZFFdch;KoAyYh3?e9*byE{XhltLXJaK@>Rg~9Y)z*eub&2*Ww_N*5xi-Chc~sf*Inl^6 zf~_MbWvGUsR&_7fd5mdAF4jkcqC-T(W!INSP{&*~47GYhWCRG&o&CoDqwMOvYg(x$ zT2qM760KL;SBc;(;c7DJIKJO9J zJ3n3?K`pTp2f6HoV=^icT4HA{a_KxqCg}6a`H%z4ptgiPzH{4k(>Yz)S8RvYrCgkA z_Z_ibhPY+dzU6tPy{rAEJyI!y<3Y(b=86sx=Ux1Sb-?KauH6h4lzk9^?@Jzg&c_wTpW4&e>l=g_` zK*Vc6kjrZF2zt9FE$v%)_4mt0YrVQt>z?Ryq!7VgR)lid?_NeD-2Z!L9!Rqv)ZJRE zv`6d>#La6!kjrZF2zt97%{(l&CRnevR_VWnAeYtT5li4PxI6QU+S+Elris#j4M8re z$s@MG+3JGKi(^)e^_nJ1d&HLi1wk&W$s^jpk8vhWWgI~}i?CkPL}`zh13w1OajQd+ z%WCq7w|=bj6xrHly{3uMe+@w{tH~oCTwdv|wH=xDnkGvBH3Ye=CXaxxy|hQ>zp{Oa z^_nJ1d&C?dwpjy$Tvn4u+<=+BFIFyl*G`kH*ECW3uOY}~HF-ogtc`!v_dYVSaIDuf zQQ9LO2I8yCM^+PpT=u(1+=8|7d**eva|!D;O_VOnh#@0wc})m%+3y~4Db~g>nO9A1 zt!Y9TMtejXAo^yWyP6Q>vfn*|dO+BV|6QU>0Zb;s%X8braBwAuV zD{`4{$s;!FGSR+qPqf6mL*z0qPIVbtVt$xZM&`xwh#fxLqEd#Gn8$-$qdr(Scl0i` z(l?~aR&gw)cIz*U^s#>Wgwo`{% zRYfS5ogbg})-D@#Im&! z?Kka_O0C!qJKeJ`MTdx9t4=D<5^cF^xO%M=py#il#6SH_N#h3R4dg)YYJ_mmT0|N6XM7|YnzNb zc*BI6sZ~>(Xtdwe{u_c^R@48}*qMM!R#j(vGb6J~3n)$~0!~pQAky8Xkq8=5aYX+Z z!2!h~5vK?!UPgx`zY2&T@sFZ{8i|TFAk@8u$e<#~6hv?UR5S*Z(E(cd*LT+bPQAOT zZg=`R-Dh5$8Mfus<~TQqwJu76CAQT+Jm=%{ zk072G#KM0*V1>ODmtM}7y{lSnTECa!5)rm1XG|&Q1hGZ^wurr4ca0(m9S=Rr=-qGa zwpq6?QLXI7d1ZUe23e?U7z2@VJzFKRXgS@f_QEvSYlgo`9vo)GM>KK=>9>x z{=z@5u$SV}%lWcaH^g}RTS%OJw&mqWNjxe>FM7D^D|@l-By>Dfvtukw@GP<|!jUq^ zx%h6By%dXHwll}gF?u`IzT%2wTX7vJb6gz6@)-oZY-f&`B?HeAuFkdM96%IZ_h8U#nA_9zFcy>+E{qA=}Qsz3QG1?zj2;Z>rY$;P7qc zd@#JpfBsAvqGOZf=c=pvkt0AQQNjiRUYU57*yIT`~a9Gr;>Yjgg)2LO|I`{F+ z@rcbj{q~Na*XNJkX5L!oKCXM*_$8WkI`!`?m&nWgqq^J9TJ4bv{DXItmER!2d?vEx(z#!;L8_R$ zzLPa!q|mw#V$%!PiIEx4T@j{LcN5u;i|&2IQ{=6?33{h=-!^z%RWUcAmNTyH9FLB8T&nz& zu&tVy$Xb0WYIXP(=bZbUc(=$UlV_3XJU`Tq9YXiK#2Zf}xZK(W7Kb-mSW6Jz~RrmZydzX2sm@Dq-2bXzkpeM0&)jg+| zY4xa&XYWdz+Pdd1QCt)1AKN`KuDqt_u{T{*PY zxsPXG>C=o4g|_pR2k)}8OBBm-RV&ib^3>VxR#AJ2aNR}tc#iqf)ew_(>bLJ*bSabIleK%x5B32KCjhx92BVmwkBU@KaUy zoc(5dOj!5aCCcvpQQd9#wHo{`zEgd4dG8q{n9oGEJao^OTKC-bRV>r0iS5i0y65`N zc6Y@gVVgv@!)KJ%M0&AS&XL4#9kNW$ZkE#EhYTY~s* ztfC|smvku`tY#)Eu5)BxEk-b(iL6zbTQ>Yz)at)uO?1iRS!6oTkK^C5YrOdxsJEQ-E{KokTPZJ%tH4L=`%x}YEaoHK zy@Mq!q;B;&e!CYBuc^A{zxeAzhVKtua=oMGe0tn22+* zA=q!ETjC#Yx^eiNs(XIwx(mZ^Rju>q|JxPA1FHu5;>1O-xNNAm$Tc>kTVmTQ&Kc^h zZh5`v&J%|JRJG3UIrK}z2UiXB#fi7?b=pvGdr#8wY$;};b2ZRcL@pF)3w^}uYWz19*(@+)AI81B-nD7kf7ZY{aW(d zub(wMxayv}hVt_9B((BqJyGwvL~%{fPD1@;y}msj_qpNaRrlPqynH-~x{7u=T%x!p zXiwMblc#)ixI@)FH!Uw8pU&YD#Wg`Y3AI|SSIfOx%FDF8d_0M}!drhABPMD2`OnxR&@aa*+7sN4_-NscM~*ZgbF!*OHd_GIEf(WBpGI53gG1q~n`_ah^+s z=FwlfY6Y(>OaJlZLu;L%z4I%E)<7@i12NwF$4Ywl@%Miky-e$>|K3~o9qwN>(0gTy zkyHr{5eBwpqFygjpLa}g84|dIe4XK+{ZlovY`|Vx}GlYL_0_@AL(8# zv>U-AuDW5UH_A268*O*lP&!LG&u!GA7tf;Egg)CQ!CoNU=J1NFns}DT_9`lSal&(Kl5PpFmh$o$CEF|9 zbPf_eKPKtWnRr6!$9%{8{xF=Yy60@uf9?It;RaO$y_7SzKV>)7?Jv<+^m_g)?-=T> zb>;Z`7u+$_`}$d{^B=mF@6{TD`AC;?B2=20ojtn#g;xxv$C^2Ad(pf493)sn(y`se zOk^zf+dnK_7)p&VbBsr1ZbX7{Ntg06Sf(okxA(>X{mF6mOJ-_BT^$2@OD zjQffN!$BjejONjPrmn}bL=Wq6U z`Xrc-bo^TLpU>*QU&8FKIq96CwC)s_=i_+%v@(!jKGLCb@|W?N$XMrWaoSLteagYJ ztIa`zaY>i5SG547M{zj9}k#61ElBMCKsj62;;QXFGGmn0LSKs1u%qZN)W_IjF4aCyk2b z-j(e;;mkp0RT3WaNg9h!+@*S5(*B%xTkRbS?+r+J-!@6NId~7~y`czS2lL*5_faJH z6qt0I!+RXX^1ej2cT1UL%*+kwb<6pG7{0e^o%7j1sJGs;O}D4klT;GSN4kB!>*t0V z13xv=^9vu(XBm9f=MoaMlPLGzw@bEVZp5dK&LM)4#_iVCnO?qri14Z{JMO%Gbz*7n;Zl0Ce-h|2b}xa4MS_7w*`cc&v>0e!lA`@ruPy8hkv7_eK0SMjqv$m+#L+ z+s>6Ce#d06L9}I(a9k4Ej&&o4l+r~sXAbW(@rghwq4z2c(<#DqR}<1@c=t{HJ*W4a z%Fbt&Ug5G<+pYW$kKl-2?p=Agcau2whhyDy63j3d6F*W5oib3b`p%# z<{-gq2I)@sT*}-7vAzmx{oqy9cCK(${dJZY%8vb%u#=1q^p&CQL#7^ZD)?CmBxIEFs-;I zGRLLSYX9e5#~;KRt>XO{}$dC>94ek@d-HhzTU}Xj!+n1eog$9Rxt_Y zBOMp#(2f36s2hJI2;O3C;_MY>c z@V+zto<2cvoJoh?Qg|N{f2AGGSl+!TNBb#RRkU6%MQaj_OS+T?hidkXk>lhb7|Xjb zFO(8W=_4zpldw%9`|9SOykvCg&iMu?_qcrSV>^lcFL=r5 zkN;maHe7?ThXD{_A zug*T6<8f~gcb>O+4$&quN9gsBPKq}Uzj*hNXECm8!ggfK*Ijbx=w*@P*c%Q$i(aIi zL-|Vi>(EDeb5#U->@7bT?p1Zq|FYK4hnH2Yb05#|2(OONH=;?G61wLD>z=zrUUxkC zmf`P0KSObSJadHZ`6`J?I#!=l>*>xY$CcM@Oa3_2`}&IO#O#TOGwa8Vzc;O zxOLARS6-pdFn>zbI`{D;HdzfZNyj$^K6}Z+bE{^J z6JK$CJafcYjJA(4S&W#Z^WBW~Lk~%WE3cn!_=lnN zUKH2IGsl}(Lrl`8gzour>z+HVysq5)e}_^9Qd}R;9Ip=|)~v1_E+IiXiK_D75soXb zV-LJ(cx%-<_wgj&9|}!tR~0Cikf5D}RQ@-t>Pe0(uT#$a$?(>yb?)Oy=$8cEvkGF8 z?#>VWE-hoq{BkHgtjwX>-{&9F%)j%)O zJ@*s(hG1OMZ95o?>-kqUU3*^oec6u4VI7tM3C1N|%DbUS&RAT}Lyvy`sH%b9)`|q< zlGd1ywY(XN>-kHczVW{rzjf6>Z*wp^=iFfQpf2V-%i<_f+z!MLPLd2#Ie;;Po|`k2Etlp2NYY)2@ikD!#^ zx6m|+)Uvp7zis=L|K-?QhEEHf43&7Dm;Lsi-!`-cdZ*Id6ZCRxMfkdsImT@tU)5CN zx_3G1cuW)Y@*I!6?v!K#UuhUOoXZ~@aFC(w}4qtD6?W%!3ZiVI* ziF5A!^H4f6B1n%3ogeI7_7(fEB_2Qc)lkYKic5l#;`iv^a%!*A%$BoOtZgY&X(sWY zf4yrcts3Pc9ZCpGzvyp&4))mZmqRJGOxB9Ejs5N$9@*^x)bb}rJER>mNib3=U%BH@ zf6JmjYeleDtnIk3c%F+;|E#Q9=cHSLwc;FOPqzfUNHbq4TkM}_lv*B2GxJjBQLQ)z z?Yw&6o5w2V^zs!>w68?6+gj1fy8(Ims+~mWp7$e2FYjvP<=saTZ>WUYK`+i%@4J$C zFMdgYUK#^w`pBzYOWYFWAfefJLRBClZGZhc*YqxXfqmE#QH%L4>r5oUaf)xN|0?myK!TClmUGNmE7o>Q zXgo-$e|%*iJtj0BtQBe2u+u&7uOIXx&3v7f#bCpFujW{~-f@Q8&g)>PISkgDL73J| zG?8<+{$gRLJLs#IVsSOFojD#9_s#!XpMH?At+*yKhcqUh_~(2k;}XT<)!BC6j+umM z#Wj&RHi)NPPx*ZQR-@Mp#bV2CXO3w3z`xZjv?r`s|g2ZN)W_ISvekf2)!Bd{!*h%68^h zj4-XZCNjszL+3?jmHNt8VZ~ytZ1*|zyM0rHX~i{>IUXDH_I~wgl&?jK#ah|U9FJdw zFs-;IGROaoGd6x3psSU4kc!1x+0Gmn2Jx^NglWY!kvaZ8X5o(YiI-P6#bT{&XO33| zvBM0)wBnk`90$eu_kjBQoZgox7HefYbA(d*Xk~q}O~SU~n#dgQh*@}D)jjuWsaUL) z?acA=ApDDkBy20LiOiw-q(5=R8Ev%m=Am`ZeJ8{xcd|=);azKYJIgp{NA&WuC3*Q- zRubR4^9cVk(1>1siX$&SHA-TSJI6Wb<>w{x^7EM_{_gq*d4Dyc*NXq%X#Uw%>)cO5 zlE`-JzjF=Y>!7?ykNrh>?<_C&0{gHfyg#2L7^x-L4quT)vxbWk-Y1A4-4d)7$A)cc z3E%xFE(u0z363CZ#rAc2$lk+^NO<3-e5BhP-la~~inVPC<{-^{Ey323V5FAteo(dI z>}%)M_wF3)p3}=uyhQs6o9s3Rz5HxRUVcV4P0-6vapdKvM$-hn{Jcb7em*lz(98E~ z@>=}-AmKYY5v1Fevv=7G?8BDOnWOs;#U;T=Ey0$vR;=yfgl38E=#`IjOX%#>UFu}5 zSlhT`*?Rr%{Lo6R^FYr?CJ9C=Wt08J3j7>%){5;@j?_I@4iY*i^n^wENVn}^tw^({ zTY_GsnXgmkmgaJ|PvlDGbx>C_+p6K>glQ6a9Xvh0zw(HSQ^lOK!Exo~<4JrZh=2ZW zuY2C#5AxhLowd3wh(qGrHQT;?*E3zhxbh+$-w+Do2^Z)0GMHVo=dq7xj@pjynWamV z!vyUlo)-$rU)!zMJ@4asE{U+6#Iu7qdj`QACPc^g^us$ee!E>COE~5}o;jq_Y~6Eu z@yU&kXO6E1v3KOy=EC>v;u6JjTzQc$<+S+z${Eqanvbk9fDJ?E8$v~AJxY$*uoo`3kuuh_-0RAMj1 zWu#L0iwNA~knr)Wm53c;6g3_$VGi0!ghu=*G~!1dK|Sk{muY#aulx)szEiXsVv>&U z!{wMy<c@g zw^=rPUD~DW4Ml5unO04FJZlxY=fj_c;p zbn|7mTzTJ6UOt}0x}oJAIl8{0*XNGjX4yHX-Pg6l$Me4Siw{hN@pqj0=@l+vT-Azn zr(!;M%hJ@@W_H(IgpbQ!J)wN0<4NkKV}^XcdH;OxP};HfB9Y3fp?luHBco`V~G z<9@!QAGqHq*C>xup63{khG1Og>r~7Kp?khmy5|o&rYzh4pSPV?eXrfSEc@8{o6jrm zmk%z>_C9Qz&Q4;l-{&{a=w(_x>f_nFdhU8yd>c@;bBW@bP(Ir|F*@{j`ANeozq@kj z-g8;2%lBQm^nIIeJ})mH9}}T_-kl%xde2u^F5T?|S$7}LzS0xt?f>`a;l^v-w6jYX zSG6Kt%2oG_b+(z^br<2|vg5l3t09z+bbeN}^iSDW*Bnrmh3@&h&Q5!g$eF0#-6uv+ zy-P3mv}oJeSNfi_ROK(Y>#cuHg85A3%Ame_LH%y+_ddLG>3?jnq^lMC&GwjhTvcOt z342#{cVA_#^!?oj#Bbz&a=%|Zl?3yd$d-rhdH+n`^;Im>s)_B)5xVF7Gkp@aNn|_J ztNCYcL@(CLIg+^Y$N%c@^)&>0mvku?9=vSn#eaEfr*y*>lJGcX%in+MvZYrCA(dki zj7z$dFRo@LDz0;6Uxn^@uPW~xDzQx>YxT;5mM#5b)au+=;T&u7EHa(v$5uxyTY5(j z=S>h?aoTfm%ahOY)AND*eR7TRIOTc1{ZV`LpVyLLT;?mKDgt$TIH{cK4J7HFKP*(a z*9~P2y^kTqQ@taZ?`G6Dq&tFMQaRN-OM08b$MdZe6HoliLw9wFVlf}-R%KHfB#Qw;_Tfq(-Q1A(qn&p4?x=HdW&4Kq+qVM zy=6-aUGJbz=O7`KbiETkNsn{HZfUS}Xq&GLjdOWP!CY@*%a#_p-u9l(K|(6&dS82z zjyDdYcb{C}sosCdKAcNP&`v_yZBiIhJETXhw@c+E4SK!7DlZ>Tf{O1hAwhe(R?=11`?~USPs_{4 zlVHnTLV|Wr^zD$&z20Dzmuo05A5Vh1YAzu`dzz4bzTRM!muY$VcoNZ$zE&9Q5J}*AlNo4ieJt z*1P-4LAuRBFJ4Pp;w8vILR#Tc6i^P*rF=hT;uU|lsno{lnLLWtXGToXui%?wBZOeI;k#@V@@D?Gh zc)in|wYmVagaogzq}v?4dNHmv@AYna<_Nv;ekPJ&KGJOtUXdAB+WmURK66}+93+^J zben@$ddAhS3rH&BC95zC9=JW${rK?Oqhh{ z*d#qB^c>EsrM!Gb$@U7@=9naWeoWG(yzyDj=zCXs{d%KZUaXy9Xfq# z<)D|;to6pdyrhe*clVPx_m|K0omWFJAL;m}BxVV-vqzJG48Fo5ee3ibZBy5 zwlfxcTFTba@0-p+f^kWg@)qc~GZsfp%GOfg%N*1sC&9R+OL-OA!C0L6Jk#R6ZJbdg z7?*S@U;Wwrcg`N38%fVz+7GHPS2fP#Ql9&P!+U~WQpT6oglMmJ+46^-{)B#BkzhX3 zrF`f`cR$s&Vs@$FOW#g$c|MNkh~_Q{<|EzBlD-{`B{h7h{3!>|t~Lh=#wFe9(D!R1 zV@VBPdV|WrbG{ux5{yeaegO(+6k~Cv=4#irg9PJ}Zl6r}9MrXl=edvPn1@d4DDDZn zYm`e!&`yH)A0&7_+Rp1Bci|*#E3S#mL1k{2C>GC0+nGbxSzT|{Yb0zdu8GXStFucK zi|3>5%u$~dbva1bR$LRAgM>>Ii>ra{%)!1QVOw!c^f~%x0Ny7k7H5X-%yCcbee|0w z>MIhq71zXc4wonvXQJ)C9sMs(k+7|}CNc+~0k}l5ct+XI9Msb%VOw!cWDd1jtyjxk zqF7uRY)`j?gl)w&G2ITAC>B>Z+tckJVOw!cWRBlMg_h3~-Mfm*`(3ryf96IcJmw-u z+gtz64ZJRCf6lwD_KszUdjk^Qw@uP*4&DQLZz#go!Mr!P3pq&eDKP0ahxa&&<$Z~4 z@0K!$naO9CQsS1zkG%M7pp?Dt-Nx6b<|!xhk#2vX!p{vg27YR!rx8BhKQHNj)50Yr zXiq)M81bp2b97^l=a;3N_xw-vdr^A%`XR!rw(L;6xbT#IXGwzjNV{+KZ#?~|dlB_0 z?*XMQFDUv-PdR0Kh09vK z@ZLc`uju98m6v-riSf*ui_bE~PlTC|bSY1SuCt$oPS%8x#u>DGCE=BNk}hTQnnU-T zeikY(5{%U5AmJ;{Bpu36(7^VyP9Nif(NuVVgweh<5aM6TWv=EZ*bV&Ky*gCt+K0O=J#z zO6Fa-?`svydq#QL&K!#orb%Rut0IS<>uX-IPdqc^Wjk|FlbnQY5`B(dTivrkvDk9k zeUARhNy4_`n&@-%?QkzD7H6XEKF1(F&FETA!nWd?$Q;}Oc*ZFfd)IcKqi+WZ+lp%< zb5J9mW6RlYJ9FsU5AiLCt{o(7E3S#maejDfwr^RUwJYyZ_?eFHeR6+QXM2~!y9t$e zpP)UQ?bH|5uiY$-92ebp{w}^2iQry~_adddH)i62btZaOtXQ`BErP7oR-p*Ie1l6D zjtNy@?u2L6Fl%)|5W7^(WqNV9?43;JIH>9&A09bKFdyko_k8(}L)H3(Ab97+UT9nX zH{pG1{Qb!U;p?kvLOOmMFltreuT+{jg5E!fXzw|H8ZF;Gh?6D=jx*^}o)z9JgZh^s z7|XjCmUm&w(SAzy&B&pae|dsnT+*dHA-wMj z>SIALmUolN(SAzCz9PZ6q~nSlIo654M@J6E;#_KH3Hyo!nud{?ZNd-owbG?zn(eYg1g<_UuNNXNH7!#lLqmmfPp zc)z2#{3O1V#cIWxkS^uAh(8~HS40lR^1e+u_(^=5g9PJ}F6Cb${(kXS=OANw|EV1O zBtEo1!&@zvsyqqCB^|1c;r)*Idvy?u#q*piM*P-qcuTYYstJN|Ntbd-th>HTowc58 z_sVlVpM}TW@IX5Nm&nUcymZa5t>f{H=*Y22tnGh1sOSDa(>{lSiy6;}i!g^t&AHyb?c@_Yx2dv$wF_ChH) zKWVeU<8PcMOq0mI`qdRL8JxFgzJ10$E}#3@UNvD_J#8ZQCDBiV&^_>FcF93i zt;ccY_1n-8);s!&>*JZ@r>h|*=~6bjeXPCXxbl)#yfhOO*T*x*#;YMF>G+M2P-%W( z)x~jKc}as_@3t$hk7tgHgLvpFh)Fu$yblGM2UP_c$CcM_LxWyQ4vOpJnd4uB_U< zoy2eN8NV@dUX3fS>qCQH8ZTWA!YDTA8SaL!^bm6D5Z~nUiFq-LV|V@aej>A{OD$hX{mF6p>S z#reTlUbPih8uU_so6bRkaY>i*$Y+j!7l5(6&MWR8LxWxlm6?O{sv&SyBi)WUV{tu~ z2E7z9`yAu%QzJX$l5TS_mRD`XeNbr7OQAAzjG4Is3C1N|%HWyf^@_2$o=byX>XB~8 zcuge1xTME*(iz2AT+iPY8uU_j>~r)hH3`Ng-JTze#g&>Xcv~wHj7vJ6U&RjN&2`sD z!Znl{h3#y|0YN-`24R{+YFUKtdEatrUrFggC0?~|yBu{ql34bp&-bejy*$U{<++dqRhsGLvrAq+Z<1K+fV2A?^pc*i z6lvu3m&4avw(i&dr?cCZlaOYyRA@wy9uvCOvUk~6?8BCjVwqG(6qf`eb-L$Pb?nbU z5v&z!E6wGd`j)e=q)qOYlP={{s5DD|Oe!stwPJ1KndO7;=*L_o(vF!V7%6@$<&JxI z&i0SbS`n-jYdh{Mp64Q@c`iMiNjmP&?l`oc?W`5&7<;49bC+J6uimL85xVF7 z2+~UmY0@N<*X*@KIY?;sNi|Ib>9*zUUG@TddQ2#X^p!jlNib3=_piSsFxhg}inZ-# zN#Anzl~x0{oV1AXF9}F%$!8R6#oCs#&$f5;b609fUKvO*QYo*z{oZZ_b$)QnSu57I z?JE-MA72?rmvYVRhxX?OYekwh>~zojcF>D7^L5WMMxlE?RQ()F*E`N|+j$+-y;|s= zPZ6dyuT13J-7M~#H?4Z%zIrJZR|DIbLt4n8iQL_DlCZ6~CNhT z`*sYr`|~tmT5(Nej?i=-9a*1Qdd*NQw%m5+ctQ}z%pgoFu8GXCdEEcMt3F}zd7xNq zx$VqxFP`F%u&uZzGDrOO;7GqHs4@5XtXQm-?LNmy+Rl@NX~i{>IYRe*dFY;Z&oaD{ zDHdyGJ9C8Y`SQ>`pCU{vu8GX?so0I}U7x*r|Djl{mF+%9udPnPw&I$|9MmND`K(y1 zmF>(Cy63%q2?^VZYa(;3AG0v@Ub^1(RamiDE8Cf4!$ke5u8GX?oS22X*Jos2 z;S`ItvYk1kV*bDxglWY!kvW1GgzkAa9^RKI7HefYbLc5*=$=mzrWMyj=7{@`QQUuY zE1XwL#bT{&XO7T4ABFDu6k%F%O=OO3u0O%osL}dMZ(e%SDSzse>U<}}CwH=ScKgrV zh+clSBriY9N@9~UKHIk_ve!YBegl$4quT) zvxbWk-Y1A4-4d)7$A)cc3E%xFE(u18@0Z+nc|YbHLDq`xE9K#P|7|}LNqFC;e5Bi2 zd6zm_E7mqtVfXon_lYCsAkBPj4z`vABbD;4dtTPJ!}~$iinEWivXo6R+v(*eUZVYk zO?F!=dimLsy!?zTi5K2=L|-d<`6-UP{M2YV2fh5fL|%SAGfmLT_iFNL&yR6S=0+rZ zM<;^x*k9)$dzZbyK5Pl^=oOa)Beeuu&RVgy@vRrkT@t=`RzA{g4xOF4OP#D0Ya8#F zY<*0BM(I4zlY&Wtk=h&_bJmKrE#;=I*7v=^h=k4wJz-Hk(rpgbiZpw=lsE5v;mnyx zn)!N--)@(|mCWm)u4J}V!%p{n6iVq+glQ6a9hAzg)Na)x&IZSomyaj$!yvBzb`tdB zx$Wawt9J!)@FjaLU-*Q~iF4OO(R|?WV7~ zeTltP;<+Tkb`tA`vhl;7p5K!pVVi{PP8E0*y60UE$5IK$+{ZJ=M?yjQwUwY3pWOI( z=GZ7|bpIe;AG+r*nQRB?R&$v%&a~qCc;*O=?S;@i@7m!K*Lk^hon4~1CTJ&7Rpq-{ag{MGFCSksLODox=itD~++2|v*T*wQD08opP!7`F zY#(^Gdsn1bjw`};=J@ycPSN4t$?q-k%0k+<=u+aW9mH9?@cZM=+1asFVlTyIr1;iD z5YLJ+(aIn~&wVBdAJ1Be*k={QB;EJ!KsmT$VO$^29DftN>lMx=ife*)68!A}65h$k z%eLtF_Ghf1Z>Z|{d~QhEcILP-h{p%<{m?ykES1pHFc*wT%@3HRr;oHogUA4{!_uG8l8tA1Qx_%PsE0)++ zO&lp}_0dHLdf86x&x^P0w7f^kap_^(&cChdp4(R3&u+T;yfx56VIlR~JAx&)buat* zqqmv226`!v*(Gz_{{aV`X)nd4m-A(BX z6vT5cTxX~eoJGjX$CC)%^QXvL_XaFs+_qNfJx$Q7?cIIio$A{|#r#3>P7Yh^u~Exg z;)Ebh-0_^<LNv~yCiQ+q{N4(y5ECY{$&TWs4?3TcIGz7icT1nB` zy62BLrp#OS{J#z^^VT}QZtpU04fIa;d}Q5ome^MBI+E=C{9`V3wpBZOsqXZ$ovV*N zX$WQRZtm{)-Ic=^RNZsiihJe0D~HxV&+m)gyfO)v*jB#xes$&08tAFtzTd6!9QpVo zcD9$|(#!d>R?pn#nBlJV8L~@6*p^q@jvsA3o1mBN>?@7O-Ssn;A0ANVzg~6E?WLJ$ zI|+SOWZiR?xToc1JI`}H2Y+Ua$6I&&_Z71Uc`zB5e2V7<{3A zg2fW|mAq`{IVd&uAH;V?pZAQ@pE`?>7ju`gaVT>~e|2lSTd26CZD-5Bo$B9<67q7S zBydKJSi-n%t$y>675yqof?jR!-u; z_}=Kap>@youl~P#+a=WHA6+%j$NsS|X@~+Z_F+rBCA7_-S9Q-J{M}{7gP=O z#R+=JTmPT$olDK!8t7wxwSxq`7HvmY-jJro8F`C>if>K2zmK<61N5+^)J=$y`g`7OVvHMtsGZ}X0WN7W1O2$tAZ4rx|f1HIRKog(OEJ9AWJypCXrZRPL`mEEa8^)0uTV$sWX zpJSl@QePb(dgPC;y63hPSL32F$sE6qp0zTby%dXHwlfFEL-9qa#J1vcY})a#mk4^< z?sG`Zs%wYFTcs+otsJgxwxjC9O%e36J)J{yM`NuL+ltG4T|4^Twbx{=Ok@r!2x#tT z6jfqdIUFh5u^2%w+nIwc=W1zNahb1OckMMsn&(>w^;aMN*jX&m z6~EUyuh*-5FSX9ZZoMMme4Q7raBa(Z%~0Q{UAiu*4QfkXqc*v5JWEK>tGVtX$=rZf zGL5md&Y7>2UtlJZpciu^Ma)EAUo}^)bDkbgV7@lN1}8Bd z^|=vCNHk~H7>IU|pcmT*APBF{%I;NEwr9z7tw_+z^KF{&%Bd2saI$?yC2_wu@7;eU zOoCoMKa$w-38f!F&0Ebnm1y2t>zuU>rSv^^I6K?lwp?1+);gE6wKdQ~?d=`?8wyQd z(Tlm`my|I}SQDvPTkD)X-6=u$?I1y~wjI0k)Rjz#r?p~?%&r+V{F}X&R4H+Ij>&( zfwg*qC0^C!r5R!k^!U{B#3%IgiUhrwyVE`ITh5yBjM8k;SY@raUXh>|bC+^7)N_wcXuqa2zmK<60DVDDXz~)+DXLo znEsi}EJ9vBo&@hd7}w{ca@bxoLSBxP1l!?QitCkub`sn(%p&CF<9!bOPGh%w^;KVS zJxgf!Ir_WpS%kcNd^!i?diE)Y?dcq|2zmK<5-}bljfu`I$5LFMMYPw9ke4GRQT6n@ z9E|JLKsjtDQFZ7SCFJEuNyM1<s5{RbdFhsynH-~!=Om&r;dutdtCRfj*nL> z?Gs7R%VR!847^57-q-LhEUr=5x07hR7QK(+eV?y`%I7^}-baP*d4DHNf?j+&+_Ze) z{f=UJw*0T&hLF%8E^yi1Y zG*a}kT}SYq`}!RjpES;*r^bB5SYDmw)m{zWcg?3f9t}Y+<{tNL_w=LgKh*E)O>3R= z-moQD;{AhY?@Mw7KmLJ(&q{7?K!RT0)g-ZFJgK$rxt{H+&T1{62-?o^kOJoJ_4)2B zLS8X?R~e$9Q8USi*ZX+c|>qJ0^n->gNWt2zfbQ68e-u zzW}aU@htM4SJywd|170ym@Z0ajdG-1uReVDP5u7L`%h)(n%F+GeA>N(e)q}}kAZ0S zZni`9&p)xk;fXN4n7fpBV-@AoOwz2Or}%iM?ry?n*V z90x%In@=-Iw*+&LpqHQMYDi9c6S3F($#4ifb8&N6enpteJA3GovJ(k;OpB6Ty)67=G=q?AxG*XlD8=_|6<3}1I?=SsagLSBxP1b6zrb61I<6wuD~ zYITIX9BG>1?!|ZU%3*uW2zfbD647!gzIW>`uVlOq+Fmn4UXGN6o{L(O-1p9^yYF#n zCs9@9yIRd6Mu(apqJguHyb z&mm3nuH~FdZmn|I?sG_!d{IJPj+8`vqCe6n`#L{32A+M&VLOSqI!pa~Q9@phl*FY` zBWucfjw-Huly(wTBfe|LEJ9vBo&?9kW2?BH;k1)r%V!bt^6?~MM>bei$AkAAzTeUQ zs`-4U)S1}zm3J20w@Fjf`-j}a=^GZ;N1neb-`>U7B@w*m;JzzVRbnjSyNO*6?}QcC zyKvDyo;m)q!KKT87>d?AhAJ?3#jc5H);8Wm3Ju}&g1A&##rV|QI~nERJ~;GCf_P^T z-<=@n#oX~dnb5!9EYzT-l+HUZwwygu%3CA;HzLpF69m0{)m9Bl`QPw9Bd9Zi;0W?l zGVdjlsA|&-(!eG`FOGkFJ{UPph#aFJ7?+=tc~>)?g9N>puav7I$61l%%*esG{FKbQ zv&_K}Btb9ci#OaNM`%ZPIT)9pl6jXo-3}7;V!l%DjvT|taeB0aaXCvk$9iS%ZahfP zi}_0VOvDc@`sJUA96k>;!+Gz_JMVa>A&8TsW;X=E67M+FTAp2{>=biXTH9ZrAn3*1 zUCS4u<;&G_=HRFA-Us!)yI?hT67*sX;~QJij?YDovm*!N^3!+k=Q2mMVZnOgB;RRt3fa>SBdsKkF&P#D-!f# zzPK}ubyvUQqU#{naGu+?bN9MwU8zN|gipC_=k?=?h`%JLYY+L*&a()4F?al;%4pAp z`!C72=sbUvolie(XO7T4U$E{uOZ;?5Ubb~jEafW~?78s$`raK&cz!sy&YL&~&)aih zt%+Lc%3?3pFl%*m)XMMnF^37owVl_f%R*!O_Ndiy*T3fMS?y5WTjKYx-E6esDBqmq z{+#)2XRSghePpHdS%kcNJc-afA6fUD`&vKik(cf4-B+FclF==1%{M@25%Ti!BtrLm zWZiSdvaK9`&XBcQ8N_`tCYp&Xv90m&wLRzVc|m->zAft#^}B72M|*YNFvk0?n2nP; zOfW}|px(@^y60yxmfNA$x`x?~ts=({7xr9u&+(_8#S-UGTt+ITsx)`C+A*|=t$S`; z-w~Fcur<(2sY=jO1iftM_uDrJwUa}uS`SNXE5{w7Cu|M$_$F}>@0&r;%Xa42FqBB% zT(x&tVp};v_hV=c^io3ie7TjYn0K*MVlU;;SX@&z&_h8vh*yqv&wGMi zwll{aq15xys79r?mJ9B(06`HzT21{%!?$t3CE2{>2cYZ9l zQo6kqi(a-f#~CpeKd36^EU~Q|8jH|qsqGMP=?sEiwlhclU4Z4f8nDE+a(pg&)*9&D z`7wy|V~U`c?aU#S|Mg?dQVy2bRt~Q7ol^Q>gBb+9Y-f(Go_R_CxtjEdt$Qxr;M1$t zIoJ944bW@9;m-{QB2N_pmVXbqn^KD;|pcnIXy61ggF|NkKTIXEnBgc=P+MiJ*=*4_(%NbW= z@t~@8?iD=e?xmZ*reA$X(2M!vmwTTvUauHeV_~gxuJdiJNYIPn_$r67*uexGufz#D4W*T&~*fNmp&GyHKvY6G4Nw>tPsx+%s zY&mP#*6R7ocIsPBf?iUG9=AMn&wE0xlc#!-HEe73@Q0*Iv)Z9JR+}c>663ay&sybR z4cl5RN}%rQH~q~qKMN|&tQBj*`4&oryYJM`U6wE|BgGX5za*fu$=NxtI5y)}OwKD` zeN=Z}?Xn$XX0E?-s>Ih_*}l#vK^1eBc*h|x?{JccGpZkRmUyovFV5pq7GB?fPru*w z$%|`=M(|Np1AW{IwVbi&rMYG`qLyIqvPav#I^^1a>sC0;M5zotpepc_Zi%qcke81qp=UC;Rs9mi^>t7=Y$p+SsiWVm zf{>RZC9!#^KyMLh&^lARekiV6OFN0sJs&{#yx)17ke4GR@rQWA@-Ow7jL!+hb!%xS zaYGRC`)A#giCKiad_0Lq#Z%7x>Qhdi+luR&&`x6eAYQ!+LSBxPMChI`K=-`AgLF-l z!*&t}1QFWKT|2xEPI~!xpF`T}-P1wuMMStJw3DdX>WdQca-<}#TKgDjl6ST8xvjXa z3GF1luo^;Mj@0KETKC*nWW{w&X!ki*Nyy8Ql30jmi7%@v=Dsc|u4_U&iTNP*T?HX8 zM@r(w@kDr+`b5~fNyT+dXeaT~)e!P>q$J)RGd-RmcjMs|PH|lm+G|G0%aM}UD`xug zvF>?)@8p^&hwUU@6~qp!AmqgzPXD`0-I~a?)-_QM+nHncI5+-KpTo@}XujF@_uf*9p163gf(ny^B`-f)N+NX6dx9l?IwUVY#c__cedje|iJ!yBi>t)A z9h&Vd;rZcvwahVQT7q7_)0-yPyX-gi$T)*)<=wqvkzSl&%h{&3R(}iKa}xB@EK$3% z9f$3GVLu)^o8+ky*08PBj$5za&t07pjzzj9e)j5X`ZJ1S&KkD0iX6T-7?Gft&K0d+ z*^W*28>{@YR;&pl>GuuBEoTYiGEzJPxb7u`$2>h%%(<#@O|+d?wOcjLQ0 zgR82Fxl2UYo}4kIEJko%+0K?fEYy1c7^=NGQ(U6BoL9D!prZ9GLS8%GZwhl|k%M36|JaTt3kWmCYD$>7J_{_EKDWIbYW5M;Gq7T*~qyIQwkN%aM|h znsumJPZ9L8t=z4)I?p28ipzYZP+Q$zibXHmnPWwa-g9cpx#HMX4oAv%RF&qg9rjWz zdfCn#p|h=D66gr7&bAfTkut|(1ifr$4t=L6RNuRMXYY^{i#cp3aa<5j`)(4v%9xgy z?X1;xK^zyl=NJ8U<6RkR7M;Y!K|DBSie?G-JGSN3<`A*N41!*^vmJ3pjY3s^pd9KG z%~O@wRu1Otl+tGs^s=2f9vr_5uzpqMc3hQcoV6O!&X#W##QiG4XNacdWjk|(?)gZ% z=W2)J%4-&##9Vw&?c1@+iO{Up$|i!e?Ig|!VzdfEUXGN+)-e__CQ~`+rL)$(5Icn+ zX4Q&bwzIExi`D1$xaz1KE>U)kq({?s5`!Rqy9z>Hj+De>qgEHyc1Wjv-w$rIY{}UV z?0ykJ_Sql&^wRYXSZCSxr`@l!OL-I8L4sbk6)C>)8?*39bp%;rTRE=UeuHKDD?9Wu zf_Ux>f?l>W$1}qF{5soNVq0<52Ib5gA}*Lg(93q_xF-7P)_QejiEYJIpQ%@BJAyc< z{#t>(6pLQAGslV~y7h`Bw%v}`Jml`0qtjW`79;3oJ9DfZYvNY5kL3=5d^4ZIF=7`xo@>;?Y z+ls4x(=5##BD|K^OR?x>J99k$2DGjeR3V&(RVpq;#ny#o-4Hp-9On5 z<&hW9TA%-Yt$OVQmT6?*bGOgo z8LkqKhisoKNw6I(@w}3k+NZNP3ATeJo*DA;IiJLe+HyTlWQk|H3FUW=er4zgmvF|g z*T=2UQ#F=|R8J@_`!IfsZpoJY6EBvq-`FE<4wkSN*uFLgOJuuEtZkcvC9ENH$35UH z@9sZoUa_dKuV3eq?J?o2^DIJMKAwd3C9kf#aK}>J zU;e?3=Ff_2EbTE7JDF~mF^iCwk0()g8Qm_Napm>edT!fZGeTaDlmvHVj^#1P5%Zs6D!_AGVW-yF1O2ZZA5Eke81qu}JA9stke!5{u549z`m+dm`FIi!j+Wn7 z@8})N4o!@j~wz1}xz@(av4&^jX5$*Upmtv8QH<`bRTSEpNvo?hX1~I7`^0?RY%t zq}=;xzsnNU%Du~8FJ;#yTXroM!4mc~`_QA8cSS5=zp+PJf+g$)woiM8$lTL}R?f*WV5E4vKcBD+#JVOrKis>tbGB=RizgF{67q7SBx0A*KTl*_ z*F-sNuNfgPM@nMc_PLSIJH}-@WXIsuM8uWcwU+C8r-(S zYm~fvM#*Ncx9wmFdzyVXCUiH!64~xI_Q;r+>?`&H+t=>fS;984wrviUu!e1|Hp9N1 zCCtZ2rRdjgy_3Zf&IqU?^V)@pT74%MvPJ*Ax%p&CF<4M$+*wu=0HT$$KDu?YP>TF+>ke4I%gm(HJ z;aG~RRl)7B-PcNY6N?h^a-<}9U+Y-Pp;g-BVLOR>kJIItMaav?lh`os3$}@?r$*4R zltZh($KQ4mG3FzW`7AlZc)E=+AX6nMKIU$CKFT8%H_nu+E5}p(7+~t#PmT>m9v*bA3 zf3QUTqnW5)Xvc&11}tHZw&QU(?mt+fTIs5$9PD+CwEwi@!JcLx+FSq54Oqf{V~>mp z-5aoky} z4c5KE_&K%D3Fq+DK)HSO8Mi`vQI>c#Mf(iST8)`(xnp_m%FC-n5`V(Joh6=ECcFlB z`}TgP?=?zZKBHu_*T;2IJ6OV=W*?UFgeAxK-xp;G`;9%)=3oi?hwY2seO>0^Lqd+v8^0Gh-+Yc5>#{4&(*q>!Cs0*FWZ?z&nrc#*H~g(IkaLcTAsB_gZN&( z*4j(4=w&-|aL>RJ+lu?rxc;i|GDm!eWfb46>2?|RQY?De&Ky?-v1R>kElX^>9sAWQ zTq*J0tI@0KzTIAKhrN_rcIJ3owEX9F7tRvf%Ap?7Dv|A2H;9MUU7x)ai(a-fM;-Hl z$HOa*y%bktp%o)@)G?nT=w&-|)S1{3EU~S)8jEvc51%>eY@Z_NWjk{Ou{_R?j$nyx z#nqZSZpUH-y=-R=-m$R6wsM>oV=*2N-WAzPvFK$xbG#?+y#A?accDJii`8}D0?Xuy=-TW&js<5i}Q?PiEXz- zb3k?}Uk~EbaZOjP?4?-BXD{2C9I1WVX&Yt~onAGWXCGxYaSEMc2i+qPCLVGY-;R?Npp`7KsIRdZa;YTFtE z&dUA?{Ydq*mk4^<&hw+Lq8-5!+n!fG3%Z?*R_ZB&BWQc-9PFM`>nu_Uy?j09zHpl-51NuGN literal 0 HcmV?d00001 From 4260ba13458fe4bd77fcf27f2ba340ca43f5ccf6 Mon Sep 17 00:00:00 2001 From: julienthevenoz <125280576+julienthevenoz@users.noreply.github.com> Date: Fri, 2 Feb 2024 16:22:07 +0100 Subject: [PATCH 069/162] Add simulation system tests --- .github/workflows/systemtests_sim.yml | 75 +++++++++ crazyflie/config/motion_capture.yaml | 2 +- .../data/multi_trajectory/traj0.csv | 6 +- systemtests/figure8_ideal_traj.csv | 24 +++ systemtests/mcap_handler.py | 5 +- systemtests/multi_trajectory_traj0_ideal.csv | 52 +++++++ systemtests/plotter_class.py | 146 +++++++++++------- systemtests/test_flights.py | 62 ++++++-- 8 files changed, 294 insertions(+), 78 deletions(-) create mode 100644 .github/workflows/systemtests_sim.yml create mode 100644 systemtests/figure8_ideal_traj.csv create mode 100644 systemtests/multi_trajectory_traj0_ideal.csv diff --git a/.github/workflows/systemtests_sim.yml b/.github/workflows/systemtests_sim.yml new file mode 100644 index 000000000..e30cd8fc7 --- /dev/null +++ b/.github/workflows/systemtests_sim.yml @@ -0,0 +1,75 @@ +name: System Tests Simulation + +on: + push: + branches: [ "main", "feature-systemtests-sim-fixed-timestamp" ] + # manual trigger + workflow_dispatch: + +jobs: + build: + runs-on: self-hosted + steps: + - name: Build firmware + id: step1 + run: | + ls crazyflie-firmware || git clone --recursive https://github.com/bitcraze/crazyflie-firmware.git + cd crazyflie-firmware + git pull + git submodule sync + git submodule update --init --recursive + make cf2_defconfig + make bindings_python + cd build + python3 setup.py install --user + - name: Create workspace + id: step2 + run: | + cd ros2_ws/src || mkdir -p ros2_ws/src + - name: Checkout motion capture package + id: step3 + run: | + cd ros2_ws/src + ls motion_capture_tracking || git clone --branch ros2 --recursive https://github.com/IMRCLab/motion_capture_tracking.git + cd motion_capture_tracking + git pull + git submodule sync + git submodule update --recursive --init + - name: Checkout Crazyswarm2 + id: step4 + uses: actions/checkout@v4 + with: + path: ros2_ws/src/crazyswarm2 + submodules: 'recursive' + - name: Build workspace + id: step5 + run: | + source /opt/ros/humble/setup.bash + cd ros2_ws + colcon build --symlink-install + + - name: Flight test + id: step6 + run: | + cd ros2_ws + source /opt/ros/humble/setup.bash + . install/local_setup.bash + export PYTHONPATH="${PYTHONPATH}:/home/github/actions-runner/_work/crazyswarm2/crazyswarm2/crazyflie-firmware/build/" + export ROS_LOCALHOST_ONLY=1 + export ROS_DOMAIN_ID=99 + python3 src/crazyswarm2/systemtests/test_flights.py --sim -v #-v is verbose argument of unittest + + - name: Upload files + id: step7 + if: '!cancelled()' + uses: actions/upload-artifact@v3 + with: + name: pdf_rosbags_and_logs + path: | + ros2_ws/results + + + + + + diff --git a/crazyflie/config/motion_capture.yaml b/crazyflie/config/motion_capture.yaml index cf5e025c3..c9324ea41 100644 --- a/crazyflie/config/motion_capture.yaml +++ b/crazyflie/config/motion_capture.yaml @@ -1,7 +1,7 @@ /motion_capture_tracking: ros__parameters: type: "optitrack" - hostname: "130.149.82.37" + hostname: "141.23.110.143" mode: "libobjecttracker" # one of motionCapture,libRigidBodyTracker diff --git a/crazyflie_examples/crazyflie_examples/data/multi_trajectory/traj0.csv b/crazyflie_examples/crazyflie_examples/data/multi_trajectory/traj0.csv index 98c33752e..8a257c03e 100644 --- a/crazyflie_examples/crazyflie_examples/data/multi_trajectory/traj0.csv +++ b/crazyflie_examples/crazyflie_examples/data/multi_trajectory/traj0.csv @@ -1,5 +1,5 @@ Duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7 -0.960464,0.294342,0,0,0,-2.11233,4.6768,-3.73784,1.04989,0.172656,0,0,0,3.30457,-7.9007,6.65669,-1.94082,0.069979,0,0,0,-0.297773,0.623628,-0.493335,0.138654,0,0,0,0,0,0,0,0 +0.960464,0.0,0,0,0,-2.11233,4.6768,-3.73784,1.04989,0.0,0,0,0,3.30457,-7.9007,6.65669,-1.94082,0.0,0,0,0,-0.297773,0.623628,-0.493335,0.138654,0,0,0,0,0,0,0,0 1.57331,0.176622,-0.147985,0.0532986,0.0623229,0.343746,-0.500924,0.241338,-0.0403025,0.289553,0.0742267,-0.0522539,-0.0351683,-0.975361,1.50407,-0.788135,0.141456,0.043558,-0.0592408,-0.0401473,-0.00342225,-1.05145,1.64557,-0.878344,0.159958,0,0,0,0,0,0,0,0 1.68226,0.294342,0.17123,-0.0334701,-0.0192207,-0.0992382,0.118149,-0.0472082,0.00658999,0.084993,-0.0345305,0.0714366,0.00548031,0.800464,-1.18606,0.592827,-0.10086,-0.246232,0.00212717,0.0685892,0.0024846,1.23285,-1.76366,0.869779,-0.147011,0,0,0,0,0,0,0,0 1.92896,0.374489,-0.0338637,0.00252255,0.00888171,0.0111398,-0.0108929,0.00298726,-0.000251823,0.276975,-0.0784884,-0.0934159,0.000645144,-1.04135,1.33809,-0.584077,0.0868443,0.183524,0.0937667,-0.0541849,-0.00524925,-0.318377,0.393297,-0.166638,0.0242508,0,0,0,0,0,0,0,0 @@ -29,5 +29,5 @@ Duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1 1.27955,0.296893,-0.0207413,-0.0288722,0.000206756,-1.45292,2.73635,-1.78001,0.396694,0.363893,0.0205828,-0.0396241,-0.00426978,-2.18054,3.96089,-2.52441,0.555328,0.000432,0.116162,-0.0271769,-0.0121203,-0.0967398,0.0511672,0.0231312,-0.0137364,0,0,0,0,0,0,0,0 1.25924,0.129979,-0.0386626,0.0254433,0.00229348,0.314605,-0.568015,0.359101,-0.0786867,0.096373,-0.177655,-0.00188175,0.0162637,-1.43193,2.92354,-2.00733,0.465729,0.019741,-0.0837562,-0.0114419,0.0108961,-0.89746,1.80018,-1.22397,0.282268,0,0,0,0,0,0,0,0 1.35118,0.155486,0.0338914,-0.00270101,-0.0039661,0.202739,-0.374799,0.237823,-0.0512712,-0.106737,0.0769914,0.0704076,-0.0152089,1.54198,-2.90366,1.8396,-0.394692,-0.101778,0.0286494,0.0412961,-0.00329222,1.31264,-2.35215,1.45212,-0.306802,0,0,0,0,0,0,0,0 -1.14424,0.2,0.0015442,-0.00224162,0.00123466,-0.00661606,0.0134679,-0.00982511,0.00245085,0.1,-0.0953098,-0.0830381,0.0218392,-2.55729,5.66335,-4.2252,1.06822,0.1,0.0445589,-0.0317429,-0.000623191,-0.213517,0.427027,-0.293881,0.0698972,0,0,0,0,0,0,0,0 -1.06974,0.2,-7.36408e-05,0.000107209,-5.42089e-05,0.000468972,-0.00106323,0.000841569,-0.000226684,-0.1,0.0736875,0.104178,-0.0410587,3.38468,-7.9737,6.38949,-1.73737,0.1,-0.0104492,0.00871066,0.00133714,0.089598,-0.209747,0.164384,-0.043835,0,0,0,0,0,0,0,0 +1.14424,0.2,0.0015442,-0.00224162,0.00123466,-0.00661606,0.0134679,-0.00982511,0.00245085,0.0,-0.0953098,-0.0830381,0.0218392,-2.55729,5.66335,-4.2252,1.06822,0.1,0.0445589,-0.0317429,-0.000623191,-0.213517,0.427027,-0.293881,0.0698972,0,0,0,0,0,0,0,0 +1.06974,0.0,-7.36408e-05,0.000107209,-5.42089e-05,0.000468972,-0.00106323,0.000841569,-0.000226684,0.0,0.0736875,0.104178,-0.0410587,3.38468,-7.9737,6.38949,-1.73737,0.1,-0.0104492,0.00871066,0.00133714,0.089598,-0.209747,0.164384,-0.043835,0,0,0,0,0,0,0,0 diff --git a/systemtests/figure8_ideal_traj.csv b/systemtests/figure8_ideal_traj.csv new file mode 100644 index 000000000..5b91fc79f --- /dev/null +++ b/systemtests/figure8_ideal_traj.csv @@ -0,0 +1,24 @@ +duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7, + +#### wait on the ground +0.6,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.0,0.000000,0.000000,0.0,0.0,0.0,0.0,0.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000 + +####takeoff +2.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000001,0.000000,0.000000,0.232052,0.184839,0.030911,-0.176192,0.050572,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000 +####hover +3.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.0,0.000000,0.000000,0.0,0.0,0.0,0.0,0.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000 +####figure8 +1.050000,0.000000,-0.000000,0.000000,-0.000000,0.830443,-0.276140,-0.384219,0.180493,-0.000000,0.000000,-0.000000,0.000000,-1.356107,0.688430,0.587426,-0.329106,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000, +0.710000,0.396058,0.918033,0.128965,-0.773546,0.339704,0.034310,-0.026417,-0.030049,-0.445604,-0.684403,0.888433,1.493630,-1.361618,-0.139316,0.158875,0.095799,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000, +0.620000,0.922409,0.405715,-0.582968,-0.092188,-0.114670,0.101046,0.075834,-0.037926,-0.291165,0.967514,0.421451,-1.086348,0.545211,0.030109,-0.050046,-0.068177,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000, +0.700000,0.923174,-0.431533,-0.682975,0.177173,0.319468,-0.043852,-0.111269,0.023166,0.289869,0.724722,-0.512011,-0.209623,-0.218710,0.108797,0.128756,-0.055461,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000, +0.560000,0.405364,-0.834716,0.158939,0.288175,-0.373738,-0.054995,0.036090,0.078627,0.450742,-0.385534,-0.954089,0.128288,0.442620,0.055630,-0.060142,-0.076163,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000, +0.560000,0.001062,-0.646270,-0.012560,-0.324065,0.125327,0.119738,0.034567,-0.063130,0.001593,-1.031457,0.015159,0.820816,-0.152665,-0.130729,-0.045679,0.080444,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000, +0.700000,-0.402804,-0.820508,-0.132914,0.236278,0.235164,-0.053551,-0.088687,0.031253,-0.449354,-0.411507,0.902946,0.185335,-0.239125,-0.041696,0.016857,0.016709,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000, +0.620000,-0.921641,-0.464596,0.661875,0.286582,-0.228921,-0.051987,0.004669,0.038463,-0.292459,0.777682,0.565788,-0.432472,-0.060568,-0.082048,-0.009439,0.041158,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000, +0.710000,-0.923935,0.447832,0.627381,-0.259808,-0.042325,-0.032258,0.001420,0.005294,0.288570,0.873350,-0.515586,-0.730207,-0.026023,0.288755,0.215678,-0.148061,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000, +1.053185,-0.398611,0.850510,-0.144007,-0.485368,-0.079781,0.176330,0.234482,-0.153567,0.447039,-0.532729,-0.855023,0.878509,0.775168,-0.391051,-0.713519,0.391628,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000, +####hover +1.7,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.0,0.000000,0.000000,0.0,0.0,0.0,0.0,0.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000 +####landing +2.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.000001,0.000000,0.000000,-0.232049,-0.184841,-0.030916,0.176196,-0.050573,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000 diff --git a/systemtests/mcap_handler.py b/systemtests/mcap_handler.py index de15911c1..5e55a8784 100644 --- a/systemtests/mcap_handler.py +++ b/systemtests/mcap_handler.py @@ -41,7 +41,9 @@ def write_mcap_to_csv(self, inputbag:str, outputfile:str): f = open(outputfile, 'w+') writer = csv.writer(f) for topic, msg, timestamp in self.read_messages(inputbag): - writer.writerow([timestamp, msg.transforms[0].transform.translation.x, msg.transforms[0].transform.translation.y, msg.transforms[0].transform.translation.z]) + if topic =="/tf": + t = msg.transforms[0].header.stamp.sec + msg.transforms[0].header.stamp.nanosec *10**(-9) + writer.writerow([t, msg.transforms[0].transform.translation.x, msg.transforms[0].transform.translation.y, msg.transforms[0].transform.translation.z]) f.close() except FileNotFoundError: print(f"McapHandler : file {outputfile} not found") @@ -62,3 +64,4 @@ def write_mcap_to_csv(self, inputbag:str, outputfile:str): translator = McapHandler() translator.write_mcap_to_csv(args.inputbag,args.outputfile) + diff --git a/systemtests/multi_trajectory_traj0_ideal.csv b/systemtests/multi_trajectory_traj0_ideal.csv new file mode 100644 index 000000000..5cc458941 --- /dev/null +++ b/systemtests/multi_trajectory_traj0_ideal.csv @@ -0,0 +1,52 @@ +Duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7 + +#wait before takeoff +0.5,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.0,0.000000,0.000000,0.0,0.0,0.0,0.0,0.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000 + + +####takeoff +2.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000001,0.000000,0.000000,0.232052,0.184839,0.030911,-0.176192,0.050572,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000 + +####hover +3.5,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.0,0.000000,0.000000,0.0,0.0,0.0,0.0,0.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000 + +####flying around +0.960464,0.0,0,0,0,-2.11233,4.6768,-3.73784,1.04989,0.0,0,0,0,3.30457,-7.9007,6.65669,-1.94082,1.0,0,0,0,-0.297773,0.623628,-0.493335,0.138654,0,0,0,0,0,0,0,0 +1.57331,0.176622,-0.147985,0.0532986,0.0623229,0.343746,-0.500924,0.241338,-0.0403025,0.289553,0.0742267,-0.0522539,-0.0351683,-0.975361,1.50407,-0.788135,0.141456,1.043558,-0.0592408,-0.0401473,-0.00342225,-1.05145,1.64557,-0.878344,0.159958,0,0,0,0,0,0,0,0 +1.68226,0.294342,0.17123,-0.0334701,-0.0192207,-0.0992382,0.118149,-0.0472082,0.00658999,0.084993,-0.0345305,0.0714366,0.00548031,0.800464,-1.18606,0.592827,-0.10086,0.753768,0.00212717,0.0685892,0.0024846,1.23285,-1.76366,0.869779,-0.147011,0,0,0,0,0,0,0,0 +1.92896,0.374489,-0.0338637,0.00252255,0.00888171,0.0111398,-0.0108929,0.00298726,-0.000251823,0.276975,-0.0784884,-0.0934159,0.000645144,-1.04135,1.33809,-0.584077,0.0868443,1.183524,0.0937667,-0.0541849,-0.00524925,-0.318377,0.393297,-0.166638,0.0242508,0,0,0,0,0,0,0,0 +2.03711,0.374489,0.0286391,-6.1852e-05,-0.00368623,0.00253097,-0.0050055,0.00272644,-0.000441277,-0.358361,0.0262046,0.110055,-0.00620508,0.544041,-0.672761,0.279349,-0.0393627,1.0461,-0.0452504,0.0303272,0.00292994,0.0964916,-0.116635,0.047237,-0.00652766,0,0,0,0,0,0,0,0 +1.08507,0.4,-0.00978883,-0.00352811,0.00421159,-0.147076,0.385891,-0.320935,0.0884478,0.1,-0.0261795,-0.0932209,0.0135473,-3.39392,7.64989,-5.90562,1.55714,1.1,0.0120733,-0.0160302,0.00109914,-0.170679,0.405338,-0.316775,0.0837347,0,0,0,0,0,0,0,0 +1.46341,0.4,0.0345966,0.0216228,0.00040938,0.113468,-0.193811,0.109932,-0.021215,-0.1,-0.00953811,0.0938259,0.00686414,1.78784,-3.00192,1.71647,-0.335021,1.1,0.0162005,0.0183118,0.001431,0.543281,-0.905734,0.51742,-0.101032,0,0,0,0,0,0,0,0 +2.19353,0.492638,0.0469231,-0.0199807,-0.000892996,-0.0338512,0.0362701,-0.0130911,0.00162474,0.203839,-0.0288206,-0.11848,-0.00554452,-0.630569,0.72139,-0.276928,0.0361384,1.209968,0.00986131,-0.0243065,-0.00119445,-0.0998581,0.115095,-0.0441976,0.00576199,0,0,0,0,0,0,0,0 +2.40126,0.48694,-0.00615544,0.0115191,0.000423929,0.00796213,-0.00925373,0.00321793,-0.000373305,-0.469909,0.0557579,0.149918,-0.00106415,0.538482,-0.564538,0.198219,-0.0236403,1.119622,0.0192151,0.028845,-0.000113746,0.115626,-0.12072,0.0423492,-0.00505007,0,0,0,0,0,0,0,0 +2.46094,0.515442,-0.000365976,-0.0122673,2.25527e-05,4.3861e-06,0.00181356,-0.000737567,8.47618e-05,0.463845,-0.0412104,-0.17329,0.000264977,-0.593703,0.60121,-0.20494,0.023781,1.330891,0.000348253,-0.0330759,0.000313802,-0.0979748,0.0999974,-0.0342066,0.00397451,0,0,0,0,0,0,0,0 +2.68427,0.48694,0.00486563,0.0132321,-0.00114426,0.0129524,-0.0144619,0.00482814,-0.000528691,-0.71593,-0.0408684,0.184692,0.00619732,0.442694,-0.405637,0.125531,-0.0132641,1.142929,-0.00451953,0.0270264,-0.00218942,0.0121858,-0.0179685,0.00647746,-0.000732907,0,0,0,0,0,0,0,0 +1.92558,0.505486,-0.0481952,-0.0204291,0.00284946,-0.0470553,0.0773259,-0.0377233,0.00598077,0.718761,0.267399,-0.141554,-0.0117975,-0.800345,0.963882,-0.403221,0.0582575,1.098904,-0.131338,-0.0396354,0.00782912,-0.4965,0.661823,-0.295209,0.0445271,0,0,0,0,0,0,0,0 +2.0699,0.421491,0.0186218,0.0156054,-0.00129697,0.07458,-0.0953844,0.0399616,-0.00562765,0.302142,-0.266958,0.0381168,0.0177516,-0.0552536,0.0911841,-0.0450511,0.00702141,0.771628,0.115857,0.0879918,-0.00554767,0.814447,-0.973674,0.396022,-0.0548837,0,0,0,0,0,0,0,0 +1.9596,0.48694,-0.0304046,-0.0213345,0.00170875,-0.231304,0.295149,-0.127553,0.0187408,0.120541,0.123032,0.0122544,-0.012462,0.149347,-0.218046,0.101473,-0.0155924,1.505486,0.00192474,-0.107286,0.000790515,-1.01863,1.26183,-0.536142,0.0779269,0,0,0,0,0,0,0,0 +1.70183,0.333009,0.0183142,0.028215,-0.00185434,0.43896,-0.63547,0.3139,-0.0528803,0.232223,-0.140993,-0.0449547,0.00936592,-1.12957,1.6455,-0.81818,0.138527,0.832615,-0.101997,0.0790866,0.00096767,0.497639,-0.719611,0.351991,-0.0587304,0,0,0,0,0,0,0,0 +1.34472,0.48694,-0.00625689,-0.0317257,0.000382684,-1.03393,1.83762,-1.13117,0.238966,-0.226478,0.0101228,0.0610516,-0.00764983,1.25229,-2.30188,1.44081,-0.307367,0.917626,-0.033286,-0.0550669,0.00313228,-1.52482,2.7969,-1.74891,0.372958,0,0,0,0,0,0,0,0 +2.1222,0.333009,-0.0545061,0.0199991,0.00480515,0.107972,-0.116334,0.0436145,-0.00566624,-0.072397,-0.0307885,-0.0689067,-0.00236443,-0.48434,0.57055,-0.226496,0.0305878,0.717497,0.028035,0.0816772,0.00612047,0.73381,-0.837942,0.327938,-0.0439369,0,0,0,0,0,0,0,0 +2.22722,0.421491,0.0660872,-0.00287208,-0.00340824,0.062709,-0.0713995,0.0277343,-0.00364623,-0.495874,0.0534612,0.0981472,0.00118253,0.675836,-0.73877,0.276221,-0.03532,1.457563,0.131649,-0.0799577,-0.00792167,-0.366161,0.385528,-0.140404,0.0176255,0,0,0,0,0,0,0,0 +1.85734,0.540865,-0.00634081,-0.00724899,0.00147892,-0.0808568,0.10675,-0.0483186,0.00746342,0.379252,0.132248,-0.0957692,-0.00873243,-1.07307,1.34465,-0.588112,0.0887744,1.038957,-0.200084,0.0246642,0.00970083,-0.25658,0.36452,-0.173423,0.0277121,0,0,0,0,0,0,0,0 +1.69138,0.496281,-0.00160133,0.00618968,0.000136705,0.124512,-0.174729,0.0851269,-0.0142547,-0.1853,-0.289684,0.024136,0.0175717,-0.384504,0.663858,-0.362455,0.0651215,0.81169,0.0702784,0.0295687,-0.00247486,1.21881,-1.70715,0.833757,-0.139995,0,0,0,0,0,0,0,0 +2.19933,0.540865,0.0144117,-0.00391837,-0.00119932,-0.0275664,0.0268387,-0.00940817,0.0011576,-0.385893,0.235345,0.0702187,-0.0148152,0.588274,-0.67496,0.261551,-0.0343838,1.323729,0.185085,-0.00841054,-0.00925475,0.039381,-0.0748132,0.0351087,-0.00510156,0,0,0,0,0,0,0,0 +2.68201,0.500322,-0.0412104,-0.00763103,0.000713901,-0.0520821,0.0470691,-0.0146416,0.00155911,0.387882,-0.0842107,-0.121138,0.00454433,-0.324702,0.302031,-0.0946549,0.0100916,1.366876,-0.264264,-0.0765883,0.0107036,-0.298247,0.281606,-0.0893991,0.00961875,0,0,0,0,0,0,0,0 +2.21932,0.292621,-0.0377479,0.0107761,0.00185615,0.0523879,-0.0498758,0.0171324,-0.002072,-0.664787,-0.0756608,0.114634,0.000204595,0.482644,-0.530616,0.198653,-0.0254146,0.289226,0.0179677,0.111474,-0.00732309,0.507412,-0.56779,0.21534,-0.0277882,0,0,0,0,0,0,0,0 +0.826943,0.365479,0.0796986,0.011073,-0.00345361,6.10559,-17.7498,17.8943,-6.18313,-0.128196,0.0924843,-0.0686475,0.000538459,-0.967377,2.3937,-2.12002,0.661123,0.899606,0.03983,-0.0650002,0.0145722,-1.19604,3.65303,-3.72378,1.2885,0,0,0,0,0,0,0,0 +1.70943,0.515442,0.0778242,-0.0130839,-0.00452718,-0.0331128,0.0135171,0.00336571,-0.00165812,-0.128196,-0.0503162,-0.00225906,0.0131073,0.046757,-0.0481522,0.016617,-0.00196654,0.899606,0.0424298,0.0647269,0.0125499,1.45743,-2.08038,1.01596,-0.169609,0,0,0,0,0,0,0,0 +2.0764,0.515442,-0.0859543,-0.0188315,0.00474201,-0.258721,0.311102,-0.127276,0.0176996,-0.128196,0.0471026,0.00501662,-0.00187713,0.203127,-0.228639,0.0905749,-0.0123697,1.418091,0.0269611,-0.0986299,-0.00460336,-0.709972,0.831305,-0.332664,0.0455369,0,0,0,0,0,0,0,0 +1.34033,0.241704,0.00169625,0.0267376,-0.0040746,0.496448,-0.922,0.581167,-0.124661,0.125962,0.103337,0.00817997,-0.00308402,1.45034,-2.64983,1.66366,-0.356691,0.813306,-0.0951879,0.0808931,0.00400333,1.56751,-2.73421,1.6614,-0.348002,0,0,0,0,0,0,0,0 +1.27955,0.296893,-0.0207413,-0.0288722,0.000206756,-1.45292,2.73635,-1.78001,0.396694,0.363893,0.0205828,-0.0396241,-0.00426978,-2.18054,3.96089,-2.52441,0.555328,1.000432,0.116162,-0.0271769,-0.0121203,-0.0967398,0.0511672,0.0231312,-0.0137364,0,0,0,0,0,0,0,0 +1.25924,0.129979,-0.0386626,0.0254433,0.00229348,0.314605,-0.568015,0.359101,-0.0786867,0.096373,-0.177655,-0.00188175,0.0162637,-1.43193,2.92354,-2.00733,0.465729,1.019741,-0.0837562,-0.0114419,0.0108961,-0.89746,1.80018,-1.22397,0.282268,0,0,0,0,0,0,0,0 +1.35118,0.155486,0.0338914,-0.00270101,-0.0039661,0.202739,-0.374799,0.237823,-0.0512712,-0.106737,0.0769914,0.0704076,-0.0152089,1.54198,-2.90366,1.8396,-0.394692,0.898222,0.0286494,0.0412961,-0.00329222,1.31264,-2.35215,1.45212,-0.306802,0,0,0,0,0,0,0,0 +1.14424,0.2,0.0015442,-0.00224162,0.00123466,-0.00661606,0.0134679,-0.00982511,0.00245085,0.0,-0.0953098,-0.0830381,0.0218392,-2.55729,5.66335,-4.2252,1.06822,1.1,0.0445589,-0.0317429,-0.000623191,-0.213517,0.427027,-0.293881,0.0698972,0,0,0,0,0,0,0,0 +1.06974,0.0,-7.36408e-05,0.000107209,-5.42089e-05,0.000468972,-0.00106323,0.000841569,-0.000226684,0.0,0.0736875,0.104178,-0.0410587,3.38468,-7.9737,6.38949,-1.73737,1.1,-0.0104492,0.00871066,0.00133714,0.089598,-0.209747,0.164384,-0.043835,0,0,0,0,0,0,0,0 + +####hover +2.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.0,0.000000,0.000000,0.0,0.0,0.0,0.0,0.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000 + + +####landing +2.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.000001,0.000000,0.000000,-0.232049,-0.184841,-0.030916,0.176196,-0.050573,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000 diff --git a/systemtests/plotter_class.py b/systemtests/plotter_class.py index 5655aedb6..4b34d461c 100644 --- a/systemtests/plotter_class.py +++ b/systemtests/plotter_class.py @@ -9,8 +9,8 @@ class Plotter: - def __init__(self): - self.params = {'experiment':'1','trajectory':'figure8.csv','motors':'standard motors(CF)', 'propellers':'standard propellers(CF)'} + def __init__(self, sim_backend = False): + self.params = {'experiment':'1','trajectory':'','motors':'standard motors(CF)', 'propellers':'standard propellers(CF)'} self.bag_times = np.empty([0]) self.bag_x = np.empty([0]) self.bag_y = np.empty([0]) @@ -20,13 +20,16 @@ def __init__(self): self.ideal_traj_z = np.empty([0]) self.euclidian_dist = np.empty([0]) self.deviation = [] #list of all indexes where euclidian_distance(ideal - recorded) > EPSILON - - self.EPSILON = 0.05 # euclidian distance in [m] between ideal and recorded trajectory under which the drone has to stay to pass the test - self.DELAY_CONST_FIG8 = 4.75 #this is the delay constant which I found by adding up all the time.sleep() etc in the figure8.py file. This could be implemented better later ? + self.test_name = None + + self.SIM = sim_backend #indicates if we are plotting data from real life test or from a simulated test. Default is false (real life test) + self.EPSILON = 0.1 # euclidian distance in [m] between ideal and recorded trajectory under which the drone has to stay to pass the test (NB : epsilon is doubled for multi_trajectory test) + self.ALLOWED_DEV_POINTS = 0.05 #allowed percentage of datapoints whose deviation > EPSILON while still passing test (currently % for fig8 and 10% for mt) + self.DELAY_CONST_FIG8 = 4.75 #this is the delay constant which I found by adding up all the time.sleep() etc in the figure8.py file. + if self.SIM : #It allows to temporally adjust the ideal and real trajectories on the graph. Could this be implemented in a better (not hardcoded) way ? + self.DELAY_CONST_FIG8 = -0.18 #for an unknown reason, the delay constant with the sim_backend is different self.ALTITUDE_CONST_FIG8 = 1 #this is the altitude given for the takeoff in figure8.py. I should find a better solution than a symbolic constant ? - self.ALTITUDE_CONST_MULTITRAJ = 1 #takeoff altitude for traj0 in multi_trajectory.py - self.X_OFFSET_CONST_MULTITRAJ = -0.3 #offest on the x axis between ideal and real trajectory. Reason: ideal trajectory (traj0.csv) starts with offset of 0.3m and CrazyflieServer.startTrajectory() is relative to start position - + def file_guard(self, pdf_path): msg = None if os.path.exists(pdf_path): @@ -47,22 +50,11 @@ def file_guard(self, pdf_path): def read_csv_and_set_arrays(self, ideal_csvfile, rosbag_csvfile): '''Method that reads the csv data of the ideal test trajectory and of the actual recorded trajectory and initializes the attribute arrays''' - #check which test we are plotting : figure8 or multi_trajectory or another one - if("figure8" in rosbag_csvfile): - fig8, m_t = True, False - print("Plotting fig8 test data") - elif "multi_trajectory" in rosbag_csvfile: - fig8, m_t = False, True - print("Plotting multi_trajectory test data") - else: - fig8, m_t = False, False - print("Plotting unspecified test data") - + #get ideal trajectory data self.ideal_traj_csv = Trajectory() try: path_to_ideal_csv = os.path.join(os.path.dirname(os.path.abspath(__file__)),ideal_csvfile) - print(path_to_ideal_csv) self.ideal_traj_csv.loadcsv(path_to_ideal_csv) except FileNotFoundError: print("Plotter : File not found " + path_to_ideal_csv) @@ -91,9 +83,15 @@ def read_csv_and_set_arrays(self, ideal_csvfile, rosbag_csvfile): no_match_in_idealcsv=[] + delay = 0 + if self.test_name == "fig8": + delay = self.DELAY_CONST_FIG8 + elif self.test_name == "m_t": + delay = self.DELAY_CONST_MT + for i in range(bag_arrays_size): try: - pos = self.ideal_traj_csv.eval(self.bag_times[i] - self.DELAY_CONST_FIG8).pos + pos = self.ideal_traj_csv.eval(self.bag_times[i] - delay).pos except AssertionError: no_match_in_idealcsv.append(i) pos = [0,0,0] #for all recorded datapoints who cannot be matched to a corresponding ideal position we assume the drone is on its ground start position (ie those datapoints are before takeoff or after landing) @@ -101,14 +99,6 @@ def read_csv_and_set_arrays(self, ideal_csvfile, rosbag_csvfile): self.ideal_traj_x[i], self.ideal_traj_y[i], self.ideal_traj_z[i]= pos[0], pos[1], pos[2] - #special cases - if fig8: - self.ideal_traj_z[i] = self.ALTITUDE_CONST_FIG8 #special case: in fig8 no altitude is given in the trajectory polynomials (idealcsv) but is fixed as the takeoff altitude in figure8.py - elif m_t: - self.ideal_traj_z[i] = pos[2] + self.ALTITUDE_CONST_MULTITRAJ #for multi_trajectory the altitude given in the trajectory polynomials is added to the fixed takeoff altitude specified in multi_trajectory.py - self.ideal_traj_x[i] = pos[0] + self.X_OFFSET_CONST_MULTITRAJ #the x-axis is offset by 0.3 m because ideal start position not being (0,0,0) - - self.euclidian_dist[i] = np.linalg.norm([self.ideal_traj_x[i]-self.bag_x[i], self.ideal_traj_y[i]-self.bag_y[i], self.ideal_traj_z[i]-self.bag_z[i]]) if self.euclidian_dist[i] > self.EPSILON: @@ -146,8 +136,7 @@ def no_match_warning(self, unmatched_values:list): def adjust_arrays(self): ''' Method that trims the self.bag_* attributes to get rid of the datapoints where the drone is immobile on the ground and makes self.bag_times start at 0 [s]''' - print(f"rosbag initial length {(self.bag_times[-1]-self.bag_times[0]) * 10**-9}s") - + print(f"rosbag initial length {(self.bag_times[-1]-self.bag_times[0]) }s") #find the takeoff time and landing times ground_level = self.bag_z[0] airborne = False @@ -157,16 +146,16 @@ def adjust_arrays(self): for z_coord in self.bag_z: if not(airborne) and z_coord > ground_level + ground_level*(0.1): #when altitude of the drone is 10% higher than the ground level, it started takeoff takeoff_index = i - takeoff_time = self.bag_times[takeoff_index] airborne = True - print(f"takeof time is {(takeoff_time-self.bag_times[0]) * 10**-9}") - if airborne and z_coord < ground_level + ground_level*(0.1): #find when it lands again + print(f"takeoff time is {self.bag_times[takeoff_index]}s") + if airborne and z_coord <= ground_level + ground_level*(0.1): #find when it lands again landing_index = i - landing_time = self.bag_times[landing_index] - print(f"landing time is {(landing_time-self.bag_times[0]) * 10**-9}") + print(f"landing time is {self.bag_times[landing_index]}s") break i+=1 + + assert (takeoff_index != None) and (landing_index != None), "Plotter : couldn't find drone takeoff or landing" @@ -176,26 +165,44 @@ def adjust_arrays(self): index_arr = np.arange(len(self.bag_times)) slicing_arr = np.delete(index_arr, index_arr[takeoff_index:landing_index+1]) #in our slicing array we take out all the indexes of when the drone is in flight so that it only contains the indexes of when the drone is on the ground - #delete the datapoints where drone is on the ground - self.bag_times = np.delete(self.bag_times, slicing_arr) - self.bag_x = np.delete(self.bag_x, slicing_arr) - self.bag_y = np.delete(self.bag_y, slicing_arr) - self.bag_z = np.delete(self.bag_z, slicing_arr) + # #delete the datapoints where drone is on the ground + # self.bag_times = np.delete(self.bag_times, slicing_arr) + # self.bag_x = np.delete(self.bag_x, slicing_arr) + # self.bag_y = np.delete(self.bag_y, slicing_arr) + # self.bag_z = np.delete(self.bag_z, slicing_arr) assert len(self.bag_times) == len(self.bag_x) == len(self.bag_y) == len(self.bag_z), "Plotter : self.bag_* aren't the same size after trimming" - #rewrite bag_times to start at 0 and be written in [s] instead of [ns] - bag_start_time = self.bag_times[0] - self.bag_times = (self.bag_times-bag_start_time) * (10**-9) - assert self.bag_times[0] == 0 print(f"trimmed bag_times starts: {self.bag_times[0]}s and ends: {self.bag_times[-1]}, size: {len(self.bag_times)}") - def create_figures(self, ideal_csvfile:str, rosbag_csvfile:str, pdfname:str): + def create_figures(self, ideal_csvfile:str, rosbag_csvfile:str, pdfname:str, overwrite=False): '''Method that creates the pdf with the plots''' + #check which test we are plotting : figure8 or multi_trajectory or another one + if("figure8" in rosbag_csvfile): + self.test_name = "fig8" + self.params["trajectory"] = "figure8" + print("Plotting fig8 test data") + elif "multi_trajectory" in rosbag_csvfile: + self.test_name = "mt" + self.params["trajectory"] = "multi_trajectory" + self.EPSILON *= 2 #multi_trajectory test has way more difficulties + self.ALLOWED_DEV_POINTS *= 2 + print("Plotting multi_trajectory test data") + else: + self.test_name = "undefined" + self.params["trajectory"] = "undefined" + print("Plotting unspecified test data") + + self.read_csv_and_set_arrays(ideal_csvfile,rosbag_csvfile) + offset_list = self.find_temporal_offset() + if len(offset_list) == 1: + offset_string = f"temporal offset : {offset_list[0]}s \n" + elif len(offset_list) ==2: + offset_string = f"averaged temporal offset : {(offset_list[0]+offset_list[1])/2}s \n" passed="failed" if self.test_passed(): @@ -206,7 +213,8 @@ def create_figures(self, ideal_csvfile:str, rosbag_csvfile:str, pdfname:str): pdfname= pdfname + '.pdf' #check if user wants to overwrite the report file - self.file_guard(pdfname) + if not overwrite : + self.file_guard(pdfname) pdf_pages = PdfPages(pdfname) #create title page @@ -223,7 +231,7 @@ def create_figures(self, ideal_csvfile:str, rosbag_csvfile:str, pdfname:str): title_text_parameters = f'Parameters:\n' for key, value in self.params.items(): title_text_parameters += f" {key}: {value}\n" - title_text_results = f'Results: test {passed}\n' + f'max error : ' + title_text_results = f'Results: test {passed}\n' + offset_string + f'max error : ' title_text = text + "\n" + title_text_settings + "\n" + title_text_parameters + "\n" + title_text_results fig = plt.figure(figsize=(5,8)) @@ -321,18 +329,41 @@ def create_figures(self, ideal_csvfile:str, rosbag_csvfile:str, pdfname:str): print("Results saved in " + pdfname) def test_passed(self) -> bool : - '''Returns True if the deviation between recorded and ideal trajectories of the drone always stayed lower - than EPSILON. Returns False otherwise ''' + '''Returns True if the deviation between recorded and ideal trajectories of the drone didn't exceed EPSILON for more than ALLOWED_DEV_POINTS % of datapoints. + Returns False otherwise ''' nb_dev_points = len(self.deviation) + threshold = self.ALLOWED_DEV_POINTS * len(self.bag_times) + percentage = (len(self.deviation) / len(self.bag_times)) * 100 - if nb_dev_points == 0: - print("Test passed") + if nb_dev_points < threshold: + print(f"Test {self.test_name} passed : {percentage:8.4f}% of datapoints had deviation larger than {self.EPSILON}m ({self.ALLOWED_DEV_POINTS * 100}% max for pass)") return True else: - print(f"The deviation between ideal and recorded trajectories is greater than {self.EPSILON}m for {nb_dev_points} " - f"datapoints, which corresponds to a duration of {nb_dev_points*0.01}s") + print(f"Test {self.test_name} failed : The deviation between ideal and recorded trajectories is greater than {self.EPSILON}m for {percentage:8.4f}% of datapoints") return False + + def find_temporal_offset(self) -> list : + ''' Returns a list containing the on-graph temporal offset between real and ideal trajectory. If offset is different for x and y axis, returns both in the same list''' + peak_x = self.bag_x.argmax() #find index of extremum value of real trajectory along x axis + peak_time_x = self.bag_times[peak_x] #find corresponding time + peak_x_ideal = self.ideal_traj_x.argmax() #find index of extremum value of ideal traj along x axis + peak_time_x_ideal = self.bag_times[peak_x_ideal] #find corresponding time + offset_x = peak_time_x_ideal - peak_time_x + + peak_y = self.bag_y.argmax() #find index of extremum value of real trajectory along y ayis + peak_time_y = self.bag_times[peak_y] #find corresponding time + peak_y_ideal = self.ideal_traj_y.argmax() #find index of extremum value of ideal traj along y ayis + peak_time_y_ideal = self.bag_times[peak_y_ideal] #find corresponding time + offset_y = peak_time_y_ideal - peak_time_y + + if offset_x == offset_y: + print(f"On-graph temporal offset is {offset_x}s, delay const is {self.DELAY_CONST_FIG8} so uncorrected/absolute offset is {offset_x-self.DELAY_CONST_FIG8}") + return [offset_x] + else : + print(f"On-graph temporal offsets are {offset_x} & {offset_y} secs, delay const is {self.DELAY_CONST_FIG8}") + return [offset_x, offset_y] + if __name__=="__main__": @@ -344,12 +375,13 @@ def test_passed(self) -> bool : parser.add_argument("recorded_trajectory", type=str, help=".csv file containing (time,x,y,z) of the recorded drone trajectory") parser.add_argument("pdf", type=str, help="name of the pdf file you want to create/overwrite") parser.add_argument("--open", help="Open the pdf directly after it is created", action="store_true") + parser.add_argument("--overwrite", action="store_true", help="If the given pdf already exists, overwrites it without asking") args : Namespace = parser.parse_args() plotter = Plotter() - plotter.create_figures(args.desired_trajectory, args.recorded_trajectory, args.pdf) + plotter.create_figures(args.desired_trajectory, args.recorded_trajectory, args.pdf, overwrite=args.overwrite) if args.open: import subprocess subprocess.call(["xdg-open", args.pdf]) - - + + diff --git a/systemtests/test_flights.py b/systemtests/test_flights.py index cfd84f1c1..8f7c20d10 100644 --- a/systemtests/test_flights.py +++ b/systemtests/test_flights.py @@ -9,6 +9,7 @@ import time import signal import atexit +from argparse import ArgumentParser, Namespace ############################# @@ -30,7 +31,7 @@ def clean_process(process:Popen) -> int : '''Kills process and its children on exit if they aren't already terminated (called with atexit). Returns 0 on termination, 1 if SIGKILL was needed''' if process.poll() == None: group_id = os.getpgid(process.pid) - print(f"cleaning process {group_id}") + #print(f"cleaning process {group_id}") os.killpg(group_id, signal.SIGTERM) time.sleep(0.01) #necessary delay before first poll i=0 @@ -44,9 +45,21 @@ def clean_process(process:Popen) -> int : return 0 else: return 0 #process already terminated + +def print_PIPE(process : Popen, process_name, always=False): + '''If process creates some error, prints the stderr and stdout PIPE of the process. NB : stderr and stdout must = PIPE in the Popen constructor''' + if process.returncode != 0 or always: + out, err = process.communicate() + print(f"{process_name} returncode = {process.returncode}") + print(f"{process_name} stderr : {err}") + print(f"{process_name} stdout : {out}") + else: + print(f"{process_name} completed sucessfully") + class TestFlights(unittest.TestCase): + SIM = False def __init__(self, methodName: str = "runTest") -> None: super().__init__(methodName) @@ -65,17 +78,21 @@ def setUp(self): self.test_file = None # launch server + current_env = None src = "source " + str(Path(__file__).parents[3] / "install/setup.bash") # -> "source /home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/install/setup.bash" command = f"{src} && ros2 launch crazyflie launch.py" - self.launch_crazyswarm = Popen(command, shell=True, stderr=True, stdout=PIPE, text=True, - start_new_session=True, executable="/bin/bash") + if TestFlights.SIM : + command += " backend:=sim" #launch crazyswarm from simulation backend + current_env = os.environ.copy() + self.launch_crazyswarm = Popen(command, shell=True, stderr=PIPE, stdout=PIPE, text=True, + start_new_session=True, executable="/bin/bash", env=current_env) atexit.register(clean_process, self.launch_crazyswarm) #atexit helps us to make sure processes are cleaned even if script exits unexpectedly time.sleep(1) - # runs once per test_ function def tearDown(self) -> None: clean_process(self.launch_crazyswarm) #kill crazyswarm_server and all of its child processes + print_PIPE(self.launch_crazyswarm, "launch_crazyswarm") # copy .ros/log files to results folder if Path(Path.home() / ".ros/log").exists(): @@ -92,19 +109,26 @@ def record_start_and_clean(self, testname:str, max_wait:int): src = f"source {str(self.ros2_ws)}/install/setup.bash" try: - command = f"{src} && ros2 bag record -s mcap -o test_{testname} /tf" + command = f"{src} && ros2 bag record -s mcap -o test_{testname} /tf" record_bag = Popen(command, shell=True, stderr=PIPE, stdout=True, text=True, cwd= self.ros2_ws / "results/", start_new_session=True, executable="/bin/bash") atexit.register(clean_process, record_bag) command = f"{src} && ros2 run crazyflie_examples {testname}" + if TestFlights.SIM: + command += " --ros-args -p use_sim_time:=True" #necessary args to start the test in simulation start_flight_test = Popen(command, shell=True, stderr=True, stdout=True, start_new_session=True, text=True, executable="/bin/bash") atexit.register(clean_process, start_flight_test) - start_flight_test.wait(timeout=max_wait) #raise Timeoutexpired after max_wait seconds if start_flight_test didn't finish by itself + if TestFlights.SIM : + start_flight_test.wait(timeout=max_wait*5) #simulation can be super slow + else : + start_flight_test.wait(timeout=max_wait) #raise Timeoutexpired after max_wait seconds if start_flight_test didn't finish by itself + clean_process(start_flight_test) clean_process(record_bag) + print("finished the test") except TimeoutExpired: #if max_wait is exceeded clean_process(start_flight_test) @@ -113,14 +137,12 @@ def record_start_and_clean(self, testname:str, max_wait:int): except KeyboardInterrupt: #if drone crashes, user can ^C to skip the waiting clean_process(start_flight_test) clean_process(record_bag) - + #if something went wrong with the bash command lines in Popen, print the error - if record_bag.stderr != None: - print(testname," record_bag stderr: ", record_bag.stderr.readlines()) - if start_flight_test.stderr != None: - print(testname," start_flight flight stderr: ", start_flight_test.stderr.readlines()) - + print_PIPE(record_bag, f"record_bag for {self.idFolderName()}") + print_PIPE(start_flight_test, f"start_flight_test for {self.idFolderName()}") + def translate_plot_and_check(self, testname:str) -> bool : '''Translates rosbag .mcap format to .csv, then uses that csv to plot a pdf. Checks the deviation between ideal and real trajectories, i.e if the drone successfully followed its given trajectory. Returns True if deviation < epsilon(defined in plotter_class.py) at every timestep, false if not. ''' @@ -134,14 +156,14 @@ def translate_plot_and_check(self, testname:str) -> bool : output_pdf = f"{str(self.ros2_ws)}/results/test_{testname}/results_{testname}.pdf" rosbag_csv = output_csv - plotter = Plotter() + plotter = Plotter(sim_backend=TestFlights.SIM) plotter.create_figures(self.test_file, rosbag_csv, output_pdf) #plot the data return plotter.test_passed() def test_figure8(self): - self.test_file = "../crazyflie_examples/crazyflie_examples/data/figure8.csv" + self.test_file = "figure8_ideal_traj.csv" # run test self.record_start_and_clean("figure8", 20) #create the plot etc @@ -149,7 +171,7 @@ def test_figure8(self): assert test_passed, "figure8 test failed : deviation larger than epsilon" def test_multi_trajectory(self): - self.test_file = "../crazyflie_examples/crazyflie_examples/data/multi_trajectory/traj0.csv" + self.test_file = "multi_trajectory_traj0_ideal.csv" self.record_start_and_clean("multi_trajectory", 80) test_passed = self.translate_plot_and_check("multi_trajectory") assert test_passed, "multitrajectory test failed : deviation larger than epsilon" @@ -158,5 +180,13 @@ def test_multi_trajectory(self): if __name__ == '__main__': - unittest.main() + from argparse import ArgumentParser + import sys + parser = ArgumentParser(description="Runs (real or simulated) flight tests with pytest framework") + parser.add_argument("--sim", action="store_true", help="Runs the test from the simulation backend") + args, other_args = parser.parse_known_args() + if args.sim : + TestFlights.SIM = True + + unittest.main(argv=[sys.argv[0]] + other_args) From d468687aeb891faa2830f1c7cd29638716c5793b Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Sat, 3 Feb 2024 22:29:11 +0100 Subject: [PATCH 070/162] server [cflib]: add Status topic --- crazyflie/scripts/crazyflie_server.py | 27 +++++++++++++++++++++++---- 1 file changed, 23 insertions(+), 4 deletions(-) diff --git a/crazyflie/scripts/crazyflie_server.py b/crazyflie/scripts/crazyflie_server.py index fbbe8fe72..4ba4dcf4a 100755 --- a/crazyflie/scripts/crazyflie_server.py +++ b/crazyflie/scripts/crazyflie_server.py @@ -26,7 +26,7 @@ from crazyflie_interfaces.srv import Takeoff, Land, GoTo, RemoveLogging, AddLogging from crazyflie_interfaces.srv import UploadTrajectory, StartTrajectory, NotifySetpointsStop from rcl_interfaces.msg import ParameterDescriptor, SetParametersResult, ParameterType -from crazyflie_interfaces.msg import Hover, LogDataGeneric, FullState +from crazyflie_interfaces.msg import Status, Hover, LogDataGeneric, FullState from motion_capture_tracking_interfaces.msg import NamedPoseArray from std_srvs.srv import Empty @@ -74,17 +74,21 @@ def __init__(self): # Assign default topic types, variables and callbacks self.default_log_type = {"pose": PoseStamped, "scan": LaserScan, - "odom": Odometry} + "odom": Odometry, + "status": Status} self.default_log_vars = {"pose": ['stateEstimate.x', 'stateEstimate.y', 'stateEstimate.z', 'stabilizer.roll', 'stabilizer.pitch', 'stabilizer.yaw'], "scan": ['range.front', 'range.left', 'range.back', 'range.right'], "odom": ['stateEstimate.x', 'stateEstimate.y', 'stateEstimate.z', 'stabilizer.yaw', 'stabilizer.roll', 'stabilizer.pitch', 'kalman.statePX', 'kalman.statePY', 'kalman.statePZ', - 'gyro.z', 'gyro.x', 'gyro.y']} + 'gyro.z', 'gyro.x', 'gyro.y'], + "status": ['supervisor.info', 'pm.vbatMV', 'pm.state', + 'radio.rssi']} self.default_log_fnc = {"pose": self._log_pose_data_callback, "scan": self._log_scan_data_callback, - "odom": self._log_odom_data_callback} + "odom": self._log_odom_data_callback, + "status": self._log_status_data_callback} self.world_tf_name = "world" try: @@ -569,6 +573,21 @@ def _log_odom_data_callback(self, timestamp, data, logconf, uri): t_base.transform.rotation.w = q[3] self.tfbr.sendTransform(t_base) + def _log_status_data_callback(self, timestamp, data, logconf, uri): + """ + Send out the ROS 2 status topic + """ + + msg = Status() + msg.header.stamp = self.get_clock().now().to_msg() + msg.header.frame_id = self.world_tf_name + msg.supervisor_info = data.get('supervisor.info') + msg.battery_voltage = data.get('pm.vbatMV') / 1000.0 + msg.pm_state = data.get('pm.state') + msg.rssi = data.get('radio.rssi') + + self.swarm._cfs[uri].logging["status_publisher"].publish(msg) + def _log_custom_data_callback(self, timestamp, data, logconf, uri): """ Once custom log block is retrieved from the Crazyflie, From efeffb2a70998bb19136e741ca45c7ca4c575b3e Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Sat, 3 Feb 2024 22:29:36 +0100 Subject: [PATCH 071/162] Status topic: fix incorrect constant for can_be_armed --- crazyflie_interfaces/msg/Status.msg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/crazyflie_interfaces/msg/Status.msg b/crazyflie_interfaces/msg/Status.msg index bebd42a71..d7c2f2352 100644 --- a/crazyflie_interfaces/msg/Status.msg +++ b/crazyflie_interfaces/msg/Status.msg @@ -1,6 +1,6 @@ # Constants -uint16 SUPERVISOR_INFO_CAN_BE_ARMED = 0 +uint16 SUPERVISOR_INFO_CAN_BE_ARMED = 1 uint16 SUPERVISOR_INFO_IS_ARMED = 2 uint16 SUPERVISOR_INFO_AUTO_ARM = 4 uint16 SUPERVISOR_INFO_CAN_FLY = 8 From bcfa55372911b25f28b0f1cfc42bfa5106ed6b94 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Sat, 3 Feb 2024 22:30:15 +0100 Subject: [PATCH 072/162] server [sim]: unify naming convention for logging --- .../crazyflie_sim/crazyflie_server.py | 18 ++++++++++-------- 1 file changed, 10 insertions(+), 8 deletions(-) diff --git a/crazyflie_sim/crazyflie_sim/crazyflie_server.py b/crazyflie_sim/crazyflie_sim/crazyflie_server.py index 13bf4ae2e..8050737b4 100755 --- a/crazyflie_sim/crazyflie_sim/crazyflie_server.py +++ b/crazyflie_sim/crazyflie_sim/crazyflie_server.py @@ -210,7 +210,7 @@ def _param_to_dict(self, param_ros): return tree def _emergency_callback(self, request, response, name='all'): - self.get_logger().info('emergency not yet implemented') + self.get_logger().info(f'[{name}] emergency not yet implemented') return response @@ -219,9 +219,9 @@ def _takeoff_callback(self, request, response, name='all'): duration = float(request.duration.sec) + \ float(request.duration.nanosec / 1e9) self.get_logger().info( - f'takeoff(height={request.height} m,' + f'[{name}] takeoff(height={request.height} m,' + f'duration={duration} s,' - + f'group_mask={request.group_mask}) {name}' + + f'group_mask={request.group_mask})' ) cfs = self.cfs if name == 'all' else {name: self.cfs[name]} for _, cf in cfs.items(): @@ -234,7 +234,7 @@ def _land_callback(self, request, response, name='all'): duration = float(request.duration.sec) + \ float(request.duration.nanosec / 1e9) self.get_logger().info( - f'land(height={request.height} m,' + f'[{name}] land(height={request.height} m,' + f'duration={duration} s,' + f'group_mask={request.group_mask})' ) @@ -250,8 +250,9 @@ def _go_to_callback(self, request, response, name='all'): float(request.duration.nanosec / 1e9) self.get_logger().info( - 'go_to(position=%f,%f,%f m, yaw=%f rad, duration=%f s, relative=%d, group_mask=%d)' + '[%s] go_to(position=%f,%f,%f m, yaw=%f rad, duration=%f s, relative=%d, group_mask=%d)' % ( + name, request.goal.x, request.goal.y, request.goal.z, @@ -269,11 +270,11 @@ def _go_to_callback(self, request, response, name='all'): return response def _notify_setpoints_stop_callback(self, request, response, name='all'): - self.get_logger().info('Notify setpoint stop not yet implemented') + self.get_logger().info(f'[{name}] Notify setpoint stop not yet implemented') return response def _upload_trajectory_callback(self, request, response, name='all'): - self.get_logger().info('Upload trajectory(id=%d)' % (request.trajectory_id)) + self.get_logger().info('[%s] Upload trajectory(id=%d)' % (name, request.trajectory_id)) cfs = self.cfs if name == 'all' else {name: self.cfs[name]} for _, cf in cfs.items(): @@ -297,8 +298,9 @@ def _upload_trajectory_callback(self, request, response, name='all'): def _start_trajectory_callback(self, request, response, name='all'): self.get_logger().info( - 'start_trajectory(id=%d, timescale=%f, reverse=%d, relative=%d, group_mask=%d)' + '[%s] start_trajectory(id=%d, timescale=%f, reverse=%d, relative=%d, group_mask=%d)' % ( + name, request.trajectory_id, request.timescale, request.reversed, From 8db6586d157ba8bbbddd7483b1cab19dcd7faf7e Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Sat, 3 Feb 2024 22:32:27 +0100 Subject: [PATCH 073/162] server [cpp]: switch to the node logger so that logs are published via /rosout on humble --- crazyflie/src/crazyflie_server.cpp | 100 +++++++++++++++++------------ 1 file changed, 58 insertions(+), 42 deletions(-) diff --git a/crazyflie/src/crazyflie_server.cpp b/crazyflie/src/crazyflie_server.cpp index 4a71e0245..b4e7e65ea 100644 --- a/crazyflie/src/crazyflie_server.cpp +++ b/crazyflie/src/crazyflie_server.cpp @@ -39,13 +39,19 @@ using std_srvs::srv::Empty; using motion_capture_tracking_interfaces::msg::NamedPoseArray; using crazyflie_interfaces::msg::FullState; +// Note on logging: we use a single logger with string prefixes +// A better way would be to use named child loggers, but these do not +// report to /rosout in humble, see https://github.com/ros2/rclpy/issues/1131 +// Once we do not support humble anymore, consider switching to child loggers + // Helper class to convert crazyflie_cpp logging messages to ROS logging messages class CrazyflieLogger : public Logger { public: - CrazyflieLogger(rclcpp::Logger logger) + CrazyflieLogger(rclcpp::Logger logger, const std::string& prefix) : Logger() , logger_(logger) + , prefix_(prefix) { } @@ -53,20 +59,21 @@ class CrazyflieLogger : public Logger virtual void info(const std::string &msg) { - RCLCPP_INFO(logger_, "%s", msg.c_str()); + RCLCPP_INFO(logger_, "%s %s", prefix_.c_str(), msg.c_str()); } virtual void warning(const std::string &msg) { - RCLCPP_WARN(logger_, "%s", msg.c_str()); + RCLCPP_WARN(logger_, "%s %s", prefix_.c_str(), msg.c_str()); } virtual void error(const std::string &msg) { - RCLCPP_ERROR(logger_, "%s", msg.c_str()); + RCLCPP_ERROR(logger_, "%s %s", prefix_.c_str(), msg.c_str()); } private: rclcpp::Logger logger_; + std::string prefix_; }; std::set extract_names( @@ -129,8 +136,8 @@ class CrazyflieROS rclcpp::CallbackGroup::SharedPtr callback_group_cf_srv, const CrazyflieBroadcaster* cfbc, bool enable_parameters = true) - : logger_(rclcpp::get_logger(name)) - , cf_logger_(logger_) + : logger_(node->get_logger()) + , cf_logger_(logger_, "[" + name + "]") , cf_( link_uri, cf_logger_, @@ -228,7 +235,7 @@ class CrazyflieROS bool query_all_values_on_connect = node->get_parameter("firmware_params.query_all_values_on_connect").get_parameter_value().get(); int numParams = 0; - RCLCPP_INFO(logger_, "Requesting parameters..."); + RCLCPP_INFO(logger_, "[%s] Requesting parameters...", name_.c_str()); cf_.requestParamToc(/*forceNoCache*/false, /*requestValues*/query_all_values_on_connect); for (auto iter = cf_.paramsBegin(); iter != cf_.paramsEnd(); ++iter) { auto entry = *iter; @@ -285,7 +292,7 @@ class CrazyflieROS } break; default: - RCLCPP_WARN(logger_, "Unknown param type for %s/%s", entry.group.c_str(), entry.name.c_str()); + RCLCPP_WARN(logger_, "[%s] Unknown param type for %s/%s", name_.c_str(), entry.group.c_str(), entry.name.c_str()); break; } // If there is no such parameter in all, add it @@ -301,7 +308,7 @@ class CrazyflieROS } auto end1 = std::chrono::system_clock::now(); std::chrono::duration elapsedSeconds1 = end1 - start; - RCLCPP_INFO(logger_, "reqParamTOC: %f s (%d params)", elapsedSeconds1.count(), numParams); + RCLCPP_INFO(logger_, "[%s] reqParamTOC: %f s (%d params)", name_.c_str(), elapsedSeconds1.count(), numParams); // Set parameters as specified in the configuration files, as in the following order // 1.) check all/firmware_params @@ -351,7 +358,7 @@ class CrazyflieROS // check if any of the default topics are enabled if (i.first.find("default_topics.pose") == 0) { int freq = log_config_map["default_topics.pose.frequency"].get(); - RCLCPP_INFO(logger_, "Logging to /pose at %d Hz", freq); + RCLCPP_INFO(logger_, "[%s] Logging to /pose at %d Hz", name_.c_str(), freq); publisher_pose_ = node->create_publisher(name + "/pose", 10); @@ -368,7 +375,7 @@ class CrazyflieROS } else if (i.first.find("default_topics.scan") == 0) { int freq = log_config_map["default_topics.scan.frequency"].get(); - RCLCPP_INFO(logger_, "Logging to /scan at %d Hz", freq); + RCLCPP_INFO(logger_, "[%s] Logging to /scan at %d Hz", name_.c_str(), freq); publisher_scan_ = node->create_publisher(name + "/scan", 10); @@ -385,7 +392,7 @@ class CrazyflieROS } else if (i.first.find("default_topics.status") == 0) { int freq = log_config_map["default_topics.status.frequency"].get(); - RCLCPP_INFO(logger_, "Logging to /status at %d Hz", freq); + RCLCPP_INFO(logger_, "[%s] Logging to /status at %d Hz", name_.c_str(), freq); publisher_status_ = node->create_publisher(name + "/status", 10); @@ -415,7 +422,7 @@ class CrazyflieROS // older firmware -> use other 16-bit variables if (!status_has_radio_stats_) { - RCLCPP_WARN(logger_, "Older firmware. status/num_rx_broadcast and status/num_rx_unicast are set to zero."); + RCLCPP_WARN(logger_, "[%s] Older firmware. status/num_rx_broadcast and status/num_rx_unicast are set to zero.", name_.c_str()); logvars.push_back({"pm", "vbatMV"}); logvars.push_back({"pm", "vbatMV"}); } @@ -431,7 +438,7 @@ class CrazyflieROS int freq = log_config_map["custom_topics." + topic_name + ".frequency"].get(); auto vars = log_config_map["custom_topics." + topic_name + ".vars"].get>(); - RCLCPP_INFO(logger_, "Logging to %s at %d Hz", topic_name.c_str(), freq); + RCLCPP_INFO(logger_, "[%s] Logging to %s at %d Hz", name_.c_str(), topic_name.c_str(), freq); publishers_generic_.emplace_back(node->create_publisher(name + "/" + topic_name, 10)); @@ -453,7 +460,7 @@ class CrazyflieROS } } - RCLCPP_INFO(logger_, "Requesting memories..."); + RCLCPP_INFO(logger_, "[%s] Requesting memories...", name_.c_str()); cf_.requestMemoryToc(); } @@ -489,7 +496,7 @@ class CrazyflieROS if (p.get_name().find(prefix) != 0) { RCLCPP_ERROR( logger_, - "Incorrect parameter update request for param \"%s\"", p.get_name().c_str()); + "[%s] Incorrect parameter update request for param \"%s\"", name_.c_str(), p.get_name().c_str()); return; } size_t pos = p.get_name().find(".", prefix.size()); @@ -498,7 +505,8 @@ class CrazyflieROS RCLCPP_INFO( logger_, - "Update parameter \"%s.%s\" to %s", + "[%s] Update parameter \"%s.%s\" to %s", + name_.c_str(), group.c_str(), name.c_str(), p.value_to_string().c_str()); @@ -535,7 +543,7 @@ class CrazyflieROS break; } } else { - RCLCPP_ERROR(logger_, "Could not find param %s/%s", group.c_str(), name.c_str()); + RCLCPP_ERROR(logger_, "[%s] Could not find param %s/%s", name_.c_str(), group.c_str(), name.c_str()); } } @@ -594,7 +602,7 @@ class CrazyflieROS if (pos != std::string::npos) { message_buffer_[pos] = 0; - RCLCPP_INFO(logger_, "%s", message_buffer_.c_str()); + RCLCPP_INFO(logger_, "[%s] %s", name_.c_str(), message_buffer_.c_str()); message_buffer_.erase(0, pos + 1); } } @@ -602,14 +610,15 @@ class CrazyflieROS void emergency(const std::shared_ptr request, std::shared_ptr response) { - RCLCPP_INFO(logger_, "emergency()"); + RCLCPP_INFO(logger_, "[%s] emergency()", name_.c_str()); cf_.emergencyStop(); } void start_trajectory(const std::shared_ptr request, std::shared_ptr response) { - RCLCPP_INFO(logger_, "start_trajectory(id=%d, timescale=%f, reversed=%d, relative=%d, group_mask=%d)", + RCLCPP_INFO(logger_, "[%s] start_trajectory(id=%d, timescale=%f, reversed=%d, relative=%d, group_mask=%d)", + name_.c_str(), request->trajectory_id, request->timescale, request->reversed, @@ -625,7 +634,8 @@ class CrazyflieROS void takeoff(const std::shared_ptr request, std::shared_ptr response) { - RCLCPP_INFO(logger_, "takeoff(height=%f m, duration=%f s, group_mask=%d)", + RCLCPP_INFO(logger_, "[%s] takeoff(height=%f m, duration=%f s, group_mask=%d)", + name_.c_str(), request->height, rclcpp::Duration(request->duration).seconds(), request->group_mask); @@ -635,7 +645,8 @@ class CrazyflieROS void land(const std::shared_ptr request, std::shared_ptr response) { - RCLCPP_INFO(logger_, "land(height=%f m, duration=%f s, group_mask=%d)", + RCLCPP_INFO(logger_, "[%s] land(height=%f m, duration=%f s, group_mask=%d)", + name_.c_str(), request->height, rclcpp::Duration(request->duration).seconds(), request->group_mask); @@ -645,7 +656,8 @@ class CrazyflieROS void go_to(const std::shared_ptr request, std::shared_ptr response) { - RCLCPP_INFO(logger_, "go_to(position=%f,%f,%f m, yaw=%f rad, duration=%f s, relative=%d, group_mask=%d)", + RCLCPP_INFO(logger_, "[%s] go_to(position=%f,%f,%f m, yaw=%f rad, duration=%f s, relative=%d, group_mask=%d)", + name_.c_str(), request->goal.x, request->goal.y, request->goal.z, request->yaw, rclcpp::Duration(request->duration).seconds(), request->relative, @@ -658,7 +670,8 @@ class CrazyflieROS void upload_trajectory(const std::shared_ptr request, std::shared_ptr response) { - RCLCPP_INFO(logger_, "upload_trajectory(id=%d, offset=%d)", + RCLCPP_INFO(logger_, "[%s] upload_trajectory(id=%d, offset=%d)", + name_.c_str(), request->trajectory_id, request->piece_offset); @@ -670,7 +683,7 @@ class CrazyflieROS || request->pieces[i].poly_z.size() != 8 || request->pieces[i].poly_yaw.size() != 8) { - RCLCPP_FATAL(logger_, "Wrong number of pieces!"); + RCLCPP_FATAL(logger_, "[%s] Wrong number of pieces!", name_.c_str()); return; } pieces[i].duration = rclcpp::Duration(request->pieces[i].duration).seconds(); @@ -688,7 +701,8 @@ class CrazyflieROS void notify_setpoints_stop(const std::shared_ptr request, std::shared_ptr response) { - RCLCPP_INFO(logger_, "notify_setpoints_stop(remain_valid_millisecs%d, group_mask=%d)", + RCLCPP_INFO(logger_, "[%s] notify_setpoints_stop(remain_valid_millisecs%d, group_mask=%d)", + name_.c_str(), request->remain_valid_millisecs, request->group_mask); @@ -824,13 +838,13 @@ class CrazyflieROS auto now = std::chrono::steady_clock::now(); std::chrono::duration elapsed = now - last_on_latency_; if (elapsed.count() > 1.0 / warning_freq_) { - RCLCPP_WARN(logger_, "last latency update: %f s", elapsed.count()); + RCLCPP_WARN(logger_, "[%s] last latency update: %f s", name_.c_str(), elapsed.count()); } auto stats = cf_.connectionStatsDelta(); float ack_rate = stats.sent_count / stats.ack_count; if (ack_rate < min_ack_rate_) { - RCLCPP_WARN(logger_, "Ack rate: %.1f %%", ack_rate * 100); + RCLCPP_WARN(logger_, "[%s] Ack rate: %.1f %%", name_.c_str(), ack_rate * 100); } if (publish_stats_) { @@ -853,7 +867,7 @@ class CrazyflieROS void on_latency(uint64_t latency_in_us) { if (latency_in_us / 1000.0 > max_latency_) { - RCLCPP_WARN(logger_, "Latency: %.1f ms", latency_in_us / 1000.0); + RCLCPP_WARN(logger_, "[%s] Latency: %.1f ms", name_.c_str(), latency_in_us / 1000.0); } last_on_latency_ = std::chrono::steady_clock::now(); } @@ -921,7 +935,7 @@ class CrazyflieServer : public rclcpp::Node public: CrazyflieServer() : Node("crazyflie_server") - , logger_(rclcpp::get_logger("all")) + , logger_(get_logger()) { // Create callback groups (each group can run in a separate thread) callback_group_mocap_ = this->create_callback_group( @@ -1036,7 +1050,7 @@ class CrazyflieServer : public rclcpp::Node uint8_t id = parameter_overrides.at("robots." + name + ".id").get(); update_name_to_id_map(name, id); } else { - RCLCPP_INFO(logger_, "Unknown connection type %s", constr.c_str()); + RCLCPP_INFO(logger_, "[all] Unknown connection type %s", constr.c_str()); } } } @@ -1063,7 +1077,7 @@ class CrazyflieServer : public rclcpp::Node void emergency(const std::shared_ptr request, std::shared_ptr response) { - RCLCPP_INFO(logger_, "emergency()"); + RCLCPP_INFO(logger_, "[all] emergency()"); for (int i = 0; i < broadcasts_num_repeats_; ++i) { for (auto &bc : broadcaster_) { @@ -1077,7 +1091,7 @@ class CrazyflieServer : public rclcpp::Node void start_trajectory(const std::shared_ptr request, std::shared_ptr response) { - RCLCPP_INFO(logger_, "start_trajectory(id=%d, timescale=%f, reversed=%d, group_mask=%d)", + RCLCPP_INFO(logger_, "[all] start_trajectory(id=%d, timescale=%f, reversed=%d, group_mask=%d)", request->trajectory_id, request->timescale, request->reversed, @@ -1097,7 +1111,7 @@ class CrazyflieServer : public rclcpp::Node void takeoff(const std::shared_ptr request, std::shared_ptr response) { - RCLCPP_INFO(logger_, "takeoff(height=%f m, duration=%f s, group_mask=%d)", + RCLCPP_INFO(logger_, "[all] takeoff(height=%f m, duration=%f s, group_mask=%d)", request->height, rclcpp::Duration(request->duration).seconds(), request->group_mask); @@ -1113,7 +1127,7 @@ class CrazyflieServer : public rclcpp::Node void land(const std::shared_ptr request, std::shared_ptr response) { - RCLCPP_INFO(logger_, "land(height=%f m, duration=%f s, group_mask=%d)", + RCLCPP_INFO(logger_, "[all] land(height=%f m, duration=%f s, group_mask=%d)", request->height, rclcpp::Duration(request->duration).seconds(), request->group_mask); @@ -1129,7 +1143,7 @@ class CrazyflieServer : public rclcpp::Node void go_to(const std::shared_ptr request, std::shared_ptr response) { - RCLCPP_INFO(logger_, "go_to(position=%f,%f,%f m, yaw=%f rad, duration=%f s, group_mask=%d)", + RCLCPP_INFO(logger_, "[all] go_to(position=%f,%f,%f m, yaw=%f rad, duration=%f s, group_mask=%d)", request->goal.x, request->goal.y, request->goal.z, request->yaw, rclcpp::Duration(request->duration).seconds(), request->group_mask); @@ -1147,7 +1161,7 @@ class CrazyflieServer : public rclcpp::Node void notify_setpoints_stop(const std::shared_ptr request, std::shared_ptr response) { - RCLCPP_INFO(logger_, "notify_setpoints_stop(remain_valid_millisecs%d, group_mask=%d)", + RCLCPP_INFO(logger_, "[all] notify_setpoints_stop(remain_valid_millisecs%d, group_mask=%d)", request->remain_valid_millisecs, request->group_mask); @@ -1254,7 +1268,7 @@ class CrazyflieServer : public rclcpp::Node RCLCPP_INFO( logger_, - "Update parameter \"%s.%s\" to %s", + "[all] Update parameter \"%s.%s\" to %s", group.c_str(), name.c_str(), p.value_to_string().c_str()); @@ -1324,11 +1338,11 @@ class CrazyflieServer : public rclcpp::Node mean_rate /= (mocap_data_received_timepoints_.size() - 1); if (num_rates_wrong > 0) { - RCLCPP_WARN(logger_, "Motion capture rate off (#: %d, Avg: %.1f)", num_rates_wrong, mean_rate); + RCLCPP_WARN(logger_, "[all] Motion capture rate off (#: %d, Avg: %.1f)", num_rates_wrong, mean_rate); } } else if (mocap_enabled_) { // b) warn if no data was received - RCLCPP_WARN(logger_, "Motion capture did not receive data!"); + RCLCPP_WARN(logger_, "[all] Motion capture did not receive data!"); } mocap_data_received_timepoints_.clear(); @@ -1377,7 +1391,7 @@ class CrazyflieServer : public rclcpp::Node { const auto iter = name_to_id_.find(name); if (iter != name_to_id_.end()) { - RCLCPP_WARN(logger_, "At least two objects with the same id (%d, %s, %s)", id, name.c_str(), iter->first.c_str()); + RCLCPP_WARN(logger_, "[all] At least two objects with the same id (%d, %s, %s)", id, name.c_str(), iter->first.c_str()); } else { name_to_id_.insert(std::make_pair(name, id)); } @@ -1400,6 +1414,8 @@ class CrazyflieServer : public rclcpp::Node std::map> crazyflies_; + + // broadcastUri -> broadcast object std::map> broadcaster_; From 94a1d93ded5918f3df18e11ffcdc26db494dc3b4 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Sat, 3 Feb 2024 22:33:04 +0100 Subject: [PATCH 074/162] gui: add support for status --- crazyflie/scripts/gui.py | 156 +++++++++++++++++++++++++++++---------- 1 file changed, 116 insertions(+), 40 deletions(-) diff --git a/crazyflie/scripts/gui.py b/crazyflie/scripts/gui.py index 3941d8c77..830d94a34 100755 --- a/crazyflie/scripts/gui.py +++ b/crazyflie/scripts/gui.py @@ -2,7 +2,9 @@ import math import threading +import time from pathlib import Path +from functools import partial import rclpy from geometry_msgs.msg import Pose, Twist @@ -14,6 +16,9 @@ from tf2_ros.buffer import Buffer from tf2_ros.transform_listener import TransformListener +from crazyflie_interfaces.msg import Status +import rowan + from nicegui import Client, app, events, ui, ui_run @@ -31,58 +36,55 @@ def __init__(self) -> None: if cfname != 'all': self.cfnames.append(cfname) - print(self.cfnames) - self.cfs = [] - self.tf_buffer = Buffer() self.tf_listener = TransformListener(self.tf_buffer, self) - - - self.cmd_vel_publisher = self.create_publisher(Twist, 'cmd_vel', 1) - self.sub_log = self.create_subscription(Log, 'rosout', self.on_rosout, 1) + self.sub_log = self.create_subscription(Log, 'rosout', self.on_rosout, rclpy.qos.QoSProfile( + depth=1000, + durability=rclpy.qos.QoSDurabilityPolicy.TRANSIENT_LOCAL)) self.logs = dict() + self.supervisor_labels = dict() + self.battery_labels = dict() + self.radio_labels = dict() + self.robotmodels = dict() + # set of robot names that had a status recently + self.watchdog = dict() with Client.auto_index_client: - # with ui.row().classes('w-full h-full no-wrap'): - # self.log = ui.log().classes('w-full h-full no-wrap') - - - with ui.row().classes('items-stretch'): - # with ui.card().classes('w-44 text-center items-center'): - # ui.label('Data').classes('text-2xl') - # ui.label('linear velocity').classes('text-xs mb-[-1.8em]') - # slider_props = 'readonly selection-color=transparent' - # self.linear = ui.slider(min=-1, max=1, step=0.05, value=0).props(slider_props) - # ui.label('angular velocity').classes('text-xs mb-[-1.8em]') - # self.angular = ui.slider(min=-1, max=1, step=0.05, value=0).props(slider_props) - # ui.label('position').classes('text-xs mb-[-1.4em]') - # self.position = ui.label('---') with ui.card().classes('w-full h-full'): ui.label('Visualization').classes('text-2xl') - with ui.scene(800, 600, on_click=self.on_vis_click) as scene: + with ui.scene(800, 400, on_click=self.on_vis_click) as scene: for name in self.cfnames: robot = scene.stl('/urdf/cf2_assembly.stl').scale(1.0).material('#ff0000').with_name(name) - self.cfs.append(robot) - # with scene.group() as self.robot_3d: - # prism = [[-0.5, -0.5], [0.5, -0.5], [0.75, 0], [0.5, 0.5], [-0.5, 0.5]] - # self.robot_object = scene.extrusion(prism, 0.4).material('#4488ff', 0.5) - - with ui.row().classes('w-full h-full'): + self.robotmodels[name] = robot + self.watchdog[name] = time.time() + scene.camera.x = 0 + scene.camera.y = -1 + scene.camera.z = 2 + scene.camera.look_at_x = 0 + scene.camera.look_at_y = 0 + scene.camera.look_at_z = 0 + + with ui.row().classes('w-full h-lvh'): with ui.tabs().classes('w-full') as tabs: self.tabs = [] for name in ["all"] + self.cfnames: self.tabs.append(ui.tab(name)) - with ui.tab_panels(tabs, value=self.tabs[0]).classes('w-full') as self.tabpanels: + with ui.tab_panels(tabs, value=self.tabs[0], on_change=self.on_tab_change).classes('w-full') as self.tabpanels: for name, tab in zip(["all"] + self.cfnames, self.tabs): with ui.tab_panel(tab): - self.logs[name] = ui.log().classes('w-full h-full no-wrap') - ui.label("Battery Voltage: ") - ui.button("Reboot") + self.logs[name] = ui.log().classes('w-full h-96 no-wrap') + self.supervisor_labels[name] = ui.label("") + self.battery_labels[name] = ui.label("") + self.radio_labels[name] = ui.label("") + ui.button("Reboot", on_click=partial(self.on_reboot, name=name)) + + for name in self.cfnames: + self.create_subscription(Status, name + '/status', partial(self.on_status, name=name), 1) # Call on_timer function self.timer = self.create_timer(0.1, self.on_timer) @@ -96,17 +98,39 @@ def send_speed(self, x: float, y: float) -> None: self.cmd_vel_publisher.publish(msg) def on_rosout(self, msg: Log) -> None: - if msg.name in self.logs: - self.logs[msg.name].push(msg.msg) + # filter by crazyflie and add to the correct log + if msg.name == "crazyflie_server": + if msg.msg.startswith("["): + idx = msg.msg.find("]") + name = msg.msg[1:idx] + # if it was an "all" category, add only to CFs + if name == 'all': + for logname ,log in self.logs.items(): + if logname != "all": + log.push(msg.msg) + elif name in self.logs: + self.logs[name].push(msg.msg[idx+2:]) + + # add all possible messages to the 'all' tab + self.logs['all'].push(msg.msg) def on_timer(self) -> None: - for name, robot in zip(self.cfnames, self.cfs): + for name, robotmodel in self.robotmodels.items(): t = self.tf_buffer.lookup_transform( "world", name, rclpy.time.Time()) pos = t.transform.translation - robot.move(pos.x, pos.y, pos.z) + robotmodel.move(pos.x, pos.y, pos.z) + robotmodel.rotate(*rowan.to_euler([ + t.transform.rotation.w, + t.transform.rotation.x, + t.transform.rotation.y, + t.transform.rotation.z], "xyz")) + + # no update for a while -> mark red + if time.time() - self.watchdog[name] > 2.0: + robotmodel.material('#ff0000') def on_vis_click(self, e: events.SceneClickEventArguments): hit = e.hits[0] @@ -117,12 +141,64 @@ def on_vis_click(self, e: events.SceneClickEventArguments): else: self.tabpanels.value = name + def on_status(self, msg, name) -> None: + status_ok = True + supervisor_text = "" + if msg.supervisor_info & Status.SUPERVISOR_INFO_CAN_BE_ARMED: + supervisor_text += "can be armed; " + if msg.supervisor_info & Status.SUPERVISOR_INFO_IS_ARMED: + supervisor_text += "is armed; " + if msg.supervisor_info & Status.SUPERVISOR_INFO_AUTO_ARM: + supervisor_text += "auto-arm; " + if msg.supervisor_info & Status.SUPERVISOR_INFO_CAN_FLY: + supervisor_text += "can fly; " + if msg.supervisor_info & Status.SUPERVISOR_INFO_IS_FLYING: + supervisor_text += "is flying; " + if msg.supervisor_info & Status.SUPERVISOR_INFO_IS_TUMBLED: + supervisor_text += "is tumpled; " + status_ok = False + if msg.supervisor_info & Status.SUPERVISOR_INFO_IS_LOCKED: + supervisor_text += "is locked; " + status_ok = False + self.supervisor_labels[name].set_text(supervisor_text) + + battery_text = f'{msg.battery_voltage:.2f} V' + if msg.battery_voltage < 3.8: + status_ok = False + if msg.pm_state == Status.PM_STATE_BATTERY: + battery_text += " (on battery)" + elif msg.pm_state == Status.PM_STATE_CHARGING: + battery_text += " (charging)" + elif msg.pm_state == Status.PM_STATE_CHARGED: + battery_text += " (charged)" + elif msg.pm_state == Status.PM_STATE_LOW_POWER: + battery_text += " (low power)" + status_ok = False + elif msg.pm_state == Status.PM_STATE_SHUTDOWN: + battery_text += " (shutdown)" + status_ok = False + self.battery_labels[name].set_text(battery_text) + + radio_text = f'{msg.rssi} dBm; Unicast: {msg.num_rx_unicast} / {msg.num_tx_unicast}; Broadcast: {msg.num_rx_broadcast} / {msg.num_tx_broadcast}' + self.radio_labels[name].set_text(radio_text) + + if status_ok: + self.robotmodels[name].material('#00ff00') + else: + self.robotmodels[name].material('#ff0000') + + self.watchdog[name] = time.time() + + def on_tab_change(self, arg): + for name, robotmodel in self.robotmodels.items(): + if name != arg.value: + robotmodel.scale(1) + if arg.value in self.robotmodels: + self.robotmodels[arg.value].scale(2) - # def handle_pose(self, msg: Pose) -> None: - # self.position.text = f'x: {msg.position.x:.2f}, y: {msg.position.y:.2f}' - # self.robot_3d.move(msg.position.x, msg.position.y) - # self.robot_3d.rotate(0, 0, 2 * math.atan2(msg.orientation.z, msg.orientation.w)) + def on_reboot(self, name) -> None: + ui.notify(f'Reboot not implemented, yet') def main() -> None: From 1eb3ab65d9761cce429b29e08aaa57a68ff75906 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Sun, 4 Feb 2024 22:05:42 +0100 Subject: [PATCH 075/162] server [cflib] unify logging messages --- crazyflie/scripts/crazyflie_server.py | 85 +++++++++++++++------------ 1 file changed, 48 insertions(+), 37 deletions(-) diff --git a/crazyflie/scripts/crazyflie_server.py b/crazyflie/scripts/crazyflie_server.py index 4ba4dcf4a..ac7882d15 100755 --- a/crazyflie/scripts/crazyflie_server.py +++ b/crazyflie/scripts/crazyflie_server.py @@ -67,7 +67,10 @@ def __init__(self): self._ros_parameters = self._param_to_dict(self._parameters) self.uris = [] - self.cf_dict = {} + # for logging, assign a all -> all mapping + self.cf_dict = { + 'all': 'all' + } self.uri_dict = {} self.type_dict = {} @@ -224,6 +227,9 @@ def __init__(self): StartTrajectory, "all/start_trajectory", self._start_trajectory_callback) for uri in self.cf_dict: + if uri == "all": + continue + name = self.cf_dict[uri] pub = self.create_publisher(String, name + '/robot_description', @@ -354,7 +360,7 @@ def _fully_connected(self, link_uri): Called when all parameters have been updated and the full log toc has been received of the Crazyflie """ - self.get_logger().info(f" {link_uri} is fully connected!") + self.get_logger().info(f"[{self.cf_dict[link_uri]}] is fully connected!") self.swarm.fully_connected_crazyflie_cnt += 1 @@ -367,10 +373,10 @@ def _fully_connected(self, link_uri): return def _disconnected(self, link_uri): - self.get_logger().info(f" {link_uri} is disconnected!") + self.get_logger().info(f"[{self.cf_dict[link_uri]}] is disconnected!") def _connection_failed(self, link_uri, msg): - self.get_logger().info(f"{link_uri} connection Failed") + self.get_logger().info(f"[{self.cf_dict[link_uri]}] connection Failed") self.swarm.close_links() def _init_logging(self): @@ -406,20 +412,20 @@ def _init_logging(self): self._log_error_callback) lg_custom.start() except KeyError as e: - self.get_logger().info(f'{link_uri}: Could not start log configuration,' + self.get_logger().info(f'[{self.cf_dict[link_uri]}] Could not start log configuration,' '{} not found in TOC'.format(str(e))) except AttributeError: self.get_logger().info( - f'{link_uri}: Could not add log config, bad configuration.') + f'[{self.cf_dict[link_uri]}] Could not add log config, bad configuration.') - self.get_logger().info(f"{link_uri} setup custom logging") + self.get_logger().info(f"[{self.cf_dict[link_uri]}] setup custom logging") self.create_service( RemoveLogging, self.cf_dict[link_uri] + "/remove_logging", partial(self._remove_logging, uri=link_uri)) self.create_service( AddLogging, self.cf_dict[link_uri] + "/add_logging", partial(self._add_logging, uri=link_uri)) - self.get_logger().info("All Crazyflies loggging are initialized") + self.get_logger().info("All Crazyflies logging are initialized.") def _init_default_logging(self, prefix, link_uri, callback_fnc): """ @@ -438,13 +444,13 @@ def _init_default_logging(self, prefix, link_uri, callback_fnc): self.declare_parameter( self.cf_dict[link_uri] + ".logs." + prefix + ".frequency.", frequency) self.get_logger().info( - f"{link_uri} setup logging for {prefix} at freq {frequency}") + f"[{self.cf_dict[link_uri]}] setup logging for {prefix} at freq {frequency}") except KeyError as e: - self.get_logger().info(f'{link_uri}: Could not start log configuration,' + self.get_logger().error(f'[{self.cf_dict[link_uri]}] Could not start log configuration,' '{} not found in TOC'.format(str(e))) except AttributeError: - self.get_logger().info( - f'{link_uri}: Could not add log config, bad configuration.') + self.get_logger().error( + f'[{self.cf_dict[link_uri]}] Could not add log config, bad configuration.') def _log_scan_data_callback(self, timestamp, data, logconf, uri): """ @@ -652,7 +658,7 @@ def _init_parameters(self): # crazyflie with get_value due to threading. cf.param.set_value(name, set_param_value) self.get_logger().info( - f" {link_uri}: {name} is set to {set_param_value}" + f"[{self.cf_dict[link_uri]}] {name} is set to {set_param_value}" ) self.declare_parameter( self.cf_dict[link_uri] + @@ -691,7 +697,7 @@ def _init_parameters(self): # Now all parameters are set set_param_all = True - self.get_logger().info("All Crazyflies parameters are initialized") + self.get_logger().info("All Crazyflies parameters are initialized.") def _parameters_callback(self, params): """ @@ -710,7 +716,7 @@ def _parameters_callback(self, params): name_param, param.value ) self.get_logger().info( - f" {self.uri_dict[cf_name]}: {name_param} is set to {param.value}" + f"[{self.uri_dict[cf_name]}] {name_param} is set to {param.value}" ) return SetParametersResult(successful=True) except Exception as e: @@ -727,7 +733,7 @@ def _parameters_callback(self, params): name_param, param.value ) self.get_logger().info( - f" {link_uri}: {name_param} is set to {param.value}" + f"[{self.cf_dict[link_uri]}] {name_param} is set to {param.value}" ) return SetParametersResult(successful=True) except Exception as e: @@ -751,12 +757,14 @@ def _takeoff_callback(self, request, response, uri="all"): a certain height in high level commander """ + print("call1 ", uri) + duration = float(request.duration.sec) + \ float(request.duration.nanosec / 1e9) self.get_logger().info( - f"takeoff(height={request.height} m," + f"[{self.cf_dict[uri]}] takeoff(height={request.height} m," + f"duration={duration} s," - + f"group_mask={request.group_mask}) {uri}" + + f"group_mask={request.group_mask})" ) if uri == "all": for link_uri in self.uris: @@ -778,7 +786,7 @@ def _land_callback(self, request, response, uri="all"): duration = float(request.duration.sec) + \ float(request.duration.nanosec / 1e9) self.get_logger().info( - f"land(height={request.height} m," + f"[{self.cf_dict[uri]}] land(height={request.height} m," + f"duration={duration} s," + f"group_mask={request.group_mask})" ) @@ -803,8 +811,9 @@ def _go_to_callback(self, request, response, uri="all"): float(request.duration.nanosec / 1e9) self.get_logger().info( - "go_to(position=%f,%f,%f m, yaw=%f rad, duration=%f s, relative=%d, group_mask=%d)" + "[%s] go_to(position=%f,%f,%f m, yaw=%f rad, duration=%f s, relative=%d, group_mask=%d)" % ( + self.cf_dict[uri], request.goal.x, request.goal.y, request.goal.z, @@ -839,7 +848,7 @@ def _go_to_callback(self, request, response, uri="all"): def _notify_setpoints_stop_callback(self, request, response, uri="all"): - self.get_logger().info(f"{uri}: Received notify setpoint stop") + self.get_logger().info(f"[{self.cf_dict[uri]}] Received notify setpoint stop") if uri == "all": for link_uri in self.uris: @@ -855,7 +864,8 @@ def _upload_trajectory_callback(self, request, response, uri="all"): offset = request.piece_offset lenght = len(request.pieces) total_duration = 0 - self.get_logger().info("upload_trajectory(id=%d,offset=%d, lenght=%d)" % ( + self.get_logger().info("[%s] upload_trajectory(id=%d,offset=%d, lenght=%d)" % ( + self.cf_dict[uri], id, offset, lenght, @@ -881,7 +891,7 @@ def _upload_trajectory_callback(self, request, response, uri="all"): trajectory_mem.trajectory = trajectory upload_result = trajectory_mem.write_data_sync() if not upload_result: - self.get_logger().info(f"{link_uri}: Upload failed") + self.get_logger().info(f"[{self.cf_dict[uri]}] Upload failed") upload_success_all = False else: self.swarm._cfs[link_uri].cf.high_level_commander.define_trajectory( @@ -895,7 +905,7 @@ def _upload_trajectory_callback(self, request, response, uri="all"): trajectory_mem.trajectory = trajectory upload_result = trajectory_mem.write_data_sync() if not upload_result: - self.get_logger().info(f"{uri}: Upload failed") + self.get_logger().info(f"[{self.cf_dict[uri]}] Upload failed") response.success = False return response self.swarm._cfs[uri].cf.high_level_commander.define_trajectory( @@ -911,7 +921,8 @@ def _start_trajectory_callback(self, request, response, uri="all"): rev = request.reversed gm = request.group_mask - self.get_logger().info("start_trajectory(id=%d,timescale=%f,relative=%d, reversed=%d, group_mask=%d)" % ( + self.get_logger().info("[%s] start_trajectory(id=%d,timescale=%f,relative=%d, reversed=%d, group_mask=%d)" % ( + self.cf_dict[uri], id, ts, rel, @@ -1002,10 +1013,10 @@ def _remove_logging(self, request, response, uri="all"): self.swarm._cfs[uri].logging[topic_name + "_log_config"].stop() self.destroy_publisher( self.swarm._cfs[uri].logging[topic_name + "_publisher"]) - self.get_logger().info(f"{uri}: Remove {topic_name} logging") + self.get_logger().info(f"[{self.cf_dict[uri]}] Remove {topic_name} logging") except rclpy.exceptions.ParameterNotDeclaredException: self.get_logger().info( - f"{uri}: No logblock of {topic_name} has been found ") + f"[{self.cf_dict[uri]}] No logblock of {topic_name} has been found ") response.success = False return response else: @@ -1015,10 +1026,10 @@ def _remove_logging(self, request, response, uri="all"): for log_name in self.swarm._cfs[uri].logging["custom_log_groups"][topic_name]["vars"]: self.destroy_publisher( self.swarm._cfs[uri].logging["custom_log_publisher"][topic_name]) - self.get_logger().info(f"{uri}: Remove {topic_name} logging") + self.get_logger().info(f"[{self.cf_dict[uri]}] Remove {topic_name} logging") except rclpy.exceptions.ParameterNotDeclaredException: self.get_logger().info( - f"{uri}: No logblock of {topic_name} has been found ") + f"[{self.cf_dict[uri]}] No logblock of {topic_name} has been found ") response.success = False return response @@ -1042,10 +1053,10 @@ def _add_logging(self, request, response, uri="all"): "_log_config"].period_in_ms = 1000 / frequency self.swarm._cfs[uri].logging[topic_name + "_log_config"].start() - self.get_logger().info(f"{uri}: Add {topic_name} logging") + self.get_logger().info(f"[{self.cf_dict[uri]}] Add {topic_name} logging") except rclpy.exceptions.ParameterAlreadyDeclaredException: self.get_logger().info( - f"{uri}: The content the logging of {topic_name} has already started ") + f"[{self.cf_dict[uri]}] The content the logging of {topic_name} has already started ") response.success = False return response else: @@ -1073,11 +1084,11 @@ def _add_logging(self, request, response, uri="all"): self.swarm._cfs[uri].logging["custom_log_groups"][topic_name]["vars"] = variables self.swarm._cfs[uri].logging["custom_log_groups"][topic_name]["frequency"] = frequency - self.get_logger().info(f"{uri}: Add {topic_name} logging") + self.get_logger().info(f"[{self.cf_dict[uri]}] Add {topic_name} logging") except KeyError as e: - self.get_logger().info( - f"{uri}: Failed to add {topic_name} logging") - self.get_logger().info(str(e) + "is not in TOC") + self.get_logger().error( + f"[{self.cf_dict[uri]}] Failed to add {topic_name} logging") + self.get_logger().error(str(e) + "is not in TOC") self.undeclare_parameter( self.cf_dict[uri] + ".logs." + topic_name + ".frequency.") self.undeclare_parameter( @@ -1085,8 +1096,8 @@ def _add_logging(self, request, response, uri="all"): response.success = False return response except rclpy.exceptions.ParameterAlreadyDeclaredException: - self.get_logger().info( - f"{uri}: The content or part of the logging of {topic_name} has already started ") + self.get_logger().error( + f"[{self.cf_dict[uri]}] The content or part of the logging of {topic_name} has already started ") response.success = False return response From d0b4ad555da155aadaba4961edd2e9b8041d776b Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Mon, 5 Feb 2024 10:30:07 +0100 Subject: [PATCH 076/162] fix flake8 issues --- crazyflie_sim/crazyflie_sim/crazyflie_server.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/crazyflie_sim/crazyflie_sim/crazyflie_server.py b/crazyflie_sim/crazyflie_sim/crazyflie_server.py index 8050737b4..93dd698da 100755 --- a/crazyflie_sim/crazyflie_sim/crazyflie_server.py +++ b/crazyflie_sim/crazyflie_sim/crazyflie_server.py @@ -250,7 +250,11 @@ def _go_to_callback(self, request, response, name='all'): float(request.duration.nanosec / 1e9) self.get_logger().info( - '[%s] go_to(position=%f,%f,%f m, yaw=%f rad, duration=%f s, relative=%d, group_mask=%d)' + """[%s] go_to(position=%f,%f,%f m, + yaw=%f rad, + duration=%f s, + relative=%d, + group_mask=%d)""" % ( name, request.goal.x, From e996e62258d88b8bbfcace57b78fa9b647099015 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Mon, 5 Feb 2024 10:46:07 +0100 Subject: [PATCH 077/162] remove hard-coded path --- crazyflie/scripts/gui.py | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/crazyflie/scripts/gui.py b/crazyflie/scripts/gui.py index 830d94a34..5bd156634 100755 --- a/crazyflie/scripts/gui.py +++ b/crazyflie/scripts/gui.py @@ -1,18 +1,17 @@ #!/usr/bin/env python3 -import math import threading import time from pathlib import Path from functools import partial import rclpy -from geometry_msgs.msg import Pose, Twist +from geometry_msgs.msg import Twist from rcl_interfaces.msg import Log from rclpy.executors import ExternalShutdownException from rclpy.node import Node -from tf2_ros import TransformException +# from tf2_ros import TransformException from tf2_ros.buffer import Buffer from tf2_ros.transform_listener import TransformListener @@ -215,7 +214,9 @@ def ros_main() -> None: pass -app.add_static_files("/urdf", "/home/whoenig/projects/crazyflie/crazyswarm2/src/crazyswarm2/crazyflie/urdf/") +app.add_static_files("/urdf", + str((Path(__file__).parent.parent.parent / "share" / "crazyflie" / "urdf").resolve()), + follow_symlink=True) app.on_startup(lambda: threading.Thread(target=ros_main).start()) ui_run.APP_IMPORT_STRING = f'{__name__}:app' # ROS2 uses a non-standard module name, so we need to specify it here ui.run(uvicorn_reload_dirs=str(Path(__file__).parent.resolve()), favicon='🤖') From 8bd3ca6190f22c7c4e01996e7534add720e4e8e1 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Mon, 5 Feb 2024 10:46:56 +0100 Subject: [PATCH 078/162] update documentation --- crazyflie/launch/launch.py | 5 +++++ docs2/faq.rst | 4 ++-- docs2/overview.rst | 2 ++ docs2/usage.rst | 8 ++++++++ 4 files changed, 17 insertions(+), 2 deletions(-) diff --git a/crazyflie/launch/launch.py b/crazyflie/launch/launch.py index 8a9290c11..4eec72a92 100644 --- a/crazyflie/launch/launch.py +++ b/crazyflie/launch/launch.py @@ -134,4 +134,9 @@ def generate_launch_description(): "use_sim_time": True, }] ), + Node( + package='crazyflie', + executable='gui.py', + name='gui', + ), ]) diff --git a/docs2/faq.rst b/docs2/faq.rst index 8270b9343..7422be127 100644 --- a/docs2/faq.rst +++ b/docs2/faq.rst @@ -45,9 +45,9 @@ Crazyswarm2 was forked from Crazyswarm. However, there is also heavy re-design o In Crazyswarm1, a simple visualization of the setpoints for high-level Python scripts is supported. There is no support for simulation of ROS code that does not use the high-level Python scripts and no support for physics-based simulation. In contrast, Crazyswarm2 implements the simulation as an alternative backend. This will support multiple physics/visualization backends (optionally with physics and aerodynamic interaction). -- **Support of Distributed Swarm Monitoring (Planned).** +- **Support of Distributed Swarm Monitoring.** In Crazyswarm1, a common swarm monitoring tool is the chooser.py (to enable/disable CFs, check the battery voltage etc.). However, this tool was not functioning while the swarm is operational. - In contrast, Crazyswarm2 will allow common swarm monitoring tasks without restarting ROS nodes or launching additional tools. + In contrast, Crazyswarm2 allows common swarm monitoring tasks without restarting ROS nodes or launching additional tools. How is Crazyswarm2 different from Bitcraze's cflib? diff --git a/docs2/overview.rst b/docs2/overview.rst index 014cfc93d..cc413fe1f 100644 --- a/docs2/overview.rst +++ b/docs2/overview.rst @@ -67,6 +67,8 @@ Support functionality with backends +---------------------+---------+-----------+---------+ | - default: odom | No | Yes | No | +---------------------+---------+-----------+---------+ +| - default: status | Yes | Yes | No | ++---------------------+---------+-----------+---------+ | - custom | Yes | Yes | No | +---------------------+---------+-----------+---------+ | - Add/Remove Srv | No | Yes | No | diff --git a/docs2/usage.rst b/docs2/usage.rst index d8278958b..52117f0ae 100644 --- a/docs2/usage.rst +++ b/docs2/usage.rst @@ -155,3 +155,11 @@ You may run the script multiple times or different scripts while leaving the ser [terminal1]$ ros2 launch crazyflie launch.py [terminal2]$ ros2 run crazyflie_examples hello_world + +Swarm Management +---------------- + +The launch file will also start a swarm management tool that is a ROS node and web-based GUI. +In the upper pane is the location of the drone visualized in a 3D window, similar to rviz. +In the lower pane, the status as well as log messages are visible (tabbed per drone). +In the future, we are planning to add support for rebooting and other actions. \ No newline at end of file From 55e11dada5b5cd106c168ed9869b41c6630247a8 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Mon, 5 Feb 2024 10:56:41 +0100 Subject: [PATCH 079/162] enable status topic by default --- crazyflie/config/crazyflies.yaml | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/crazyflie/config/crazyflies.yaml b/crazyflie/config/crazyflies.yaml index e136fcd8b..f102bd78a 100644 --- a/crazyflie/config/crazyflies.yaml +++ b/crazyflie/config/crazyflies.yaml @@ -72,11 +72,13 @@ all: # firmware logging for all drones (use robot_types/type_name to set per type, or # robots/drone_name to set per drone) firmware_logging: - enabled: false + enabled: true default_topics: # remove to disable default topic - pose: - frequency: 10 # Hz + # pose: + # frequency: 10 # Hz + status: + frequency: 1 # Hz #custom_topics: # topic_name1: # frequency: 10 # Hz From 60524ac0c50f01c68ec223e81e3cbe5725326c8e Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Tue, 6 Feb 2024 07:13:24 +0100 Subject: [PATCH 080/162] Kimberly's feedback: 1) unused code removal 2) Better error handling of tf errors 3) Improved handling of simulation time 4) Unified error handling in on_timer --- crazyflie/launch/launch.py | 4 ++ crazyflie/scripts/gui.py | 82 +++++++++++++++++++++----------------- 2 files changed, 49 insertions(+), 37 deletions(-) diff --git a/crazyflie/launch/launch.py b/crazyflie/launch/launch.py index 4eec72a92..624ae65fd 100644 --- a/crazyflie/launch/launch.py +++ b/crazyflie/launch/launch.py @@ -138,5 +138,9 @@ def generate_launch_description(): package='crazyflie', executable='gui.py', name='gui', + output='screen', + parameters=[{ + "use_sim_time": True, + }] ), ]) diff --git a/crazyflie/scripts/gui.py b/crazyflie/scripts/gui.py index 5bd156634..9bc434aad 100755 --- a/crazyflie/scripts/gui.py +++ b/crazyflie/scripts/gui.py @@ -48,8 +48,6 @@ def __init__(self) -> None: self.battery_labels = dict() self.radio_labels = dict() self.robotmodels = dict() - # set of robot names that had a status recently - self.watchdog = dict() with Client.auto_index_client: @@ -60,11 +58,13 @@ def __init__(self) -> None: for name in self.cfnames: robot = scene.stl('/urdf/cf2_assembly.stl').scale(1.0).material('#ff0000').with_name(name) self.robotmodels[name] = robot - self.watchdog[name] = time.time() + # augment with some additional fields + robot.status_ok = False + robot.status_watchdog = time.time() scene.camera.x = 0 scene.camera.y = -1 scene.camera.z = 2 - scene.camera.look_at_x = 0 + scene.camera.look_at_x = 0 scene.camera.look_at_y = 0 scene.camera.look_at_z = 0 @@ -80,21 +80,16 @@ def __init__(self) -> None: self.supervisor_labels[name] = ui.label("") self.battery_labels[name] = ui.label("") self.radio_labels[name] = ui.label("") - ui.button("Reboot", on_click=partial(self.on_reboot, name=name)) for name in self.cfnames: self.create_subscription(Status, name + '/status', partial(self.on_status, name=name), 1) # Call on_timer function - self.timer = self.create_timer(0.1, self.on_timer) - - def send_speed(self, x: float, y: float) -> None: - msg = Twist() - msg.linear.x = x - msg.angular.z = -y - self.linear.value = x - self.angular.value = y - self.cmd_vel_publisher.publish(msg) + update_rate = 30 # Hz + self.timer = self.create_timer( + 1.0/update_rate, + self.on_timer, + clock=rclpy.clock.Clock(clock_type=rclpy.clock.ClockType.SYSTEM_TIME)) def on_rosout(self, msg: Log) -> None: # filter by crazyflie and add to the correct log @@ -115,20 +110,38 @@ def on_rosout(self, msg: Log) -> None: def on_timer(self) -> None: for name, robotmodel in self.robotmodels.items(): - t = self.tf_buffer.lookup_transform( - "world", - name, - rclpy.time.Time()) - pos = t.transform.translation - robotmodel.move(pos.x, pos.y, pos.z) - robotmodel.rotate(*rowan.to_euler([ - t.transform.rotation.w, - t.transform.rotation.x, - t.transform.rotation.y, - t.transform.rotation.z], "xyz")) - - # no update for a while -> mark red - if time.time() - self.watchdog[name] > 2.0: + ros_time = rclpy.time.Time() # get the latest + robot_status_ok = robotmodel.status_ok + if self.tf_buffer.can_transform("world", name, ros_time): + t = self.tf_buffer.lookup_transform( + "world", + name, + ros_time) + transform_time = rclpy.time.Time.from_msg(t.header.stamp) + transform_age = self.get_clock().now() - transform_time + # latest transform is older than a second indicates a problem + if transform_age.nanoseconds * 1e-9 > 1: + robot_status_ok = False + else: + pos = t.transform.translation + robotmodel.move(pos.x, pos.y, pos.z) + robotmodel.rotate(*rowan.to_euler([ + t.transform.rotation.w, + t.transform.rotation.x, + t.transform.rotation.y, + t.transform.rotation.z], "xyz")) + else: + # no available transform indicates a problem + robot_status_ok = False + + # no status update for a while, indicate a problem + if time.time() - robotmodel.status_watchdog > 2.0: + robot_status_ok = False + + # any issues detected -> mark red, otherwise green + if robot_status_ok: + robotmodel.material('#00ff00') + else: robotmodel.material('#ff0000') def on_vis_click(self, e: events.SceneClickEventArguments): @@ -181,13 +194,11 @@ def on_status(self, msg, name) -> None: radio_text = f'{msg.rssi} dBm; Unicast: {msg.num_rx_unicast} / {msg.num_tx_unicast}; Broadcast: {msg.num_rx_broadcast} / {msg.num_tx_broadcast}' self.radio_labels[name].set_text(radio_text) - if status_ok: - self.robotmodels[name].material('#00ff00') - else: - self.robotmodels[name].material('#ff0000') - - self.watchdog[name] = time.time() + # save status here + self.robotmodels[name].status_ok = status_ok + # store the time when we last received any status + self.robotmodels[name].status_watchdog[name] = time.time() def on_tab_change(self, arg): for name, robotmodel in self.robotmodels.items(): @@ -196,9 +207,6 @@ def on_tab_change(self, arg): if arg.value in self.robotmodels: self.robotmodels[arg.value].scale(2) - def on_reboot(self, name) -> None: - ui.notify(f'Reboot not implemented, yet') - def main() -> None: # NOTE: This function is defined as the ROS entry point in setup.py, but it's empty to enable NiceGUI auto-reloading From 9f136a2e17786e0b5aff403ba772f4c02fbeee0f Mon Sep 17 00:00:00 2001 From: phanfeld Date: Tue, 6 Feb 2024 14:59:38 +0100 Subject: [PATCH 081/162] first, untested version of image publisher --- crazyflie/config/camera_config.yaml | 58 ++++++++++ crazyflie/src/image_streamer.py | 158 ++++++++++++++++++++++++++++ 2 files changed, 216 insertions(+) create mode 100644 crazyflie/config/camera_config.yaml create mode 100644 crazyflie/src/image_streamer.py diff --git a/crazyflie/config/camera_config.yaml b/crazyflie/config/camera_config.yaml new file mode 100644 index 000000000..2c801c64a --- /dev/null +++ b/crazyflie/config/camera_config.yaml @@ -0,0 +1,58 @@ +image_width: 725 +image_height: 500 +camera_name: crazyflie +camera_matrix: + rows: 3 + cols: 3 + data: [383.76372, 0. , 363.38408, + 0. , 381.38288, 271.61177, + 0. , 0. , 1. ] +distortion_model: plumb_bob +distortion_coefficients: + rows: 1 + cols: 5 + data: [-0.001747, -0.009650, -0.002608, -0.002890, 0.000000] +rectification_matrix: + rows: 3 + cols: 3 + data: [1., 0., 0., + 0., 1., 0., + 0., 0., 1.] +projection_matrix: + rows: 3 + cols: 4 + data: [380.19111, 0. , 360.28396, 0. , + 0. , 380.987 , 270.48483, 0. , + 0. , 0. , 1. , 0. ] + + + +# image_width: 533 +# image_height: 320 +# camera_name: hoverair +# camera_matrix: +# rows: 3 +# cols: 3 +# data: [295.21347, 0. , 284.02365, +# 0. , 294.30945, 196.91373, +# 0. , 0. , 1. ] +# distortion_model: plumb_bob +# distortion_coefficients: +# rows: 1 +# cols: 5 +# data: [0.029797, -0.026754, 0.000635, -0.001295, 0.000000] +# rectification_matrix: +# rows: 3 +# cols: 3 +# data: [1., 0., 0., +# 0., 1., 0., +# 0., 0., 1.] +# projection_matrix: +# rows: 3 +# cols: 4 +# data: [297.20145, 0. , 283.47583, 0. , +# 0. , 296.96598, 197.18161, 0. , +# 0. , 0. , 1. , 0. ] + + + diff --git a/crazyflie/src/image_streamer.py b/crazyflie/src/image_streamer.py new file mode 100644 index 000000000..ed5ce88ee --- /dev/null +++ b/crazyflie/src/image_streamer.py @@ -0,0 +1,158 @@ +import socket,os,struct, time +import numpy as np +import cv2 +import yaml +from ament_index_python.packages import get_package_share_directory + + +import rclpy +from rclpy.node import Node +from sensor_msgs.msg import Image, CameraInfo + +from rcl_interfaces.msg import ParameterDescriptor, ParameterType + + +class ImageNode(rclpy.node.Node): + def __init__(self): + super().__init__("image_node") + + # declare topic names + self.declare_parameter( + name="image_topic", + value="/camera/image", + descriptor=ParameterDescriptor( + type=ParameterType.PARAMETER_STRING, + description="Image topic to publish to.", + ), + ) + + self.declare_parameter( + name="camera_info_topic", + value="/camera/camera_info", + descriptor=ParameterDescriptor( + type=ParameterType.PARAMETER_STRING, + description="Camera info topic to subscribe to.", + ), + ) + + # update topic names from config + image_topic = ( + self.get_parameter("image_topic").get_parameter_value().string_value + ) + self.get_logger().info(f"Image topic: {image_topic}") + + info_topic = ( + self.get_parameter("camera_info_topic").get_parameter_value().string_value + ) + self.get_logger().info(f"Image info topic: {info_topic}") + + + # load camera parameters from yaml + # TODO: could possibly be done in the same way as with the other parameters + config_path = os.path.join( + get_package_share_directory('crazyflie'), + 'config', + 'camera_config.yaml' + ) + + # create messages and publishers + self.image_mgs = Image() + self.camera_info_msg = self._construct_from_yaml(config_path) + self.image_publisher = self.create_publisher(Image, image_topic, 10) + self.info_publisher = self.create_publisher(CameraInfo, info_topic, 10) + + # TODO: just for testing, needs to be moved + self.info_publisher.publish(self.camera_info_msg) + + # set up connection to AI Deck + deck_ip = "192.168.4.1" + deck_port = '5000' + self.client_socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + self.client_socket.connect((deck_ip, deck_port)) + self.image = None + self.rx_buffer = bytearray() + + # set up timers for callbacks + timer_period = 0.5 + self.rx_timer = self.create_timer(timer_period, self.receive_callback) + self.tx_timer = self.create_timer(timer_period, self.publish_callback) + + + def _construct_from_yaml(self, path): + camera_info = CameraInfo() + with open(path) as f: + config = yaml.load(f, Loader=yaml.FullLoader) + + camera_info.header.frame_id = config['camera_name'] + camera_info.header.stamp = self.get_clock().now().to_msg() + camera_info.width = int(config['image_width']) + camera_info.height = int(config['image_height']) + camera_info.distortion_model = config['distortion_model'] + camera_info.d = config['distortion_coefficients']['data'] + camera_info.k = config['camera_matrix']['data'] + camera_info.r = config['rectification_matrix']['data'] + camera_info.p = config['projection_matrix']['data'] + return camera_info + + def _rx_bytes(self, size): + data = bytearray() + while len(data) < size: + data.extend(self.client_socket.recv(size-len(data))) + return data + + def receive_callback(self): + # first get the info + packetInfoRaw = self._rx_bytes(4) + [length, routing, function] = struct.unpack('{:02X})".format(length, src, dst)) + chunk = self._rx_bytes(length - 2) + imgStream.extend(chunk) + + raw_img = np.frombuffer(imgStream, dtype=np.uint8) + raw_img.shape = (width, height) + self.image = cv2.cvtColor(raw_img, cv2.COLOR_BayerBG2RGBA) + + else: # otherwise set image to None again + self.image = None + + def publish_callback(self): + if self.image is not None: + self.image_mgs.header.frame_id = self.camera_info_msg.header.frame_id + self.image_mgs.header.stamp = self.get_clock().now().to_msg() + self.camera_info_msg.header.stamp = self.image_mgs.header.stamp + + self.image_mgs.height = self.camera_info_msg.height + self.image_mgs.width = self.camera_info_msg.width + self.image_mgs.encoding = 'rgba8' + self.image_mgs.step = self.image.step + self.image_mgs.is_bigendian = 0 # TODO: implement automatic check depending on system + self.image_mgs.data = self.image.data + + self.image_publisher.publish(self.image_mgs) + self.info_publisher.publish(self.camera_info_msg) + self.image = None + + + +def main(args=None): + rclpy.init(args=args) + node = ImageNode() + rclpy.spin(node) + + node.destroy_node() + rclpy.shutdown() + +if __name__ == "__main__": + main() \ No newline at end of file From 9d9ec2636054b97392b595176c28efcde058c8c8 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Tue, 6 Feb 2024 16:38:44 +0100 Subject: [PATCH 082/162] watchdog bugfix --- crazyflie/scripts/gui.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/crazyflie/scripts/gui.py b/crazyflie/scripts/gui.py index 9bc434aad..9a7d4b9e5 100755 --- a/crazyflie/scripts/gui.py +++ b/crazyflie/scripts/gui.py @@ -198,7 +198,7 @@ def on_status(self, msg, name) -> None: self.robotmodels[name].status_ok = status_ok # store the time when we last received any status - self.robotmodels[name].status_watchdog[name] = time.time() + self.robotmodels[name].status_watchdog = time.time() def on_tab_change(self, arg): for name, robotmodel in self.robotmodels.items(): From 9efb8ed7df87ca16eaa55ee1c31dec27b4240bdd Mon Sep 17 00:00:00 2001 From: phanfeld Date: Tue, 6 Feb 2024 16:58:35 +0100 Subject: [PATCH 083/162] working implementation of image publisher --- crazyflie/src/image_streamer.py | 37 +++++++++++++++++---------------- 1 file changed, 19 insertions(+), 18 deletions(-) diff --git a/crazyflie/src/image_streamer.py b/crazyflie/src/image_streamer.py index ed5ce88ee..204d824eb 100644 --- a/crazyflie/src/image_streamer.py +++ b/crazyflie/src/image_streamer.py @@ -56,7 +56,7 @@ def __init__(self): ) # create messages and publishers - self.image_mgs = Image() + self.image_msg = Image() self.camera_info_msg = self._construct_from_yaml(config_path) self.image_publisher = self.create_publisher(Image, image_topic, 10) self.info_publisher = self.create_publisher(CameraInfo, info_topic, 10) @@ -66,14 +66,16 @@ def __init__(self): # set up connection to AI Deck deck_ip = "192.168.4.1" - deck_port = '5000' + deck_port = 5000 + print("Connecting to socket on {}:{}...".format(deck_ip, deck_port)) self.client_socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM) self.client_socket.connect((deck_ip, deck_port)) + print("Socket connected") self.image = None self.rx_buffer = bytearray() # set up timers for callbacks - timer_period = 0.5 + timer_period = 0.01 self.rx_timer = self.create_timer(timer_period, self.receive_callback) self.tx_timer = self.create_timer(timer_period, self.publish_callback) @@ -123,24 +125,23 @@ def receive_callback(self): raw_img = np.frombuffer(imgStream, dtype=np.uint8) raw_img.shape = (width, height) self.image = cv2.cvtColor(raw_img, cv2.COLOR_BayerBG2RGBA) - - else: # otherwise set image to None again - self.image = None + # else: # otherwise set image to None again + # self.image = None def publish_callback(self): if self.image is not None: - self.image_mgs.header.frame_id = self.camera_info_msg.header.frame_id - self.image_mgs.header.stamp = self.get_clock().now().to_msg() - self.camera_info_msg.header.stamp = self.image_mgs.header.stamp - - self.image_mgs.height = self.camera_info_msg.height - self.image_mgs.width = self.camera_info_msg.width - self.image_mgs.encoding = 'rgba8' - self.image_mgs.step = self.image.step - self.image_mgs.is_bigendian = 0 # TODO: implement automatic check depending on system - self.image_mgs.data = self.image.data - - self.image_publisher.publish(self.image_mgs) + self.image_msg.header.frame_id = self.camera_info_msg.header.frame_id + self.image_msg.header.stamp = self.get_clock().now().to_msg() + self.camera_info_msg.header.stamp = self.image_msg.header.stamp + width, height, channels = self.image.shape + self.image_msg.height = height + self.image_msg.width = width + self.image_msg.encoding = 'rgba8' + self.image_msg.step = width * channels # number of bytes each row in the array will occupy + self.image_msg.is_bigendian = 0 # TODO: implement automatic check depending on system + self.image_msg.data = self.image.flatten().data + + self.image_publisher.publish(self.image_msg) self.info_publisher.publish(self.camera_info_msg) self.image = None From 597e943b330f813122430988f899329587f99405 Mon Sep 17 00:00:00 2001 From: phanfeld Date: Wed, 7 Feb 2024 09:45:19 +0100 Subject: [PATCH 084/162] correct camera calibration --- crazyflie/config/camera_config.yaml | 48 +++++------------------------ crazyflie/src/image_streamer.py | 5 +-- 2 files changed, 9 insertions(+), 44 deletions(-) diff --git a/crazyflie/config/camera_config.yaml b/crazyflie/config/camera_config.yaml index 2c801c64a..69527384f 100644 --- a/crazyflie/config/camera_config.yaml +++ b/crazyflie/config/camera_config.yaml @@ -1,17 +1,17 @@ -image_width: 725 -image_height: 500 +image_width: 324 +image_height: 324 camera_name: crazyflie camera_matrix: rows: 3 cols: 3 - data: [383.76372, 0. , 363.38408, - 0. , 381.38288, 271.61177, + data: [181.87464, 0. , 162.52301, + 0. , 182.58129, 160.79418, 0. , 0. , 1. ] distortion_model: plumb_bob distortion_coefficients: rows: 1 cols: 5 - data: [-0.001747, -0.009650, -0.002608, -0.002890, 0.000000] + data: [-0.070366, -0.006434, -0.002691, -0.001983, 0.000000] rectification_matrix: rows: 3 cols: 3 @@ -21,38 +21,6 @@ rectification_matrix: projection_matrix: rows: 3 cols: 4 - data: [380.19111, 0. , 360.28396, 0. , - 0. , 380.987 , 270.48483, 0. , - 0. , 0. , 1. , 0. ] - - - -# image_width: 533 -# image_height: 320 -# camera_name: hoverair -# camera_matrix: -# rows: 3 -# cols: 3 -# data: [295.21347, 0. , 284.02365, -# 0. , 294.30945, 196.91373, -# 0. , 0. , 1. ] -# distortion_model: plumb_bob -# distortion_coefficients: -# rows: 1 -# cols: 5 -# data: [0.029797, -0.026754, 0.000635, -0.001295, 0.000000] -# rectification_matrix: -# rows: 3 -# cols: 3 -# data: [1., 0., 0., -# 0., 1., 0., -# 0., 0., 1.] -# projection_matrix: -# rows: 3 -# cols: 4 -# data: [297.20145, 0. , 283.47583, 0. , -# 0. , 296.96598, 197.18161, 0. , -# 0. , 0. , 1. , 0. ] - - - + data: [169.24555, 0. , 161.54541, 0. , + 0. , 169.97813, 159.07974, 0. , + 0. , 0. , 1. , 0. ] \ No newline at end of file diff --git a/crazyflie/src/image_streamer.py b/crazyflie/src/image_streamer.py index 204d824eb..6f831895e 100644 --- a/crazyflie/src/image_streamer.py +++ b/crazyflie/src/image_streamer.py @@ -19,7 +19,7 @@ def __init__(self): # declare topic names self.declare_parameter( name="image_topic", - value="/camera/image", + value="/image", descriptor=ParameterDescriptor( type=ParameterType.PARAMETER_STRING, description="Image topic to publish to.", @@ -61,9 +61,6 @@ def __init__(self): self.image_publisher = self.create_publisher(Image, image_topic, 10) self.info_publisher = self.create_publisher(CameraInfo, info_topic, 10) - # TODO: just for testing, needs to be moved - self.info_publisher.publish(self.camera_info_msg) - # set up connection to AI Deck deck_ip = "192.168.4.1" deck_port = 5000 From 6d1495b659278836f2524ff276e9779ee8a995fa Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Wed, 7 Feb 2024 16:39:12 +0100 Subject: [PATCH 085/162] server cpp: improve handling of crashed CF When connecting two CFs and turning on off, the unicast connection of the other one essentially froze. There were two reasons: 1.) Division by zero caused a crash; 2.) The crazyflie_link_cpp essentially starved one connection. Fixes #419. --- crazyflie/deps/crazyflie_tools | 2 +- crazyflie/src/crazyflie_server.cpp | 8 +++++--- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/crazyflie/deps/crazyflie_tools b/crazyflie/deps/crazyflie_tools index 36ea3d401..4b6255529 160000 --- a/crazyflie/deps/crazyflie_tools +++ b/crazyflie/deps/crazyflie_tools @@ -1 +1 @@ -Subproject commit 36ea3d40161db8f580dbb8846789bc036a2ccedd +Subproject commit 4b6255529698e421f802b020eabeafd63b14be66 diff --git a/crazyflie/src/crazyflie_server.cpp b/crazyflie/src/crazyflie_server.cpp index 4a71e0245..07734ed32 100644 --- a/crazyflie/src/crazyflie_server.cpp +++ b/crazyflie/src/crazyflie_server.cpp @@ -828,9 +828,11 @@ class CrazyflieROS } auto stats = cf_.connectionStatsDelta(); - float ack_rate = stats.sent_count / stats.ack_count; - if (ack_rate < min_ack_rate_) { - RCLCPP_WARN(logger_, "Ack rate: %.1f %%", ack_rate * 100); + if (stats.ack_count > 0) { + float ack_rate = stats.sent_count / stats.ack_count; + if (ack_rate < min_ack_rate_) { + RCLCPP_WARN(logger_, "Ack rate: %.1f %%", name_.c_str(), ack_rate * 100); + } } if (publish_stats_) { From 6762111d07b8090dbbd76175d11030b4d1e36ca1 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Wed, 7 Feb 2024 16:41:25 +0100 Subject: [PATCH 086/162] update submodule --- crazyflie/deps/crazyflie_tools | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/crazyflie/deps/crazyflie_tools b/crazyflie/deps/crazyflie_tools index 4b6255529..0ad0c3d79 160000 --- a/crazyflie/deps/crazyflie_tools +++ b/crazyflie/deps/crazyflie_tools @@ -1 +1 @@ -Subproject commit 4b6255529698e421f802b020eabeafd63b14be66 +Subproject commit 0ad0c3d791e2220d5ca832bd6d7f8a2fd3d5149f From fcb287a75f376fa7614003ddbee67562d4be6e63 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Wed, 7 Feb 2024 16:43:07 +0100 Subject: [PATCH 087/162] update submodule --- crazyflie/deps/crazyflie_tools | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/crazyflie/deps/crazyflie_tools b/crazyflie/deps/crazyflie_tools index 0ad0c3d79..32218e742 160000 --- a/crazyflie/deps/crazyflie_tools +++ b/crazyflie/deps/crazyflie_tools @@ -1 +1 @@ -Subproject commit 0ad0c3d791e2220d5ca832bd6d7f8a2fd3d5149f +Subproject commit 32218e7429651a681edf573d2ec24006fb07591e From b3271b992670b84ea63454cc69b791335f9e3979 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Wed, 7 Feb 2024 17:00:55 +0100 Subject: [PATCH 088/162] fix regression caused by augmenting cf_dict to contain "all" --- crazyflie/scripts/crazyflie_server.py | 32 ++++++++++++++------------- 1 file changed, 17 insertions(+), 15 deletions(-) diff --git a/crazyflie/scripts/crazyflie_server.py b/crazyflie/scripts/crazyflie_server.py index ac7882d15..a38dd6808 100755 --- a/crazyflie/scripts/crazyflie_server.py +++ b/crazyflie/scripts/crazyflie_server.py @@ -364,7 +364,8 @@ def _fully_connected(self, link_uri): self.swarm.fully_connected_crazyflie_cnt += 1 - if self.swarm.fully_connected_crazyflie_cnt == len(self.cf_dict): + # use len(self.cf_dict) - 1, since cf_dict contains "all" as well + if self.swarm.fully_connected_crazyflie_cnt == len(self.cf_dict) - 1: self.get_logger().info("All Crazyflies are fully connected!") self._init_parameters() self._init_logging() @@ -707,38 +708,39 @@ def _parameters_callback(self, params): for param in params: param_split = param.name.split(".") - if param_split[0] in self.cf_dict.values(): - cf_name = param_split[0] + if param_split[0] == "all": if param_split[1] == "params": name_param = param_split[2] + "." + param_split[3] try: - self.swarm._cfs[self.uri_dict[cf_name]].cf.param.set_value( - name_param, param.value - ) + for link_uri in self.uris: + cf = self.swarm._cfs[link_uri].cf.param.set_value( + name_param, param.value + ) self.get_logger().info( - f"[{self.uri_dict[cf_name]}] {name_param} is set to {param.value}" + f"[{self.cf_dict[link_uri]}] {name_param} is set to {param.value}" ) return SetParametersResult(successful=True) except Exception as e: self.get_logger().info(str(e)) return SetParametersResult(successful=False) - if param_split[1] == "logs": - return SetParametersResult(successful=True) - elif param_split[0] == "all": + elif param_split[0] in self.cf_dict.values(): + cf_name = param_split[0] if param_split[1] == "params": name_param = param_split[2] + "." + param_split[3] try: - for link_uri in self.uris: - cf = self.swarm._cfs[link_uri].cf.param.set_value( - name_param, param.value - ) + self.swarm._cfs[self.uri_dict[cf_name]].cf.param.set_value( + name_param, param.value + ) self.get_logger().info( - f"[{self.cf_dict[link_uri]}] {name_param} is set to {param.value}" + f"[{self.uri_dict[cf_name]}] {name_param} is set to {param.value}" ) return SetParametersResult(successful=True) except Exception as e: self.get_logger().info(str(e)) return SetParametersResult(successful=False) + if param_split[1] == "logs": + return SetParametersResult(successful=True) + return SetParametersResult(successful=False) From 6b14385737483b51d6f52cc552402e7a06a488cb Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Thu, 8 Feb 2024 21:34:53 +0100 Subject: [PATCH 089/162] do not launch gui automatically --- crazyflie/launch/launch.py | 9 --------- 1 file changed, 9 deletions(-) diff --git a/crazyflie/launch/launch.py b/crazyflie/launch/launch.py index 624ae65fd..8a9290c11 100644 --- a/crazyflie/launch/launch.py +++ b/crazyflie/launch/launch.py @@ -134,13 +134,4 @@ def generate_launch_description(): "use_sim_time": True, }] ), - Node( - package='crazyflie', - executable='gui.py', - name='gui', - output='screen', - parameters=[{ - "use_sim_time": True, - }] - ), ]) From 62fc28f4ddb996a1983cf93942a3dcf928f1bd1d Mon Sep 17 00:00:00 2001 From: phanfeld Date: Fri, 9 Feb 2024 12:29:50 +0100 Subject: [PATCH 090/162] loading all parameters from config file --- crazyflie/CMakeLists.txt | 1 + ...amera_config.yaml => aideck_streamer.yaml} | 4 ++ .../aideck_streamer.py} | 64 +++++++++++-------- 3 files changed, 44 insertions(+), 25 deletions(-) rename crazyflie/config/{camera_config.yaml => aideck_streamer.yaml} (86%) rename crazyflie/{src/image_streamer.py => scripts/aideck_streamer.py} (79%) diff --git a/crazyflie/CMakeLists.txt b/crazyflie/CMakeLists.txt index c8899cfbe..de8eaf697 100644 --- a/crazyflie/CMakeLists.txt +++ b/crazyflie/CMakeLists.txt @@ -109,6 +109,7 @@ install(PROGRAMS scripts/vel_mux.py scripts/cfmult.py scripts/simple_mapper_multiranger.py + scripts/aideck_streamer.py DESTINATION lib/${PROJECT_NAME} ) diff --git a/crazyflie/config/camera_config.yaml b/crazyflie/config/aideck_streamer.yaml similarity index 86% rename from crazyflie/config/camera_config.yaml rename to crazyflie/config/aideck_streamer.yaml index 69527384f..280ba9163 100644 --- a/crazyflie/config/camera_config.yaml +++ b/crazyflie/config/aideck_streamer.yaml @@ -1,3 +1,7 @@ +image_topic: /camera/image +camera_info_topic: /camera/camera_info +deck_ip: "192.168.4.1" +deck_port: 5000 image_width: 324 image_height: 324 camera_name: crazyflie diff --git a/crazyflie/src/image_streamer.py b/crazyflie/scripts/aideck_streamer.py similarity index 79% rename from crazyflie/src/image_streamer.py rename to crazyflie/scripts/aideck_streamer.py index 6f831895e..c97df2960 100644 --- a/crazyflie/src/image_streamer.py +++ b/crazyflie/scripts/aideck_streamer.py @@ -1,3 +1,4 @@ +#!/usr/bin/env python3 import socket,os,struct, time import numpy as np import cv2 @@ -12,14 +13,28 @@ from rcl_interfaces.msg import ParameterDescriptor, ParameterType -class ImageNode(rclpy.node.Node): +class ImageStreamerNode(Node): def __init__(self): super().__init__("image_node") + # declare config path parameter + self.declare_parameter( + name="config_path", + value=os.path.join( + get_package_share_directory('crazyflie'), + 'config', + 'aideck_streamer.yaml' + ) + ) + + config_path = self.get_parameter("config_path").value + with open(config_path) as f: + config = yaml.load(f, Loader=yaml.FullLoader) + # declare topic names self.declare_parameter( name="image_topic", - value="/image", + value=config["image_topic"], descriptor=ParameterDescriptor( type=ParameterType.PARAMETER_STRING, description="Image topic to publish to.", @@ -28,46 +43,49 @@ def __init__(self): self.declare_parameter( name="camera_info_topic", - value="/camera/camera_info", + value=config["camera_info_topic"], descriptor=ParameterDescriptor( type=ParameterType.PARAMETER_STRING, description="Camera info topic to subscribe to.", ), ) - # update topic names from config + # declare aideck ip and port + self.declare_parameter( + name='deck_ip', + value=config['deck_ip'], + ) + + self.declare_parameter( + name='deck_port', + value=config['deck_port'], + ) + + # define variables from ros2 parameters image_topic = ( - self.get_parameter("image_topic").get_parameter_value().string_value + self.get_parameter("image_topic").value ) self.get_logger().info(f"Image topic: {image_topic}") info_topic = ( - self.get_parameter("camera_info_topic").get_parameter_value().string_value + self.get_parameter("camera_info_topic").value ) self.get_logger().info(f"Image info topic: {info_topic}") - - # load camera parameters from yaml - # TODO: could possibly be done in the same way as with the other parameters - config_path = os.path.join( - get_package_share_directory('crazyflie'), - 'config', - 'camera_config.yaml' - ) # create messages and publishers self.image_msg = Image() - self.camera_info_msg = self._construct_from_yaml(config_path) + self.camera_info_msg = self._construct_from_yaml(config) self.image_publisher = self.create_publisher(Image, image_topic, 10) self.info_publisher = self.create_publisher(CameraInfo, info_topic, 10) # set up connection to AI Deck - deck_ip = "192.168.4.1" - deck_port = 5000 - print("Connecting to socket on {}:{}...".format(deck_ip, deck_port)) + deck_ip = self.get_parameter("deck_ip").value + deck_port = int(self.get_parameter("deck_port").value) + self.get_logger().info("Connecting to socket on {}:{}...".format(deck_ip, deck_port)) self.client_socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM) self.client_socket.connect((deck_ip, deck_port)) - print("Socket connected") + self.get_logger().info("Socket connected") self.image = None self.rx_buffer = bytearray() @@ -77,10 +95,8 @@ def __init__(self): self.tx_timer = self.create_timer(timer_period, self.publish_callback) - def _construct_from_yaml(self, path): + def _construct_from_yaml(self, config): camera_info = CameraInfo() - with open(path) as f: - config = yaml.load(f, Loader=yaml.FullLoader) camera_info.header.frame_id = config['camera_name'] camera_info.header.stamp = self.get_clock().now().to_msg() @@ -122,8 +138,6 @@ def receive_callback(self): raw_img = np.frombuffer(imgStream, dtype=np.uint8) raw_img.shape = (width, height) self.image = cv2.cvtColor(raw_img, cv2.COLOR_BayerBG2RGBA) - # else: # otherwise set image to None again - # self.image = None def publish_callback(self): if self.image is not None: @@ -146,7 +160,7 @@ def publish_callback(self): def main(args=None): rclpy.init(args=args) - node = ImageNode() + node = ImageStreamerNode() rclpy.spin(node) node.destroy_node() From 172938185a506b0271e2420d36f4630980a3e024 Mon Sep 17 00:00:00 2001 From: phanfeld Date: Fri, 9 Feb 2024 13:31:37 +0100 Subject: [PATCH 091/162] script needs to be executable --- crazyflie/scripts/aideck_streamer.py | 0 1 file changed, 0 insertions(+), 0 deletions(-) mode change 100644 => 100755 crazyflie/scripts/aideck_streamer.py diff --git a/crazyflie/scripts/aideck_streamer.py b/crazyflie/scripts/aideck_streamer.py old mode 100644 new mode 100755 From 668c8d9dcf466559bf67ae055aef09c30bdd8042 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Fri, 9 Feb 2024 14:25:45 +0100 Subject: [PATCH 092/162] server [all]: offer all/emergency service last as a "finished" indicator * In all backends, move the service announcement of all/emergency to be the last service * Add logic to wait for the server in gui.py * Enable gui.py by default and disable rviz by default --- crazyflie/launch/launch.py | 10 ++++ crazyflie/scripts/crazyflie_server.py | 18 +++--- crazyflie/scripts/gui.py | 57 +++++++++++++++---- crazyflie/src/crazyflie_server.cpp | 27 ++++----- crazyflie_py/crazyflie_py/crazyflie.py | 2 + .../crazyflie_sim/crazyflie_server.py | 20 ++++--- 6 files changed, 93 insertions(+), 41 deletions(-) diff --git a/crazyflie/launch/launch.py b/crazyflie/launch/launch.py index 8a9290c11..7676e175d 100644 --- a/crazyflie/launch/launch.py +++ b/crazyflie/launch/launch.py @@ -71,6 +71,8 @@ def generate_launch_description(): return LaunchDescription([ DeclareLaunchArgument('backend', default_value='cpp'), DeclareLaunchArgument('debug', default_value='False'), + DeclareLaunchArgument('rviz', default_value='False'), + DeclareLaunchArgument('gui', default_value='True'), Node( package='motion_capture_tracking', executable='motion_capture_tracking_node', @@ -125,6 +127,7 @@ def generate_launch_description(): parameters=server_params ), Node( + condition=LaunchConfigurationEquals('rviz', 'True'), package='rviz2', namespace='', executable='rviz2', @@ -134,4 +137,11 @@ def generate_launch_description(): "use_sim_time": True, }] ), + Node( + condition=LaunchConfigurationEquals('gui', 'True'), + package='crazyflie', + namespace='', + executable='gui.py', + name='gui', + ), ]) diff --git a/crazyflie/scripts/crazyflie_server.py b/crazyflie/scripts/crazyflie_server.py index a38dd6808..90c476313 100755 --- a/crazyflie/scripts/crazyflie_server.py +++ b/crazyflie/scripts/crazyflie_server.py @@ -218,14 +218,6 @@ def __init__(self): " or if your script have proper access to a Crazyradio PA") exit() - # Create services for the entire swarm and each individual crazyflie - self.create_service(Empty, "all/emergency", self._emergency_callback) - self.create_service(Takeoff, "all/takeoff", self._takeoff_callback) - self.create_service(Land, "all/land", self._land_callback) - self.create_service(GoTo, "all/go_to", self._go_to_callback) - self.create_service( - StartTrajectory, "all/start_trajectory", self._start_trajectory_callback) - for uri in self.cf_dict: if uri == "all": continue @@ -294,6 +286,16 @@ def __init__(self): self._poses_changed, qos_profile ) + # Create services for the entire swarm and each individual crazyflie + self.create_service(Takeoff, "all/takeoff", self._takeoff_callback) + self.create_service(Land, "all/land", self._land_callback) + self.create_service(GoTo, "all/go_to", self._go_to_callback) + self.create_service( + StartTrajectory, "all/start_trajectory", self._start_trajectory_callback) + + # This is the last service to announce and can be used to check if the server is fully available + self.create_service(Empty, "all/emergency", self._emergency_callback) + def _init_default_logblocks(self, prefix, link_uri, list_logvar, global_logging_enabled, topic_type): """ Prepare default logblocks as defined in crazyflies.yaml diff --git a/crazyflie/scripts/gui.py b/crazyflie/scripts/gui.py index 9a7d4b9e5..086d6d315 100755 --- a/crazyflie/scripts/gui.py +++ b/crazyflie/scripts/gui.py @@ -6,6 +6,7 @@ from functools import partial import rclpy +from std_srvs.srv import Empty from geometry_msgs.msg import Twist from rcl_interfaces.msg import Log from rclpy.executors import ExternalShutdownException @@ -18,7 +19,7 @@ from crazyflie_interfaces.msg import Status import rowan -from nicegui import Client, app, events, ui, ui_run +from nicegui import Client, app, events, ui, ui_run, Tailwind class NiceGuiNode(Node): @@ -26,6 +27,10 @@ class NiceGuiNode(Node): def __init__(self) -> None: super().__init__('nicegui') + # wait until the crazyflie_server is up and running + self.emergencyService = self.create_client(Empty, 'all/emergency') + self.emergencyService.wait_for_service() + # find all crazyflies self.cfnames = [] for srv_name, srv_types in self.get_service_names_and_types(): @@ -49,6 +54,9 @@ def __init__(self) -> None: self.radio_labels = dict() self.robotmodels = dict() + self.normal_style = Tailwind().text_color('black').font_weight('normal') + self.red_style = Tailwind().text_color('red-600').font_weight('bold') + with Client.auto_index_client: with ui.row().classes('items-stretch'): @@ -60,7 +68,11 @@ def __init__(self) -> None: self.robotmodels[name] = robot # augment with some additional fields robot.status_ok = False + robot.battery_ok = False robot.status_watchdog = time.time() + robot.supervisor_text = "" + robot.battery_text = "" + robot.radio_text = "" scene.camera.x = 0 scene.camera.y = -1 scene.camera.z = 2 @@ -111,7 +123,8 @@ def on_rosout(self, msg: Log) -> None: def on_timer(self) -> None: for name, robotmodel in self.robotmodels.items(): ros_time = rclpy.time.Time() # get the latest - robot_status_ok = robotmodel.status_ok + robot_status_ok = robotmodel.status_ok and robotmodel.battery_ok + robot_status_text = "" if self.tf_buffer.can_transform("world", name, ros_time): t = self.tf_buffer.lookup_transform( "world", @@ -122,6 +135,7 @@ def on_timer(self) -> None: # latest transform is older than a second indicates a problem if transform_age.nanoseconds * 1e-9 > 1: robot_status_ok = False + robot_status_text += "old transform; " else: pos = t.transform.translation robotmodel.move(pos.x, pos.y, pos.z) @@ -133,10 +147,20 @@ def on_timer(self) -> None: else: # no available transform indicates a problem robot_status_ok = False + robot_status_text += "unavailable transform; " # no status update for a while, indicate a problem if time.time() - robotmodel.status_watchdog > 2.0: robot_status_ok = False + robot_status_text += "no recent status update; " + + self.supervisor_labels[name].set_text(robot_status_text) + self.battery_labels[name].set_text("N.A.") + self.radio_labels[name].set_text("N.A.") + else: + self.supervisor_labels[name].set_text(robot_status_text + robotmodel.supervisor_text) + self.battery_labels[name].set_text(robotmodel.battery_text) + self.radio_labels[name].set_text(robotmodel.radio_text) # any issues detected -> mark red, otherwise green if robot_status_ok: @@ -144,6 +168,11 @@ def on_timer(self) -> None: else: robotmodel.material('#ff0000') + if robotmodel.battery_ok: + self.normal_style.apply(self.battery_labels[name]) + else: + self.red_style.apply(self.battery_labels[name]) + def on_vis_click(self, e: events.SceneClickEventArguments): hit = e.hits[0] name = hit.object_name or hit.object_id @@ -155,6 +184,7 @@ def on_vis_click(self, e: events.SceneClickEventArguments): def on_status(self, msg, name) -> None: status_ok = True + is_flying = False supervisor_text = "" if msg.supervisor_info & Status.SUPERVISOR_INFO_CAN_BE_ARMED: supervisor_text += "can be armed; " @@ -166,17 +196,21 @@ def on_status(self, msg, name) -> None: supervisor_text += "can fly; " if msg.supervisor_info & Status.SUPERVISOR_INFO_IS_FLYING: supervisor_text += "is flying; " + is_flying = True if msg.supervisor_info & Status.SUPERVISOR_INFO_IS_TUMBLED: - supervisor_text += "is tumpled; " + supervisor_text += "is tumbled; " status_ok = False if msg.supervisor_info & Status.SUPERVISOR_INFO_IS_LOCKED: supervisor_text += "is locked; " status_ok = False - self.supervisor_labels[name].set_text(supervisor_text) + self.robotmodels[name].supervisor_text = supervisor_text battery_text = f'{msg.battery_voltage:.2f} V' - if msg.battery_voltage < 3.8: - status_ok = False + battery_ok = True + # TODO (WH): We could read the voltage limits from the firmware (parameter) or crazyflies.yaml + # In the firmware, anything below 3.2 is warning, anything below 3.0 is critical + if (is_flying and msg.battery_voltage < 3.2) or (not is_flying and msg.battery_voltage < 3.8): + battery_ok = False if msg.pm_state == Status.PM_STATE_BATTERY: battery_text += " (on battery)" elif msg.pm_state == Status.PM_STATE_CHARGING: @@ -185,17 +219,18 @@ def on_status(self, msg, name) -> None: battery_text += " (charged)" elif msg.pm_state == Status.PM_STATE_LOW_POWER: battery_text += " (low power)" - status_ok = False + battery_ok = False elif msg.pm_state == Status.PM_STATE_SHUTDOWN: battery_text += " (shutdown)" - status_ok = False - self.battery_labels[name].set_text(battery_text) - + battery_ok = False + self.robotmodels[name].battery_text = battery_text + radio_text = f'{msg.rssi} dBm; Unicast: {msg.num_rx_unicast} / {msg.num_tx_unicast}; Broadcast: {msg.num_rx_broadcast} / {msg.num_tx_broadcast}' - self.radio_labels[name].set_text(radio_text) + self.robotmodels[name].radio_text = radio_text # save status here self.robotmodels[name].status_ok = status_ok + self.robotmodels[name].battery_ok = battery_ok # store the time when we last received any status self.robotmodels[name].status_watchdog = time.time() diff --git a/crazyflie/src/crazyflie_server.cpp b/crazyflie/src/crazyflie_server.cpp index b4e7e65ea..2e3688778 100644 --- a/crazyflie/src/crazyflie_server.cpp +++ b/crazyflie/src/crazyflie_server.cpp @@ -957,19 +957,6 @@ class CrazyflieServer : public rclcpp::Node callback_group_cf_srv_ = this->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive); - // topics for "all" - subscription_cmd_full_state_ = this->create_subscription("all/cmd_full_state", rclcpp::SystemDefaultsQoS(), std::bind(&CrazyflieServer::cmd_full_state_changed, this, _1), sub_opt_all_cmd); - - // services for "all" - auto service_qos = rmw_qos_profile_services_default; - - service_emergency_ = this->create_service("all/emergency", std::bind(&CrazyflieServer::emergency, this, _1, _2), service_qos, callback_group_all_srv_); - service_start_trajectory_ = this->create_service("all/start_trajectory", std::bind(&CrazyflieServer::start_trajectory, this, _1, _2), service_qos, callback_group_all_srv_); - service_takeoff_ = this->create_service("all/takeoff", std::bind(&CrazyflieServer::takeoff, this, _1, _2), service_qos, callback_group_all_srv_); - service_land_ = this->create_service("all/land", std::bind(&CrazyflieServer::land, this, _1, _2), service_qos, callback_group_all_srv_); - service_go_to_ = this->create_service("all/go_to", std::bind(&CrazyflieServer::go_to, this, _1, _2), service_qos, callback_group_all_srv_); - service_notify_setpoints_stop_ = this->create_service("all/notify_setpoints_stop", std::bind(&CrazyflieServer::notify_setpoints_stop, this, _1, _2), service_qos, callback_group_all_srv_); - // declare global params this->declare_parameter("all.broadcasts.num_repeats", 15); this->declare_parameter("all.broadcasts.delay_between_repeats_ms", 1); @@ -1070,6 +1057,20 @@ class CrazyflieServer : public rclcpp::Node param_subscriber_ = std::make_shared(this); cb_handle_ = param_subscriber_->add_parameter_event_callback(std::bind(&CrazyflieServer::on_parameter_event, this, _1)); + // topics for "all" + subscription_cmd_full_state_ = this->create_subscription("all/cmd_full_state", rclcpp::SystemDefaultsQoS(), std::bind(&CrazyflieServer::cmd_full_state_changed, this, _1), sub_opt_all_cmd); + + // services for "all" + auto service_qos = rmw_qos_profile_services_default; + + service_start_trajectory_ = this->create_service("all/start_trajectory", std::bind(&CrazyflieServer::start_trajectory, this, _1, _2), service_qos, callback_group_all_srv_); + service_takeoff_ = this->create_service("all/takeoff", std::bind(&CrazyflieServer::takeoff, this, _1, _2), service_qos, callback_group_all_srv_); + service_land_ = this->create_service("all/land", std::bind(&CrazyflieServer::land, this, _1, _2), service_qos, callback_group_all_srv_); + service_go_to_ = this->create_service("all/go_to", std::bind(&CrazyflieServer::go_to, this, _1, _2), service_qos, callback_group_all_srv_); + service_notify_setpoints_stop_ = this->create_service("all/notify_setpoints_stop", std::bind(&CrazyflieServer::notify_setpoints_stop, this, _1, _2), service_qos, callback_group_all_srv_); + + // This is the last service to announce and can be used to check if the server is fully available + service_emergency_ = this->create_service("all/emergency", std::bind(&CrazyflieServer::emergency, this, _1, _2), service_qos, callback_group_all_srv_); } diff --git a/crazyflie_py/crazyflie_py/crazyflie.py b/crazyflie_py/crazyflie_py/crazyflie.py index bbb7cbf2f..30c50dd27 100644 --- a/crazyflie_py/crazyflie_py/crazyflie.py +++ b/crazyflie_py/crazyflie_py/crazyflie.py @@ -717,6 +717,8 @@ class CrazyflieServer(rclpy.node.Node): def __init__(self): """Initialize the server. Waits for all ROS services before returning.""" super().__init__('CrazyflieAPI') + + # wait for server to be fully started self.emergencyService = self.create_client(Empty, 'all/emergency') self.emergencyService.wait_for_service() diff --git a/crazyflie_sim/crazyflie_sim/crazyflie_server.py b/crazyflie_sim/crazyflie_sim/crazyflie_server.py index 93dd698da..f34c556ef 100755 --- a/crazyflie_sim/crazyflie_sim/crazyflie_server.py +++ b/crazyflie_sim/crazyflie_sim/crazyflie_server.py @@ -91,15 +91,6 @@ def __init__(self): controller_name, self.backend.time) - # Create services for the entire swarm and each individual crazyflie - self.create_service(Empty, 'all/emergency', self._emergency_callback) - self.create_service(Takeoff, 'all/takeoff', self._takeoff_callback) - self.create_service(Land, 'all/land', self._land_callback) - self.create_service(GoTo, 'all/go_to', self._go_to_callback) - self.create_service(StartTrajectory, - 'all/start_trajectory', - self._start_trajectory_callback) - for name, _ in self.cfs.items(): pub = self.create_publisher( String, @@ -166,6 +157,17 @@ def __init__(self): 10 ) + # Create services for the entire swarm and each individual crazyflie + self.create_service(Takeoff, 'all/takeoff', self._takeoff_callback) + self.create_service(Land, 'all/land', self._land_callback) + self.create_service(GoTo, 'all/go_to', self._go_to_callback) + self.create_service(StartTrajectory, + 'all/start_trajectory', + self._start_trajectory_callback) + + # This is the last service to announce and can be used to check if the server is fully available + self.create_service(Empty, 'all/emergency', self._emergency_callback) + # step as fast as possible max_dt = 0.0 if 'max_dt' not in self._ros_parameters['sim'] \ else self._ros_parameters['sim']['max_dt'] From efe3ccb32d0bc9099b518b2c8d2524b19a3bc424 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Fri, 9 Feb 2024 14:26:59 +0100 Subject: [PATCH 093/162] enable simulation systemtests on all PRs --- .github/workflows/systemtests_sim.yml | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/.github/workflows/systemtests_sim.yml b/.github/workflows/systemtests_sim.yml index e30cd8fc7..75a84d912 100644 --- a/.github/workflows/systemtests_sim.yml +++ b/.github/workflows/systemtests_sim.yml @@ -2,7 +2,9 @@ name: System Tests Simulation on: push: - branches: [ "main", "feature-systemtests-sim-fixed-timestamp" ] + branches: [ main ] + pull_request: + branches: [ main ] # manual trigger workflow_dispatch: From 369075789f4cdd02f328fcd84b2953c486292943 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Fri, 9 Feb 2024 15:07:22 +0100 Subject: [PATCH 094/162] fix flake8 --- crazyflie_sim/crazyflie_sim/crazyflie_server.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/crazyflie_sim/crazyflie_sim/crazyflie_server.py b/crazyflie_sim/crazyflie_sim/crazyflie_server.py index f34c556ef..00ddfc33b 100755 --- a/crazyflie_sim/crazyflie_sim/crazyflie_server.py +++ b/crazyflie_sim/crazyflie_sim/crazyflie_server.py @@ -165,7 +165,8 @@ def __init__(self): 'all/start_trajectory', self._start_trajectory_callback) - # This is the last service to announce and can be used to check if the server is fully available + # This is the last service to announce. + # Can be used to check if the server is fully available. self.create_service(Empty, 'all/emergency', self._emergency_callback) # step as fast as possible From 034c4d2d770aef1a85eac26dd6582c1597346b57 Mon Sep 17 00:00:00 2001 From: ben-jarvis Date: Mon, 19 Feb 2024 17:33:19 +0100 Subject: [PATCH 095/162] Fix odom logging vz typo --- crazyflie/scripts/crazyflie_server.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/crazyflie/scripts/crazyflie_server.py b/crazyflie/scripts/crazyflie_server.py index 90c476313..b47c636af 100755 --- a/crazyflie/scripts/crazyflie_server.py +++ b/crazyflie/scripts/crazyflie_server.py @@ -543,7 +543,7 @@ def _log_odom_data_callback(self, timestamp, data, logconf, uri): pitch = radians(data.get('stabilizer.pitch')) vx = data.get('kalman.statePX') vy = data.get('kalman.statePY') - vz = data.get('kalman.statePY') + vz = data.get('kalman.statePZ') yawrate = data.get('gyro.z') rollrate = data.get('gyro.x') pitchrate = data.get('gyro.y') From c29f0e16fd48eb8669442c901ca48db295bbe431 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Wed, 21 Feb 2024 07:19:09 +0100 Subject: [PATCH 096/162] Docs: hint to explicitly build in release mode See also https://github.com/colcon/colcon-cmake/issues/96 --- .github/workflows/systemtests.yml | 2 +- .github/workflows/systemtests_sim.yml | 2 +- docs2/installation.rst | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/systemtests.yml b/.github/workflows/systemtests.yml index 1cae1631a..dc2d7f34d 100644 --- a/.github/workflows/systemtests.yml +++ b/.github/workflows/systemtests.yml @@ -30,7 +30,7 @@ jobs: run: | source /opt/ros/humble/setup.bash cd ros2_ws - colcon build --symlink-install + colcon build --symlink-install -DCMAKE_BUILD_TYPE=Release - name: Flight test id: step5 diff --git a/.github/workflows/systemtests_sim.yml b/.github/workflows/systemtests_sim.yml index 75a84d912..4ef5f583e 100644 --- a/.github/workflows/systemtests_sim.yml +++ b/.github/workflows/systemtests_sim.yml @@ -48,7 +48,7 @@ jobs: run: | source /opt/ros/humble/setup.bash cd ros2_ws - colcon build --symlink-install + colcon build --symlink-install -DCMAKE_BUILD_TYPE=Release - name: Flight test id: step6 diff --git a/docs2/installation.rst b/docs2/installation.rst index 325bb73f0..72bd74f8a 100644 --- a/docs2/installation.rst +++ b/docs2/installation.rst @@ -51,7 +51,7 @@ First Installation .. code-block:: bash cd ../ - colcon build --symlink-install + colcon build --symlink-install -DCMAKE_BUILD_TYPE=Release .. note:: symlink-install allows you to edit Python and config files without running `colcon build` every time. @@ -99,7 +99,7 @@ You can update your local copy using the following commands: git submodule sync git submodule update --init --recursive cd ../../ - colcon build --symlink-install + colcon build --symlink-install -DCMAKE_BUILD_TYPE=Release .. Once you have completed installation, From 0e15e749dfacd50aad8ddac0d86a038329345b31 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Wed, 21 Feb 2024 08:53:39 +0100 Subject: [PATCH 097/162] fix typo --- .github/workflows/systemtests.yml | 2 +- .github/workflows/systemtests_sim.yml | 2 +- docs2/installation.rst | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/systemtests.yml b/.github/workflows/systemtests.yml index dc2d7f34d..68f851ef5 100644 --- a/.github/workflows/systemtests.yml +++ b/.github/workflows/systemtests.yml @@ -30,7 +30,7 @@ jobs: run: | source /opt/ros/humble/setup.bash cd ros2_ws - colcon build --symlink-install -DCMAKE_BUILD_TYPE=Release + colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release - name: Flight test id: step5 diff --git a/.github/workflows/systemtests_sim.yml b/.github/workflows/systemtests_sim.yml index 4ef5f583e..439c4ad17 100644 --- a/.github/workflows/systemtests_sim.yml +++ b/.github/workflows/systemtests_sim.yml @@ -48,7 +48,7 @@ jobs: run: | source /opt/ros/humble/setup.bash cd ros2_ws - colcon build --symlink-install -DCMAKE_BUILD_TYPE=Release + colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release - name: Flight test id: step6 diff --git a/docs2/installation.rst b/docs2/installation.rst index 72bd74f8a..d9cf15381 100644 --- a/docs2/installation.rst +++ b/docs2/installation.rst @@ -51,7 +51,7 @@ First Installation .. code-block:: bash cd ../ - colcon build --symlink-install -DCMAKE_BUILD_TYPE=Release + colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release .. note:: symlink-install allows you to edit Python and config files without running `colcon build` every time. @@ -99,7 +99,7 @@ You can update your local copy using the following commands: git submodule sync git submodule update --init --recursive cd ../../ - colcon build --symlink-install -DCMAKE_BUILD_TYPE=Release + colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release .. Once you have completed installation, From 4bbe8ce98ad5ca291cfcd5a9184233242b09bae9 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Sat, 24 Feb 2024 23:23:51 +0100 Subject: [PATCH 098/162] dynamically update use_sim_time, depending on backend Fixes #438 --- crazyflie/launch/launch.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/crazyflie/launch/launch.py b/crazyflie/launch/launch.py index 7676e175d..bd958cd10 100644 --- a/crazyflie/launch/launch.py +++ b/crazyflie/launch/launch.py @@ -134,7 +134,7 @@ def generate_launch_description(): name='rviz2', arguments=['-d' + os.path.join(get_package_share_directory('crazyflie'), 'config', 'config.rviz')], parameters=[{ - "use_sim_time": True, + "use_sim_time": PythonExpression(["'", LaunchConfiguration('backend'), "' == 'sim'"]), }] ), Node( @@ -143,5 +143,8 @@ def generate_launch_description(): namespace='', executable='gui.py', name='gui', + parameters=[{ + "use_sim_time": PythonExpression(["'", LaunchConfiguration('backend'), "' == 'sim'"]), + }] ), ]) From dc7491e6bb85b34a74329e1966318aad9b3e6bd0 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Sun, 25 Feb 2024 22:00:43 +0100 Subject: [PATCH 099/162] crazyflie_examples: add launch.py --- crazyflie_examples/launch/launch.py | 50 +++++++++++++++++++++++++++++ docs2/usage.rst | 12 +++++++ 2 files changed, 62 insertions(+) create mode 100644 crazyflie_examples/launch/launch.py diff --git a/crazyflie_examples/launch/launch.py b/crazyflie_examples/launch/launch.py new file mode 100644 index 000000000..2b2e82e82 --- /dev/null +++ b/crazyflie_examples/launch/launch.py @@ -0,0 +1,50 @@ +import os + +from ament_index_python.packages import get_package_share_directory + + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration, PythonExpression +from launch_ros.actions import Node + + +def generate_launch_description(): + script = LaunchConfiguration('script') + backend = LaunchConfiguration('backend') + + script_launch_arg = DeclareLaunchArgument( + 'script' + ) + + backend_launch_arg = DeclareLaunchArgument( + 'backend', + default_value='cpp' + ) + + crazyflie = IncludeLaunchDescription( + PythonLaunchDescriptionSource([os.path.join( + get_package_share_directory('crazyflie'), 'launch'), + '/launch.py']), + launch_arguments={ + 'backend': backend, + }.items() + ) + + example_node = Node( + package='crazyflie_examples', + executable=script, + name=script, + parameters=[{ + 'use_sim_time': PythonExpression(["'", backend, "' == 'sim'"]), + }] + ) + + return LaunchDescription([ + script_launch_arg, + backend_launch_arg, + crazyflie, + example_node + ]) diff --git a/docs2/usage.rst b/docs2/usage.rst index 52117f0ae..74caf33d9 100644 --- a/docs2/usage.rst +++ b/docs2/usage.rst @@ -127,6 +127,12 @@ The configuration of the simulation (physics simulator, controller, etc.) can be Example: +.. code-block:: bash + + [terminal]$ ros2 launch crazyflie_examples launch.py script:=hello_world backend:=sim + +which is a short-hand for the following two commands: + .. code-block:: bash [terminal1]$ ros2 launch crazyflie launch.py backend:=sim @@ -156,6 +162,12 @@ You may run the script multiple times or different scripts while leaving the ser [terminal1]$ ros2 launch crazyflie launch.py [terminal2]$ ros2 run crazyflie_examples hello_world +If you only want to run a single script once, you can also use: + +.. code-block:: bash + + [terminal]$ ros2 launch crazyflie_examples launch.py script:=hello_world + Swarm Management ---------------- From d3a2ea85cca7233c7f124522a6720d20dd1967a6 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Wed, 6 Mar 2024 21:04:14 +0100 Subject: [PATCH 100/162] add latency to status --- crazyflie/scripts/gui.py | 2 +- crazyflie/src/crazyflie_server.cpp | 4 ++++ crazyflie_interfaces/msg/Status.msg | 1 + 3 files changed, 6 insertions(+), 1 deletion(-) diff --git a/crazyflie/scripts/gui.py b/crazyflie/scripts/gui.py index 086d6d315..a0f221b71 100755 --- a/crazyflie/scripts/gui.py +++ b/crazyflie/scripts/gui.py @@ -225,7 +225,7 @@ def on_status(self, msg, name) -> None: battery_ok = False self.robotmodels[name].battery_text = battery_text - radio_text = f'{msg.rssi} dBm; Unicast: {msg.num_rx_unicast} / {msg.num_tx_unicast}; Broadcast: {msg.num_rx_broadcast} / {msg.num_tx_broadcast}' + radio_text = f'{msg.rssi} dBm; Unicast: {msg.num_rx_unicast} / {msg.num_tx_unicast}; Broadcast: {msg.num_rx_broadcast} / {msg.num_tx_broadcast}; Latency: {msg.latency_unicast} ms' self.robotmodels[name].radio_text = radio_text # save status here diff --git a/crazyflie/src/crazyflie_server.cpp b/crazyflie/src/crazyflie_server.cpp index de21f2544..98e964fa0 100644 --- a/crazyflie/src/crazyflie_server.cpp +++ b/crazyflie/src/crazyflie_server.cpp @@ -816,6 +816,8 @@ class CrazyflieROS msg.num_tx_broadcast = deltaTxBc; previous_stats_broadcast_ = statsBc; + msg.latency_unicast = last_latency_in_ms_; + publisher_status_->publish(msg); // warnings @@ -896,6 +898,7 @@ class CrazyflieROS RCLCPP_WARN(logger_, "[%s] Latency: %.1f ms", name_.c_str(), latency_in_us / 1000.0); } last_on_latency_ = std::chrono::steady_clock::now(); + last_latency_in_ms_ = (uint16_t)(latency_in_us / 1000.0); } private: @@ -949,6 +952,7 @@ class CrazyflieROS // link statistics rclcpp::TimerBase::SharedPtr link_statistics_timer_; std::chrono::time_point last_on_latency_; + uint16_t last_latency_in_ms_; float warning_freq_; float max_latency_; float min_ack_rate_; diff --git a/crazyflie_interfaces/msg/Status.msg b/crazyflie_interfaces/msg/Status.msg index d7c2f2352..61494cc13 100644 --- a/crazyflie_interfaces/msg/Status.msg +++ b/crazyflie_interfaces/msg/Status.msg @@ -29,3 +29,4 @@ uint32 num_rx_broadcast # number of received broadcast packets during the last uint32 num_tx_broadcast # number of broadcast packets sent during the last period uint32 num_rx_unicast # number of received unicast packets during the last period uint32 num_tx_unicast # number of unicast packets sent during the last period +uint16 latency_unicast # latency (in ms) for unicast packets From ec415695e3662e19ceb2f07c0242f0a792e8daf5 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Wed, 6 Mar 2024 21:04:43 +0100 Subject: [PATCH 101/162] launch.py: disable joystick teleop by default --- crazyflie/launch/launch.py | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/crazyflie/launch/launch.py b/crazyflie/launch/launch.py index bd958cd10..f20f49550 100644 --- a/crazyflie/launch/launch.py +++ b/crazyflie/launch/launch.py @@ -87,11 +87,12 @@ def generate_launch_description(): name='teleop', remappings=[ ('emergency', 'all/emergency'), - ('takeoff', 'cf6/takeoff'), - ('land', 'cf6/land'), - ('cmd_vel_legacy', 'cf6/cmd_vel_legacy'), - ('cmd_full_state', 'cf6/cmd_full_state'), - ('notify_setpoints_stop', 'cf6/notify_setpoints_stop'), + ('takeoff', 'all/takeoff'), + ('land', 'all/land'), + # uncomment to manually control (and update teleop.yaml) + # ('cmd_vel_legacy', 'cf6/cmd_vel_legacy'), + # ('cmd_full_state', 'cf6/cmd_full_state'), + # ('notify_setpoints_stop', 'cf6/notify_setpoints_stop'), ], parameters=[teleop_params] ), From 6a9d1c396e8fa92bee7d2ade4855a9e422bd6da5 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Wed, 6 Mar 2024 21:05:07 +0100 Subject: [PATCH 102/162] server [cpp] log message improvements --- crazyflie/src/crazyflie_server.cpp | 22 +++++++++++++--------- 1 file changed, 13 insertions(+), 9 deletions(-) diff --git a/crazyflie/src/crazyflie_server.cpp b/crazyflie/src/crazyflie_server.cpp index 98e964fa0..a31a5e5e1 100644 --- a/crazyflie/src/crazyflie_server.cpp +++ b/crazyflie/src/crazyflie_server.cpp @@ -821,23 +821,23 @@ class CrazyflieROS publisher_status_->publish(msg); // warnings - if (msg.num_rx_unicast > msg.num_tx_unicast) { - RCLCPP_WARN(logger_, "Unexpected number of unicast packets. Sent: %d. Received: %d", msg.num_tx_unicast, msg.num_rx_unicast); + if (msg.num_rx_unicast > msg.num_tx_unicast * 1.05 /*allow some slack*/) { + RCLCPP_WARN(logger_, "[%s] Unexpected number of unicast packets. Sent: %d. Received: %d", name_.c_str(), msg.num_tx_unicast, msg.num_rx_unicast); } if (msg.num_tx_unicast > 0) { float unicast_receive_rate = msg.num_rx_unicast / (float)msg.num_tx_unicast; if (unicast_receive_rate < min_unicast_receive_rate_) { - RCLCPP_WARN(logger_, "Low unicast receive rate (%.2f < %.2f). Sent: %d. Received: %d", unicast_receive_rate, min_unicast_receive_rate_, msg.num_tx_unicast, msg.num_rx_unicast); + RCLCPP_WARN(logger_, "[%s] Low unicast receive rate (%.2f < %.2f). Sent: %d. Received: %d", name_.c_str(), unicast_receive_rate, min_unicast_receive_rate_, msg.num_tx_unicast, msg.num_rx_unicast); } } - if (msg.num_rx_broadcast > msg.num_tx_broadcast) { - RCLCPP_WARN(logger_, "Unexpected number of broadcast packets. Sent: %d. Received: %d", msg.num_tx_broadcast, msg.num_rx_broadcast); + if (msg.num_rx_broadcast > msg.num_tx_broadcast * 1.05 /*allow some slack*/) { + RCLCPP_WARN(logger_, "[%s] Unexpected number of broadcast packets. Sent: %d. Received: %d", name_.c_str(), msg.num_tx_broadcast, msg.num_rx_broadcast); } if (msg.num_tx_broadcast > 0) { float broadcast_receive_rate = msg.num_rx_broadcast / (float)msg.num_tx_broadcast; if (broadcast_receive_rate < min_broadcast_receive_rate_) { - RCLCPP_WARN(logger_, "Low broadcast receive rate (%.2f < %.2f). Sent: %d. Received: %d", broadcast_receive_rate, min_broadcast_receive_rate_, msg.num_tx_broadcast, msg.num_rx_broadcast); + RCLCPP_WARN(logger_, "[%s] Low broadcast receive rate (%.2f < %.2f). Sent: %d. Received: %d", name_.c_str(), broadcast_receive_rate, min_broadcast_receive_rate_, msg.num_tx_broadcast, msg.num_rx_broadcast); } } } @@ -871,7 +871,7 @@ class CrazyflieROS if (stats.ack_count > 0) { float ack_rate = stats.sent_count / stats.ack_count; if (ack_rate < min_ack_rate_) { - RCLCPP_WARN(logger_, "Ack rate: %.1f %%", name_.c_str(), ack_rate * 100); + RCLCPP_WARN(logger_, "[%s] Ack rate: %.1f %%", name_.c_str(), ack_rate * 100); } } @@ -895,7 +895,7 @@ class CrazyflieROS void on_latency(uint64_t latency_in_us) { if (latency_in_us / 1000.0 > max_latency_) { - RCLCPP_WARN(logger_, "[%s] Latency: %.1f ms", name_.c_str(), latency_in_us / 1000.0); + RCLCPP_WARN(logger_, "[%s] High latency: %.1f ms", name_.c_str(), latency_in_us / 1000.0); } last_on_latency_ = std::chrono::steady_clock::now(); last_latency_in_ms_ = (uint16_t)(latency_in_us / 1000.0); @@ -1361,11 +1361,15 @@ class CrazyflieServer : public rclcpp::Node // a) check if the rate was within specified bounds if (mocap_data_received_timepoints_.size() >= 2) { double mean_rate = 0; + double min_rate = std::numeric_limits::max(); + double max_rate = 0; int num_rates_wrong = 0; for (size_t i = 0; i < mocap_data_received_timepoints_.size() - 1; ++i) { std::chrono::duration diff = mocap_data_received_timepoints_[i+1] - mocap_data_received_timepoints_[i]; double rate = 1.0 / diff.count(); mean_rate += rate; + min_rate = std::min(min_rate, rate); + max_rate = std::max(max_rate, rate); if (rate <= mocap_min_rate_ || rate >= mocap_max_rate_) { num_rates_wrong++; } @@ -1373,7 +1377,7 @@ class CrazyflieServer : public rclcpp::Node mean_rate /= (mocap_data_received_timepoints_.size() - 1); if (num_rates_wrong > 0) { - RCLCPP_WARN(logger_, "[all] Motion capture rate off (#: %d, Avg: %.1f)", num_rates_wrong, mean_rate); + RCLCPP_WARN(logger_, "[all] Motion capture rate off (#: %d, Avg: %.1f, Min: %.1f, Max: %.1f)", num_rates_wrong, mean_rate, min_rate, max_rate); } } else if (mocap_enabled_) { // b) warn if no data was received From 1e8ef226cf47d5e72a7ee61cf3afbebd141a3a00 Mon Sep 17 00:00:00 2001 From: julienthevenoz <125280576+julienthevenoz@users.noreply.github.com> Date: Mon, 18 Mar 2024 12:17:59 +0100 Subject: [PATCH 103/162] Feature infinite flight (#444) * infinite flight example --- .../crazyflie_examples/infinite_flight.py | 89 +++++++++++++++++++ crazyflie_examples/setup.cfg | 1 + crazyflie_py/crazyflie_py/crazyflie.py | 35 +++++++- 3 files changed, 124 insertions(+), 1 deletion(-) create mode 100644 crazyflie_examples/crazyflie_examples/infinite_flight.py diff --git a/crazyflie_examples/crazyflie_examples/infinite_flight.py b/crazyflie_examples/crazyflie_examples/infinite_flight.py new file mode 100644 index 000000000..6aa94c6fb --- /dev/null +++ b/crazyflie_examples/crazyflie_examples/infinite_flight.py @@ -0,0 +1,89 @@ +#!/usr/bin/env python + +from pathlib import Path + +from crazyflie_py import Crazyswarm +from crazyflie_py.uav_trajectory import Trajectory +import numpy as np + + +def main(): + swarm = Crazyswarm() + timeHelper = swarm.timeHelper + allcfs = swarm.allcfs + + traj1 = Trajectory() + traj1.loadcsv(Path(__file__).parent / 'data/figure8.csv') + + TIMESCALE = 1.0 + for cf in allcfs.crazyflies: + cf.uploadTrajectory(0, 0, traj1) + timeHelper.sleep(1) + + # pm_state : 0 = on battery 1 = charging 2 = charged 3 = low power 4 = shutdown + flight_counter = 1 + + while True: + print('takeoff') + allcfs.takeoff(targetHeight=1.0, duration=2.0) + timeHelper.sleep(2.5) + for cf in allcfs.crazyflies: + pos = np.array(cf.initialPosition) + np.array([0, 0, 1.0]) + cf.goTo(pos, 0, 2.0) + timeHelper.sleep(2.5) + + # fly figure8 until battery is low + fig8_counter = 0 + status = allcfs.crazyflies[0].get_status() + # while status['battery'] > 3.8: + while status['pm_state'] == 0: + fig8_counter += 1 + print(f'starting figure8 number {fig8_counter} of flight number {flight_counter}') + allcfs.startTrajectory(0, timescale=TIMESCALE) + timeHelper.sleep(traj1.duration * TIMESCALE + 2.0) + status = allcfs.crazyflies[0].get_status() + print(f'pm state : {status["pm_state"]}, battery left : {status["battery"]}') + timeHelper.sleep(1) + + # not sure if useful + # check if pm = 3 just to be sure, if not abort test + if status['pm_state'] != 3: + print(f'power state is not 3 (low) but {status["pm_state"]}. Landing and aborting') + allcfs.land(targetHeight=0.06, duration=2.0) + timeHelper.sleep(3) + return 1 + + # now that battery is low, we try to land on the pad and see if it's charging + allcfs.land(targetHeight=0.06, duration=2.0) + timeHelper.sleep(5) + status = allcfs.crazyflies[0].get_status() + + # if not charging, take off and land back again until it charges + while status['pm_state'] != 1: + print('Not charging, retrying') + allcfs.takeoff(targetHeight=1.0, duration=2.0) + timeHelper.sleep(2.5) + for cf in allcfs.crazyflies: + pos = np.array(cf.initialPosition) + np.array([0, 0, 1.0]) + cf.goTo(pos, 0, 2.0) + timeHelper.sleep(2.5) + allcfs.land(targetHeight=0.06, duration=2.0) + timeHelper.sleep(5) + status = allcfs.crazyflies[0].get_status() + + # now we wait until the crazyflie is charged + # while status['battery'] < 4.1: + while status['pm_state'] != 2: + print(f'Charging in progress, battery at {status["battery"]}V') + timeHelper.sleep(60) + status = allcfs.crazyflies[0].get_status() + # check if it's still charging ###not sure if this check is useful + if status['pm_state'] != 1: + print(f'charging interrupted, pm state : {status["pm_state"]}') + + print('Charging finished, time to fly again') + flight_counter += 1 + + +if __name__ == '__main__': + main() diff --git a/crazyflie_examples/setup.cfg b/crazyflie_examples/setup.cfg index 0c0238812..f387d09cf 100644 --- a/crazyflie_examples/setup.cfg +++ b/crazyflie_examples/setup.cfg @@ -8,3 +8,4 @@ console_scripts = cmd_full_state = crazyflie_examples.cmd_full_state:main set_param = crazyflie_examples.set_param:main swap = crazyflie_examples.swap:main + infinite_flight = crazyflie_examples.infinite_flight:main diff --git a/crazyflie_py/crazyflie_py/crazyflie.py b/crazyflie_py/crazyflie_py/crazyflie.py index 30c50dd27..a1e39466d 100644 --- a/crazyflie_py/crazyflie_py/crazyflie.py +++ b/crazyflie_py/crazyflie_py/crazyflie.py @@ -14,7 +14,7 @@ # from .visualizer import visNull -from crazyflie_interfaces.msg import FullState, Position, TrajectoryPolynomialPiece +from crazyflie_interfaces.msg import FullState, Position, Status, TrajectoryPolynomialPiece from crazyflie_interfaces.srv import GoTo, Land,\ NotifySetpointsStop, StartTrajectory, Takeoff, UploadTrajectory from geometry_msgs.msg import Point @@ -136,6 +136,9 @@ def __init__(self, node, cfname, paramTypeDict): self.setParamsService = node.create_client( SetParameters, '/crazyflie_server/set_parameters') self.setParamsService.wait_for_service() + self.statusSubscriber = node.create_subscription( + Status, f'{self.prefix}/status', self.status_topic_callback, 10) + self.status = {} # Query some settings getParamsService = node.create_client(GetParameters, '/crazyflie_server/get_parameters') @@ -699,6 +702,36 @@ def cmdPosition(self, pos, yaw=0.): # self.setParam('ring/solidGreen', int(g * 255)) # self.setParam('ring/solidBlue', int(b * 255)) + def status_topic_callback(self, msg): + """ + Call back for topic /cfXXX/status. + + Update the status attribute every time a crazyflie_interfaces/msg/Status + message is published on the topic /cfXXX/status + """ + self.status = {'id': msg.header.frame_id, + 'timestamp_sec': msg.header.stamp.sec, + 'timestamp_nsec': msg.header.stamp.nanosec, + 'supervisor': msg.supervisor_info, + 'battery': msg.battery_voltage, + 'pm_state': msg.pm_state, + 'rssi': msg.rssi, + 'num_rx_broadcast': msg.num_rx_broadcast, + 'num_tx_broadcast': msg.num_tx_broadcast, + 'num_rx_unicast': msg.num_rx_unicast, + 'num_tx_unicast': msg.num_tx_unicast} + + def get_status(self): + """ + Return the status attribute. + + Status is a dictionary containing: + frame id, timestamp, supervisor info, battery voltage, pm state, rssi, nb of received or + transmitted broadcast or unicast messages. see crazyflie_interfaces/msg/Status for details + """ + # self.node.get_logger().info(f'Crazyflie.get_status() was called {self.status}') + return self.status + class CrazyflieServer(rclpy.node.Node): """ From ff3f67307505205e57c8b6c1857167944c902b60 Mon Sep 17 00:00:00 2001 From: julienthevenoz <125280576+julienthevenoz@users.noreply.github.com> Date: Wed, 3 Apr 2024 06:47:30 +0200 Subject: [PATCH 104/162] Fix systemtest (#464) * tuning delay --- systemtests/mcap_handler.py | 6 +++++- systemtests/plotter_class.py | 10 ++++++---- 2 files changed, 11 insertions(+), 5 deletions(-) diff --git a/systemtests/mcap_handler.py b/systemtests/mcap_handler.py index 5e55a8784..b5945a214 100644 --- a/systemtests/mcap_handler.py +++ b/systemtests/mcap_handler.py @@ -34,15 +34,19 @@ def typename(topic_name): def write_mcap_to_csv(self, inputbag:str, outputfile:str): '''A method which translates an .mcap rosbag file format to a .csv file. + Also modifies the timestamp to start at 0.0 instead of the wall time. Only written to translate the /tf topic but could easily be extended to other topics''' + t_start = None try: print("Translating .mcap to .csv") f = open(outputfile, 'w+') writer = csv.writer(f) for topic, msg, timestamp in self.read_messages(inputbag): if topic =="/tf": - t = msg.transforms[0].header.stamp.sec + msg.transforms[0].header.stamp.nanosec *10**(-9) + if t_start == None: + t_start = msg.transforms[0].header.stamp.sec + msg.transforms[0].header.stamp.nanosec *10**(-9) + t = msg.transforms[0].header.stamp.sec + msg.transforms[0].header.stamp.nanosec *10**(-9) - t_start writer.writerow([t, msg.transforms[0].transform.translation.x, msg.transforms[0].transform.translation.y, msg.transforms[0].transform.translation.z]) f.close() except FileNotFoundError: diff --git a/systemtests/plotter_class.py b/systemtests/plotter_class.py index 4b34d461c..af35a0cf4 100644 --- a/systemtests/plotter_class.py +++ b/systemtests/plotter_class.py @@ -23,11 +23,13 @@ def __init__(self, sim_backend = False): self.test_name = None self.SIM = sim_backend #indicates if we are plotting data from real life test or from a simulated test. Default is false (real life test) - self.EPSILON = 0.1 # euclidian distance in [m] between ideal and recorded trajectory under which the drone has to stay to pass the test (NB : epsilon is doubled for multi_trajectory test) + self.EPSILON = 0.15 # euclidian distance in [m] between ideal and recorded trajectory under which the drone has to stay to pass the test (NB : epsilon is doubled for multi_trajectory test) self.ALLOWED_DEV_POINTS = 0.05 #allowed percentage of datapoints whose deviation > EPSILON while still passing test (currently % for fig8 and 10% for mt) - self.DELAY_CONST_FIG8 = 4.75 #this is the delay constant which I found by adding up all the time.sleep() etc in the figure8.py file. + self.DELAY_CONST_FIG8 = 1.3 #4.75 #this is the delay constant which I found by adding up all the time.sleep() etc in the figure8.py file. + self.DELAY_CONST_MT = 5.5 if self.SIM : #It allows to temporally adjust the ideal and real trajectories on the graph. Could this be implemented in a better (not hardcoded) way ? - self.DELAY_CONST_FIG8 = -0.18 #for an unknown reason, the delay constant with the sim_backend is different + self.DELAY_CONST_FIG8 = -0.45 #for an unknown reason, the delay constants with the sim_backend is different + self.DELAY_CONST_MT = -0.3 self.ALTITUDE_CONST_FIG8 = 1 #this is the altitude given for the takeoff in figure8.py. I should find a better solution than a symbolic constant ? def file_guard(self, pdf_path): @@ -86,7 +88,7 @@ def read_csv_and_set_arrays(self, ideal_csvfile, rosbag_csvfile): delay = 0 if self.test_name == "fig8": delay = self.DELAY_CONST_FIG8 - elif self.test_name == "m_t": + elif self.test_name == "mt": delay = self.DELAY_CONST_MT for i in range(bag_arrays_size): From f54270244954be90f2f89127468cc77970003bcf Mon Sep 17 00:00:00 2001 From: Kimberly McGuire Date: Tue, 9 Apr 2024 21:08:48 +0200 Subject: [PATCH 105/162] Swarm flash utility (#456) * add flash as executable * manage flashing with simple zipfile * flash both zip as bins * works with absolute path * add flash to cfmultitool * flash target based only on file name * add missing variable --- crazyflie/CMakeLists.txt | 1 + crazyflie/scripts/cfmult.py | 22 +++++++++++-- crazyflie/scripts/flash.py | 61 +++++++++++++++++++++++++++++++++++++ 3 files changed, 81 insertions(+), 3 deletions(-) create mode 100755 crazyflie/scripts/flash.py diff --git a/crazyflie/CMakeLists.txt b/crazyflie/CMakeLists.txt index 8a2e4f378..352c472cb 100644 --- a/crazyflie/CMakeLists.txt +++ b/crazyflie/CMakeLists.txt @@ -111,6 +111,7 @@ install(PROGRAMS scripts/simple_mapper_multiranger.py scripts/aideck_streamer.py scripts/gui.py + scripts/flash.py DESTINATION lib/${PROJECT_NAME} ) diff --git a/crazyflie/scripts/cfmult.py b/crazyflie/scripts/cfmult.py index 9f1ee126c..e3beef82b 100755 --- a/crazyflie/scripts/cfmult.py +++ b/crazyflie/scripts/cfmult.py @@ -25,7 +25,8 @@ "version", "listLogVariables", "listParams", - "listMemories" + "listMemories", + "flash", } @@ -46,6 +47,9 @@ def main(): yaml_parser.add_argument("-C", "--configpath", default=Path(__file__).parent.parent.resolve() / "config", help="Path to the configuration *.yaml files") + + parser.add_argument("--file_name", help="File name for flashing the crazyflie", + type=str, default="") args = parser.parse_args() @@ -63,13 +67,25 @@ def main(): # Run for all URI's determined. for uri in uris: - cmd = [ + if args.subcommand[0] == "flash": + SUBPROC_TIMEOUT = 20 + cmd = [ "ros2", "run", "crazyflie", - *args.subcommand, + "flash.py", f"--uri={uri}", + f"--file_name={args.file_name}" ] + else: + SUBPROC_TIMEOUT = 1 + cmd = [ + "ros2", + "run", + "crazyflie", + *args.subcommand, + f"--uri={uri}", + ] print(f"{' '.join(cmd)}") subprocess.run(cmd, timeout=SUBPROC_TIMEOUT) diff --git a/crazyflie/scripts/flash.py b/crazyflie/scripts/flash.py new file mode 100755 index 000000000..af58e1d0b --- /dev/null +++ b/crazyflie/scripts/flash.py @@ -0,0 +1,61 @@ +#!/usr/bin/env python3 + +""" +A flash utility script to flash crazyflies with the latest or custom firmware + + 2024 - K. N. McGuire (Bitcraze AB) +""" + +import rclpy +from rclpy.node import Node +import cflib.crtp # noqa +from cflib.bootloader import Bootloader, Target +from cflib.bootloader.boottypes import BootVersion +import argparse +import os + +class Flash(Node): + def __init__(self, uri, file_name): + super().__init__('flash') + + self.get_logger().info(f"Flashing {uri} with {file_name}") + + base_file_name = os.path.basename(file_name) + + if base_file_name.endswith("zip") and base_file_name.startswith("firmware-cf2"): + targets = [] + elif base_file_name.endswith("bin") and base_file_name.startswith("cf2"): + targets = [Target("cf2", 'stm32', 'fw', [], [])] + else: + self.get_logger().error(f"Unsupported file type or name. Only cf2*.bin or firmware-cf2*.zip supported") + return + + bl = Bootloader(uri) + try: + bl.flash_full(None, file_name, True, targets) + except Exception as e: + self.get_logger().error(f"Failed to flash, Error {str(e)}") + finally: + if bl: + bl.close() + + return + +def main(args=None): + cflib.crtp.init_drivers() + rclpy.init(args=args) + parser = argparse.ArgumentParser(description="This is a sample script") + parser.add_argument('--uri', type=str, default="radio://0/80/2M/E7E7E7E7E7", help='unique resource identifier') + parser.add_argument('--file_name', type=str, default="cf2.bin", help='') + + # Parse the arguments + args = parser.parse_args() + + print("URI: ", args.uri) + flash_node = Flash(args.uri, args.file_name) + + flash_node.destroy_node() + rclpy.shutdown() + +if __name__ == '__main__': + main() \ No newline at end of file From bf00cb7688e6ba9c0e848e35f3d3d2e38f8e8def Mon Sep 17 00:00:00 2001 From: Kimberly McGuire Date: Tue, 9 Apr 2024 21:11:55 +0200 Subject: [PATCH 106/162] server yaml file substitute with temporary files (#454) * got external yaml file to be entered in launch * used python expression to choose parameter file * implement param load for mocap and teleop --- crazyflie/config/crazyflies.yaml | 4 +-- crazyflie/launch/launch.py | 44 +++++++++++++++++++------------- 2 files changed, 28 insertions(+), 20 deletions(-) diff --git a/crazyflie/config/crazyflies.yaml b/crazyflie/config/crazyflies.yaml index 5a49a0e0e..1c13f9ebd 100644 --- a/crazyflie/config/crazyflies.yaml +++ b/crazyflie/config/crazyflies.yaml @@ -3,7 +3,7 @@ robots: cf231: enabled: true uri: radio://0/80/2M/E7E7E7E7E7 - initial_position: [0, 0, 0] + initial_position: [0.0, 0.0, 0.0] type: cf21 # see robot_types # firmware_params: # kalman: @@ -17,7 +17,7 @@ robots: cf5: enabled: false uri: radio://0/80/2M/E7E7E7E705 - initial_position: [0, -0.5, 0] + initial_position: [0.0, -0.5, 0.0] type: cf21 # see robot_types # firmware_params: # kalman: diff --git a/crazyflie/launch/launch.py b/crazyflie/launch/launch.py index f20f49550..d5df4b37d 100644 --- a/crazyflie/launch/launch.py +++ b/crazyflie/launch/launch.py @@ -10,6 +10,7 @@ def generate_launch_description(): + # load crazyflies crazyflies_yaml = os.path.join( get_package_share_directory('crazyflie'), @@ -26,9 +27,11 @@ def generate_launch_description(): 'server.yaml') with open(server_yaml, 'r') as ymlfile: - server_yaml_contents = yaml.safe_load(ymlfile) + server_yaml_content = yaml.safe_load(ymlfile) - server_params = [crazyflies] + [server_yaml_contents["/crazyflie_server"]["ros__parameters"]] + server_yaml_content["/crazyflie_server"]["ros__parameters"]['robots'] = crazyflies['robots'] + server_yaml_content["/crazyflie_server"]["ros__parameters"]['robot_types'] = crazyflies['robot_types'] + server_yaml_content["/crazyflie_server"]["ros__parameters"]['all'] = crazyflies['all'] # robot description urdf = os.path.join( @@ -36,8 +39,9 @@ def generate_launch_description(): 'urdf', 'crazyflie_description.urdf') with open(urdf, 'r') as f: + robot_desc = f.read() - server_params[1]["robot_description"] = robot_desc + server_yaml_content["/crazyflie_server"]["ros__parameters"]["robot_description"] = robot_desc # construct motion_capture_configuration motion_capture_yaml = os.path.join( @@ -46,40 +50,44 @@ def generate_launch_description(): 'motion_capture.yaml') with open(motion_capture_yaml, 'r') as ymlfile: - motion_capture = yaml.safe_load(ymlfile) + motion_capture_content = yaml.safe_load(ymlfile) - motion_capture_params = motion_capture["/motion_capture_tracking"]["ros__parameters"] - motion_capture_params["rigid_bodies"] = dict() + motion_capture_content["/motion_capture_tracking"]["ros__parameters"]["rigid_bodies"] = dict() for key, value in crazyflies["robots"].items(): type = crazyflies["robot_types"][value["type"]] if value["enabled"] and type["motion_capture"]["enabled"]: - motion_capture_params["rigid_bodies"][key] = { + motion_capture_content["/motion_capture_tracking"]["ros__parameters"]["rigid_bodies"][key] = { "initial_position": value["initial_position"], "marker": type["motion_capture"]["marker"], "dynamics": type["motion_capture"]["dynamics"], } # copy relevent settings to server params - server_params[1]["poses_qos_deadline"] = motion_capture_params["topics"]["poses"]["qos"]["deadline"] + server_yaml_content["/crazyflie_server"]["ros__parameters"]["poses_qos_deadline"] = motion_capture_content[ + "/motion_capture_tracking"]["ros__parameters"]["topics"]["poses"]["qos"]["deadline"] - # teleop params - teleop_params = os.path.join( - get_package_share_directory('crazyflie'), - 'config', - 'teleop.yaml') + # Save server and mocap in temp file such that nodes can read it out later + with open('tmp_server.yaml', 'w') as outfile: + yaml.dump(server_yaml_content, outfile, default_flow_style=False, sort_keys=False) + + with open('tmp_motion_capture.yaml', 'w') as outfile: + yaml.dump(motion_capture_content, outfile, default_flow_style=False, sort_keys=False) return LaunchDescription([ DeclareLaunchArgument('backend', default_value='cpp'), DeclareLaunchArgument('debug', default_value='False'), DeclareLaunchArgument('rviz', default_value='False'), DeclareLaunchArgument('gui', default_value='True'), + DeclareLaunchArgument('server_yaml_file', default_value=''), + DeclareLaunchArgument('teleop_yaml_file', default_value=''), + DeclareLaunchArgument('mocap_yaml_file', default_value=''), Node( package='motion_capture_tracking', executable='motion_capture_tracking_node', condition=LaunchConfigurationNotEquals('backend','sim'), name='motion_capture_tracking', output='screen', - parameters=[motion_capture_params] + parameters= [PythonExpression(["'tmp_motion_capture.yaml' if '", LaunchConfiguration('mocap_yaml_file'), "' == '' else '", LaunchConfiguration('mocap_yaml_file'), "'"])], ), Node( package='crazyflie', @@ -94,7 +102,7 @@ def generate_launch_description(): # ('cmd_full_state', 'cf6/cmd_full_state'), # ('notify_setpoints_stop', 'cf6/notify_setpoints_stop'), ], - parameters=[teleop_params] + parameters= [PythonExpression(["'teleop.yaml' if '", LaunchConfiguration('teleop_yaml_file'), "' == '' else '", LaunchConfiguration('teleop_yaml_file'), "'"])], ), Node( package='joy', @@ -107,7 +115,7 @@ def generate_launch_description(): condition=LaunchConfigurationEquals('backend','cflib'), name='crazyflie_server', output='screen', - parameters=server_params + parameters= [PythonExpression(["'tmp_server.yaml' if '", LaunchConfiguration('server_yaml_file'), "' == '' else '", LaunchConfiguration('server_yaml_file'), "'"])], ), Node( package='crazyflie', @@ -115,7 +123,7 @@ def generate_launch_description(): condition=LaunchConfigurationEquals('backend','cpp'), name='crazyflie_server', output='screen', - parameters=server_params, + parameters= [PythonExpression(["'tmp_server.yaml' if '", LaunchConfiguration('server_yaml_file'), "' == '' else '", LaunchConfiguration('server_yaml_file'), "'"])], prefix=PythonExpression(['"xterm -e gdb -ex run --args" if ', LaunchConfiguration('debug'), ' else ""']), ), Node( @@ -125,7 +133,7 @@ def generate_launch_description(): name='crazyflie_server', output='screen', emulate_tty=True, - parameters=server_params + parameters= [PythonExpression(["'tmp_server.yaml' if '", LaunchConfiguration('server_yaml_file'), "' == '' else '", LaunchConfiguration('server_yaml_file'), "'"])], ), Node( condition=LaunchConfigurationEquals('rviz', 'True'), From 366c8e44cf1536b69c40d8c355d455f443112ffe Mon Sep 17 00:00:00 2001 From: JulienThevenozIMRC Date: Wed, 27 Mar 2024 12:20:55 +0100 Subject: [PATCH 107/162] Denis' plotting now more or less working --- systemtests/SDplotting_save.zip | Bin 0 -> 10078 bytes systemtests/cfusdlog.py | 126 +++++++++ systemtests/data_helper.py | 179 ++++++++++++ systemtests/info/info_cf231_.yaml | 5 + systemtests/logs/cf231_ | Bin 0 -> 85439 bytes systemtests/plot.py | 319 +++++++++++++++++++++ systemtests/reports/cf231_.pdf | Bin 0 -> 58244 bytes systemtests/save.py | 57 ++++ systemtests/settings.yaml | 447 ++++++++++++++++++++++++++++++ 9 files changed, 1133 insertions(+) create mode 100644 systemtests/SDplotting_save.zip create mode 100644 systemtests/cfusdlog.py create mode 100644 systemtests/data_helper.py create mode 100644 systemtests/info/info_cf231_.yaml create mode 100644 systemtests/logs/cf231_ create mode 100644 systemtests/plot.py create mode 100644 systemtests/reports/cf231_.pdf create mode 100644 systemtests/save.py create mode 100644 systemtests/settings.yaml diff --git a/systemtests/SDplotting_save.zip b/systemtests/SDplotting_save.zip new file mode 100644 index 0000000000000000000000000000000000000000..1a85fddaacfb400332b82a7ecd043fa1e792d136 GIT binary patch literal 10078 zcmbt)Ra6~YyXD5+-3cB%I0Sch4K5pZcMtAP@Zhc+4-nkl-QC^klY9Gg|M!l29{%pH z#*%udIjd^D%rU>IC<6hB3HVcN9;GXOiTxj$K)7;t1OqOn z_dz3AVoD^g6n?$V+s&qN($N9nLK%xyJ6uvLG~&BOG};EW+fgRNFG3THHV&WkX%A*O z1QBj0vkUS+qf}a&zP*8<bDTB)p*pNt8nT_birEx_m+o-d%K6;WF)42GR9$VKkgX!$*6W;%mP)f7x= zt+edqx`+=;XRSAltDR(rv9(Txuh6$TR6!K_wf%LJw_ptZbdxN5BAjKk8;_&<(nBtb zsYDG4hb^;1pvu`Jn&~)s&aT}toarPPVZ(h7ULap%UfzN{$MCxTm6Fd`DZ^8)#jPuj zBrKP_psrA|jb+(-3Jo+Purh?&1c^KYv&J*;xb=m1+pS+5VOkT7hj<8Wr)T! zT#zW%gb0|dg(drRm(a^H8$}dbNL*Ec#aZi2;*2=*j^m`s*Zq!bxfzTk?8e55U+_MM}dS4?3h(>IBzlP$9 z$CoM0r|NVzwT;XsDH)7p&-WNc_bNN7Hp!gT#WhWam#t32x|1ztVPLl3!Tt~uTCIz>W&KX(9n zabt0o>a5eh6IzA-m}Vu_w}B2{wj;*68Vej#d2j>}m$v!EOv}{++m2d2j}Lg3FaB*G zHe=o#us&&hK1CkF=w(1!KL8Dx8U8y+HV7lAoFqMMK32<-m@tQEngLuta3cijd=%>O zXB z-Uv>119cg&joRsd3gZ>%%dQ4@NAR!*G;i9deFH8%r3W@7eED*!WY(q|7Ox#wzY&0> z;%VS3PpXA4VQuisDXq>Rh8=Ze+6YM;$x9_UkvV1tChj?pD|e_QEu{CRKx@!af&E8( zBk?eT3SGdZcX_P}Wz7QG36cD%SS)w6v3#TM` zWF^wo7wVTyKqc8(i1>tBa__R~MZU!ixb|oVf8p6TT(m>@M2r8s{jj`P7 z@Wb$>)_bez9kU-qI3zQ5HG{Ldd|t>rNRv<9Ls2C5p)`-qkscOn{s05?!d}7lLNCpf zKA{doiM-#Cc7cJX0vM2Mx0Y6+HMi~ayyU;}I~rn*uClrqctSqV)&lTrX?eLg_;}pTKg-W(^Lxj5=j&Y3 z9L-wrM=Uols2DtXj#cBPJs(qs+{1NmHxiQ3GL%O~kXU#(0fLtafe_^vJZYLk$6f#>Ay^q+F5Gj85!nASW%{(VP~Wb*Wgh4|WfJI&f(lkVDX;0q;GIf|+4ug5`Dkdf0vp=@-l-o28MlnR?k*dXqx+NbT)$+@1{Q z0V}}jvc3fO1nXyU+&*WtzMMupj`etB{D=VczK#372kvKqsLyoy7j8A?qsG9c2K=j) z@nd<|g3@c&*eT*H`&cZ@-h_h7UH$sf1j1u!gPtD;!-?_v@VI$ZmsmOLLl_<+F(UO z;W@eXs^itbdi6wOpkK=mY+z2ERtUWo*=||auT%eP^ywXr0(m`u3YFsTLpDc}-+Yix zDs{sX0N!3md#oUTcUh^n4r38K1tK0P_}yPPVHWs4ne^KQY-? zAVYVXOE&P`WkdD_+vHrF(gR)HRTf_qs7T<5mFADRiONSPmFSKf5Q~4f(1j-U)YS zJT%Qpim_d7Dda^k&3~W7_lTcGI``d0Z*V>BQ?TRu_y#hk;s>016qQR9ylx)WH}-P3 ztOpy*jz=a%85r1w_hqa!H~`>}?)y)f`QH`c2oeCm^v{aW*wn?z#M;j6-xY-}>N0ja zgJ@KrrHjn9d}Gc$C=MMMtpttFctYu+*ZT$&c(?mg2&LACaN!^$))KgjB<1Sa^$0Lg z1v9k$*GS@md`3U}k#+_z?4s&FG%rP~%q5+rgBhj2l~g^K9b4742DNaj1a$hn?U|V} z(hdtG$G$6Hw)<0KPAcwc=F!ga-f4d4-?Ipsb&!@bd9G!AxpfFRW_zo2oP~C@Gz};&3Fp;Z12Ke>V{M=nNOG~vY05s>Z|x- zH^_wsmNyDVL$15f^u&D?=$oU2&LV)wmDgA!6$=BgZU3^}e$Zl_k=e2x9Q7^P445%v zhP9t*n{G;n>k!IEO)ZSrbI@l*k|e&yK#hx88D#3QagKdKnti9k&sEP&=lUyGn{YAD zpq(bL3n4N;P8e3KI2ExmN?>n;0)sR6XGhfC?zKabyWR1 z_mLBUq6Ju;SrjDScIIOH1pFYbCK@RdWKb@h^@7_Qe{DEKe0uI@c>oonC%6hEQ2LY^ zk#GT;R~W*K&0jDv*RyIs_&S`+&?KK7w75u5v0~&^bb_JNrkgMeLoURH0Ody1OM|-L z){fSPYn#gFwkgk-+fqQs2Ih<@42^3RfCzqkUt`8nxm9w~vLzLuh?Cbw4%UtOJ>da- zUn!WA46;a0(EgKc`iYOTGK>fbS)P%!QdmMghWmH^!Cs`X^{|)C1StZ10C0MTU>`Oq z*OTe8eG^f|2|TAYP3du!ZKcM-V>#a&YwHssQMlw|n4x&@A z`c03Aa4i&^V;#iDg4lff;PB(JuE|Pm+VT{npZr732sCI|e+5!2RUZ^Dg}R9b_W**d zqVqYxqD@QJedX}I3RL~%e68l_pp@U<4C|LIsUXO$MGUfIwYTQxe3Cc4r4DB0rh*lO{s0wh&g zt6v&u-vl3@?D|k1PA6H`u3v`?U!crG^Q%I-96FaxPF3b7d9|e)W?m=yYwC)6evCyD z!JR8c5!7JaQU|LK5L5=GZ266W!lZhMizZEyT9b_ec5$v84qjP~e-Tab_mfh&CyXTR z+%&%dXcAYYU2UDEx|VT)bB^oG{$ODx=3c3#zc`BWMaG=Wr9w=)fG?QL=f}28yf}z` z&qvF=OEbDbpyyRNuau5`>d5eF?nDPF$;z5>ntaOZo||i&g3_H8>qOIjCrPF=oOQGq z`)%J2o>TB?pgQ6bu6CQi9b@B*Kr_uX>FRmr_rAEVQb44wJwj`o9;cEb2rwuz`bJt2 zCRFf_oCgHU%(L6{!^eC7H~5=w3>gilvb=p;Vhh6Jm}g?RlS|wt3U7F4Sjs?E>Sec< zTKv+~V=UB5czISLUkt8J?;Tc39qu3%7{BT*v>%dU%c6aWlIC2>SOritGGNhSc}lw3 z%F;4uJXMoy=v+zzpW{15ClLpyRfU$4?_pdjBuXV=Myk6U#ee=x0sE$9DGzFJ@XQRK zW<&5qeAYS@62K{>UY=bT6~&tvoX_3oqKl$oRiYavfiYGg8yEYQ6kX@+dba*RKkk?B z?~1KKefSxMRWRK2=W5J!D&KC(hSEFJ@G1j*7RkZOusgB$gwzJX<_ochVP-V8e=Jl3 zAyctfSIj4~ToXgB=`A>)#EAnYtx4+2vOZ zZXr+Zx$LPv>FqV{O73v7%qLq^pqv}c_1EtJlMEW(jfV=LU1JO0k5&E7$lrji@0#(h zR_3AWpU#ubzw-wZ8;=OCPGg(I64N%_@4z&n4_y&Pk%(lYP~qFx0}jh~*av;S^Lv!| zdt>plvVQBS=+xNob?6knaRlON@Q-r8HVsO!rru~o?0Pw52F)GCY<-nrPv5{B?hu^y z{fX3ivQtXc&!UHkkQ&+a0;ny2@B&xIaPOZ&^uF&b8Nk1w%6S*KoYCjM?wLYWz~%bx z38o|3J9Cm_YinyX*Xj=L0ylg+a!{~J-}4(*0wdD^(m6A+xK_Q~fnI9C!n#INx1v4v z9$8+Ot1-LZl3^U)4e-5-7|~DFt;!Gj_2fgizI1@c_syY*6P4k&aSsWS>qMSu?~)sb z+Zp4kbd^i6{Ml^9$*A*fn^gspj~1q$_d}qu;U-G0NAMUvTZT+6F=9H&N#+upJW9(+ zq$bXRJ)v=h1GFs;xkPVzyg);iN{PFDboh+@$}y{!=XMkyBmkcv=8QYf>-TmNjDIPD z8}5m{1X#0*D{=o1fv6ddgZrm_PwP!N>HUIxE*6a9+#dtn_hYD47*VeF9ISg(*`eNF zH6_Gg$PsoBbxJn3aVMy{&pieT31?#F5`6bjcVa4o5eh!(LFTC*b?J(3 z5A;{k;7M_$C~-1??Npr7YQD_5)k*`06n@ZiG-G9G`gDG$Do#I6%+P@!2AP($w#I$? zK5bKSQVKN}>>)l<;z?V~53WT_F(j!`+k246!bBoBle;jxsvyG}@(jrara`uK0cTzj zxL4MC+0(sU2A}3P40g<<_9m_{6lRn^gV%M|G_$2WG(X|YW8ZlO0NQI1FY}tz`fj!8 zw%mD(m?Ad(POkI^zv18%O^9;Y_6~p8gL*<8^T@=b@)<8`FjiPFQjvBb?&oP_0dKj= zTy=Q(6j@sf;kF(>(9wIr>`kV?x8uMl#RW8pDgwjAO<;Kw_<;DMmZqP3hihR0fIph( ze^yJC!~g)xKdYrbmY=?*i?s#N_TLpug;X&+w> zF5Xvt?kL5csP{(op*O4^Ur9baxqPSl3U8)!R+rtHUmHB{=A3Tk%EB^nZW3>`rZchl zWt!uONM+yYSGWA9JuI)nEOeEQ3i~Xxbq)7@#kF*|5#F}qh!^wt6UJNGugUA%<76tU z@SN`NXe*_yb8Akk&Z&=tOuT`}bvmLgY@bOONa((@yG>QzJf&i}y(=zhIcUVFuPvYB zciarnvMFw)=;sr57AwR8-YJ>Q&-{IDw#WLCfGNwTXzlW>nB=o-D%M6^q6lv?rm&}ZyrVt za#5=reHo7FXRjg;1-fH`g+;XPS5prsLqn0#Ub8BM|(n)_kEzfxPmEG17iN|OEqSySH*Kfr4(C+zX%je=l z0cTM=s~M7~fE5HCflJOAhp%t#86 zrkEZ6cD6q+fwQ9Yfi}m|M0(|P#x_M2c@+~$E=jDcdx*nJ>5kZYtFqjob!apa^wVT~ z!wn!~j`0ykj$yG7`V1w07OP=*#vdzc`7L!UjJe-K6k_2A5E&v^(UBzS$C7SnCS<}3 zIY10Do_f;=O5ET4ccoPWcHt?Qkc?jV#Nr2253awr?g63Py(^Jdg^|{nLt1lyVXQ!vP2Rwg1yuVDgw-)>M zLTd4cPJ~4aoLVakRR?}pyiE+fFU+_;O&sQYjK0g%eZUl-1rSq7@mNvo6|~&!sR6zD zlX*GuuF`~D<;HKld6a!vri&%3-!G<1^+O)%W*o{IkV#$cMsd?|Fy-RwxkJy|8;LR+ zj3L@CZdYqgVdOVE&S8iMjnBvXe`91$VPrDXb3jZX5l*>696OeA@#rG3Gbtv-|MH50~JCIk4816r~ufyPKuJAt_bsBiYe10ff~ z7~`=>#dwHWRX)sx;wrRJH>-DFyZ1`66Y?=wq7J~fPM4)#nn@8XfYwEnn%v`3%Nwx= zZQAz`O%^D;ogz4jys0si?TnDJkkpi;l_&DSIEmAu&#MKJ+tCGpr|+sACS4937i>XX z3&a;ww@q^$TnGDUT^k~1+}S5vTnE$8 zO=9YF1fazh7%W*!eg!O7R22Rir2=j4hY?JLbMA3Oon3w_pK)O*rqcqs>GxI-?wRpQ+~s?Wft(3njmh9&ZT|0e6tVnMsC zzSzMI>tqmBQUFELP${$HkSh|F30wh*vXD89gG@w6c*0%D-ri4s!4!&vU{SJ}{t)a? zP_zMH4h%!Fi(eQg+xG0rcA_95H^l%jN{wZ*(p<8sWYKgYV!Sz*u>6vPxpxQP?9=j2 zD05ec)YF#31-C3M%H5cO8E8SQPAi5`*d(ykN6-ALpMD!#Zy#a=$Z3n>nhY7uob;Fl z@If+Piv^rYtXm%jUXry#EbjG;X7O`;Ip7Gl*exJ{T++xa-W{o{Y)3P)nIP)Jd-OTX zUJLlHO7eNHX|RBu!al~dBt#uZmrH9cRapupHxVpDeV%^y7#!q?0pmb1q{|6iwqF-~c+ZtWofuhMq?sIIGx2Q-va^YQU2jzgfUI+8*t#Wx=fy?~}^R18=5P ztp`E7zH1wVMsFV*v%NqMlHD*u!Hk_ptvrsCwc^*d3x3`<316%syTl>sa0pGI$}*_N zkbGNgW(D5$(a|(-41L2^YQ>%<+^t2f5jB6^JxM9`?Zq%y&tVa`axDRhl1Kvx0}NgZ zX(9uS!a2l;QHaYQyaZ$MQ{(`B3*R9BfyLF%(HsBY_?#H1vcGyjq!?I_t9j3c4myZ+ zT-$(z{zAJhF&^Jg*vaR9r-%lJ6m?Fv_#SB$c-i=Q1H;>P&0*xQT8rl1IL@V<_93@(?Lg=NAiq^T0Z=RXuGbMRYN8N-!XFnMTY{$fOjco76A^8H>+*?DhzNQ6J?zoj4*d8Yt zlNcFrOeaZxV$ooBjb7-#Gx)?Jc_Ts<@aiZ0g5_QAKU+SDB={0=9Z&m?e4`&A2UZtL zy#i#1`VfE?tl084+Adb&D?0=BD&Rf7k$_=W8Aj>~`Vv3&9rE^fkPb9b_$W=MQrJj6 zvn=ZguM`JL-(sqFCm)h^(hFS)Kz`5fJA`K() zs)O`e(k%Ns@BTBw>rE^R+x^tjX17$VNPl_ph*~h|?><%r#%$Z#ioq4@w?XL_?1@2I z{!iuZ;_6p$TB*|=oD+ksPr(%#W+rRA3<&eD8iVCx>PCLU`xHC-KY{$+%Y!AZ>&U(q-g%o{McmK0jL9R0p01 zOz18N;~4v0I9V_UZ~e)yV_|ZRBJn_PbvYNOrbd!7auUY^ofR!*gA{f70lZx7YMMc2 z@Iyu4K7DBM6%3bWmQU^!|(Yg4nS(n5fy?e@P z{3YsI)QivDgqz-e3FLN?bUeE=mQIEfOyqge=xm59Qq?Lt&MlbLBth~NRJ*)s?}T7V z@@+>oWIf{R_Ow8>ovijiWfRDSF;iaql7_(k2qqY}aTp<4Cx>`)xbG5A3inRh*Tuo% zN9lAgKH=%GdV*+LvWVV&$wAT9d^5ZtHa!MaK#UwYS(!X#anyt|$w=9S9dR3>912~y zKHFwWInz+ddZD}vC#BzHAg?_d9?@Y8GMNa78wV6<1{jOMuipHjwyZ5A4 zw{ygu2=;MZqYB6wz?=>vOQ0B3_kFb#!SccLOGHNb%G>v7(VNS?trF` z7{*p>cN)~&n?Nk}?R3c1W-6}>HOOsjyT_tKWu~ ztbDTl5&4ast5q& z{mnbMs8bG!mK8~~Zlv#^u7UdaFisAd$}|ktcA% z5jGql6~B=t4~p(wCFt5Yaap%%L%gDNo7Y{his)k9w&Ly#LK^ktcIqcl{aPAP7?b4I z?L7N!VW63Du5#U|3c||Tk7W~1WUN2=Z#i9 zQ}$UY{%%cwS9KxH$TT=K)$n93DY|-k5!pWYYw8|-P!!Y1@V9Pl;mT(zA?nrw+q?~I zPt{rY{G4|?({xV)OFW*mM_~GJ-G>XiSNc(ojv968Rd}fq14wI1(kTiu2CP!9NcfrqQp`W7UQ4o4rf?knEFR_%^iOlWQ8C|*VvB%={v26zE zS*L!NJ#$pOgM3>~Q&rNiPpcUz4ozI-_60jdzFj7|iGa#NZl>mJvB3tiR^*3}PR-d{ z-i(~3sI4O^HOz~4Vw$QYgRlFy)Wn)(b=mLgl46WFPmY%fwFWxO(!*Zgv9uI+5@{Qw z+sbY!r~1FFqxchhXPP|OM4{|(tX)nM9Wq=@H`ytCfc9@09stzBq0e1yPJ}0_&d@`N zCZ4V#8iUX1{BrL^FlZ%7T>bF8k+Okw3gBRG{DBYdjC{k^gjriM3bzVYm0z1SYV4!5 zQL=mm0~3hqxqSj7U0SOMaJDmToT}m47&q|?wpz2i2!i6>^V6U zJ@FN{NWdBj$Jt)T^u=?WB8dl99lBpZcG}2dr$0J*h>p(=4!~dC_eyOu6;S7%3gW*r zg+FLq@5|#l1XKx8-y!pbA_&5kkrgq$r!0@JG|s@FCw;)*eOc0Joln5JUPyW!Gpk5m zbm!LcszwdDu_GO-6Xx(hpdZ9R;dxAYNP37O0M3~V-PoyDvb=44!2B^y-Y=p@L8t)0 zA8SNW1`He%;-5oNe}|;rg#PUQt%%hB1^(AO(;t{WA*sLXO-Smm?Y{v3dy%RCB>B5V z_OH#eKcT6=t05r!pGp3oB2<6>x4)VH)rk7jocp^P0&3v@@$>#)TXp}P{9h0BkJt5g hH3Y0<{3H4Qhx4T<0|otu1M07f9UK6_p!{?9zW`Du*3JL` literal 0 HcmV?d00001 diff --git a/systemtests/cfusdlog.py b/systemtests/cfusdlog.py new file mode 100644 index 000000000..fedc807e7 --- /dev/null +++ b/systemtests/cfusdlog.py @@ -0,0 +1,126 @@ +# -*- coding: utf-8 -*- +""" +Helper to decode binary logged sensor data from crazyflie2 with uSD-Card-Deck. + +Source: https://github.com/IMRCLab/crazyflie-firmware/blob/master/tools/usdlog/cfusdlog.py + +MIT License + +Copyright (c) 2021 Intelligent Multi-Robot Coordination Lab @ TU Berlin, Germany + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +""" +import argparse +from zlib import crc32 +import struct +import numpy as np + +# extract null-terminated string +def _get_name(data, idx): + endIdx = idx + while data[endIdx] != 0: + endIdx = endIdx + 1 + return data[idx:endIdx].decode("utf-8"), endIdx + 1 + +def decode(filename): + # read file as binary + with open(filename, 'rb') as f: + data = f.read() + + # check magic header + if data[0] != 0xBC: + print("Unsupported format!") + return + + # check CRC + crc = crc32(data[0:-4]) + expected_crc, = struct.unpack('I', data[-4:]) + if crc != expected_crc: + print("WARNING: CRC does not match!") + + # check version + version, num_event_types = struct.unpack('HH', data[1:5]) + if version != 1 and version != 2: + print("Unsupported version!", version) + return + + result = dict() + event_by_id = dict() + + # read header with data types + idx = 5 + for _ in range(num_event_types): + event_id, = struct.unpack('H', data[idx:idx+2]) + idx += 2 + event_name, idx = _get_name(data, idx) + result[event_name] = dict() + result[event_name]["timestamp"] = [] + num_variables, = struct.unpack('H', data[idx:idx+2]) + idx += 2 + fmtStr = "<" + variables = [] + for _ in range(num_variables): + var_name_and_type, idx = _get_name(data, idx) + var_name = var_name_and_type[0:-3] + var_type = var_name_and_type[-2] + result[event_name][var_name] = [] + fmtStr += var_type + variables.append(var_name) + event_by_id[event_id] = { + 'name': event_name, + 'fmtStr': fmtStr, + 'numBytes': struct.calcsize(fmtStr), + 'variables': variables, + } + + while idx < len(data) - 4: + if version == 1: + event_id, timestamp, = struct.unpack(' None: + pass + + @staticmethod + def generate_data(data: dict[str, np.ndarray], + event: str, + info: dict[str, str | int | float]) -> dict[str, np.ndarray]: + source = data[event].get(info.get("source", None), None) + t = data[event]["timestamp"] + t_fit = data[event].get("fitTimestamp", None) + + if info.get("derivative", 0) < 0: + raise ValueError("Derivative must be greater than or equal to 0") + + if info["type"] == "linspace": + data_new = DataHelper.generate_data_linspace(source, info["step"]) + elif info["type"] == "poly": + data_new = DataHelper.generate_data_poly(t, source, t_fit, info) + elif info["type"] == "cs": + data_new = DataHelper.generate_data_cs(t, source, t_fit, info) + elif info["type"] == "bs": + data_new = DataHelper.generate_data_bs(t, source, t_fit, info) + elif info["type"] == "custom": + data_new = DataHelper.generate_data_custom(data[event], info["target"]) + else: + raise NotImplementedError + + # exit 1: add each vector of the custom data list iteratively to the data dictionary and return + if isinstance(info["target"], list): + dict_new = {} + for i, target in enumerate(info["target"]): + dict_new[target] = data_new[i] + + return dict_new + + # exit 2: add single vector to dictionary and return + return {info["target"]: data_new} + + @staticmethod + def generate_data_linspace(x: np.ndarray, step: int) -> np.ndarray: + return np.arange(x[0], x[-1], step) + + @staticmethod + def generate_data_poly(x: np.ndarray, y: np.ndarray, x_fit: np.ndarray, info: dict[str, str | int | float]) -> np.ndarray: + p = P.Polynomial.fit(x, y, info["degree"]) + p = p.deriv(info["derivative"]) + + if not info.get("original_length", False): + return p(x_fit) + + return p(x) + + @staticmethod + def generate_data_cs(x: np.ndarray, y: np.ndarray, x_fit: np.ndarray, info: dict[str, str | int | float]) -> np.ndarray: + cs = CubicSpline(x, y) + + if not info.get("original_length", False): + return cs(x_fit, info["derivative"]) + + return cs(x, info["derivative"]) + + @staticmethod + def generate_data_bs(x: np.ndarray, y: np.ndarray, x_fit: np.ndarray, info: dict[str, str | int | float]) -> np.ndarray: + tck = splrep(x, y, s=info["smoothing"]) + bs = BSpline(*tck) + + if not info.get("original_length", False): + return bs(x_fit, info["derivative"]) + + return bs(x, info["derivative"]) + + @staticmethod + def generate_data_custom(data: dict[str, np.ndarray], target_list: list[str]) -> list[np.ndarray]: + pass + # init objects for computing custom data (residuals, state errors, etc.) + # res_payload = ResidualsPayload(data) + + # check and generate target for custom data + # custom_data = [] + # for target in target_list: + # if target == "error.px": + # custom_data.append(res_payload.get_error_payload_position_x()) + # elif target == "error.py": + # custom_data.append(res_payload.get_error_payload_position_y()) + # elif target == "error.pz": + # custom_data.append(res_payload.get_error_payload_position_z()) + # elif target == "error.pvx": + # custom_data.append(res_payload.get_error_payload_velocity_x()) + # elif target == "error.pvy": + # custom_data.append(res_payload.get_error_payload_velocity_x()) + # elif target == "error.pvz": + # custom_data.append(res_payload.get_error_payload_velocity_x()) + # elif target == "error.cpx": + # custom_data.append(res_payload.get_error_cable_unit_vector_x()) + # elif target == "error.cpy": + # custom_data.append(res_payload.get_error_cable_unit_vector_y()) + # elif target == "error.cpz": + # custom_data.append(res_payload.get_error_cable_unit_vector_z()) + # elif target == "error.pwx": + # custom_data.append(res_payload.get_error_payload_angular_velocity_x()) + # elif target == "error.pwy": + # custom_data.append(res_payload.get_error_payload_angular_velocity_y()) + # elif target == "error.pwz": + # custom_data.append(res_payload.get_error_payload_angular_velocity_z()) + # elif target == "error.rpyx": + # custom_data.append(res_payload.get_error_uav_orientation_x()) + # elif target == "error.rpyy": + # custom_data.append(res_payload.get_error_uav_orientation_y()) + # elif target == "error.rpyz": + # custom_data.append(res_payload.get_error_uav_orientation_z()) + # elif target == "error.wx": + # custom_data.append(res_payload.get_error_uav_angular_velocity_x()) + # elif target == "error.wy": + # custom_data.append(res_payload.get_error_uav_angular_velocity_y()) + # elif target == "error.wz": + # custom_data.append(res_payload.get_error_uav_angular_velocity_z()) + # elif target == "residual.f": + # custom_data.append(res_payload.get_residual_force()) + # elif target == "residual.tx": + # custom_data.append(res_payload.get_residual_torque_x()) + # elif target == "residual.ty": + # custom_data.append(res_payload.get_residual_torque_y()) + # elif target == "residual.tz": + # custom_data.append(res_payload.get_residual_torque_z()) + + # return custom_data + + +if __name__ == "__main__": + pass + # small test + # data = {"event": { + # "timestamp": np.array([1, 2, 3, 4, 5, 6, 7, 8, 9, 10]), + # "source": np.array([10, 20, 15, 30, 15, 10, 5, 10, 15, 20])}} + + # info = {"type": "poly", + # "degree": 100, + # "derivative": 1, + # "source": "source", + # "target": "target"} + + # target, generated_data = DataHelper.generate_data(data, "event", info) + # plt.plot(data["event"]["timestamp"], data["event"]["source"], label="source") + # plt.plot(data["event"]["timestamp"], generated_data, label="generated") + # plt.legend() + # plt.show() + + # another small test + # x = np.arange(10) + # y = np.sin(x) + # cs = CubicSpline(x, y) + # xs = np.arange(-0.5, 9.6, 0.1) + # fig, ax = plt.subplots(figsize=(6.5, 4)) + # ax.plot(x, y, 'o', label='data') + # ax.plot(xs, np.sin(xs), label='true') + # ax.plot(xs, cs(xs), label="S") + # ax.plot(xs, cs.derivative(1), label="S'") + # ax.plot(xs, cs.derivative(2), label="S''") + # ax.plot(xs, cs.derivative(3), label="S'''") + # ax.set_xlim(-0.5, 9.5) + # ax.legend(loc='lower left', ncol=2) + # plt.show() + + # print(cs.c.shape) + # csder = cs.derivative(1) + # print(csder.c.shape) \ No newline at end of file diff --git a/systemtests/info/info_cf231_.yaml b/systemtests/info/info_cf231_.yaml new file mode 100644 index 000000000..0c3730bb0 --- /dev/null +++ b/systemtests/info/info_cf231_.yaml @@ -0,0 +1,5 @@ +experiment: 184 +trajectory: figure8.csv +timescale: 3.0 +motors: standard motors (CF) +propellers: standard propellers (CF) diff --git a/systemtests/logs/cf231_ b/systemtests/logs/cf231_ new file mode 100644 index 0000000000000000000000000000000000000000..51a797a46198f9e4cc135dae03fcc0a4f06fca54 GIT binary patch literal 85439 zcmZtP30O_v{`m3Al*~uS5J?oGLWcI*=g62@#!yl;D20T|6hc(yM1xYHLZ*;T9YbWE zJE)LUWS(UR|Ib>V{rl>k|GLlfeeQkU&+D%5+UxAS&p!LqE?Y-SN9*rj_t^n%vxfM& z&0px|J2OzLhSmaq7k{_G3;bvMz<+lSFmvy$kpln!6hxD*mfHgVv2z#9_Mbi1SF5Jh zg1HO*X1bXT=&Uto?#%Iii*PLIf3rcP|1JH$dw9>RtwsOy<##^Odypiwwr~>v{wVH*+$`uo)zzAOm^(zk4a^Tus7dj)DB))}ifi8I;-+6P zXNRbX>(^-ERCkKkS8?&aRshHJbxqRawj#3yc;L1W*aynii35va(8m_-@mm_U{3F* zCaa1Qge*43vKw3+Q-nEau$pXej2B9}((SJGg^PRYxUog*XRjuPk-LTBE))xtNPw)#Ux{I3b(ijm2Di<|XEKZfa6HFHRWAmQJkg&fEDX zHOBlA@TZ(O;S0m%=3M-?H|7rRYLW-|IXfoO#&hv{C(KW!X*^;tw_y+$w+X=<4!G~F zI3b1Yj8_x5_;?!TK)?ofV4c}+zWNdukGO+*)GRd_cPUONVtC>^E`DB#xi75q=2LOP zJ%+#Nd+?Snur20!Gt{JcYMgL};jsc2HyMoC5?=23_&DJs!`7}`oZ^kyV7i(djgAur zTGIXbaVQrL+=|%)4o#EDIN?0Q!wz%tgG|gj0e9XIC)BW_BiFpo#lFRu`@l3vP@M3R zjhs=%#kFgDvPEhE8(7;XPUy%+Zqfm(#xc0Z9P?AaJKbUDXSi?}7xx;Ec?hg?xm%oY zj7=kC9v5E^#B2k25sVzp*4ZwKi)SWaz5~+;ag7rMw%2K?xcE;V=52uQPLC6E*v>zs zjElFv#rzePZktn_kjW0KI`wArcBIbwn4iOoA^`ShSf>XUpS8if2=Jq6aN1^gw*wbX zbHUsbreW$3Cp2L=e>oSwUx&FpEZxjWal+Nkbl=#qmy6e?WA=n2WijAiW)ye3&c%jm z%#LsjZk-q>3}YkfeCFcQzc3$$qx;8rcm)}DYw5*Xx{=11^WcmWFfLA*$Z*I0TwH30 zIlu$nCPu{xRt)F6bMcb7m~{c)9uOx?W_U{k7dPL5ITq%8qhFj5!>}TQi&L{PC&6lb zvyKyT8BQ(aV%t*8p@84_i4$%!JV)D`w;B)YV(tsrP>d6Pxwy_`%vS-M$m4_u3|lSa;@!(I)3=G=HgQ5J!}nvjxOXz<8?eqRdc+B_3&?a6 z*pxOnO@ z%*L>Ri>hLUy=>0Q?r`ykhnVX>QWLL>k-}g$a!^3ABHy+bFuyl%%=daF^&_Cu(POG+n2W*2OD56 zhB-n191Z z0hvjhu$+w?lfcDwQ!q~i9MB<7_{^~XB`!|BiFr2Qet^$2Z2gXl`+mhd8qOO*MsdPl zHs>Asb9qa5t2O2saHI@q5hnyPEEl-gV*uvq@S+&hjT0OgZs5wr+Osj&nxiH)e#Z*N z42Oks@%Bxam8EL(?r5aYlpQI(4|B2kNz7@!YI5gWtdPKt!7pkqzVHb1vAJrptTI+; z&hXJHE_SXlk1djHo|=?=j}@ZXJM33utQr?opF3lYfRS~7#tN4iJ~fPsH;lzx5AYC} zvp$=~&UsvHv>3C&3)sNjkwQyjdUOwo;^OQ$%r9Z&gXOV;2b;$394;Pn0rQHN@Sd_h zQgAk+BfFJx@rzfOFTiTtuZR`Sno?{~Z$58FTG0ga55T?N#tKIm4z%LpR(&xW%~zAJ zZ(@a2Y|c|0xcJa?%)u~n)azKmfbB@yE4X;@8qCvS-w1mdD=cG2io;$meslnH4cJ9H zzKRvB*%_(jbuM0f7qf@Anv8}ydoz6T6BpO}f!Pp7?gp#Tnc>iue!QhiY=_w!aOd~2 z!hJU98vVJr-w@1g0eAlzD?~AT(w&R*=U{e%Ie&s(bSA?~Be>Xe8|F`NbO-&46&|s5 z9-YC(e@|l$fm5yp99H!h4k_f~sHd23!711JL#*(c?fe6@7w}f2M;*+?fDK`<3t=Oh znsM>PZkQhcjxLQA+}Q?tjpkyf37FMzu6t4f@7?T0*|?C4zXW0ShBJSi$Fag=_EGwM z3>RCFZP0V>N?r<6NbU2w8-j5ZUvX4u;FS%Ix4)bTgH}YeJW(+@U z5#0tCFG*4;fgu`4xEuDL<&0@-n*KM zTdc?I4XbhRVys|?p9j;pIQ=l@3K+R`WTem)SK|&BkGPMy80I|wLaeZq;dPZ<{J0A9 zDY&jXW)~?OW4K4#g}kL(*a34N*!fFyV+Aj^fmMUJxWRDD_a3Xs@F9`H2DXb%_vYfX zd6?J2F_?NjR!C*LsLoa{7NanG0#3?{71pqkb2GVEor8HjTrtXS#0odqVYR=Qi@nM) zpN0dr**$n`V|Z-sMZDFhRS)w4I8uB8pJ4d3IT!D=!dw$xl+^37LMg*OI^R$6ObtA%h+1Gkcr3k-){SdolljX*7j>V?D!TE^+ajTGLo*H!C0cZk6im}?wRlj-la3*Xu6x=X76 zGmXE0A2keQOXmvzzT%SYLIu0pvuuP_1N&KHj)D!0E8Z^jXZVs-HL#u|;&rfen_q4h zQrT)um#PNdy$bP;!)jvwce~)taHUi=aKBW<`{1Q2Hi#6G*)+CFRRiC+g*fM^n)K)u zDGcjKUqQ3mST*phZN#>i(kBOZHNP0j^H3Yl!_oVRdC zb~uH(IUGMG%OZtq>=IljlZ(GT#vBRL=ocI*>|=P`6E0p?a|v6Gx3C(&Rz(U93|rK~ zsxfE7u9%m?D_98An9`2ED7U4mfsffEc7pvm%@5xG*)h0k9Czf=0hs6RQxmmEq;Qwv zHi2CHbT{VuNovx<6?P6U12*m(~epYoyiM;&HVfr#NncId0!WqW-o|IN(I_$?h6BeW(ju z$&49+SwEwYB(B;oCZAxZVKV?%E#cyzotPV%KO#nJQiStu zTmZWya&eP0m}@ydA~ma01iv7PYhK~v1Lc@Q=RP9tb5aGf^AxAOuZHK!Rtva+iuxWy%mO@c0~g2c!+i5ZKJhmU6DBlv2VCo@ z237~mhLL;Sz}!g}ex_z{n4s)58}Nw-Tzu^_=Akk7NciC}p{&#kaL6AC(;bO!pyw7J z7}>qmDz5;AJB;@TT(% z0dMiZ>@v2Hc(jZVhV@wlxQm|#?obp6xbsHLZpuRP$UZ_SI35J}#!d}<^7Aslxfz%T zeJCU^0B@PN0(-!_u8x3Y8Z4cB7ZN1 z3tHdT08Xrr^}l0qWS{kb*P3A-HKK@g>=`GFJG36KT~7^MJSGBg`!Sf+o<+o2*elpv zjR0JGss_&X-v;=^Ld-SR6p`XasluV|+W;R3*1%&Uq5zMK#T>A^h{Rn_6V_Pl1UzPc zHM}q8g3#?)9N@C^nCBfYB8q9*!kAjS0e`xof#K)2055-u`Q7;?qR9WK? zwnnce6%zdcHwDN32Ve-f30AEEGs+44BP0$!2{^4cW|v*XY)Y?xUBcvY)4Y>n7zP#iYr1>k;dF+0C4CHH4EB|EKN0oJvxhV>qFAXTX! z0pA#eIjnsdIdRs2xDi~`{s)qN)3?f;> z>I3dtjJb1M85yjyA^IQc1Gdvy`)@VA{GLEYyEX=Vz82i#3Qw_sOn3V2q4fxAA%t2SnNaMxRNZFUxfZHz8z_AyM z0Iv_ke7|)$@tNgLHdwU>d@Z&bh7%f@P}&i&Q3B@7hh=0#KOgem*c5P&+-ew3JEXo& zSHLIpFsBrikxm-}$insJfNQTpDK}2gW!0yAaGQ7eoo4~s<;68IPH?}Jxg?8Cw`||mKyUeSG;fzZjB+UbSD-v^9 zyCRY?+&l%i*)hyDx@D7A_VvWYZaIKkW>mwS9UF;T-evo%z8^RNik_EKAdm^ z@CH)})8lV!L<_Na%niT`Mq>W+`#8Cm-dsHK_%7hU(HeNC?_I!p3oy@mc$91v4aCX9 zL%?kpR>SaKAdZcA061|MW~0(0WPH8WqUo~7fOp17n4U=}h64bwcoy@>P6x>)yEdZy z>odUQd^NmS)lR%O>KWkM&oP%hPbFR7wH5o>Rseopp@Db5e*xIDK{#8a*Dq5@PXi;d zcGg?K9~xoRqNhrD`-gqwEnux)m~UDplYJ+QMb+TXfE{~l;Pyv80gj%Ex#f>NWc%X| z;+SpU0c$%|!@J*`!oE=nxcf@XdbReD8B02e`_B9Z9JpEoC(rv0_~L%d{f;FNlVnqI z>}G8RtaDm5Y^7^1rVrIt{Qc{A6SEiK65B4~m##Gd=iHVsedC~bn?X&$m0vLLToOw{ zy}F7zCA9%xtJJ_B_SXg+);fYM-H(uH^8Glrfg}A&!6Toe@YTy~=jR9Aj!0c7Nh13nO5C^6;1$;8I8is2!5sntX!H+Oc*tCVH z*IS8(mdyb-EY`p+Yc>bmqQ*wH8e>DZkShy%h?`Cr0KQWTs}|irI`YD827r%s#$35? z3-Ps$}9ynzwm7lGCA8~eVZmX;A<|2WJiQ#O!#S9^&qHy8uwghY&s)0wlS^|zbfVqLoYI5Y9wRrbI z55O^pHSkW~9)KZ4eXWO3-Fcim}i%)B7PgJMMbMVfUi_( zU{S9RV5fGQ+0u=AzKSfJYc1}u?+5t0F;=brTa9(i`vLws81tiFtH|a_)}o!a0JvzF z2A(=g031FCb79NX#7AK*n(Pt*&zmPi`bE=I@cm8u%Z2{Xq#cWc4De3gEhgkV;AmH(38d&ea zK)@BXx3JZ4{~JJ@j#!EPD+dEE(8H=l=S)Ywwr4Ql)!i@`ZCp$qwy+ZKs)qvhx6;7+ z=|cgxn1Ffxn?R~;^y&n__Z1r0D|-T9xvP{%FD4#?&BfgzlK?++uZHOxP~zZ8fbWK4e!6He z+0n3z_`<*eux*3}c5Uncc=ln;Q+F>WMU`ga=bR~k%a3c|=v`9)Yu(3Od44gmSzspK z89EK{v_cIGpI!jRRAGKlwwMTg&BPBE907mU+Q!xh?jX1k`rfU3&=Igj2h7*)=928s z9mQZW9q=|&4Xm)94mfWZ=B9tW$hZe4;?`r%fOn17z>8JRfSu-Hb}#WH6UUl}+ss@5 z>n+s49c#M){=NgVU4aMb*~~<|7~~2#Bc>XrS2B*9TmgsYVD@+PAdBy|7r#873E1kq z2G)Bp6L5zz%=b+^NL;3o_|w!4@VyERoY~e5uu^Y3Tcq8MJ;;q-MxwjBJ7AwiSlQCi zOSQ))?tmv+VP4$OgM7VZDC!1z01oV}fy3r_0Dd_ca}xs(vSMEw@olsx-~vYte8kTa z@XFGmM$yI zgUFH$M7x1LfPWfdWlKj#p489>@InRVw#gnur>lWD@F&H42Wj9X`o4f0yJH@i?LkKW zY9ZR*^aX6~T@BM~{uTukCx>Icl^K*&a2#{O8xOMgh`xBq zY#!jrnHu<_(LBKS3NVN1coOZN`l9CzivK*RhUw=N_>d0RS8E4b4c}&-Cs}LOSlrs*4{+r; z4cxGsA7D#=%#TD*()v>)G4D9V;ei^s{Sk_x=rG`~i>G$I6zDPQ#&}KVUO!%w}Gmq*>$o;_P6G>k8E{{R~?YL~-^s%&&Ys z$%BHr;<`MF=euZNuWX9PufjZVz9%_+Rag93b0Odsp&IzhZ;D^1V0M}3Nv4g}70>mj z_*Oa>uepV}*xQplHPRJ}Cs7=%u7>F+`ellRFmlUpm=Cyll9-pZ#7oO5?pvjSYp0F&Xi9tb4@%s^q&l+Q8OGigWY&Q_|TnA5L>QqyV$fbDTFbxdX9WZj~Y|Mk; z<^J3i@Jos-=5q1k&6pbw_ax(tYKjHlC|8*jPhvZPV$;1`Y;_THV1);HZTo|Co=Wk(Yg~NgHRdpQhm}44P8K*) zyzvtk&yYp4rR#dlgY?M#PG&k${Mi62Te^Q6_^U7Gi7F3r_~v&~V>-n<6kNQ?8T0nz z9>f!Fl$~REjC(aqZ^7Zxby|zL=>ZRN;N%yQ>lSq)}8xE9&D$0Tp<^~`GNUHqzB2K@sZ^1rue>A3|k|%8g$M$jnzh& z?IS$Mslgvf$X<$9nsRZgp_n5>JV?aIk7Rrr#YUsKIKv0C+fonGeC9{8=@7*o7FNUb zR%ga#x*B%dF<1F}kUkyW5|evu8Zlh_I16)-uLt?l_%*rxoZ^n>x!Au1^UB#CMe#jCw0d>e5MB(u- zOX4@3;_Io^FunhbSnCSr5-$(Z*1eoe@T1t^4i`tg$E=v^LH3U@Pq%^67 zoXVkixVHu_xJjq+bv@>p0UpG1M+s?KPO;urE)G9}c}1WH3EfpfW>iwVJ5vL@HV%N1 zO&?(Xy~KkYOfDho+Xn#dP+SeuZx9eGe`8Kr;X!Iod`wpNqPU>e?tjPNKRnI^b1WQI zzpaW$tU&P`b1r^49P@U#a1AysB!39S&&O%tH}-VSA@ea;ZilmIS^??eOmSEs7aQ!v z{AD-nb^ZmUy)VT}6S(-W3Ufe;2k~_+ASnwd*1E*SL(4HQIs$W^SwLznq&V@d241+0 z&bg#sJX<8iNe}YFr+{pXqWDi!tZYZ3U+W-V*aP#s(;h@0e)P*>KgFpwT-;y^=4hn{ z@%nw23_C>eSQjo%UV*s{VD~R~NV9Z`XN7XHVjt#En1(Fi4q1DU;x*}9eD6Bu!I^MI zvb{rwq){B8=3=kUm@Q9vkT>1#kdzdPZ~xN3@bwuiop!4PwsaP-bgjDHA&;(7>~D;f zEgk(j3UO?I%v(-)kSq7DlRiZhPaVd^mL8bDXLyh;hpv*j&nUh>my0h&VBQ07nt@4I z$kK9(m+jzU=M2nF$2`c|&R2+%VWXUCn0~{AbN*3?`8447(HF??GCFeCGA@qL-osYo z1kAa>@jSW0@J>CfY&HIk+|dm4I9O-f;pd1J!vn3jID0haa(KDRZ=NMh*=poW=Hkf< zF+0JIv@8BB$u6dI9==?{^hVjgX}pe+MqW6NEZK3EjC?}zr(`Z(bsqDX`~GBX!dWt$ z;pW#ROz)h~ucL73TE4^_W#>yaPRu4V*fiWeRU7#q&S;d#md@+&0&>+Ri*$QRr%|^h zR(6N#AGYg_dD)CbB-7?Jabq|{!NtXnm~}E1llfON$s2}E-K$~xtr*UE@oLOJCkK%C z12V`YhVO=Rag#L6Uy}n!^9ILA9kzkx$2IV}=7Dge?7fZI@lpW!pmUTo)(M0S99PK2 z{VOqd$`2r|HXk8R^(n5Uoy68iy49IMaO4Mun4Dh(i!~R?xw*_JZqu4Hni+g2a zp13oB1l39w>wbMe-3n4h0pO_JejKeZdhN=Gg> z55#r#i_gYmc3mDq25e3s?(-?Wkjljld6?s(LdYDS1hUzWV)xtC zF#U2adKcZm_ir$p$A=K@Cb6Vj6vc}xxp+g`v#)Xh|A9oS&REl-mVr5JBZ{)T% zn2RDqNaUxTWcpExlLm3|i5Zv;!$L?*$WCILLGd>)E*`lK^SNaqq=WNLvXkLETe$ee zA;B=i_LzNpg^&aKTglgSI`VjPE*@luIk;^IS=MR`aX3hE-Z%-ByrGb8(len7_3TClOJhq{5rxBWf-_4_~O$$MePNg_BVSLy753 zikDPX!*plDX*jk>VR+BSFmlo(ghV(~Ji{0(Te^SvgNS+Y!!S}lW)=B0o#Oh#xOm+x z%u#2;$jz}U$v1{S%;(~EVVDo>3nPD@1e1wu8UuE4an@1HE)iiwo)JtcXV7U(&*9?H z4>7m)4FMjR9UNe6R^?@Z?61Adq%wFo2K;{C{g&J^!m&cy?FVJ^^t zulY~SC*#a0{+P_gg=a8td%uB1JIyEa8IHRqVfs@4+d%*4m>;fKOYBF?C+isA|A~ur z8>F#C+Af5U9n^W~0nG-jk zJY!2Y*IfhS1=ZbP%%2Tb5%KJNl2(td#@p~}m|is^cHfUV?fFU)YdV`WsG=8vJC1Yl z?;DuSFRvum%V&{6Unu@wz{T6YV7{2Kl6+FTlF{!ePSiSpI}%;zf77sNjainmk~lwe zA)Vh)Jk*qnb8Rul#IGdD%U#IeR}|-s;^L{Em|yQ&N$h62z)vkueAi#X^ac4hjZYgf z_n99=EWBMvZUx0nW4Ji{1m-)n7Lo3&UC2F#JDlfYqeqxmTw6fK?r|a87>=mm;!K@` zY?1aK^dqOwxDa=Sn>E79u0`oj7~?BArZeVaZTyI3`zb_V8)({_i(iew9GgF%WU42S z6>RB}9VJXx;@`;27h#@W=}CrUjwAD5)72Qhnv0voVZN|>7U`H_Pg37fyg!wT59VUF zAK^;O751dnM~cVX=Hj8RFeh5O5MO7@zMY}C{U8a`m7xFN$a>Q;hbbqMVZ@%KouoL=i;I&( zq>-J+6H`Zf((4Gt_qK3x-vgKri1s98sXeK|ZYCd$P+d!Rmn43NuLjK;gCkYJKFz4bOgE0p#8bBtM z*^@(T8vDj^akn{`jYsz zBh|K~2Af8GeXLslJF;;%%-v!v$bLs#@`!CqA@O+QpWnFx*zp_t1?G$c#T^d$}1zOi-(7uP$C z*}%C0@$v0N2C+MVy>hrXQH^<4od%@M=pJO?VY-VRFO@L;m7IUm=vRe#?0}l&=TIwh zhT&;?NAVc^Uz~4@+4<{VVdpJN@`~YER$S~k4D;{Tzl3hPEy*Q@XH4eezjHBfH2oIK1 zm>qqJg|UY$$vTFIe&XWkddJuzt(aUSTs>z=HZq)LfE7;WI1PLs{A!8$W=MfB<$)z> ze3!l`lN4OMX)@;d4<8CyZ!F2dQi|WZNf_?cu?@tLJ1oa+G3Ju+L)(fBVizZ$!>eI> z&?3%C#ys|nO0b`9M(jV(kry22V*6{DTb#-g`pZm6zfTmmDCFWdA2GM7%oOHSwkPEb zFVs4YI}+St5&lhMr2*z9FZK!TDviifh8vl3aSH|JyvDnQgR70mD~3;x;^M<@n7bG6 z66#MhB9|F%y^xECg=6kiW2aC&)QEIrcxa4-;UciwoF5;<{I+ExShA}E_w!u5 zumH2$$6&#CQhPFiT_X*z;NtpP8ElcxL@X4nD~w1vyX^Ve5G%bhuQrYSoiGPKnJdJf zGa^md%N=da#lk4e`#1UswX%%JGKPyBB@8F>Y9r?_z#KEdUWiC+PYl^@@Oi7b*ee=y z@Z*7kqJc3{me76ULn;^Rp2J+=DGDd-j7e>F6E*BM7w>w3xv5uAA@O8;_`w=Fa-T{G z!x^dCoGlxkU`y9?dsE?|r7?+MBi}T{3QJcVU+#r@n^05OI@_4^WVdH$4dP&&eA6qjUo%}9d51Tv6S(-uNzCN?oW7&}G$A9}(~(c)aq-Z{n4`CB z$XxKd2}v}jc@uNv ztqm79u*cjk$@p|eBN-XOZm@TD(ZG1OXYXRn>Yc`?CmYB}z)(7}WhfVu-I%jI+MW(D zk`WuYg$>^wr%M=K?ku{_IP!xFnAgUcXI(dy5j%EIW~iEry@Fku?4Hc$ zUtFvs%VbNZ9=|T@dM_DK&!W@tF~&+yU)83ut1o7w+Z(g$3NrGEVc9S)?&XZx;O~~K zZMHJd=T?M;d|E4F*34+;YK+c7;kk} z-o<=>dQD~YBpGS2mTutbQZC-|1M~U*y2`WDWMsk)immic|KBl)bHRhC@!(&;_M-qyR6q!mclVOVh_c293%`UbG8~d@&q5udJ1#pJr@~qNTT@TGA@3% z4RiiqqO^6Dkrxc_Nao^IS(xiu4OaRC&R}@YH7;&dg85dXValE}Wn>(~tv+$_(K=ad zk$#*Vu59EcBV!ZkoK*%`>5f!w14nkpd|b;%ndu=TE!b*YQ*d#~1kBxjFH?qi$;kQy zI&v3xE?&F@vv&K{N^2h(nayy1I2Sic#Js=B8fDsC8Cl7&|8Xu(y^OiT%Qed7^JU~B z!*vR|SbUFJ=(Sc!{AA=H!|_^5+>zjds@iJgH^Z#gFiM#VBR66=#*~Za5X{@WuEvp3TwHf1W_fUu(hxRq7{gQixj11x=5(*U$}6yRYZx9C!^J(0VAdo1lq2TI zh%KA*)pJ~YZ;^-1-s4 z!&h^0ZWQKvT4$8gJY}S?nBv2!Ts&EYd4z7R(%xN0yh|vaaGQ(YmtnT}ctKeS$6z7D z4Jx^KZM__}NV~3FRF=YdBaPwdhFIxu+E&}Zjy*8XX_=?&4`-xa3~LYK;tU7O&L(-v zuhV6uEyE4Hx!8UM=C<|olvkZ(ue%#ROW zR6d3C^FD@)pKx*W&zLI$E-GgMe!{R#Efwxa|GOH8T4D~iy{PO7cniZ%yK=E@f6OE6 zUsRe>%r@}uI1PNTO%Uv&PuwvdE4ZLMG*w2f>IA_ClE7-1eo#leAOdqr+6Cp~cXi3H zrW8Mm=VILq%y(8?P}VzKi`;{MAN(BS6)xUWh&g-81*PYP8pNnQ#nx}RxUcpZwn)SK zUQl*hq(dfkptz_hR<qxPl z3m56S|N8Wmvi@Ti1Jn3StvLaBMyk;YJ zy3fVuDlm^YnyYNNT$@Z{_-qvyPj7UVEnVL3T;;Yk+T;jZ4Tla`HJ0w1HRfiUa+UKp zYLf?So!<`Q;&4aI4OhWxL}?QB^>n(|wO@_dXK}9bPhCBt97IA$(rwJseRGwU0veO?P85$QtA^>mfzv4ahWYgTT;*}oy5#c= zif8DZ`*#ff!z&FjSHYae1l1z_Tq!QGtcL$>p#C7t<|}fQ!Hwz@f#HzJT%7KOxo}Oc zva?$wV!^Q4axNCPV3vpFDmyf9LY6Zenasucr!cpLS1|iy6H?4@&ud)l{RH!Jom^!n z9T}m23Y?)nd3S~cg6fH5O$;l84+hvTu;Hp zR^u=W;knBGnKI(X=G@Aii!TRYo*$X3d~#k!>N6Y=&c(CiG22GxDlcA?k?{=c9_QlU z7cmcx%T>DO%7{LjbNxat-u?#j;)Gn~$s8Hk%J4?5+=81uo$VW&ytp`eDdq>m6O~be;F{l*z9?i17h5M`p6r;Y zlq=xE)r?~0DK5Tp1@j~CMCDjPM&cQEeZs{qA22TuOjI`S3%4vf(~&3F%H!=wmCZ4? zU6-h|w}wkKhI6`d@m3MD%Z@~4ZVwsR#IWl)F77l7^Wpu8%10J(Ey}QeAQ$Is!2B^Q zQR!z6pJCYs{)y+}2}d#ay_Kk3Y9=Ey**YiXaq;^Hn7fxID!;*vvN-k%j(f|+tN&pB z^A(n^os4v1_-xZlyrpZ^5%aU!Ny;g$;ILwNnhh5p8-e+Lvm|9`^Z&!2XJ}yjP&3jG zbFp!fa=1PmRyF7=7`l#&pYFuGt9z2NXHyyJ|A}6iyQOn+z!}WMCP}$Q1~?T+KcSpiGUvGsu zJ`7d^Uha#rbQ;!ux!A)N^Qx^$${&CY8Mbof;$I$^TSg@*bDGIW8-@$lXkfg1xpgDv z&|OK&bFhm(4x-bTd60{{oWR@`a83)jvA}*9&+;A@Uo67xz9UIF8}7IcV0Qv@e@OWM zZaU#Krs!N{i{x}_tMVd@Y~wB6qy!!^F7OY0d42nAr<>K{YFz4T2 zqb$&a)nFqp_2FWZMVK!|tya$d*@V<^r6d2^#>FRNG52y=rJP&RgdAo#KdTz1*UvcT zQMs7QQ&uW{?duZ1nRH~k5-u)(iFsn@mC7DvHAy^Mx-WIE;f_R??%&8O8e>j58?3w# zszVO4AC~sF;NoU|Fb7T#R`%@$AMxDjG=e8`ahen6hwoM>OPsWbu?NLhmT>Wa5X`-G zS150<{3|T;qjDeikk!t{>oKRo{q<`ve{l!H5$ z31=8Cc+bVU-!YH(4-oyX!>a2fwXEEmQy`r;h&HaQ;Y)4x2 zry8bTRpM$`*1o|OX+nGFEYWs=pu=##j#$|@HL#HqzGRMh(cliJ-`=e)l(7Bz&WQiP zt8H-PspByZ{8ipBf5kSNi}UE56aBdOTOj8BIfeaH&+6GcWFyzwC1Kb&8#)&pc|!u` zw8>j+2Bgcf#?GZ9$DjER*AU?UkcGIzCCpYIe%SQSiO;HJ2dv$53DcFJuOi}8Z!zbM z=qaT4?w~xwey!ko{hR;oNCMrN5Kqv@TrkZ^_)s`md4Y{Qzo&%h3qr3)5m(q?4i60# zdVh&mc4WBCR0-3ah~ED~yxawIrNMq-#HVY@^X&BXDpiu ztokBh`U42?6J-)E`i1#uNhk7dw?noo8`-V(t^byeKBQT~^NleN7ZqgS;HBAX*pZ?) zK*IFr)Zj<-CER2f=70qbq{)tL*{#@_e~zbw=}&dS@=18_T+AoU{fT&QfA(P*`S0Jp zJFvAF@G~l8iM}X1^gbJG{nPf%=cdJBzu*2vRf{sn=LPqF#Nmd^B*Pb zSBiN^y#vJl!t?CQY>%m`a~n6C{^}F_rn-b{>tQ~o$|T*s|H-yv3%akngz2yH!P6pg z@O4eF#GIXdnd}~4Kc_3h<0eX&{WGFRy>qU!U!G}sMZ)yy7H~*N z`1@7NMa>$DZDfOUy0G(9>kks9k4c$PK32jJA2H9EW*{oWi8=MzIy*JLgG&dy7d(Z} zMZ#tVn0s29h|O!x%K6AfZYoNcK3)l)Pa@&da?ICmSc+ML{Bu^ak@IFs7@i_4!oDcs ziEfxap^kNUMV*0b}R=kI_)}PE;3#zUhz7fvwA6=^Vty+rqBL{ z-~E&D(~+2OyRR41zvSfLcYD+QB;46?lh`lgvV<2cz+B_a7V*fw%Q?&0@9vAaW_gum+ zexL=U(}Ts{^+d=9z;hTx=F(DtV%gND^G>DRAXCw(boWy+gqrTiKVX$hA7rhz(_7PU`WGng7A0t&kOX(1{kEJ1^ zceRwKA$dL7tBkeOyy&er>Uw!X+1R-tEokIdEsYQ)ty6hdpd6Qruuvu95^JdjJmWpRk#HWTD08~Ld=T%@?~ZfRue={9nBP?Ut1UBH}I zV}N|$jzCqHOBCOgs+MeZe>wcDm4x+QBfhfNPOftjQnM2h-yOx#X8NfYSHItuZ&zRVVk~~14<{!Bm0J`EPhaYNRV*Lnv>-E z>FXqXcRFT2tLgGLM&T-7?InOsT_xPw!U+3 z4ktF%9pfc1XRU*nXFZ!E|M6~{YON{7wGT^pP}m$fT$@NZ>MmyMOa5}Jk|Kafu--7DeE+c00wh>)N0Pg9*0D2|MhF#IhDIh>3o+$jt5!)sgQ?FOZ* zF7~6?L?vPR#B6v@w1jh>Vm|UVQr_szQPuw56rU@TFnwb7%T7mCQ)kf^Wqh57Y&FdF zqvhjQoKSU{M6pvntXk2#cFDc6GbH?~8|DsVx7?}DX_Xrcp{u2~k}$mI%HP;$N_fo# z%*|&d%0Go>s}_1u9ONKjcw3VDyiiKmUa#D!C-zDhmQ4;%pq5r+=w-}y_tWK1H|MFIkED3ibqO!gPnTcYb5X)2 z?=UC)I3{0pe6*x>M}aU&3}JS#YG>lJH(v%t5(lOrOQ= z+W4V_z3*ezNw_ZeTUey}W}eLrw?z?#wHyS!<|N7bW5Iz(3|X^2ZBD&d&_C=Ky`IcBeMRdVB*pHCw)5?;F(v+GnX#k@;jRQ3!9rAZj>9Vi_7eUaYL4XK4DAesBNrR(XUG7w~UT_NFS@#@cNMdTe=8q%)`5wD6SU% zQhi_}j}aui&A^1cD0nGq>WF!%Z70PCyI-nLyXnXwE)s@63&Zve#L88elg-T(TOEF? z%#Kj34wW!`Hh?Gd{*;cv@u`>-O}Z#dSNu=~oThm3VF|zZ)mhQl0p1?j74fTEnB^VJ z6~;c_ReJ1l*5JN`;i<-oH}>BpyyhEb>yF(Oe-)J~y|Zl2RT8F;Acu2@bOtmqEM`l0 z#mrJ+UHhBLxQt@+4p_B>Vhcs$;BOK>G7$6Mx;+#>;JoqfE5-MQNqEg`D}`6~7YPsb z!ff)pr{d;-&#Fm(D4sA+!nZ1WDth+(Ea7LHF;Dtot=Jm#QMG`*(|p?@;Z5hQ74UbF zB)sSp=FK=Q;n_4E}=w1C3 za59!~a?Ph~H70Eo6d&B*s6=*|rBx5B7JXj%ps+U*R&>R@$5m8pa(SilVi%o>RuXP) zAu8ZKLBjX!F^@A>C}M0XROPnxeb?AQ!bLyiiX(m%(#4Qh0OtK4`YU$Vc&@tbPVvp< z5{|vlU*YclT*BJ%n7xk;P?+bHs+dQ9hywl$mV__MO4!obd>*QJG5nD# zVI9S>EwO6teh<$)Kln&hx|d#|I`_jo^Y}2u=iLP=A(f4+kgz&nnBriYLJ9wL#vCD^JKoTXTnA>oLq(TWA0cO;yB5A)=)V-+#qZ>Sv3QGByd!WWIkDr!!;DdEXK zFE3QH%mz?_-lqzGSlSQRQ;3OKB{gu5Mcf>Xf}3GbbV`BW2U zMc|nOsxlLbH#teT=*M(8x(`a2EXADYGDESVZi*_)g5q7PCA{8th64WPkA(9RG0XS5 zDEd!KR*BXWo25y(&w3Yy#p7gY1AVVxHY#;htaD0GU2RJ7$~zJ+zwN3>AG$}vIv+6i zX*)~tc|)vfsW!zezDszU!7N2F0U zaE=M)bbTL%*S*E6+ixg-W-ej+By@UP2M^c@BQOtZ;H&8H)mN4Hnqr^v5~fc=r#FnG zqkBH)Q#I!*W;na6)GsN16)53^R&y2b)OiW7-HAEn*IdP>nNF&Q6%>~xNLVPI3#VLX z3AZ|fdG4)wio@q7sOGbgoi9mvM)^Di+y|2I(Q?dZGUh8zo*$udenm&F@lL|@dF7w( zj*{@O`p?-SO%3)_6dDgyRkD#?^s#EuN08IIhPZ*HJunY(U7(n1W~1_CbFL#um_Ah; zzC@7l;whL{oBJzlBCJ$#a0b-XI^`l^`k-*QIVa&p!I+=E@>dLxGE*I4BVP%XFnydi zTqjAV+2tKtU2QMn{x>jJ^j@UsakaV1<0Qo&)Doso zG={&QBjNndm>(1_QhdJMK=tYX#gSDKrqA$&hn!1zPOBGe=^|z=R`?vP37_RC{$h+( zi#`GNu}N(S*RaL>v_^oU71h0p%$v zEMqPJ(rd+==jEm^nCjWV~hGAe77YVi~7YA=$~YWisKYa??!L653iC%aTK9vW#Y#XhfVX#8Dz{-Qps~) z5-z!Fn#rS+uCA5x)(mBY*`O|6#5|5Ao-#ldN&=KII0t>lQ&tr$`G=+!h6=7_1} zBMk`K9-C&GGx?a=!2_$&uPMuTqe2?iOeMGJPx#{XX{M8x`xxBiD0k|x3^J75gybi4 z3ESVEW?HeXsWRLJORl&ygN%uAlKplQUUGSwX-wg8#R7qaOw?hP@tKXM$&p;(I^pq8 zrkR{7yi_W{#euH@-pe3k-j?JYUkR^Eo@QD$3UZ)QZe#mO#t23QSaL!5jupr2X_?wm%NHiKgp=@lxGTzQ?Uk{@7nC3M zV;NKP_~~1cgZ&9Roc1#Q=(7n)sP^ZO$fQS&hn(FW;3mJbFIZUzs{rO}N~$(UpOP?q}$!ZkX2nOc3=B0kE?J+2MQ_#%eifTi~QW(Z;b z?*mN@%Y=)u-!OD*Ca{dJc+akdu{?h6ae0ju-7L{D`AmQsB z`RuG`0~i|u>`_7@Afsl58W%4$gW^Q3d{Jy3$LXtxBE-jG_jBA z*~9%J|8FeWKKDDi2emDIpgr$rIk^(ywD-MCb-x`Hi=@2Om1TIWnegkfROhMf33nOR z)3oLH5fLD(QKT2kotO56dHy3T7xE^Y^>%ktz@g)!pNz)InJmL=2Rvbqv%G6PVTWej zOjUx+B0 zOC3zrvYr$EvWZ?Zu{^C%M-!wNS>Du#aEr?AOwlxbI`J$QI@1 z9azQ>bVjv)!gAZrgjWUDGrfBJMEJ;(&v>)E`+XhgsFGQJ=1aKxhB~Iaf0D(pELifM z4J>;;t8FUPCxr(%{+kHrQEQu87*a$9Ic6z*ie(sr;Clnh`Ogq;5L?rfW#Kd7D_;c? zp0f-qaBy0h<(;nxXMI@RG+3vt;E<(R%K!x#(SgIOLsfUwi$%BK8XUy9=`Q64&n zdrW3hei{~w{b!APX!d?qE`2!n%VHpOICf6KkEXRE#yd|)->2#4aA!K473!_}WQN9|>(+cIwAkVKsc-@V>rko;ORIP(0pYOu5YmPh_LRYdI;cRMd zlTU$kvDy{oy?!hYh{-8sdL2JLm9YEnoTgk`(}Y3F#ka6rC@QJ;$Mp{Ls1S-WBFUxEV9*+Jo63V@h!5LPP)Dp z;c^8|>4IM=bokkBZ2Tk_E=>53gRQCNqF18PL@e3TnB|MUe_-*_OP2Q;2oHGjTZFBB zDZ(b9Jk*nAc##vQKfhqP=^(;$j(rzz&%O}Ly-{u!#4;>575IsCs>a;~g!_7Y7Jc>S z;;awKPxi44D;{wD2FsK76Mj(my~w#GRaEvxx%MrVvEkzy4k|hK9m1b?riu2Go{2_& zD1Z3DGS(M6Mv^!EA{;XOg>Y}0B7&!)98&HZg$_knNy>7)3WS@A6k$G>EWD?qY;dvix%mVbj#R;z)~!qUa$kxtPi_KB4i^MkTMY5YAidrl{EIfyib-IWd`KSbz)N zzKvlr)c1K1s}Xr@~K>eJNU+lA<+rKMNY(Kugx;71BPXO zcUd0bN;shLIq`1a9Z~xtmi(~?%dqAPS2_urY5v%g@PUG{qUh3F;*gYA&0ra_Q?R)7 z2Fr_P5?=n@BKi)vA^OT0{l*b2*B=lgZ~+sQTzWgOW7 zJp1Cs?5vo4IdX-I2#!4>AmztJwEIA~)XZq{!Q+zHo*iY=XO@3OM#Cb@ODsQg`XNJ? z-fo}pIeS5PooeCGn8w}=vLo1wgX3d@ZTFMuW6`&quUfpEgw zd7^ZlJtEeGa{OkNaTRHq`FmI%bc%4#E3-w8;GN>F5#^z0S%x%}I524!%fFu!jymlx z8Z?Lyo(7b=y=EDv;9$911k20w{gR>kaBiYFv3slVZG`fw0z@%W1FNF9vFuWxaB;U$ zVokP9qH_b3t2JgBzB&x+`8Khv_a)qI(jc+F$9i#1<}^w1(w3y9m2~_7L0BLPQ@azuU|5)vsM)DdY;4=U*k9HL9Ix z@qVdjEbF}RCd;t$Tog@Q#&XFogmZsuAzBw-Bs`>CsKq{ zRsKLRSXSd~S)w-Z+5opzAj|Dq5Z-^S9!!J;h&6RFbQ4;$JOkc6`UTHnIe8@E3qxy& z3G=3j+;vdCHI`*qfg^Bgh`JvC<%FZ0D~pADy+v?7lmk|=3`>k)wXP4#g^m$k;9Xke zv>7elKtGkkrm~r3oQ%XZ*HrSZB*G&ciVEi`gT$_nDDQm2GOYW82i_2tO^V z5UzH8#7~)8^~gaK)_UfLAJ>oNJ5>qK-JL^hU)M!^ld07oHCb-oFek3^XL({5!Uq@G zijTY9#SU5W$?h!UP6&AEW!c`3aKwX8#*I0fiat^vJDp`1D;OItY{n0d(9MLGZcjBf z%i2)PxP(8jOgPIp_YCv=EY~|rIAC0Y@o9VwvDu7r*hQA%`DKK(4$D_w6Siv*XZ)O} zk|=)!<#z8_h6kPz=W_WWUEr?_ozqXVam?=$ViRO+ppz*=6dIBWTbD|){G$w5|N<(p@`axvX#IE>X;7|k+tU$8~&y^-XeHwhPr9Ao@a zvuKd{{@!XvVrRc_e$8+%E)<9e2HuOV&|BRMsO@WGACl?A7| z8t2GreA8LR1Q+b6V0r2j!smw8Rs0XsG#aEFn#wXB77qWh?3lw=M&oDRK!e+o?8cb= z7`nlEiQ-`q2K<^fRby98!sCtEsyvQY6VOx)W|+BeyEd6O>3P zAL+v~<_6&pSiU=ru*>Rks{8bvhA1i53HVPQs=^-_sN`{Bggd_4tLE}tU@j`O zWZT!-Qs=s@Wu9E%6NPV<$nv1cLW{5b*-l4UwyPFofg6rxm%D^}Z(MEZGHs(JT(+2`2P{MLvcO(Jmi6C+ z|E>+Q98&jLTFU6p&yq#P$ObZo7T7w$a-WKXle!$RH2z!0svz5`PUVtceN*Z*;Ec@3X9KSrf zw(wSIEm_LZjabGN9WX7!a-rUYyF2C6YIbqf-bZ2RW)EZ;_cg*(o#kD#2#@?#NHdhE ztMdR*e!ug`gYx52^)ovZd zYBapbGA@R>=qp&B_>u6QO;xljaqimn6DU9W&N9rvY43KnV%fg9y$s#0BegZBJDs)J z@=@wpmZ%NxYlPiuEQdBF9N43wcH>?zt)Ge|=WNX~*4LP;C(HGQ6JFO!Xwx2eYQ<#9 z2gb6D`x?+AejOcE}s$ zBH=7Uu3GzWV=2oEV+ofiGgCX=aD|q0B+BYVmP68~YqYkB1A z8RZ?zZS&00;C+te!w%VH=$^F?)E-q@udVUKlAjeJYIAAZd~Hzvbu71QKzR4-h1%Ng zq1xzyC@(OwjH?9UYyyok_o@8|mtM3~%e8BZHbYK}wjaVWy!dJVb_Dv*CA`2TL@RtQ zOzS20X4MU5x#OVa8uX-Gvg2;T8_%uMy2NeQqUB1I(nnan`gNrSFWD^bx<; z_Vqul<&YV;t^-(xp$6Qrr&)IKCwzR_DXqZSvs$!_#)o+| zUe)P=W>@K^R#jGG=}MNLZojX=+#bux`v{L~_E^iFa!V^Cvxbf_EaN^yT;)$C``;p* z);2|pn{Y=vBcl=hm}Qv8)rw`k!*ZdYgufJfp(~Ulp5BXO5RnD z@N~yCZEyQT?U%eLWoxnwxgrf-D_J(V6aI1MtyW_HJ#EWJY<1_lvAnhTTiDqeqV1Ek>xHl@_`Ho}+;E3mFG#jm z2?uQcsr||OP%Bm$<#iWW#+`1sr<3H+WWpy_{?!KmdZ^v4g>tjEEJIEJdeMh0*Ugzn z2C4rZTmAdPN80#$C?6FsnLWFIhh-RA>X3$IS${`ZTa#BW z)8nZ&UgkeH{bm_<73$dXsN^0+^UBbTneL!3k9w-rmrtu!6^X)t%0b6HJS4v{65cl1 zQNNruMe8Z|ufJ@|GVChMATJm~c#U5{eRSaz?U|IvOk{cY`vMu{l8Xtq>t9%J0VR)7 z@S>Dn$MUD&g>*=Ka5WA^6F$(rsP5&GqNOxJIbLJgn5$?8xm^O`7d?yVP0FWehh;R@ zK4baMEvF3fvpg->M@S?h<^dg&|YNO=k{#}P< z7?n$z1}FL36Mp4bMlTG}pVJ%bJhL~;FnuO33dy@B5%$kkP7k}0tQkh3Tyi$ckl>Y< zo8;!}375=PLBG{7S-U?8<>?fG<+uMTG!wjk=*6_6Y^ zoAAZXHT9s;Nm?nHk7dctj<5_{5OwUnNd6U1 zcvj9j`mW0Nwc%2Jd7tH9k*+#+j3h7rM0m{Ox_aO5iP~r>ueHlh4N3K>tK(*OdO>h0 zLD+F$eZ6vAg7$t3{=h<2ScVy19XoT9^=5>Z`ZUz1cfYGOm&5p@ome*JYN+F5g5=&K z2#;ypSpTNo)*|J5il;BjK}8zt)q?J@oW6|k+cF0Ib^lx1H2DT}J(OiwpQ7W|e=2$Y z5yJhiE6_x5Xs1=I^TX3D!~BL0SwEIbJ|JwrSm%I3!1NedwfkZ9FW}&SCS%!1AfMW;$+- zBl&43!hJ8c(2E?rqcK1m)!If;S;0U>PuUk);>tN%x{*T|7@c}QjO&Y`3uO<9sJx*e_G&_)?Lc2DiXDU zjD`Mh)16;K!nr~_=*^Qg%}dt#QCpTDb?TtMnXYS;vB*AvaP=CU^b%uKtyl%Dv+qQf z;hkHLm|$Uf(>%f(4t3Ut6^qe!)I<6G29`Sx>a61qJx+b?A$+Qyhi+bZObd_+s=KFH zh8JEPPXQtM%5}n14|UaZeL1WhlBus5FIa~CiaMl5S@!xyIFD<0-O%BnRzhGke&s7j z_aN+7)a%y$|LuI=OEZq@q4(XgU-Or#uO0Q7!hS{lZutLi=L=~`cuUn@`uewfwW~7q zWgfsXtS;8^je_c2eGK7(JA3QXO}n*NnHf4dhh^BWs6)DrWqk$VAe+AW&ETEdHklb3 z63H^`SJd&XjY{rug0TPSe)_155!wP7=K|MQhNOv(C&ZAP{)q4hwZC5a(l*Ucrjgvf zvJ4AD;h7S~@`7xIWRSYs4Ah^V->jXGX{3jxh}yuCQ|OD%V6(=JIl`)HP7nXHZ*1*y($rxLFHW{|$6$7=0{l(&Si z3=43f`&z?t%2vW3s}9ktxUA6PUGZ`^I?ggI?S&p`CEqFj=LwG=I#j>>eVJA&FUpAz zSw3ERD0DKxEIYg*{Ce6jy-?s{t-ufL3WnJiriL_Z*f1U6>Z#w@S%~o9@Zox~1`D(~ zZ&9vWon@Fg(f{o#Y;GWY;J^qy_n~=OUAfyW)Pv;%lSV*S5XdFp_9FcBz(_r+Ux2pn z8J6ts&+>qnkvb#-IT~XZ5S|b}O5YzfO~vkbHGa8a7GtUV>XV$vl2#mGjQ ztGr=%{$zRGxJf!}^w(yM!VSi~a}||AN~r9u|2P2CvpuoSM-wT5ZCH zd)~TFgo{>t1j>cmuzdBaw+`bZmgn^(?6%ZL_xe#*t1|)RnDHz>nd$=r*9t6`m`T{L z)MS17S0_#NMp>+3d4_2+40}qzYaZ75XawPg`egn2h5TBvbttE*EW_j;+=B&KZgYun zp4Ps)X?_kZW;eTnD2oZM9iG-);&#CO%tW`Vi_|&_wv@t|@x<8jmcwAEDg2C(E#hN5{E- zl6MRxeCo>-eczHR7X1UtH)gO5+a{qQ-C$WPAsp7-Pal$?S_b?^d0GU^u$2hfMl8#> z4-$^v;HURIyvI_-ZU)H9F0l-IEOp%6SfbVpsPlwG!XIw<=}z}ISiGE3{`8(@*kg(P zGs{_Ripd}qbn(}V6D7P@N3>&L- zSO#K=n1I!&(}D22(f;}-`}US{BTzm&lx5hx2?N*OEXR8jPG0S=r);faN%Kc}#F7j$ z%w2 zWP@_?KFV)5WRNk3N+k#FB0P7Jzn;HzvQqp!%5kSy#)|?Id@L8gO89}%Ur%US(AXpf z<-spl#>)-U7O;o_t8wr%;ZI-v^Z_>-7>5IeU4;%MD0C=8Cu5{Kw<$?@_GLfa=-AhI z;2O#y^;yPNhY5KqIi)$_(o6jGreU*;KV>yc{aA(_dOGx^EKeCpcv3Szy=vhQQUR z%5ox<0pmKZMzbWsv-3~U=hr!BbeC7~Ogk{*N4sR1#VJQ|~Zr9C(!`A!g8<#nVa+^?& zJ;pL@6x4BZBgq%f5O&G#qc>RYB%X$%JnA9Kuu)KlqoG*#d`&pMv$x*1XgN`TGs+|F zOHo6D;~3$MzBJ1}90@dD!nf@sEJI6APH{ifxmeXz!Zk;wx|CZ2I6dHhXt#p=gBm-|j zEYJH+xUADSy`pzNk<}CBI|WNq=pfgI!ycAPlqI~f#aO-j$swZaV3b!hVfn+2u`o3> zh~=ZL2-hD!M$eHtMwA+ka$zr)<1dfVahV?dz&2wE`}&R6SAF#n4P@x_AeP~T3%p@j zezKDA$(5t@xJlE+ydxsVZCk5r|<%z-!)d;vK z3s@F42@i`Hrl&7lD)!bz`J+3_cGZT%T)`5SZ+9a+deu;UWQ`CpxHigb#)mm*Gd|qLne>qtYL&5^A6Epd#({qQa-7&oa^pjnC)51 z^2Q5<$1NSCFaEqi1Xah9yFF#OU+^FuGI=c5c}sX#883b3@6Dotls$5lrG|trVy60= zS&lDE_|n6H`ufRXVz`tmxw4F}c#x)K*-Ih(-gBTn`*FC)T?4CO?#VK~JmOklx`N*Z z5kBfYKyNX8hbSrK<1<)>V|4I^m*wDvgf|8E)AxVbEn3KGq(`tkYg9jcm1eo>0m6As z_0=mr+bga~Ip7k@urO3#x;Bbs?G9l}R3Cl8p#9>Cl#730xx)S4(4M1N?*5x_*O|R_ zL)nAkpp^GHm7~y2UfD~BQ%+eUOC2cP+P*S?)1=` zr5_WurTlOx%fYeTapr{O;u8r+Ozo}*ro;%7l!KPA+^canoReYs;9A1zS-R;jLM=j< za?L|5mpkC0+t{3Bxs68n*ennIdHs{3n!G3pi7daY+yw`&ET^OpzW1rK-dm3qlce0( zraVOhHaF^!d1QG?Zo;Nc9rfQy=R}gM#-qwC!{$aEPYtEPwnH7lOs4(7Z?;#&Ja}z@*Z)&2!!C8WyRWf4<}%^^lUwV>c3l&nUZGs? z1Ab7srTG@L!5ny^8I`jD0FZpnvRE;QZzz~5%$R8ra#zvOC(5n zetnkVEfeQ*S+3obaA4c!dgR(WqMfY9-@Yt|o@uJX$*e427)JQaoTj?gCP93Y^42*l z!;Tu5lSyQG;8Ma3jtad>Vxq{JhIMWk$ugWh2c67)mcJh&JnOllx9fRdm}KZ2uCWX+ zyEwtl^3r>RKNmIV#o`}`mT*`AoGg!WaJQn`%QQkO; zWjH+$QzYD;U-=O3w6m`6e(Q;7P#Bx2F@$9}mk={GEC*~P+$_pfuXQI`oO4Dw=W&){ zV1hXymW#y_ULRLWAH3kHIOK}5`$LvtWftbGSU&WEaQSOB^x{2I#IS}ace1ZU4JoEg zbsf&BWx2Hj;hJgH^k;8UghvyUuT^6ilP@s5Wcg8j!ge33=-y+WiA@HSr+Ki9X&v0> zM4h>BKf+hjob{TIo{1vz3G3|7a#F?08RYzP3AaeDr0>a|Dk5dc3%9Tgr(x>2r<2AT z5s`#z->#q+=#(m!_rq$`KgaUT4&^h*hHHe+z9^?V4o(#*V^DsS#3GNID@El+p^|Hb5biOrsNTQT zGjVb%mRvWA<>1)D@^aJ2Jnk6bC*Fniks55j-H7tNTP(LaS`gEeJlG!akZ`V{1$CR} zPsOi2DEIow@~=oo*+i-2&sm*ikgD`_)Pt)%75fjNY+IfvY-@MG%p;e)v>M@*HV*no zL$VOZP(I|&@`#YUm`r5Z*@JKaV_to_>k~2VILb4|vyAy}+^I&@F#8d{pD(xGxWr@8 zU&>|Iu#A~>>{O8O)+KiO{Gazk5h*XM&2s1& z8`Lk|*yY{4w;CHnzhpu|;0)CYM;o6QOYr z9LafZ5snOer!`-CLmZHE1^3^xjAxm`3LKUreh|JKCLsAnYr>nZKh=DvT^1vyd~YbrxX=T)5RyD{ z9N{8I;3I{eaiWiuXDwkF_D5=Xm;%W*s|lCibYF9|xgh+c{O2Icc zoa>ZWBxM_CmNB1+2fS0s{c90kyZn;YcC9APNO@lemN7*MtE*Z5)}3&{t>?9h`Bc$R zUX-8SEMwNO!u=C0FPTpG&F0hE)Tt*#s+1pZU>Sy%8l1C>Ha7Y36+C}RG(!`_u=U$B+oVy4sbf49kAakrhZ2G zeqWaH^iJFjNpjI4gge&QtJN+aDH?x4x#C=w@$^prmpfQKxQMVfTR>+1*?S+-1b3l9;|U$NvT$5@6JbPck2ERWF%KZshag}Vid(((#Ue#kPs`a{35 zgk_sl!s^u^ZTY>$qN0?G+1H?G;8C9gVivNzE)U@bm*#1`l0Cr|H^~xpT!LDWCOY8Iy828A2uZ zpH0~PtB)2@X118|4ojZAg=IV!6iVkC_R|i+zER_~v?J5RbvYr~^c>4D(}U~GSza7Z zc+BzJbr2*C4WrT0GZ>Ob{>Lc=cqg*+Zx2vEmp7Au{DWa^lVnS`P{0z#ypR$Y_S@3I0Bwu?; zc<-6w+E7bX(fv5e_jA^!h6I~PH8|LwP@&MWQ^bHq&+E3P3MfK~QS- zZv(>9E;wrOQRT#`%_zI{WEs9=1&d2dv%H}{;cwA-wcABYi?E3(FP*{iL}M-ucE7M( zV;Qyhgwaioh}?yf)ko@F@q!h+x5qLROUB^>+xn`Qspyy9L}tj1U;R|*|&M}m3_ zTCuRGG~tW6-dWb_ImEKcC>JoXj3>LoE+dx9w%BS%&vl+!e+0 ziP40Uhdj1S{%a%R-r)XUhBQ(&x~(7_J?Wk$zsoPS>6rx+ z8MOTD`EkO70&ZBgZTM(B_!>*@naDB>04?|hHIipNBJAgL*|IIq8>5gLaO`dBP&D8K z0}HIKX1Pc?zncR#q{)ovAf*3_xd@@xN#2; z<)n3t+tLZQnzqgIsAa72O$?k-;N%6Cn-n5EJZht5`X!5ThFp8;QJ-bp zI|vbB`C1dgQ{KU5!_CKxm*f%uS^KdJ+j=Z`kSJASv=`we9wC;Jdk-12OvGyJpTjbq z%?pREv-~HBaR0B1Ez{rZGcJ*fOY26mjC&qkbL?e#O%&nyu0fUxH+CC$jK`7_uCfei zRSSfVKx3@s3S?=&u^=`)3Qw zpr{4LN*?%2nwBJrCm!HFRF>z}CcJ-{Vp)@CzVWUJ zd15bPL3zYq*UcXw@OiMrnE7>mwU793O1zBK?kZr%QMo)Yid>| z+#%quYU$->ymAJs5!#q#cuJ@+L}K}Ld%}II#H$t0n~au2C@&hwGQ5?l&`eqO^d`LX zrmhA|GZ^3OLAhQa%g}SFc!B^`pqsDGg5IUKFP~Y5`OY@ zj~dsgu5tJ-lz-f08F#hgA`6nsJtzFrEnH2?Q^VL=$}4}cj0;(yO|z`#Z6t%V^XCTD z2k34oS1U&pPJ&>i{vlR*&$Joy*j!*>fDru#;gm>Lo;>w#%TmJ>=4?z+fDjo6yYm@egMwOEEKsJKjqN*>>w@b4)_)bP-3 z#sg!qDK4iJxQNnp2Tr^K?_*oezKh*W(BFoT_%y1vFeDwk0g*PM3BbuZu zPVz%tTi>w^m)i_gVR=}VCNf9^o-H)LSDq<8K3I)xMTy$L{b$DG)2YsXs}Q#P+SP0) zl9Ufp-fv_XB4LJ`R-yJB(wXpqQiaS9jklF6Yp~>AL;jQJ#^8wRiDz)*n^{SG-17-1-We8mp=nlBfiyaLzbh9`4H91)7h;nE#%JV7_ zwSj0DpgZ7_D>ous@JVu$y8ZSkJ>fG1uwbEmCYhpfYyja}^Ku$K?uk^s2BMtPn`O8t z_?dgIM#uSt^RBON=z1eusWlblz3cxgc`lr>v61D}J%qF09c`%hI8-Sl+eWvOEJLXV zJb8qw5qN`e+3=MHuYs$TIN6?0q*|2=eJ6b3!8Sv|OCbtHMNmV+Nc@w#7bg5`eS4)!;|fY$ zS?3j1t;+8Vgpb_lqC~tZtJILusL_RGyn1*QsT%VJ5mqDnDa+OtRd!1G+7zpDiG_r{ z(!7+g@&%P*Rq+R|*_=VfmPaKY+)sGC=MZJfp&Uw>l*^rE8Jp)nxx*d8WfI0Jdv|70 zHcR>9Ype2;UxaUupQPmJY^%6PxorUxh3v73s9<_O*IUzhS3-uXjK+#3Eyl!M{$3YY>1a~ z;e9M)pMiY`RpYjWaJIBS#W3QUAyvx#Zd#Scq!3PXU8ocpbKc-u9jnp&M<$v2y6m}| z${@9HTcmWXf7&pyBg&7<61Blj5j#hcH@XsT^5_avjLa{9vZg7+1jpeJX%0spj?saX2Qlk7egOK0)Y-DB`d;NcP z{&tCQ<9chA@q@M+>dWzlb8-e5E;;|e;17hS_F1pI_X;+oNcmchX4H_d2OGA7#${XKVm7{H%%OC|ige#ASH8b>+uO7{c61Bk*!M{4YI}_g3X{Ta1 zYce!Dj3w_fW|HZ3>2U|bi-t!k-I|#Uk8h*gb4Ugm#~dV2^C8@EQw&y|SUP|5!9JW}rCZB^blhj6<}hm`f#r#Gqd27ln|^;YF3k%a5k zKcw^@GP%iZ8M?reEaT7;2e0%4FJC2mc=$2p%!#{=>BAXipIenZzYzX5^@OtHLaD}! zWHn;)y3sxOza{@HNqE8Z80EXI*3ckjk9t<+RV@hj{uHC^`c?Y)c3J0yK33%_qX=hr zHY*GI1|7dEPc8`vuqs=Y6E4%xtX%Tjc)Yxn|Ln9XcRNP7eFL+i?A>(S|24*W#}%vc zn5lyAXCB9jl}#dL3UU<<29m%I*9J2dBg;xdU4r-z?=n!5L)e z>td*FJlah7uG49y(1iwA32Medy@(NaC)ay(#{Xo|rgg+$3Di=rCo2O_f7cJ2G zU+ADSH&e+M$`TegW0h_Voz1QZD1T{WRUX=!aLk2RB{Fv-^M+?AZyLxlzU=-h`P*2+ zH$I+IMs{p!ejsnF)`3<_Ubc#`|IIVXh^B7lHPDOx{aeXQ^vbnZkb;5%4cL`Gj!ITIZGck)zCCzEv|$`7kKJ-0u_q?2)al%5%CC{;(%bIqx>tT<{~x#m8BdOHL>3{vuB4>om{o zAn9N zGs1mm#VYe&C7CaIeLRG2G?!^h8Z5*Q%X!F^8T)sABsb^Jw(3EhM>M_c~Wxvfoc45g|`&gB| zhZ9zuW0aJ58+EOe+Xq;cb1fr$vT}^l?u@NEIuc8c+sQJIs=3bF4-@|J@rY8Uj-Bc$ z>pba-Rk`tf!Z#BSDWm(^sfFaz(fPAg`I>D98KjO^4=Nsm?9{JPeqVwp55fOGbi-W; zcj$Of(R$jc(`B5OHn%FUk|LxLtYZDwr!6h zp4+OklTp^QbfkuaC1bjPO8)FX_`~Ym3YjAw1Jkb&-m+-B5?!x=Iz-B`=~m_0UkN|(30Ka#7f^dh`Lkmu3f=#fT%t5# z`|)8)pSA_m?^52}$f~^Gjd1G^+muz!3#b9|q4{Z`Rk_t@!seK5N{0po)KDq=1X`7o zLI}I=*rxP$DWJZQ)o8dclT3NvDaQ%d58tMIEmlBX=7`zZ$~RfYDH04F$$1|UUgy0@ z*_*q7nj}yA^!Q;_4zuqpgEVcxM#c2UQEecT#J|cCg-`ZoELl`1T&ed4CH{k>T16(d z*SEGR-|`^*`N4Xn;Y&v~t`^q0$T+L=2!FyM+t({LPaM@nwNbXLvMOiUN_frk^-9fq zj_N@v_cODM(`WypvHBe0sXbRK^KLn+1El=o97K4d(^4fzsH0l7E{5(~m{qw#6ybFH#Y(^yM>Rmop%<;nCvFj*VYf)R zw%JiFFXiU%tjgVf63(|^q2jd3QSDO)t8u!B2Zio`>-@SLVTY~@l?qVjiSh@IGO`Rq z_zXXAwmadxx#ufyL7p$;TyTh0x$t*xw*|z zEu9zZJU7~^+*&34c}ReAI|44Zd{3#CU{$`KOt@gp0A=e=NA;+@yHEVFDo@PWRR*bX z@c<=05-y4ystv0|)COnL|8#wZbO$YrT9Ka^_G--t+y&)4JRBMJV|K+@(G%5(5=d&;t1DpnWT&XdA1z5 z&PrvOb0Pd_vwu(c^}3Nt9LOc)qs=*QH)=@#D{m@Fcy^zmN{%Q;^`?|>*0n0v5`-JH z8LT{pl8?zaukT}3K0kzTTIWGZG|1KED7R&RRe9)Q!j)3JloC*loKk+blVwaJ{kwuc zq6tsv+FP;P@2HlP^4Kd@<+TZf10B07D-JlSx|Gv@S(Tmt5`L1@S?PDjL2U<3^zYwO zmAcE&mAcnanVjUH(q~{tI1{z`-^z7sPk8RH4obo^2laX86>NWvWlU%OYl}BO5q3XYQR(^HLH#9Ha+Uv@Nv46t z&=Ngm=-d{SRkGRTSNj#m?(%9WqB3>-@3Hi^8Q~eLN-H_CGDm}6)zq9Klqfzf;eq~Xq{Az<57!A#yC?xTyWO~vp zu0ptOK?h}OrTl85oDnNj-Kt!sGvPyB@+rm|`PF23&)@a1Dj)SF>{BM6vbb)3bx;y^ z@w5F|hL@2Hm%GCz!V7%um8OmItCMe_oMme!nO;_3oF<&m%2vsyy^F z*w-$<8rT5k!%Z^Dl(TI)fUqIzm*HjC{Oa-F{vh}9Vi|MH_<9CwHKAinm`8Z~;@5`m z+p??T7|Mx38DwnFaPSex6ZQ~}Yw*<2AWI%K$0(GiMrDw(WH`$R5ATN;Xm+2!zH@R3b_&Qf+hmgAcp{Jok0I=_G0D)r@L%)gi74+G zpGk(}i9r6df^eCV4-KQQ{4uvk^#!@lnoKh61Oj=*3BsZK9vW6?f6Ontq3mU08RpsK zMS*kMK(6wb@b&BQhIMg&%)?Jk26^q%Ofn3LKt7qRuZ+g}t!EAX&;OVQS4DYEE}}RU zB};}Ahd}OIgK)3Qrwqd#{+gFe@WDE}W|HB=A&}p8CH%wrq#@e$*St2u8|1S+Gs&ut zH^_lg371%}8&>%KH9KCL1ai>KOfr1g4&+kX2)iuT4HXXkHDCQQ5#);7Gs*K`PXzhc zdBVBR>4w&y{+dgdL^wT=b-2O$i&dbh8N{dwj?w!y!T-KP}WxhVIRT zlZKm$je4T_c#xBvi2fHkI7A5KsRqKSmrojY^|Mi(dX58mmWgF}!Ip7`gBC$9G>EX< z@%@H#{x<6T&SOC?J}i^mBi~q%cP${?pw&*p@>MqKp<-h|Ua=&T4CexYY}!wFwk!O5 zdu`O*??!>#<4`6U&IJPb?rp-QJhmCOoU&1SUKt7U-^5HZoPG)N#9xHF25&X&xn-kv zTrvXW?Kb^ojO1sm@a~2qCqcHaKzM%Nt%jgyHtIsdaFDAyXOiKlACN=a5MDigt6}>m z8#VRmP>^qT$Ru|I{P%C&350j-*lGy2vsIf04FP$gPbRrkpCKS$Swpye`c}hg2V2!C z+hCBJZpg4GIKrZY+^uN$u^c?_lHCMvzONSXIm~7R+r~N>- z)XyY`r1t|^>q&TX|1g7VTU+&U>%Jg+^~)r~Zak2?&m`==D$LNLtF5{ys5i*Yb2G^s z*7pWEJ%X^ynJ~ke-nQzAgq|Q@h|DA>Ug-&P&?Uk?Z^I04``N1V^Y;LG{IyIn?DGS; z#0SEKiiR7U`rE1>m2M!v`jSb8Gj>2e=rmAiAU!&d#hxHHIZZkc2_BpKwCp@i4Y4>v6AY^%;%))C~$QJLhdJvxHyw}kM( z$Z*4Si1XMP?LqDol1YYRb3k@DM0m}maKpV8wrWsdTaZ5=%OwAp*%ss-iG=N6ha0jO zZPis%-9f(bFp~@?SA*Ql##2UPcJ>Iv_Xf7=!ojUTo@!6@zi12_)(Yg?l?ksd7h&jF z$5#E?+70CL)icQ}o!mek(}D2c1`&qlwQSYKIh%vL&?A%FHcxYqv-l7$)@9FkAt7ftvy3;pZ~R zu%8m-i_Zxswumqsu5POqbZ886f%Hr=oWu^YXFe|(y7Yz-218|Ab>-OxARj46^uN$m z3u*xJk9vgPl#ehJDQ>F{=~NHo$xSlJ@FoQEvc7~5+D917*=<#?R9BEIcx95|yc&=z z&msKvNw}fbI~z50UM-O0f-=cf`qcti-9`A*iEu+Ibh)Fm)&RLuYgJkH| zGz&Krx{+%BHoFqYQ_B;Tp~I4!dsYIuSPQ}x%Y_?q8k5aiUzP{isZA#N*|qW@A0A0~ zf3|SLv{#SJHM*1q`Skcqa)G&JL3UqGc)|NHL+F`@=JCH(nO zn4xi#hvxkrB|v_yW|FU$F9EV|5@G#Hn4$iUB=eoEP9QITnn|9#(g|e8tb=7Vy2gYV z7A7W{Fa9YEa@Sl$|BFVktVRB>t^1Fw>HY&aUMfx!<~FN{YE9<%c5ZXKpHC{qn6IBR znME>%NLwqFAN`ONqUG0!r5Yu}G79KhTAV2;VmB6cSL&(r{ZJxGP&9vUzmkGUctizMu;mQv1l2AuAr z!qaOz1HKf2xyPI=QvYMMB#@4P9imlukyS^)^V2aqjmaWOE32jB%Pj!^vAq?un?QC1 zdnQ-_Ha>~jCw)IjiKv$P-4g&Ol&NsZQvvYi2bi}ED=OYQ^lfhkZy4 zKXL^;sLM=c=uX)GLR^i`O7d0{z^T?)m7!xeZi5NnGdj!-vv-oIo+Z-pH%5S6-CHr+ zXNKXIynv_qVV*tfAh}h4RJwQh)eyKM1*&jN(5oS`{4@cxTj&u|bEZ%#3w{Q8R&&GDgbnC3}JCkLmzVu*bZnp@bA#Nz$;3HGo~5RhTV^CCm4R zV}8{B1QEMSQj1g#`1t6zFdP{6LlVHtf-#4ioFI=5=Sto)t^y7UQ(?9Wjx1ZR#~gjL zgd8->l)e}MPoFok*rLMhq4cu+ivjbDoDw1(+A4WXJP){{NQK#IaI!r7Hs+|ACB!>B zO_Kdi1CFUzVfOrVS-#yaP#L6%?j@whzRgm^v=e}xI$>3Yj=ezkNOV~aAAotsg<^8n zd$Sbha}02niweU7831?q0`s=T#l+KkvsAUg0C>2s3d3)00cS75oa9_JCmGct(yh_yY|Gv%%vL&)1W8PI8s6hr4ZecPV^VB4F2kD$JG`k!8bYm=k=8$=u;ovU?E^`22)cj2A|4$;c=c@WgL1 zf0D9~#J$u@JG;RX<&9=XsWAK(0&x8gm<_hMq|ai#G-7ll;CtIt7#S zC2mHNEcyaIqQUz24V47Ti~#oj7_%+OAS11w8)6Pm0_?9>Vff)H;Omny{~VJ+!m1w| zCd?lPxVOIwvsHd&`MVg*_B%32H?w9#lj}&pml9Q&JziXvEweE{Fk}#0za~TAyF&p- z?^R)!X?nn!XEB?XWsoUTnhafD=mA?@QDJyc0ASr?%%5J%Ab!6z8E(~xfET`0Vfc9| z;BuQFW#}f~&mc9rX2Xz*et?}EvHml31FM|?2YFy7E$}0O>SjZ8$p?VzN2oA+7CHRW zDG>7%IfD#c^VqQVKo7thL;i*14eTNDvbEG|d24(OvC!1%b{@+ETos_gZ2bl}yW=tUs*NE|P8wIQ*|~tH zC97}*JlG!Y%yTi%>lRDg&i8aZRi6pC>wXo6uT=mJEyvv1J(eU^IJk}v-U_&=QiWlS zE5PQ@FgN(elH$pBuHkhX0cRQoD`WJ}Xu$FpfHUnd*T%<^Ne`@CLxR=<9_g&Y@S!|l z_}!1PjkK&-vc9*4tH<=!fNMspFk6#BmM;Wh4m=u5db_l7z2mSFaA;U7hIcB$4hpQ5 z0XQ%f^R=gb#ARWNZd!37;7(gqTV@M5$nxs~%t2<~lBx@hy4~jz0PiVMVK`d=Z@Pim zuOW)q+Slo7%$EWFpk9SxjVr+Y%;qaEFy(MGxs-NScgA-q;PQ@G{~0>A+Jh{Y^u@gA zSS-nZct>Y$@l>?TNsE_aI9+t%bHi_rr zq-~g=r7b0vvl?_yDj6P?tHSsKdzNCJ`FtrUact5Zvxx(2QO?B$jhLrTh$mH{&vlXT zfS7-Ge!= zXa~t3`&8#Rk4+@&LtH%cGUiv2*+iSvpu5>_Ip7mFR2b)T<$p1sx|U7Wr&jBt$FTW4 z&FmXI2iae3@Z$7{zj44^Ut2)FD7V+Yy3TNOUoLJx0`su>$H|R5GxU=zlK`)pz{TnF zF`wFYg0!rU)8BfB;oebP?6Lv#ADc_bS+^DX;l>Q#-`0xZ?cuF`J||&*GxjR+%T3mw zsAKz_TFS+$8_%Ccia3cBqgt@!Mn6525rw{GV=7#-VF8=d0=Jvfzs7=zJ`l(55*8O&w zixd9BY;I#plNZ0yuN=hij+ZKoXNtpnp~}$ZMVQi*_9kTFGj^toe;+GczSs*iVMh@z zUkBVU4_#qO`<*c*IbSjSd}J$TpGq@~XZL?*V%~Y91N~u*8A*G^E(KFVxVUyDX6vTT zH2azvDHy}B`9>~|*@wBbstf($ju{y*vkPP45f#QuZs)6*UGgl^;rF&$#aunvy zFE!Mm!h|^8T?Dx2WG)U0#r(}58v2dgh77p95b&XBE`GELv)6774fkk6G>aL|+Rnwx zk6{jr(a`JJ#-#phhVPZNV)p$Fb_8*s9qwTsTHK8;8DdOc1uz`b%*6*fgeim6`({tN zq=PXz>BDe{HCDKozrE#ABIfIL4)i;XG3n8nVOMu9uK5zPPn{zjG2WQ`8Xg7sLBLy> z-5J1#wlL01Vlh9M`9AHl@O@&pasl9!WEEyhB*}8;9L#67zfTRK3vmhv1#G#$6|=AF zur0GCl4LpO9OkVb_oIW$hmcpl1_S=3Qia(PN$_Ff6UI z{H!--0=rS`WK7zOXV}k$i`S0DY+jNE`D?$b3(e7RyYXc7)%0K zx3qII0#W#0hHVfBM+aUrm^=9~F0T+i~#Ox8QrCZ@ygst(O^|gq?7$H z7xvRqUn_x39m$4Hqvzu3pJR6JrKRWJ5y%+@7ft8lCsCM>_tetFP6BzX;K)QSUX_7) zosE`Wv=qoC1v~HMV#iahSfiym9pFq+@U_caeB>eKeU@5UX(5n-3SRP(i@&g1s0`ho z?X+|d;Ef74am1<`x;j1Paj;;}=Jo}MkF z1Ne!8+im3H-Fq?jXcp;Wz(xw*SIEWQS1>Dw1Vx7mhdK$y)|av{USXJc#?vT_2S}!A(&_6iL@N>6~cxt zX*3s)4!|6=N2HN}+bZ~zFfOiNg?Ym+kv@YLXr$nqXJ0z?HdN{L^vF zIU7Ve3U=c&Wy@pAx!9!+v)?+A<^vWKT-U%?U_P2G(kwVr?kRXv5ErM$VcxS+q)%aPBq+P_X(|`@-ibLS zNu&vI3sIopI|W>P>^$b>%SB3^1Ts;Xb$&Ov_^YRw*Dn*P5!}f*D5sU9SuAfNJ?e&e z$5N3tIt%22vgLDqxj23(WTPKkI%2o8|ZCpI^Am*Q8%UwSb$YcdiF6H7|RhZMGMEX&Gfix@lXd@R#n8YcA z6dVb-uR#7#@C*%B)kM=t%BR=xj1_qX4?fK{qjSBTvPD9>0Im= start_time] + + t = data[one_event]["timestamp"] + if end_time is not None: + for key, value in data[one_event].items(): + data[one_event][key] = value[t <= end_time] + + # add additional data to the data dictionary + # add_data(data, settings) + + # print(data[one_event].keys()) + # print(data[one_event].items()) + + + # else: #if only one event + # if settings["convert_units"]: + # for key, value in settings["convert_units"].items(): + # data[event][key] = data[event][key] * value + # # shift time vector to start at 0 + # data[event]["timestamp"] = (data[event]["timestamp"] - data[event]['timestamp'][0]) + + # # crop data + # start_time = settings["start_time"] + # end_time = settings["end_time"] + + # t = data[event]["timestamp"] + # if start_time is not None: + # for key, value in data[event].items(): + # data[event][key] = value[t >= start_time] + + # t = data[event]["timestamp"] + # if end_time is not None: + # for key, value in data[event].items(): + # data[event][key] = value[t <= end_time] + + # add additional data to the data dictionary + # add_data(data, settings) + + # print(data[event].keys()) + # print(data[event].items()) + + return data + + +def add_data(data, settings): + event = settings["event_name"] + print("...adding data") + + for info in settings["additional_data"]: + # print(f"found target: {info['target']}") + dict_new = data_helper.DataHelper.generate_data(data, event, info) + data[event].update(dict_new) + print(f">>> added data: {info['type']} -> {list(dict_new.keys())}") + # print(f">>> data shape: {data_new.shape}") + + print("...done adding data") + + +def create_figures(data_usd, settings): + debug_all = False + debug = False + debug_figure_number = 20 # Residual Torques + # debug_figure_number = 4 # UAV angles + # debug_figure_number = 13 # payload position error + # debug_figure_number = 6 # payload positions + # debug_figure_number = 7 # payload velocities + + + log_path = os.path.join(settings["data_dir"], settings['data_file']) + print("log file: {}".format(log_path)) + + data_processed = process_data(data_usd, settings) + + # create a PDF to save the figures + pdf_path = os.path.join(settings["output_dir"], settings['data_file']) + ".pdf" + print("output path: {}".format(pdf_path)) + + # check if user wants to overwrite the report file + file_guard(pdf_path) + + pdf_pages = PdfPages(pdf_path) + + # create the title page + title_text_settings = f"Settings:\n" + for setting in settings["title_settings"]: + title_text_settings += f" {setting}: {settings[setting]}\n" + + # read the parameters from the info file + info_path = os.path.join(settings['info_dir'], settings["info_file"]) + print("... reading info file: {}".format(info_path)) + + try: + with open(info_path, "r") as f: + info = yaml.safe_load(f) + except FileNotFoundError: + print(f"File not found: {info_path}") + exit(1) + + title_text_parameters = f"Parameters:\n" + for key, value in info.items(): + title_text_parameters += f" {key}: {value}\n" + + text = f"%% Report %%\n" + title_text = text + "\n" + title_text_settings + "\n" + title_text_parameters + "\n" # + title_text_results + fig = plt.figure(figsize=(5, 8)) + fig.text(0.1, 0.1, title_text, size=11) + pdf_pages.savefig(fig) + + # create data plots for each event + figures_max = settings.get("figures_max", None) # set to None to plot all figures + figure_count = 0 + for k, (event, data) in enumerate(data_processed.items()): + if event in settings["event_name"]: + print("processing event: {} ({})".format(event, k)) + + # create a title text for each event + t = f"%% Event {k}: {event} %%\n" + fig = plt.figure(figsize=(5, 5)) + fig.text(0.1, 0.1, title_text, size=11) + pdf_pages.savefig(fig) + + # create a new figure for each value in the data dictionary + figures_key = f"figures_{event}" + for figure_info in settings[figures_key]: + if figures_max is not None and figure_count >= figures_max: + break + + title = figure_info["title"] + figure_type = figure_info["type"] + x_label = figure_info.get("x_label", None) + y_label = figure_info.get("y_label", None) + z_label = figure_info.get("z_label", None) + structure = figure_info["structure"] + structure_length = len(structure) + + if figure_type == "2d subplots": + fig, ax = plt.subplots(structure_length, 1) + + if structure_length == 1: + ax = [ax] + + # iterate over every subplot in the figure + for i, obj in enumerate(structure): + n_x = len(obj["x_axis"]) + n_y = len(obj["y_axis"]) + n_leg = len(obj["legend"]) + + if n_x != n_y != n_leg: + raise ValueError("Please specify the same number of x and y signals and legends") + + # iterate over every plot in the respective subplot + for j in range(n_x): + x = obj["x_axis"][j] + y = obj["y_axis"][j] + + # print(obj["legend"][j], bool(obj["legend"][j])) + if figure_info["marker"] == "line": + ax[i].plot(data[x], data[y], label=obj["legend"][j], **figure_info["marker_kwargs"]) + elif figure_info["marker"] == "scatter": + ax[i].scatter(data[x], data[y], label=obj["legend"][j], **figure_info["marker_kwargs"]) + else: + raise ValueError("Invalid marker") + + ax[i].set_xlabel(obj["x_label"]) + ax[i].set_ylabel(obj["y_label"]) + if obj["legend"][j]: + ax[i].legend(loc="lower left", fontsize=5) + ax[i].grid(True) + + # DEPRECATED + # if figure_type == "2d single": + # fig, ax = plt.subplots() + + # # iterate over every subplot + # for obj in structure: + # ax.plot(data[obj["x_axis"]], + # data[obj["y_axis"]], + # label=obj["legend"], + # linewidth=0.5) + # ax.set_xlabel(obj["x_label"]) + # ax.set_ylabel(obj["y_label"]) + # ax.legend(loc="lower left", fontsize=5) + # ax.grid(True) + + if figure_type == "3d": + fig = plt.figure() + ax = fig.add_subplot(projection='3d') + + y_label = figure_info["y_label"] + + # iterate over every subplot + for i, obj in enumerate(structure): + ax.plot(data[obj[0]], + data[obj[1]], + data[obj[2]], + label=obj[3], + linewidth=0.5) + + ax.set_xlim(min(data[obj[0]])-0.1*min(data[obj[0]]), + max(data[obj[0]])+0.1*max(data[obj[0]])) + ax.set_ylim(min(data[obj[1]])-0.1*min(data[obj[1]]), + max(data[obj[1]])+0.1*max(data[obj[1]])) + ax.set_zlim(min(data[obj[2]])-0.1*min(data[obj[2]]), + max(data[obj[2]])+0.1*max(data[obj[2]])) + + ax.set_xlabel(x_label) + ax.set_ylabel(y_label) + ax.set_zlabel(z_label) + ax.legend(loc="lower left", fontsize=5) + ax.grid(True) + + # show plot for debugging + if debug and figure_count == debug_figure_number-1 or debug_all: + plt.show() + + fig.suptitle(title, fontsize=16) + plt.tight_layout() + + # save the figure as a page in the PDF + pdf_pages.savefig(fig) + plt.close(fig) + + figure_count += 1 + status_text = ">>> created figure {}: {}".format(figure_count, title) + print(status_text) + + pdf_pages.close() + + +if __name__ == "__main__": + # change the current working directory to the directory of this file + os.chdir(os.path.dirname(os.path.abspath(__file__))) + + # load the plot settings + settings_file = "settings.yaml" + with open(settings_file, 'r') as f: + settings = yaml.load(f, Loader=yaml.FullLoader) + + # decode binary log data + path = os.path.join(settings["data_dir"], settings['data_file']) + print(f"Processing {path}...") + data_usd = cfusdlog.decode(path) + + # create the figures + print("...creating figures") + create_figures(data_usd, settings) + print("...done creating figures") \ No newline at end of file diff --git a/systemtests/reports/cf231_.pdf b/systemtests/reports/cf231_.pdf new file mode 100644 index 0000000000000000000000000000000000000000..51e26ea486127d7efafd6a949e540aebca00cdb3 GIT binary patch literal 58244 zcmeFZW0YmfvNqh+)zxL&wyjmRZQHhO+qP}nHoI)A%l-A<`|NwpckdZ@-0|Yy`(ur{ zW{%9r%oy=xto39>5X%Y*Q`6HhK@eAN;#IUm(BskJ+31@?004NjvU(;)4tNZ|TjcR* z72Rx&@Ms0}9Q7=1Oz^n5A&jgI|LDl}F9U>J9Yquz^&E}xnEo0hY-8<+$N1NGSv^Nb zBYSH+=09E`Xl3nf3>1tU@iczVBPje^zLBdV9<7+w?>YJZ@f7&SQw&cFk5<7{&(O@; z1drvf;i@wF=0*mNc&vX4|L1b(|8)a=*48$T4tVr*f2}~^_iBu+e>brI^)6*(Xr{++ z8D!EassvDyF7#UJYV7e)Lb^l!}x zn_2$eD;}+|P>|Obz$#jn@=d5zv6Ujt@i{Pu8zrd4!wrgBQIxm z;!XQsqrlk1Ud-m9{L~V4J}`!kAO;@R&B}T{PXzeWXY_S}N6)h>mqGvwFga1`u`uqU zFZYbjFu&XjXg%bJM_yP{Bc!*}dbQ3NhPjk}ue3T=NNXx*PMg7!7LpyB)TMfR!kAXXGs-~c zQhv7v992<{o7sePU)kC)FY}?JI`I23NI=^|8fp2%FVkw)STX_r5Cxvu*Q;t5hC%A9 zcBCpACG_vV99hD)l{=a9hd`7W_+dFQxPy7_Nw7&aTqzOMT1K?VgkzCkymj}1(;Y#l zCR4E!%&J(*B=nP9GS&C#02x{zYn7%Q7%Ht$19E?x=HHn32SWb?6ZHRp>AwNRAHeuu1jV0H|DO84Ma7@E{sT_`M1@kH z^>0*ky-^+^fD~$t4D+6e` z+M-C6v~&$xqP=qv`t%ffLO+zobsb>F@Q+$-gH?p`_@BivATMCLQlf4wLdN2emrp zb0)(ICp2s&*f_^E)K0VjutECgfQb+}p(umMO%qToqdA~%n6kVQC$FLhL*#fj^R=Zf z=LCl*n{7d$lNx%qkL&_n<;tjNS*cTK=h#fyb9E<>$+mw6IM;JN2wL5}ddCk3Mzu-` zOB&=pU;)Lw>(Vd@tN4d51?Qt~KsDWQ|H=SJ#TA6o;?e{1T0DF++8~vURO@z`afvWP zl!uO+*)8T^e^;z_)LL1ql7-R<(ML6Ky38vX1gj_b0lmnTE7pPw zi{-kap`KDIp}*zeUvEcMh@_2r)jSOB7>A;eH0`ID zY$TYbVtzguzi1>gPT{ksw*CajjRQu&4gw3nd>)FHM!@vtO(4?03z%AlhOKKnrDvNZE-dAtH zhp$h_X~Gwes_D991cT<`w#hc8Fz#m+8=0K0Ozn39X?jW8p5`$3my(6+l9+xh?(9#x zuJ^;!V_F#gL2+Q7%I<4y`s0F#<{KiE#F?RRaiXiR65YELoo?|j2`?dQ^_1|zT)aTcq|s?4<>qI*jYWK{7x6f zy1GeNH-NYs07Q=sOGSB0K^l#op9@n|g>=1|AEf4A%+E>d9fvZ2`|+`Vde~9|_=%)$ z6K`>=Qg!`#^7EJkNJ%xy%F4d(ZaTdc*zDw|+DicQODtkfXZ~Otvm;l|`89H@RsD6H zf>HI$`1}?*3a);Jz(m<%{<9lbgVl5rh&qMAEyf@1Iu*Ek8Ve#<(mT|B%t~w)MZom2^8zfu4rIB5-YNfa|Pt4AB*9U^p(YJ5xv0 zrx@Gs@V~)AKj|zhIg}9F6PZH;+@Xgc6*ku@+9wA~#LOV4a z`WA+}j#xlqab6at`A~!BkE}O!>BPHPNWE$j7eD*OOV+gwy@j(#dG1FV&HO5RmJ=|8 z9^-sGU0GS+zOtW7P_Gc)@Tesk2xy{hMbRLtEf6R^S>L*?Yfp}czIK?)Rm}>8)E;$< zrk<$^C^Mx~uCca5z&sX`e>`G;TJPj4-DerzD1p2Ax)T zX+?wJpPK`%5CrN#7=0P6EC&TiSVN6cceJ|KJWKc!8I9e2E#(NgLJvZc5SvSQX#S#U zl~cluukL=}8}g)Ov$elhr0h2)$N2>Zqyfl#m)b2-m7jP^8!EGi28YoQPsnRqrURBr zg?_{4j5DkEh5ZY8ieEe7oEL2qb0vHraK7`XL)nxaFG9~W6sHdO8$`%f@|1QX^$cDb z2q<;s*q)#nsBLFp@(&hQn2@H97LqCE$|Q{6 zWE9Lvkj$KKATF?Wg%K+n8a0m*cx1ZuTLU5^%lM7@hzClJX6xQ2foIK{M?|P$03UuP zzR}vigpBCRa#ho zb55BU-P3N~B&({c-%1+%+4WQ!tOKLQ7;9(mq+zwZyqLXEW4|X|yxc>+=UGs~!~u|t z3uE{plW{{pl2ly#mNaNaC{riOoACqG1h^gk;Rz#Sl0UN{y8(JpiZ6#2MHugJ7$Xv5 zr}J3gD*N|_fmq(Uxb=A7TXjqt4!-j_M0RnD1NDLPNT%6EMl0|wwP0Wa=mSMnf2s%L z0kx?{d90BH{P^!c7I72Vt{$y6u_8BCWxY-2)QDHqv%}cqT*ni&E>1KbPgiYB7+dz) zUS=!+&z>gK9OD|t*2Vhum$~3wktr)3i8an+MjE}{pXVzEFYTrb1 zATSmBG0mw|esuiBbCtx$ubsB!?i5MJ3)gw;SRT%jMQ*(WD59#G&#MY%nvOf*fzY2^ zis__9Hpnt80oY7Q1rL|%n|U@B^P7@C0!-p%Bz}}cF z@JOj|}WTl&dagdS*h<-aKLc8BnOYhwm4*nLeY!Hxd zpE!tVc@@{HWM)ljr&APGw^jG(Q$7zk9n8_`i;ZDEDf-&;MFeJq)%o4l)8f>6xZ0sY z*e$WY!8h3;(cQ%vSJs^WC9E(VwvS=CjwJP&aV+IW2pdi%6;h1z)%Q645|zl^^jZ%6 z4N~Ui4)xU}`Fkw0lg=iIh9eB+DO(U2G4+Bhq4{-H_sELvUh;aFGnlIt+~aZp(Mn*1 zi$%78Irv!2Yv2CM(T^Fjm3P|vH^edKI*NI2BM3|X+dY4^(qLhnm-KXmZx=+i$82ZF zoC1;T4IlbMEK0zb+FKq^QR1d~;gpq#r>?#e`&t3&@nznAOwl{9mE?Xd$zu!2cz_1pz68p7|Sj+pXZDzNrmfLWWo|_GHyF)ukgPd| zJ%B9NH6i)bpi}@(IeRJJav`@l;vreRb~=t`HQ@#Mh10~_0(0Py#PNdz6279u?=pvW zfbBJG&||Fo1EwNyR=*;MvtYH+we={|$c`>=rzmPPPKth%QuHsN^1GWd?^k%ErKQ35 zFJ0Z3e(-2K0S@fh4R0$vI!eHs;E#q$i59_;xR*L&a#!>45xA?NDM5R+t64W z>?Q7j?1SQyucEWTsFe1T)i#2PI6t;ISvpf1aX4V>FqNu1o8P3~_7_kWvO1K)gh5E|5pqF7<8^>KX@7$jOfLSxe>ZB2%1;gwE0U@O<=(IMUDs~2(;L=|TO zqVeNjO0G(=oJkt6Eso}I3uEhHyOH@yhpd{kaHp*Zdc~I7#t)I;(o@%+zk{r*Wq9#I zUA^e!4whgWDnRt>Kk4M}XUlJfOhQD%ot%P%U@ zrrM8CRX>SIlG`ThIXtr08Z5_CU&Eo{x5{e`g+TQyV2{LFP}kHok`vAx>kJWUKV(I) zg>NdA+O#_W5uq{9^I(GX^0ALnj+<;vc5r7BN>SdAM7utEPO5MhHNgUpQc6?`2K%aF zO%E*^&!zS*yY7_70bcS0f!ub`z>XY|&786jW`sViI)+sF<_3EPIlRSr#ADt%6up}=de9|&#*zWbC^tqL@{B1cv5T8skm0|C3Y*pC(KEE|o?WPI zO(wziZ2BO-_PU3i?*6nt+hFY@8F*Jp9apO_+YmA3uv9|oAJP4$R3C=mZQ<{Z=j!sj z8%j@G8l#t?V}Ta!^do&_v z(kKzm1R=Y5+WF@%Sw*+djulMPk7#4quv*wspE2{Twqnx9GRiYOnn*E~2*Cbn_?>~h zU|L~&$00f5&^jF)7Y8GsSPA{tjK>?XZ$0&0?d7Ay!6O9M_&z+)aurxz(U!5LF$j;X zZ6l%W?TM{2ivji1i11D2(*v{L$zSP|IKSf(pP#+%a%;ezvC0fA=hD^$UlkYZseM)tC6l69&05(m>i+gZ#mlKM7hORvin9( z+PeX+z*@L$4$x;ebnSc$+>$HNeIlpr?IeFTJ3({Y$R0uM-N>~+LH!=G6x54((#~f{ zQ;_sa!R^J2WW~xrA<|VVsPpkBJhn~a9>ezVG$92}jI>9eaM3Nn2t54tz|BAf);e7d zB+vOZ;d`WVW=>R=$n&XxK06D}N>P@KkN^~HXr?k|?*`Lkn;{$9$@*LV9*>F1A-JZu zPKu9C)O}a+11SQlP}H693%7ChoC?k*aPh;@@pty=ui_bf01Q?UlU*9A+NZSb(S?aI zWSQ;VUS}l=jD~F0opg78y*|uZ{@-j^ni~zwOl^cbG;wWTXA69tU-~mKXA(8*{Lxos zj;FfLo4LUu&g?}e1vH6_GNg@Nt`=OW!oe_c@EDw`y45jUWUfO!V z#U+yM^dChT?W+VYQ#2g%8>juOEZV2G#6yckkvFT~>Q`^xt{x1bmWtU72W< z_$?GbnNPa5j%pKbR~tZq=LH=OmD>{f3lM9RZkLwLyqR&~=HlpRhnpJq)SHT#*2L^1 zoSh}CC@QeS@5qwFFOr}j(S!(Su@H{jbYc2*f##f}MRrs7=wrE8EY=kTP76W(4LYGuhjg%ZfsOX2iEk z#MzR%hM~!HiE1+qMl^?RqV5>bL_#nd3OW-iDgq{Crc{q6k5!}tm~-uh7&gJa*st&dXYVO z;23W5H3#}H62(VwLk!@bBntBB7Cfs5Yvlp&(;B{HF4TIxC3SFw{S+xhqeI)(Mj@XiK;TRxc z%=be#FLAV5lD+RwM-u9<6gI9rA2v=^aAnd+d!Fv!TzE zgzlfD=%0ixBMZadj4s0;mll6hs{deg8UAr$`5%lf!yi|Izi;jS&ojDzO8$HL|L%5! z;ji14{~x29F42HB1RwPCp3)s0vgs`DQQhB&(m#t=j}{DNu&H+xAuyJ{*{7=~L5b@p zzSb16Wsp>0VOn7^2PH14jPc_>DedRyz)}Qlj(7LRRmH;oxy^4H)Xrlp=enh~>tLov zV>A2i_)TGF<2+%h)`h!EJ*PgY>yA2;=i|`v_3Gi7(fcmhNk)e2GS5aXLMO-m+(Y7i zqhenJ#)@_SP1F6e-I?Ks87@c>0mREliG)4JkZwm)w#AnFcE}Jsri?iLWwOU9plX>5 zDT2Pi48jh!$~i*g?6oLqIX0$S zg@&Zw%#u3}hbgtkIAKdYv4lqr$~mZG8myENH%rw*F)U8Y5LfVa|0=>+iS7|fw@BVw zj{(<1m6atwCWk7eD7yCH+sV z7ET@O%7~&%{6qlNh+awJPt{76PYSyZcdys?HUg&>*}9c`o*bNCe7ntDzpfs}c(}K+ zdjLt;QX-en1d|}Qsy9uvJ52b-&7E}zog)@H3{S@NLpwNK9TTkG2R~9!$_&o9&8-)D>07weE(?Vw zAXlCIr+tle}HfS0w=B49D=FXGVw_X&?)iCR*j_Ad=L!*q#()~G;8c8Sf->L0r zpV?fgk~%>l%^sw-XYh~ZSEQknUPGC!b3uMZrYgr4$`!gbmg9z0o0KHidhutv+Lm|4 z)UjZwnnCTO1Ez#`H`h%AyH?Rc3w9kRm|f#x6~prs70Xr2ie!_M>*ma96JCW?&I#Q} z^snX|Y|^5>!uH~y+m^kOgPlggTwa1gT|-}I;L$L?7Zi`&D&(1gve=LwY`pU+Qo z=eXYQhnG(WC70-82P1ca?FsB{3N((=L!8FvLTQK&cF*6(z!_s>0Bx?4d1}|W`UCKG z19x2CupMN>aNMU6xTo30L_k2&6)6m4VBqR@UWaeTi+{TVFz=Vtu-Wew)Uqe*#=a() zhIY}p4+1f1-0_^?;&4f1$jVUM%JjjjxyZo+_sXx@AW8do>~?r)$Y6IcU`OF)_QZ~y zqRu}vcb{(ip=rH&HJ@^3D+UWVBO z#=6XJX3eteX+8kUuJ%W;@BkXLL_vp(czL2*DX@Eu=7@|c~qOZ)MhG|0y8X!FV~ZON1<@uH!)8^g&e`?I#Ex zYy-zw{Y)abi?4$BS$RiAI}J?P++u(v4Fs(sabo@JFOWizx;gs*tQ2_n5DQIt7H%r@ zA2Ogmlok~QPC&q*MX`J`cqS0PL|VGH)Kd;SGVvYxvk_qgqxykg-2Iw9?tjHM1@Rxt zN0f%Au8UGUm)F6|Gpp5^_R7LVtbW;)g%hV;GJ7a&O&uhOiy?%|a?JtNprm$34zN5V zVn90$kuN={WW*#Dj>{tZVhHrj@X`>i3B*CYmw;-kQ<}(}Meb}z=BZF`+9LN_HYBmj z6(;_tu1_w!wVxiFOFthHAE6I1`*H)K4R zyvivnqWNU_h)GBq{5uYTqc8ry@LKq)%<&y;7%}OU&g!4D>9TBDV0BDkP%y~HJNYgq zXh=1LI(T7`2J_evg_2E)+2=dfoOP%hW8@+1;4KUJ1P=}ClSnx?h8PXyugckb(TE=J z=soV25!H#NAzMK5BSUw9U};})4^#J+;n;%Y7_WuqZ7HPR`sM%(dF)H;Lkh+qQ0Xl= z)H67FF_U8Mk*JWL0kH`OmF659ET$v;7vo`(?376vy_n|1Us5LgL>T-N8ch_5S2N}* z$dS7m+7+*G3oFb$N9?mjzJxR9NR^r>kcOh&&5yo-qM<~a8j?_BKxgn$lcw97(=#9V z*FWVX7J3Mi{7fv=#e%L^iZ2EUz+oHsl`lRYWz(|kH{w{hr>d(Cyv-|u7Ju7wDKGW9 zQZ6>OSiSysHufu@qR+t;w17ikFT!=u&TOiGaX@GzRKwj1q7jZYxDyo&^kk&uTb?=) zUtVx%t@1uTT4K`fZM7e=RAtytJ??kqs#oCy!6N=z1%Cse+uK!eabT{m=N`e`1=>28 zV>h!S%_eZGIaqP?TL{`2<>&|L!#`I+mFNi%a0^Qu&6wzZ)=4kVDQ#Gee4yUoXQ?K@ z)I(ft^z|5!+9!WGniJGEwM%T0lkX(P)n9~RJ2mv*l*SdMfu>;P8nUY|AR+hF<4TlS z!#ZL)uSP0U)5$p>1W3MtC!-r zV-{5~hM@j~q09N&zY9&ySdqOXL$pY@KBD!F&h_S2%0YgX`IW!JI~Y{TIJU&=AUFA_ zzFYR;%fnZ;EY+gJLA|cyr|$31(cO=FuOv~*P%wFHmxWG`dePt24NNm*GdbsDxCM3W zCd5-h+666dZrAamM5iTQpF&P0_7*(*dlO*+77u1Rck<4=SYe8Vst2HnEYf18ekf>3 zl2R1sQ}&S`TXu6>Fh|AhHqDqT-}gG<+8<|TXq$Pgc&zVvhw$N_sT^m-zCgfK{lbV{ zGZl6p2hqPh)M^9}=a#FL&E~WJ%2VW+iPyXzV>oooJ)+W{EuNM{M#@e*o|UiI#i@Eb zqc5#KjU6~Be>tlZ+o^-BVgp$`OuufrzalPw4!sotF8YYaGvm%lET%YSqjW|cIFB_C zPG{H<$yiVYq9BH)g$SpV8e}_=MTUOAWgNmwY~$P!6bH-Ilad_|Q-~jM$tSsz@^YD^ zrgo!GFl#TiFpysH#IzT^nPW!B2O5rF7>cBNf4ItB>ON4^f@Wi4z?TvR;7H^kD2fWN z(5=dA+mGW&1`>T)XJ5AudljFg15}j`S(S~MF)zu__XeA`zKe_5OOn_wG0RYOt*)7; zo42RZ;H~KyPR1`m3d#8aVCczm-Vijd4_C8yV$P2s76tXL+e-K<39bMg_ZCrdIVl{0%D?9MD<9x!0_j_)G_1ld0Ds6D& zK5yHx-~wgi+FR@a6;%N6qkzrZioed>4klXMAZkHXfnA1rb{6u5PDlVEH47QxPVY>W z$C(1+N@Ek-V5R47oX6|*A{DSbw^LN=8H%Xcl~D~+@0814?%Ntu>u~PA`Zc|1hDxQS z=#EN-vHkSZJ4!-~Z}8Ey_qMH6p-LEz_xOVK<}k?JMY#!fsESkm>egak#}NX=JsA=w z=>*m^A8pW==r}@O6>|*ZR;XZVh8q=woKg zC+!R8hA*~=$EPSq49OTm9&=N$+aL)q%BFQUSMeiv$853^i?~#F?2wF@8t~r$A{tV`amSxXgOlM^#b5rNO>r4&L}s<;pW$d>gN_nlMc#{cmE|Tgzs7 z1Oa$47?OyGjBEzTmSyk{9!#-$g+|Qbr9b*l{r#V8ic$Oo;g#P66m&d8>pZ~}%R_*Z zmzHTfA3AcVHmTYVCd`J?jRn)ktudbAG>B)AF!t88CUM;s&^E6>nM@N4j_rG1oY{M4 zg*BGG_?$aKwT%%od0UyI>uKOX)H-f`UFH^HfA})p??}w%>Wj%Yx-~v&3Y}=m_{wBV zd2>UqLL9yQjX#$x-N{%}fotUWsJq_+Qg*457@Fe!6@zW5Roq@{^Pq5Fxk%7z;n{0D zq0Xy7+25IQ4qU-kknEf3b^AT8!>F*k?rkc7fv?6bNaXO=Vt#K*vSL;SR}(~wD86M1 zxU-3ykd#uN+%CW>czItFRi%lcSsbgI+JRtYQTFi&dHTIwM*pked%JOsZLZ{P?Ti>r zU8OoN=ggRdozXY#19@{uYJ2;|Jm!3a6}12a?PAMU1E53REZn06$<|SMkpp}~EzAUD zeWk(GcnABUTK$!JYtWR=MB!dboK98dmdDNL`-kX&8=aMLgR!;NvOEQ~foeUf54Yr) ze5J}4Qw7|)khzF^#jRI0P5n!P1|#!td8x@u43R=;sYbk(>RY3Ggj@JLoC-D$8KoT# zly>8{_F(s~D~=`BXS9q;A}&S?Y7beSazV?Y&?sppWK2?CFX5eRd=59`1f<)V1WQSF z4_b>L12_i*7b|XSR%PesdDW{!y%nRsBKH)rm5L%0GkK*V=Yd7KI{Y&`S#0E)oj|G` zk739vuBh*XRPs*g)=oPqVu^8{c95$whP&*Q(9P@wuPZUrj;cXc7QUIw`q52krv@AU zO4!L~yb%Gj{wjdsXHorK3P=0XNe`2>4;g4Oym}WJrgV`D;RM~2?Bujyjipnt8>GMu z<-(5$cdVuadljUG4!zdcUY1vsW>HJGAleLRHUn&QkO_=s<68|QHZyoz8{kwr($|Sz zn-0_*x71f?{<~XY)jbDX9b1&IX~_Xyv0RC!!d1Cm>%oDN{eFbkIYo6Vix{B*4;4G_ zOZr5|cZn$=9RUvn`6RFP0Je=-v<}Rv#1C$= zK0Eic@2$iIiYNXmU|j;d$7zA10ya@!GL6Q>eszLzO!+h$aCIeaKi~}k)faU)dUT(z`GA=QHL-X1-@3COspz2M@ z)rRs)2&tj8RvLKaOcw*sV+9i~AzJ+@+l2#1tPi|iET)TDcy?Q!<$>3su*`=D=WG!u^UU}a{VwgKH~bPaCtsBf z3=8%Hr4ATSOGGN10?-2TF=wF1Ska+;K?YR9kxIT~fLq%K`q18%uOGwA>)qV7 zhU1g`xP0|8blFw2(kzpR5U*21e|Dwy8Ro5b7_UNu-p(hcfY4>erYy_m&`m8Eb$R9} zK=AzvS9>eYd}Xy6Q$}_yt3&hLE?J9OX~tirM7mpKWrynG$YQ!9rzeNi&adL-?Ae}s z^fB0b6|=c*{`~0L?d>H1@#yjs{QmUpQp_{e@ht>HCn&9zvE+-3w)@~t*xaQ{6OD9sM>fSeP1jATRJc- z{=4h@s+x<_OJUljbZ=pOoIbV6Y*bXtCrhjy6`7~%gjmzx5xAf#l>tx~djEHF0Ulk~v zd(=~JXbVu($1ZFu&=lnK+0^hsTFszadf&VkY<%c-Fq<%68=W|mEwvY!d$cGw5~z z)Cobck14}?Vw>@H$MyN;`Rey8aW#_xp{7J87{4tBM8sfoNGqsloEpz4>Y#AqWISUttqL` zE3K_@X?=K^mF+fPScgZh;VVZc@Q%mys$yfQMtvt>}?LMKj|oX20eC+B{mbxbUc4dXcA5^6MZnsRKqKc{E?2p^y# zf|!{4L&@G*=R9p3lxH4^nk52j;eH4CN!IX`@nz~Tkw$zw?G(n>^C+6xzY zSFSqf7Q{1l;Oh5Q2N+&Squ>o{?AP=$VetrV^i6^3yp%L9(_kiK8 zQnDLOk}n~5qVZ|O+e6W|&Cn%tFUA)DuzXq8_(PnNfwlYjZ*kk=5EFWOPzAKDDz+a! zn?p;-iE^AZt>^wcqgpFR$sN{ITZc6M5j0Jzwc)Z|BU&%bDC3KS=u*3r5Ur&|t-IMA z&pAB0*i_yffQm($oKsV$kCo@Vpm~qG+P8mi=S&SV zp$4H5f$LDcU02&yN&8H0D(cMOgU)T)S*u;QZxSP~)^(Ei#z=D@BAyzk*?VY*bOIll z8B|3<-M<4-I2dqVa+4Uf^TmDlH5DyxdmYTRmJ!1+9olx@wa#x@&PVLX%zWT2O$>+| z4WkjiV8fGiUKKED%q%G-^^S!>u>j;XZL5Glpf`Wworj>)u%L#B^sX(4ubY__bXeZx zZcAvmnn-+G-{~F!GsuJHxs~g~svdIOVVg&R62l#)gb78Q;Y!knJfL<;PimlqL z9U$LH1HQ6~q`y_&Uu#{`^Om{D)TpxCH5*i{*moQB1TgN(BNOPt04~_%!;^z=_+9S` z4OqVcd1$!89$%uRV3FXo>QRDjJ75m|_TsS{ekLzodm!K0Z5k5Q)txq-9C-Fw_Mm{T zx(*C-mWZ0TEY%y3neRNs^@J5F3K9oAFAHA1FgFTG*_vexhX5$jg18+}%qu5->%x?% zr1w1>0j&w9mlp?usmvo>Bqc9kkVmS+gOHoXpfDg5wt*{PZ&aOf{s6awRl5F0;EeCl z^MJDNacKMflt~28BWCZGS0!*jO%DfjmMm`k3E2DLXMt_md)-u7g!(>JBU*YJu|lP>F)uu))+DX{=bKub)-uoowIf&D!sBW=Ig8STEL z13I?A=!MrlhgGDo+e9w=G&^CuCB$fyT}4;XNRFCV9Bx^VTM~)YgH*al($rv)IfZ(K zk3iOeVw!Xo1~(0zk2;DYdRaAAe-x5&gClSg!wP|xcuM55YR;1GCQ0h!I`*r(wNAlB z-XRz(8>Tbj%5A_`CuAT!a813GWKykIEEZwnmPc!#WEw_CJel{9xWe|zS$GZ#}AD5Ig~6|=8bYQ+Zc^F4TW&TY7f!0W4|-k?zXS{ys)+=WgZfG3~k6Y zi3Ci#9A#}S{B(TYt+_}Dkd((fc#UKo~tuHn}@wBZjt7o6_S+6eJKoL3B24q>m(oCkOfjY!dYo{ zMP=^El-IyDAPhRbV$fIs!8MA&!&a8;XpQd%g-148AVpW6qLD6$*uhQwzzRJ7Sdt2M zkAYKq%fLoIk>Gfl%>|tMfTlid2ammBr7`nBVNl54xL;=}4QhL2noQgcFlMZY4^E=l z=1400T<(_6E}g8jf=(9AHodGMzX>d=6P>thJu1i!ci1H%Gh~)cR1F5C>qrFASku67 zI?HaGGM)Eg3lJwTf*w`#S2vq@WD9>zBw>B|-t3e*LlKWax6JOKhKf)p)e;na#0NJ& zIF}elhD-x9J#_>kt}7;OQzrV&M1N@ii(i;4LBB~+kjRIy|F<#=sW~o19I6^JLQCDk zDYvdDwKJp&K{~0~WI&nwNw!`9A;HQa)-CkG)V(J((T>q!!`_-{-F2B_NKo2#R&w~=TCAnyDXC6j z8->zgSA}{-x>u(5lVw(FI1mS2$X^j|q*4XItpq-n^J0KcxDrEdWUI*q0!D!Lu2Pxg zW{gYvYbZCkU=Y-{yy)&blG0b~m=0}0)0BAPCMDFyVz|O@^`jQl){qUZ$jIhb)(Td| zmP{)76y^^#QX3Cc57-so_dp2z>WRy~Xc(f-8%A<)1yv?S;4^x?`EfPE%-A6C1`%DD zC8=798_#}|*A}ezCzoh)K<*V}n90O|O@Sf+eoU)3bWcy0dTgd>8lx09Dv`T6L?}|! z?9#%6&Kqi03|=Q8Y!Ed;RhmPj5u=X_1q14=r<^FsDrYjOX|UrLuCey#54c{kZ^ar> zQ}DJ$S`HP`Ki59mGE-Dcr2IOjTYoXDi$@ zUTxMHpO--0@wExq>YORQScD}p^dqsET*@g z^qTou`FAX->{-60^KyxywLu~VL3=Se{e-h4WE3SjMCw;pE_0~4{P79fJSt|X95L-y zXMzt+Vlk!xwQ)={QVhT~W|1GH5SouNv3NFnO`0sEsERn(Sjv`^90TFE#AsfQ>x+D$ zA!=kp(TApYhuee*9RFc8H02j3h+APdN`^LkYOIwjxhCiY3@+ ziK#GB3@8PGYdLL#uO*4aZTT3rrvyWM5U8X-MQ>u^lSWNHm&@As6z~rDlU%sg$JAl7 zN@M#C0;2~ls>gs67B0p0aERaq(_0nsc0`NAbvJXF@>z?(Q6E{*3co6tgfM3D!$czq zz%zvJT`(tMF4~n3i}6jvG@OYI;3@j&vz3PAAK&dG=GSVZc=PtwhW$KFAbQ zyxSelg!h2_kO`!~3#zcIAM>Z+o~@PFGH!w2q!3kM)H2LN)YM>XY`_Q=RK`=+QhW#iC9befST(ke4RLA;PJRGh%68Y{-*4IYH$Y=dojE%IxV* z9~sQamv%8J`jI8}WjZ7IOYL#CiQ?}X>(qoQonM;^QY%~1&?5b0ryK;+fMM2WuP=1) zd4ND5*Ft;@V@-mQ>sZlfy6B#`@M~ zk7{#LVkJ_o@h%ju-~g9!!iF#K$lusGN|1;Kvr^0~A9;<8(7ds7wvi72P)%1^E*4By z)XKwaUe?R6jB!!S1q{-~#A`pD#yzx}S9Md#JwkA8WE#(D6E-tbB`bru^Re1p`HePQ zr~@g3D^P{f70Sj>?9!`A8dWNggl6p4x9>5_h;@aczm5aVNKGL>Wm=UEqpX`=kcyE& z#HcXjP#K<5dsRVt=uH!qt}B)&caY*Ar*mbIN|~i|$H`l^Sy<+s$$WFfohmy#p?+YO zNjjpH3y40@Ax3L3NI6mg#V8a$K_Mf`ChKnk-;-`a6?s(q1aIDaOu`-!sM&(?Tr9kz zBHuq<1lT;j=0Ghr^};e2);5ElbrC5;KJTQH%A3rh53-Oe7|0-_}IO&j&+ zaVu`Mj$$2{EXuI&*`Uh{X7)P`c#Pxu4#$}hi-MKOtHP>a$Gz$ce@3xajm=!ldih?l zwg2h`g%A+HG^52)ifIAkj+R0+F*zQ46*VGnl5{ISE?I^`Cx@10p4tQX$@ku0vL46F zduvu%(wG;Q227fBtN`>n_=p`d;0>*$CcZN4tUSpKHHJe-3A zRJ!VOy8l-F0$@qAzUFx-RW*71c+q9nOPN{i24jgWbJon2tGG4ooa^8CHR{Zrc_NyN z291N$nWx=;+ivM|P2)uPYm|y6o1G_=cfxm@doPYt-OCg9MdQUbFNE#~yPbhD;d@xG zxa-aQS^p-M5rTW-zJB~eV&36VGb}&gzC)+-aqxv(2wn(rT8c(&=c9#;4VO0e0#~<~ zw|3OQ6k67=fqR59R_U7pLn_=+93FAKl%}Za^NY7Rir~4O)?Gwigc@`^WcoG%PU+KitpDybt$3 z7S6ZXYv+FoqBd#e>@5WR9wT9ir3xm?x$y5 z&m?WwKmp!HRC?}~*x?g=RHkDy;HEEIZqBOG9{QdRw632WeolBCkI?4uc)ZSB`@GLg zrLao>0`d77L;7!stG}ybFfp^R{~ff(_-{&7F#hKf6%2pmD*xA@wLenv|2NX{|CIVa z30PzNH$^J`UpoH(OUM6TO~?P!p8haA=6|N+GyW@s`VRt^@jsWPVEp%GDgFwv`*?w!Krd2}KRztj~J6RVXI5`e=d8@CFBA9_L;22;xgSOGLeQdb> zR;_qlP@eAgftP<;E|?S_eJ8)zjm1zlGcVs{c}ABV7}1W3!#JcL)6W?gTyo z`+PrvkWzDVTvOs}b1kjjzkYLi`9yA}{r}N+PC=ptQI;*dvTfV8ZQHJTW!tuG+qP}n zw(WV{F+CsC{V_lDoslPQ+{nm#4>k{62oVaQr&r+3drf7!r|NV=YzLT5k=&TSxT^`zenJ}4Q6a~X4Vg6owo8qhGqpj;r ziycATJIYK?0{xMyq%H+lpDLee=)(lmTtzcYdaue%eLhuANBE zeBH?B4cO<)@g3zGdfW)WQ(Rr0qWVZkQCrTUl6#ivT1ux&SL=h8ik`CSTQB1NeOt;$ zlN-e1)$!%-{{6Yg*URf|E%XU4FEY=PQsvMx5cp*}S2O1h*n>Vvsh|kXBGrv6r12=F zuYQ;z^jBl%#B3O%LCv|2?HR-<;5zBddXZcX_T-lHaZia3~cb91~N!%8=3V z+L^2eV;~Zf4sh)flX+CpvVAylc3>YJdyYUTY{;{sOn+IPSZTU)cf8~^vDdq!>t{b{ zg*N}W1VTjhj?{BC_siTC(U6j*rEoku<#mO)7LoJr7S8;=k>x#2s>eB=h?GoWQP%=5 z;1cx%kSA=QJQgCxYJ5Ek9wl zjCNQhDU)8ADgpigz||b>VDi^0K7VvW>a*_bA7TK1`>!y}yM2LFi?fJtJ2P@?`XbdP zABr9&y%qRI8S9T-&(UWM>dB^{a8&CxW+zIJNn$E&88Q@VaSgek=JSh)(&Q8x14Lzd zR>e3Is9weRVg+TlYpM`Q1K1Ht;-IQ%#&~>i-5hBuOIQIvoBKqX93zLMY&A&-?l}0b z;X?=HLx-s=-%-$vW7L{)G2| z4HaksJq0yviK4O$^dcRJ*bV9)A3+^&F}6CO-&Pgoa8st`xuqmIt~wgoA3o@)vq-`b z{c0MZys2qB-pp!3;NzJ#A$Oy?ryOPl_mXIT6jlh7^&p_dREDy zTF}X>c^Tn|ux2sTem`r~J6Qfa!$`&Y5S$WGjtaH4*i6_f@O#LeusCo4tr?3(>pQ8Z z;=g)9JH#=vVmhi7cTEJ2X*8Ko{a@)ES4R7U&669DsDjc_eRJ^j!$%<9EU9K?;k=lDkdWHa zF#xKOjD7+;7<~ofRHZu}EjGz9mk#KnHz(@orUi!?xPJirU(2se_K`_C(>mF%pB|%F zLN%GDgT4iaY+Bjb(FGp%`+gC)I{atn)H){-%tZF1sqy|f!$nzm!WzZZ{r8B77m^Fc zkqW$qy)bU~5Ub|2Vfp9)IkqbzXM#>0_@Q1em!tBH(n;~ zyv(=$jfq5$MId5&D+*ey6KH85^kGz%l@LdGf@*NhbxaWjwQ1ANY9a!t)za(;JSJGz zHep!CLsd+th32VCX5y6m+^2&usPG3N^y1ow4vDT_Oe z_}!MX?fIUqzt{z@jDLg73~x^-EF;_^n0lF(2J=T!4-f>Jr_w6f)z(MG@ONIi7`;Vs zJZzL#UrcL7^v0flMqUBVkcY01d3xs)F{rN#6*#^@`UZf!)X2yDTWp>}wCzOoSM96| zU>76UnI$9^ca4`W1gx5Q)-^BFX5>FVVKc}p%jmowx}R0(uuTihyYV(1D1%f^x_x(1 z109%yViZ-U!*_YfC-1OMi__@3EA9}3>Ho1XN>OD7VxN~>0uk%9SdFin{|FRjhP?8O z-y}wnb?Nf%gv^0r$l^d=B%rD?!n;v{7T=M^^Kk|D&yqUfu1UF%1Zy>Fx_m zK;~GF!mQ|vOh!&$d7(NL&1h2L7MarEASgS62BJ%)s04PC%Mf(G&G$L|V=vv9@pne? zHyFK!D5^x?Y}+CKn@zLYiP{*5i6e7KxQf$My;|a<+h%&}2@(@fwU(6OL(G2PzAP zls4B$OnCxT*>K5kz!>L4C+NrW~agO`TZ!9@B(k1}bO*6{bJ+fq1Qaxb*{=M^RDH z7z8y>q&1`X%z*(}W}=;K30Mt`pt%8sz-l4Ksy1^3YMfEwo0LcF3E@iq!B^6Bpi389 zobk#RIQ2m~rb|OJVq|XmH_5D7^^iD7EwTz<19nCW!`lU&2t@Zr5^nne;9(K5y;cq}E@{z7tPcFs43F;Ok%i)hW;?NY-GO2YtpC$A|Q zTy4p^b45vkS7jcr2l-(DQDMWPeZOW$oQGGnR6G#{G67k6m+G=DDgM{h#EPrv|QwrLzsJhX}xknNY zM8wHV>5iunwTc#iUhSV?A$ilEL@6F^1h%Rz?9f||A)s0u9b-&bFRq)9FOOYEYpJFI zQQ~NljvFpzq8d<$u|Fw$D%%h*MBmOjrpLJr^hMH{nUF!aMB!%@d;cLh(oq&Rk^Ka| zwSmB0@BboW(8!y)(Cuaf*0LM22{xhJGOQ}ejtBc8)MYWc+!Kg)n3|0^%qJ9&DsHb( zF&rF8cmQ2XOvBz*(|eHiJaaqesCAj(`sacR8H!|NmAxX!-Z*V0x{5H&9EF2m zLorzlH2znv&NpB(A5xl$7wgtn!R1oN@7(JOkkzph$}Sd_$JPnP(?c7B-RG;W#qtKI zt}MR0HqZfY=upQ`zzhBzxjn!%R^A7|9&Yrs6RHn+f{T7^;`3k4rd^OU;nf`w zeO5CDG7lHd&&pdMazW9!?<1?zN3JFGQG1?O z-x|<$vJbCZueJ>hvn4prRZm=b(1-7|g|V?+$XSwLIY8$h;b%t8*a!95pcR2exJ0bB z*Ub5jygP}e8Qel$(MyGa3->up@Mj|jqDdbr%~WLG;Fb5r#mT=s6Dxd3nqbbn(l&dG zwxX8-17!1@p86gb)uZn3r~a1s#^ZdUgeMV>Gimv!1wRbsn}Q_Jjy|ExK~rzu4FA0Ae&8Mo->+pjZo0M@<(V*;%ts zp+v+zcmE3;qh^ufLo0Y%k74ehWh_2xN~6DjU6__}>)Jp0jeg~IUjtE}@c7Rv zmVxGJ;~wOh_EM7-srgxc1}PsD{RoG%LytyEaE@wO6F?7^Y){RlhtaHRRT77oNZE`E zyrj;AYpT`?g}BJDGc2B0I#9XXDT#qS8o4N3%E3QXnNOH{Gv2Bq40SAJk6<+qu@We0 zXSVE@w^C&r_&bqeja3BkW#-*c|JYgKhkrIEHP3y;-Dh7$4YjaxC5_daltQVfmb|M| zoM=SjG$%-iz`&N4r17G<1~d-^U~Uh&AHEl?sJMsdgHZtJcr9@oEdelJ+ZCDeo#Cmk z&LrD&F3!+(LeokZRE?f*4cE*oT*MeQu8JQ;J#} zqOXbyCivM9OA?r(8G^mXx4Gi_xojj^B^}()By2%S25^PMiFNZL=FD@V1hR-7UJ;pF zmo~%V+AVn7*(TcL+=kohCEf%Y3PDHYw>>LF{rowRW>6iMC^`%#L89B0z={U6>>Ej9 z{w&&zkucXzw7^YxnbXQrSp^L|_tIsu;62Nea11p?=Lpyh~z!|a!oz)+5qV~iA(vqqYUAs#qC@J1QSt+h11 zqO|V}Jw%*7#e81@fMl8N%(f;?b#Yq`yA2aZX*JcI>*4fL}5t(`Lky(_?^x_Mn_Xt+Y3Pi150m7q7)>9+c=?LgC^dFMwmLe=>H}mKW64YAB}MQ(^`ebf z@DSLVSLgKaYhTkOO=FGk_tzo_lAwN*;%_1!?eD{Rf}7T0&(G7(XRr6~V(e|{_u~04 zpeG6u@P8LKnEnr9m5G(*|A-s^17nrx|7NT*{eNSu{%7U?m!>ZB|G-%N=gKt^arob^ z+_mJ`u~m4?PGVDL63@8{K*~ipWf0IUo7R6L`6%h_m#Y2Ur-V@J;>)~bUA8w=%*Zm-wRa;DziC2UGVZ;3J-l^@ z(qo-s28sxg9%AWIk6j}BWi5GDJ)XQ^BZ*jdk_0(vUKiZ8s?EqzjZEi|4=^;ZQDc{$ zQ&lwwc|Xj{TaCpa52>412p_K-vFH-G-t>IScitxh8@m{1GDIz(!zi-aHD`sOs*k1J zk5prf&##sZy$xv}i_520OPV*HjvTbOjm~JIh#0<+r?v)TrOy~{?@rKiNjbQ2^!BU; z{jxtgSs&i;rG1vUZS)Wb^ysHH1XUjbSJVa1O`?`!zw;8@EvYs|3R*T3qa{gSfzO$PIuE{!U~K-sv~wKe3!_S3nH5F zC<41Npf1&^Xnm>(;s{F65WMOMF!P!Covng{7y%Q#>S+u>i0caBHx{X@}^;lZOPiGoXaAjSj?a zvpWOgv$^pK&{4wIs-jO$@)6c}n897m%$6r+F>V_^Qq1rIKqvQnjH^JbnHFA-V-Bn@ zJ1?Xe6&{{1x2|`-_M1O7I3{P;=iNuO=-bibzYffY-p|YO>hAZ`_-3!qYin-IY%gCA zvAdT@4nLl;^o^N5Vj<;>nDunRN?K$=LJ>E39VuE=r)5-8B7%8!5++>Nj%e!+Wy)!F zebBCHH1R(96bTLrD=~QC8B>ZNYvOk(cySGKSEFzMXCP=d%*z8kK;vl~7{|jDOUdqE zJc!}B#(UZZec=HmDXU?j+&0?ps$_NFB>tW1c|4Ydz#~BcW$lnr4+Rgewvju1^Zou8 z9tNfGzzyo7z(3MQ$`4^!eS)9}*8m7&x7{b7O4foQ@tj(O5mmt0xcGm49SY!H_wK_> z*k{l!YtQRkP!sag6CvEtkP<j!Su1&2pL1&ecnQ7)6FZ}r% zx+RR|WdZMDCmuRzkt_$-fW2;f-y?-IAqoU=hb;|TbxC4Ok^S^^(|XE*g6mHQsBOS} zZZK>fm3B#l=|MTVXh?V5qn3z3zLIxCZ7234Ye>Fdo<3qWa!yy-tw%LMX+;hVpm)5Q zAzr@GiM$bLd&>i6nH>b`L6etfYlX8&-W6BtD!k73qZiQt01ns-5h@YpPrZH5R$vza zbJhVTa{c#YqBwg9D|j$oq^aFnB4tbv$sCvBQFpAJbL{vJIrTIBzO)4ji#fZxOmMPB9sid&;)pD__{ky1Lx@&Ds46ZXBIfr-U>)U zN?hY1ZP7TEyaJ*!NAT4`u-mZ?zy$nIFy;hi>1UKY=~<71X@G$tA$T1BjsPxDER970 z^bn9+B{Dvj@ZXbHlgJTt&=s|Owhd=vnAACX1nUT)dnzXNn za#@KZY0_0C^g3?iN9MGhuqOe6dY@xcj;M9R^jb^p{QcK2G`WW)+Fd4v{HwbgSbU>1<@^1rU z_&kMHvBU$wkCxB*h~*^@6r@eafD2Z!NkKO<46Bb4F2s#2h&^glgaYn$v1yV-9C|4e z^6>m{VF4YX6Oei-vy=0eUNfHLi-CwzL1c*+j*3T6LqM#8u73_A(^eyZ?9j>zo}Uh{V2f$G(yX=*MkP*C=6eES)a zSfKt>VvmMV{eU9GBZ~)5?t6J7kcZ*F>zaM`qT$*DU6v}oav9ioyK1Evqo7TKBGHx4 z0RBi<)c~tkd%w82OL68h2?F_0DR8N{NVrS$gRs2yz}Fa0d8DZX@&HIHB^C|J%;?2S zII}CKGAZ0bc>@ zmQy7e3sVWfH)RQtfK+4>N8$kFfY(#ar4ZtG3#_mqVwnX?8u8vzQmoz6ZM+z;Xy0;_ zm%rb+c)c7y&u=$rlN7K)?1g1kC{`7E9KV)qbTC}a4uDfWzXYN?a}!I%x~`RYFn+Hm z>2#lYEfqGm(FaqRziU+aB`)NhXb$7wH9FR(2QFKwrj-k$az&6Yki-do&g-6JjFFcf zeG^(m5;!h|&gQ%NmW)NI3hano3Q#zHPYq`3%42x(qzL9c*P>@_IE)2d&nsb9&hl3A zm&hNegm>*%4uFEXGA9A3jo-S6(w5PCTDr~tewl_dPyl0G<%~3+_S|Wtic%J>7HMXx;525|Rr?BLgPLv$9eEXcqOi$h-uCL;SsYv z;fL#XAp`I5TnNE%QeU(b;0z!4n|0cBBak{*ilA@3wR;Hq#0(xP>;uraEiEh0^MrIr zp9J7c);;}4g5%Q1B-)#)973>3xN4`(`QTK_9pPwluLQ2S79{iGWo>NFwlBNMfi0(J z--3F1bmE~!XB+u;5?|@V4KU^9d=xvC%D3xB2O_7h!{$v7V{j1g^~Pn-;4|emoGtn_ z6E-U$w@Rl~%&;?xFTCh7OR{064Q6r-{T5Ce%ou9+T1g*GsKtfmSKk$j ziibFy|K#Gic0aAd7M=DBHl zKDTY}{k(7dyUIF@LIhR)f^6&w4i8_VpfzR1i4Am23wW!CD-vk0CAjirik>kzI3lQS z)=+f3tx?exH*q>4PD(XS|F}-2TQp8-L`*Ao8;KP~)hEV1{Cgi_c~sN(;{GiU!q-R< z`RCI%s&rgl%HQ3_r88AKFnAN%)JN4WlMR9GCW5eDMu#~%r`O)rgkGv6i7!Q4F+fo8 zjcif|n_OG#qzQtmT3SU)G_uQ~f@=W1)?8FcwE0ts53Rv_^0(wChhcFLN9M7*-Q{#t z&(jl@+b-rMXD;Y8v?p`+mh!j4FZk~CDcy0^_;|2LtNG(8JZJi??2Gb_8LRc2YW{GY zwQTM?ld=1 zzW@DGEko7Lz{*$$UHv)hEW$KF*)Rv?FfE&Rwo056_J}rts}S7xozO`zqNe+c7N|^P z4vR~W_kgRbf9@&=@XN{p;%FpXS>wO3lT{jB8ZywS)qS&7v(4UGhmdsq0k4 zc&$;FmEw)O)aYKmmFBZPBY@YcLdhgsHktgVkWv|f3nxG(CG|3TShioxyo-@dvN@HW zPE+}y`3C1o2>zx40UL@7-l<}@Ky7^q(OwY@a9A)?lZ6uqyoH|QgCK~tBJBoZswJ4n z=fy>O+-E)CT99G;EZwF2Lu#UsHb@k)l~^%W>%-MW*h2B;;F^DZ`S+~D6W=q^M3xsA zr}{ie!IWe%-ZGOkGg zgk$%uIa2+IvQ_D-m13z3c&^-;hfg#OP!Jg>o9hh++~;7l_zrso7FV`=n{#x&sWC1ga*WxTpl<0ZibAy3VSjsgbFW845-Mt27* ze+-+IGf2?d^M(?hbNW!XQZX%lC&p;sX#}}qlzfzXNnp%Fd5LAA(dxSiChW3C8=1`CN>%jjORDwqZ)tA=i{OO?@{8E8>3UYD6{(#QlTg31&@EXObCX>4cx+vtim<#Thq6gYeBxZ84DL0v5@VJ$ zf`GrU`(;H3lOo?|DRPb%@?O!ptvK~%oBR!ImNUj0(8_BQB|zeW67fa`Gff+k4bj@z)(5$etGP3F6^Oz+|_ z=YrwY=O*2$LkYA=I{!`#wQj;%yj%79Ni>mLX5HPnTQeQ3woB7$o|~@7Y|DcjnOMvp zdd)3bp}ThkJ=Dl#n;%twWZ}H=Bl2dD_;wwV=9(l3@B&RaOCzN5@VU8aCPfUH6aPN) zzNQME?CWNFZ8=2VKXim%8~cGbI+fVi{tZR(H6MG0^rQX`9vg>gnp2O|&S6B(=2N+$ zsHM8W`r|)kh00(h=%({rf2smrICB3PZM)$2Du7(LB4!(VFB8IZ)l01uVVHi#dX>s6 zaLn3~_r_h}u@#BMbtlY=@@0_A9WvgT{k2kB#~MGTiO&(2=Q|h;kx=()(gN8!ot?NZ zs0kxv5fYz9t*8M-f4W>5GK@=?ur*8^HCUN{=33%_9~Q5u&mzDZ=Ny)A1lC_+R#e)F zi>quBjzK1%IU_#wWc|a!IwCLfC+%{`sez$2|CDxm)OQw8>!3**o2^nsUMQ_I)I&@R z;46Jf{Nsaf19aelG3)$^s_5GPdqya815ZqO_ZXBt1=`*QAM{{{qXfjVBzBJkneFeo zs6)OUZ@!E)|IQ3`X$BQ^?q+&^Llj6QV65gi*&LrCPNbS`If;80Eau+i!pSGQ7Q{?O zRv}hQDL9h#X~kP_9>>z3xLxC8{W5MQAVX#TV&0ISv&~^l;v-|f!G*;XtAi{alvFbb znF!cGf1NR9Q`biyL4jo;tB8$U!p@jc~rp_DwD&*zJ6TJnjIdKk%U6>nBLfC zR93!ua!hlJ1@tdBBR;L+LYjgrvy3*um^x8zhdYr6-(19GL)&jRU)U83j3qI{TF7T{ zx!lCe4Iv5)0ztdqtMN19aqF{e0Jh(v+F7-qZuQJ|3TdIM<;!*D_r5jN*p4$I7$UsWhf& z!4py@dp!N-(!OlD`>>RaMu-IWd4a zU0-;|PNjNsm@@^zq9VHFka`zUCwO=^fF+wD54CjCN_UGKX~jZC&1l`;5G4m46q1aXRy0mFrl_!F7Jf{~WPPnuq(6Tm4*rY<>dg~0afi5I_9Q)2CrMy;-W2b& zJMw`?{l&pIf%7;!Qa3Sxb6im*R}HPB)#A=_=A%tejl(o(Ss;{y+Hv)HOYw~+Eq%h> z!myq`i;%iOAetT4asw6Q^MW>TdBs3t&=SGCIj7^pdZZFi%?gO2PRs0Yzp|^{nw`J! zLNp?w-AQ$V^l9e1$kxw7e@q(sV|w+=MvrZHfL}Ba(fd8^zTP-fTsm3z^ndF#_b64mCL# z$ssQ_fncO@Av#jEQfj(|)G=;Tl~Fo#O%6jm*}ez|AYF{}O5twPnM0=-kO6(o3KMMPQ! zIUPA%ecgf#Qzz%q`t70AAj_>PEf;j6Hq&{4+D12DQ$_=;to^*xO#KypIILlJKWWsi zF6wA!**GFgv90UCo`5$_czh4IVNOAB0d{{BVUOUClKENn}c%VzmQ*DNtSvE`!; z)8$RY))gbR)fPd(f|JZ4i$He_M7c<0rPnecYR!oKjBe|=O~qKPK?rTG91L*}<|b`b z3hMz;y^nKuc#~oY576u?dk6Z}VI2+2g}yJ3-t@beMMj3{mA#YQjgD}+8uM9>ufug- z3E06~|DAp~NB$Y6)aJBHf<(dy6Bb3ccX(8K_j^%-DV|o@o)VQcE(E^I;|(wyPWDtG z&>Q*E<-4h~^YXkyr@tlV@_D8GR^YP}k6b|Q3c0UZEwk;otwNhakZ_GnTLz^KalKkz zdTN~R^|=~`Io=ts4O+s>dRvgOVx`>1vb5x8Rm$m2s!Ox&qOp%urTJ4(ck}wsQZ-WM z*Ikgt^BZUBgsiaZ6@JnsWVUO*!y*rt%_}v;PUuGU*XVWF$htEKmI`=@r^}1Gv;XrX z;^wp+_~9L$-n5tw@tv}Mm~OpkYo}z{G!nR{%0O2e09taCvN!ds zW-6=RI_1-ojty6y7^p7S%9jtjH0_t04OJR95$~PM1u^CQ0vTcx#dg-z+7mTYCxZ)4 z0eN4M-d)9Do{5kJY8jfb)a(lGjT!tf*CY2~f|lh=@2xCnat1m{bn5w?>=$F}{VsKa z`IakAiIw}#o10#MQywmJ=8b8?MeoGxnLd6-)?QtPX_ zTc>6@Y}hqq7AwBD80jzfA1{3cIiY$$UXT9Gqki~YxLpLr&u4+|+AXV=6{-8v)s^dK zOl?uyU+I=lm!B+QSY8>nFR7LUx1dkMym!-<-)=8xK9lc9)|rR*o2;#?eA`RUO8eq9 z9-D{P)z{5BKl%c7DM873FFFyHfF= z&Hn#T1z71h=>JQpVE!N2!OZ_RJDB*r`|W-|iT3qsOExNZD_h>yd~a*p z>KjQ>8=Sj!y!+$B`ThKKq2zN+mh*X#^m#FnaG$G0KQ zNBs$C=xQk^MQ(3he{wu(oARsPqowPO`7}`XwY5nqe`S$x@`{ARuv}I(YgDPrZ_McVV{C({4Y;-a=b=8;sd(*P&NVQa9 z`&nz_qh@As3h_v528m)HF@_V(v}@!|b-GPRV>TIH9mgvYxcTYGG^xn+gS zQ9Cab`g4naHa(e7UCF#%VGG*xf+wj)7_$<4S|7x#K{G_jygrEj`)v z^i!l7SxM7~7-8Am0O>6*`3B}CE7>rr^0qo@i4w{qKKY^cSgQWHd1%Ko3(W-tuW{i& zo>S4fs>6d^ftD_+?Zfh2F(TYw)5ZFvTg))v36u9fddrkD~%$HYJ*Vl8x^0gU_=Vk=>RL$p!%oD#RjRBSQ;bY7s%JoHD zZy&C|6L*(sBKJC8&qHXmuDLdcSnLaS+5Y?8gzMcYDQi{x<&b+iqd>GlcDg8b4*z8) zG&T9=NvnFxNL{rX6iw(ZQ-o{}A@ODegLOOBX|s&ixZPHog!5NX@CmDx@(0f_uhvd0SjA(Luv|1(Lfb!@_pEP-yd!`AltM+(=z~0<$sl=gJ=GF3j5H5PI`U ztiw9fZ}b>jX=<4V#^}|D?~_G(a7U3&lb20}bdO+h>d>lWJ^Cri+%6MQ(w4RzKDSwB z1C0XaF&q^7274`y1Z?0_Hv41sw~#a0n#^5{wpzamNs4llFPX2LwiVS7*8Ba?J~5tA zd|2MWcq6)Akjh3pYlOPO&|_e?2N^DzZH4RYX$OsmZ~w})b{}@87kEHNF!r1_q{vbs zyJ;}5)y|9kB7 z4tQIVW@lh-wJ*{xNyX-y`zjv*nxoA=EN}NK1NWWoZm!!VLhstCJ-1kHuE##?tZ~cC zuQxnyMkw7@ztMz7z&o%Vn$F{o26wf1f66yg+bA!s^}Pd@YqL|XUc{gR=hxsKcJ?OY zH4Hod870SEpq-nM^YzSQS(LRxY`>Z=yqcbl%(;QvsG!Xu!>8_Myht~At~!Df>icbO zT^Y{JTVS<=9_A{db@NIW$_Gx4&~vJDH=f*4{|VA^xnhTBsG>cHlPJey zGgEGbl^Q|+Iz5OaPS#lno%A9Lo32*ZMszy*V{p^e13odm3!aw1p@&c7qa1py+1(zC zlxdtt#UOCMRt;{zjfy^^E{mP&rS@Rc5tdUBRwN~L3JJXlX^$dA#-*Yj%tDmupO<#RPz}flh+;%7tVi>(@~zCAQw=8CKet26f-ajHLE(KMyhz+~3e zdusa>2HbKW7uzJ!gEvB^p)Aqhsl;%vb#G%eYn}ug2$_@6Imt@<5j?wt5oGKG=p7Lt zQcW?sXC~HGQlw1mCHx(@(1oqbpNcB)*qM{CWSMegUqxp@pUJ=qA<(OB78iG!xO-c&*f)-d@5 zo>TOh3@kk+XxN^)cwAVGL|hmXpxr>}sM*8c0S=(}gp--TYpGER2-y=9>i9hasS@Vs@6Oy99;vL>____!8jNp{+Z7In@Q$ zn9&(x*pZ@-F>BC!DgkciJDM@C;=Zz^7X+rA|V)3QIH`K*N;^?_PcqevDDchrZ_O|8wK+v zh}aR`e)^CSLrDtWvi7G)w(iZ}OYh%pwiSWZG{6?^q-m_%5$(EF-lk5r)uxH&SP zS~d$SO^3TVwyT=zR6jnprNlmh|}buc1phgNPA_Yj77-)9j`OcM0-dp>~b$ zhpvTampxVw%`gY9i&3KMPBx(DIcX3h6elS)+%8biuY*{&k%~~z!se5fNX?A5r0x-B z-j`hGK!TLVD5Uun3PO^3QG}aA2L_fO!%QIs>%m|}t%9InnNpo2!I+*L^(;|WE7%UI zd&?&`gKpAVm*5-5MN-=Eub1qARdr+|)yJ+1vVdoI?GxAXT8KS!zA~$OL(ckEt>_Qw z&a&IuO-rik>uK%iJe-((~Akc`P>LI5MCLPg_N^2@-8%zj}hLj^I?2M*;{Q0>1@8lks$>=B;8 z2TXXl_j%a7gR9rli2ydsvWkVyiVidlh|G9q9Y{V1qBFF%J4l9HyWm9^L}a7#Fh=7d zi1*nmO-;kh59xoC>8iaVQpy+_Z8JfB`_ohivacah9*Phc2ITxgANxk9;r3^ig&=Is zP}M|g-wMrMCK)ZC1j1#twJV`0%{}K!s@NwXWauvx7Eej7qlK8j5cDu3EQRN!J#>zV zX#zb&H(9TVa6Q3UvAx3Tw|FHXoVqHGj|uB)D9b)My;^hX5J$e}PDRjy9o>A1Ml?n{ zea92zTnE7-`0Wy! zmg-U-$n}&b1#I}LCgZ=5B*1#1{uwZGu0nXMP&0YEc+e6)%K9Rx$Wiw+2I7fWmHI^# z#qvtxx!E8>tSKP9%duFyp}>pgu_(KT8YT&%0K_U>JiCYL8JU0)f)DbpK)!w-ecJ?s z&-0?c*O#1j+@6Ws3xi1#vqZ%uyaSOC!+hjZ|4ED_ zt|*~Q-;=?r2TkTpv^-!Revb}iW6r|y5V7`c8Y5APP9k1zYhJMkT)R~_Te?9w z;j3yYP71t$PFiUoy$x*Iyc9QIBww230nZZkSC{3Xl-zU^xwS*-*kRMjHd#@vmwFF{ zrgFCP>WT8c7=KKtNv&Mmp?=1um}YQoQ-W;JssDQBS^k=)vfMxf3a;`Hzz@E$zsAWVZM2-dqXlWnvev6_v zi;h3R69dwIm16_P1Vp4hDBmrJd$%gDW28%{85CCFECkxjSGi{i&>&GFNpunTNxFif z+yKat0DrS@{M}!<7BsTW{l0Lyzb9U}NwbqFs%=ZRG9X^$bjd(LTVtz&dQ|u5TGz}9 zyn27HKHSEbh06s8b;7gSzx&Ur%Fyqc(}H;Xr^jVFy~ODVJ0-Weg|=+SUHg8$f@a=$ zqE~~3+NjqU5j#Z`Fd>xVgHXz!PQT*}b%!S44dZ5hSm6E;v%Ul@H}OI?LELj=kj|w5 zbV6BCM?k{O6AX8vd8%5 zRioj-J_*8TB&hyE8fhpy8G~c=WgzzuH(Liul~ceB7(I;(;Py~7h)tMe=%6K9;)SAd z1B=P?g>o;(tE*Z}d23M86+6_?94gC0BSi|tqJAZ_nND7H3{ro`p+X2XgE!>U8+bvP znH%ztueWSyAnZ?GN?eMM|0Pr;k5geg7&NesWFSH>-^6eg+z?=+z|rxMSpxtYz-1`LLD@bCajEF)Z~ zheFkADs&D;qRrEt!Igc3wJ5;`RiM1wf14oxDJ|QcmJ^7fm5(&jjoxl*hF!F|7HEd& z9`~L#kM&@y)?9 zF49~!!@)h&LWnnXkR|K_b*v>-(Rcmz&(|?$T8WYgUIY`LT4uI zMf^&uvfi11_PDe)@|mS6*&HiMsa>S*PgFE-V3F!!v^froN^B`pY-@TYs=d_d+*Y(e zNH^3X>gbdl*i>dzlt+msCI=B|pk1G?Gun2(B@k`VNg|#gVT8+h9)8hNfv1!Gkr1E( zU6e~12}f9#7_75c&Y##Lze%(gugXH>Y+N18De8ciSq6-q9ZF{D@ds%83)GAvF0;+{ zQmP%f6FonmWN90evLG*5jto@gp(&33#TsT$eI6#XX5^0)*U_~H13iUkwK7ih84=T= z7t_|1e#+LeTI9;NUz(}XCKhu%WI1C?A+Al~)ZKH0A0|G>dO6t6`5J5`hoK|9@@X}T zKy+2hvIW1Qk8oXfNB?wiH;u}`p5Hum?NJm&adw#-a*JWKF_(FyMdtMeoP}*-B}uj& z=Y>OqvfVv^OAMrHg^7Cen1U#AI*#X(HNJ5=xuvq_qGswzTeU`{%xbj+uX#{1WEs*S zqTEU-pid-nL)cRNUltXz?869)%jaUa8ihC{q8eiIh*q1RV%Q(=KMpiS1wE;dlAudN z#)di6DU)a8P>BtJ=EdsX7or`33ZgqT!bZb^>mPaDyNh21sAzC-Iu6RvfJ z>2KC^l?@c~ac0eqX9*8e5kOZO&{D5IB-u0qWqFeyM7@<7UJ7h>3~m%^RQx>~Tr65V za5nWPbXZhF=`PS3{C5OpG2qT)^BToN=V4)voa~HD$jU4S)emiERFJQhT7b|%i@oBb z{#Sc%9#7TR{tsu$7@3pl$Q0qshm$#ThRh+AdC2S>k|wi+%tT6tWR_?$mwAdJk|a?S zQ7NRsv-VM++jQTz@Avt=p68z*ul?HlTzd`ITGzGKdavQS_Gi}y{lu$}$%hm)wE7Gc z6Xdu=zkPV|{F5q%kT@T+|4Y<4O`2yeUwq5@3(c~)4;^QVu1Gx`Ux77fq5oDC)i3pS ze>8Wh^2xq5!@*;BsO@X_;CB+6dm^?SVV^E}{}O#9O}#iuazN$IVP15-&cnIMKBpd@ zAgthoX?e-%gvcvjA}gyUU0W&}>qI46)v80HT*i#$3kIF*qQ*rQZYt>2JWNezS*YDt z|3;9#;eE}1uV#v|FclMFOmLdo^wV43eGwx8S1Rj#S_yZ$ZEp8V4Rv19PzqP=Ou5@HlG^{%ae}V-+1O}sG4!peSAUs zU9QZ1>~^x)!Qsnn!!X7lpG&eA)eEv@eoWokACfzsJNC`8lrgjNN%&B8)unD?{&)X{ z39d7hy?J^L@%}O|KVSJYJX}4@d-urVObPGB`**?7TZn`g3Ux1)3!k0o(>*!=DrR=3 z`snQ58n(KZyu-tart-bYf_cI53Sn_rT#Scg9Taa5H?M zmcMb~(<3N+AFiS>4|*pjzigU|2HwAM94VI9tBx_S3M2zcFSi?Ni5@`Qw-mf>l!kQL{f3 zzASzIHCmcvbN&15b^m+IvU!WW6U)s79TY>Qa=(5Z&S?Jp7_AUfYfnMYDH7V|Z5CG=Fwh2Az^@O|{b??c!7i}t*4Qsz7z5&1@? zxt-tG+wJFH`-pH(cHxHUKh4{58e}CdQ}x+Tp`vSk@stMd^1SwTXs$aY$+AVR^rXiP z>7}ZA1=-pOsgp&kRY$I%w5p1VVq`|H5(Qn=UtK#Px5u?~{@K+9pC5_7OZ!c~ zr=%9{v#lfi635LdUOc<->q_bJT=U4V)iZV3%pZ({GrT&-2aU`PL<{SCO9 z_SX^BDjMlSiRf+O?{8Wb=WrywVll~4POn)l)G(~>6fRX%j+U_@gDA2ula1?p zQR{BWud$&{kG4Es}IcMI=gJ{>(lxJ49cEIjG+Q@M9B_%Lg- zlHxZ}7dg4Ucc{MH&xTi~Gy4-7^1P0nVCUCu54Wf+&E$BT`EE?5>%#p$iF5g-R;(5M zJz2{ZOb9#Iy*^PwJuQrHxQ3knTytZ-}H5g`*Xibz^iOz zs=!GXZrkuA0oichyY(kzrM~O*f1T^kKRd-1_LjrAL5A9stq*n2!Tqq_T=9EnZGLTy z=TYVIyNakK%wk82UX7jUA6WWHHJ=@FXrq2%|EiLl91Q*+#e$MqBNl8t-rWwlQ)TY_ z#mWG(XSr|X+!#b|&1NhaxKZ!8EzGX=rLe*6a@AQsix_M9@Uu$<=gPB+cX|tQ&&oe* zDY$2H8}+cP$aH9`?W5_>+w`vBtkCg8MQ6>~MEh@h>ghPPNcTQ_7n#%=c?v@q)QJo< zbdNlx|FtkV`J9CQK}W}{kutl6ym>4|9>1ZSserrP5_K%FniNynd3aK`LXac93#a7~ z^r2SbVA<=a543Ed-hNVZECqG;{I~U{dx;!hBY9dU_SrmwxV6*iOzv`=4*4 zI2V}7wXke{cl+RwXUJ6tW9115E<6+I!dwVqWa&mKCH%z^qJeSE+lUh0La7nh(WAFx-7?sTQ zY<|tPU~OU1VjssF8q#%{)Ib zb<+#=h@nbC#KEfMVyUWBo<8{pgD*}F*{@IJ2GyQzG)?`+!AYY=E+XN$?{@}8?-U0w z1IOi$(jDb;^K`vLiO$nurtc0K?1Qu8x4Npg z{$$G;JQAC*xq27*KMDzK_^#>9VvvlD2pY=M$IAGX$X#83UQ5r~cV^jxsYQ#f(Mh@L zbpy<*(ERC>oO+iQjkXg3M?VQBY&T_fx))-4-A61_#_4^L;7+$AeO3HlEA`&QX*b0e z$oDPfUU)mxvrqk=Gg-_v{9x6AE5RLDE~-=+u|wwJdQZO&+VSZ}3Z;0tbgRt$a(tTd zSaBDbl

_`a6XDx5}46uPGEZN|~-+iH2gf_7M}C=|It0eKDx=xpPh<7z7x3_J8%< zZu7+u&RYI#v0Y00b$*!=Dma&wocqzdI>2s{k#216pTFgO7QC&G~6!^3bt82l6r z?hiW(gBzdn1Zn=00uU+aEWHUtC>NlyaEP4)2R!^hT9QZv5(kq+W05c<4mfT^B5*QL z5>OCTdxEXEvnSER8-^kImjlTFvaU7J+Zl?BkU}7!_7DF5c>+;&tpDVM!eZ&*de&}$ zm;X?7BOe6o^k3#zYV5GH9nlHY3F!+dbf6se?sianBeCaNy~1Q;H-Qiv@S|G#if2iGE6yE@w{yF0qtL)qzC z`;qvCA<;DX_>I2dr+2$R8~VbY)h zNy`8R5a1cQL+^nbM}SCS(jY#RCSC>)?khCtPAUvqnhv@{OhAQ#E*ug~ii-sWUr7Um z1^JSm0q{df%aAUtG@f+FO9OrZ9fw4L0{oe1$P-xSU>BBH&^;*0bfqyg#1-wP@^4j}_%2zZ5bV3P|E@*wF2=!J2suD?3*_YQOc@Q0xz-J$1I z7fIGD@1ZdNT##NsQibmSOqoan!{0v74Mv)w0Oz{|P=lbC0Z&9A{OHvil0f+Xil`S%fX zu2yze!v!nGIBw^98tEA7<(*_WaYLF{c2c5}i#g_>lQ) z`A(PtoPy%{bD`OX>Ou;Qu`_!QpK1Sq>G&jTKHk)QaCE%p0$q;yBRXg5Zf{dG!!_8p!hE5bBKWiCZKiR8~N2VVPD zQ~P_Himvg4P3mmRm>jom?i%}$Sp{J7S<^D%fB+@=HaqXdx@8xo1WP+!tA%{oz*vKD zbc5rYw&30}jHd^ClnYI%;8z-5u)osyFwKvFp6sS|oUPP|NwUe!q>{AgYXdd5%Fmor zushsd1b!)wQGA4bmHlb=G~WU0vb{uidkgwhGdY)Z+0N|FiF0~GC*^k)=k^szdk+rC z@9*f-KW6bGx$;lfrHlf=lDp=m#1rZGzChRk4jFH|!nVJN0Bb zu`o*|g$qd?RID9j<()d60TL?OcF7TC0|HsNWjcw1U}4NutUhfuqsSk`$+BNM7WpI@Nx^jDpv>X~UY&9wh*&m0}rdFC^L zztg`ymC>(g)!}k_QC|C8=s|FbV4`T+(?XkX6KYJu{B75EF>J!rR^c)dj3TRB5;Rk5 zfH9~nq#w}Owj3~5(fdB=<@qBWsl;G5+YY$uVd8XBIB*abz2IbfC`8ioEpfM=5m!uP zmBZ2N9oDE`kLt7s^~Tn5&!)4Mc2#H26*+{LnxK&((y1)Ft;A1yGkyDZQ|9APe5~tX z>z=E-bIK8&aX;mE8WDO37vg>j9`|;!?n!;e$thXLRcx>GWZJsGRg&RDwDQUJZ+-qH za|q_yIf@Zw1-ng({1;CBw;2Ko^!@9K>`f`~r^x3=<*pv=%9{8+)H;*u8e35Rh1H9P z)p70uO%Bh`B5MbI*6Q$3m1kD6*Qe?omGoZkmLiIIX1@p_oVnU?g)Z%Wc#G>D&7!Ms zbp$>jM6_HdwOVnHoxI1=Ultg@(s8M2esjh9WL3M%i{wW&;q6N@W5)PGahEt8bE=vP z_d|8Q>08~|g-#vj;xDD6bdRzoHC$<$F&}Pwb8)uRa_pJJ!_I|qf9dy4;7n*3zRvm!Foe^leNh^D7cA6S-R~@I)+j15O%Q$jbc8OaD$e)r^r}{+*6d05&3Lioo z6a93uMlL#|r7G6qlW`9JeVp6aFSBwHx@2{U(7~2ke&KPy6F<4h5~ z^-pyBCy0fQ1Yq3s_=UBYvZ$(#G+ctyqcr^u8{)72yj4PF%9%+^u+J=RO7DHPc!&IUyFjTK_mIa`6g|qOM)`&_ zQApa0Qr6UNbwu*v`3E@@I2ftZLFBB_h7yhY|Bv8Jtw${bXLzQ|I;)cx2~&0 zV~i2{Jy>!UhcJ<=<7;SDO6^#@Q$9Io$V+b z(hz~cP~Fz)iq5n_L@SwV$13CXf8i~;ESj2T<7b< zO3_La4`DirqqrpaT1t&UFzO1WmRpoU(Lo&&%4Mu(nN1TpRM;nLk+{u zZ?0-8VuZM7AC5OXrguqp*t5WIF+k+sr0%y0sifDg zHKFff^norQjC!yboH61y#uOoq*4IRilhXy7J+MTS@gO=nSsGCoX%(CIXh2_Ilq(-G91mDW5}a6K1xGch--y5J+!CFjW0u|5?AS zf2LZr>3aD5@_=DG8;z3i-TT5ewu0nv74JR+hjCwA-b3dYLyU%ln7ZJ4rqve8zUFylb11w*k zic_{5-5q%!#Nt-CMEFre@Al&btDf)a4_a?oFH9sC)!UD;Cp4LDmp6EzjXWFs!8KDf zvwCkvu&cs}3#uu59bZR0e7LuVar(hW$2TSdPDh7ty4mKbA8hHZ+o7u)PxD=s*6}W8 zhU547ZZI48!K5c(%)Cj3Z54~HS0^0qFhU=Jp^Q^k-%gjSWO`A6Q?tIORaGE`UWmr# zZGbs|r&%)8B_iSbC_1-0hvre2!9GMwMrVpMOI&b;I`o^ZoTZyEv{j@876;d;6Rra2 zH$oaxCyWUKg#yf>41j*4Fc@ky;ek~U-YPkQEY_Mv=;3al*A|5O{jl5m#Vh@sR~C!o zCcJDFgrLCcz-nf&hw$+LwRM~dRX~{R8d9pedGjvr`Sz(b*fsIf8GalRA6s!pMC0YhVWWnI5p6dz65AEs+7s#aJ3OJ3V0rM`j#XEtqe{y# ziYpQIfiKs0&)Fim*6jV0cDj#?1XBll4-KU*@_61m{=!Z#sfEbbxtLz@I2g}fxiA)i zqt=anF*&`!>MRa7tm3t}dd`O>X?WMfE|wI>^IRi#%ipPghg!FPTQ1~3&Woy6ZB#g&%~&{Gej!!e9V``FFhvZJ@jS~r kKQ$L8`dtOW_Ph6giFnJ8ZbGp< zw$jF1Wu}a2ydE<5VJ_i)aQ`tekUy#4Q>S9;TT7VeS7Ko+5%h+wg(D_`-O9lJ{e*fQNyu2j-?+r6tfYy ze8@8cVZ;+HcJhmDOn_J735lCde#f*Q>o#yoo@AB0QJj*%<#B%|WkDm!EpCTewyH#PUEpV36EcKfLVht$fFS*g`&`ywmAQX>+u-u$i9JRJi-vhp zHV2Mg;O@?3{v@C2!eU-l^BFIZol2;s<`2D3iOwXmJ*$O!koPW0fK`vdhlkN3=h1x^ zn}#%q+0RQ(rYTmTPqe?8`5g~cxSXHrI}?Ave^gg?PbVK; z4oX&X-<{KqAKU|%6gvz*{c2lSXCFWQKNYmyMNa>F8b@ z5=j6cC3+|7jMW6=Ob8YI-BarPR7oPo*v+U9+P>6}QK}jBmTY@T#pEe^{zZ>*dUEec z=Qu4Bv6ne4r~1*Uej8+`gIuP+O^+$AS@^}ka+0q9+jfppBQhUJ-Lfov{b%HF)c3IMbXo7 zd2AUkK97}sRnHw{xA->mjz5M z4|~%IDNou-8aiM+vNRso^5DGgm?V~;Um1YPhM?HK6`XhE&AfGeM$!A zNaL#@qV7Qx0Sp;S7zdbxJ8UN{H`eAyJUAf5smajT zPFBtkP$8Tibipy;GR$pf6O2Q(EH#2ll{cL%t^=9}2oG_zZNkr1ktA{*Skk=&x;X&` zirMNt{7QRVHCs>LwfJcLW7&n*u;7{;>bciFt!Q!XXRo6C=u&b1US633>a#4zddl;b zwhImJ86qPOW|pJZ;FL{hyJuw7{Y7?8=*vT;VVI;=%wGA{?L;b3g>2@850|xhN@kCq zwCa3Zru@J_P5C$Vci)sLio#uR@=eOJRS>#vLtnlV&k}&3q3XG2^iwdTbG8j>{z+v`0Qz#_f1)hx1Lz`xSCfFqcJQg6$OIY}=PE zySwjC;!S0_so2!^UT!m)EF&+JHEK+Ci8wK3Yd?O!S9Uu%iE*?2J9Lmr9r2UM1k+^L1!PFU5WPIq!R-~dsTaI4g;KE z(6M)SBszg@TsrtaCl=H_yxsop@0%U6Ibm;0TqFK56b500z+p{V-=d^(z1(#;C!{Zsm02ILsbkar}Z)g7X>L4x*bqrxCIZ}=dOnJ zy=JiBD%POB7eNt|LE(3WhpA?ZDIINpzQ?&^S;i@S0!(wpoDvPsK4@}IB7Szl5%$p+ zv+_DH`X^>{UEjH%{nf{;aqrxj$KO>vza9TpXEThy5)s(e&P&tv!RY08oNQKQW!vwZ zmX}2X=k`sTSUa0*chKIuTIHZb`_c&iqEKFupKkyB#<~wpkYUeJ0)%-rc=Lv_Jp*S`*UJUM&C~R)@YX6z!M#fWNZ{6*1!s2T1 zgj>Q3J#?SXM!aKN7=D&qu7XK%!k?o@ix+V7_G;tOJjGcnufJ?SFYRz6QkaJGl^ucg zdg?YCy?P7SC${M+c;h^sJfW*6+!cbA3`+A6jb3Snmon>IJa2Tv z--;SN-=vDRid)w8i)#OD(^^rU6PZ^4F6Up>?bs>oeqVH0-jbI#Rm>gTptAiMgGAU- zufVU#2zpBm{YzJ;v#p=iexQv0mTNdS%anL+y68>V6dCz}-J6{E1^d%mlpcER+*4P- z%?(KJM-@0lP(R62#YY_}cl+0Qm3G?r6esOBnO_o*B)8iy2;x23D&MMv>m@mVaqsCW zE&H9#K<>M&Z@jZuxa?r3-k*?ynKp7)9czL!TmbSSUE zBMRjoGsf!OZ!Z1NE1M)l5m6aCci;xy6knfkR?NPk%Z69=B;W2z$(THS=F&F#rdQD~ zpR{yvMycPC%zJVoNrnl*YV;(@t1vDwk#)O@qsCzj{f*Xk{{z@Z(fG{Nng&lRijMM- zoEyc4)lBweljKKV>>tA%47#-K(a7GYZ%f+?ejXzog#NQJ{b%PLzf~B41e^P7wEhqt zETA(C{h~Vu3-B?!`zm42WbE(r#go^0DVeYPwcgIQrD8+|YPIl0q*U<##6&Ae1g8o5 zA80~Ic;d7I!<9|74l5i<*Aciwbxd=ypG}Ti*DmN<%LU&132l=UvxY~?d?v|0?lciP zTFziwR$S>RZ%v79@@Ied4PhG*uaRM*Jw-;vy7=__`5E_F-?L;^O$gEfg>}W-GAaQl z7FHJz8`H4^6i;O~Er_17r~9_tp^MkUiOVj+H>nsdBicjXP@^-_x)n;Ojf?T`x>%jn=W`?;c{O5HJc-S^!Q6Z#IsFW zi8a)|EeJ6Bg4q3fPc;s?Xi z?Q{usOA<%kDp_} z8q!^E6;L-| zomvE>lQ`KH216ezjD6IyYrSs6doXIA9A-SuI2asPeyuoH_6z=JV)xseZu8>)vTqR* zvC3q;v0icpfl~RJ1G7BoZP(+lh=fP{aX}doy1K4tvm1dLLE52@i{y~c%b#qcX7|E- z$>`I1U*8=(G=C|hCHLBSQ)1{xFTBES6U%H9S>FuxCW^F=jVF$K_zoK;&5WFqIpXkD z{!PuNuI>e7o@b#_wv_)=?MeP{mGi14_fOD&uK&p1-E}IIH8q-*_sQoa%8LiKvyX<4 zRpIFp!}33G_Y~t zGruow-bB1xMSJVC7rn9?ia}7vtA{Bi$3+}~)@QdhcD@aweYbjTHhABTZKD-CE^m_c zmJuIt4Yj)E=o(ZNgH4_(`A`lSu*Xw-O3Kf#$$lA^lTMkhs=}t#)?id=*KU3Gpt|NI zDJHkw+OCyy(g%#fF9zkiM0`jrOwH{ylF;p$du3koZrAJ6CenQ)UoRXZk244|u?}R6 zmA!AZIOrncYCyjS8K#d8aDGHbxX*&5(KJ&*$E*&$UOI6RVzepEWr9?&wE;nupw?i>JxjxsM*(r0!Nj zy#IvZz(J_hRfk5Aj)Gu}5Xd`V{ra9ULi)BbSi>f5iNxA5avHN=CX4R~ENoxdkr6t~ z_+*pZw+`CYcIj%dcowkWL`kR#64kT}S}5wc^KfZ7pSoWo>peM!r;>;wRnU(s<<3F5_z1;3%!dV`?ugkRN}mBFebtX+6|Ls6ryj@&{|X zt-?AN=mun3=62`=Nl$GoC^*@-#X*0)ZH%O$ws#YZVTeF?^g4QxdR*>3vCCS$ zsWV!AMZOJ-IC#b!b}zfX@m_SNQs`)DVP|N!=1}YY3mxDiXz`Mvr&T4!k&SYVL9>OQ z`S`vUb+(mLH^T={GVPo13$Yg%YvOug&E8_oK5ll)N1))epHWUjzR>fr$Yq5lf+VHn z8TFokmkB1k>eJQ5BBqQQ@72RJZCnnB4-PI zfPPFE-P>!bUcupu(>!76>T&6p*}{<-Zw>9PXSF?e@;<%cq$wbJXtX!IxaCNj7&P zUSX}y3F&UuJET{87(FF`XQ$1#u{iwDnJv|Zc8KM;k%3W~KiBUcUuHhbp8HKEK{!L$ zOfFl+iR%vdpwT!ZXp@qhB{w&0lk))*oq-a9^s&i2QY!Se2sazo94iN#?RMrcB&-tJ z6ug|qy2+P!kch2fLo_(OzPdevLDHQH43gbq_mysZI`nw1pdhjqtg5rtuC*} zPql0Ngokc4j341&5H36LDh4=YHEdeoC}-=IEY;{{z9&gXX}~IPmI`Oz)7SlVa(|xZ z!HmGeH22uJtAn++1)o@?=DUH0=}#y%SJ|KpDT0Ka6P&$hBD_T+&gWEL8xbwe$^0sB zp4u^zpnao-tfx@7Gf=A5@J`nL1l`;A>cYyqtmtvMpd57vYvgB{IQx zL%6e%ZU3zn@@j{)XC{+YkNCpHq7KuS=kd9IIl`Kh!&^MYHHdiCfiSYk9KA)=_s+&X zXy)x0w)D}3j|K@x8$4%{yH3(Par({8(f-<&Jw8C=W*N&4XPNp7_1BKcG##5`#WU7l zu)Ufl!C>noa?}4(M19Y-@*CF8EqoT==9rA%p9$YgF}930*G{oW<5@rhn+iDT#`})K zaI>VhjP$_NdbN<%z)28F$o?li>r#CS|AZIneJEl1W588+R$KW{?~aqScfS`fgxhiZc9PMJ zOSdAk5i#=>uIzlrvySZXiB}A66ol{E3)={4jGbmv*K(O*r9>D#?{5a z8sgo-d}itw-C0tJey5LmEOZTQnni2cr>0f?$s8g*l^<}earW|WurqXOle?22&)jl2axU4qKE^L3eP6$1iy4(6_pr>ziwl|HV;5euJ z`MO5*+4)_@X0Rt8d9*yEBJ|?|d;?!-GT={3_!{tkMejwjPQKt)d#M~K9Df<#R7w0g zve;90{rB@I>AL;m?~hoR+dfs`{+QS-fqL(6_LVr--x5rZna%n+@r;25V;>#gOkMl} zAC{GBVCr{IC1FPwvPEEy@md2H?ZG8Ewz?Q$R^G(c5yl;v=a2JcN2TLlk-y7QbYrJx zd{f?V>_H&=K~9(W1+sjd$-wu^rJwKA4uEgJe+<|JmI2e0Ee<@Wb-+y0K+Bs#nWn0H z-`5a_nI%*v_r z%v#WqQ85)IRY8!KhE1rOrC7(ho9;%lT*8EE3WOG1$$3nv%o0_i9*y&6`*8yvLku&C z&O=TUB;Ag8>&m$FOq&&b8BgRp>Ln%02`}RL`VB|HY2aM+MM<;%mpjup!tI0+KkbRf z9KB{MyTOGNunTl@}VIqMs!)g`Rjn!gQ zAsvc*#F-a@uAh*rE2wmutt(cc_6hts4)c_g>+uqjBHB$xUD|hrXRN*)X8Y!e%yQd( zg+`?EaF(Q5if_wcCkx>b3Q2xfy=_n~tDdRFl7_`Dg}=5Qw&!TfchfoZgs8I~?$m zmwB3)nb|fj5r=pB0++*hq->1{*U6OBnscpo7bu4BgXS7Zu`IKj@br&i_J2FZ2h3$w z^MuuXz#M>p<{BFHF`Cs(Ee0XKj!cJOlJzo}+o@f~$%00s;R1_UaITO$^i1MEG>Oku zcQ~>Ou{M-Sd@4w1cOwY14w~y^mn(OCE&k{c%vY&6e2Ir{GY+>3X^`s%cX+aRrLPkwo#!yJ=_Ip4PjPS#+sfA8@nvBH7N;8x29S# z-pF~%s}bjKBeTnruY&v1o3hCz=BjvyvpvlRDutZ_P8S(Dzs&VwZREvLeGvPQo?X53 zK}Npgb4>g&raYc-e@ETvZli(an}yXK->GU&O8wrfSX+fgC}3E!rsfUs(5}t&0fz&UC33&o34s@QtOe9xG5(4hut%euJ z*GD*92!7~%`94{i9GS|%lRN_zPQISL8%BF?y`)qC9#@!#ZSMr8+!dIJfZ6Qjl2Go- zS7YUH>lV$y)`6wYS1BKdTa9isC+`Z}PG%~@GcY;uDM|j2$P*$vs;>~+v5S^fZI9gd zOS#Wjrz|i}Q7nDU%ta?Cs%3v6^tNqd_39wE%Q%==KHlh2_O*Qb;icbX85+jP8!HHy za{X&r@n80n2XqY#*4R(3wwnYyAi%n1jol>OI=e}5${SAbw6?W}0fRHRr@c4HIuNW( z!o7Svi1q|vZ3!&-;GWjN($dx50a$F39=%ESgcuAAZtLOZW(^r1LXn+4>>y)JxWB!( z2Mq4v4q_5df+wPrw>@}v@bCd!2oBD^;F$o-CE)~nUwd~Le8oBuD?cA)o2G@guEq}N^Oa^dm2+Rq=Mgt6P0)v~vfH@A_#@pJ~#hwVU zNe5OF|NdU#6&zE6`?%ZLdlPIuyzOClkhnDr56Wo^gWCZX0ADb;Be2l|;hbUc6EL_7 z4DJeSO6lN$Lr?}!P$e)p;Gbk(3ipA*eODQo9;N#qT9|IW%d*zO6r2<$$?tz^VG1gW zWMR5NIack{{Cmq%ECl%0*hHRdCl&u2i&9egAfvJW zYf(zFNc_JRrT^8U6lmK2S&LF&Kl#76CaSzUrLM-^DBuF%wBI0&-xx#$N=8Z zk)Y1XgdD{30m1%ou?lt|5r4P<*a3K~ASDR0BF#EL3a7y19~MXu3JDCMp)dgN{@Epk znE0!n>cDdRPZsJZ7|FrL>Yxyle}gI`Nj@`FlmYE8Q1K&b7!j?B0QuNjgLO-g2V5ET zHyD6ZD?S?3HVcOS8w?=@P}ybyp%iio)#lr`3kwFL7cD5tA5Lu~tFuj1P9JwML)QZ$m zEAp5`^?Y5<_5={-<>M){ej>$-nYM0!#T-xdLNsqO*s)Dpd1(RrjM1 z;6M!6Zb70TuOs^qC{YALRE!R;0)+!!M)m^NBA%`uL|11Um@iriD}|JRIT4ATg#B>1 z+dr?QJiHx2B;YQ^&c_y<(^(zM)6M~A10iE~yFV$2t>Vtl+unf=I7&cb=zx2PKYyU_ z!h%9N!2Y2DhbW|XF!w(+EEWgpH}toPhJtE*9SsfD+BzC`lk~7)2C^X>)E}>j3w}Ty z>pB`5a(1?chQ^_w-e(OBfj~j+ZygN}^^R+4pcMkyuA!lUV=E;PcdrAeb8&ok?2kk^p4G?3l~c_5`x8}pDsKy7YqdNPm!_F5Vm zhuI(xqznRTjBDZoKQ~a9x{f9d4eV=ZAiWLp0CBKTob*&s`_G~~u+U0k5f z8|q3Lw?XgG(s*bTgZ}>2AE2=iFj_|g#Pu|kG?*8z3x~mN=p)descxtPJbpv}f&nVD zo@WdKv!R`XqbR8L`V6#cgDf#5hfr(z!ywTcc*Y<>gIiY)AhnI@fxdpdUSUuh+Ytr@ zlw*B*C}{{1uBlTD3J(E=wKTxq`u2+f+nO80VK?%EmVx#a)~1I+0zWwGY1j>VfWgQ> zcxY{0EOJBJ!T_~euNxSw^oBN#!OB1`T-K(CLqL=Gbu>_^8))bax{JXKTiK+-I%j4~xWa zjEmYRb1Z73j$=`njd@_DSC1(~Z);~)dvB75LM?X(4*-6ECPEWALk|xC?^m9Uoc-+~ cSOj4u0@2!=NJ2_jtc(njPFPs&kUHJ}15r=hE&u=k literal 0 HcmV?d00001 diff --git a/systemtests/save.py b/systemtests/save.py new file mode 100644 index 000000000..49d1f7c39 --- /dev/null +++ b/systemtests/save.py @@ -0,0 +1,57 @@ +# -*- coding: utf-8 -*- +""" +Tool for saving parameters from the crazyflie.yaml before every experiment. +""" +import os +import yaml + +# Dictionary to store extracted information +info = {} + +# Prompt the user for the experiment number +# experiment_number = int(input("Enter the experiment number: ")) + +# File paths +crazyflies_config_path = "../crazyflie/config/crazyflies.yaml" + +# Read information from crazyflies.yaml +try: + with open(crazyflies_config_path, "r") as config_file: + config_data = yaml.safe_load(config_file) + # extract the trajectory and timescale + obj = config_data["all"]["firmware_params"] + if "ctrlLeeInfo" in obj: + for key, value in obj["ctrlLeeInfo"].items(): + info[key] = value + # extract the ctrlLee parameters + if "ctrlLee" in obj: + for key, value in obj["ctrlLee"].items(): + info[key] = value +except FileNotFoundError: + print(f"File not found: {crazyflies_config_path}") + exit(1) + +experiment_number = int(info["experiment"]) +info_file_path = f"info/info{experiment_number}.yaml" + +# file guard +if os.path.exists(info_file_path): + print(f"File already exists: {info_file_path}") + ans = input("Overwrite? [y/n]: ") + if ans == "n": + print("Exiting...") + exit(1) + +print("========================================") + +try: + with open(info_file_path, "w") as info_file: + print(f"Writing experiment info to {info_file_path}") + for key in info: + print(f">>> {key}: {info[key]}") + yaml.dump({key: info[key]}, info_file, default_flow_style=False, sort_keys=False) + print(f"Experiment info written to {info_file_path}") +except Exception as e: + print(f"Error writing to {info_file_path}: {str(e)}") + +print("========================================") \ No newline at end of file diff --git a/systemtests/settings.yaml b/systemtests/settings.yaml new file mode 100644 index 000000000..99e19a593 --- /dev/null +++ b/systemtests/settings.yaml @@ -0,0 +1,447 @@ +--- +# general settings +data_dir: logs +data_file: cf231_ +# data_file: log129 +info_dir: info +info_file: info_cf231_.yaml +event_name: +- fixedFrequency +- estPosition +start_time: # s (w.r.t log start time) +end_time: # s (w.r.t log start time) +output_dir: reports +figures_max: +skip_data: +- timestamp + +# title settings +title_settings: +- data_dir +- data_file +- info_dir +- info_file +- event_name +- output_dir +- start_time +- end_time + +# figure settings for event fixedFrequency +figures_fixedFrequency: +- title: UAV Positions + type: 2d subplots + marker: line + marker_kwargs: + linewidth: 0.5 + structure: + - x_axis: [timestamp] + y_axis: [stateEstimate.x] + legend: [ekf] + x_label: "$t [s]$" + y_label: "$x [m]$" + - x_axis: [timestamp] + y_axis: [stateEstimate.y] + legend: [ekf] + x_label: "$t [s]$" + y_label: "$y [m]$" + - x_axis: [timestamp] + y_axis: [stateEstimate.z] + legend: [ekf] + x_label: "$t [s]$" + y_label: "$z [m]$" +- title: 3D Trajectory + type: 3d + marker: line + marker_kwargs: + linewidth: 0.5 + x_label: $x [m]$ + y_label: $y [m]$ + z_label: $z [m]$ + structure: + - - stateEstimate.x + - stateEstimate.y + - stateEstimate.z + - ekf +- title: 2D Trajectory + type: 2d subplots + marker: line + marker_kwargs: + linewidth: 0.5 + structure: + - x_axis: [stateEstimate.x] + y_axis: [stateEstimate.y] + legend: [ekf] + x_label: "$x [m]$" + y_label: "$y [m]$" + +# figure settings for event estPosition +figures_estPosition: +- title: UAV Positions + type: 2d subplots + marker: line + marker_kwargs: + linewidth: 0.5 + structure: + - x_axis: [timestamp] + y_axis: [locSrv.x] + legend: [mocap] + x_label: "$t [s]$" + y_label: "$x [m]$" + - x_axis: [timestamp] + y_axis: [locSrv.y] + legend: [mocap] + x_label: "$t [s]$" + y_label: "$y [m]$" + - x_axis: [timestamp] + y_axis: [locSrv.z] + legend: [mocap] + x_label: "$t [s]$" + y_label: "$z [m]$" +- title: 3D Trajectory + type: 3d + marker: line + marker_kwargs: + linewidth: 0.5 + x_label: $x [m]$ + y_label: $y [m]$ + z_label: $z [m]$ + structure: + - - locSrv.x + - locSrv.y + - locSrv.z + - mocap +- title: 2D Trajectory + type: 2d subplots + marker: line + marker_kwargs: + linewidth: 0.5 + structure: + - x_axis: [locSrv.x] + y_axis: [locSrv.y] + legend: [mocap] + x_label: "$x [m]$" + y_label: "$y [m]$" + + +# unit settings +convert_units: + timestamp: 0.001 + stateEstimate.x: 0.001 + stateEstimate.y: 0.001 + stateEstimate.z: 0.001 + # stateEstimateZ.x: 0.001 + # stateEstimateZ.y: 0.001 + # stateEstimateZ.z: 0.001 + # stateEstimateZ.vx: 0.001 + # stateEstimateZ.vy: 0.001 + # stateEstimateZ.vz: 0.001 + # ctrltargetZ.x: 0.001 + # ctrltargetZ.y: 0.001 + # ctrltargetZ.z: 0.001 + # ctrltargetZ.vx: 0.001 + # ctrltargetZ.vy: 0.001 + # ctrltargetZ.vz: 0.001 + # ctrlLee.rpyx: 57.2957795131 + # ctrlLee.rpydx: 57.2957795131 + # ctrlLee.rpyy: 57.2957795131 + # ctrlLee.rpydy: 57.2957795131 + # ctrlLee.rpyz: 57.2957795131 + # ctrlLee.rpydz: 57.2957795131 + # ctrlLee.omegax: 57.2957795131 + # ctrlLee.omegarx: 57.2957795131 + # ctrlLee.omegay: 57.2957795131 + # ctrlLee.omegary: 57.2957795131 + # ctrlLee.omegaz: 57.2957795131 + # ctrlLee.omegarz: 57.2957795131 + # acc.x: 1.0 + # acc.y: 1.0 + # acc.z: 1.0 + # stateEstimateZ.px: 0.001 + # stateEstimateZ.py: 0.001 + # stateEstimateZ.pz: 0.001 + # stateEstimateZ.pvx: 0.001 + # stateEstimateZ.pvy: 0.001 + # stateEstimateZ.pvz: 0.001 + locSrv.x: 1.0 + locSrv.y: 1.0 + locSrv.z: 1.0 + # locSrv.qx: 1.0 + # locSrv.qy: 1.0 + # locSrv.qz: 1.0 + # locSrv.qw: 1.0 + +# units for the report: +# timestamp: s +# stateEstimateZ.x: m +# stateEstimateZ.y: m +# stateEstimateZ.z: m +# stateEstimateZ.vx: m/s +# stateEstimateZ.vy: m/s +# stateEstimateZ.vz: m/s +# ctrltargetZ.x: m +# ctrltargetZ.y: m +# ctrltargetZ.z: m +# ctrltargetZ.vx: m/s +# ctrltargetZ.vy: m/s +# ctrltargetZ.vz: m/s +# ctrlLee.rpyx: ° +# ctrlLee.rpyy: ° +# ctrlLee.rpyz: ° +# ctrlLee.rpydx: ° +# ctrlLee.rpydy: ° +# ctrlLee.rpydz: ° +# ctrlLee.omegax: °/s +# ctrlLee.omegay: °/s +# ctrlLee.omegaz: °/s +# ctrlLee.omegarx: °/s +# ctrlLee.omegary: °/s +# ctrlLee.omegarz: °/s +# ctrlLee.thrustSI: N +# ctrlLee.torquex: Nm +# ctrlLee.torquey: Nm +# ctrlLee.torquez: Nm +# acc.x: m/s^2 +# acc.y: m/s^2 +# acc.z: m/s^2 +# stateEstimate.px: m +# stateEstimate.py: m +# stateEstimate.pz: m +# stateEstimate.pvx: m/s +# stateEstimate.pvy: m/s +# stateEstimate.pvz: m/s +# locSrv.x: m +# locSrv.y: m +# locSrv.z: m +# locSrv.qw: +# locSrv.qx: +# locSrv.qy: +# locSrv.qz: + +# info for adding additional data (fmi: data_helper.py) +# (1) type: linspace -> takes data and returns data with more points in between (needs step) +# (2) type: poly -> takes data and returns data of a fitted polynomial, or its derivative (needs derivative, degree) +# (3) type: cs -> takes data and returns data of a cubic spline, or its derivative (needs derivative) +# (4) type: bs -> takes data and returns data of a b-spline, or its derivative (needs derivative, smoothing) +# (5) type: custom -> processes data to compute and return new custom data vectors (based on target string list) +# additional_data: +# # ================================================== +# # fitting: new time vector +# # ================================================== +# - source: timestamp +# target: fitTimestamp +# type: linspace +# step: 0.0001 +# # ================================================== +# # fitting with new length +# # ================================================== +# - source: stateEstimateZ.px +# target: fitZ.px +# type: bs +# smoothing: 1 +# # degree: +# derivative: 0 +# - source: stateEstimateZ.py +# target: fitZ.py +# type: bs +# smoothing: 1 +# # degree: +# derivative: 0 +# - source: stateEstimateZ.pz +# target: fitZ.pz +# type: bs +# smoothing: 1 +# # degree: +# derivative: 0 +# - source: stateEstimateZ.px +# target: fitZ.pvx +# type: bs +# smoothing: 1 +# # degree: +# derivative: 1 +# - source: stateEstimateZ.py +# target: fitZ.pvy +# type: bs +# smoothing: 1 +# # degree: +# derivative: 1 +# - source: stateEstimateZ.pz +# target: fitZ.pvz +# type: bs +# smoothing: 1 +# # degree: +# derivative: 1 +# - source: stateEstimateZ.px +# target: fitZ.pax +# type: bs +# smoothing: 1 +# # degree: +# derivative: 2 +# - source: stateEstimateZ.py +# target: fitZ.pay +# type: bs +# smoothing: 1 +# # degree: +# derivative: 2 +# - source: stateEstimateZ.pz +# target: fitZ.paz +# type: bs +# smoothing: 1 +# # degree: +# derivative: 2 +# # ================================================== +# # fitting with original length +# # ================================================== +# - source: ctrlLee.rpyx +# target: fitZOriginalLength.rpyx +# type: bs +# smoothing: 10 +# # degree: +# derivative: 0 +# original_length: True +# - source: ctrlLee.rpyy +# target: fitZOriginalLength.rpyy +# type: bs +# smoothing: 10 +# # degree: +# derivative: 0 +# original_length: True +# - source: ctrlLee.rpyz +# target: fitZOriginalLength.rpyz +# type: bs +# smoothing: 1 +# # degree: +# derivative: 0 +# original_length: True +# - source: ctrlLee.rpyx +# target: fitZOriginalLength.omegax +# type: bs +# smoothing: 10 +# # degree: +# derivative: 1 +# original_length: True +# - source: ctrlLee.rpyy +# target: fitZOriginalLength.omegay +# type: bs +# smoothing: 10 +# # degree: +# derivative: 1 +# original_length: True +# - source: ctrlLee.rpyz +# target: fitZOriginalLength.omegaz +# type: bs +# smoothing: 1 +# # degree: +# derivative: 1 +# original_length: True +# - source: ctrlLee.rpyx +# target: fitZOriginalLength.alphax +# type: bs +# smoothing: 10 +# # degree: +# derivative: 2 +# original_length: True +# - source: ctrlLee.rpyy +# target: fitZOriginalLength.alphay +# type: bs +# smoothing: 10 +# # degree: +# derivative: 2 +# original_length: True +# - source: ctrlLee.rpyz +# target: fitZOriginalLength.alphaz +# type: bs +# smoothing: 1 +# # degree: +# derivative: 2 +# original_length: True +# - source: stateEstimateZ.px +# target: fitZOriginalLength.px +# type: bs +# smoothing: 1 +# # degree: +# derivative: 0 +# original_length: True +# - source: stateEstimateZ.py +# target: fitZOriginalLength.py +# type: bs +# smoothing: 1 +# # degree: +# derivative: 0 +# original_length: True +# - source: stateEstimateZ.pz +# target: fitZOriginalLength.pz +# type: bs +# smoothing: 1 +# # degree: +# derivative: 0 +# original_length: True +# - source: stateEstimateZ.px +# target: fitZOriginalLength.pvx +# type: bs +# smoothing: 1 +# # degree: +# derivative: 1 +# original_length: True +# - source: stateEstimateZ.py +# target: fitZOriginalLength.pvy +# type: bs +# smoothing: 1 +# # degree: +# derivative: 1 +# original_length: True +# - source: stateEstimateZ.pz +# target: fitZOriginalLength.pvz +# type: bs +# smoothing: 1 +# # degree: +# derivative: 1 +# original_length: True +# - source: stateEstimateZ.px +# target: fitZOriginalLength.pax +# type: bs +# smoothing: 1 +# # degree: +# derivative: 2 +# original_length: True +# - source: stateEstimateZ.py +# target: fitZOriginalLength.pay +# type: bs +# smoothing: 1 +# # degree: +# derivative: 2 +# original_length: True +# - source: stateEstimateZ.pz +# target: fitZOriginalLength.paz +# type: bs +# smoothing: 1 +# # degree: +# derivative: 2 +# original_length: True +# # ================================================== +# # custom data with original length respectively +# # ================================================== +# - type: custom +# target: +# - error.px +# - error.py +# - error.pz +# - error.pvx +# - error.pvy +# - error.pvz +# - error.cpx +# - error.cpy +# - error.cpz +# - error.pwx +# - error.pwy +# - error.pwz +# - error.rpyx +# - error.rpyy +# - error.rpyz +# - error.wx +# - error.wy +# - error.wz +# - residual.f +# - residual.tx +# - residual.ty +# - residual.tz +# # ================================================== \ No newline at end of file From 63836f03e9428d2e8d1bfbbae3ed3ca4ad501c90 Mon Sep 17 00:00:00 2001 From: JulienThevenozIMRC Date: Wed, 27 Mar 2024 12:24:49 +0100 Subject: [PATCH 108/162] also the config file --- crazyflie/config/crazyflies.yaml | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/crazyflie/config/crazyflies.yaml b/crazyflie/config/crazyflies.yaml index 1c13f9ebd..0372349b6 100644 --- a/crazyflie/config/crazyflies.yaml +++ b/crazyflie/config/crazyflies.yaml @@ -8,8 +8,8 @@ robots: # firmware_params: # kalman: # pNAcc_xy: 1.0 # default 0.5 - # firmware_logging: - # enabled: true + firmware_logging: + enabled: true # custom_topics: # topic_name3: # frequency: 1 @@ -94,6 +94,13 @@ all: stabilizer: estimator: 2 # 1: complementary, 2: kalman controller: 2 # 1: PID, 2: mellinger + ctrlLeeInfo: + experiment: cf231_ + trajectory: figure8.csv #translation_y.csv # yaw0.csv # # # + timescale: 3.0 # 0.75 # #0.34 + motors: standard motors (CF) + propellers: standard propellers (CF) + # ring: # effect: 16 # 6: double spinner, 7: solid color, 16: packetRate # solidBlue: 255 # if set to solid color From 425e75762ed03805a3684da87a85b619597fca6d Mon Sep 17 00:00:00 2001 From: JulienThevenozIMRC Date: Wed, 27 Mar 2024 13:46:43 +0100 Subject: [PATCH 109/162] changed cf231_ name to figure8 --- crazyflie/config/crazyflies.yaml | 2 +- systemtests/{ => SDplotting}/cfusdlog.py | 0 systemtests/{ => SDplotting}/data_helper.py | 0 systemtests/SDplotting/info/infofigure8.yaml | 5 +++++ .../info/old}/info_cf231_.yaml | 0 systemtests/{ => SDplotting}/logs/cf231_ | Bin systemtests/SDplotting/logs/figure8 | Bin 0 -> 85439 bytes systemtests/{ => SDplotting}/plot.py | 0 systemtests/{ => SDplotting}/reports/cf231_.pdf | Bin systemtests/SDplotting/reports/figure8.pdf | Bin 0 -> 58225 bytes systemtests/{ => SDplotting}/save.py | 4 ++-- systemtests/{ => SDplotting}/settings.yaml | 4 ++-- 12 files changed, 10 insertions(+), 5 deletions(-) rename systemtests/{ => SDplotting}/cfusdlog.py (100%) rename systemtests/{ => SDplotting}/data_helper.py (100%) create mode 100644 systemtests/SDplotting/info/infofigure8.yaml rename systemtests/{info => SDplotting/info/old}/info_cf231_.yaml (100%) rename systemtests/{ => SDplotting}/logs/cf231_ (100%) create mode 100644 systemtests/SDplotting/logs/figure8 rename systemtests/{ => SDplotting}/plot.py (100%) rename systemtests/{ => SDplotting}/reports/cf231_.pdf (100%) create mode 100644 systemtests/SDplotting/reports/figure8.pdf rename systemtests/{ => SDplotting}/save.py (94%) rename systemtests/{ => SDplotting}/settings.yaml (99%) diff --git a/crazyflie/config/crazyflies.yaml b/crazyflie/config/crazyflies.yaml index 0372349b6..6966f2819 100644 --- a/crazyflie/config/crazyflies.yaml +++ b/crazyflie/config/crazyflies.yaml @@ -95,7 +95,7 @@ all: estimator: 2 # 1: complementary, 2: kalman controller: 2 # 1: PID, 2: mellinger ctrlLeeInfo: - experiment: cf231_ + experiment: figure8 trajectory: figure8.csv #translation_y.csv # yaw0.csv # # # timescale: 3.0 # 0.75 # #0.34 motors: standard motors (CF) diff --git a/systemtests/cfusdlog.py b/systemtests/SDplotting/cfusdlog.py similarity index 100% rename from systemtests/cfusdlog.py rename to systemtests/SDplotting/cfusdlog.py diff --git a/systemtests/data_helper.py b/systemtests/SDplotting/data_helper.py similarity index 100% rename from systemtests/data_helper.py rename to systemtests/SDplotting/data_helper.py diff --git a/systemtests/SDplotting/info/infofigure8.yaml b/systemtests/SDplotting/info/infofigure8.yaml new file mode 100644 index 000000000..faac515d4 --- /dev/null +++ b/systemtests/SDplotting/info/infofigure8.yaml @@ -0,0 +1,5 @@ +experiment: figure8 +trajectory: figure8.csv +timescale: 3.0 +motors: standard motors (CF) +propellers: standard propellers (CF) diff --git a/systemtests/info/info_cf231_.yaml b/systemtests/SDplotting/info/old/info_cf231_.yaml similarity index 100% rename from systemtests/info/info_cf231_.yaml rename to systemtests/SDplotting/info/old/info_cf231_.yaml diff --git a/systemtests/logs/cf231_ b/systemtests/SDplotting/logs/cf231_ similarity index 100% rename from systemtests/logs/cf231_ rename to systemtests/SDplotting/logs/cf231_ diff --git a/systemtests/SDplotting/logs/figure8 b/systemtests/SDplotting/logs/figure8 new file mode 100644 index 0000000000000000000000000000000000000000..51a797a46198f9e4cc135dae03fcc0a4f06fca54 GIT binary patch literal 85439 zcmZtP30O_v{`m3Al*~uS5J?oGLWcI*=g62@#!yl;D20T|6hc(yM1xYHLZ*;T9YbWE zJE)LUWS(UR|Ib>V{rl>k|GLlfeeQkU&+D%5+UxAS&p!LqE?Y-SN9*rj_t^n%vxfM& z&0px|J2OzLhSmaq7k{_G3;bvMz<+lSFmvy$kpln!6hxD*mfHgVv2z#9_Mbi1SF5Jh zg1HO*X1bXT=&Uto?#%Iii*PLIf3rcP|1JH$dw9>RtwsOy<##^Odypiwwr~>v{wVH*+$`uo)zzAOm^(zk4a^Tus7dj)DB))}ifi8I;-+6P zXNRbX>(^-ERCkKkS8?&aRshHJbxqRawj#3yc;L1W*aynii35va(8m_-@mm_U{3F* zCaa1Qge*43vKw3+Q-nEau$pXej2B9}((SJGg^PRYxUog*XRjuPk-LTBE))xtNPw)#Ux{I3b(ijm2Di<|XEKZfa6HFHRWAmQJkg&fEDX zHOBlA@TZ(O;S0m%=3M-?H|7rRYLW-|IXfoO#&hv{C(KW!X*^;tw_y+$w+X=<4!G~F zI3b1Yj8_x5_;?!TK)?ofV4c}+zWNdukGO+*)GRd_cPUONVtC>^E`DB#xi75q=2LOP zJ%+#Nd+?Snur20!Gt{JcYMgL};jsc2HyMoC5?=23_&DJs!`7}`oZ^kyV7i(djgAur zTGIXbaVQrL+=|%)4o#EDIN?0Q!wz%tgG|gj0e9XIC)BW_BiFpo#lFRu`@l3vP@M3R zjhs=%#kFgDvPEhE8(7;XPUy%+Zqfm(#xc0Z9P?AaJKbUDXSi?}7xx;Ec?hg?xm%oY zj7=kC9v5E^#B2k25sVzp*4ZwKi)SWaz5~+;ag7rMw%2K?xcE;V=52uQPLC6E*v>zs zjElFv#rzePZktn_kjW0KI`wArcBIbwn4iOoA^`ShSf>XUpS8if2=Jq6aN1^gw*wbX zbHUsbreW$3Cp2L=e>oSwUx&FpEZxjWal+Nkbl=#qmy6e?WA=n2WijAiW)ye3&c%jm z%#LsjZk-q>3}YkfeCFcQzc3$$qx;8rcm)}DYw5*Xx{=11^WcmWFfLA*$Z*I0TwH30 zIlu$nCPu{xRt)F6bMcb7m~{c)9uOx?W_U{k7dPL5ITq%8qhFj5!>}TQi&L{PC&6lb zvyKyT8BQ(aV%t*8p@84_i4$%!JV)D`w;B)YV(tsrP>d6Pxwy_`%vS-M$m4_u3|lSa;@!(I)3=G=HgQ5J!}nvjxOXz<8?eqRdc+B_3&?a6 z*pxOnO@ z%*L>Ri>hLUy=>0Q?r`ykhnVX>QWLL>k-}g$a!^3ABHy+bFuyl%%=daF^&_Cu(POG+n2W*2OD56 zhB-n191Z z0hvjhu$+w?lfcDwQ!q~i9MB<7_{^~XB`!|BiFr2Qet^$2Z2gXl`+mhd8qOO*MsdPl zHs>Asb9qa5t2O2saHI@q5hnyPEEl-gV*uvq@S+&hjT0OgZs5wr+Osj&nxiH)e#Z*N z42Oks@%Bxam8EL(?r5aYlpQI(4|B2kNz7@!YI5gWtdPKt!7pkqzVHb1vAJrptTI+; z&hXJHE_SXlk1djHo|=?=j}@ZXJM33utQr?opF3lYfRS~7#tN4iJ~fPsH;lzx5AYC} zvp$=~&UsvHv>3C&3)sNjkwQyjdUOwo;^OQ$%r9Z&gXOV;2b;$394;Pn0rQHN@Sd_h zQgAk+BfFJx@rzfOFTiTtuZR`Sno?{~Z$58FTG0ga55T?N#tKIm4z%LpR(&xW%~zAJ zZ(@a2Y|c|0xcJa?%)u~n)azKmfbB@yE4X;@8qCvS-w1mdD=cG2io;$meslnH4cJ9H zzKRvB*%_(jbuM0f7qf@Anv8}ydoz6T6BpO}f!Pp7?gp#Tnc>iue!QhiY=_w!aOd~2 z!hJU98vVJr-w@1g0eAlzD?~AT(w&R*=U{e%Ie&s(bSA?~Be>Xe8|F`NbO-&46&|s5 z9-YC(e@|l$fm5yp99H!h4k_f~sHd23!711JL#*(c?fe6@7w}f2M;*+?fDK`<3t=Oh znsM>PZkQhcjxLQA+}Q?tjpkyf37FMzu6t4f@7?T0*|?C4zXW0ShBJSi$Fag=_EGwM z3>RCFZP0V>N?r<6NbU2w8-j5ZUvX4u;FS%Ix4)bTgH}YeJW(+@U z5#0tCFG*4;fgu`4xEuDL<&0@-n*KM zTdc?I4XbhRVys|?p9j;pIQ=l@3K+R`WTem)SK|&BkGPMy80I|wLaeZq;dPZ<{J0A9 zDY&jXW)~?OW4K4#g}kL(*a34N*!fFyV+Aj^fmMUJxWRDD_a3Xs@F9`H2DXb%_vYfX zd6?J2F_?NjR!C*LsLoa{7NanG0#3?{71pqkb2GVEor8HjTrtXS#0odqVYR=Qi@nM) zpN0dr**$n`V|Z-sMZDFhRS)w4I8uB8pJ4d3IT!D=!dw$xl+^37LMg*OI^R$6ObtA%h+1Gkcr3k-){SdolljX*7j>V?D!TE^+ajTGLo*H!C0cZk6im}?wRlj-la3*Xu6x=X76 zGmXE0A2keQOXmvzzT%SYLIu0pvuuP_1N&KHj)D!0E8Z^jXZVs-HL#u|;&rfen_q4h zQrT)um#PNdy$bP;!)jvwce~)taHUi=aKBW<`{1Q2Hi#6G*)+CFRRiC+g*fM^n)K)u zDGcjKUqQ3mST*phZN#>i(kBOZHNP0j^H3Yl!_oVRdC zb~uH(IUGMG%OZtq>=IljlZ(GT#vBRL=ocI*>|=P`6E0p?a|v6Gx3C(&Rz(U93|rK~ zsxfE7u9%m?D_98An9`2ED7U4mfsffEc7pvm%@5xG*)h0k9Czf=0hs6RQxmmEq;Qwv zHi2CHbT{VuNovx<6?P6U12*m(~epYoyiM;&HVfr#NncId0!WqW-o|IN(I_$?h6BeW(ju z$&49+SwEwYB(B;oCZAxZVKV?%E#cyzotPV%KO#nJQiStu zTmZWya&eP0m}@ydA~ma01iv7PYhK~v1Lc@Q=RP9tb5aGf^AxAOuZHK!Rtva+iuxWy%mO@c0~g2c!+i5ZKJhmU6DBlv2VCo@ z237~mhLL;Sz}!g}ex_z{n4s)58}Nw-Tzu^_=Akk7NciC}p{&#kaL6AC(;bO!pyw7J z7}>qmDz5;AJB;@TT(% z0dMiZ>@v2Hc(jZVhV@wlxQm|#?obp6xbsHLZpuRP$UZ_SI35J}#!d}<^7Aslxfz%T zeJCU^0B@PN0(-!_u8x3Y8Z4cB7ZN1 z3tHdT08Xrr^}l0qWS{kb*P3A-HKK@g>=`GFJG36KT~7^MJSGBg`!Sf+o<+o2*elpv zjR0JGss_&X-v;=^Ld-SR6p`XasluV|+W;R3*1%&Uq5zMK#T>A^h{Rn_6V_Pl1UzPc zHM}q8g3#?)9N@C^nCBfYB8q9*!kAjS0e`xof#K)2055-u`Q7;?qR9WK? zwnnce6%zdcHwDN32Ve-f30AEEGs+44BP0$!2{^4cW|v*XY)Y?xUBcvY)4Y>n7zP#iYr1>k;dF+0C4CHH4EB|EKN0oJvxhV>qFAXTX! z0pA#eIjnsdIdRs2xDi~`{s)qN)3?f;> z>I3dtjJb1M85yjyA^IQc1Gdvy`)@VA{GLEYyEX=Vz82i#3Qw_sOn3V2q4fxAA%t2SnNaMxRNZFUxfZHz8z_AyM z0Iv_ke7|)$@tNgLHdwU>d@Z&bh7%f@P}&i&Q3B@7hh=0#KOgem*c5P&+-ew3JEXo& zSHLIpFsBrikxm-}$insJfNQTpDK}2gW!0yAaGQ7eoo4~s<;68IPH?}Jxg?8Cw`||mKyUeSG;fzZjB+UbSD-v^9 zyCRY?+&l%i*)hyDx@D7A_VvWYZaIKkW>mwS9UF;T-evo%z8^RNik_EKAdm^ z@CH)})8lV!L<_Na%niT`Mq>W+`#8Cm-dsHK_%7hU(HeNC?_I!p3oy@mc$91v4aCX9 zL%?kpR>SaKAdZcA061|MW~0(0WPH8WqUo~7fOp17n4U=}h64bwcoy@>P6x>)yEdZy z>odUQd^NmS)lR%O>KWkM&oP%hPbFR7wH5o>Rseopp@Db5e*xIDK{#8a*Dq5@PXi;d zcGg?K9~xoRqNhrD`-gqwEnux)m~UDplYJ+QMb+TXfE{~l;Pyv80gj%Ex#f>NWc%X| z;+SpU0c$%|!@J*`!oE=nxcf@XdbReD8B02e`_B9Z9JpEoC(rv0_~L%d{f;FNlVnqI z>}G8RtaDm5Y^7^1rVrIt{Qc{A6SEiK65B4~m##Gd=iHVsedC~bn?X&$m0vLLToOw{ zy}F7zCA9%xtJJ_B_SXg+);fYM-H(uH^8Glrfg}A&!6Toe@YTy~=jR9Aj!0c7Nh13nO5C^6;1$;8I8is2!5sntX!H+Oc*tCVH z*IS8(mdyb-EY`p+Yc>bmqQ*wH8e>DZkShy%h?`Cr0KQWTs}|irI`YD827r%s#$35? z3-Ps$}9ynzwm7lGCA8~eVZmX;A<|2WJiQ#O!#S9^&qHy8uwghY&s)0wlS^|zbfVqLoYI5Y9wRrbI z55O^pHSkW~9)KZ4eXWO3-Fcim}i%)B7PgJMMbMVfUi_( zU{S9RV5fGQ+0u=AzKSfJYc1}u?+5t0F;=brTa9(i`vLws81tiFtH|a_)}o!a0JvzF z2A(=g031FCb79NX#7AK*n(Pt*&zmPi`bE=I@cm8u%Z2{Xq#cWc4De3gEhgkV;AmH(38d&ea zK)@BXx3JZ4{~JJ@j#!EPD+dEE(8H=l=S)Ywwr4Ql)!i@`ZCp$qwy+ZKs)qvhx6;7+ z=|cgxn1Ffxn?R~;^y&n__Z1r0D|-T9xvP{%FD4#?&BfgzlK?++uZHOxP~zZ8fbWK4e!6He z+0n3z_`<*eux*3}c5Uncc=ln;Q+F>WMU`ga=bR~k%a3c|=v`9)Yu(3Od44gmSzspK z89EK{v_cIGpI!jRRAGKlwwMTg&BPBE907mU+Q!xh?jX1k`rfU3&=Igj2h7*)=928s z9mQZW9q=|&4Xm)94mfWZ=B9tW$hZe4;?`r%fOn17z>8JRfSu-Hb}#WH6UUl}+ss@5 z>n+s49c#M){=NgVU4aMb*~~<|7~~2#Bc>XrS2B*9TmgsYVD@+PAdBy|7r#873E1kq z2G)Bp6L5zz%=b+^NL;3o_|w!4@VyERoY~e5uu^Y3Tcq8MJ;;q-MxwjBJ7AwiSlQCi zOSQ))?tmv+VP4$OgM7VZDC!1z01oV}fy3r_0Dd_ca}xs(vSMEw@olsx-~vYte8kTa z@XFGmM$yI zgUFH$M7x1LfPWfdWlKj#p489>@InRVw#gnur>lWD@F&H42Wj9X`o4f0yJH@i?LkKW zY9ZR*^aX6~T@BM~{uTukCx>Icl^K*&a2#{O8xOMgh`xBq zY#!jrnHu<_(LBKS3NVN1coOZN`l9CzivK*RhUw=N_>d0RS8E4b4c}&-Cs}LOSlrs*4{+r; z4cxGsA7D#=%#TD*()v>)G4D9V;ei^s{Sk_x=rG`~i>G$I6zDPQ#&}KVUO!%w}Gmq*>$o;_P6G>k8E{{R~?YL~-^s%&&Ys z$%BHr;<`MF=euZNuWX9PufjZVz9%_+Rag93b0Odsp&IzhZ;D^1V0M}3Nv4g}70>mj z_*Oa>uepV}*xQplHPRJ}Cs7=%u7>F+`ellRFmlUpm=Cyll9-pZ#7oO5?pvjSYp0F&Xi9tb4@%s^q&l+Q8OGigWY&Q_|TnA5L>QqyV$fbDTFbxdX9WZj~Y|Mk; z<^J3i@Jos-=5q1k&6pbw_ax(tYKjHlC|8*jPhvZPV$;1`Y;_THV1);HZTo|Co=Wk(Yg~NgHRdpQhm}44P8K*) zyzvtk&yYp4rR#dlgY?M#PG&k${Mi62Te^Q6_^U7Gi7F3r_~v&~V>-n<6kNQ?8T0nz z9>f!Fl$~REjC(aqZ^7Zxby|zL=>ZRN;N%yQ>lSq)}8xE9&D$0Tp<^~`GNUHqzB2K@sZ^1rue>A3|k|%8g$M$jnzh& z?IS$Mslgvf$X<$9nsRZgp_n5>JV?aIk7Rrr#YUsKIKv0C+fonGeC9{8=@7*o7FNUb zR%ga#x*B%dF<1F}kUkyW5|evu8Zlh_I16)-uLt?l_%*rxoZ^n>x!Au1^UB#CMe#jCw0d>e5MB(u- zOX4@3;_Io^FunhbSnCSr5-$(Z*1eoe@T1t^4i`tg$E=v^LH3U@Pq%^67 zoXVkixVHu_xJjq+bv@>p0UpG1M+s?KPO;urE)G9}c}1WH3EfpfW>iwVJ5vL@HV%N1 zO&?(Xy~KkYOfDho+Xn#dP+SeuZx9eGe`8Kr;X!Iod`wpNqPU>e?tjPNKRnI^b1WQI zzpaW$tU&P`b1r^49P@U#a1AysB!39S&&O%tH}-VSA@ea;ZilmIS^??eOmSEs7aQ!v z{AD-nb^ZmUy)VT}6S(-W3Ufe;2k~_+ASnwd*1E*SL(4HQIs$W^SwLznq&V@d241+0 z&bg#sJX<8iNe}YFr+{pXqWDi!tZYZ3U+W-V*aP#s(;h@0e)P*>KgFpwT-;y^=4hn{ z@%nw23_C>eSQjo%UV*s{VD~R~NV9Z`XN7XHVjt#En1(Fi4q1DU;x*}9eD6Bu!I^MI zvb{rwq){B8=3=kUm@Q9vkT>1#kdzdPZ~xN3@bwuiop!4PwsaP-bgjDHA&;(7>~D;f zEgk(j3UO?I%v(-)kSq7DlRiZhPaVd^mL8bDXLyh;hpv*j&nUh>my0h&VBQ07nt@4I z$kK9(m+jzU=M2nF$2`c|&R2+%VWXUCn0~{AbN*3?`8447(HF??GCFeCGA@qL-osYo z1kAa>@jSW0@J>CfY&HIk+|dm4I9O-f;pd1J!vn3jID0haa(KDRZ=NMh*=poW=Hkf< zF+0JIv@8BB$u6dI9==?{^hVjgX}pe+MqW6NEZK3EjC?}zr(`Z(bsqDX`~GBX!dWt$ z;pW#ROz)h~ucL73TE4^_W#>yaPRu4V*fiWeRU7#q&S;d#md@+&0&>+Ri*$QRr%|^h zR(6N#AGYg_dD)CbB-7?Jabq|{!NtXnm~}E1llfON$s2}E-K$~xtr*UE@oLOJCkK%C z12V`YhVO=Rag#L6Uy}n!^9ILA9kzkx$2IV}=7Dge?7fZI@lpW!pmUTo)(M0S99PK2 z{VOqd$`2r|HXk8R^(n5Uoy68iy49IMaO4Mun4Dh(i!~R?xw*_JZqu4Hni+g2a zp13oB1l39w>wbMe-3n4h0pO_JejKeZdhN=Gg> z55#r#i_gYmc3mDq25e3s?(-?Wkjljld6?s(LdYDS1hUzWV)xtC zF#U2adKcZm_ir$p$A=K@Cb6Vj6vc}xxp+g`v#)Xh|A9oS&REl-mVr5JBZ{)T% zn2RDqNaUxTWcpExlLm3|i5Zv;!$L?*$WCILLGd>)E*`lK^SNaqq=WNLvXkLETe$ee zA;B=i_LzNpg^&aKTglgSI`VjPE*@luIk;^IS=MR`aX3hE-Z%-ByrGb8(len7_3TClOJhq{5rxBWf-_4_~O$$MePNg_BVSLy753 zikDPX!*plDX*jk>VR+BSFmlo(ghV(~Ji{0(Te^SvgNS+Y!!S}lW)=B0o#Oh#xOm+x z%u#2;$jz}U$v1{S%;(~EVVDo>3nPD@1e1wu8UuE4an@1HE)iiwo)JtcXV7U(&*9?H z4>7m)4FMjR9UNe6R^?@Z?61Adq%wFo2K;{C{g&J^!m&cy?FVJ^^t zulY~SC*#a0{+P_gg=a8td%uB1JIyEa8IHRqVfs@4+d%*4m>;fKOYBF?C+isA|A~ur z8>F#C+Af5U9n^W~0nG-jk zJY!2Y*IfhS1=ZbP%%2Tb5%KJNl2(td#@p~}m|is^cHfUV?fFU)YdV`WsG=8vJC1Yl z?;DuSFRvum%V&{6Unu@wz{T6YV7{2Kl6+FTlF{!ePSiSpI}%;zf77sNjainmk~lwe zA)Vh)Jk*qnb8Rul#IGdD%U#IeR}|-s;^L{Em|yQ&N$h62z)vkueAi#X^ac4hjZYgf z_n99=EWBMvZUx0nW4Ji{1m-)n7Lo3&UC2F#JDlfYqeqxmTw6fK?r|a87>=mm;!K@` zY?1aK^dqOwxDa=Sn>E79u0`oj7~?BArZeVaZTyI3`zb_V8)({_i(iew9GgF%WU42S z6>RB}9VJXx;@`;27h#@W=}CrUjwAD5)72Qhnv0voVZN|>7U`H_Pg37fyg!wT59VUF zAK^;O751dnM~cVX=Hj8RFeh5O5MO7@zMY}C{U8a`m7xFN$a>Q;hbbqMVZ@%KouoL=i;I&( zq>-J+6H`Zf((4Gt_qK3x-vgKri1s98sXeK|ZYCd$P+d!Rmn43NuLjK;gCkYJKFz4bOgE0p#8bBtM z*^@(T8vDj^akn{`jYsz zBh|K~2Af8GeXLslJF;;%%-v!v$bLs#@`!CqA@O+QpWnFx*zp_t1?G$c#T^d$}1zOi-(7uP$C z*}%C0@$v0N2C+MVy>hrXQH^<4od%@M=pJO?VY-VRFO@L;m7IUm=vRe#?0}l&=TIwh zhT&;?NAVc^Uz~4@+4<{VVdpJN@`~YER$S~k4D;{Tzl3hPEy*Q@XH4eezjHBfH2oIK1 zm>qqJg|UY$$vTFIe&XWkddJuzt(aUSTs>z=HZq)LfE7;WI1PLs{A!8$W=MfB<$)z> ze3!l`lN4OMX)@;d4<8CyZ!F2dQi|WZNf_?cu?@tLJ1oa+G3Ju+L)(fBVizZ$!>eI> z&?3%C#ys|nO0b`9M(jV(kry22V*6{DTb#-g`pZm6zfTmmDCFWdA2GM7%oOHSwkPEb zFVs4YI}+St5&lhMr2*z9FZK!TDviifh8vl3aSH|JyvDnQgR70mD~3;x;^M<@n7bG6 z66#MhB9|F%y^xECg=6kiW2aC&)QEIrcxa4-;UciwoF5;<{I+ExShA}E_w!u5 zumH2$$6&#CQhPFiT_X*z;NtpP8ElcxL@X4nD~w1vyX^Ve5G%bhuQrYSoiGPKnJdJf zGa^md%N=da#lk4e`#1UswX%%JGKPyBB@8F>Y9r?_z#KEdUWiC+PYl^@@Oi7b*ee=y z@Z*7kqJc3{me76ULn;^Rp2J+=DGDd-j7e>F6E*BM7w>w3xv5uAA@O8;_`w=Fa-T{G z!x^dCoGlxkU`y9?dsE?|r7?+MBi}T{3QJcVU+#r@n^05OI@_4^WVdH$4dP&&eA6qjUo%}9d51Tv6S(-uNzCN?oW7&}G$A9}(~(c)aq-Z{n4`CB z$XxKd2}v}jc@uNv ztqm79u*cjk$@p|eBN-XOZm@TD(ZG1OXYXRn>Yc`?CmYB}z)(7}WhfVu-I%jI+MW(D zk`WuYg$>^wr%M=K?ku{_IP!xFnAgUcXI(dy5j%EIW~iEry@Fku?4Hc$ zUtFvs%VbNZ9=|T@dM_DK&!W@tF~&+yU)83ut1o7w+Z(g$3NrGEVc9S)?&XZx;O~~K zZMHJd=T?M;d|E4F*34+;YK+c7;kk} z-o<=>dQD~YBpGS2mTutbQZC-|1M~U*y2`WDWMsk)immic|KBl)bHRhC@!(&;_M-qyR6q!mclVOVh_c293%`UbG8~d@&q5udJ1#pJr@~qNTT@TGA@3% z4RiiqqO^6Dkrxc_Nao^IS(xiu4OaRC&R}@YH7;&dg85dXValE}Wn>(~tv+$_(K=ad zk$#*Vu59EcBV!ZkoK*%`>5f!w14nkpd|b;%ndu=TE!b*YQ*d#~1kBxjFH?qi$;kQy zI&v3xE?&F@vv&K{N^2h(nayy1I2Sic#Js=B8fDsC8Cl7&|8Xu(y^OiT%Qed7^JU~B z!*vR|SbUFJ=(Sc!{AA=H!|_^5+>zjds@iJgH^Z#gFiM#VBR66=#*~Za5X{@WuEvp3TwHf1W_fUu(hxRq7{gQixj11x=5(*U$}6yRYZx9C!^J(0VAdo1lq2TI zh%KA*)pJ~YZ;^-1-s4 z!&h^0ZWQKvT4$8gJY}S?nBv2!Ts&EYd4z7R(%xN0yh|vaaGQ(YmtnT}ctKeS$6z7D z4Jx^KZM__}NV~3FRF=YdBaPwdhFIxu+E&}Zjy*8XX_=?&4`-xa3~LYK;tU7O&L(-v zuhV6uEyE4Hx!8UM=C<|olvkZ(ue%#ROW zR6d3C^FD@)pKx*W&zLI$E-GgMe!{R#Efwxa|GOH8T4D~iy{PO7cniZ%yK=E@f6OE6 zUsRe>%r@}uI1PNTO%Uv&PuwvdE4ZLMG*w2f>IA_ClE7-1eo#leAOdqr+6Cp~cXi3H zrW8Mm=VILq%y(8?P}VzKi`;{MAN(BS6)xUWh&g-81*PYP8pNnQ#nx}RxUcpZwn)SK zUQl*hq(dfkptz_hR<qxPl z3m56S|N8Wmvi@Ti1Jn3StvLaBMyk;YJ zy3fVuDlm^YnyYNNT$@Z{_-qvyPj7UVEnVL3T;;Yk+T;jZ4Tla`HJ0w1HRfiUa+UKp zYLf?So!<`Q;&4aI4OhWxL}?QB^>n(|wO@_dXK}9bPhCBt97IA$(rwJseRGwU0veO?P85$QtA^>mfzv4ahWYgTT;*}oy5#c= zif8DZ`*#ff!z&FjSHYae1l1z_Tq!QGtcL$>p#C7t<|}fQ!Hwz@f#HzJT%7KOxo}Oc zva?$wV!^Q4axNCPV3vpFDmyf9LY6Zenasucr!cpLS1|iy6H?4@&ud)l{RH!Jom^!n z9T}m23Y?)nd3S~cg6fH5O$;l84+hvTu;Hp zR^u=W;knBGnKI(X=G@Aii!TRYo*$X3d~#k!>N6Y=&c(CiG22GxDlcA?k?{=c9_QlU z7cmcx%T>DO%7{LjbNxat-u?#j;)Gn~$s8Hk%J4?5+=81uo$VW&ytp`eDdq>m6O~be;F{l*z9?i17h5M`p6r;Y zlq=xE)r?~0DK5Tp1@j~CMCDjPM&cQEeZs{qA22TuOjI`S3%4vf(~&3F%H!=wmCZ4? zU6-h|w}wkKhI6`d@m3MD%Z@~4ZVwsR#IWl)F77l7^Wpu8%10J(Ey}QeAQ$Is!2B^Q zQR!z6pJCYs{)y+}2}d#ay_Kk3Y9=Ey**YiXaq;^Hn7fxID!;*vvN-k%j(f|+tN&pB z^A(n^os4v1_-xZlyrpZ^5%aU!Ny;g$;ILwNnhh5p8-e+Lvm|9`^Z&!2XJ}yjP&3jG zbFp!fa=1PmRyF7=7`l#&pYFuGt9z2NXHyyJ|A}6iyQOn+z!}WMCP}$Q1~?T+KcSpiGUvGsu zJ`7d^Uha#rbQ;!ux!A)N^Qx^$${&CY8Mbof;$I$^TSg@*bDGIW8-@$lXkfg1xpgDv z&|OK&bFhm(4x-bTd60{{oWR@`a83)jvA}*9&+;A@Uo67xz9UIF8}7IcV0Qv@e@OWM zZaU#Krs!N{i{x}_tMVd@Y~wB6qy!!^F7OY0d42nAr<>K{YFz4T2 zqb$&a)nFqp_2FWZMVK!|tya$d*@V<^r6d2^#>FRNG52y=rJP&RgdAo#KdTz1*UvcT zQMs7QQ&uW{?duZ1nRH~k5-u)(iFsn@mC7DvHAy^Mx-WIE;f_R??%&8O8e>j58?3w# zszVO4AC~sF;NoU|Fb7T#R`%@$AMxDjG=e8`ahen6hwoM>OPsWbu?NLhmT>Wa5X`-G zS150<{3|T;qjDeikk!t{>oKRo{q<`ve{l!H5$ z31=8Cc+bVU-!YH(4-oyX!>a2fwXEEmQy`r;h&HaQ;Y)4x2 zry8bTRpM$`*1o|OX+nGFEYWs=pu=##j#$|@HL#HqzGRMh(cliJ-`=e)l(7Bz&WQiP zt8H-PspByZ{8ipBf5kSNi}UE56aBdOTOj8BIfeaH&+6GcWFyzwC1Kb&8#)&pc|!u` zw8>j+2Bgcf#?GZ9$DjER*AU?UkcGIzCCpYIe%SQSiO;HJ2dv$53DcFJuOi}8Z!zbM z=qaT4?w~xwey!ko{hR;oNCMrN5Kqv@TrkZ^_)s`md4Y{Qzo&%h3qr3)5m(q?4i60# zdVh&mc4WBCR0-3ah~ED~yxawIrNMq-#HVY@^X&BXDpiu ztokBh`U42?6J-)E`i1#uNhk7dw?noo8`-V(t^byeKBQT~^NleN7ZqgS;HBAX*pZ?) zK*IFr)Zj<-CER2f=70qbq{)tL*{#@_e~zbw=}&dS@=18_T+AoU{fT&QfA(P*`S0Jp zJFvAF@G~l8iM}X1^gbJG{nPf%=cdJBzu*2vRf{sn=LPqF#Nmd^B*Pb zSBiN^y#vJl!t?CQY>%m`a~n6C{^}F_rn-b{>tQ~o$|T*s|H-yv3%akngz2yH!P6pg z@O4eF#GIXdnd}~4Kc_3h<0eX&{WGFRy>qU!U!G}sMZ)yy7H~*N z`1@7NMa>$DZDfOUy0G(9>kks9k4c$PK32jJA2H9EW*{oWi8=MzIy*JLgG&dy7d(Z} zMZ#tVn0s29h|O!x%K6AfZYoNcK3)l)Pa@&da?ICmSc+ML{Bu^ak@IFs7@i_4!oDcs ziEfxap^kNUMV*0b}R=kI_)}PE;3#zUhz7fvwA6=^Vty+rqBL{ z-~E&D(~+2OyRR41zvSfLcYD+QB;46?lh`lgvV<2cz+B_a7V*fw%Q?&0@9vAaW_gum+ zexL=U(}Ts{^+d=9z;hTx=F(DtV%gND^G>DRAXCw(boWy+gqrTiKVX$hA7rhz(_7PU`WGng7A0t&kOX(1{kEJ1^ zceRwKA$dL7tBkeOyy&er>Uw!X+1R-tEokIdEsYQ)ty6hdpd6Qruuvu95^JdjJmWpRk#HWTD08~Ld=T%@?~ZfRue={9nBP?Ut1UBH}I zV}N|$jzCqHOBCOgs+MeZe>wcDm4x+QBfhfNPOftjQnM2h-yOx#X8NfYSHItuZ&zRVVk~~14<{!Bm0J`EPhaYNRV*Lnv>-E z>FXqXcRFT2tLgGLM&T-7?InOsT_xPw!U+3 z4ktF%9pfc1XRU*nXFZ!E|M6~{YON{7wGT^pP}m$fT$@NZ>MmyMOa5}Jk|Kafu--7DeE+c00wh>)N0Pg9*0D2|MhF#IhDIh>3o+$jt5!)sgQ?FOZ* zF7~6?L?vPR#B6v@w1jh>Vm|UVQr_szQPuw56rU@TFnwb7%T7mCQ)kf^Wqh57Y&FdF zqvhjQoKSU{M6pvntXk2#cFDc6GbH?~8|DsVx7?}DX_Xrcp{u2~k}$mI%HP;$N_fo# z%*|&d%0Go>s}_1u9ONKjcw3VDyiiKmUa#D!C-zDhmQ4;%pq5r+=w-}y_tWK1H|MFIkED3ibqO!gPnTcYb5X)2 z?=UC)I3{0pe6*x>M}aU&3}JS#YG>lJH(v%t5(lOrOQ= z+W4V_z3*ezNw_ZeTUey}W}eLrw?z?#wHyS!<|N7bW5Iz(3|X^2ZBD&d&_C=Ky`IcBeMRdVB*pHCw)5?;F(v+GnX#k@;jRQ3!9rAZj>9Vi_7eUaYL4XK4DAesBNrR(XUG7w~UT_NFS@#@cNMdTe=8q%)`5wD6SU% zQhi_}j}aui&A^1cD0nGq>WF!%Z70PCyI-nLyXnXwE)s@63&Zve#L88elg-T(TOEF? z%#Kj34wW!`Hh?Gd{*;cv@u`>-O}Z#dSNu=~oThm3VF|zZ)mhQl0p1?j74fTEnB^VJ z6~;c_ReJ1l*5JN`;i<-oH}>BpyyhEb>yF(Oe-)J~y|Zl2RT8F;Acu2@bOtmqEM`l0 z#mrJ+UHhBLxQt@+4p_B>Vhcs$;BOK>G7$6Mx;+#>;JoqfE5-MQNqEg`D}`6~7YPsb z!ff)pr{d;-&#Fm(D4sA+!nZ1WDth+(Ea7LHF;Dtot=Jm#QMG`*(|p?@;Z5hQ74UbF zB)sSp=FK=Q;n_4E}=w1C3 za59!~a?Ph~H70Eo6d&B*s6=*|rBx5B7JXj%ps+U*R&>R@$5m8pa(SilVi%o>RuXP) zAu8ZKLBjX!F^@A>C}M0XROPnxeb?AQ!bLyiiX(m%(#4Qh0OtK4`YU$Vc&@tbPVvp< z5{|vlU*YclT*BJ%n7xk;P?+bHs+dQ9hywl$mV__MO4!obd>*QJG5nD# zVI9S>EwO6teh<$)Kln&hx|d#|I`_jo^Y}2u=iLP=A(f4+kgz&nnBriYLJ9wL#vCD^JKoTXTnA>oLq(TWA0cO;yB5A)=)V-+#qZ>Sv3QGByd!WWIkDr!!;DdEXK zFE3QH%mz?_-lqzGSlSQRQ;3OKB{gu5Mcf>Xf}3GbbV`BW2U zMc|nOsxlLbH#teT=*M(8x(`a2EXADYGDESVZi*_)g5q7PCA{8th64WPkA(9RG0XS5 zDEd!KR*BXWo25y(&w3Yy#p7gY1AVVxHY#;htaD0GU2RJ7$~zJ+zwN3>AG$}vIv+6i zX*)~tc|)vfsW!zezDszU!7N2F0U zaE=M)bbTL%*S*E6+ixg-W-ej+By@UP2M^c@BQOtZ;H&8H)mN4Hnqr^v5~fc=r#FnG zqkBH)Q#I!*W;na6)GsN16)53^R&y2b)OiW7-HAEn*IdP>nNF&Q6%>~xNLVPI3#VLX z3AZ|fdG4)wio@q7sOGbgoi9mvM)^Di+y|2I(Q?dZGUh8zo*$udenm&F@lL|@dF7w( zj*{@O`p?-SO%3)_6dDgyRkD#?^s#EuN08IIhPZ*HJunY(U7(n1W~1_CbFL#um_Ah; zzC@7l;whL{oBJzlBCJ$#a0b-XI^`l^`k-*QIVa&p!I+=E@>dLxGE*I4BVP%XFnydi zTqjAV+2tKtU2QMn{x>jJ^j@UsakaV1<0Qo&)Doso zG={&QBjNndm>(1_QhdJMK=tYX#gSDKrqA$&hn!1zPOBGe=^|z=R`?vP37_RC{$h+( zi#`GNu}N(S*RaL>v_^oU71h0p%$v zEMqPJ(rd+==jEm^nCjWV~hGAe77YVi~7YA=$~YWisKYa??!L653iC%aTK9vW#Y#XhfVX#8Dz{-Qps~) z5-z!Fn#rS+uCA5x)(mBY*`O|6#5|5Ao-#ldN&=KII0t>lQ&tr$`G=+!h6=7_1} zBMk`K9-C&GGx?a=!2_$&uPMuTqe2?iOeMGJPx#{XX{M8x`xxBiD0k|x3^J75gybi4 z3ESVEW?HeXsWRLJORl&ygN%uAlKplQUUGSwX-wg8#R7qaOw?hP@tKXM$&p;(I^pq8 zrkR{7yi_W{#euH@-pe3k-j?JYUkR^Eo@QD$3UZ)QZe#mO#t23QSaL!5jupr2X_?wm%NHiKgp=@lxGTzQ?Uk{@7nC3M zV;NKP_~~1cgZ&9Roc1#Q=(7n)sP^ZO$fQS&hn(FW;3mJbFIZUzs{rO}N~$(UpOP?q}$!ZkX2nOc3=B0kE?J+2MQ_#%eifTi~QW(Z;b z?*mN@%Y=)u-!OD*Ca{dJc+akdu{?h6ae0ju-7L{D`AmQsB z`RuG`0~i|u>`_7@Afsl58W%4$gW^Q3d{Jy3$LXtxBE-jG_jBA z*~9%J|8FeWKKDDi2emDIpgr$rIk^(ywD-MCb-x`Hi=@2Om1TIWnegkfROhMf33nOR z)3oLH5fLD(QKT2kotO56dHy3T7xE^Y^>%ktz@g)!pNz)InJmL=2Rvbqv%G6PVTWej zOjUx+B0 zOC3zrvYr$EvWZ?Zu{^C%M-!wNS>Du#aEr?AOwlxbI`J$QI@1 z9azQ>bVjv)!gAZrgjWUDGrfBJMEJ;(&v>)E`+XhgsFGQJ=1aKxhB~Iaf0D(pELifM z4J>;;t8FUPCxr(%{+kHrQEQu87*a$9Ic6z*ie(sr;Clnh`Ogq;5L?rfW#Kd7D_;c? zp0f-qaBy0h<(;nxXMI@RG+3vt;E<(R%K!x#(SgIOLsfUwi$%BK8XUy9=`Q64&n zdrW3hei{~w{b!APX!d?qE`2!n%VHpOICf6KkEXRE#yd|)->2#4aA!K473!_}WQN9|>(+cIwAkVKsc-@V>rko;ORIP(0pYOu5YmPh_LRYdI;cRMd zlTU$kvDy{oy?!hYh{-8sdL2JLm9YEnoTgk`(}Y3F#ka6rC@QJ;$Mp{Ls1S-WBFUxEV9*+Jo63V@h!5LPP)Dp z;c^8|>4IM=bokkBZ2Tk_E=>53gRQCNqF18PL@e3TnB|MUe_-*_OP2Q;2oHGjTZFBB zDZ(b9Jk*nAc##vQKfhqP=^(;$j(rzz&%O}Ly-{u!#4;>575IsCs>a;~g!_7Y7Jc>S z;;awKPxi44D;{wD2FsK76Mj(my~w#GRaEvxx%MrVvEkzy4k|hK9m1b?riu2Go{2_& zD1Z3DGS(M6Mv^!EA{;XOg>Y}0B7&!)98&HZg$_knNy>7)3WS@A6k$G>EWD?qY;dvix%mVbj#R;z)~!qUa$kxtPi_KB4i^MkTMY5YAidrl{EIfyib-IWd`KSbz)N zzKvlr)c1K1s}Xr@~K>eJNU+lA<+rKMNY(Kugx;71BPXO zcUd0bN;shLIq`1a9Z~xtmi(~?%dqAPS2_urY5v%g@PUG{qUh3F;*gYA&0ra_Q?R)7 z2Fr_P5?=n@BKi)vA^OT0{l*b2*B=lgZ~+sQTzWgOW7 zJp1Cs?5vo4IdX-I2#!4>AmztJwEIA~)XZq{!Q+zHo*iY=XO@3OM#Cb@ODsQg`XNJ? z-fo}pIeS5PooeCGn8w}=vLo1wgX3d@ZTFMuW6`&quUfpEgw zd7^ZlJtEeGa{OkNaTRHq`FmI%bc%4#E3-w8;GN>F5#^z0S%x%}I524!%fFu!jymlx z8Z?Lyo(7b=y=EDv;9$911k20w{gR>kaBiYFv3slVZG`fw0z@%W1FNF9vFuWxaB;U$ zVokP9qH_b3t2JgBzB&x+`8Khv_a)qI(jc+F$9i#1<}^w1(w3y9m2~_7L0BLPQ@azuU|5)vsM)DdY;4=U*k9HL9Ix z@qVdjEbF}RCd;t$Tog@Q#&XFogmZsuAzBw-Bs`>CsKq{ zRsKLRSXSd~S)w-Z+5opzAj|Dq5Z-^S9!!J;h&6RFbQ4;$JOkc6`UTHnIe8@E3qxy& z3G=3j+;vdCHI`*qfg^Bgh`JvC<%FZ0D~pADy+v?7lmk|=3`>k)wXP4#g^m$k;9Xke zv>7elKtGkkrm~r3oQ%XZ*HrSZB*G&ciVEi`gT$_nDDQm2GOYW82i_2tO^V z5UzH8#7~)8^~gaK)_UfLAJ>oNJ5>qK-JL^hU)M!^ld07oHCb-oFek3^XL({5!Uq@G zijTY9#SU5W$?h!UP6&AEW!c`3aKwX8#*I0fiat^vJDp`1D;OItY{n0d(9MLGZcjBf z%i2)PxP(8jOgPIp_YCv=EY~|rIAC0Y@o9VwvDu7r*hQA%`DKK(4$D_w6Siv*XZ)O} zk|=)!<#z8_h6kPz=W_WWUEr?_ozqXVam?=$ViRO+ppz*=6dIBWTbD|){G$w5|N<(p@`axvX#IE>X;7|k+tU$8~&y^-XeHwhPr9Ao@a zvuKd{{@!XvVrRc_e$8+%E)<9e2HuOV&|BRMsO@WGACl?A7| z8t2GreA8LR1Q+b6V0r2j!smw8Rs0XsG#aEFn#wXB77qWh?3lw=M&oDRK!e+o?8cb= z7`nlEiQ-`q2K<^fRby98!sCtEsyvQY6VOx)W|+BeyEd6O>3P zAL+v~<_6&pSiU=ru*>Rks{8bvhA1i53HVPQs=^-_sN`{Bggd_4tLE}tU@j`O zWZT!-Qs=s@Wu9E%6NPV<$nv1cLW{5b*-l4UwyPFofg6rxm%D^}Z(MEZGHs(JT(+2`2P{MLvcO(Jmi6C+ z|E>+Q98&jLTFU6p&yq#P$ObZo7T7w$a-WKXle!$RH2z!0svz5`PUVtceN*Z*;Ec@3X9KSrf zw(wSIEm_LZjabGN9WX7!a-rUYyF2C6YIbqf-bZ2RW)EZ;_cg*(o#kD#2#@?#NHdhE ztMdR*e!ug`gYx52^)ovZd zYBapbGA@R>=qp&B_>u6QO;xljaqimn6DU9W&N9rvY43KnV%fg9y$s#0BegZBJDs)J z@=@wpmZ%NxYlPiuEQdBF9N43wcH>?zt)Ge|=WNX~*4LP;C(HGQ6JFO!Xwx2eYQ<#9 z2gb6D`x?+AejOcE}s$ zBH=7Uu3GzWV=2oEV+ofiGgCX=aD|q0B+BYVmP68~YqYkB1A z8RZ?zZS&00;C+te!w%VH=$^F?)E-q@udVUKlAjeJYIAAZd~Hzvbu71QKzR4-h1%Ng zq1xzyC@(OwjH?9UYyyok_o@8|mtM3~%e8BZHbYK}wjaVWy!dJVb_Dv*CA`2TL@RtQ zOzS20X4MU5x#OVa8uX-Gvg2;T8_%uMy2NeQqUB1I(nnan`gNrSFWD^bx<; z_Vqul<&YV;t^-(xp$6Qrr&)IKCwzR_DXqZSvs$!_#)o+| zUe)P=W>@K^R#jGG=}MNLZojX=+#bux`v{L~_E^iFa!V^Cvxbf_EaN^yT;)$C``;p* z);2|pn{Y=vBcl=hm}Qv8)rw`k!*ZdYgufJfp(~Ulp5BXO5RnD z@N~yCZEyQT?U%eLWoxnwxgrf-D_J(V6aI1MtyW_HJ#EWJY<1_lvAnhTTiDqeqV1Ek>xHl@_`Ho}+;E3mFG#jm z2?uQcsr||OP%Bm$<#iWW#+`1sr<3H+WWpy_{?!KmdZ^v4g>tjEEJIEJdeMh0*Ugzn z2C4rZTmAdPN80#$C?6FsnLWFIhh-RA>X3$IS${`ZTa#BW z)8nZ&UgkeH{bm_<73$dXsN^0+^UBbTneL!3k9w-rmrtu!6^X)t%0b6HJS4v{65cl1 zQNNruMe8Z|ufJ@|GVChMATJm~c#U5{eRSaz?U|IvOk{cY`vMu{l8Xtq>t9%J0VR)7 z@S>Dn$MUD&g>*=Ka5WA^6F$(rsP5&GqNOxJIbLJgn5$?8xm^O`7d?yVP0FWehh;R@ zK4baMEvF3fvpg->M@S?h<^dg&|YNO=k{#}P< z7?n$z1}FL36Mp4bMlTG}pVJ%bJhL~;FnuO33dy@B5%$kkP7k}0tQkh3Tyi$ckl>Y< zo8;!}375=PLBG{7S-U?8<>?fG<+uMTG!wjk=*6_6Y^ zoAAZXHT9s;Nm?nHk7dctj<5_{5OwUnNd6U1 zcvj9j`mW0Nwc%2Jd7tH9k*+#+j3h7rM0m{Ox_aO5iP~r>ueHlh4N3K>tK(*OdO>h0 zLD+F$eZ6vAg7$t3{=h<2ScVy19XoT9^=5>Z`ZUz1cfYGOm&5p@ome*JYN+F5g5=&K z2#;ypSpTNo)*|J5il;BjK}8zt)q?J@oW6|k+cF0Ib^lx1H2DT}J(OiwpQ7W|e=2$Y z5yJhiE6_x5Xs1=I^TX3D!~BL0SwEIbJ|JwrSm%I3!1NedwfkZ9FW}&SCS%!1AfMW;$+- zBl&43!hJ8c(2E?rqcK1m)!If;S;0U>PuUk);>tN%x{*T|7@c}QjO&Y`3uO<9sJx*e_G&_)?Lc2DiXDU zjD`Mh)16;K!nr~_=*^Qg%}dt#QCpTDb?TtMnXYS;vB*AvaP=CU^b%uKtyl%Dv+qQf z;hkHLm|$Uf(>%f(4t3Ut6^qe!)I<6G29`Sx>a61qJx+b?A$+Qyhi+bZObd_+s=KFH zh8JEPPXQtM%5}n14|UaZeL1WhlBus5FIa~CiaMl5S@!xyIFD<0-O%BnRzhGke&s7j z_aN+7)a%y$|LuI=OEZq@q4(XgU-Or#uO0Q7!hS{lZutLi=L=~`cuUn@`uewfwW~7q zWgfsXtS;8^je_c2eGK7(JA3QXO}n*NnHf4dhh^BWs6)DrWqk$VAe+AW&ETEdHklb3 z63H^`SJd&XjY{rug0TPSe)_155!wP7=K|MQhNOv(C&ZAP{)q4hwZC5a(l*Ucrjgvf zvJ4AD;h7S~@`7xIWRSYs4Ah^V->jXGX{3jxh}yuCQ|OD%V6(=JIl`)HP7nXHZ*1*y($rxLFHW{|$6$7=0{l(&Si z3=43f`&z?t%2vW3s}9ktxUA6PUGZ`^I?ggI?S&p`CEqFj=LwG=I#j>>eVJA&FUpAz zSw3ERD0DKxEIYg*{Ce6jy-?s{t-ufL3WnJiriL_Z*f1U6>Z#w@S%~o9@Zox~1`D(~ zZ&9vWon@Fg(f{o#Y;GWY;J^qy_n~=OUAfyW)Pv;%lSV*S5XdFp_9FcBz(_r+Ux2pn z8J6ts&+>qnkvb#-IT~XZ5S|b}O5YzfO~vkbHGa8a7GtUV>XV$vl2#mGjQ ztGr=%{$zRGxJf!}^w(yM!VSi~a}||AN~r9u|2P2CvpuoSM-wT5ZCH zd)~TFgo{>t1j>cmuzdBaw+`bZmgn^(?6%ZL_xe#*t1|)RnDHz>nd$=r*9t6`m`T{L z)MS17S0_#NMp>+3d4_2+40}qzYaZ75XawPg`egn2h5TBvbttE*EW_j;+=B&KZgYun zp4Ps)X?_kZW;eTnD2oZM9iG-);&#CO%tW`Vi_|&_wv@t|@x<8jmcwAEDg2C(E#hN5{E- zl6MRxeCo>-eczHR7X1UtH)gO5+a{qQ-C$WPAsp7-Pal$?S_b?^d0GU^u$2hfMl8#> z4-$^v;HURIyvI_-ZU)H9F0l-IEOp%6SfbVpsPlwG!XIw<=}z}ISiGE3{`8(@*kg(P zGs{_Ripd}qbn(}V6D7P@N3>&L- zSO#K=n1I!&(}D22(f;}-`}US{BTzm&lx5hx2?N*OEXR8jPG0S=r);faN%Kc}#F7j$ z%w2 zWP@_?KFV)5WRNk3N+k#FB0P7Jzn;HzvQqp!%5kSy#)|?Id@L8gO89}%Ur%US(AXpf z<-spl#>)-U7O;o_t8wr%;ZI-v^Z_>-7>5IeU4;%MD0C=8Cu5{Kw<$?@_GLfa=-AhI z;2O#y^;yPNhY5KqIi)$_(o6jGreU*;KV>yc{aA(_dOGx^EKeCpcv3Szy=vhQQUR z%5ox<0pmKZMzbWsv-3~U=hr!BbeC7~Ogk{*N4sR1#VJQ|~Zr9C(!`A!g8<#nVa+^?& zJ;pL@6x4BZBgq%f5O&G#qc>RYB%X$%JnA9Kuu)KlqoG*#d`&pMv$x*1XgN`TGs+|F zOHo6D;~3$MzBJ1}90@dD!nf@sEJI6APH{ifxmeXz!Zk;wx|CZ2I6dHhXt#p=gBm-|j zEYJH+xUADSy`pzNk<}CBI|WNq=pfgI!ycAPlqI~f#aO-j$swZaV3b!hVfn+2u`o3> zh~=ZL2-hD!M$eHtMwA+ka$zr)<1dfVahV?dz&2wE`}&R6SAF#n4P@x_AeP~T3%p@j zezKDA$(5t@xJlE+ydxsVZCk5r|<%z-!)d;vK z3s@F42@i`Hrl&7lD)!bz`J+3_cGZT%T)`5SZ+9a+deu;UWQ`CpxHigb#)mm*Gd|qLne>qtYL&5^A6Epd#({qQa-7&oa^pjnC)51 z^2Q5<$1NSCFaEqi1Xah9yFF#OU+^FuGI=c5c}sX#883b3@6Dotls$5lrG|trVy60= zS&lDE_|n6H`ufRXVz`tmxw4F}c#x)K*-Ih(-gBTn`*FC)T?4CO?#VK~JmOklx`N*Z z5kBfYKyNX8hbSrK<1<)>V|4I^m*wDvgf|8E)AxVbEn3KGq(`tkYg9jcm1eo>0m6As z_0=mr+bga~Ip7k@urO3#x;Bbs?G9l}R3Cl8p#9>Cl#730xx)S4(4M1N?*5x_*O|R_ zL)nAkpp^GHm7~y2UfD~BQ%+eUOC2cP+P*S?)1=` zr5_WurTlOx%fYeTapr{O;u8r+Ozo}*ro;%7l!KPA+^canoReYs;9A1zS-R;jLM=j< za?L|5mpkC0+t{3Bxs68n*ennIdHs{3n!G3pi7daY+yw`&ET^OpzW1rK-dm3qlce0( zraVOhHaF^!d1QG?Zo;Nc9rfQy=R}gM#-qwC!{$aEPYtEPwnH7lOs4(7Z?;#&Ja}z@*Z)&2!!C8WyRWf4<}%^^lUwV>c3l&nUZGs? z1Ab7srTG@L!5ny^8I`jD0FZpnvRE;QZzz~5%$R8ra#zvOC(5n zetnkVEfeQ*S+3obaA4c!dgR(WqMfY9-@Yt|o@uJX$*e427)JQaoTj?gCP93Y^42*l z!;Tu5lSyQG;8Ma3jtad>Vxq{JhIMWk$ugWh2c67)mcJh&JnOllx9fRdm}KZ2uCWX+ zyEwtl^3r>RKNmIV#o`}`mT*`AoGg!WaJQn`%QQkO; zWjH+$QzYD;U-=O3w6m`6e(Q;7P#Bx2F@$9}mk={GEC*~P+$_pfuXQI`oO4Dw=W&){ zV1hXymW#y_ULRLWAH3kHIOK}5`$LvtWftbGSU&WEaQSOB^x{2I#IS}ace1ZU4JoEg zbsf&BWx2Hj;hJgH^k;8UghvyUuT^6ilP@s5Wcg8j!ge33=-y+WiA@HSr+Ki9X&v0> zM4h>BKf+hjob{TIo{1vz3G3|7a#F?08RYzP3AaeDr0>a|Dk5dc3%9Tgr(x>2r<2AT z5s`#z->#q+=#(m!_rq$`KgaUT4&^h*hHHe+z9^?V4o(#*V^DsS#3GNID@El+p^|Hb5biOrsNTQT zGjVb%mRvWA<>1)D@^aJ2Jnk6bC*Fniks55j-H7tNTP(LaS`gEeJlG!akZ`V{1$CR} zPsOi2DEIow@~=oo*+i-2&sm*ikgD`_)Pt)%75fjNY+IfvY-@MG%p;e)v>M@*HV*no zL$VOZP(I|&@`#YUm`r5Z*@JKaV_to_>k~2VILb4|vyAy}+^I&@F#8d{pD(xGxWr@8 zU&>|Iu#A~>>{O8O)+KiO{Gazk5h*XM&2s1& z8`Lk|*yY{4w;CHnzhpu|;0)CYM;o6QOYr z9LafZ5snOer!`-CLmZHE1^3^xjAxm`3LKUreh|JKCLsAnYr>nZKh=DvT^1vyd~YbrxX=T)5RyD{ z9N{8I;3I{eaiWiuXDwkF_D5=Xm;%W*s|lCibYF9|xgh+c{O2Icc zoa>ZWBxM_CmNB1+2fS0s{c90kyZn;YcC9APNO@lemN7*MtE*Z5)}3&{t>?9h`Bc$R zUX-8SEMwNO!u=C0FPTpG&F0hE)Tt*#s+1pZU>Sy%8l1C>Ha7Y36+C}RG(!`_u=U$B+oVy4sbf49kAakrhZ2G zeqWaH^iJFjNpjI4gge&QtJN+aDH?x4x#C=w@$^prmpfQKxQMVfTR>+1*?S+-1b3l9;|U$NvT$5@6JbPck2ERWF%KZshag}Vid(((#Ue#kPs`a{35 zgk_sl!s^u^ZTY>$qN0?G+1H?G;8C9gVivNzE)U@bm*#1`l0Cr|H^~xpT!LDWCOY8Iy828A2uZ zpH0~PtB)2@X118|4ojZAg=IV!6iVkC_R|i+zER_~v?J5RbvYr~^c>4D(}U~GSza7Z zc+BzJbr2*C4WrT0GZ>Ob{>Lc=cqg*+Zx2vEmp7Au{DWa^lVnS`P{0z#ypR$Y_S@3I0Bwu?; zc<-6w+E7bX(fv5e_jA^!h6I~PH8|LwP@&MWQ^bHq&+E3P3MfK~QS- zZv(>9E;wrOQRT#`%_zI{WEs9=1&d2dv%H}{;cwA-wcABYi?E3(FP*{iL}M-ucE7M( zV;Qyhgwaioh}?yf)ko@F@q!h+x5qLROUB^>+xn`Qspyy9L}tj1U;R|*|&M}m3_ zTCuRGG~tW6-dWb_ImEKcC>JoXj3>LoE+dx9w%BS%&vl+!e+0 ziP40Uhdj1S{%a%R-r)XUhBQ(&x~(7_J?Wk$zsoPS>6rx+ z8MOTD`EkO70&ZBgZTM(B_!>*@naDB>04?|hHIipNBJAgL*|IIq8>5gLaO`dBP&D8K z0}HIKX1Pc?zncR#q{)ovAf*3_xd@@xN#2; z<)n3t+tLZQnzqgIsAa72O$?k-;N%6Cn-n5EJZht5`X!5ThFp8;QJ-bp zI|vbB`C1dgQ{KU5!_CKxm*f%uS^KdJ+j=Z`kSJASv=`we9wC;Jdk-12OvGyJpTjbq z%?pREv-~HBaR0B1Ez{rZGcJ*fOY26mjC&qkbL?e#O%&nyu0fUxH+CC$jK`7_uCfei zRSSfVKx3@s3S?=&u^=`)3Qw zpr{4LN*?%2nwBJrCm!HFRF>z}CcJ-{Vp)@CzVWUJ zd15bPL3zYq*UcXw@OiMrnE7>mwU793O1zBK?kZr%QMo)Yid>| z+#%quYU$->ymAJs5!#q#cuJ@+L}K}Ld%}II#H$t0n~au2C@&hwGQ5?l&`eqO^d`LX zrmhA|GZ^3OLAhQa%g}SFc!B^`pqsDGg5IUKFP~Y5`OY@ zj~dsgu5tJ-lz-f08F#hgA`6nsJtzFrEnH2?Q^VL=$}4}cj0;(yO|z`#Z6t%V^XCTD z2k34oS1U&pPJ&>i{vlR*&$Joy*j!*>fDru#;gm>Lo;>w#%TmJ>=4?z+fDjo6yYm@egMwOEEKsJKjqN*>>w@b4)_)bP-3 z#sg!qDK4iJxQNnp2Tr^K?_*oezKh*W(BFoT_%y1vFeDwk0g*PM3BbuZu zPVz%tTi>w^m)i_gVR=}VCNf9^o-H)LSDq<8K3I)xMTy$L{b$DG)2YsXs}Q#P+SP0) zl9Ufp-fv_XB4LJ`R-yJB(wXpqQiaS9jklF6Yp~>AL;jQJ#^8wRiDz)*n^{SG-17-1-We8mp=nlBfiyaLzbh9`4H91)7h;nE#%JV7_ zwSj0DpgZ7_D>ous@JVu$y8ZSkJ>fG1uwbEmCYhpfYyja}^Ku$K?uk^s2BMtPn`O8t z_?dgIM#uSt^RBON=z1eusWlblz3cxgc`lr>v61D}J%qF09c`%hI8-Sl+eWvOEJLXV zJb8qw5qN`e+3=MHuYs$TIN6?0q*|2=eJ6b3!8Sv|OCbtHMNmV+Nc@w#7bg5`eS4)!;|fY$ zS?3j1t;+8Vgpb_lqC~tZtJILusL_RGyn1*QsT%VJ5mqDnDa+OtRd!1G+7zpDiG_r{ z(!7+g@&%P*Rq+R|*_=VfmPaKY+)sGC=MZJfp&Uw>l*^rE8Jp)nxx*d8WfI0Jdv|70 zHcR>9Ype2;UxaUupQPmJY^%6PxorUxh3v73s9<_O*IUzhS3-uXjK+#3Eyl!M{$3YY>1a~ z;e9M)pMiY`RpYjWaJIBS#W3QUAyvx#Zd#Scq!3PXU8ocpbKc-u9jnp&M<$v2y6m}| z${@9HTcmWXf7&pyBg&7<61Blj5j#hcH@XsT^5_avjLa{9vZg7+1jpeJX%0spj?saX2Qlk7egOK0)Y-DB`d;NcP z{&tCQ<9chA@q@M+>dWzlb8-e5E;;|e;17hS_F1pI_X;+oNcmchX4H_d2OGA7#${XKVm7{H%%OC|ige#ASH8b>+uO7{c61Bk*!M{4YI}_g3X{Ta1 zYce!Dj3w_fW|HZ3>2U|bi-t!k-I|#Uk8h*gb4Ugm#~dV2^C8@EQw&y|SUP|5!9JW}rCZB^blhj6<}hm`f#r#Gqd27ln|^;YF3k%a5k zKcw^@GP%iZ8M?reEaT7;2e0%4FJC2mc=$2p%!#{=>BAXipIenZzYzX5^@OtHLaD}! zWHn;)y3sxOza{@HNqE8Z80EXI*3ckjk9t<+RV@hj{uHC^`c?Y)c3J0yK33%_qX=hr zHY*GI1|7dEPc8`vuqs=Y6E4%xtX%Tjc)Yxn|Ln9XcRNP7eFL+i?A>(S|24*W#}%vc zn5lyAXCB9jl}#dL3UU<<29m%I*9J2dBg;xdU4r-z?=n!5L)e z>td*FJlah7uG49y(1iwA32Medy@(NaC)ay(#{Xo|rgg+$3Di=rCo2O_f7cJ2G zU+ADSH&e+M$`TegW0h_Voz1QZD1T{WRUX=!aLk2RB{Fv-^M+?AZyLxlzU=-h`P*2+ zH$I+IMs{p!ejsnF)`3<_Ubc#`|IIVXh^B7lHPDOx{aeXQ^vbnZkb;5%4cL`Gj!ITIZGck)zCCzEv|$`7kKJ-0u_q?2)al%5%CC{;(%bIqx>tT<{~x#m8BdOHL>3{vuB4>om{o zAn9N zGs1mm#VYe&C7CaIeLRG2G?!^h8Z5*Q%X!F^8T)sABsb^Jw(3EhM>M_c~Wxvfoc45g|`&gB| zhZ9zuW0aJ58+EOe+Xq;cb1fr$vT}^l?u@NEIuc8c+sQJIs=3bF4-@|J@rY8Uj-Bc$ z>pba-Rk`tf!Z#BSDWm(^sfFaz(fPAg`I>D98KjO^4=Nsm?9{JPeqVwp55fOGbi-W; zcj$Of(R$jc(`B5OHn%FUk|LxLtYZDwr!6h zp4+OklTp^QbfkuaC1bjPO8)FX_`~Ym3YjAw1Jkb&-m+-B5?!x=Iz-B`=~m_0UkN|(30Ka#7f^dh`Lkmu3f=#fT%t5# z`|)8)pSA_m?^52}$f~^Gjd1G^+muz!3#b9|q4{Z`Rk_t@!seK5N{0po)KDq=1X`7o zLI}I=*rxP$DWJZQ)o8dclT3NvDaQ%d58tMIEmlBX=7`zZ$~RfYDH04F$$1|UUgy0@ z*_*q7nj}yA^!Q;_4zuqpgEVcxM#c2UQEecT#J|cCg-`ZoELl`1T&ed4CH{k>T16(d z*SEGR-|`^*`N4Xn;Y&v~t`^q0$T+L=2!FyM+t({LPaM@nwNbXLvMOiUN_frk^-9fq zj_N@v_cODM(`WypvHBe0sXbRK^KLn+1El=o97K4d(^4fzsH0l7E{5(~m{qw#6ybFH#Y(^yM>Rmop%<;nCvFj*VYf)R zw%JiFFXiU%tjgVf63(|^q2jd3QSDO)t8u!B2Zio`>-@SLVTY~@l?qVjiSh@IGO`Rq z_zXXAwmadxx#ufyL7p$;TyTh0x$t*xw*|z zEu9zZJU7~^+*&34c}ReAI|44Zd{3#CU{$`KOt@gp0A=e=NA;+@yHEVFDo@PWRR*bX z@c<=05-y4ystv0|)COnL|8#wZbO$YrT9Ka^_G--t+y&)4JRBMJV|K+@(G%5(5=d&;t1DpnWT&XdA1z5 z&PrvOb0Pd_vwu(c^}3Nt9LOc)qs=*QH)=@#D{m@Fcy^zmN{%Q;^`?|>*0n0v5`-JH z8LT{pl8?zaukT}3K0kzTTIWGZG|1KED7R&RRe9)Q!j)3JloC*loKk+blVwaJ{kwuc zq6tsv+FP;P@2HlP^4Kd@<+TZf10B07D-JlSx|Gv@S(Tmt5`L1@S?PDjL2U<3^zYwO zmAcE&mAcnanVjUH(q~{tI1{z`-^z7sPk8RH4obo^2laX86>NWvWlU%OYl}BO5q3XYQR(^HLH#9Ha+Uv@Nv46t z&=Ngm=-d{SRkGRTSNj#m?(%9WqB3>-@3Hi^8Q~eLN-H_CGDm}6)zq9Klqfzf;eq~Xq{Az<57!A#yC?xTyWO~vp zu0ptOK?h}OrTl85oDnNj-Kt!sGvPyB@+rm|`PF23&)@a1Dj)SF>{BM6vbb)3bx;y^ z@w5F|hL@2Hm%GCz!V7%um8OmItCMe_oMme!nO;_3oF<&m%2vsyy^F z*w-$<8rT5k!%Z^Dl(TI)fUqIzm*HjC{Oa-F{vh}9Vi|MH_<9CwHKAinm`8Z~;@5`m z+p??T7|Mx38DwnFaPSex6ZQ~}Yw*<2AWI%K$0(GiMrDw(WH`$R5ATN;Xm+2!zH@R3b_&Qf+hmgAcp{Jok0I=_G0D)r@L%)gi74+G zpGk(}i9r6df^eCV4-KQQ{4uvk^#!@lnoKh61Oj=*3BsZK9vW6?f6Ontq3mU08RpsK zMS*kMK(6wb@b&BQhIMg&%)?Jk26^q%Ofn3LKt7qRuZ+g}t!EAX&;OVQS4DYEE}}RU zB};}Ahd}OIgK)3Qrwqd#{+gFe@WDE}W|HB=A&}p8CH%wrq#@e$*St2u8|1S+Gs&ut zH^_lg371%}8&>%KH9KCL1ai>KOfr1g4&+kX2)iuT4HXXkHDCQQ5#);7Gs*K`PXzhc zdBVBR>4w&y{+dgdL^wT=b-2O$i&dbh8N{dwj?w!y!T-KP}WxhVIRT zlZKm$je4T_c#xBvi2fHkI7A5KsRqKSmrojY^|Mi(dX58mmWgF}!Ip7`gBC$9G>EX< z@%@H#{x<6T&SOC?J}i^mBi~q%cP${?pw&*p@>MqKp<-h|Ua=&T4CexYY}!wFwk!O5 zdu`O*??!>#<4`6U&IJPb?rp-QJhmCOoU&1SUKt7U-^5HZoPG)N#9xHF25&X&xn-kv zTrvXW?Kb^ojO1sm@a~2qCqcHaKzM%Nt%jgyHtIsdaFDAyXOiKlACN=a5MDigt6}>m z8#VRmP>^qT$Ru|I{P%C&350j-*lGy2vsIf04FP$gPbRrkpCKS$Swpye`c}hg2V2!C z+hCBJZpg4GIKrZY+^uN$u^c?_lHCMvzONSXIm~7R+r~N>- z)XyY`r1t|^>q&TX|1g7VTU+&U>%Jg+^~)r~Zak2?&m`==D$LNLtF5{ys5i*Yb2G^s z*7pWEJ%X^ynJ~ke-nQzAgq|Q@h|DA>Ug-&P&?Uk?Z^I04``N1V^Y;LG{IyIn?DGS; z#0SEKiiR7U`rE1>m2M!v`jSb8Gj>2e=rmAiAU!&d#hxHHIZZkc2_BpKwCp@i4Y4>v6AY^%;%))C~$QJLhdJvxHyw}kM( z$Z*4Si1XMP?LqDol1YYRb3k@DM0m}maKpV8wrWsdTaZ5=%OwAp*%ss-iG=N6ha0jO zZPis%-9f(bFp~@?SA*Ql##2UPcJ>Iv_Xf7=!ojUTo@!6@zi12_)(Yg?l?ksd7h&jF z$5#E?+70CL)icQ}o!mek(}D2c1`&qlwQSYKIh%vL&?A%FHcxYqv-l7$)@9FkAt7ftvy3;pZ~R zu%8m-i_Zxswumqsu5POqbZ886f%Hr=oWu^YXFe|(y7Yz-218|Ab>-OxARj46^uN$m z3u*xJk9vgPl#ehJDQ>F{=~NHo$xSlJ@FoQEvc7~5+D917*=<#?R9BEIcx95|yc&=z z&msKvNw}fbI~z50UM-O0f-=cf`qcti-9`A*iEu+Ibh)Fm)&RLuYgJkH| zGz&Krx{+%BHoFqYQ_B;Tp~I4!dsYIuSPQ}x%Y_?q8k5aiUzP{isZA#N*|qW@A0A0~ zf3|SLv{#SJHM*1q`Skcqa)G&JL3UqGc)|NHL+F`@=JCH(nO zn4xi#hvxkrB|v_yW|FU$F9EV|5@G#Hn4$iUB=eoEP9QITnn|9#(g|e8tb=7Vy2gYV z7A7W{Fa9YEa@Sl$|BFVktVRB>t^1Fw>HY&aUMfx!<~FN{YE9<%c5ZXKpHC{qn6IBR znME>%NLwqFAN`ONqUG0!r5Yu}G79KhTAV2;VmB6cSL&(r{ZJxGP&9vUzmkGUctizMu;mQv1l2AuAr z!qaOz1HKf2xyPI=QvYMMB#@4P9imlukyS^)^V2aqjmaWOE32jB%Pj!^vAq?un?QC1 zdnQ-_Ha>~jCw)IjiKv$P-4g&Ol&NsZQvvYi2bi}ED=OYQ^lfhkZy4 zKXL^;sLM=c=uX)GLR^i`O7d0{z^T?)m7!xeZi5NnGdj!-vv-oIo+Z-pH%5S6-CHr+ zXNKXIynv_qVV*tfAh}h4RJwQh)eyKM1*&jN(5oS`{4@cxTj&u|bEZ%#3w{Q8R&&GDgbnC3}JCkLmzVu*bZnp@bA#Nz$;3HGo~5RhTV^CCm4R zV}8{B1QEMSQj1g#`1t6zFdP{6LlVHtf-#4ioFI=5=Sto)t^y7UQ(?9Wjx1ZR#~gjL zgd8->l)e}MPoFok*rLMhq4cu+ivjbDoDw1(+A4WXJP){{NQK#IaI!r7Hs+|ACB!>B zO_Kdi1CFUzVfOrVS-#yaP#L6%?j@whzRgm^v=e}xI$>3Yj=ezkNOV~aAAotsg<^8n zd$Sbha}02niweU7831?q0`s=T#l+KkvsAUg0C>2s3d3)00cS75oa9_JCmGct(yh_yY|Gv%%vL&)1W8PI8s6hr4ZecPV^VB4F2kD$JG`k!8bYm=k=8$=u;ovU?E^`22)cj2A|4$;c=c@WgL1 zf0D9~#J$u@JG;RX<&9=XsWAK(0&x8gm<_hMq|ai#G-7ll;CtIt7#S zC2mHNEcyaIqQUz24V47Ti~#oj7_%+OAS11w8)6Pm0_?9>Vff)H;Omny{~VJ+!m1w| zCd?lPxVOIwvsHd&`MVg*_B%32H?w9#lj}&pml9Q&JziXvEweE{Fk}#0za~TAyF&p- z?^R)!X?nn!XEB?XWsoUTnhafD=mA?@QDJyc0ASr?%%5J%Ab!6z8E(~xfET`0Vfc9| z;BuQFW#}f~&mc9rX2Xz*et?}EvHml31FM|?2YFy7E$}0O>SjZ8$p?VzN2oA+7CHRW zDG>7%IfD#c^VqQVKo7thL;i*14eTNDvbEG|d24(OvC!1%b{@+ETos_gZ2bl}yW=tUs*NE|P8wIQ*|~tH zC97}*JlG!Y%yTi%>lRDg&i8aZRi6pC>wXo6uT=mJEyvv1J(eU^IJk}v-U_&=QiWlS zE5PQ@FgN(elH$pBuHkhX0cRQoD`WJ}Xu$FpfHUnd*T%<^Ne`@CLxR=<9_g&Y@S!|l z_}!1PjkK&-vc9*4tH<=!fNMspFk6#BmM;Wh4m=u5db_l7z2mSFaA;U7hIcB$4hpQ5 z0XQ%f^R=gb#ARWNZd!37;7(gqTV@M5$nxs~%t2<~lBx@hy4~jz0PiVMVK`d=Z@Pim zuOW)q+Slo7%$EWFpk9SxjVr+Y%;qaEFy(MGxs-NScgA-q;PQ@G{~0>A+Jh{Y^u@gA zSS-nZct>Y$@l>?TNsE_aI9+t%bHi_rr zq-~g=r7b0vvl?_yDj6P?tHSsKdzNCJ`FtrUact5Zvxx(2QO?B$jhLrTh$mH{&vlXT zfS7-Ge!= zXa~t3`&8#Rk4+@&LtH%cGUiv2*+iSvpu5>_Ip7mFR2b)T<$p1sx|U7Wr&jBt$FTW4 z&FmXI2iae3@Z$7{zj44^Ut2)FD7V+Yy3TNOUoLJx0`su>$H|R5GxU=zlK`)pz{TnF zF`wFYg0!rU)8BfB;oebP?6Lv#ADc_bS+^DX;l>Q#-`0xZ?cuF`J||&*GxjR+%T3mw zsAKz_TFS+$8_%Ccia3cBqgt@!Mn6525rw{GV=7#-VF8=d0=Jvfzs7=zJ`l(55*8O&w zixd9BY;I#plNZ0yuN=hij+ZKoXNtpnp~}$ZMVQi*_9kTFGj^toe;+GczSs*iVMh@z zUkBVU4_#qO`<*c*IbSjSd}J$TpGq@~XZL?*V%~Y91N~u*8A*G^E(KFVxVUyDX6vTT zH2azvDHy}B`9>~|*@wBbstf($ju{y*vkPP45f#QuZs)6*UGgl^;rF&$#aunvy zFE!Mm!h|^8T?Dx2WG)U0#r(}58v2dgh77p95b&XBE`GELv)6774fkk6G>aL|+Rnwx zk6{jr(a`JJ#-#phhVPZNV)p$Fb_8*s9qwTsTHK8;8DdOc1uz`b%*6*fgeim6`({tN zq=PXz>BDe{HCDKozrE#ABIfIL4)i;XG3n8nVOMu9uK5zPPn{zjG2WQ`8Xg7sLBLy> z-5J1#wlL01Vlh9M`9AHl@O@&pasl9!WEEyhB*}8;9L#67zfTRK3vmhv1#G#$6|=AF zur0GCl4LpO9OkVb_oIW$hmcpl1_S=3Qia(PN$_Ff6UI z{H!--0=rS`WK7zOXV}k$i`S0DY+jNE`D?$b3(e7RyYXc7)%0K zx3qII0#W#0hHVfBM+aUrm^=9~F0T+i~#Ox8QrCZ@ygst(O^|gq?7$H z7xvRqUn_x39m$4Hqvzu3pJR6JrKRWJ5y%+@7ft8lCsCM>_tetFP6BzX;K)QSUX_7) zosE`Wv=qoC1v~HMV#iahSfiym9pFq+@U_caeB>eKeU@5UX(5n-3SRP(i@&g1s0`ho z?X+|d;Ef74am1<`x;j1Paj;;}=Jo}MkF z1Ne!8+im3H-Fq?jXcp;Wz(xw*SIEWQS1>Dw1Vx7mhdK$y)|av{USXJc#?vT_2S}!A(&_6iL@N>6~cxt zX*3s)4!|6=N2HN}+bZ~zFfOiNg?Ym+kv@YLXr$nqXJ0z?HdN{L^vF zIU7Ve3U=c&Wy@pAx!9!+v)?+A<^vWKT-U%?U_P2G(kwVr?kRXv5ErM$VcxS+q)%aPBq+P_X(|`@-ibLS zNu&vI3sIopI|W>P>^$b>%SB3^1Ts;Xb$&Ov_^YRw*Dn*P5!}f*D5sU9SuAfNJ?e&e z$5N3tIt%22vgLDqxj23(WTPKkI%2o8|ZCpI^Am*Q8%UwSb$YcdiF6H7|RhZMGMEX&Gfix@lXd@R#n8YcA z6dVb-uR#7#@C*%B)kM=t%BR=xj1_qX4?fK{qjSBTvPD9>0Im>VU>LLxK_w9JqsRh#&g9gqz8^!T<07LWh{KAoJtsj(wIK)0{?gy{KvaEzBWFcqM5#t zxs544>)*}QWDP8g4W01W{xbgW!(sT>3Gmz4*g84lGtmD%0>R&-F}C@Af#dJ*(#A&S z`U19YzsKFdFm8ES9>EXNI zR3}Lw#X4a}ypC3{Nat}?wpd$RBH+(P^%O41Oc^dic)K%g!s9rm1VN>^X8KA7b)?uaL6=Qld6+u zq45F8F7>m;uIQCN4(H-t50t&Q4QrhmgB~>NDTHrgoG85sQyW{qyiW{DMSmZ>^p-^0 zl$2Y@6x^M+ppUl*Ec)Xm&rMtmjchvT*Bfy{4C}-$7XOz; zhs}Gtel-Dk(`-=ed)Fr8S3lW%0cwJ&M(+95D2EBCRdceF8{;|HN;o!`A^>1-; z?LIGxHZ8Vyouw}{ zA|0-Esfi>imXWEpr@uI@=_#dZY8Zj;DCRU&Mtp>GzPkdF9l1Ok!!Cug(l%|MW%(#r zj3$T7kIg@&`n+qk)FbK`u_VFnPyyAty*hENO2m5sZX#`E|HI!u7SKOP{A*$TS%EC9 ztpB8w;SX*9T$TUC;U94R8x9QrAoRcB;SUr4FM0UO>OZ^wZ-Mv==|3d>-vJRbrHVh= zk}2k?=De}FPAQ;AjsOHHv;O{uLncjxav>CnfiZZqJ?Vxkbv0BYHZ-^gYJ)d+&?Uh+ zpdXzA9LTcHWv7;R7_@64xXCwlsIQ`uu<$M+77~e_y<&EK(!w_}hBd(OJa$up<;Ub) zb}Zv9#(H1^k;nlyt)Gr_lS<+K)si^?3=0s;xMCQOiA_DXSRFL?Jp@hdle9PG;M(=T zPyXt`KUAxm0w&aJh93Y)5lMM%0xGalN($ab6m8rk5xES?Q#^SeI|yb8YMku~YB!pn zUoWM5qb?tTVI6I&P0txozxAg^fXO~#A~F&`W-YsV*d(e4R z{g^*31p{cd-kWO5hT^#kj>$Ml_mVmjjVq)Xn!S4PcDukz6Py^AZa+ zU;h^X{8>nU0l-54Zvg!3WBH!|{NpkH?*RNAMd|ZKl1jvKfbQ$da-_7R4zn5u2i~~ zvU^AJ`sNHg(0snL51&H4zuZ&otZXEjrD1(OnY?JGFjDyhPyG0F;Pm$PxTU~#4|UPa zvdC1-NqA^aMQ&aYgCM#Y@xyjXN$`~X@}3W4uFGuf=;k?s)fSgknM9<*v8lb>{I zTU+`=`iC?fkMxB^hEKS@p4iDlY$?4ZT)kzPG<^>ZaQ7qw%T&kZBc$!C^Xu8e;ltny z3(%yt&fqQ5T5DPmDjKUyuKrgaz=xl2=xO2?&+6&=6hy<8k@m@U=5U^8Ra@EI?kt^m zLKy}ry55#>kC)Pg>(bZ(Y@VD?`tJ9`(_=bWT@5zgFW&M4*d)U}I2Vw3CAKSju-@o% z&y|l!i}0%@+Or4msAoK1Qg4_#5}ShlNxcJoYcB7Zo{#Oe_9WHm91il zuvl^P8#)#b4*(ZCG3u%rR(YonXIuSE^&rx2AP@r%95vM~C0PtcK^|;zHS+apL9lv2 zi2xU!Pdw@%-p9xO>0xUr;3u+%ZGz>kYW4N!$MwyT zFL6k{T?Iq!EKc0H=hrB0)(zM7ipDiBjn>o2AR3g0x0rjJ zqr7=s{vv~~sj9Z-dx@X!=vNfsHfjll&2?Fn?n?tvFuLB{t()L(DgCNNQu6Gd zAXVQ!{1(9~?X@3eJoBskSzgc_W{m6cbY*3M=gMI&QKM31!?TWfFtC}f4ONr4u28V# zWPR(lz9S_8=Gt*CPc1tPO6R+K49!e+V7VE+O0A7OBG$36!s8Lg(|Q+o**@#YMk)Nw z*PZZ4UCD7qTu+?4b*kI29+YO3V0-k=G#u3Xw8F)+yKS9WkUfkZwfZ3R?WV&V=u`}< zN~QVPIi7MDDv~a=P0^ibE(mlNE^AuEfV^B7#b7W;qL|AN6?teVqFNf%`lHpomRX{o zDCis>YpF*lmHLoUL^#|c!}Ax-t6Y-i{Pp*P-%uv4T5JNmqvXCZJIyaRA`e2{yVh-y zss6-Y+EATEGCYidd_q~GS^#aq^c+&gq>D5%_>Yj=WfsJ@+vB`{P{nU{+osa)@40n?4aTRbyw zh*}a04i+hHt%Z54B%er(MVD2Z;VzszCyDBnt&`BGF1n<~FcOz7jUE+4bae7+1v`MS zux3(e;-(y3Vf_@aH zY$QWiyMu(n5F*-oIwKULgW_wgYiLiD@@oiFlhNqz@yV`-x`saSjTTP zMm9pkN=D3}ZpMUBIhLQMJ)=Ec0H zbRuVIcCzy;)2c&QR&*latJA{=T5`+9>7RDdnN1o4lcnQ3wq(FE!ShP zqnKwGnXDnU)I)#`VGfkk0;nHM2GysU6tG7V2@*hoEaN9~+&tTC<3w+)%ln!wXppXG zW=C+wxsNC6T%Bn@p03)NF}ECYyvsPpjC9zWV1xI!TB-Of%8Ef|Se4eiuzI2!| z7PcUviaMGKN9ehS0Gip)zqE-2g1}Z9#I~eS`_l`Q%vF&bzjoPCcu*#rEL`WWV|%(t z6}$HlqKc_$J+CU7YdP&e1i^fAD`k)s+oH&_2I4R$7d~8SZ06fm&TmTn2sBNQmHbhW zWhKf*P8kZZ+1f6;t5V#aJ_r^|oSQVr&#@Nes-zU-;1)QA16!+jNQ#B8u2oH268v1Qs#W1kIA!!K9>MFiX+1!TAUbi^Beyje`w_+Y}I+Uy19~aAV zQv9{|izw_Uo6EbMm*uI=NR4Bqh5F^ddhhoV@Ruj z+r0qwvJes6my8U=Zx_UN$Lwb)T!K*?jUNWYtjfSxI$NGk(Gq6)5ma3I(`j%tA(HXP z*vIzLSEyD1e)D>cobt+5aa1_wN)s-7V&m#k!mXPm4Hj!+RB9&_=kER!hdM!;@nx2K z`t)UasT;8bw~^<#&yL;dTcodp#A6;zKtk)!}j7~b0`!}aXh00Pw=jti)BofFW z_fJnywFtVEDhD>L^QN@B2~7&MU*)ujxae73dZ`VsPdZ(&u#%M zZuCrV5MYBIW^iEOLg)0clm@}$BNNc0WK56<4bW;D8YV4el(q8u9B_g}u|vq}^gRSG z8YAwckC^j?RYMhmr1S4a4#-!7)3^J$RRVQ0xyGWLOG+A0X5uj1AG*q<$|o@vbj`>V zkRA%{B1|ci$2+iH1+Xzw`%FM;BWx(S!Il!r#mfWVvf2`tnOAUEK~!g$i7IAs36>?6 zPAV{Yb^12u@Y;lzlA?@!N)zO`XGI|s+|g3a<60xc4B2)aNh*!Bh1kas5k|E_5VT01 zE$cG|RDK?+7m?xFT&)I_Ocj`H0Tj!)*l-m z6X`B?>?e`I8%%))pQ$ZP&GviB3iyP*Wh9IbSLtL>UDi==jQRK+fbW zHVuP;#v&O*i;(2uZ}t)=2rmrzfWo^U^G#bxvlCC+0KY%RPHzWJjqE-Shjp`Y~?~_%;|`u z%Uq`6VsVppJ5Wed#O7EA8!F9kUme9NM_psWNMu+qhH8zY-p~C_aEN&I2%X)4tStq) zl}{%5fW1P8SC?#?zd_ht2u*?+h}K_VDWy8qY9@Kmt|UgFJ)FIl{YLgHJ&IcL!kvy1 z*cE$Py8vXOYj1r|!48U=w$a54P0ebpg~vMO2;-@rDp{fdH6!LqqCqYo$ftN%13|Il zSS_OdduURlwX~o2iV6o@dO>lq4)uPdn#M_NvivrA@8OYy_D}`B#u_fIfOURb7$lm1 zAx9MUf`*o!vAjsuSXZcU#~~Y{9YS-N^rrm*h$yW^z9%!3x35FAO8jJ7ilYa!aH`6F z6#Dhib8@AJm?<_yv~rSi2>4f38wMD$1a9?rxpn7!PKeSUh!l21hV~Rl>=sl-u%is= zHL+wWH#aylC=snLqt;_XX9l&GY9Lw~&DVYoMWy+f5tC*)Oyq-6vLz(Bl~L@nPxfEb zzgSw-2tugEZ_&U)Ef~3`)aT*bQLnK0`1RlCnG?Z`j>P7yGpeVD$G$}54i_b$0b!j( z2S9atiZqIqo8n*`0+~j1ppOeLfzWCNHtvcMoW&5m>wr0fZWy9}mrFqkBYHu}sbWQS z$Qzq9R91K+{;CXi-gdGG9+@DbKRr$&B*#KoZ*_2#q+ElXp;gp^IFEOF^+PHc{`G%+& zrMQ;k{pO4f|aMf+&N3Kr-SE6m=5mZ6Ey`Oz7TgCRN1LuXw)QgXS zeu(V@^MtJnF}RLHn(|q1=vlMPv#T;*9j>oE`5CJEDH|t^)SGht72!?Iz5GOezqI#p zbsE1`R)avE-=LY{?CW_I@5AQGl0}PhB?{Zm)6GAB$u7QyajImVencO`fz!s3{*0Y( zvlEv&mQ|VQ)k2P~LIe&-C+G_51J@4UI}Xj2fYI&byf_&B#7-QzW;))8d+TlJ?x^@q z5;977P2kH5BVUQ#9b*+&7K`}U);=26(UH_9yBOFojfBu#F+Dg7O7Tjs%ms=^a(?!@ z%cBW*#wI(soJUt1h$VbnXmyF<6;*v68S-YuO|HX>pjnv!fVPQCg==g!ypeCIsX@MK ze5{lDV0MDZxaI7S7vqsw$>|?G>F5Et0c+#2JHnjZ(0A}N@<^@3^oyQ$bddga*%^lO zM(zlD??%4k3Ho=FrQklSlMa3(+QQ^titaDwq$}2jicxOb!Cj9(5pZmq_87NErimzV zV`V)1MT&0;M-dRN2X6)|vDfKyp?J@)iQc1BvT~!dMW0Ut3OHDCSBkS`g$1GE!m?Db z`Zky++l|=SPuAZG_IOQA4@^cgro07UU*D$=2USnflD5ajzKx5 zze;5G12EY{O?PRf>z>lLzb{OTp~!CU_PHoiVm9We?PPce==WpQ36RX_rMuI@&eTOJ zz>w7SceNta`)53pa3#~Q%^!VL;e4v^x|tgq=E_-gRz#P~EJxnh4!v9QB;z zu_N4^)os0J&j8A6FX)@X=f+H{EMTb!#&XiVbySylyV?i_JTK&UsM4M|P>58ke7m%4 z?!$ryKNn9=H`3g=r_o%(ye94t>Ea@3O<9Q(aYvpKaghuSg)U4;hmCmTt_Rz%2Q=pr zBf6WmuRstL69iI{gCs$_>|vid9a-X+>0gIkg@AjS_tMaPrz43BuNFaAgr#kXa9 zcODjvqzzNTx!a21zP{mZCry-Yk=K7gRWS1^FQJfXtcsCTjb&UgR*Tv)P0p|ZQ`K=s zj-2U+JR>+anZ?n*TwWaZGc%z>GTx5NEgW68TTF*}D6%DN6K%(kHVTr(NXUgG>U6=P zWY_ox3zEfZOH=3SNf_7s{>!M0sbh^PkbV35XbiKQL(gsNNkq`)`a)CuPqT03bvepi zaump(z2^nVguwQg3P{$QBnonbgEpspw%>Fdd7QsL4x>@-;wDA9eeOfN@dS`9HUWPAhF*_x_-B@1Ff=i+4ESIU}rAc<5b`B z8@QFQn$_F0s({+8r0`q>V-Vd_0FLFMSaW3fB3W_-KgH!##J`s5t<8021|rl@%nm z?-~pGvIQ4W7*Srwq`A1sC{n8kg$k;UR*qearQJxtyoT{8D8iMpAL|}CMQSdDgOqLp zA_4iDS&|V8qV^|RiP4;HmGd6=b|qB^Y-BYVT%YJtvNN31%TG{ z-06fYq&5S=}g&817~d`?DcLd z`Lff=EC^R68Jgar3~inye&yq#t4=h!-PNf&lX__5Iw00#VtFB)1bk+>x`@Y;gvudB zLgYZDIOvw9b)?ztW+m6;C#utoP~u z&GpCoN9J{}XY1N?_9v7M?vKX*Ea?6vivA_&GO;rLQ_*Govs>{`N%bF!F5^EoDgRB; zW&E=Z_C=Iu4mJ0EM+}N%Xz}gtO;qOoNuWJNVihbMRFqy+!byckCTsGzPe%9oIk*%_m+RB> zaaFmne{TC*2DSGb%e`)`>pqyN)!fXvJAPB#**H&Js&nP(*2ry0?!KeR;{7;udcAsh zX7ag9ah8?kzRb6kkJQa|IQNvi->BTzgtcbdf79~#>~LZHVU7n$fF&zIaGBzH3aDP@Mvi1?G>5c@t9FUhJbNupUXF|H(LAGBOBq;|tZo+b zdVL=XG=lwn3O!4|{*kqxT))DsQK>1VKeOb4%V|dAIZo8tKqBc`i+T>`lny6t%)?r} zPy&bBI?NriJ+O*+R;qV|+9R6(RyCN2=bK`5)8y^n3;_gqti*2Lf=K*PGokHWL1$Rh!Y#n{RK@TUyOm4VrYf@dk{}5{J*r=t^i!>h^^?-R)5H7qy`9jx zRjz*Jo;Mfw7yoVx_phsmFNlRD#LD#6IF5{C4 z!|)Dncjp9K&%w_b*%_G$H&5eHdBO9i8XUt7OLB(e>fK5MY+;wE7Nls1+M$SAY9U24 zFLUh;?XYN*@{9nkf|mkDDwyD?HPh&g%uf?>(TQE4i1 zMe;@NO%-^dHKwI0b>0G5Zgv&jvGuH&YUa@U7=S5}-OY8gpzc-lu)r zMF>y6p#6&el28N#b+B1Qi9I^ma>;pTyvhT(1(5Y@^YoVyG~Jy(O+CFs9S&hN5Sab6 z``A5eW_5o!7@n~G^*o{as3Vc1U6IyFW|+(5TsR%c z(f%2941y^x7SQe{m9KuCXE2ChKX}Le4aZR~9M@wSk!PAiToeQ(Ly6K*78bsK=XK(#WH}NyYGO~}!dk~CG=Skp#kbqAnM^S<1QDF#K%|i(hyjOYE z0ZHD!Pwfl5C07K`)r}-?P|5Fd^G>x2ps~Ja6h$=nw zYkXlktiAk(MDaymc0fy+%`)sJF!p6Z3tP5*Z_5FAPE7!!r6=xbKSc1Es&@X;1eC|lo>g{Kb<)9AEG!2}(?QTHlP1=` z{sJiish@KQ#7;%<2({EwVCA8<_#q4COJ!ME=nMo5RvgDKi*E|~OSH9TOC$BLGmF4U zAO{InD0%?+#lye(lt8OPVn+1SP=&ICDkdy4k@#%#FGfJ$j4qAPn?W2k`Ut7F zx@3qgSmn=lWS@%kr!DiYiOm&*!b(SyAJRp^Me^wQ1F7S4>j*Fb$i$f zdLf*0f|g8ExRVbKc_^O)NjSxfgk!#Q%|(}{DOLf}9>J=J zU+B=NA(@P8W0=WE;i`h851sh&j=}SO8A*e98mbkfAS!GJ2#)Rr?=Wp|8J;~@p6Ob6 z-i}h{t$z-{n9s4aKCEa00-e!{OEZI;A3G`T5rqcz85oy%P-Vfn!D==ta4{Yp#X*&v z*@tB@@+Eb`Uz9N*vB^}4WHoc1k^-f>u|w$!uc*?(Yt$h}^h*Rwu5_8HB3T&v-Te0# zFm%)yGb2(OOqfhQ8nO%r3kH^hfQF~sq#{od(w|91de|@x$_XVPfw=60zX~MgqitK4 z{YRaO_SEz=fVcTX(GzZaFBPO;S1QEE7Hihu&c=QfQ1&~TffaHJ?nSx{*_%%dEDj29 zglT$sLpH&)g><2TgPn|)e#_SY;?EBWt5ex0Ku=2Ey{+*_k**5=sn7GSQvE7&AXF?+ zrx;)ebbGrBApy+&_1rV0r%*>1YwTurw8a#DH5WU6ehX12vjXEFW8~*5m@)&=0bWt5 zlQ}c}&w82VIpqzj(GRp6f^4-!*apa}js9LkGKZ8eM{`0tX7)+V@(Nufcm|8G?59Qn zn=*J}v@n!x+{5+_g`^aI`rJvfYuHDu=QYSBPZjPnm^7&4hlf^3>5IfB-=lfL^(^75 z2eN;0t?oFY4^+3CQu&+n{OY58?wmyviY09LVC;6e4(LXgH&Nm!%@ixvYlv)nqj$Tx zm3CB^WqB3o^a%lzHi;|sKFCWsYUq)B`10_TJzK5#a7e%V_^Ai$7#400h=8uY=EG12OKIIVgv1LEE1$$J|VcUYW0=m})-|;vzL)XG< z&1-YdH%x%=Ozkuy{sj`Y`WI&0nwf~lIEcaRp>`91B(Flfe71n&SH2SGOoG<^7~`Q+ z-VwFVY{|3~3UW^R@vK7SE^hVP8ADmkY24sJ#miZh_)a}kH9N@SVa9dy{S`^YbJ(pY zaPdb1zBx~BQVHcTJCzIC;CY-yNCxAEXy$?%5G4s59b^QR^bq@j916_)Ez>Z5Qajg< zkOX+1zO>wUxMISfYXRw%w72Ud4UIcPqIpM&rJ>A<7nXzA%^V8`0nkXo!f+Jz`@>b< zQqO^sHViv6BZ0IC09P^>QAtc>g??2*$6*{-Dv0>YI>)+0_^ZSuJ)pX5*t&eooMlO2 zzAwbA?Oj6LL5kFFiA9#Wdv(ns!=fXN7Jp6OXfk05N?6_>0Lwt0`-Z4_eYlz}B5j>B z;n?baOgyquPBeHJbRgw3R?aM4F0d~awAvt3Oi|Qru9#Cr^MmlZ_~_~medFQ_F`HS_ zS^0sVJ=YTfg8y?nod0HwcUhwo&w2ZfB{vv5_ugVJn3y6!02O@RPU3aub|}g621y&b z8vHWMtE-4VY(f$crB%cPe|l%8GR_gEQqJJb^D&0~Nlv2-)v?F0?nR1b<~WgscxT@X)(o@q zaEPdxi05+vIjZS-g0R+OM84)G{4##?!K&ZDTL4E9TS9hatW4oFjY1Fh|g+}dsGt>S{mw4;p9sQ zQ>i+`Be3-@uMO97Huxrfy|rwfPZ)?Fiz$V4$i!}lVpWdt;K>}9Uu4V@QTAitG$7!~ zwglB*2tnmdP*K+_tlkS;sUj3OWoen#>!CB3dXu{2V8VPj!$c@!+y?U*UXx@78FOz< zdlJum0e$oOli4h(@YtdE#f779Rz!2@i|@G$bo&?yvyZg}hQ1~)WS!I2*JU12j)yPP z15PCDZhlz&-?zpm&0vzum|mGpsBUg3R7qmCzX{}#XE>W^DRPe~k3p>ZT!S(JM` zLYaQ=kTv)!^xk1oYnLZ=TQ?(4TVJKY$2Bu1X>a^Z=Rm;%ipIfVF`uOXaYa24QK!V} z)ez{AFB|VDQL62`g6IK(kv3K$ih=UbYJ#Ifah<_RgAG_}SCUAd6>gUrOY7ri%>6@5 z;EnFexZ&7ZTY0{s`e2Pd^@n>(Y=Lssi5NAcMFEgBL6AYu4rG=lM0O!+n+Ce?{#n;V2hJ zC1vqRN6iC^c6SD3b+OtiusDO%I32^1S6&CZQCL9)s_IALjOq8E9gAP5I1zwq-@I0t{QT071d_8-#pIPYveTjUjmf}@~ ze%rx;vcrC)_c>)v8>={xATKos-%G|sC#d8UkglL7qC&FwdLVn|c_O6$&T^#n-9#`2 zTv3h;7xJ_5V!MtA5qc-qRMH0zdB43!I%pe7q0&i!DtNab-*I}-cR}0eFImQ8;=j7U zIj4ME47t0Lwjc0^ff|Z?S_oiK2nA-EDoSxBeK-#n;3b-Fo5%1Kp18i0ZQ3-I z%glD#V27e%HnTsl&84@MryaAdRC*Ke2D`k9`8zWi6_3kFGM~7bbQky+ zfdQX>Ln$BD2ZF>fr8gUp2rgsFN5Y;)S`nn@?3NN4kw56t370#em3vEL>>vjFqKp$^ zghG$(2i+=tU#0_rz){nCIrqAVv~o&=(jU`1L3H1#Wld@9*p`)mXreSGES%nQDv;oT zKuQug1M}E?q8Q>4Bs{k0CgQ6r>cDOqo_Ha|@IY>%F+?u**ub7Ru9xnB^}L~|jZ)~0 zK+D}~P_{O5ii;@-l`;&qgHud{S`?mmF4&-kdzx4E#c0tXxe)%WKj5b8YS{?4D`BBs zHb1ZO2?dWtps{7`n(tUBe@N}7^lC$8C6vraMmrs%YNnf!_py>04{Fro!Fx+iclS$o z-dfo)Z4zct*_1_NrAKaaEM(3>W8_RIk1(CVl-^xwD_@2Bsy)fpRA-m=zK=ZXsA9Marj}%>heq_IUJ;y3kNz z9nM`9+DrivV2%Eo+l%{42FcG;H;l(FosfHK>Alg>6QMw^ZlvM}cnR`j5qZ_osrCr} zYfGW8{Q1<)XE@3HlXnPk_;oirIB*}gdnXq7OTTE{8#_2@7_4_JTx8VpYmYNjor`O0 zSJaNqN%!So7-{0aVrU!wda?4awYjvT%3ID2qYcx;IGow#IEFy9W+|( zo#L9$yb~x?&ut}PN6^+39Uw2t*bW`L_j+;9k%rwTZ$mhAaHGxO)>6=?rX3)EFq&R% zpJyNPSfyt9{MtNGFs`2R4uc-Q;qVO2aAY$jcL}qE>ZUzk(Tl_*CXmtewnV_;k6n%N-BuEH)g{QL>Z?Ur4f+Z_Amffj!Zl9t}qdXI!S}M~c zy0Sxkab!8&ncJJoX76A5a`x=N^ZhZzXBDfZeg6FD+WqY%5b5ah6XO2#>{8q-?sAFf zEt9HNmS{Vri!<6o^=>-s*4#hU|Kqwnw!%D7{282?b#l9%HrjuFqe_r0|@S4KA*w|7)jr{Stl@!Ye4WR10 zzmvt3<=Xhfv3#kc*ut|_r3Ek7+IOpG1GhJ|DZ0sf5`i5S>+=QqiBkZZr74GFX<`ruAYXU4)zyvb9d^1?-RZ64{NDEy1gFuGOv9++P!Z+p2kj*cvpX|PRz~oNXT+)zZ^k& z#pPZzxuljFo_M0O*B2+e25L`9e_m;CjmsDy$gXU+`@uOra*td&IYV?lW>lA$!2NW3 z*#dKpu%6l6TNd{ zX>0`75syf-iOY<0)8jcK`$xneH8JemWyMZU8z|mE-CNYwX&tWXd@pgq>J|RR%{jq~ z3wFxAO<~kx&5Rom-cg-r)Yc)rWJ_xjFfJ8GPyOJyW^A3#&vgX9$JZ#d8-3W$(ba6& zN|b_#MMBFL*eB0n{Yz_6H5qR_m|gjr;9C%{xWTL6QypY{C5uKdtcyR-ba_nmS+L8?(5B;Mc^=0nrX2nkhdPrWTyOo^Yan}u zU84fzqR06O)F-~EZl-2TPyGX?k80^|3~7O+{E6nLF<&ob`!-{@?7cXDAi(NnS@VxM zXG0s0^WWySB_JpC^`Q&t+End6d^d-ej+5lMYTM2Oc)x3}9Hn&HP;VX521L>}tJOuw zb&qPlw4jbJ5@AU1PC~Yo5x4E;a6aeq>fuoPbOI_DX>(7_oIh5c^MmI-@9N$jmLhpc za8syT#g1I9g8NGs{UK(CEM2lR&4n9kW zzS`7F-J2lKfrxr(qUG$NAJPkcWMxtp2lxC=MB!w_eaTB^(kYPe+t*UEyzO(e&|XFg z$8v1ndDlL_Wj!CYCpY&+urf6yX)=mI`htT%+I3aPtU0r!oZL4S4$TTs(6Xxr0)g55 ziGLo7LCcC3D%!WUAhB+4Uf5}MleaCY>1HbVZGER_6x=W$hWA#!AG>DQX@`9t6|ZGWw8N#95IB1^N{e%E|RsdC?a z$P2)7vJ2IQ&f26udko{CM1+on$iw(W>D{5y)rZTOqM zc<+ILa@aN|X=pfaIy>_2v+h9yUv(cC<}ML8b6aUNqOja~N$86xRu(1=dR-R2dSh)A zk+HYP8Vv(bWrXlLp;=Z=`qxFM(8%t4IRo1g%`Ptvgwj|>xk*c3z@d)RMuwm^O~7D5 zDD8q)z~895o$5hw= zWuPTy61a;K{Gfqe($V(c>Wof*@&P@2P|U(>zvC)$_-zumL%O{P{t{9Q>aLQTSQKY% z94?O>$StYl>OmU)BUxIA=$vAM;ztnMUBHu8qwJq}*N!2#st1}9aK7^KjY6_Wl95$;6N$aBx zPzo)R6Ta+wXnave)hq%hB}(q&Gbv(w(n$N*+~G~hL;mP-_>$nLK)<}OJ|M%u@>!h* zQww1y8Aha30aO+@QW-h;ytSs&zt5W`Vi3QztVOQal06LtF&t;yzM4=CTg6N>kTk-?gTxjEB7fQaJbo%N5;tpfx_(4rf`ZNFFsCj%B05+%8r#UQ;mwsm4<* z{n-D^t*8C#J|CQ&X}PDQK4UvdZ4x1~9%p%bs{lQ}Pg@=`;Z8ccEY|HNBlkr(2Jr) zECcIoiW$Qa`R?hI$&L;h?yTre3R`+kzKKvm81~o@E0zsLmd1$CkJ%8=0q=d=CmEP2 zjl}`fI*NfkgpMrTVQUqJsil1n?=(vhdYTCy|GGn*B&hHduJ7hT!0zdwhF7dLWQ{Cs zdS3>MREi)!&o;>qKWvGdfp}JyQ(2XFGUYvZ4G4!xs2nm8M0ATL^t6*BKU(9zLFJW; z5lq!nplqTKCUJC^IIxB&IF_P@+hgRC*)p^>NFqF5W_N|)IiPI_-@)f-TxrTWP#h9= zFd5KYN{8MaohFxX2aK6$5kQb?wL6i?Jy*DAaLA-6uV9eJuum^5Dr^Fa>Bb~2+k6+| zfIsY(lpQwDA+7-j(sLq)Y^rS(Fq`GDOP$Vtu>(jD8pC{757025cw~=wP9kM{0c~+k zo1siVq+jN6R7XRsmu?M?IpT+(ADT;wCr6=$ot`=ZkQ5c`(laY#6g z-!*$;Q4(0uYz^A|8)}9`dR#{ZbWBdWs8XCq02j7cn&(~^n7(W_WO%5Tjq{PSvNP`I zh$sy3cp)X1RaEA9;(XqBKg95h1TE%)8OL#@ZD!k*1EuWnDado~q?!tj>BGL- zX}xvX5-2db4mJve-8$^0lqu;h5nIKw5jVvKCHhz9j+13J8h8*#J*Z!i?qt%1z-@%S zR`cS3Pxw+J9u(`z1wtl(&aQH~)Ml(}#%mZ4gitW_wu0F1JF@auoY+nsA+yv3l4fPJ zrV{v~Zw=oqX>6bx-B3_0u51*oORShx3n(ofYNaMG`Q1zxi`F!Oqws@&yxLm?x`QNtn!jQ_vA=2%wN`c0}nDVw}msgiD1c1b$3! zF!IRAkbZ2TY#yVMFfNt9IYca0((2a6hshsqQ3_cnC2ABiMN^(bq7`R|4+974YM`1Z z&8}cJt!=ay5UI5Z5D2_pa%jUIRaf+}LtYLOHaOQg+A>#CN}~Eo+J3g{NLjyQmGMPr zD$q05BxjZo;;Y~{n=}8xc{fsyoJC{N`pE5$cBbL9quK-*8Q+&6z45gPxSHH4{y4;8x|aBsrpW$A07wCv zMgIP-OA%ghLZlJBFp;f=k{p(gzs#D&Sp_Jzbj~dQ(s_mC@Y)bDqmY9*y+PvH5elj@ zJrd2U8@C1YT*3H+T|PC7bgsBgn+xHG7Ku3Xp!ztLITUTT%=k=k-N_@GuREk=R4?yW?$QByPZnI=ae>Gh_*xs-yr~wY8n# z5lm8n->1B%h>;}xTYIsWJmnHxjO0`}878!%;I+IC;n&inlJ)}3x>Leoen>R3pJF$0 z2+7~gK9|co_7w3C1(IF4*T*#AvdiKI41;2ZENjMq6BjNe^l^z1gfiNc@OQ*YBJ?)% zm|L-VV=dZOjEM73!#19Y58^8Y6tI_t798L0 zBNfzXruy*p=RMNM0?JIC-o_CR!Y5YqAuxyQ+N=noo7}{}PHBp0gU03FNnrXbcob<0 z&Zt)odN4Cg8q>fyf!rp6Oq-FBB0)XX*y+vhi+)$f+CF$=)&ic>LQPuEh7ig3t-%pbP5otKTJl5MFIn*Rt+G-=vY$ zVAV4%Le~VchV!nCiN$62r(4s7BIAFLhGKG>hOEi%>D_yFJnrvWRYXR%RnstMw@ospN!^bjCp_^eoueIZBj_0k>Al zsu+EZiqyKXcCl3m1W->`TP+q&R@NyXXk9iatc-C}&IJz9$0q1JoyI@3SycB>%RfSL zZ)BOw=@7NBP^YMXd+@W_U-^G;ywCtrfl#Clqc4(6nAl}dmolzWBn`{lZRprzkrnR_ z!+0GBnvtGDdCIab8$n$+yC4%Mg^X2Y%%wIurSYzY^36Dgf~@wctZ2QA)9$O;PMNP4Px(Kj+e9eVkZ0>_&DXMEJH;g}?vo|1+iccOB zT(@M#h!Bz-z`mV5xCKN@6__;{%;QzwY9GZpGFz78+_S?}6wd5-8Sr9h-FTPs~p=3&J!bzWNLam_9|vf(JbX& zaa_6#jX?n;$1=4C@{|94pmaT+kMGvJs%qu?R_u2%OF!zaXD2y3E9V#V)7?SmXklh%Y^c)H z8u!Z(Ynt=DK{aE{CC0Ebo2& zkzyC|AKFJp4CwRqnI;N19TgFroM1B5pVI@k8W#X7+VwTBL+R?tYB449bwb<>wpnVcSZSTD~ zPxUTOI2KJ7+r1Hc9_)7p%SG~SByg} z+(Pm}O3+a@;kXC$Ip?gfxp>(-j(xKEnMf(u!cG-B} zsaA9Q%p6skb;B>6pX7d^-@B5^Jd7O_j?A5R&La~Z6zY`W?kMrgcd%sh^QSs%38;d( zfV8wkYgRI^NZd~DQ? zVz;|^*w{b5x2I)|Rs7*`UhZ?a|FLks&2HO!7=0furV#p_v^{^fc0@OeShEHJ+13MP zH^aGix9!KHaA4&%Y?(y;{qBB7=JibShAlMUZB(`QZixdS(N}dkE)#zGvi0VyI{l&l z=|KDX+41Lu=kX|AF0be7%(d_P%v36y%r6k%pRr{Bg>d!H6ET=sSULWgw8r#b981CU zACIMA{8Ov^pOe=9)ZqVrsKfuu>i;BRjp_gKV2b}!hyQ=-@c##O_=KP!&q-|O(1 z{#82thjPpG9}l8n`mYb7_}@^6|Ci36g_~@ zZO{8vZ?EtD z7GBS*!Aq&FOl^#@R!HkHd#E$M*y7b#Lc!Zx~~QOG{fs&%y+3k$%npMcX+Ai55gzw(!cfZQHhOyXuu~ z+qP}nwr$(C=XJ+Se@yqs{LFVop15%%Bkzr~_gNdMNM7}tq8ZZv_b+1lPHw8BvqAuM zd1&)x!eoX~6bzq)`Frhcim#TBwyrlVb_8|rC^J0?^hc_ax)fY}s(hxQ4--&x70on} z%RF<=B3o%~YOd=uVAyu~X%~gNb|N|Rbt9iQV4p9?ca(4FaU%dvadmZy>LVdVZ8?id z?pda5DV;7|tq)o%ddjMAy@>nwZ7Cm3ZV-!C$CtbN_va#CFR!O2EnRf)eI75@1 zbpBzv%X5{I{B~V{L#Ytqn3&pChK!Ea&SX6p1Cf|?fNPhS%%h5y?Zb()1N-RMa|A+R zL!K37`pfdfO4F6Q<0Y?&z1|&NKl@25wE52^5F)B~q@Js}U*@)mhLkKVh2z;NuPem0 zh@5w~aOUrgEbnPjJ_$Reao~{`)_wAIKDss`rzMp*Lc4_)2)0xzgOF@d_Ujc565zot9UrO z5$(e}gE&2*d!$}sJXk%6C7y4Fp(=s>q$+?c10L27M>TsOK(jrrgWyIqCSvCBTLBA2 zqY4=;JpPER0G6oG4Z&ME5%i93`3bXSw8JV%ne@t33GfF1uI6Y5lfPE+`J)?BpLJ*d z*aG<5e}!S*?F*z@oJD-wnUP!57pXS+Q1mG2t-v?RSbyw#jy`KpPc{XGqgt;qJ5hp6 z5>sKzkfBhEYsdvPpI=0jCa2ICAS%W^(w{}D=52NQ-w$xz>ZK72USHg#^ZzQ z=15an!V37=+$YlH7&#4=d`0%OAb!1%jjT%@lk`XIfg)q-!j#QQRHkLjcmS z2=cpXx(PV}izK9Ls6Y$oDX3vf6qRM57wJgEZcz952ymdAJ4Q2xf|6zz0@TjHn{U7 zcBa@gs^~CXc0QiC2lGA2>+lRnM39Dpy!zo~a;FO4R zRH&`RX2M>9-$U+%#eoB8%~&*A-$^|c|J4iHA&!w1(^0LsYa(z=qsfHo|57Ihmvdm$ zZXL0rg)|ZwK=aw3;-aSCaPyP6(AgINfF#j!((02W-wKQeyo}qMjo)UxGTJ9>p4@;$ z6_k$Zn}e?(J_6}xNi{1A=fwnsgw&Rf0Z@%(^b^>@=qnhfD&6sDu}O}(bU+uqIZ;P9 zEjY};{R80tT7GS^k4(~;*2#AL^cckws>w7R^es4K)5^|{F7UA5_lv;Q;Xga4);Wn_ zCbAz*jrY$IF3Q3a)+ny-zehy8kX$g1RNyu2g>k!wST&~&%SQ*uv0V{46Ljjp5A}Mv z9F=dJCc((@Ky8&9DwHg40KI-BE)oq0?NEgUs@$dtkrNq!g)w^+jca{<9zhY|u@%G> zfnlx44jbUe9(lVJB2WyP{Rqg2bc9|Ws<8q_Dk3j%WTUH%q71rzW5m;(wB`c0;BP%I`y^uPn2-a$C$Wxn-qOeA_N0uj?&QP5(YKuZIm52LcIggC+z zRD)}-V~QxKO`CRB6A?hImS#ubF~PdF3BxiT%1U7Jbz8OP9yspDOw7&hHeZKWp=He1 zZ3YaVkNRfiY$95Cm9jedkKv-7>OqiO;EmS-rmjD+J-;k|b_Is~MvclHnTFY>h zGCjoN&cn1hJR0dt6u^N8n0@FoeiU3bfvT-_s6WmC+b1&Y{H9WVt$I6a*!}p%wzC5` ztPU+_$oGq^6I-{yJKzux_HLa0`@xfZcAJ-Ywp&2@y>z>Jo6tBCrPRm5jIgcTb60XY z;40tMWv?|tNCn=HIbXmaxUZ8-S=?#F@3x$6&-ZNo#V&Yd{2OFuczZfw8Q~Ve)XTIq zm_L$wfFRI3l~&2Fwmve3zw^??=q-ZdVWYhIVp=PrH}?E9@(OTtGtL494Q z!0`>zHvr_NMn2}>V)GQDZ6~U~YG+*lyBNXFEFrPDYrJ$JVAagCu6da@Bmemcn?YV# zM(6d={j5TVZCYU7jkoDQ8KiR3?YoN_=)fElqo_I^zROEKd53jcoJQAOafcX8|Br=H ziYhY@`@G~5h*+n^YJA=NN1!k>#oh_nqPffK{FqK846DjkNDOAU~2iarQ5UpR#sP?)2yO5Be)k ze5z_Wc?}lJQ~!)`2S%ed-;j`0QI=no;#IN!cGFa|ElN8GynomTxG&b>bC|bX35uqr zjT!?#vYO}oA8l>)>TdUpX+Qu?cVA!vGRJxpW<_6QGIILL3)QJ;Mw1G+$dm>LLD>;B z5M3%oC9s=ZhM@axzR&3&d+ElEzcY%z!RR$aQ6>6j+Yb5PY?{?h)W$$e9GOePRh*{k z)e;}wHq#5&>U%PZ(zQKpQe^Y&hQmB!No(UnY#-VzCW^qxZQoLvWC9MzEi9kPBZSe0 zAeeQ8sxvaf5%QP9sr@w!S{G%adQC2y@7%!E)38nWnDU6qjx>P^|`S8mkHaqaJyDWqzcljljtvTce2A_gNjJp`+ z$d4QLar=^CM_?ms!>NUK3&co(5Y3B6B>2OS7-W?-)cXxDWNfnw>OcrCb zm?ji6P(c%@F#V|y#B1fltslTVii(QHAgFmFtr^8<4h+aL6YXqEz-nLw%?&67Rtq^+ zwV5MOIRKpWPu z=faBy6(+NXs6`x(U9s412mi)ax^yUsTE=M&mDxAfURAY)@N&)mo@bV>%@lD~w^)b8 zV=2M*7m_QpbG|W*iE1%lMBC=dGos}_AnP<+HhPgbN$g>)%LRnQnwrs&N|Bd>X3P@E zQ1&rlK#ZP>)NIBfH(;ECIwlD4$XL4YvCDosEVBvtDN^o&+iL&ZyIgy~TsL^hRRA}% zD-K2a1_tDDVa}Y5hp1#Vql*V#jhbN7XmeT*a|*;CJ016M^dO%{HOg>=J`ZCiyL91f zC~8eS@&YZ>tr~DdvIfIE=rguRmW~T&{EMAKZn6x|Ej}nD#OX*u0dxF*D>2-^p51*r zZOXv_q5sl?BJ^fDz7Mgnpc$@6+PZ<9Mp)^{m|(W9*h1eWAPUm2khqgN$533C4S&-s z$r#y$td>Q*X`ZPImEXi6h-ZpIVMjy7NiEiZFvd~!NS9IH5fx)_|D05S2$*ob#_TQw zh??mE9|@t3;D$7nh!{Bmrz;Hz>7F^~YD?CgD@qEyD)V?f$PWXE3L6&f`!zfAB)Vdn zzo`(_o)!}~OUdlIuM@BNJtDDCwv0S;Dh6mYCf_O!K)R5Zh)-_N zRwHv5Buu|&`HTCWQqX=y)s05ZJ(74JB2H#XcRY=#RkQ%~YX1Za$(#NpO7UnTuvKkg zhu(4w0oCH@7-PbEaov1;dF(n`OEnFM5=WDC+;Axq)qp~b{YlwV*@k!_`gYbaJ?iQ84Fv9b{}&m9M&8VYZZ{*amfes|unFasVO2?X zJlGGRE{oCSoJpuzDuD(OHs=UCAC9gQk1(wbZjYASat;+=0 zKl@wAP$VO(>=i-w#%VLrRfJ*YC>#VEipgT2@xO9)z5$c@kkU-NShv0kE|)rf=U!KU ztd5;fcCn~DwoWjf9@-e}K3{b$mN!6kW%1p$fev^>hdO=&Uhwb81@fXM%#a3WT9fy* z0GE7L0o)a{2P29-(5`@KH!UrLeX#pJX!`Kcu7IHRi625_p?h=9;R6h}GEUOA@;(6e zaHFT4P<_Y~T=ZiTpZ{t$?SiBUukL{8vzjrGdAM+XR^9@U3yQ{lA6fmLv;x%m3e||` zu(KZGiI}wlyx{SHefvT?axI~c+Vi~n)_|^)eR$=1wQXpaEx~cFdg981K76MwjE(I= z&XNSn0XqK(KQn5^KB&(Itq3&2C1SO`X3lry-AOdf;1=qNUMdV+xX)pNKN~p^P5Mx2 zrXuqOue>)dPX6VYSm8s`1asz>6}=1?Ae-m()c3%s9(8{|^|!}=E3X+s)@z!fW7e~w}kyS8B>>|`bw<) z_&7%u*D+ObsxWSwBw1vdNfjk zb5zTk0D7=wdulE{jAm7$jThB5pm`_&b9>1B@V#I~ z#XUqHi~>N%Yl+)v34r<9uE><{3{QP^CfS~IafYrVIxyC(&S;}tr6l4yO!PY`Y9Yh$ zZiEAXREt&-#F$dXKD?akb8~E;QqEM1Q zVGB|+fGZ?UteY1xXPy%!kVWk9ipbo$v>6uHZo%8mHqj>MHr!q>@g~qv2s$Fa?O7q} z=g)~WgX*|M(P1zN65Xx@Ry3ex-$)YkXVGSigt>O21#ZI2oK}{~Drn%jmoAe9?^&LN zW2h-QN5EbYCMaa-!Q-UD^L@GAi zxJuI=GTv}>t-SGq*Bw%#Deth!Rc)ea5@YZz)MpjOerD9;x^#@1+hP+EN7i2-X1}Ba zhH|7FW2B&*HPTEB@xb|kH_BLUt)=l5rG01UA>#BY=KBf&B+G1Pwl!(0i`#P8ZJ0Pp ztEuiR=lK2kB`>Wn_@t+kA7fhAYSawkvR=uN5i1z=L44F*_^@wy-nGn*wmq@ppglUo z&R#%K@ja7Be$lm|Fysh$q*Tn+nb&}j#BN-gA_uo_pqJHe?VKs-T>&Q5&Fex#!+j!! zqyeb$8yhvKFXY@k0#MVP0{#wVBr1NYF!U5=P3RxVFglrL#y|=@vl7#KBn?bm<+nYV z%6abjbl{w0!D5qIO{MW2%&;YXNeDyKj0<36(TlNiD{L*M0;zhnXnHqf3wXBr)HzvF z{Ido9la(!?la0fw54Yg4-+rjCjWg=#t^&g%uE#QVnI?NUIZ2yi!kFwKV6X}-1cu!4 zoL0Awt(QECm|UK!Q_LU#;*eK|toz%Bc=t6EFf)E94W1$e)$V0+j<>=`oo!lW(e#^| zcISRisFgeP@$A2+m^Xij7VXHK2KMH{h+_VOJex80ld%b@bV{c2p7tenIJyD2&|GTQe^j~aMCRUdJQZ@buxGK~C4OeCQ z{{~n6&&vNVOW#x6als%j4MewdfH8jC?5Qa7&G_uL zyiW!;b}`Omh*~~}QDn7i&I&Ivx|LVsC)GFJes));SpbmoXnVdX33@ zMLc@yFAX_X#fh?mCNPXwk^N@>rX+fGTdXMiJACvtEeQ#TCg%Cl$;$-(gIom{fYOz) zO7lFN?xw|r6&Qz9N9;=YE|Do0L^R`31a@OUU8+;j0J9Q}IZc!@Z{o85>l?G%u>6%7 zVb2SElCl>x%^y918OU*<7*w8(;lB5v?H zQnaW}%c!D61oP@7Ot`Kc(bgTxl+)_^pk32w;(hWd5*!p(V(`K;u_?x zM&SU?K+tZOmj`-)#?v@3j)y6hlHI>}5W{ng_p}ZA!UIZDR>MNMZM5H2$?CpI{5#e2 zcq|KnM}h*%+99JJ3LaisMC?+P?0IZ8L=ywk}wW*nH*6Wj_&@EiylO-Dg-@tQS6C>e60 z3GmeLb$6Nu&eJhe+H3&MEO4m36_A9KxW+@;qH!#F1w>_z;H!mTw__cE3HYI4%n8iW z&nS7)vmOW200Top@HqY*0bHP18jAwxAt1L(WPC2+zbCIIkt67!D{A>{8_vcssdMxQ z))7MYR{8>m7;bw*iU=tcXX-IK*pT^9Ros#HS8N1b%*c`}=}4QEUJ~0TRW8H<&4y@F z`oitKqJ+f?UM%X|70_VUU_>!|l%eV(F_gGOQLet> z@`PBUJ;UhWsRe?hdrU`@i_lNpRm6Cf4Ka`87-3uy4l>Acgq&qOD0h-m2)DCIam5*B zNmWDJ~hK9(BKrmlrUW`#Ii7elk1IR zON7V8K{8aof$0h-3M$&jX^fKCYxD!~c?zv!i3flmEuZrd%S#?8NSlxW7p!8Ff^K9O zRv#r?h#OfDd(@~11>Eam(er09u1@V0Y!*M77w1>_wq&{55s@gHT&#E z!?g#xELD8vGO+P>)k-l&L7N0cqAQ;P{E@Dz0amZ}esOV^;>=|d1oEL$;8JmsaF^x> zVR`F;uQ8tTNK*;q0gzToEE<%V(TkUGW>-#SQn-ck1VSU^B62ZJ(edS$O7FAG)2qE> zj0j$|A^*urIFM7&vULad%vUd`GAxxWr%EywrV@g0$`T?0smLUb!~w_wucw+zA;j+% zSYboNG7FY8;=QG$Si7g&crjqnzU3${f4_6_dO3cc-)_<-DPV)x3(KrftSa<4el6MP zV7Qtc0H=I@2}F11CYFeGT`Tcm{9aGe=|1yXDr|0}52iAI*QoMKT*y1o9LB$EbgWMg zT((k8D;GxPiXdMgi4**s*FDJ?BQHJrCbWtqa9jwT&3E-J8H-XC*b%!Fpm6-28qCy{ z$ME7w5zKq8MbFxB7z?_dSHiBG<*ni`kv~ug@7k{%00nhrP6ALHzjYC%Eu;6ebesMC zG7V>-0LHk=8EHQ4xzk9?;aC!_dE`n&_lX&R?xUMECEdoElZnaY&@E^pG3((I2jo;} zC`wzds)9F+S}HDv%-PVc|CnlXS72^5yfP8CIYkuV0$s&DHWbo{4P=s9P<}Q~^#iYU zPFInRG+hsSHqS|$oo@JK@i2(gaPGhmZq*h?Sw0Aw&solR^VKdx`bVe(_RqgOf)LPS z`x&hFbd5ZkQj#sNl2NN-ZRg^VVzbFut?8nKivc>7@drMOUU{Ys;O^tt!LR3r=qz4Y zkbxT(hrSe04#cOv6yQFG9eZHHBW8QT57+HN2HxSh5Q5>PzGx}H89wee>$K@cAa$-3 zLEn07_Ym}n89Y?j2cU6VT2`Lt3F(kN3BZ}Gd-{(A$EA-+v^P^ZgkY0!)lQr9!Ksux z!qMbj30!k6Nan-K+Ss0LUv`rNTTaiu1@-di#6yeDHuCKxzS4&qV9Lw+D0V89Z`Y3w zL{49a&6^&^;2_}Zjmw_FXUc6jTl8xtY*s>Ul}@XeVP_Oyc+q8+WW!7w%;XsQEu1!( zG1T(ys#yx<2^ER7l0KSHiwn)KzAF|L50_p86cQ_CzKDyyn2?!Rx3$NveT*o)P)9Sa z{s9Vd8P(NL%*Is`Nz7qQByOK>#e}p6ygGED>VI&;NS5wh+h^b^LSFSm@Wf)sZIUAc zYo^^G-;9aV-BHkpKlzg3$Xb2ObJO&EZrk4bdEfYVm30_}2&(!8+1L{t9==3DYs!if z8|au8@Kz63B+y<A1X6a%NwVrq`9@D{QXy zgL>6MzmG`hkdzAKBiRI<`4``P%i4-5gHh0wF7`k%2);R_oB!s76+LQ~)sEF{0@BpJ zBP%E+9$^W@U#R4Itet_bDtedQX>Ou?|NEy}hN_)`m9Y-G`g7JSgq>Y`>U!7bBZwb1FTZrt(4a4bGJi{7nM_HWU}UQ^jt9+WHcry&@Rk zuwbSp3nvhG3q8jNK@e+2+6}~1OE8hoi;MKQ&w9SKAj9@qx=ZHUIkZ?^%Z@zGtL~EH5xl^?8zlDamrs+7(HoE9LWBS)-7kY?;KoL)M}M z&CHqTDircp75{M8hqDctx}fsQ*vusf$L?Emr1}wMtI|~~#ZnpYT)8t3pJ*DOAV!?l z!ZiR#bpnkeI+JbKn$t<1Vy3=;dmk;;*^ws>%M@h6nPy~6&k0V((&!(JX~5k}$cUKB zcy*=5OM(kRo|+LI1q_9iWo8{{(a6 zDed&A?<}C!L6bB#TcwJ;P+DiGhnN_^SNfFr2L|5;=)ePG*7*}v(Y62gj8NtVo|y9P zF(`Wqw7m^J=)n$035aD$>>dd++uwCjhkQNWd>Lu}of+!V3@Yf{&Gh_+D3D6PSj};= zIX*+2NHyDX68A1x%)QBllTUUnh?$J6Ladlla3t%~inrc8j-@|wyT-@*W!y|ahRXcK zydghlo5PsIN5+1G3yUdM2U$EQsb&%~5wL;&I%CSp(XbWNuf$|_>BQ*86W|@bM2C9v zsDdk0CWnW8{kWVpJ3J;M35Db_y|K-xtbFt2nC2D>=wDz)d|JbWGzC{?8Et|wb)wu3 zcOnnIxroVzw%=~PuqzfAOJat#kk8_Bxrvz@LKGMTWZ!Y!m9dH5R)0fBp_|h>u872wyhoQTuY_7A8CnOnbfMVLg2oA$5a5G&`*21}ezs1#RH+ih;zSC4zZ# zPRED!NF|_}6%a$6mf7KcWmmg3JAdJYXhcH0lj;QN;nooarg^LZ+Y_D(X12;R#W3em z`Q;{X3Kbm1atzU|<`{BKPxY;xc*josK*gj%#z1Q$MfoL|t%60kb-;ISIL?9+3Ygkf zOb+(QouUvalqSoRxg&KRfd#5N#p331@t68*bI zB>Ox!imMyE*@`|FGOev*1jsQRYH~1=LtbhE!ARpmbfjvf)N~7}W89`Hqjct)9ENzZ zeGv{ox)|q`!ri7bhfXmd1Nxd3Ci;pk`6F@GBJU3ciGedTQoryW*GYBPx)l+~Z_2#e z6~{phPG+(z1l>coUHQFbC+-Z z{fo4hjOBA#*p@Dr&GLt?Sz>r%%SRig%bSX=D@JUqErNgrCz(SQf$kWHa*@bNuVq5i zni2aM-PUoNim_UQ5ZYWh7~&qxP1>py)&rt?ALs7yCdCpSpxIUS4)m+TIvSP>eP15E z>31=Uj11E&dndaa9pQ2{=Cd4MhwHo&u!Fb$JN&1pOE(OH@=o4;o*o#SV&t5TSu+AZ5SA?V!& zOQfRTedpOa&lB9Ez``!68qwZaV6_O+yTJJD$C!0tOGoY*|PX)zt*J7xVa z-Fnm3PRX)qBydlafvz?HwB#sdZ|YagR93xp%BLqC8?HPtP+hK-FCTVk+AlX7sx)pQ z-aDBKV#@mkGQ=i|?X0P_Cu*op1{a(H^1dRyyNba)6Cn%KGBjhU*%jOyGx%YyNAAM} zEz6hQTUpNJ40Mv{)bl&pFUHpUUFrn$EmxcpEBBo@H^ZtgCKYtCcrpL-TE0Q=KQJ!V zS7YUEbsE0rn16PR(-IuxrRHR(x+U(qHaBUiu1hLiK>W9{rm~ z{qVVPy9kP(&jQ`GTUISAQun8;E7#AM+M>3<(k-7ZKUu=CyfSQGQY{H?L7#?s@1`xk z-CodqCf|>&GY{`KSzA~6wwIoj_Qh*FHV?0@hhAxHZ3=zUn@!T(wL z|4FI%@6h1oEU84|;pE`gcPc{&sDkfr^#F8(5}X2SQ-Vbx%Y3jE7~rUo`QF@H?bxZO zu#2iHD=d1@bm9xAq|ndjPxjLevEGlb%-^5UOxvHgVYA8G9?tHLpQn@3M7^HlUSF-P z2b$k+_xnk-uUA{LQMp^$^0wxCTiaIONQ&Cv+^yr?A0N)|=cfxLpJTF|&x54Ti;08- zP3<5Am`U-cd>U2n{%fx0jM zaYp-+7p7mWj>qn{4Me8(+QtwT7BsD#6PIDyM0RiI4~O@C?w&#V#kVxjqZ#?}Y9H#C zCybQu_b1@r%M>|mqT`N_18ta@_l7^J7nqSAk2g>2m&ePu-v`?dAGM_|BO4u5Q3JF8 ztm@|PV~=N}lewv@zU<$dmQ_cpr3%~6dOKZ<;JIG^EYf$$aWc=Itskd3?rdtt(%d%~V8f zx{0|s)?`)T?{mm@xTZOsOjQ()zuRHp)8?B8nG-$hu zSFy(+ts%QrzaiMG7fOW+i!Mz7cDUwfpDGv_a<&5CAQ{KmoV z25NTtFfUojhEbKb)k#Z~ zP#*Eg54Fcq_0P>iJDyo+E+BY~3;*$)iq=&f9^?wNbWv>|mhXxY;r^N~)+gm^cLY@1 zSXUfW#eIt0pc6DHXd+pBN5w`7k&&~H_#Y~iag?CIT_4_SqF-meyt=x+o)ea@&1gI~ zBfzI>K2Kzx_%&$^sH_hkVFMU$D#e-|r?| z?@mcstJ*Jz+|wBaq7AasMX_`EFEgR3$v010)mujDs@f#fajgdcB_DFYO)-H$8n^$5T)|q~z$Jk0!%RDefuReUAEYgEJigcR1Y$~LC z1dCILRwe7vPf_M}nTV3MwC(V@%`zKk6flqBpwKtiYiT541D~?lAFIEGoXOT??qamn z`c+6$l$(6XeC4#QsD`lK?}zq@@r>fb@(#uu(e;8Y3mI~QTgL$oXUhF41pY{ytr&7>zs2ZwhP+6C-xQJNG z&|(<-8FKdA>C_%zt{}a#d&&0*`R^1tg-)xD>-;SH9+cfCNu)xf$h+A9)C2rtHt|MzM0xa zd1D&BXCBLaB_s6Q=Pl<RFQK_qdq&O+#<7g^YJwYoN<)6pM; zo30-4iRoSNv;+=4d>S9+&|}T+_E@A$<2)(`f%~;;a06~s^bvJg>{Ktc2b+$toPw|- zDXCLP=uJp_6d^LMt^J2YKu@dNm}B-D)*J8}Ggcu;K7nu}(sP2961!W7?-dar_Nvw( zWX>=P$#f?+MpOI}=K`c-1tGxMY!j;z$au$x#tUz~#Sh*H&W|qD=q1v=fGE zKu$muBWhtinunEdW#*i!v@h>Zyy+yi0h*4~yw#JmIbZTva*AL5LBmtUzkV0|Q9~Ma zS&ueXWK~$5x!;IW{ppIPDWwJ`v$oz-+ov$#mIJxiCW#)r5i$*Bi3U$4hI_4h8>?CK zB;Y{EoP^FvR@#r?*&U1^V;?~8hyamliqSnYv9^*TWnwSk@4$sFY+e3TRC&kFoP;II zlq35pIt%(t{;gG+Z6utMV|;{?bNZ=L3se!&r!<-OW0wj8MVe*cI%t>Dy?oNFGhI=9 zus3k$tZw+i^w#&65bo9Bp{hZjiea0!>Mz6PYm6=?MYI%uYN-PwDft&cLLx1X+$Y;W zP-J7bcwmgi%Faq0G|ly<5=yX!$tUofqR(Vt=`lgW_RPiO!fGVq!k7T<21-ZG9{vt+ z0L3Sq%miLbjZ#3!o}f_wXDVFYUpI)swo9fMpp~#r9<81%5QAYtB5XiiyOlf)0d*C# zvqaq`D4Zwq5UjwL0Iv>h-QmlrF0jUo&Je?n6n%_YgWgji0E30WjJuKgC@;z=6YapU zDl=Sdd*3d*uRb(+hl0`$`vJt98cT~mrh#8~Xt7L5G9x~3Oqob4I{AejH_R6a!H|lA z42igYtkSXH%`=Uq&IU2Xfob0;m@h%Zj_CH&hm;sfQt+0wKSi>2Z~k6-56>rArDaL% zqyW7x+7ul6jLp@;RNrAyky#zrzN7>kIbm+8hhEB|xW6a|driuk@MBYpCqh^cW{t*j z5<;ukt6#$;!m5SdR~37t3Pr%pk@?iJSy*X0+|99F)l{eYG4dS7bOqAPa=Epn$FF}4 zUCJ3mj5u6_yP%q8H#N9RkoO9;YkWU+EkwKQv3h8RIdEN!5?yz)0X@%2gBYPWNvYv> zfr5S=#IlW4gn||}pR`13X1pbJk1+GT2Ti3Mp6* z1}kb61O>~K>KqBi^yH{#iMm?Bc2M10KDilmlh(Qf-!Lwc(uRM%WCyIOBO9qcc2$rC zJiBY3xR%#K?3weGS=}3Q*0*X!e@J(h-PUeeQdM71Yeyd^ugQ=ER%~X)lwh|pf4y=D z<9*R!Eu?WrQQ7t$9-2e9a)>~WXUTfM`>hPsO*J>R$$TVVz8od=RVhLpd_Mv9O`0x< zN=iaz`pP7f2~WMYyrd{9`EJ(KiV_S-($mYdZ9t}8cH$;L1}5v>`%jFb=!_V)B)Ki^TC%aKCSm5>)lmB`kjk!b*2HzLF(zhtT>a8@Y#MOePZo7%>$p8n=>P21aD| z3riU)h><>UD7S)Y|9#R3y}e_P@B}_!!o$7K!{!}ay_QY{uvwN>EOb_MplLv4#xv_c z@<9-tp|#yXGUVC?FS;Ni8x#?G=$y#?WY+3G&;Yrb3W? z4UzItgupN$=NJ0eH#!ZsKeH?ZVRMG6CQ|!WX!bJ6X!#@%E~~9w2}Nn{IbTx6J_#X1 zf1$8=N@^V~!~}+*hZ$ihJSXj;b4*MV=pnkvdQF7u3C@b`6;{8+D+%G$RdIYwSXVKRvAQ9EfuqnBA5}g8`@=A!$7m~`7JI~1u~fZ zF&XU0#~ZoJ#A+|D!bSlC3jOqLH*BiRoz@GyK0iDI77Svfj_aCrgHPXA(PL>6L_TFkLVVa6K49qmmk4qistls!Bs{`fJZb4a#LUHCBj;+Ii!i0| zN|$E#R074YQeH%eAdc8W5Et>M4oZI#Dew0x=RKzu?RTj~9g;zN#2^{llsocP#PS72 z9U9_nX97s4O#)c+ibdest-9IL4Z;auRa0?N;01KjN(1R_VAJNMxcMUa(j*UfmZ-nF zEDxpRrklvE9ZJUzn@+aLifX;odnh!Ovz=E@l=sE>V?s@8<>C(YGd9IEgKL`-WP?uq z*E7%Z*EE&o1|m>!m4^U+$dc)bvjQTp;kgriBmoe7D8t6#&RH?!B8hXE%ks+Jn=xS> zH~wdLY4}AgBQha!G%!F*`;hlr6unt={0W{IkoKz_8#pE)BK1M}Zb96;Re2pFT|&*E zumWcx&}P2MJxhQFi4sYoi@;CP6%^$LK#m0Xn|rtWk!|kxh0Fat@xo1-olH?} zTe_72@gk>71`665TNTu!x<}W#W>(xDWZT0p&TECQvP)M9cQRJGy!iI zH}k^+_lKDEC1AOU7qSWBo*RR7E(M?y%8EJy680~3vGS}L_~7^hCH4gw)>DUejuihmVaF+pBr8%Xf9{e!#y77T4G;E75Jn?G^%v4eL)pm~9HTD-xreyfI!LOV z0%pMIXM-b1)KZp6(2;>>I2_2{xz#<>mg{1o=;C z+4i)YKn$&Xq?vB?c2hI#qRq8HGd%Zr4SWvgRJEz0a-=~o2jn8EQ-nlzpTr3IX{}@h zYa!{ReT47<{n^CslCB?8#WIa=4wi9|=CT#u*dX5mt1 z-KD7bxRM2hrGp#0b6tQ0G(KZxSxraop9(BFE~x_p%zg`r{utR?V$ z2fWNOVC?KrGE0v?K-*uSW)yLmZMK(E?Z}#{rgr-Qp`R0j6^=BaCsq9BU1 z%iNG#45N*?%p)x_uQ%W$Rzd-NB9R-ymg@hqsE}nJMp#@v7sJ&k#32#Y z5R*r=+5{ED{&@d!peZWoNrjXIT^cer%%M)1JR2vkb1z9pRuFFyuwC{Xn$2F}tMr1h zULEo*YMIBHiAAP($0nIE8#eBrCOvx;$-Z0K*d9x$qXZ9r$`{GYz|ndM+L0uc06pU; z3Z|i>5?>U!+b_S^5WN;_G{P~1kqmAlnoKdI+>+{yvf#fuV&ol`7t?%RxAT5XSdQ3& zke}}oMnuWXeZEi*boo#fGlKO=89=D*@Jy8ckz>?L_s3i>dV6t8a!h~Ph%PMbt}*r< zT2~rRHD<@|%T!j1nD-C&9x;|?(vbeBTG5feS+7-Nn^^i6P0key+FM?$p%M9vLY zuR*s3b4V_eS4r}C?Sxe0ljoRltusu2v!1JLppcI;RV6$Uzqfn#b@7dsD(c*!#sXw8^q8dtff!5%^BPfdjcOIM9C>}Zw3v=XT zXJkTFW;v*SXfvaNe6`d9ga%sd6(4nPH7K8yJp;7KD<-j|$d|~CLH2yHv34iS?3nZt z%lQ!HBM$z*+WYc&s=oK%Oc^6{G98&BocVAvXG-QVq%segokP-OmXMi9$&kpDXfl_1 ziXxIEQ4~=rq`_VLsJ^D}=j->q_jT_-m)Cyneb!#X^Q`r(^}N^cJo~B3XW!Dk0<$b` zy`yZ=<*5hb%drN{^j{03`lR0Mjpj~OKHi&VIB?`PwSCPl{B~kfcf^)M>{G?>UZ4-9 zsTV~__N&}J$cwJielR=H>(tE?gcTe&Eh|2m5P9iyWJQ&vYjZ_It*B&+T2)At%c!yZ zjREJ{s4k7Kn4^q=v=4rq z=+u0xvXk)0-L<0PY@x|<^08jF+{fJaeVHqYn=4U|rUFf#_tg31DdN;L3Y34m7fQfSCg!?u9Imv6Z zO=m{K@}%STHk^7As%G4H4}T;54p-(Lb~{<@z|cjuAsFNLPsP~_>Nm1vzE9rV8majsJpJ$bqg@%}O|K3)1aG*mUjd*{%?bTRMwdw0Om zTPO%G6zX0g7d|uHt8;wrWz5WU)!~`l)oisdc!!1*PckbE`Cpors@bl1d~xo0oBK#l z==k6Qv40A8=Dx#e?u_Z&p(c2L4S&P@@fYr+DeYEwKfRkCbURhau6UNohqdO&{j)oU zhYBmBj~3sO|8+`#QQ=IyCs=@a8KdXebN5rh3BJ(lE+Nt*?H3d;2yQb{IOBJ-xg_<2 z{k^?(V@an@%`l#QJgX)>@}7Dm0qZf^44Vr{-`9_RWI}_jf9upD9~#`(aqk z-w-pI_Oboc+)>PX!OF@0sG08ypBF#<94Se%x%zG9s{h?3*}R3G@uj94?G%G0azB3_ z%xL=b_*xA`Z+MF0pmFojY#(vu46|I+FOGoY@9W;PAUa-0nMYDH7V*_{C3IKGh2Aor z_kH-@?|tXH^Y*;2Q)WFK5&1?XxgB5G+wA9F`G{~%bmE5SKhD{48e}CdQT5tSqN1yR z@{|Pc@VxS7aJDNY$+B6lBY)A1=*pWb>1gNsFOvjREIC2G%E`WV`PRe69rw> zUtT#Tx68F;?&;-upYMsji+fGKrKA?@v8^Ti6vxddog)KWJzr=o%d5*XQ*8GVD);-6^<( z`FQvk;U-a}q2RdB59OYP;DfBmN{U}aUF76?-=cbRKN(({%Ir(1&+|HRjGbSnE!?7_ zB$MM&=G#$~&U5#ACC=oRSh1G(b!RPEFd^(*cl$&Mb<4aer_Q{rZqQ_)o9&P>H_d+U zZGSvoWj1>MyT&h*+@Jbf0$ye#Qw5H@aNC9_3CM=~-l;n#EA>sg@5^jo{^?1!us0mW z^)l3+Y`v(v4(GoJc}xm-%&^{VHP`5_;U1AU;p9{s=4eCz4h{i{Ub_p zaxnNmHVaB-RkL8@@$PoW?JBcp&sPMHJRv_En#-G&js~v7b{Qu zS;Sb&ho4>~I9Hrjyxnsn_q6=e<{NiSZlNBO7Mc!Dwtg`Eaf{v+oE18%S9sc-O|?eRvvkkXw~TM94WJ7(3{6n2kQ+ zO;N`iRuf_>+Ye62mJ4#Ecj7cXg5K9i94LJi^`4e3)Z0&LmgPpRJ^wA;C)N_~COcJ< znJ}N!oSs}p^`@V>8Md8MZ|}1$6lVf6x#pM5?`$0y^bEP|V5~fj>GB)py%*J;O2K~2 zw81j|p-#^EIRD9}3R_J+-RW9<&gU1JXuRp|U4v?Fe7;0gDo>yMy}@TEhwN9!a)WA4 zH<+e=<=~`IBNvfy-194gqGytWmx1Hr2kG`QxjDKXqD05ZuoFybf@ikAv2eGtFAB~G z<4v2t zteJDlu^kIlyIrgfh`o1q{90T2#-D5{gGXWmGFR>*|6?P84c}FRSqze~0YO7~@<=Ja z61l7Ek1Od}drmERFg0t^H8?3(zN&{=6_`JHoKxr0tkHTb;P6MmgsrBmPIp60ulk5( z$~e6%6x{B1sJD{;ONH+1IIYI`8}hx2x#!+YckfZZ>r57N1wT-^?^19(mWwJ?MoiB< zT=&VB0XshZNTC!jmoAmrpN>yb9x3i1lhWCMt3N8_KUKaAdKFXHC}p}jB^rvEnuknm zru~Jd^~Ipd=gv8aU=U#B+55$FtIcOaIBVI{g*GXzSNWw%sNh^ya_)z_cRMpt8+8?n z#Z0A)Tsq^^DmYL5+Hr@-deSf}zxT1vnqaT);ZB6XHB=6oshaLlwLfNU>SJW>PLR~I zadr0cv4_D`oUFa|y*+FRFbv5Mkq)lrZtG#^?CuDI*i&_OaIp8bcek}Czz)HX2s{k# z216pTFgO7QC&G~6i^Fg~82khb?hiW*gBzdl1bP0=0W>KXEWHUts1zWvaEP3J`#k(W zUXn-z5(kq+W05c<4tQ)tB5*QL7ElybdxEXEvnSER8-^kImjl^=U>$3sw= z-45z+By#?AJY|BdJ*Zwh@E8eKvG&|=@9gMAgxG}Whu%n{fEg%U-PPKW0K?;!nb-vT z|ABHkxF*rs)!A0r-O<$^Do)4Rk3=sFi3WNKZbYUBV}M1(7M2hAxs7s$Kud9Iy_)YS_T0_Nn>GXJn-%bE-c6&dJn}% z5i8M^n!345(OAsE*AsJ#e%PI zqw!EW3=9kIGN7`cJLy6}@o=O{fbLNFq(*}(5YPZBmJTWt3(}A(Srfbu_L@Ta-{+(DDk{UL;u z14bGN5-hhPBnN-Wfs@ zKrSGeSaFf$0g{P77fDur%LF73D=&yH(r=IlBpZJ&h;tl52DBld6_SAsE<7lMBo|;5 z#;v&i$i$yJkOe>=hK_WHo>yF?wqAY@#rb|pZq}kEkB)rVShU(^@m|0g=q-s!r!APcC(Wl{AyT$jjG&MhoDhCnR}0U zK_*~6B8zSAm)ki>&KL6UB4%B!>@J53mXC7W%JnqTHq^~K&T#CSG_UN0aOY1lFW)gtu<|))OO5t-h#t8K+WQJS zylk(V7u)Qg95Sq~>HnM|-lowvBym@Fp!dK~mgAJBrSB0vH|L`}eAuL^;u!g5tEj*2 zdMhEdH_m zi(e_kG(}}DMmve*&nyLA`C47`Ym17G@%;_zY}1$=w`T4d`+!*mVDcH$QsICACHYo6 z?}geW7o`MCJ6@~#eA&QQgK%`cGjb2YZwYO^M(a8Xd5|((oY7kAa@-x^x`W5%cNFFJ7D{^$^vmyU@6|tI@jc{`Q~6KPet0GF2!ALWo@N7PHw(d~ajWD5 zjg>Y*=-({g!jc>ImhP>3GM!kMrINzAq;@LScCxY#?T!Em6)n5uh*E)AdmHPp1{AI| zplz4gR;8V;I*c7(c#0W{FlTvQv-v{}3@Exn2+Z1e-DUr{V+KcJBb)t}41q44Bq zt)%LyDKyQL|1HlPZPq#FQ-QzIzdVuAFK^N2a(Z4?^GxV|aEf4}Xxftko3G<)Ohf#w zS9UOLK-6a8G7@N!l|2cXsnx?6ROZw7X>3^vm@V&l7xd!nq4rc_Fq>^VT=gJvDk&T| zh>Mh=$?S7rHb==dbti>HwnX`os;Uy+$WQcSs z%T6otP1}y)9Q~zm(fC6Lx8kW5&1%9)9c0}&- zfzGV)UxO{vsjjg%>OQl2@vu71o}o3uz-3xDay}iHi@*8b|_XrV9*9pxQ+#@IN(exKLj9+TIR5!i889{z(v6XMO!+Cl~l6W%_-e=SLVyy#gT8R|cxaZ+Tzr%wUQX{-pTw;2`e?74~Ok?LSo*dd)-;Ybg8Vk}}O?tJU76?l?a#?nX zoBPP0kW;7nMF`w5C|(fOLmUzPc)VIJI-|KV*5ada4*xxz+vrcTG7-9Db&1e{<{EzC zF~4I!xXI-?ogYSNt1}8wc-8iecljrXg%1Z{+;sVcHJP%gDi76PfYYP)`y1BBU;c5k zn97thla^qsBP4j;H23YdXK2eNR$HOGG%BHYtn>Ln%+5`=5Uc- zkt%xTZ|$xt(;640Z$TIK*C2Fz)M<|&tEk>H_jR^IC~A<$*YrT{13crjeF8qnu0&SE z_2KCD*_ZM`aTld)BPE0Oq~QDQ7EAfnxZef8UQ90#D`OY_p^_w5`g-S5#_;!Vvp;@O zN9{f%xIyczoK^nQG#=+51&zwtL!{V1iTyhvrkAL=#Hiu>C=JPsUFX#=B|XhL}FZhnpw` zhRzoxy!1YJgv?#m^Q)^y&#yVIV+kQc4RIF@&(Qe|Ek4FYoDVxu9O@r1jWrWX3n`?U zD&5vm&T?#+v9Pagc3^4e@TYGSR;;*%4Vc_4I+9*Jc%aJ=20*iHu|X5iR0Kh-P&O4Q zL3;F6C8-oDGgx?gclY)-6b@;Kz+k9uX?I3v+90Bp%(Y^b@%lgUmRy$3TZkx@%=Pqu zVR>^<2#r{+R^;Qg+$oS?G*bwb+FrLfaAh`Ucg4k*X9q=v-<{_f;7~i3T%m1l#21T6 z2s!)iqi5;m&$6yv4i2v@vQi@6B#w8p+e~Mj8t70zY%bdPKEz?~-3bFcCpAvzMn-|e zwIL}##(t42hvt|StGci9^eVsr!>)z}C;8=$sG3Yn zP-{f&vQ6O}A62G(ci^Fu#kr*8Y81-TpUc}$(oPS)Jl1lHI{)G$Suuy3lSD%)cg}DD zzLw8+y-&)j%4n~e zjh(J{p>w2(?z}!*&;9yphV5Tn)l|d?aZleLt$#%ClI+UicVLl0H-@)huSwI+dV=*{m#4U^|LK>~VA2~)&7if0h5>d*7 zXzyTYKw+d+Y~H1D?X!)G_UZt|7QP6Mqzwq#EbIX@sg)h@H$j+# z%LL(os4f!}gd{wWxarEssm&W=ztv_3R~oFeBcLfzc!VLA3-8(EeGhf-$(F@@4z&%4 z*(}~!t7jpQ-hg1J{LcQPZcE>Em1yJD@VTXa!!|Y=CE+{wgl%jE$>GQa{J9qk@z`vU zGmhQ|e@N(sYCJ4@rO6hUGIGQ>sGYmXUXc;aUzK9|D5oibp+yZRFUO2}CcJ$wqH?Rx zGl%C9H3B1Lf`*;y$vyonU!I6lwi(?Seiy{zR(zW9PS`OAAzBaQ&-gY;_LJqb`NLkCu$i6laz==L!wz z*IPJCHXvxTNC_+st`a9)IgoFJG$c+K69ftch(j3w`9@(d)M&zet025pas*kdHI2}N zoj|TF2z7g5xAcpa$2qSo7RL=}*(?Y_fz^SP#9;OC@c^~8p9obznCuu-s=a>w4({2v zvla2Fy0ISxT6eF_PXoEY7p9aMbk;xE3yi=bD zBN*p=X}y4YJ0TM%dL?pZZcxG(e}-|A9v3aZKE5FCAA}3enmREG043pIYUF zFpQg)qtC!*I{i(^(Q02J-|gKjgnensQmg`<@5FPrr|B1#WnVQk@XS}ZK2ex)_RUet z4YpvwBw}-V0R@%}R@RrizU&260ftF@DEy<)XF*Rs^#VzUnc-rJG%jUdu>qQ*>)f zq}%K8m{Nk}{wq6H9hvq@O~WXzMAUn}T;E-%3*}m}_fFX9JSr4S9q7>;OkLpdynFPy zoo-Syk*{MRz5G!yp1opzGy+Gh6a9Q*YM#|u9Bx?2YjOFE4@=U}j`1BVDUN5khV7QV zQU40J*tLPgZ5Ga;!J5yi8Z^{$Z&acg9A~q<`sCxKt`mkPLsj2BTvQD6#j7HaO^DNN zvG?C-9cJ+gZM}P>_>f%gDXBvisVB}=Mn(%O+BQL0piSK~81>aw_MUgwR+ znG5@pL#bnRKW5TDJdOV~3J-YDe{nisg}&7Tzi|WmMzUpt%ooG4K6*kBEW%NqwH$<&$SxzUuuV z4q9~jRC&{6DZSBA{#eOatX|sCfKs>|E#{vkadT%{l{)%?^>*gI`T7=$oj<*+wqvfl z>?$|gb?LT^YV>(mf_yb)pY}{6zOSD3q3g`$zRX)_w75Xf^NO%zlS;m2HM5>~G8EAh zS#BG&>1NRz60EbXY*U>WWkw1l*d96&nxOTHTtK_w! zlmsr1d($cN8cA+(+tj)w>G$=!#(zTvQlHv!QNw4{`C9YP95|@)W6L8~jOKcVz`FZ? z*UfbdG|y82B|FZ(s3dSCq3XIys>=9Me;Z>co|3jCJ|X#{89fs+gkM5_Ax?lG{geAl z)@G35^*?I zl=&ly58GO|Sy=Vwa~nhk?MdvTC1#m6+~{~!_O{PgT1E2ntGv^n7M)B}tU@1aeKqqt z8me$HKh<|SexLt{j_j@uKDr!~tmK~CCmY_o2QDhM8-D!RI={eM!qoZ0GJS&@+$@O0 zuU-~Yi+;ci?ba?CE7Q`^J=YUS03aoLJL;6xIOB8(75$wP>ikqmB1hQGs1Mk_(2r57 z9`TlJeL=lZ7#&4o^G-ary*y8E`(03O11dL*?AFe~ z)xcn+iliB=HS!GHKavtVTYdvV`G+oPKka-)Yvtzgi8!5{2Vy-SPX9F{Yu z=WUv$0yqlCYaTFe$-B;4PSwKod>SX_w8f+%QuAT1~O@74veNvqJ85-Ki$`}I5h0}x1IR;#WxovNRaj2H2MsTU}rjy0BL-PRP zL5|i9=-DiiM6Ll#Iv2n&C%`~4Q?-j9=Hxc)XRb!2ha%OmM}6q7kdM3L@)_(dg5rbQan?zXLkS z74-hSz4bD+cx+nBiOFmIw7e-{(CL~W!GIrQatR0Qk@uHy+aB5B zd{gp%h8z&gWsw+XJApXe`nl8Y&b#AyQ(0~*HnrUsTTLcP$qQtS8d6;%j!oLykKOB$ z-3m^k9LDF{d1XiW82gBOYIh}lH5mHlYo2&ogVCPuSs{VP^;Mf&{SHy}OGVR+^ARvT zQ6r7U53qrc)S}U+lM42DUUr>(tc75t{JD?y;#j28Btu|Rr_q-&mZ{NE-|;{zj}y%M z2e!Aw3GCnv^1W=i^t$g`^^#YZY}akBVxF1T$1nEzHXpT#XD5(Fz7WeBcagH_=i2)+ z0o^>7`#tQ@eXEqpVC|W2ihW&+zbN>`92Pfd!Ic>AUz`76-%}C;c8!tJV9-aR!1wl` zvk%U$M0;=2i2}`pwntv39 zK^P%$Sd*4FC}|vdnRlIpAVCmDFBEB|Y=;K(Y4%yVQyb8_Y3u?hUny>Cv9jP$6@$u2 z-Aus+K?;Q~2b36Y-oy5pt6^P_87#PxHK_M_P{c$~_#NRPs+l56N82CoaPC-^F-o5R z)0|PKM8nhf8=aGgpPX=nJ@iGaybg^1iP>CNx9??t`5|k}J9qlgHxn^jTK`YWgTMPdJ$JyRyu&gNR}w0AF8Iw;Y;Fv34CkXPiV+dH?O zSFjzuNf8Ho#VdK0*S{Z4iDYO$9J{i z&5d5}J(b+Rcp~hLyB$tgTn(OZQ+U3c?$harw`}u6Pm{}3Fey&>GxTWj8{E7-TDUY% zan_2fFY3{Y+uVp0rr~_0hhW_~R{eKi-px!q7#^guM($!bptE(U*gGcUNF=vH{U;T+ zxOm35*d?={p9$MajABIN+&yYuA4$(=q+sTWPpc9a|*!a{L9*H+lAfl zi4MtI^3tY?xufegbw;qp|r_0yX7l+j;v4QFSV60b}Zz7Crt zBj2}kgY&*%e|nRxhh9DR)X{Hs1FiSH5}YEao8YPBqmGoj_4BMs8*O}wlh*6Z&xwbU z+wA8B@gA)eZ&bo{lbk=hcXyVQ{>o+`_g&IA-d-eJdZ5GdiF+wV6FyKc6P@C6`@(qs z$q@5wzmKEOdc*?X$)g@PlvU#q1@ey=V|DK}mAvnfO%kGrsED22ca3h6uU9xLX3yY7 z!^^soZ+4_)Oq@J*VT*j@%jg%6o7*{~)Nf1XJwBEs!-QZpdYt4{5Eq!px>dzd;~<9q zT1%V%KJ3G2d}eBOy{8pLds#@%wIahRCVR38^25*fj$#f3UD)z)cz4v-#jQ7f93dTq z{=G5%d*>a$Sr~x?oBOMzUJnlz&>04Q(w%_?_?X>!nXqdj_Se~>iL1Pn%vb$dZe`n2 zF(Lysn|UHq%K3j_qLn0q(**tZH6kQDahieQ%BGqJ6%M6q3*4qUvVWnEO^#c~F6c`0 zIo^8-trHY8hKEXhCdfW)HxW8q#$a1oRN*OaO^I#vXMg(@VH**zkzt}WNk+xG@Z{Us zY4;i5(_~hS2+{$CHSBE~m4FiqE7`-wv~L6Ksm!DW(NlJJ-ICKge>I%A+iL2f?TE0kUXg;3;N1#M{Pui(X-YjOZ3c9Dj@GNBcQy8Mcm421y;PTD zTZYWtFsfXga$(umr`UBD;e>>|Brbc#mO`T;-Ilf>_KTdo-ost@io7#f`R?qg&ysCC z=Y5IGdEw_wj`ZQ9FZ>WsH|UX@MJgD?>d7V6Q0tZ;!07X0_v(yOV~`4Zxkswi-u@bl zyLmG1Dy0ymLzjTc+eF3ph9}$T5^5JE4!zF(Jkwgu{pP@@Qencmr-@w&%r+5G*LS?< zx*f!|i>7p+26kKsMy}nt+nP0`tIR5(w%^9rP4Q`{Z%#^a@}wV1$w92}rdH`A{rU%) zLT+d6jqza?1v`^$?xj053rHt%vds^KK2R9_plR1~)rR*#)Eqg?c#Lr%IIiqU zQLgM~{Ex)0H#uGAMSZ1TBP3##$#`SE%=8<`x1xndc{*yJw`NLJtsutfnM*peq1AABJ ziBQ(mXjb0GpB5?4@7u~g5)lfg6_>&r+K#8;=Sk*44KtI zJLjM`%^Xxti9wiO7ap4Y_(9G5uB2&$=G`pXTO+;b<<(FOf;wJ3Oer}oVjr|VyQQJy zO%Uzdm20!Xd$w&EDc^Q+gQ7Q$_<(Dul|4ttpt1;T@=VHya>#%^o|+R(d9+_g|1=a@(opS|KOB&nWzSP`*pV`^19O+zulNo$lF}=EZM! zygF$j-8=l{+!69PgCG;@K*m_vdsYhrE+Vc5^t+H@`se`XhjfH{EJ#YOsN0S^62%#G zpLU5K{0_fv|4jU*AL8;Z#an4k*N;~4_)UsY?|b$lsnTCShh{o@t8IsbUW-1Y?9i-UjQ}ca0I!w~WCWHfc*F z){c?WnEfJIe0yL)+wzW#&_Tw>8b|0kciU!ftoI>u#S1UewpUkZQ4Q7lj|7;C;K+3^w-+PNE&K+H^LYO z33P|Aq8F&gB$wL9QWarr;AF-?ze!)-viQ_`q?dJ#)Pw_5!1gT+gl9o2}W$%x?M! z+&JlHlvAHC^lUV8NuiM-Nhx_sy*uFOSVqZ(SKs0}oaZmP^%VQx)Rw)GbCbtak8nif zsD1xu|)2%s(o)o~d)8^Y)9DLx+mTE&g$a2)k zz$ne1>(}?s)1PF|{34SeoFZ)0E}O-PYYzCJ(KsV$laibzH#cm9^8peaff9oBvB^AA zD)hDpHyhU+D+imccIGf7tOD8;yqLzi!IyWCh|OX{G&sG!vOfYP=}rZdWS7`IrE4Gc z9?jmk5m^IP)mf|AwGmdMVsP^(S~b1GgV*ZE4)Mk4$Ca8YZBT|3K|;?6 z&R#ST-XalabE>Wkix%Z%evvm%Z68k1y4KCBqdP&?*w(0d^|0o*tEm?csK%#Eo-W<@ zC9E!9PC*0N8Zd>6aLb|+8Rxqu+|j_c_hvJBl|$N7lL@PbeBokI2kFc5_*_39Vol27 zEgIz-K)h^67};cw+@$J#YhxcY{bm$f^6=aTgM`ENp3}*l$7vor{o>|mdu7WWAE0r) zlx3Tuyqo-?tdYouKP;aHS4BkK8vrjOvdj{g>NJn zn?{?fr&uI?7EsTo0#3T|zNIkSDC6dX0BlDZ)nQY`YODzsa@d3Rf&&5n&M#s z`jHoR#!1?{-whbVZM$_V$>`dJn~~Xwn7MLScD|!ohj#hID+V`+!(WV6@U~p*t9+Ri zS#vgr3`x5YJDUY|XyC4KB|BI{ygQiBO#Y-h4GVA|oEd=akNZ)(Eq{QG!i#8_C~INt z+a4Zje0z%ctvu;Di}cuW`_Km3)&iCfhGF~js!Ro*&ZMGB?qVG&TMVx~9LpK=Y7J7X zzjmFz`P-e+k~b~9F??q1f|;sysK$ngoym`;Z#o=0lk8j<;}?>?r%$rkjLMLENan-& z`AqP!lC9^eQ~U8t{KX z??$ptJm*$>p&Te2e-YnULHshj&|P}<*Rv?;+P&iM4q2GnK2hNQkk}-FdgpKUg*e;S z988ay$@($=lz|0fA06LBUGy9umX&H?>UUQqVOuA%Szwm&NeOejxh+PM7$3vV84{z;{a}pKjOmgKxio2-pCY z0n?OCDjw7tU?ypx=}nFeRDbEDs*O2)^({h&B% zb?DqiBEDIKi3G+BD@9xB-t1e=Srtv1(!GNC?&4F4Eza8lrOA!~gWexuv z_*(7ULqGry zoKtpCr^^+2`}dr(y^|fC!y8X7^E5Ftvn^aA4sZ1ZE{5?)*%}e9k}0V*P*wZ25+%s09vrJQGCnWyxw9}AyeDiPGGr1vMcjSB7V=Dv|u zA7*uFwDF0svC9Hmqmr<6OR5#)wVWrs8gc$MGCM5!%DFGRE}d9pu8em$-QBdWLf9$b zWTBDsi(D_(23{=Hd$ITF*;U)`XXHCR!^96^%Hj$4w$+~OGU{KtUQpHkjjH;%)US=$ z+AK6e0mG72HE)22c5SBSfmMT06x>fQYj@|b+RmuQrhE@9!^#r{Qa>9eHr^ zTwxlry&afxM_@bxX0w}1Lb)?vjg`Z#OEd>t3zj-xrhFJ`F}l{2yd!WcnW+p<|3v@C zBzZlN$3%8iZvnP_2Q91GF1c?Pa-XtJT40`_SbCe73y)D$$^Jy>ZrQ@>)lP1gaUij5 ztihx7OWD?gi@(S+G>ntiR}e7e`q#4Jzw9UX=@=NSvY%XOHwkt?fOX3%yGgn=c9Yh7RQB>fsJ-*I;mE7!DAm0xT9`0Gq?rfl(3+t_uTO{&0Pm44~Q&m=l7H z1{mA~1~-KPa~!yhx3#T{JrN?44y-2r`MpdlIHm&kaksPgCfIs-+r#i6b88qL@M#N! z+W`^)T`;&Ku+akXoMG@|Ft`g0?h0&5>EM7uz=J2K5*QrNPckos`@rD7D~wDJ)BO)E zOgG+TS#4noP70IS?|*7x3Mz_ZVY*H@R_xRKd&^QR1o&3jM6JXa|0By%G-|D7>Az+B z-%|YVElPotivPxP8UNg=D!|F;&U*nhSt1tb0cRf|%R%KT$dstl}6Nn;_9|r6PNnwVN79)+`MlfJ}LJBj6bQ04|f>dca7#+W?e6=m2PKQm7~JRPg)hFVG04K|fb%20nc!UJD z^Q2V3wFKff9m}u=f(+md9SQ0zPsl+k9}w*~6)Ru|67ib~fE|Fx3Q~rkDAKG0hToYPsE%G1sPW&6sxXk>I(`udJT!u>iiZGeL~Ch5AZ4JDa8*1saHOz~7Nj(!W>&=mwn)J5#M&?n zH14m82l4}cDprSqw2)VrRq>F(3}r3NNE8+tpI5~L`9a{N9dmyEOJDfG~kTM8pcwLniILd6TS#QRww; zgvMdkwFmH#1NGh2Y4Lby&2?268i9ZuNvsaTVb-+=3Xg{dk~Q&wrQ6yt8QgmLlR-mz zYjs)~#JcuH<8ctkSRD_CS=W}JHP+QV8nnkc-lVaRc3PdEG!DWMYr*@e>!L?~I!0Ku(%@_m*QkJXA07p?E-MuDE zdR<#$KtErX7KvU*GX^QWZk)s*W!C2hhM~1`g+Za#$p!|6gD}Ku`hcgQb^M}aAhfhP z9vTTDo;6`;NLj53!>p$Tbl-L5Vn~2xby`rR>*Gm7_-}PQAVTYC!J;6vx+WfOU7yBa zWxyKMns~sG(Yi8l$aV4uPO+|&T?`JlZv4aGWY+a_j5K1MtbtK?-Pn!+BDqe6fJdlx z^&*2@8xQ#VT363_XnwaQKRkY&UIjjfAbbz~ z{ne{j1O}QptO>)e8(**p>2+<1MFOR_HZ2&&*Ybu1I&Up~012#5i(232z=za2ez7Rb z`ZBPfG5f<+KkA`q>;i6o>1 QP!A48CoHU{r%w030Dcm;D*ylh literal 0 HcmV?d00001 diff --git a/systemtests/save.py b/systemtests/SDplotting/save.py similarity index 94% rename from systemtests/save.py rename to systemtests/SDplotting/save.py index 49d1f7c39..fe6213d6a 100644 --- a/systemtests/save.py +++ b/systemtests/SDplotting/save.py @@ -31,8 +31,8 @@ print(f"File not found: {crazyflies_config_path}") exit(1) -experiment_number = int(info["experiment"]) -info_file_path = f"info/info{experiment_number}.yaml" +experiment_name = info["experiment"] +info_file_path = f"info/info{experiment_name}.yaml" # file guard if os.path.exists(info_file_path): diff --git a/systemtests/settings.yaml b/systemtests/SDplotting/settings.yaml similarity index 99% rename from systemtests/settings.yaml rename to systemtests/SDplotting/settings.yaml index 99e19a593..fbaba1536 100644 --- a/systemtests/settings.yaml +++ b/systemtests/SDplotting/settings.yaml @@ -1,10 +1,10 @@ --- # general settings data_dir: logs -data_file: cf231_ +data_file: figure8 # data_file: log129 info_dir: info -info_file: info_cf231_.yaml +info_file: infofigure8.yaml event_name: - fixedFrequency - estPosition From 1a21101023ea0f98e085d1b86c8be4186c860600 Mon Sep 17 00:00:00 2001 From: JulienThevenozIMRC Date: Wed, 27 Mar 2024 14:56:32 +0100 Subject: [PATCH 110/162] last work in date --- .../crazyflie_examples/figure8.py | 6 ++ systemtests/test_flights.py | 69 +++++++++++++------ 2 files changed, 55 insertions(+), 20 deletions(-) diff --git a/crazyflie_examples/crazyflie_examples/figure8.py b/crazyflie_examples/crazyflie_examples/figure8.py index af75d2998..72e0f1aa9 100644 --- a/crazyflie_examples/crazyflie_examples/figure8.py +++ b/crazyflie_examples/crazyflie_examples/figure8.py @@ -14,6 +14,9 @@ def main(): traj1 = Trajectory() traj1.loadcsv(Path(__file__).parent / 'data/figure8.csv') + + #enable logging + allcfs.setParam("usd.logging", 1) TRIALS = 1 TIMESCALE = 1.0 @@ -35,6 +38,9 @@ def main(): allcfs.land(targetHeight=0.06, duration=2.0) timeHelper.sleep(3.0) + + #disable logging + allcfs.setParam("usd.logging", 0) if __name__ == '__main__': diff --git a/systemtests/test_flights.py b/systemtests/test_flights.py index 8f7c20d10..72df164a8 100644 --- a/systemtests/test_flights.py +++ b/systemtests/test_flights.py @@ -66,6 +66,7 @@ def __init__(self, methodName: str = "runTest") -> None: self.test_file = None self.launch_crazyswarm : Popen = None self.ros2_ws = Path(__file__).parents[3] #/home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws + self.src = f"source {str(self.ros2_ws)}/install/setup.bash" def idFolderName(self): return self.id().split(".")[-1] #returns the name of the test_function currently being run, for example "test_figure8" @@ -79,8 +80,8 @@ def setUp(self): # launch server current_env = None - src = "source " + str(Path(__file__).parents[3] / "install/setup.bash") # -> "source /home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/install/setup.bash" - command = f"{src} && ros2 launch crazyflie launch.py" + # src = "source " + str(Path(__file__).parents[3] / "install/setup.bash") # -> "source /home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/install/setup.bash" + command = f"{self.src} && ros2 launch crazyflie launch.py" if TestFlights.SIM : command += " backend:=sim" #launch crazyswarm from simulation backend current_env = os.environ.copy() @@ -98,8 +99,36 @@ def tearDown(self) -> None: if Path(Path.home() / ".ros/log").exists(): shutil.copytree(Path.home() / ".ros/log", Path(__file__).parents[3] / f"results/{self.idFolderName()}/roslogs") + command = f"{self.src} && ros2 run crazyflie downloadUSDLogfile --output SDlogfile" #if CF doesn't use default URI, add --uri custom_uri (e.g --uri radio://0/80/2M/E7E7E7E70B) + try: + downloadSD= Popen(command, shell=True, stderr=PIPE, stdout=PIPE, text=True, #download the log file in ....../ros2_ws/results/test_xxxxxxx/ + cwd= self.ros2_ws / f"results/{self.idFolderName()}" ,start_new_session=True, executable="/bin/bash") + atexit.register(clean_process, downloadSD) + ####testing purposes + print("waiting") + time_start = time.time() + ####### + downloadSD.wait(timeout=300) #wait 5min for download to finish and raise TimeoutExpired if not finished + print(f"download lasted {time.time()-time_start}s") + except TimeoutExpired: + clean_process(downloadSD) + print("Downloading SD card data was killed for taking too long") + return super().tearDown() + + ####try to plot the SD log + SDlogfile_path = str(self.ros2_ws / f"results/{self.idFolderName()}/SDlogfile") + pdf_path = str(self.ros2_ws / f"results/{self.idFolderName()}/SDreport.pdf") + print(f"SD logfile path {SDlogfile_path} and pdf path {pdf_path} and self id folder name {self.idFolderName()}") + + command = f"python3 save.py" + savepy= Popen(command, shell=True, stderr=False, stdout=False, text=True,start_new_session=True, + cwd= self.ros2_ws/ "src/crazyswarm2/systemtests/SDplotting", executable="/bin/bash") + shutil.copy(SDlogfile_path, str(self.ros2_ws / "src/crazyswarm2/systemtests/SDplotting/logs/figure8")) + command = f"python3 plot.py" + plotpy = Popen(command, shell=True, stderr=False, stdout=False, text=True,start_new_session=True, + cwd= self.ros2_ws/ "src/crazyswarm2/systemtests/SDplotting", executable="/bin/bash") + return super().tearDown() - def record_start_and_clean(self, testname:str, max_wait:int): @@ -107,14 +136,14 @@ def record_start_and_clean(self, testname:str, max_wait:int): before forcefully terminating the test flight script (in case it never finishes correctly). NB the testname must be the name of the crayzflie_examples executable (ie the CLI grammar "ros2 run crazyflie_examples testname" must be valid)''' - src = f"source {str(self.ros2_ws)}/install/setup.bash" + # src = f"source {str(self.ros2_ws)}/install/setup.bash" try: - command = f"{src} && ros2 bag record -s mcap -o test_{testname} /tf" + command = f"{self.src} && ros2 bag record -s mcap -o test_{testname} /tf" record_bag = Popen(command, shell=True, stderr=PIPE, stdout=True, text=True, cwd= self.ros2_ws / "results/", start_new_session=True, executable="/bin/bash") atexit.register(clean_process, record_bag) - command = f"{src} && ros2 run crazyflie_examples {testname}" + command = f"{self.src} && ros2 run crazyflie_examples {testname}" if TestFlights.SIM: command += " --ros-args -p use_sim_time:=True" #necessary args to start the test in simulation start_flight_test = Popen(command, shell=True, stderr=True, stdout=True, @@ -148,17 +177,17 @@ def translate_plot_and_check(self, testname:str) -> bool : successfully followed its given trajectory. Returns True if deviation < epsilon(defined in plotter_class.py) at every timestep, false if not. ''' # NB : the mcap filename is almost the same as the folder name but has _0 at the end - inputbag = f"{str(self.ros2_ws)}/results/test_{testname}/test_{testname}_0.mcap" - output_csv = f"{str(self.ros2_ws)}/results/test_{testname}/test_{testname}_0.csv" + # inputbag = f"{str(self.ros2_ws)}/results/test_{testname}/test_{testname}_0.mcap" + # output_csv = f"{str(self.ros2_ws)}/results/test_{testname}/test_{testname}_0.csv" - writer = McapHandler() - writer.write_mcap_to_csv(inputbag, output_csv) #translate bag from mcap to csv - output_pdf = f"{str(self.ros2_ws)}/results/test_{testname}/results_{testname}.pdf" - rosbag_csv = output_csv + # writer = McapHandler() + # writer.write_mcap_to_csv(inputbag, output_csv) #translate bag from mcap to csv + # output_pdf = f"{str(self.ros2_ws)}/results/test_{testname}/results_{testname}.pdf" + # rosbag_csv = output_csv - plotter = Plotter(sim_backend=TestFlights.SIM) - plotter.create_figures(self.test_file, rosbag_csv, output_pdf) #plot the data - return plotter.test_passed() + # plotter = Plotter(sim_backend=TestFlights.SIM) + # plotter.create_figures(self.test_file, rosbag_csv, output_pdf) #plot the data + # return plotter.test_passed() @@ -170,11 +199,11 @@ def test_figure8(self): test_passed = self.translate_plot_and_check("figure8") assert test_passed, "figure8 test failed : deviation larger than epsilon" - def test_multi_trajectory(self): - self.test_file = "multi_trajectory_traj0_ideal.csv" - self.record_start_and_clean("multi_trajectory", 80) - test_passed = self.translate_plot_and_check("multi_trajectory") - assert test_passed, "multitrajectory test failed : deviation larger than epsilon" + # def test_multi_trajectory(self): + # self.test_file = "multi_trajectory_traj0_ideal.csv" + # self.record_start_and_clean("multi_trajectory", 80) + # test_passed = self.translate_plot_and_check("multi_trajectory") + # assert test_passed, "multitrajectory test failed : deviation larger than epsilon" From 4696275bcbe82d54e8c97bd0912df3e4725dc8d3 Mon Sep 17 00:00:00 2001 From: JulienThevenozIMRC Date: Thu, 28 Mar 2024 13:45:18 +0100 Subject: [PATCH 111/162] basic working state for figure8 --- crazyflie/config/crazyflies.yaml | 10 ++--- .../crazyflie_examples/figure8.py | 4 +- systemtests/SDplotting/plot.py | 2 +- systemtests/SDplotting/save.py | 12 +++--- systemtests/test_flights.py | 38 ++++++++++++------- 5 files changed, 38 insertions(+), 28 deletions(-) diff --git a/crazyflie/config/crazyflies.yaml b/crazyflie/config/crazyflies.yaml index 6966f2819..889e66612 100644 --- a/crazyflie/config/crazyflies.yaml +++ b/crazyflie/config/crazyflies.yaml @@ -95,11 +95,11 @@ all: estimator: 2 # 1: complementary, 2: kalman controller: 2 # 1: PID, 2: mellinger ctrlLeeInfo: - experiment: figure8 - trajectory: figure8.csv #translation_y.csv # yaw0.csv # # # - timescale: 3.0 # 0.75 # #0.34 - motors: standard motors (CF) - propellers: standard propellers (CF) + experiment: figure8 + trajectory: figure8.csv #translation_y.csv # yaw0.csv # # # + timescale: 3.0 # 0.75 # #0.34 + motors: standard motors (CF) + propellers: standard propellers (CF) # ring: # effect: 16 # 6: double spinner, 7: solid color, 16: packetRate diff --git a/crazyflie_examples/crazyflie_examples/figure8.py b/crazyflie_examples/crazyflie_examples/figure8.py index 72e0f1aa9..1e7199826 100644 --- a/crazyflie_examples/crazyflie_examples/figure8.py +++ b/crazyflie_examples/crazyflie_examples/figure8.py @@ -39,8 +39,8 @@ def main(): allcfs.land(targetHeight=0.06, duration=2.0) timeHelper.sleep(3.0) - #disable logging - allcfs.setParam("usd.logging", 0) + #disable logging + allcfs.setParam("usd.logging", 0) if __name__ == '__main__': diff --git a/systemtests/SDplotting/plot.py b/systemtests/SDplotting/plot.py index e07ffe7a2..abcd52942 100644 --- a/systemtests/SDplotting/plot.py +++ b/systemtests/SDplotting/plot.py @@ -165,7 +165,7 @@ def create_figures(data_usd, settings): with open(info_path, "r") as f: info = yaml.safe_load(f) except FileNotFoundError: - print(f"File not found: {info_path}") + print(f"(plot.py) File not found: {info_path}") exit(1) title_text_parameters = f"Parameters:\n" diff --git a/systemtests/SDplotting/save.py b/systemtests/SDplotting/save.py index fe6213d6a..046459da4 100644 --- a/systemtests/SDplotting/save.py +++ b/systemtests/SDplotting/save.py @@ -12,7 +12,7 @@ # experiment_number = int(input("Enter the experiment number: ")) # File paths -crazyflies_config_path = "../crazyflie/config/crazyflies.yaml" +crazyflies_config_path = "../../crazyflie/config/crazyflies.yaml" # Read information from crazyflies.yaml try: @@ -28,7 +28,7 @@ for key, value in obj["ctrlLee"].items(): info[key] = value except FileNotFoundError: - print(f"File not found: {crazyflies_config_path}") + print(f"(save.py) File not found: {crazyflies_config_path}") exit(1) experiment_name = info["experiment"] @@ -37,10 +37,10 @@ # file guard if os.path.exists(info_file_path): print(f"File already exists: {info_file_path}") - ans = input("Overwrite? [y/n]: ") - if ans == "n": - print("Exiting...") - exit(1) + # ans = input("Overwrite? [y/n]: ") + # if ans == "n": + # print("Exiting...") + # exit(1) print("========================================") diff --git a/systemtests/test_flights.py b/systemtests/test_flights.py index 72df164a8..a686654d9 100644 --- a/systemtests/test_flights.py +++ b/systemtests/test_flights.py @@ -93,7 +93,7 @@ def setUp(self): # runs once per test_ function def tearDown(self) -> None: clean_process(self.launch_crazyswarm) #kill crazyswarm_server and all of its child processes - print_PIPE(self.launch_crazyswarm, "launch_crazyswarm") + # print_PIPE(self.launch_crazyswarm, "launch_crazyswarm") #this will always print all of the STDOUT and STDERR since we killed it beforehand. Not smart ? # copy .ros/log files to results folder if Path(Path.home() / ".ros/log").exists(): @@ -101,7 +101,7 @@ def tearDown(self) -> None: command = f"{self.src} && ros2 run crazyflie downloadUSDLogfile --output SDlogfile" #if CF doesn't use default URI, add --uri custom_uri (e.g --uri radio://0/80/2M/E7E7E7E70B) try: - downloadSD= Popen(command, shell=True, stderr=PIPE, stdout=PIPE, text=True, #download the log file in ....../ros2_ws/results/test_xxxxxxx/ + downloadSD= Popen(command, shell=True, stderr=False, stdout=False, text=True, #download the log file in ....../ros2_ws/results/test_xxxxxxx/ cwd= self.ros2_ws / f"results/{self.idFolderName()}" ,start_new_session=True, executable="/bin/bash") atexit.register(clean_process, downloadSD) ####testing purposes @@ -123,11 +123,21 @@ def tearDown(self) -> None: command = f"python3 save.py" savepy= Popen(command, shell=True, stderr=False, stdout=False, text=True,start_new_session=True, cwd= self.ros2_ws/ "src/crazyswarm2/systemtests/SDplotting", executable="/bin/bash") + atexit.register(clean_process, savepy) + savepy.wait(timeout=5) + print("savepy finished") shutil.copy(SDlogfile_path, str(self.ros2_ws / "src/crazyswarm2/systemtests/SDplotting/logs/figure8")) command = f"python3 plot.py" plotpy = Popen(command, shell=True, stderr=False, stdout=False, text=True,start_new_session=True, cwd= self.ros2_ws/ "src/crazyswarm2/systemtests/SDplotting", executable="/bin/bash") - + atexit.register(clean_process, plotpy) + plotpy.wait(timeout=5) + print("plotpy finished") + if(Path(self.ros2_ws / "src/crazyswarm2/systemtests/SDplotting/reports/figure8.pdf").exists()): + shutil.copy(str(self.ros2_ws / "src/crazyswarm2/systemtests/SDplotting/reports/figure8.pdf"), + str(self.ros2_ws / "results/test_figure8/SDreport.pdf")) + else: + print("ERROR couldn't copy figure8.pdf to results because wasn't there") return super().tearDown() @@ -146,7 +156,7 @@ def record_start_and_clean(self, testname:str, max_wait:int): command = f"{self.src} && ros2 run crazyflie_examples {testname}" if TestFlights.SIM: command += " --ros-args -p use_sim_time:=True" #necessary args to start the test in simulation - start_flight_test = Popen(command, shell=True, stderr=True, stdout=True, + start_flight_test = Popen(command, shell=True, stderr=False, stdout=False, start_new_session=True, text=True, executable="/bin/bash") atexit.register(clean_process, start_flight_test) @@ -177,17 +187,17 @@ def translate_plot_and_check(self, testname:str) -> bool : successfully followed its given trajectory. Returns True if deviation < epsilon(defined in plotter_class.py) at every timestep, false if not. ''' # NB : the mcap filename is almost the same as the folder name but has _0 at the end - # inputbag = f"{str(self.ros2_ws)}/results/test_{testname}/test_{testname}_0.mcap" - # output_csv = f"{str(self.ros2_ws)}/results/test_{testname}/test_{testname}_0.csv" + inputbag = f"{str(self.ros2_ws)}/results/test_{testname}/test_{testname}_0.mcap" + output_csv = f"{str(self.ros2_ws)}/results/test_{testname}/test_{testname}_0.csv" - # writer = McapHandler() - # writer.write_mcap_to_csv(inputbag, output_csv) #translate bag from mcap to csv - # output_pdf = f"{str(self.ros2_ws)}/results/test_{testname}/results_{testname}.pdf" - # rosbag_csv = output_csv + writer = McapHandler() + writer.write_mcap_to_csv(inputbag, output_csv) #translate bag from mcap to csv + output_pdf = f"{str(self.ros2_ws)}/results/test_{testname}/results_{testname}.pdf" + rosbag_csv = output_csv - # plotter = Plotter(sim_backend=TestFlights.SIM) - # plotter.create_figures(self.test_file, rosbag_csv, output_pdf) #plot the data - # return plotter.test_passed() + plotter = Plotter(sim_backend=TestFlights.SIM) + plotter.create_figures(self.test_file, rosbag_csv, output_pdf) #plot the data + return plotter.test_passed() @@ -197,7 +207,7 @@ def test_figure8(self): self.record_start_and_clean("figure8", 20) #create the plot etc test_passed = self.translate_plot_and_check("figure8") - assert test_passed, "figure8 test failed : deviation larger than epsilon" + # assert test_passed, "figure8 test failed : deviation larger than epsilon" # def test_multi_trajectory(self): # self.test_file = "multi_trajectory_traj0_ideal.csv" From 262352319703edeea4cf608e39f0f681979a3834 Mon Sep 17 00:00:00 2001 From: JulienThevenoz Date: Thu, 28 Mar 2024 15:51:24 +0100 Subject: [PATCH 112/162] got rid of Popen for plotpy and savepy and simplified a little bit --- systemtests/SDplotting/plot.py | 36 +++++++---- systemtests/SDplotting/save.py | 105 +++++++++++++++++---------------- systemtests/test_flights.py | 42 ++++++++----- 3 files changed, 106 insertions(+), 77 deletions(-) diff --git a/systemtests/SDplotting/plot.py b/systemtests/SDplotting/plot.py index abcd52942..fa5b9ac5b 100644 --- a/systemtests/SDplotting/plot.py +++ b/systemtests/SDplotting/plot.py @@ -5,7 +5,7 @@ # attidtue best: 22 -import cfusdlog +import SDplotting.cfusdlog import matplotlib.pyplot as plt import os import sys @@ -14,7 +14,7 @@ import numpy as np -import data_helper +import SDplotting.data_helper def file_guard(pdf_path): @@ -128,7 +128,7 @@ def add_data(data, settings): print("...done adding data") -def create_figures(data_usd, settings): +def create_figures(data_usd, settings, logfile=None, out=None): debug_all = False debug = False debug_figure_number = 20 # Residual Torques @@ -137,14 +137,20 @@ def create_figures(data_usd, settings): # debug_figure_number = 6 # payload positions # debug_figure_number = 7 # payload velocities - - log_path = os.path.join(settings["data_dir"], settings['data_file']) + if logfile != None : + log_path = logfile + else: #choose default log file path given in settings.yaml if no specific path given + log_path = os.path.join(settings["data_dir"], settings['data_file']) + print("log file: {}".format(log_path)) data_processed = process_data(data_usd, settings) # create a PDF to save the figures - pdf_path = os.path.join(settings["output_dir"], settings['data_file']) + ".pdf" + if out!= None: + pdf_path = out + else: #choose default pdf path in settings.yaml if no specifif one given + pdf_path = os.path.join(settings["output_dir"], settings['data_file']) + ".pdf" print("output path: {}".format(pdf_path)) # check if user wants to overwrite the report file @@ -299,7 +305,8 @@ def create_figures(data_usd, settings): pdf_pages.close() -if __name__ == "__main__": +def plot_SD_data(logfile=None, output = None): + # change the current working directory to the directory of this file os.chdir(os.path.dirname(os.path.abspath(__file__))) @@ -309,11 +316,18 @@ def create_figures(data_usd, settings): settings = yaml.load(f, Loader=yaml.FullLoader) # decode binary log data - path = os.path.join(settings["data_dir"], settings['data_file']) + if logfile != None : + path = logfile + else: #choose default path given in settings.yaml + path = os.path.join(settings["data_dir"], settings['data_file']) print(f"Processing {path}...") - data_usd = cfusdlog.decode(path) + data_usd = SDplotting.cfusdlog.decode(path) # create the figures print("...creating figures") - create_figures(data_usd, settings) - print("...done creating figures") \ No newline at end of file + create_figures(data_usd, settings, out=output) + print("...done creating figures") + + +if __name__ == "__main__": + plot_SD_data() \ No newline at end of file diff --git a/systemtests/SDplotting/save.py b/systemtests/SDplotting/save.py index 046459da4..72365ea58 100644 --- a/systemtests/SDplotting/save.py +++ b/systemtests/SDplotting/save.py @@ -5,53 +5,58 @@ import os import yaml -# Dictionary to store extracted information -info = {} - -# Prompt the user for the experiment number -# experiment_number = int(input("Enter the experiment number: ")) - -# File paths -crazyflies_config_path = "../../crazyflie/config/crazyflies.yaml" - -# Read information from crazyflies.yaml -try: - with open(crazyflies_config_path, "r") as config_file: - config_data = yaml.safe_load(config_file) - # extract the trajectory and timescale - obj = config_data["all"]["firmware_params"] - if "ctrlLeeInfo" in obj: - for key, value in obj["ctrlLeeInfo"].items(): - info[key] = value - # extract the ctrlLee parameters - if "ctrlLee" in obj: - for key, value in obj["ctrlLee"].items(): - info[key] = value -except FileNotFoundError: - print(f"(save.py) File not found: {crazyflies_config_path}") - exit(1) - -experiment_name = info["experiment"] -info_file_path = f"info/info{experiment_name}.yaml" - -# file guard -if os.path.exists(info_file_path): - print(f"File already exists: {info_file_path}") - # ans = input("Overwrite? [y/n]: ") - # if ans == "n": - # print("Exiting...") - # exit(1) - -print("========================================") - -try: - with open(info_file_path, "w") as info_file: - print(f"Writing experiment info to {info_file_path}") - for key in info: - print(f">>> {key}: {info[key]}") - yaml.dump({key: info[key]}, info_file, default_flow_style=False, sort_keys=False) - print(f"Experiment info written to {info_file_path}") -except Exception as e: - print(f"Error writing to {info_file_path}: {str(e)}") - -print("========================================") \ No newline at end of file + +def write_info(): + # Dictionary to store extracted information + info = {} + + # Prompt the user for the experiment number + # experiment_number = int(input("Enter the experiment number: ")) + + # File paths + crazyflies_config_path = "crazyflie/config/crazyflies.yaml" + + # Read information from crazyflies.yaml + try: + with open(crazyflies_config_path, "r") as config_file: + config_data = yaml.safe_load(config_file) + # extract the trajectory and timescale + obj = config_data["all"]["firmware_params"] + if "ctrlLeeInfo" in obj: + for key, value in obj["ctrlLeeInfo"].items(): + info[key] = value + # extract the ctrlLee parameters + if "ctrlLee" in obj: + for key, value in obj["ctrlLee"].items(): + info[key] = value + except FileNotFoundError: + print(f"(save.py) File not found: {crazyflies_config_path}") + exit(1) + + experiment_name = info["experiment"] + info_file_path = f"systemtests/SDplotting/info/info{experiment_name}.yaml" + + # file guard + if os.path.exists(info_file_path): + print(f"File already exists: {info_file_path}") + # ans = input("Overwrite? [y/n]: ") + # if ans == "n": + # print("Exiting...") + # exit(1) + + print("========================================") + + try: + with open(info_file_path, "w") as info_file: + print(f"Writing experiment info to {info_file_path}") + for key in info: + print(f">>> {key}: {info[key]}") + yaml.dump({key: info[key]}, info_file, default_flow_style=False, sort_keys=False) + print(f"Experiment info written to {info_file_path}") + except Exception as e: + print(f"Error writing to {info_file_path}: {str(e)}") + + print("========================================") + +if __name__ == "__main__": + write_info() \ No newline at end of file diff --git a/systemtests/test_flights.py b/systemtests/test_flights.py index a686654d9..4bb4eec1f 100644 --- a/systemtests/test_flights.py +++ b/systemtests/test_flights.py @@ -10,6 +10,7 @@ import signal import atexit from argparse import ArgumentParser, Namespace +from SDplotting import save, plot ############################# @@ -120,24 +121,33 @@ def tearDown(self) -> None: pdf_path = str(self.ros2_ws / f"results/{self.idFolderName()}/SDreport.pdf") print(f"SD logfile path {SDlogfile_path} and pdf path {pdf_path} and self id folder name {self.idFolderName()}") - command = f"python3 save.py" - savepy= Popen(command, shell=True, stderr=False, stdout=False, text=True,start_new_session=True, - cwd= self.ros2_ws/ "src/crazyswarm2/systemtests/SDplotting", executable="/bin/bash") - atexit.register(clean_process, savepy) - savepy.wait(timeout=5) + # write_info() + # # command = f"python3 save.py" + # # savepy= Popen(command, shell=True, stderr=False, stdout=False, text=True,start_new_session=True, + # # cwd= self.ros2_ws/ "src/crazyswarm2/systemtests/SDplotting", executable="/bin/bash") + # # atexit.register(clean_process, savepy) + # # savepy.wait(timeout=5) + # print("savepy finished") + # shutil.copy(SDlogfile_path, str(self.ros2_ws / "src/crazyswarm2/systemtests/SDplotting/logs/figure8")) + # # command = f"python3 plot.py" + # # plotpy = Popen(command, shell=True, stderr=False, stdout=False, text=True,start_new_session=True, + # # cwd= self.ros2_ws/ "src/crazyswarm2/systemtests/SDplotting", executable="/bin/bash") + # # atexit.register(clean_process, plotpy) + # # plotpy.wait(timeout=5) + # plot_SD_data() + # print("plotpy finished") + # if(Path(self.ros2_ws / "src/crazyswarm2/systemtests/SDplotting/reports/figure8.pdf").exists()): + # shutil.copy(str(self.ros2_ws / "src/crazyswarm2/systemtests/SDplotting/reports/figure8.pdf"), + # str(self.ros2_ws / "results/test_figure8/SDreport.pdf")) + # else: + # print("ERROR couldn't copy figure8.pdf to results because wasn't there") + + + save.write_info() print("savepy finished") - shutil.copy(SDlogfile_path, str(self.ros2_ws / "src/crazyswarm2/systemtests/SDplotting/logs/figure8")) - command = f"python3 plot.py" - plotpy = Popen(command, shell=True, stderr=False, stdout=False, text=True,start_new_session=True, - cwd= self.ros2_ws/ "src/crazyswarm2/systemtests/SDplotting", executable="/bin/bash") - atexit.register(clean_process, plotpy) - plotpy.wait(timeout=5) + plot.plot_SD_data(logfile = SDlogfile_path, output = str(self.ros2_ws / "results/test_figure8/SDreport.pdf")) print("plotpy finished") - if(Path(self.ros2_ws / "src/crazyswarm2/systemtests/SDplotting/reports/figure8.pdf").exists()): - shutil.copy(str(self.ros2_ws / "src/crazyswarm2/systemtests/SDplotting/reports/figure8.pdf"), - str(self.ros2_ws / "results/test_figure8/SDreport.pdf")) - else: - print("ERROR couldn't copy figure8.pdf to results because wasn't there") + return super().tearDown() From 83c085294109aad5623bba1f9e00833a6b14b8a5 Mon Sep 17 00:00:00 2001 From: JulienThevenozIMRC Date: Thu, 28 Mar 2024 16:08:14 +0100 Subject: [PATCH 113/162] SD download and plot working for figure8 but now rosbag plotting seems to be broken --- systemtests/SDplotting/save.py | 2 +- systemtests/test_flights.py | 27 +-------------------------- 2 files changed, 2 insertions(+), 27 deletions(-) diff --git a/systemtests/SDplotting/save.py b/systemtests/SDplotting/save.py index 72365ea58..834bc70d0 100644 --- a/systemtests/SDplotting/save.py +++ b/systemtests/SDplotting/save.py @@ -14,7 +14,7 @@ def write_info(): # experiment_number = int(input("Enter the experiment number: ")) # File paths - crazyflies_config_path = "crazyflie/config/crazyflies.yaml" + crazyflies_config_path = "../crazyflie/config/crazyflies.yaml" # Read information from crazyflies.yaml try: diff --git a/systemtests/test_flights.py b/systemtests/test_flights.py index 4bb4eec1f..c7937e195 100644 --- a/systemtests/test_flights.py +++ b/systemtests/test_flights.py @@ -89,7 +89,7 @@ def setUp(self): self.launch_crazyswarm = Popen(command, shell=True, stderr=PIPE, stdout=PIPE, text=True, start_new_session=True, executable="/bin/bash", env=current_env) atexit.register(clean_process, self.launch_crazyswarm) #atexit helps us to make sure processes are cleaned even if script exits unexpectedly - time.sleep(1) + time.sleep(3) # runs once per test_ function def tearDown(self) -> None: @@ -120,33 +120,8 @@ def tearDown(self) -> None: SDlogfile_path = str(self.ros2_ws / f"results/{self.idFolderName()}/SDlogfile") pdf_path = str(self.ros2_ws / f"results/{self.idFolderName()}/SDreport.pdf") print(f"SD logfile path {SDlogfile_path} and pdf path {pdf_path} and self id folder name {self.idFolderName()}") - - # write_info() - # # command = f"python3 save.py" - # # savepy= Popen(command, shell=True, stderr=False, stdout=False, text=True,start_new_session=True, - # # cwd= self.ros2_ws/ "src/crazyswarm2/systemtests/SDplotting", executable="/bin/bash") - # # atexit.register(clean_process, savepy) - # # savepy.wait(timeout=5) - # print("savepy finished") - # shutil.copy(SDlogfile_path, str(self.ros2_ws / "src/crazyswarm2/systemtests/SDplotting/logs/figure8")) - # # command = f"python3 plot.py" - # # plotpy = Popen(command, shell=True, stderr=False, stdout=False, text=True,start_new_session=True, - # # cwd= self.ros2_ws/ "src/crazyswarm2/systemtests/SDplotting", executable="/bin/bash") - # # atexit.register(clean_process, plotpy) - # # plotpy.wait(timeout=5) - # plot_SD_data() - # print("plotpy finished") - # if(Path(self.ros2_ws / "src/crazyswarm2/systemtests/SDplotting/reports/figure8.pdf").exists()): - # shutil.copy(str(self.ros2_ws / "src/crazyswarm2/systemtests/SDplotting/reports/figure8.pdf"), - # str(self.ros2_ws / "results/test_figure8/SDreport.pdf")) - # else: - # print("ERROR couldn't copy figure8.pdf to results because wasn't there") - - save.write_info() - print("savepy finished") plot.plot_SD_data(logfile = SDlogfile_path, output = str(self.ros2_ws / "results/test_figure8/SDreport.pdf")) - print("plotpy finished") return super().tearDown() From c2ac0ec74393ec05f8eef1d9d07f4fca5af42e76 Mon Sep 17 00:00:00 2001 From: JulienThevenozIMRC Date: Thu, 28 Mar 2024 17:06:46 +0100 Subject: [PATCH 114/162] changed mcap handler --- systemtests/test_flights.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/systemtests/test_flights.py b/systemtests/test_flights.py index c7937e195..65adf75ee 100644 --- a/systemtests/test_flights.py +++ b/systemtests/test_flights.py @@ -141,7 +141,7 @@ def record_start_and_clean(self, testname:str, max_wait:int): command = f"{self.src} && ros2 run crazyflie_examples {testname}" if TestFlights.SIM: command += " --ros-args -p use_sim_time:=True" #necessary args to start the test in simulation - start_flight_test = Popen(command, shell=True, stderr=False, stdout=False, + start_flight_test = Popen(command, shell=True, stderr=PIPE, stdout=PIPE, start_new_session=True, text=True, executable="/bin/bash") atexit.register(clean_process, start_flight_test) From 812b29d6ab41865d2d4c0c5e999cff02c2aee003 Mon Sep 17 00:00:00 2001 From: JulienThevenozIMRC Date: Tue, 2 Apr 2024 13:33:34 +0200 Subject: [PATCH 115/162] working for figure8 --- systemtests/plotter_class.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/systemtests/plotter_class.py b/systemtests/plotter_class.py index af35a0cf4..5833de3b9 100644 --- a/systemtests/plotter_class.py +++ b/systemtests/plotter_class.py @@ -25,7 +25,7 @@ def __init__(self, sim_backend = False): self.SIM = sim_backend #indicates if we are plotting data from real life test or from a simulated test. Default is false (real life test) self.EPSILON = 0.15 # euclidian distance in [m] between ideal and recorded trajectory under which the drone has to stay to pass the test (NB : epsilon is doubled for multi_trajectory test) self.ALLOWED_DEV_POINTS = 0.05 #allowed percentage of datapoints whose deviation > EPSILON while still passing test (currently % for fig8 and 10% for mt) - self.DELAY_CONST_FIG8 = 1.3 #4.75 #this is the delay constant which I found by adding up all the time.sleep() etc in the figure8.py file. + self.DELAY_CONST_FIG8 = 1.3 #delay const used to temporally align the ideal traj with the real traj self.DELAY_CONST_MT = 5.5 if self.SIM : #It allows to temporally adjust the ideal and real trajectories on the graph. Could this be implemented in a better (not hardcoded) way ? self.DELAY_CONST_FIG8 = -0.45 #for an unknown reason, the delay constants with the sim_backend is different From ebaddd93262e209180c9bbf3363571aab1ad61a4 Mon Sep 17 00:00:00 2001 From: JulienThevenozIMRC Date: Tue, 2 Apr 2024 16:41:21 +0200 Subject: [PATCH 116/162] working test_flights for figure8 --- systemtests/SDplotting/info/infofigure8.yaml | 5 ---- .../SDplotting/info/old/info_cf231_.yaml | 5 ---- systemtests/SDplotting/logs/cf231_ | Bin 85439 -> 0 bytes systemtests/SDplotting/logs/figure8 | Bin 85439 -> 0 bytes systemtests/SDplotting/plot.py | 12 +++++++--- systemtests/SDplotting/reports/cf231_.pdf | Bin 58244 -> 0 bytes systemtests/SDplotting/reports/figure8.pdf | Bin 58225 -> 0 bytes systemtests/SDplotting/save.py | 22 ++++++++++++++---- ...l.csv => multi_trajectory_ideal_traj0.csv} | 0 systemtests/test_flights.py | 10 ++++---- 10 files changed, 32 insertions(+), 22 deletions(-) delete mode 100644 systemtests/SDplotting/info/infofigure8.yaml delete mode 100644 systemtests/SDplotting/info/old/info_cf231_.yaml delete mode 100644 systemtests/SDplotting/logs/cf231_ delete mode 100644 systemtests/SDplotting/logs/figure8 delete mode 100644 systemtests/SDplotting/reports/cf231_.pdf delete mode 100644 systemtests/SDplotting/reports/figure8.pdf rename systemtests/{multi_trajectory_traj0_ideal.csv => multi_trajectory_ideal_traj0.csv} (100%) diff --git a/systemtests/SDplotting/info/infofigure8.yaml b/systemtests/SDplotting/info/infofigure8.yaml deleted file mode 100644 index faac515d4..000000000 --- a/systemtests/SDplotting/info/infofigure8.yaml +++ /dev/null @@ -1,5 +0,0 @@ -experiment: figure8 -trajectory: figure8.csv -timescale: 3.0 -motors: standard motors (CF) -propellers: standard propellers (CF) diff --git a/systemtests/SDplotting/info/old/info_cf231_.yaml b/systemtests/SDplotting/info/old/info_cf231_.yaml deleted file mode 100644 index 0c3730bb0..000000000 --- a/systemtests/SDplotting/info/old/info_cf231_.yaml +++ /dev/null @@ -1,5 +0,0 @@ -experiment: 184 -trajectory: figure8.csv -timescale: 3.0 -motors: standard motors (CF) -propellers: standard propellers (CF) diff --git a/systemtests/SDplotting/logs/cf231_ b/systemtests/SDplotting/logs/cf231_ deleted file mode 100644 index 51a797a46198f9e4cc135dae03fcc0a4f06fca54..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 85439 zcmZtP30O_v{`m3Al*~uS5J?oGLWcI*=g62@#!yl;D20T|6hc(yM1xYHLZ*;T9YbWE zJE)LUWS(UR|Ib>V{rl>k|GLlfeeQkU&+D%5+UxAS&p!LqE?Y-SN9*rj_t^n%vxfM& z&0px|J2OzLhSmaq7k{_G3;bvMz<+lSFmvy$kpln!6hxD*mfHgVv2z#9_Mbi1SF5Jh zg1HO*X1bXT=&Uto?#%Iii*PLIf3rcP|1JH$dw9>RtwsOy<##^Odypiwwr~>v{wVH*+$`uo)zzAOm^(zk4a^Tus7dj)DB))}ifi8I;-+6P zXNRbX>(^-ERCkKkS8?&aRshHJbxqRawj#3yc;L1W*aynii35va(8m_-@mm_U{3F* zCaa1Qge*43vKw3+Q-nEau$pXej2B9}((SJGg^PRYxUog*XRjuPk-LTBE))xtNPw)#Ux{I3b(ijm2Di<|XEKZfa6HFHRWAmQJkg&fEDX zHOBlA@TZ(O;S0m%=3M-?H|7rRYLW-|IXfoO#&hv{C(KW!X*^;tw_y+$w+X=<4!G~F zI3b1Yj8_x5_;?!TK)?ofV4c}+zWNdukGO+*)GRd_cPUONVtC>^E`DB#xi75q=2LOP zJ%+#Nd+?Snur20!Gt{JcYMgL};jsc2HyMoC5?=23_&DJs!`7}`oZ^kyV7i(djgAur zTGIXbaVQrL+=|%)4o#EDIN?0Q!wz%tgG|gj0e9XIC)BW_BiFpo#lFRu`@l3vP@M3R zjhs=%#kFgDvPEhE8(7;XPUy%+Zqfm(#xc0Z9P?AaJKbUDXSi?}7xx;Ec?hg?xm%oY zj7=kC9v5E^#B2k25sVzp*4ZwKi)SWaz5~+;ag7rMw%2K?xcE;V=52uQPLC6E*v>zs zjElFv#rzePZktn_kjW0KI`wArcBIbwn4iOoA^`ShSf>XUpS8if2=Jq6aN1^gw*wbX zbHUsbreW$3Cp2L=e>oSwUx&FpEZxjWal+Nkbl=#qmy6e?WA=n2WijAiW)ye3&c%jm z%#LsjZk-q>3}YkfeCFcQzc3$$qx;8rcm)}DYw5*Xx{=11^WcmWFfLA*$Z*I0TwH30 zIlu$nCPu{xRt)F6bMcb7m~{c)9uOx?W_U{k7dPL5ITq%8qhFj5!>}TQi&L{PC&6lb zvyKyT8BQ(aV%t*8p@84_i4$%!JV)D`w;B)YV(tsrP>d6Pxwy_`%vS-M$m4_u3|lSa;@!(I)3=G=HgQ5J!}nvjxOXz<8?eqRdc+B_3&?a6 z*pxOnO@ z%*L>Ri>hLUy=>0Q?r`ykhnVX>QWLL>k-}g$a!^3ABHy+bFuyl%%=daF^&_Cu(POG+n2W*2OD56 zhB-n191Z z0hvjhu$+w?lfcDwQ!q~i9MB<7_{^~XB`!|BiFr2Qet^$2Z2gXl`+mhd8qOO*MsdPl zHs>Asb9qa5t2O2saHI@q5hnyPEEl-gV*uvq@S+&hjT0OgZs5wr+Osj&nxiH)e#Z*N z42Oks@%Bxam8EL(?r5aYlpQI(4|B2kNz7@!YI5gWtdPKt!7pkqzVHb1vAJrptTI+; z&hXJHE_SXlk1djHo|=?=j}@ZXJM33utQr?opF3lYfRS~7#tN4iJ~fPsH;lzx5AYC} zvp$=~&UsvHv>3C&3)sNjkwQyjdUOwo;^OQ$%r9Z&gXOV;2b;$394;Pn0rQHN@Sd_h zQgAk+BfFJx@rzfOFTiTtuZR`Sno?{~Z$58FTG0ga55T?N#tKIm4z%LpR(&xW%~zAJ zZ(@a2Y|c|0xcJa?%)u~n)azKmfbB@yE4X;@8qCvS-w1mdD=cG2io;$meslnH4cJ9H zzKRvB*%_(jbuM0f7qf@Anv8}ydoz6T6BpO}f!Pp7?gp#Tnc>iue!QhiY=_w!aOd~2 z!hJU98vVJr-w@1g0eAlzD?~AT(w&R*=U{e%Ie&s(bSA?~Be>Xe8|F`NbO-&46&|s5 z9-YC(e@|l$fm5yp99H!h4k_f~sHd23!711JL#*(c?fe6@7w}f2M;*+?fDK`<3t=Oh znsM>PZkQhcjxLQA+}Q?tjpkyf37FMzu6t4f@7?T0*|?C4zXW0ShBJSi$Fag=_EGwM z3>RCFZP0V>N?r<6NbU2w8-j5ZUvX4u;FS%Ix4)bTgH}YeJW(+@U z5#0tCFG*4;fgu`4xEuDL<&0@-n*KM zTdc?I4XbhRVys|?p9j;pIQ=l@3K+R`WTem)SK|&BkGPMy80I|wLaeZq;dPZ<{J0A9 zDY&jXW)~?OW4K4#g}kL(*a34N*!fFyV+Aj^fmMUJxWRDD_a3Xs@F9`H2DXb%_vYfX zd6?J2F_?NjR!C*LsLoa{7NanG0#3?{71pqkb2GVEor8HjTrtXS#0odqVYR=Qi@nM) zpN0dr**$n`V|Z-sMZDFhRS)w4I8uB8pJ4d3IT!D=!dw$xl+^37LMg*OI^R$6ObtA%h+1Gkcr3k-){SdolljX*7j>V?D!TE^+ajTGLo*H!C0cZk6im}?wRlj-la3*Xu6x=X76 zGmXE0A2keQOXmvzzT%SYLIu0pvuuP_1N&KHj)D!0E8Z^jXZVs-HL#u|;&rfen_q4h zQrT)um#PNdy$bP;!)jvwce~)taHUi=aKBW<`{1Q2Hi#6G*)+CFRRiC+g*fM^n)K)u zDGcjKUqQ3mST*phZN#>i(kBOZHNP0j^H3Yl!_oVRdC zb~uH(IUGMG%OZtq>=IljlZ(GT#vBRL=ocI*>|=P`6E0p?a|v6Gx3C(&Rz(U93|rK~ zsxfE7u9%m?D_98An9`2ED7U4mfsffEc7pvm%@5xG*)h0k9Czf=0hs6RQxmmEq;Qwv zHi2CHbT{VuNovx<6?P6U12*m(~epYoyiM;&HVfr#NncId0!WqW-o|IN(I_$?h6BeW(ju z$&49+SwEwYB(B;oCZAxZVKV?%E#cyzotPV%KO#nJQiStu zTmZWya&eP0m}@ydA~ma01iv7PYhK~v1Lc@Q=RP9tb5aGf^AxAOuZHK!Rtva+iuxWy%mO@c0~g2c!+i5ZKJhmU6DBlv2VCo@ z237~mhLL;Sz}!g}ex_z{n4s)58}Nw-Tzu^_=Akk7NciC}p{&#kaL6AC(;bO!pyw7J z7}>qmDz5;AJB;@TT(% z0dMiZ>@v2Hc(jZVhV@wlxQm|#?obp6xbsHLZpuRP$UZ_SI35J}#!d}<^7Aslxfz%T zeJCU^0B@PN0(-!_u8x3Y8Z4cB7ZN1 z3tHdT08Xrr^}l0qWS{kb*P3A-HKK@g>=`GFJG36KT~7^MJSGBg`!Sf+o<+o2*elpv zjR0JGss_&X-v;=^Ld-SR6p`XasluV|+W;R3*1%&Uq5zMK#T>A^h{Rn_6V_Pl1UzPc zHM}q8g3#?)9N@C^nCBfYB8q9*!kAjS0e`xof#K)2055-u`Q7;?qR9WK? zwnnce6%zdcHwDN32Ve-f30AEEGs+44BP0$!2{^4cW|v*XY)Y?xUBcvY)4Y>n7zP#iYr1>k;dF+0C4CHH4EB|EKN0oJvxhV>qFAXTX! z0pA#eIjnsdIdRs2xDi~`{s)qN)3?f;> z>I3dtjJb1M85yjyA^IQc1Gdvy`)@VA{GLEYyEX=Vz82i#3Qw_sOn3V2q4fxAA%t2SnNaMxRNZFUxfZHz8z_AyM z0Iv_ke7|)$@tNgLHdwU>d@Z&bh7%f@P}&i&Q3B@7hh=0#KOgem*c5P&+-ew3JEXo& zSHLIpFsBrikxm-}$insJfNQTpDK}2gW!0yAaGQ7eoo4~s<;68IPH?}Jxg?8Cw`||mKyUeSG;fzZjB+UbSD-v^9 zyCRY?+&l%i*)hyDx@D7A_VvWYZaIKkW>mwS9UF;T-evo%z8^RNik_EKAdm^ z@CH)})8lV!L<_Na%niT`Mq>W+`#8Cm-dsHK_%7hU(HeNC?_I!p3oy@mc$91v4aCX9 zL%?kpR>SaKAdZcA061|MW~0(0WPH8WqUo~7fOp17n4U=}h64bwcoy@>P6x>)yEdZy z>odUQd^NmS)lR%O>KWkM&oP%hPbFR7wH5o>Rseopp@Db5e*xIDK{#8a*Dq5@PXi;d zcGg?K9~xoRqNhrD`-gqwEnux)m~UDplYJ+QMb+TXfE{~l;Pyv80gj%Ex#f>NWc%X| z;+SpU0c$%|!@J*`!oE=nxcf@XdbReD8B02e`_B9Z9JpEoC(rv0_~L%d{f;FNlVnqI z>}G8RtaDm5Y^7^1rVrIt{Qc{A6SEiK65B4~m##Gd=iHVsedC~bn?X&$m0vLLToOw{ zy}F7zCA9%xtJJ_B_SXg+);fYM-H(uH^8Glrfg}A&!6Toe@YTy~=jR9Aj!0c7Nh13nO5C^6;1$;8I8is2!5sntX!H+Oc*tCVH z*IS8(mdyb-EY`p+Yc>bmqQ*wH8e>DZkShy%h?`Cr0KQWTs}|irI`YD827r%s#$35? z3-Ps$}9ynzwm7lGCA8~eVZmX;A<|2WJiQ#O!#S9^&qHy8uwghY&s)0wlS^|zbfVqLoYI5Y9wRrbI z55O^pHSkW~9)KZ4eXWO3-Fcim}i%)B7PgJMMbMVfUi_( zU{S9RV5fGQ+0u=AzKSfJYc1}u?+5t0F;=brTa9(i`vLws81tiFtH|a_)}o!a0JvzF z2A(=g031FCb79NX#7AK*n(Pt*&zmPi`bE=I@cm8u%Z2{Xq#cWc4De3gEhgkV;AmH(38d&ea zK)@BXx3JZ4{~JJ@j#!EPD+dEE(8H=l=S)Ywwr4Ql)!i@`ZCp$qwy+ZKs)qvhx6;7+ z=|cgxn1Ffxn?R~;^y&n__Z1r0D|-T9xvP{%FD4#?&BfgzlK?++uZHOxP~zZ8fbWK4e!6He z+0n3z_`<*eux*3}c5Uncc=ln;Q+F>WMU`ga=bR~k%a3c|=v`9)Yu(3Od44gmSzspK z89EK{v_cIGpI!jRRAGKlwwMTg&BPBE907mU+Q!xh?jX1k`rfU3&=Igj2h7*)=928s z9mQZW9q=|&4Xm)94mfWZ=B9tW$hZe4;?`r%fOn17z>8JRfSu-Hb}#WH6UUl}+ss@5 z>n+s49c#M){=NgVU4aMb*~~<|7~~2#Bc>XrS2B*9TmgsYVD@+PAdBy|7r#873E1kq z2G)Bp6L5zz%=b+^NL;3o_|w!4@VyERoY~e5uu^Y3Tcq8MJ;;q-MxwjBJ7AwiSlQCi zOSQ))?tmv+VP4$OgM7VZDC!1z01oV}fy3r_0Dd_ca}xs(vSMEw@olsx-~vYte8kTa z@XFGmM$yI zgUFH$M7x1LfPWfdWlKj#p489>@InRVw#gnur>lWD@F&H42Wj9X`o4f0yJH@i?LkKW zY9ZR*^aX6~T@BM~{uTukCx>Icl^K*&a2#{O8xOMgh`xBq zY#!jrnHu<_(LBKS3NVN1coOZN`l9CzivK*RhUw=N_>d0RS8E4b4c}&-Cs}LOSlrs*4{+r; z4cxGsA7D#=%#TD*()v>)G4D9V;ei^s{Sk_x=rG`~i>G$I6zDPQ#&}KVUO!%w}Gmq*>$o;_P6G>k8E{{R~?YL~-^s%&&Ys z$%BHr;<`MF=euZNuWX9PufjZVz9%_+Rag93b0Odsp&IzhZ;D^1V0M}3Nv4g}70>mj z_*Oa>uepV}*xQplHPRJ}Cs7=%u7>F+`ellRFmlUpm=Cyll9-pZ#7oO5?pvjSYp0F&Xi9tb4@%s^q&l+Q8OGigWY&Q_|TnA5L>QqyV$fbDTFbxdX9WZj~Y|Mk; z<^J3i@Jos-=5q1k&6pbw_ax(tYKjHlC|8*jPhvZPV$;1`Y;_THV1);HZTo|Co=Wk(Yg~NgHRdpQhm}44P8K*) zyzvtk&yYp4rR#dlgY?M#PG&k${Mi62Te^Q6_^U7Gi7F3r_~v&~V>-n<6kNQ?8T0nz z9>f!Fl$~REjC(aqZ^7Zxby|zL=>ZRN;N%yQ>lSq)}8xE9&D$0Tp<^~`GNUHqzB2K@sZ^1rue>A3|k|%8g$M$jnzh& z?IS$Mslgvf$X<$9nsRZgp_n5>JV?aIk7Rrr#YUsKIKv0C+fonGeC9{8=@7*o7FNUb zR%ga#x*B%dF<1F}kUkyW5|evu8Zlh_I16)-uLt?l_%*rxoZ^n>x!Au1^UB#CMe#jCw0d>e5MB(u- zOX4@3;_Io^FunhbSnCSr5-$(Z*1eoe@T1t^4i`tg$E=v^LH3U@Pq%^67 zoXVkixVHu_xJjq+bv@>p0UpG1M+s?KPO;urE)G9}c}1WH3EfpfW>iwVJ5vL@HV%N1 zO&?(Xy~KkYOfDho+Xn#dP+SeuZx9eGe`8Kr;X!Iod`wpNqPU>e?tjPNKRnI^b1WQI zzpaW$tU&P`b1r^49P@U#a1AysB!39S&&O%tH}-VSA@ea;ZilmIS^??eOmSEs7aQ!v z{AD-nb^ZmUy)VT}6S(-W3Ufe;2k~_+ASnwd*1E*SL(4HQIs$W^SwLznq&V@d241+0 z&bg#sJX<8iNe}YFr+{pXqWDi!tZYZ3U+W-V*aP#s(;h@0e)P*>KgFpwT-;y^=4hn{ z@%nw23_C>eSQjo%UV*s{VD~R~NV9Z`XN7XHVjt#En1(Fi4q1DU;x*}9eD6Bu!I^MI zvb{rwq){B8=3=kUm@Q9vkT>1#kdzdPZ~xN3@bwuiop!4PwsaP-bgjDHA&;(7>~D;f zEgk(j3UO?I%v(-)kSq7DlRiZhPaVd^mL8bDXLyh;hpv*j&nUh>my0h&VBQ07nt@4I z$kK9(m+jzU=M2nF$2`c|&R2+%VWXUCn0~{AbN*3?`8447(HF??GCFeCGA@qL-osYo z1kAa>@jSW0@J>CfY&HIk+|dm4I9O-f;pd1J!vn3jID0haa(KDRZ=NMh*=poW=Hkf< zF+0JIv@8BB$u6dI9==?{^hVjgX}pe+MqW6NEZK3EjC?}zr(`Z(bsqDX`~GBX!dWt$ z;pW#ROz)h~ucL73TE4^_W#>yaPRu4V*fiWeRU7#q&S;d#md@+&0&>+Ri*$QRr%|^h zR(6N#AGYg_dD)CbB-7?Jabq|{!NtXnm~}E1llfON$s2}E-K$~xtr*UE@oLOJCkK%C z12V`YhVO=Rag#L6Uy}n!^9ILA9kzkx$2IV}=7Dge?7fZI@lpW!pmUTo)(M0S99PK2 z{VOqd$`2r|HXk8R^(n5Uoy68iy49IMaO4Mun4Dh(i!~R?xw*_JZqu4Hni+g2a zp13oB1l39w>wbMe-3n4h0pO_JejKeZdhN=Gg> z55#r#i_gYmc3mDq25e3s?(-?Wkjljld6?s(LdYDS1hUzWV)xtC zF#U2adKcZm_ir$p$A=K@Cb6Vj6vc}xxp+g`v#)Xh|A9oS&REl-mVr5JBZ{)T% zn2RDqNaUxTWcpExlLm3|i5Zv;!$L?*$WCILLGd>)E*`lK^SNaqq=WNLvXkLETe$ee zA;B=i_LzNpg^&aKTglgSI`VjPE*@luIk;^IS=MR`aX3hE-Z%-ByrGb8(len7_3TClOJhq{5rxBWf-_4_~O$$MePNg_BVSLy753 zikDPX!*plDX*jk>VR+BSFmlo(ghV(~Ji{0(Te^SvgNS+Y!!S}lW)=B0o#Oh#xOm+x z%u#2;$jz}U$v1{S%;(~EVVDo>3nPD@1e1wu8UuE4an@1HE)iiwo)JtcXV7U(&*9?H z4>7m)4FMjR9UNe6R^?@Z?61Adq%wFo2K;{C{g&J^!m&cy?FVJ^^t zulY~SC*#a0{+P_gg=a8td%uB1JIyEa8IHRqVfs@4+d%*4m>;fKOYBF?C+isA|A~ur z8>F#C+Af5U9n^W~0nG-jk zJY!2Y*IfhS1=ZbP%%2Tb5%KJNl2(td#@p~}m|is^cHfUV?fFU)YdV`WsG=8vJC1Yl z?;DuSFRvum%V&{6Unu@wz{T6YV7{2Kl6+FTlF{!ePSiSpI}%;zf77sNjainmk~lwe zA)Vh)Jk*qnb8Rul#IGdD%U#IeR}|-s;^L{Em|yQ&N$h62z)vkueAi#X^ac4hjZYgf z_n99=EWBMvZUx0nW4Ji{1m-)n7Lo3&UC2F#JDlfYqeqxmTw6fK?r|a87>=mm;!K@` zY?1aK^dqOwxDa=Sn>E79u0`oj7~?BArZeVaZTyI3`zb_V8)({_i(iew9GgF%WU42S z6>RB}9VJXx;@`;27h#@W=}CrUjwAD5)72Qhnv0voVZN|>7U`H_Pg37fyg!wT59VUF zAK^;O751dnM~cVX=Hj8RFeh5O5MO7@zMY}C{U8a`m7xFN$a>Q;hbbqMVZ@%KouoL=i;I&( zq>-J+6H`Zf((4Gt_qK3x-vgKri1s98sXeK|ZYCd$P+d!Rmn43NuLjK;gCkYJKFz4bOgE0p#8bBtM z*^@(T8vDj^akn{`jYsz zBh|K~2Af8GeXLslJF;;%%-v!v$bLs#@`!CqA@O+QpWnFx*zp_t1?G$c#T^d$}1zOi-(7uP$C z*}%C0@$v0N2C+MVy>hrXQH^<4od%@M=pJO?VY-VRFO@L;m7IUm=vRe#?0}l&=TIwh zhT&;?NAVc^Uz~4@+4<{VVdpJN@`~YER$S~k4D;{Tzl3hPEy*Q@XH4eezjHBfH2oIK1 zm>qqJg|UY$$vTFIe&XWkddJuzt(aUSTs>z=HZq)LfE7;WI1PLs{A!8$W=MfB<$)z> ze3!l`lN4OMX)@;d4<8CyZ!F2dQi|WZNf_?cu?@tLJ1oa+G3Ju+L)(fBVizZ$!>eI> z&?3%C#ys|nO0b`9M(jV(kry22V*6{DTb#-g`pZm6zfTmmDCFWdA2GM7%oOHSwkPEb zFVs4YI}+St5&lhMr2*z9FZK!TDviifh8vl3aSH|JyvDnQgR70mD~3;x;^M<@n7bG6 z66#MhB9|F%y^xECg=6kiW2aC&)QEIrcxa4-;UciwoF5;<{I+ExShA}E_w!u5 zumH2$$6&#CQhPFiT_X*z;NtpP8ElcxL@X4nD~w1vyX^Ve5G%bhuQrYSoiGPKnJdJf zGa^md%N=da#lk4e`#1UswX%%JGKPyBB@8F>Y9r?_z#KEdUWiC+PYl^@@Oi7b*ee=y z@Z*7kqJc3{me76ULn;^Rp2J+=DGDd-j7e>F6E*BM7w>w3xv5uAA@O8;_`w=Fa-T{G z!x^dCoGlxkU`y9?dsE?|r7?+MBi}T{3QJcVU+#r@n^05OI@_4^WVdH$4dP&&eA6qjUo%}9d51Tv6S(-uNzCN?oW7&}G$A9}(~(c)aq-Z{n4`CB z$XxKd2}v}jc@uNv ztqm79u*cjk$@p|eBN-XOZm@TD(ZG1OXYXRn>Yc`?CmYB}z)(7}WhfVu-I%jI+MW(D zk`WuYg$>^wr%M=K?ku{_IP!xFnAgUcXI(dy5j%EIW~iEry@Fku?4Hc$ zUtFvs%VbNZ9=|T@dM_DK&!W@tF~&+yU)83ut1o7w+Z(g$3NrGEVc9S)?&XZx;O~~K zZMHJd=T?M;d|E4F*34+;YK+c7;kk} z-o<=>dQD~YBpGS2mTutbQZC-|1M~U*y2`WDWMsk)immic|KBl)bHRhC@!(&;_M-qyR6q!mclVOVh_c293%`UbG8~d@&q5udJ1#pJr@~qNTT@TGA@3% z4RiiqqO^6Dkrxc_Nao^IS(xiu4OaRC&R}@YH7;&dg85dXValE}Wn>(~tv+$_(K=ad zk$#*Vu59EcBV!ZkoK*%`>5f!w14nkpd|b;%ndu=TE!b*YQ*d#~1kBxjFH?qi$;kQy zI&v3xE?&F@vv&K{N^2h(nayy1I2Sic#Js=B8fDsC8Cl7&|8Xu(y^OiT%Qed7^JU~B z!*vR|SbUFJ=(Sc!{AA=H!|_^5+>zjds@iJgH^Z#gFiM#VBR66=#*~Za5X{@WuEvp3TwHf1W_fUu(hxRq7{gQixj11x=5(*U$}6yRYZx9C!^J(0VAdo1lq2TI zh%KA*)pJ~YZ;^-1-s4 z!&h^0ZWQKvT4$8gJY}S?nBv2!Ts&EYd4z7R(%xN0yh|vaaGQ(YmtnT}ctKeS$6z7D z4Jx^KZM__}NV~3FRF=YdBaPwdhFIxu+E&}Zjy*8XX_=?&4`-xa3~LYK;tU7O&L(-v zuhV6uEyE4Hx!8UM=C<|olvkZ(ue%#ROW zR6d3C^FD@)pKx*W&zLI$E-GgMe!{R#Efwxa|GOH8T4D~iy{PO7cniZ%yK=E@f6OE6 zUsRe>%r@}uI1PNTO%Uv&PuwvdE4ZLMG*w2f>IA_ClE7-1eo#leAOdqr+6Cp~cXi3H zrW8Mm=VILq%y(8?P}VzKi`;{MAN(BS6)xUWh&g-81*PYP8pNnQ#nx}RxUcpZwn)SK zUQl*hq(dfkptz_hR<qxPl z3m56S|N8Wmvi@Ti1Jn3StvLaBMyk;YJ zy3fVuDlm^YnyYNNT$@Z{_-qvyPj7UVEnVL3T;;Yk+T;jZ4Tla`HJ0w1HRfiUa+UKp zYLf?So!<`Q;&4aI4OhWxL}?QB^>n(|wO@_dXK}9bPhCBt97IA$(rwJseRGwU0veO?P85$QtA^>mfzv4ahWYgTT;*}oy5#c= zif8DZ`*#ff!z&FjSHYae1l1z_Tq!QGtcL$>p#C7t<|}fQ!Hwz@f#HzJT%7KOxo}Oc zva?$wV!^Q4axNCPV3vpFDmyf9LY6Zenasucr!cpLS1|iy6H?4@&ud)l{RH!Jom^!n z9T}m23Y?)nd3S~cg6fH5O$;l84+hvTu;Hp zR^u=W;knBGnKI(X=G@Aii!TRYo*$X3d~#k!>N6Y=&c(CiG22GxDlcA?k?{=c9_QlU z7cmcx%T>DO%7{LjbNxat-u?#j;)Gn~$s8Hk%J4?5+=81uo$VW&ytp`eDdq>m6O~be;F{l*z9?i17h5M`p6r;Y zlq=xE)r?~0DK5Tp1@j~CMCDjPM&cQEeZs{qA22TuOjI`S3%4vf(~&3F%H!=wmCZ4? zU6-h|w}wkKhI6`d@m3MD%Z@~4ZVwsR#IWl)F77l7^Wpu8%10J(Ey}QeAQ$Is!2B^Q zQR!z6pJCYs{)y+}2}d#ay_Kk3Y9=Ey**YiXaq;^Hn7fxID!;*vvN-k%j(f|+tN&pB z^A(n^os4v1_-xZlyrpZ^5%aU!Ny;g$;ILwNnhh5p8-e+Lvm|9`^Z&!2XJ}yjP&3jG zbFp!fa=1PmRyF7=7`l#&pYFuGt9z2NXHyyJ|A}6iyQOn+z!}WMCP}$Q1~?T+KcSpiGUvGsu zJ`7d^Uha#rbQ;!ux!A)N^Qx^$${&CY8Mbof;$I$^TSg@*bDGIW8-@$lXkfg1xpgDv z&|OK&bFhm(4x-bTd60{{oWR@`a83)jvA}*9&+;A@Uo67xz9UIF8}7IcV0Qv@e@OWM zZaU#Krs!N{i{x}_tMVd@Y~wB6qy!!^F7OY0d42nAr<>K{YFz4T2 zqb$&a)nFqp_2FWZMVK!|tya$d*@V<^r6d2^#>FRNG52y=rJP&RgdAo#KdTz1*UvcT zQMs7QQ&uW{?duZ1nRH~k5-u)(iFsn@mC7DvHAy^Mx-WIE;f_R??%&8O8e>j58?3w# zszVO4AC~sF;NoU|Fb7T#R`%@$AMxDjG=e8`ahen6hwoM>OPsWbu?NLhmT>Wa5X`-G zS150<{3|T;qjDeikk!t{>oKRo{q<`ve{l!H5$ z31=8Cc+bVU-!YH(4-oyX!>a2fwXEEmQy`r;h&HaQ;Y)4x2 zry8bTRpM$`*1o|OX+nGFEYWs=pu=##j#$|@HL#HqzGRMh(cliJ-`=e)l(7Bz&WQiP zt8H-PspByZ{8ipBf5kSNi}UE56aBdOTOj8BIfeaH&+6GcWFyzwC1Kb&8#)&pc|!u` zw8>j+2Bgcf#?GZ9$DjER*AU?UkcGIzCCpYIe%SQSiO;HJ2dv$53DcFJuOi}8Z!zbM z=qaT4?w~xwey!ko{hR;oNCMrN5Kqv@TrkZ^_)s`md4Y{Qzo&%h3qr3)5m(q?4i60# zdVh&mc4WBCR0-3ah~ED~yxawIrNMq-#HVY@^X&BXDpiu ztokBh`U42?6J-)E`i1#uNhk7dw?noo8`-V(t^byeKBQT~^NleN7ZqgS;HBAX*pZ?) zK*IFr)Zj<-CER2f=70qbq{)tL*{#@_e~zbw=}&dS@=18_T+AoU{fT&QfA(P*`S0Jp zJFvAF@G~l8iM}X1^gbJG{nPf%=cdJBzu*2vRf{sn=LPqF#Nmd^B*Pb zSBiN^y#vJl!t?CQY>%m`a~n6C{^}F_rn-b{>tQ~o$|T*s|H-yv3%akngz2yH!P6pg z@O4eF#GIXdnd}~4Kc_3h<0eX&{WGFRy>qU!U!G}sMZ)yy7H~*N z`1@7NMa>$DZDfOUy0G(9>kks9k4c$PK32jJA2H9EW*{oWi8=MzIy*JLgG&dy7d(Z} zMZ#tVn0s29h|O!x%K6AfZYoNcK3)l)Pa@&da?ICmSc+ML{Bu^ak@IFs7@i_4!oDcs ziEfxap^kNUMV*0b}R=kI_)}PE;3#zUhz7fvwA6=^Vty+rqBL{ z-~E&D(~+2OyRR41zvSfLcYD+QB;46?lh`lgvV<2cz+B_a7V*fw%Q?&0@9vAaW_gum+ zexL=U(}Ts{^+d=9z;hTx=F(DtV%gND^G>DRAXCw(boWy+gqrTiKVX$hA7rhz(_7PU`WGng7A0t&kOX(1{kEJ1^ zceRwKA$dL7tBkeOyy&er>Uw!X+1R-tEokIdEsYQ)ty6hdpd6Qruuvu95^JdjJmWpRk#HWTD08~Ld=T%@?~ZfRue={9nBP?Ut1UBH}I zV}N|$jzCqHOBCOgs+MeZe>wcDm4x+QBfhfNPOftjQnM2h-yOx#X8NfYSHItuZ&zRVVk~~14<{!Bm0J`EPhaYNRV*Lnv>-E z>FXqXcRFT2tLgGLM&T-7?InOsT_xPw!U+3 z4ktF%9pfc1XRU*nXFZ!E|M6~{YON{7wGT^pP}m$fT$@NZ>MmyMOa5}Jk|Kafu--7DeE+c00wh>)N0Pg9*0D2|MhF#IhDIh>3o+$jt5!)sgQ?FOZ* zF7~6?L?vPR#B6v@w1jh>Vm|UVQr_szQPuw56rU@TFnwb7%T7mCQ)kf^Wqh57Y&FdF zqvhjQoKSU{M6pvntXk2#cFDc6GbH?~8|DsVx7?}DX_Xrcp{u2~k}$mI%HP;$N_fo# z%*|&d%0Go>s}_1u9ONKjcw3VDyiiKmUa#D!C-zDhmQ4;%pq5r+=w-}y_tWK1H|MFIkED3ibqO!gPnTcYb5X)2 z?=UC)I3{0pe6*x>M}aU&3}JS#YG>lJH(v%t5(lOrOQ= z+W4V_z3*ezNw_ZeTUey}W}eLrw?z?#wHyS!<|N7bW5Iz(3|X^2ZBD&d&_C=Ky`IcBeMRdVB*pHCw)5?;F(v+GnX#k@;jRQ3!9rAZj>9Vi_7eUaYL4XK4DAesBNrR(XUG7w~UT_NFS@#@cNMdTe=8q%)`5wD6SU% zQhi_}j}aui&A^1cD0nGq>WF!%Z70PCyI-nLyXnXwE)s@63&Zve#L88elg-T(TOEF? z%#Kj34wW!`Hh?Gd{*;cv@u`>-O}Z#dSNu=~oThm3VF|zZ)mhQl0p1?j74fTEnB^VJ z6~;c_ReJ1l*5JN`;i<-oH}>BpyyhEb>yF(Oe-)J~y|Zl2RT8F;Acu2@bOtmqEM`l0 z#mrJ+UHhBLxQt@+4p_B>Vhcs$;BOK>G7$6Mx;+#>;JoqfE5-MQNqEg`D}`6~7YPsb z!ff)pr{d;-&#Fm(D4sA+!nZ1WDth+(Ea7LHF;Dtot=Jm#QMG`*(|p?@;Z5hQ74UbF zB)sSp=FK=Q;n_4E}=w1C3 za59!~a?Ph~H70Eo6d&B*s6=*|rBx5B7JXj%ps+U*R&>R@$5m8pa(SilVi%o>RuXP) zAu8ZKLBjX!F^@A>C}M0XROPnxeb?AQ!bLyiiX(m%(#4Qh0OtK4`YU$Vc&@tbPVvp< z5{|vlU*YclT*BJ%n7xk;P?+bHs+dQ9hywl$mV__MO4!obd>*QJG5nD# zVI9S>EwO6teh<$)Kln&hx|d#|I`_jo^Y}2u=iLP=A(f4+kgz&nnBriYLJ9wL#vCD^JKoTXTnA>oLq(TWA0cO;yB5A)=)V-+#qZ>Sv3QGByd!WWIkDr!!;DdEXK zFE3QH%mz?_-lqzGSlSQRQ;3OKB{gu5Mcf>Xf}3GbbV`BW2U zMc|nOsxlLbH#teT=*M(8x(`a2EXADYGDESVZi*_)g5q7PCA{8th64WPkA(9RG0XS5 zDEd!KR*BXWo25y(&w3Yy#p7gY1AVVxHY#;htaD0GU2RJ7$~zJ+zwN3>AG$}vIv+6i zX*)~tc|)vfsW!zezDszU!7N2F0U zaE=M)bbTL%*S*E6+ixg-W-ej+By@UP2M^c@BQOtZ;H&8H)mN4Hnqr^v5~fc=r#FnG zqkBH)Q#I!*W;na6)GsN16)53^R&y2b)OiW7-HAEn*IdP>nNF&Q6%>~xNLVPI3#VLX z3AZ|fdG4)wio@q7sOGbgoi9mvM)^Di+y|2I(Q?dZGUh8zo*$udenm&F@lL|@dF7w( zj*{@O`p?-SO%3)_6dDgyRkD#?^s#EuN08IIhPZ*HJunY(U7(n1W~1_CbFL#um_Ah; zzC@7l;whL{oBJzlBCJ$#a0b-XI^`l^`k-*QIVa&p!I+=E@>dLxGE*I4BVP%XFnydi zTqjAV+2tKtU2QMn{x>jJ^j@UsakaV1<0Qo&)Doso zG={&QBjNndm>(1_QhdJMK=tYX#gSDKrqA$&hn!1zPOBGe=^|z=R`?vP37_RC{$h+( zi#`GNu}N(S*RaL>v_^oU71h0p%$v zEMqPJ(rd+==jEm^nCjWV~hGAe77YVi~7YA=$~YWisKYa??!L653iC%aTK9vW#Y#XhfVX#8Dz{-Qps~) z5-z!Fn#rS+uCA5x)(mBY*`O|6#5|5Ao-#ldN&=KII0t>lQ&tr$`G=+!h6=7_1} zBMk`K9-C&GGx?a=!2_$&uPMuTqe2?iOeMGJPx#{XX{M8x`xxBiD0k|x3^J75gybi4 z3ESVEW?HeXsWRLJORl&ygN%uAlKplQUUGSwX-wg8#R7qaOw?hP@tKXM$&p;(I^pq8 zrkR{7yi_W{#euH@-pe3k-j?JYUkR^Eo@QD$3UZ)QZe#mO#t23QSaL!5jupr2X_?wm%NHiKgp=@lxGTzQ?Uk{@7nC3M zV;NKP_~~1cgZ&9Roc1#Q=(7n)sP^ZO$fQS&hn(FW;3mJbFIZUzs{rO}N~$(UpOP?q}$!ZkX2nOc3=B0kE?J+2MQ_#%eifTi~QW(Z;b z?*mN@%Y=)u-!OD*Ca{dJc+akdu{?h6ae0ju-7L{D`AmQsB z`RuG`0~i|u>`_7@Afsl58W%4$gW^Q3d{Jy3$LXtxBE-jG_jBA z*~9%J|8FeWKKDDi2emDIpgr$rIk^(ywD-MCb-x`Hi=@2Om1TIWnegkfROhMf33nOR z)3oLH5fLD(QKT2kotO56dHy3T7xE^Y^>%ktz@g)!pNz)InJmL=2Rvbqv%G6PVTWej zOjUx+B0 zOC3zrvYr$EvWZ?Zu{^C%M-!wNS>Du#aEr?AOwlxbI`J$QI@1 z9azQ>bVjv)!gAZrgjWUDGrfBJMEJ;(&v>)E`+XhgsFGQJ=1aKxhB~Iaf0D(pELifM z4J>;;t8FUPCxr(%{+kHrQEQu87*a$9Ic6z*ie(sr;Clnh`Ogq;5L?rfW#Kd7D_;c? zp0f-qaBy0h<(;nxXMI@RG+3vt;E<(R%K!x#(SgIOLsfUwi$%BK8XUy9=`Q64&n zdrW3hei{~w{b!APX!d?qE`2!n%VHpOICf6KkEXRE#yd|)->2#4aA!K473!_}WQN9|>(+cIwAkVKsc-@V>rko;ORIP(0pYOu5YmPh_LRYdI;cRMd zlTU$kvDy{oy?!hYh{-8sdL2JLm9YEnoTgk`(}Y3F#ka6rC@QJ;$Mp{Ls1S-WBFUxEV9*+Jo63V@h!5LPP)Dp z;c^8|>4IM=bokkBZ2Tk_E=>53gRQCNqF18PL@e3TnB|MUe_-*_OP2Q;2oHGjTZFBB zDZ(b9Jk*nAc##vQKfhqP=^(;$j(rzz&%O}Ly-{u!#4;>575IsCs>a;~g!_7Y7Jc>S z;;awKPxi44D;{wD2FsK76Mj(my~w#GRaEvxx%MrVvEkzy4k|hK9m1b?riu2Go{2_& zD1Z3DGS(M6Mv^!EA{;XOg>Y}0B7&!)98&HZg$_knNy>7)3WS@A6k$G>EWD?qY;dvix%mVbj#R;z)~!qUa$kxtPi_KB4i^MkTMY5YAidrl{EIfyib-IWd`KSbz)N zzKvlr)c1K1s}Xr@~K>eJNU+lA<+rKMNY(Kugx;71BPXO zcUd0bN;shLIq`1a9Z~xtmi(~?%dqAPS2_urY5v%g@PUG{qUh3F;*gYA&0ra_Q?R)7 z2Fr_P5?=n@BKi)vA^OT0{l*b2*B=lgZ~+sQTzWgOW7 zJp1Cs?5vo4IdX-I2#!4>AmztJwEIA~)XZq{!Q+zHo*iY=XO@3OM#Cb@ODsQg`XNJ? z-fo}pIeS5PooeCGn8w}=vLo1wgX3d@ZTFMuW6`&quUfpEgw zd7^ZlJtEeGa{OkNaTRHq`FmI%bc%4#E3-w8;GN>F5#^z0S%x%}I524!%fFu!jymlx z8Z?Lyo(7b=y=EDv;9$911k20w{gR>kaBiYFv3slVZG`fw0z@%W1FNF9vFuWxaB;U$ zVokP9qH_b3t2JgBzB&x+`8Khv_a)qI(jc+F$9i#1<}^w1(w3y9m2~_7L0BLPQ@azuU|5)vsM)DdY;4=U*k9HL9Ix z@qVdjEbF}RCd;t$Tog@Q#&XFogmZsuAzBw-Bs`>CsKq{ zRsKLRSXSd~S)w-Z+5opzAj|Dq5Z-^S9!!J;h&6RFbQ4;$JOkc6`UTHnIe8@E3qxy& z3G=3j+;vdCHI`*qfg^Bgh`JvC<%FZ0D~pADy+v?7lmk|=3`>k)wXP4#g^m$k;9Xke zv>7elKtGkkrm~r3oQ%XZ*HrSZB*G&ciVEi`gT$_nDDQm2GOYW82i_2tO^V z5UzH8#7~)8^~gaK)_UfLAJ>oNJ5>qK-JL^hU)M!^ld07oHCb-oFek3^XL({5!Uq@G zijTY9#SU5W$?h!UP6&AEW!c`3aKwX8#*I0fiat^vJDp`1D;OItY{n0d(9MLGZcjBf z%i2)PxP(8jOgPIp_YCv=EY~|rIAC0Y@o9VwvDu7r*hQA%`DKK(4$D_w6Siv*XZ)O} zk|=)!<#z8_h6kPz=W_WWUEr?_ozqXVam?=$ViRO+ppz*=6dIBWTbD|){G$w5|N<(p@`axvX#IE>X;7|k+tU$8~&y^-XeHwhPr9Ao@a zvuKd{{@!XvVrRc_e$8+%E)<9e2HuOV&|BRMsO@WGACl?A7| z8t2GreA8LR1Q+b6V0r2j!smw8Rs0XsG#aEFn#wXB77qWh?3lw=M&oDRK!e+o?8cb= z7`nlEiQ-`q2K<^fRby98!sCtEsyvQY6VOx)W|+BeyEd6O>3P zAL+v~<_6&pSiU=ru*>Rks{8bvhA1i53HVPQs=^-_sN`{Bggd_4tLE}tU@j`O zWZT!-Qs=s@Wu9E%6NPV<$nv1cLW{5b*-l4UwyPFofg6rxm%D^}Z(MEZGHs(JT(+2`2P{MLvcO(Jmi6C+ z|E>+Q98&jLTFU6p&yq#P$ObZo7T7w$a-WKXle!$RH2z!0svz5`PUVtceN*Z*;Ec@3X9KSrf zw(wSIEm_LZjabGN9WX7!a-rUYyF2C6YIbqf-bZ2RW)EZ;_cg*(o#kD#2#@?#NHdhE ztMdR*e!ug`gYx52^)ovZd zYBapbGA@R>=qp&B_>u6QO;xljaqimn6DU9W&N9rvY43KnV%fg9y$s#0BegZBJDs)J z@=@wpmZ%NxYlPiuEQdBF9N43wcH>?zt)Ge|=WNX~*4LP;C(HGQ6JFO!Xwx2eYQ<#9 z2gb6D`x?+AejOcE}s$ zBH=7Uu3GzWV=2oEV+ofiGgCX=aD|q0B+BYVmP68~YqYkB1A z8RZ?zZS&00;C+te!w%VH=$^F?)E-q@udVUKlAjeJYIAAZd~Hzvbu71QKzR4-h1%Ng zq1xzyC@(OwjH?9UYyyok_o@8|mtM3~%e8BZHbYK}wjaVWy!dJVb_Dv*CA`2TL@RtQ zOzS20X4MU5x#OVa8uX-Gvg2;T8_%uMy2NeQqUB1I(nnan`gNrSFWD^bx<; z_Vqul<&YV;t^-(xp$6Qrr&)IKCwzR_DXqZSvs$!_#)o+| zUe)P=W>@K^R#jGG=}MNLZojX=+#bux`v{L~_E^iFa!V^Cvxbf_EaN^yT;)$C``;p* z);2|pn{Y=vBcl=hm}Qv8)rw`k!*ZdYgufJfp(~Ulp5BXO5RnD z@N~yCZEyQT?U%eLWoxnwxgrf-D_J(V6aI1MtyW_HJ#EWJY<1_lvAnhTTiDqeqV1Ek>xHl@_`Ho}+;E3mFG#jm z2?uQcsr||OP%Bm$<#iWW#+`1sr<3H+WWpy_{?!KmdZ^v4g>tjEEJIEJdeMh0*Ugzn z2C4rZTmAdPN80#$C?6FsnLWFIhh-RA>X3$IS${`ZTa#BW z)8nZ&UgkeH{bm_<73$dXsN^0+^UBbTneL!3k9w-rmrtu!6^X)t%0b6HJS4v{65cl1 zQNNruMe8Z|ufJ@|GVChMATJm~c#U5{eRSaz?U|IvOk{cY`vMu{l8Xtq>t9%J0VR)7 z@S>Dn$MUD&g>*=Ka5WA^6F$(rsP5&GqNOxJIbLJgn5$?8xm^O`7d?yVP0FWehh;R@ zK4baMEvF3fvpg->M@S?h<^dg&|YNO=k{#}P< z7?n$z1}FL36Mp4bMlTG}pVJ%bJhL~;FnuO33dy@B5%$kkP7k}0tQkh3Tyi$ckl>Y< zo8;!}375=PLBG{7S-U?8<>?fG<+uMTG!wjk=*6_6Y^ zoAAZXHT9s;Nm?nHk7dctj<5_{5OwUnNd6U1 zcvj9j`mW0Nwc%2Jd7tH9k*+#+j3h7rM0m{Ox_aO5iP~r>ueHlh4N3K>tK(*OdO>h0 zLD+F$eZ6vAg7$t3{=h<2ScVy19XoT9^=5>Z`ZUz1cfYGOm&5p@ome*JYN+F5g5=&K z2#;ypSpTNo)*|J5il;BjK}8zt)q?J@oW6|k+cF0Ib^lx1H2DT}J(OiwpQ7W|e=2$Y z5yJhiE6_x5Xs1=I^TX3D!~BL0SwEIbJ|JwrSm%I3!1NedwfkZ9FW}&SCS%!1AfMW;$+- zBl&43!hJ8c(2E?rqcK1m)!If;S;0U>PuUk);>tN%x{*T|7@c}QjO&Y`3uO<9sJx*e_G&_)?Lc2DiXDU zjD`Mh)16;K!nr~_=*^Qg%}dt#QCpTDb?TtMnXYS;vB*AvaP=CU^b%uKtyl%Dv+qQf z;hkHLm|$Uf(>%f(4t3Ut6^qe!)I<6G29`Sx>a61qJx+b?A$+Qyhi+bZObd_+s=KFH zh8JEPPXQtM%5}n14|UaZeL1WhlBus5FIa~CiaMl5S@!xyIFD<0-O%BnRzhGke&s7j z_aN+7)a%y$|LuI=OEZq@q4(XgU-Or#uO0Q7!hS{lZutLi=L=~`cuUn@`uewfwW~7q zWgfsXtS;8^je_c2eGK7(JA3QXO}n*NnHf4dhh^BWs6)DrWqk$VAe+AW&ETEdHklb3 z63H^`SJd&XjY{rug0TPSe)_155!wP7=K|MQhNOv(C&ZAP{)q4hwZC5a(l*Ucrjgvf zvJ4AD;h7S~@`7xIWRSYs4Ah^V->jXGX{3jxh}yuCQ|OD%V6(=JIl`)HP7nXHZ*1*y($rxLFHW{|$6$7=0{l(&Si z3=43f`&z?t%2vW3s}9ktxUA6PUGZ`^I?ggI?S&p`CEqFj=LwG=I#j>>eVJA&FUpAz zSw3ERD0DKxEIYg*{Ce6jy-?s{t-ufL3WnJiriL_Z*f1U6>Z#w@S%~o9@Zox~1`D(~ zZ&9vWon@Fg(f{o#Y;GWY;J^qy_n~=OUAfyW)Pv;%lSV*S5XdFp_9FcBz(_r+Ux2pn z8J6ts&+>qnkvb#-IT~XZ5S|b}O5YzfO~vkbHGa8a7GtUV>XV$vl2#mGjQ ztGr=%{$zRGxJf!}^w(yM!VSi~a}||AN~r9u|2P2CvpuoSM-wT5ZCH zd)~TFgo{>t1j>cmuzdBaw+`bZmgn^(?6%ZL_xe#*t1|)RnDHz>nd$=r*9t6`m`T{L z)MS17S0_#NMp>+3d4_2+40}qzYaZ75XawPg`egn2h5TBvbttE*EW_j;+=B&KZgYun zp4Ps)X?_kZW;eTnD2oZM9iG-);&#CO%tW`Vi_|&_wv@t|@x<8jmcwAEDg2C(E#hN5{E- zl6MRxeCo>-eczHR7X1UtH)gO5+a{qQ-C$WPAsp7-Pal$?S_b?^d0GU^u$2hfMl8#> z4-$^v;HURIyvI_-ZU)H9F0l-IEOp%6SfbVpsPlwG!XIw<=}z}ISiGE3{`8(@*kg(P zGs{_Ripd}qbn(}V6D7P@N3>&L- zSO#K=n1I!&(}D22(f;}-`}US{BTzm&lx5hx2?N*OEXR8jPG0S=r);faN%Kc}#F7j$ z%w2 zWP@_?KFV)5WRNk3N+k#FB0P7Jzn;HzvQqp!%5kSy#)|?Id@L8gO89}%Ur%US(AXpf z<-spl#>)-U7O;o_t8wr%;ZI-v^Z_>-7>5IeU4;%MD0C=8Cu5{Kw<$?@_GLfa=-AhI z;2O#y^;yPNhY5KqIi)$_(o6jGreU*;KV>yc{aA(_dOGx^EKeCpcv3Szy=vhQQUR z%5ox<0pmKZMzbWsv-3~U=hr!BbeC7~Ogk{*N4sR1#VJQ|~Zr9C(!`A!g8<#nVa+^?& zJ;pL@6x4BZBgq%f5O&G#qc>RYB%X$%JnA9Kuu)KlqoG*#d`&pMv$x*1XgN`TGs+|F zOHo6D;~3$MzBJ1}90@dD!nf@sEJI6APH{ifxmeXz!Zk;wx|CZ2I6dHhXt#p=gBm-|j zEYJH+xUADSy`pzNk<}CBI|WNq=pfgI!ycAPlqI~f#aO-j$swZaV3b!hVfn+2u`o3> zh~=ZL2-hD!M$eHtMwA+ka$zr)<1dfVahV?dz&2wE`}&R6SAF#n4P@x_AeP~T3%p@j zezKDA$(5t@xJlE+ydxsVZCk5r|<%z-!)d;vK z3s@F42@i`Hrl&7lD)!bz`J+3_cGZT%T)`5SZ+9a+deu;UWQ`CpxHigb#)mm*Gd|qLne>qtYL&5^A6Epd#({qQa-7&oa^pjnC)51 z^2Q5<$1NSCFaEqi1Xah9yFF#OU+^FuGI=c5c}sX#883b3@6Dotls$5lrG|trVy60= zS&lDE_|n6H`ufRXVz`tmxw4F}c#x)K*-Ih(-gBTn`*FC)T?4CO?#VK~JmOklx`N*Z z5kBfYKyNX8hbSrK<1<)>V|4I^m*wDvgf|8E)AxVbEn3KGq(`tkYg9jcm1eo>0m6As z_0=mr+bga~Ip7k@urO3#x;Bbs?G9l}R3Cl8p#9>Cl#730xx)S4(4M1N?*5x_*O|R_ zL)nAkpp^GHm7~y2UfD~BQ%+eUOC2cP+P*S?)1=` zr5_WurTlOx%fYeTapr{O;u8r+Ozo}*ro;%7l!KPA+^canoReYs;9A1zS-R;jLM=j< za?L|5mpkC0+t{3Bxs68n*ennIdHs{3n!G3pi7daY+yw`&ET^OpzW1rK-dm3qlce0( zraVOhHaF^!d1QG?Zo;Nc9rfQy=R}gM#-qwC!{$aEPYtEPwnH7lOs4(7Z?;#&Ja}z@*Z)&2!!C8WyRWf4<}%^^lUwV>c3l&nUZGs? z1Ab7srTG@L!5ny^8I`jD0FZpnvRE;QZzz~5%$R8ra#zvOC(5n zetnkVEfeQ*S+3obaA4c!dgR(WqMfY9-@Yt|o@uJX$*e427)JQaoTj?gCP93Y^42*l z!;Tu5lSyQG;8Ma3jtad>Vxq{JhIMWk$ugWh2c67)mcJh&JnOllx9fRdm}KZ2uCWX+ zyEwtl^3r>RKNmIV#o`}`mT*`AoGg!WaJQn`%QQkO; zWjH+$QzYD;U-=O3w6m`6e(Q;7P#Bx2F@$9}mk={GEC*~P+$_pfuXQI`oO4Dw=W&){ zV1hXymW#y_ULRLWAH3kHIOK}5`$LvtWftbGSU&WEaQSOB^x{2I#IS}ace1ZU4JoEg zbsf&BWx2Hj;hJgH^k;8UghvyUuT^6ilP@s5Wcg8j!ge33=-y+WiA@HSr+Ki9X&v0> zM4h>BKf+hjob{TIo{1vz3G3|7a#F?08RYzP3AaeDr0>a|Dk5dc3%9Tgr(x>2r<2AT z5s`#z->#q+=#(m!_rq$`KgaUT4&^h*hHHe+z9^?V4o(#*V^DsS#3GNID@El+p^|Hb5biOrsNTQT zGjVb%mRvWA<>1)D@^aJ2Jnk6bC*Fniks55j-H7tNTP(LaS`gEeJlG!akZ`V{1$CR} zPsOi2DEIow@~=oo*+i-2&sm*ikgD`_)Pt)%75fjNY+IfvY-@MG%p;e)v>M@*HV*no zL$VOZP(I|&@`#YUm`r5Z*@JKaV_to_>k~2VILb4|vyAy}+^I&@F#8d{pD(xGxWr@8 zU&>|Iu#A~>>{O8O)+KiO{Gazk5h*XM&2s1& z8`Lk|*yY{4w;CHnzhpu|;0)CYM;o6QOYr z9LafZ5snOer!`-CLmZHE1^3^xjAxm`3LKUreh|JKCLsAnYr>nZKh=DvT^1vyd~YbrxX=T)5RyD{ z9N{8I;3I{eaiWiuXDwkF_D5=Xm;%W*s|lCibYF9|xgh+c{O2Icc zoa>ZWBxM_CmNB1+2fS0s{c90kyZn;YcC9APNO@lemN7*MtE*Z5)}3&{t>?9h`Bc$R zUX-8SEMwNO!u=C0FPTpG&F0hE)Tt*#s+1pZU>Sy%8l1C>Ha7Y36+C}RG(!`_u=U$B+oVy4sbf49kAakrhZ2G zeqWaH^iJFjNpjI4gge&QtJN+aDH?x4x#C=w@$^prmpfQKxQMVfTR>+1*?S+-1b3l9;|U$NvT$5@6JbPck2ERWF%KZshag}Vid(((#Ue#kPs`a{35 zgk_sl!s^u^ZTY>$qN0?G+1H?G;8C9gVivNzE)U@bm*#1`l0Cr|H^~xpT!LDWCOY8Iy828A2uZ zpH0~PtB)2@X118|4ojZAg=IV!6iVkC_R|i+zER_~v?J5RbvYr~^c>4D(}U~GSza7Z zc+BzJbr2*C4WrT0GZ>Ob{>Lc=cqg*+Zx2vEmp7Au{DWa^lVnS`P{0z#ypR$Y_S@3I0Bwu?; zc<-6w+E7bX(fv5e_jA^!h6I~PH8|LwP@&MWQ^bHq&+E3P3MfK~QS- zZv(>9E;wrOQRT#`%_zI{WEs9=1&d2dv%H}{;cwA-wcABYi?E3(FP*{iL}M-ucE7M( zV;Qyhgwaioh}?yf)ko@F@q!h+x5qLROUB^>+xn`Qspyy9L}tj1U;R|*|&M}m3_ zTCuRGG~tW6-dWb_ImEKcC>JoXj3>LoE+dx9w%BS%&vl+!e+0 ziP40Uhdj1S{%a%R-r)XUhBQ(&x~(7_J?Wk$zsoPS>6rx+ z8MOTD`EkO70&ZBgZTM(B_!>*@naDB>04?|hHIipNBJAgL*|IIq8>5gLaO`dBP&D8K z0}HIKX1Pc?zncR#q{)ovAf*3_xd@@xN#2; z<)n3t+tLZQnzqgIsAa72O$?k-;N%6Cn-n5EJZht5`X!5ThFp8;QJ-bp zI|vbB`C1dgQ{KU5!_CKxm*f%uS^KdJ+j=Z`kSJASv=`we9wC;Jdk-12OvGyJpTjbq z%?pREv-~HBaR0B1Ez{rZGcJ*fOY26mjC&qkbL?e#O%&nyu0fUxH+CC$jK`7_uCfei zRSSfVKx3@s3S?=&u^=`)3Qw zpr{4LN*?%2nwBJrCm!HFRF>z}CcJ-{Vp)@CzVWUJ zd15bPL3zYq*UcXw@OiMrnE7>mwU793O1zBK?kZr%QMo)Yid>| z+#%quYU$->ymAJs5!#q#cuJ@+L}K}Ld%}II#H$t0n~au2C@&hwGQ5?l&`eqO^d`LX zrmhA|GZ^3OLAhQa%g}SFc!B^`pqsDGg5IUKFP~Y5`OY@ zj~dsgu5tJ-lz-f08F#hgA`6nsJtzFrEnH2?Q^VL=$}4}cj0;(yO|z`#Z6t%V^XCTD z2k34oS1U&pPJ&>i{vlR*&$Joy*j!*>fDru#;gm>Lo;>w#%TmJ>=4?z+fDjo6yYm@egMwOEEKsJKjqN*>>w@b4)_)bP-3 z#sg!qDK4iJxQNnp2Tr^K?_*oezKh*W(BFoT_%y1vFeDwk0g*PM3BbuZu zPVz%tTi>w^m)i_gVR=}VCNf9^o-H)LSDq<8K3I)xMTy$L{b$DG)2YsXs}Q#P+SP0) zl9Ufp-fv_XB4LJ`R-yJB(wXpqQiaS9jklF6Yp~>AL;jQJ#^8wRiDz)*n^{SG-17-1-We8mp=nlBfiyaLzbh9`4H91)7h;nE#%JV7_ zwSj0DpgZ7_D>ous@JVu$y8ZSkJ>fG1uwbEmCYhpfYyja}^Ku$K?uk^s2BMtPn`O8t z_?dgIM#uSt^RBON=z1eusWlblz3cxgc`lr>v61D}J%qF09c`%hI8-Sl+eWvOEJLXV zJb8qw5qN`e+3=MHuYs$TIN6?0q*|2=eJ6b3!8Sv|OCbtHMNmV+Nc@w#7bg5`eS4)!;|fY$ zS?3j1t;+8Vgpb_lqC~tZtJILusL_RGyn1*QsT%VJ5mqDnDa+OtRd!1G+7zpDiG_r{ z(!7+g@&%P*Rq+R|*_=VfmPaKY+)sGC=MZJfp&Uw>l*^rE8Jp)nxx*d8WfI0Jdv|70 zHcR>9Ype2;UxaUupQPmJY^%6PxorUxh3v73s9<_O*IUzhS3-uXjK+#3Eyl!M{$3YY>1a~ z;e9M)pMiY`RpYjWaJIBS#W3QUAyvx#Zd#Scq!3PXU8ocpbKc-u9jnp&M<$v2y6m}| z${@9HTcmWXf7&pyBg&7<61Blj5j#hcH@XsT^5_avjLa{9vZg7+1jpeJX%0spj?saX2Qlk7egOK0)Y-DB`d;NcP z{&tCQ<9chA@q@M+>dWzlb8-e5E;;|e;17hS_F1pI_X;+oNcmchX4H_d2OGA7#${XKVm7{H%%OC|ige#ASH8b>+uO7{c61Bk*!M{4YI}_g3X{Ta1 zYce!Dj3w_fW|HZ3>2U|bi-t!k-I|#Uk8h*gb4Ugm#~dV2^C8@EQw&y|SUP|5!9JW}rCZB^blhj6<}hm`f#r#Gqd27ln|^;YF3k%a5k zKcw^@GP%iZ8M?reEaT7;2e0%4FJC2mc=$2p%!#{=>BAXipIenZzYzX5^@OtHLaD}! zWHn;)y3sxOza{@HNqE8Z80EXI*3ckjk9t<+RV@hj{uHC^`c?Y)c3J0yK33%_qX=hr zHY*GI1|7dEPc8`vuqs=Y6E4%xtX%Tjc)Yxn|Ln9XcRNP7eFL+i?A>(S|24*W#}%vc zn5lyAXCB9jl}#dL3UU<<29m%I*9J2dBg;xdU4r-z?=n!5L)e z>td*FJlah7uG49y(1iwA32Medy@(NaC)ay(#{Xo|rgg+$3Di=rCo2O_f7cJ2G zU+ADSH&e+M$`TegW0h_Voz1QZD1T{WRUX=!aLk2RB{Fv-^M+?AZyLxlzU=-h`P*2+ zH$I+IMs{p!ejsnF)`3<_Ubc#`|IIVXh^B7lHPDOx{aeXQ^vbnZkb;5%4cL`Gj!ITIZGck)zCCzEv|$`7kKJ-0u_q?2)al%5%CC{;(%bIqx>tT<{~x#m8BdOHL>3{vuB4>om{o zAn9N zGs1mm#VYe&C7CaIeLRG2G?!^h8Z5*Q%X!F^8T)sABsb^Jw(3EhM>M_c~Wxvfoc45g|`&gB| zhZ9zuW0aJ58+EOe+Xq;cb1fr$vT}^l?u@NEIuc8c+sQJIs=3bF4-@|J@rY8Uj-Bc$ z>pba-Rk`tf!Z#BSDWm(^sfFaz(fPAg`I>D98KjO^4=Nsm?9{JPeqVwp55fOGbi-W; zcj$Of(R$jc(`B5OHn%FUk|LxLtYZDwr!6h zp4+OklTp^QbfkuaC1bjPO8)FX_`~Ym3YjAw1Jkb&-m+-B5?!x=Iz-B`=~m_0UkN|(30Ka#7f^dh`Lkmu3f=#fT%t5# z`|)8)pSA_m?^52}$f~^Gjd1G^+muz!3#b9|q4{Z`Rk_t@!seK5N{0po)KDq=1X`7o zLI}I=*rxP$DWJZQ)o8dclT3NvDaQ%d58tMIEmlBX=7`zZ$~RfYDH04F$$1|UUgy0@ z*_*q7nj}yA^!Q;_4zuqpgEVcxM#c2UQEecT#J|cCg-`ZoELl`1T&ed4CH{k>T16(d z*SEGR-|`^*`N4Xn;Y&v~t`^q0$T+L=2!FyM+t({LPaM@nwNbXLvMOiUN_frk^-9fq zj_N@v_cODM(`WypvHBe0sXbRK^KLn+1El=o97K4d(^4fzsH0l7E{5(~m{qw#6ybFH#Y(^yM>Rmop%<;nCvFj*VYf)R zw%JiFFXiU%tjgVf63(|^q2jd3QSDO)t8u!B2Zio`>-@SLVTY~@l?qVjiSh@IGO`Rq z_zXXAwmadxx#ufyL7p$;TyTh0x$t*xw*|z zEu9zZJU7~^+*&34c}ReAI|44Zd{3#CU{$`KOt@gp0A=e=NA;+@yHEVFDo@PWRR*bX z@c<=05-y4ystv0|)COnL|8#wZbO$YrT9Ka^_G--t+y&)4JRBMJV|K+@(G%5(5=d&;t1DpnWT&XdA1z5 z&PrvOb0Pd_vwu(c^}3Nt9LOc)qs=*QH)=@#D{m@Fcy^zmN{%Q;^`?|>*0n0v5`-JH z8LT{pl8?zaukT}3K0kzTTIWGZG|1KED7R&RRe9)Q!j)3JloC*loKk+blVwaJ{kwuc zq6tsv+FP;P@2HlP^4Kd@<+TZf10B07D-JlSx|Gv@S(Tmt5`L1@S?PDjL2U<3^zYwO zmAcE&mAcnanVjUH(q~{tI1{z`-^z7sPk8RH4obo^2laX86>NWvWlU%OYl}BO5q3XYQR(^HLH#9Ha+Uv@Nv46t z&=Ngm=-d{SRkGRTSNj#m?(%9WqB3>-@3Hi^8Q~eLN-H_CGDm}6)zq9Klqfzf;eq~Xq{Az<57!A#yC?xTyWO~vp zu0ptOK?h}OrTl85oDnNj-Kt!sGvPyB@+rm|`PF23&)@a1Dj)SF>{BM6vbb)3bx;y^ z@w5F|hL@2Hm%GCz!V7%um8OmItCMe_oMme!nO;_3oF<&m%2vsyy^F z*w-$<8rT5k!%Z^Dl(TI)fUqIzm*HjC{Oa-F{vh}9Vi|MH_<9CwHKAinm`8Z~;@5`m z+p??T7|Mx38DwnFaPSex6ZQ~}Yw*<2AWI%K$0(GiMrDw(WH`$R5ATN;Xm+2!zH@R3b_&Qf+hmgAcp{Jok0I=_G0D)r@L%)gi74+G zpGk(}i9r6df^eCV4-KQQ{4uvk^#!@lnoKh61Oj=*3BsZK9vW6?f6Ontq3mU08RpsK zMS*kMK(6wb@b&BQhIMg&%)?Jk26^q%Ofn3LKt7qRuZ+g}t!EAX&;OVQS4DYEE}}RU zB};}Ahd}OIgK)3Qrwqd#{+gFe@WDE}W|HB=A&}p8CH%wrq#@e$*St2u8|1S+Gs&ut zH^_lg371%}8&>%KH9KCL1ai>KOfr1g4&+kX2)iuT4HXXkHDCQQ5#);7Gs*K`PXzhc zdBVBR>4w&y{+dgdL^wT=b-2O$i&dbh8N{dwj?w!y!T-KP}WxhVIRT zlZKm$je4T_c#xBvi2fHkI7A5KsRqKSmrojY^|Mi(dX58mmWgF}!Ip7`gBC$9G>EX< z@%@H#{x<6T&SOC?J}i^mBi~q%cP${?pw&*p@>MqKp<-h|Ua=&T4CexYY}!wFwk!O5 zdu`O*??!>#<4`6U&IJPb?rp-QJhmCOoU&1SUKt7U-^5HZoPG)N#9xHF25&X&xn-kv zTrvXW?Kb^ojO1sm@a~2qCqcHaKzM%Nt%jgyHtIsdaFDAyXOiKlACN=a5MDigt6}>m z8#VRmP>^qT$Ru|I{P%C&350j-*lGy2vsIf04FP$gPbRrkpCKS$Swpye`c}hg2V2!C z+hCBJZpg4GIKrZY+^uN$u^c?_lHCMvzONSXIm~7R+r~N>- z)XyY`r1t|^>q&TX|1g7VTU+&U>%Jg+^~)r~Zak2?&m`==D$LNLtF5{ys5i*Yb2G^s z*7pWEJ%X^ynJ~ke-nQzAgq|Q@h|DA>Ug-&P&?Uk?Z^I04``N1V^Y;LG{IyIn?DGS; z#0SEKiiR7U`rE1>m2M!v`jSb8Gj>2e=rmAiAU!&d#hxHHIZZkc2_BpKwCp@i4Y4>v6AY^%;%))C~$QJLhdJvxHyw}kM( z$Z*4Si1XMP?LqDol1YYRb3k@DM0m}maKpV8wrWsdTaZ5=%OwAp*%ss-iG=N6ha0jO zZPis%-9f(bFp~@?SA*Ql##2UPcJ>Iv_Xf7=!ojUTo@!6@zi12_)(Yg?l?ksd7h&jF z$5#E?+70CL)icQ}o!mek(}D2c1`&qlwQSYKIh%vL&?A%FHcxYqv-l7$)@9FkAt7ftvy3;pZ~R zu%8m-i_Zxswumqsu5POqbZ886f%Hr=oWu^YXFe|(y7Yz-218|Ab>-OxARj46^uN$m z3u*xJk9vgPl#ehJDQ>F{=~NHo$xSlJ@FoQEvc7~5+D917*=<#?R9BEIcx95|yc&=z z&msKvNw}fbI~z50UM-O0f-=cf`qcti-9`A*iEu+Ibh)Fm)&RLuYgJkH| zGz&Krx{+%BHoFqYQ_B;Tp~I4!dsYIuSPQ}x%Y_?q8k5aiUzP{isZA#N*|qW@A0A0~ zf3|SLv{#SJHM*1q`Skcqa)G&JL3UqGc)|NHL+F`@=JCH(nO zn4xi#hvxkrB|v_yW|FU$F9EV|5@G#Hn4$iUB=eoEP9QITnn|9#(g|e8tb=7Vy2gYV z7A7W{Fa9YEa@Sl$|BFVktVRB>t^1Fw>HY&aUMfx!<~FN{YE9<%c5ZXKpHC{qn6IBR znME>%NLwqFAN`ONqUG0!r5Yu}G79KhTAV2;VmB6cSL&(r{ZJxGP&9vUzmkGUctizMu;mQv1l2AuAr z!qaOz1HKf2xyPI=QvYMMB#@4P9imlukyS^)^V2aqjmaWOE32jB%Pj!^vAq?un?QC1 zdnQ-_Ha>~jCw)IjiKv$P-4g&Ol&NsZQvvYi2bi}ED=OYQ^lfhkZy4 zKXL^;sLM=c=uX)GLR^i`O7d0{z^T?)m7!xeZi5NnGdj!-vv-oIo+Z-pH%5S6-CHr+ zXNKXIynv_qVV*tfAh}h4RJwQh)eyKM1*&jN(5oS`{4@cxTj&u|bEZ%#3w{Q8R&&GDgbnC3}JCkLmzVu*bZnp@bA#Nz$;3HGo~5RhTV^CCm4R zV}8{B1QEMSQj1g#`1t6zFdP{6LlVHtf-#4ioFI=5=Sto)t^y7UQ(?9Wjx1ZR#~gjL zgd8->l)e}MPoFok*rLMhq4cu+ivjbDoDw1(+A4WXJP){{NQK#IaI!r7Hs+|ACB!>B zO_Kdi1CFUzVfOrVS-#yaP#L6%?j@whzRgm^v=e}xI$>3Yj=ezkNOV~aAAotsg<^8n zd$Sbha}02niweU7831?q0`s=T#l+KkvsAUg0C>2s3d3)00cS75oa9_JCmGct(yh_yY|Gv%%vL&)1W8PI8s6hr4ZecPV^VB4F2kD$JG`k!8bYm=k=8$=u;ovU?E^`22)cj2A|4$;c=c@WgL1 zf0D9~#J$u@JG;RX<&9=XsWAK(0&x8gm<_hMq|ai#G-7ll;CtIt7#S zC2mHNEcyaIqQUz24V47Ti~#oj7_%+OAS11w8)6Pm0_?9>Vff)H;Omny{~VJ+!m1w| zCd?lPxVOIwvsHd&`MVg*_B%32H?w9#lj}&pml9Q&JziXvEweE{Fk}#0za~TAyF&p- z?^R)!X?nn!XEB?XWsoUTnhafD=mA?@QDJyc0ASr?%%5J%Ab!6z8E(~xfET`0Vfc9| z;BuQFW#}f~&mc9rX2Xz*et?}EvHml31FM|?2YFy7E$}0O>SjZ8$p?VzN2oA+7CHRW zDG>7%IfD#c^VqQVKo7thL;i*14eTNDvbEG|d24(OvC!1%b{@+ETos_gZ2bl}yW=tUs*NE|P8wIQ*|~tH zC97}*JlG!Y%yTi%>lRDg&i8aZRi6pC>wXo6uT=mJEyvv1J(eU^IJk}v-U_&=QiWlS zE5PQ@FgN(elH$pBuHkhX0cRQoD`WJ}Xu$FpfHUnd*T%<^Ne`@CLxR=<9_g&Y@S!|l z_}!1PjkK&-vc9*4tH<=!fNMspFk6#BmM;Wh4m=u5db_l7z2mSFaA;U7hIcB$4hpQ5 z0XQ%f^R=gb#ARWNZd!37;7(gqTV@M5$nxs~%t2<~lBx@hy4~jz0PiVMVK`d=Z@Pim zuOW)q+Slo7%$EWFpk9SxjVr+Y%;qaEFy(MGxs-NScgA-q;PQ@G{~0>A+Jh{Y^u@gA zSS-nZct>Y$@l>?TNsE_aI9+t%bHi_rr zq-~g=r7b0vvl?_yDj6P?tHSsKdzNCJ`FtrUact5Zvxx(2QO?B$jhLrTh$mH{&vlXT zfS7-Ge!= zXa~t3`&8#Rk4+@&LtH%cGUiv2*+iSvpu5>_Ip7mFR2b)T<$p1sx|U7Wr&jBt$FTW4 z&FmXI2iae3@Z$7{zj44^Ut2)FD7V+Yy3TNOUoLJx0`su>$H|R5GxU=zlK`)pz{TnF zF`wFYg0!rU)8BfB;oebP?6Lv#ADc_bS+^DX;l>Q#-`0xZ?cuF`J||&*GxjR+%T3mw zsAKz_TFS+$8_%Ccia3cBqgt@!Mn6525rw{GV=7#-VF8=d0=Jvfzs7=zJ`l(55*8O&w zixd9BY;I#plNZ0yuN=hij+ZKoXNtpnp~}$ZMVQi*_9kTFGj^toe;+GczSs*iVMh@z zUkBVU4_#qO`<*c*IbSjSd}J$TpGq@~XZL?*V%~Y91N~u*8A*G^E(KFVxVUyDX6vTT zH2azvDHy}B`9>~|*@wBbstf($ju{y*vkPP45f#QuZs)6*UGgl^;rF&$#aunvy zFE!Mm!h|^8T?Dx2WG)U0#r(}58v2dgh77p95b&XBE`GELv)6774fkk6G>aL|+Rnwx zk6{jr(a`JJ#-#phhVPZNV)p$Fb_8*s9qwTsTHK8;8DdOc1uz`b%*6*fgeim6`({tN zq=PXz>BDe{HCDKozrE#ABIfIL4)i;XG3n8nVOMu9uK5zPPn{zjG2WQ`8Xg7sLBLy> z-5J1#wlL01Vlh9M`9AHl@O@&pasl9!WEEyhB*}8;9L#67zfTRK3vmhv1#G#$6|=AF zur0GCl4LpO9OkVb_oIW$hmcpl1_S=3Qia(PN$_Ff6UI z{H!--0=rS`WK7zOXV}k$i`S0DY+jNE`D?$b3(e7RyYXc7)%0K zx3qII0#W#0hHVfBM+aUrm^=9~F0T+i~#Ox8QrCZ@ygst(O^|gq?7$H z7xvRqUn_x39m$4Hqvzu3pJR6JrKRWJ5y%+@7ft8lCsCM>_tetFP6BzX;K)QSUX_7) zosE`Wv=qoC1v~HMV#iahSfiym9pFq+@U_caeB>eKeU@5UX(5n-3SRP(i@&g1s0`ho z?X+|d;Ef74am1<`x;j1Paj;;}=Jo}MkF z1Ne!8+im3H-Fq?jXcp;Wz(xw*SIEWQS1>Dw1Vx7mhdK$y)|av{USXJc#?vT_2S}!A(&_6iL@N>6~cxt zX*3s)4!|6=N2HN}+bZ~zFfOiNg?Ym+kv@YLXr$nqXJ0z?HdN{L^vF zIU7Ve3U=c&Wy@pAx!9!+v)?+A<^vWKT-U%?U_P2G(kwVr?kRXv5ErM$VcxS+q)%aPBq+P_X(|`@-ibLS zNu&vI3sIopI|W>P>^$b>%SB3^1Ts;Xb$&Ov_^YRw*Dn*P5!}f*D5sU9SuAfNJ?e&e z$5N3tIt%22vgLDqxj23(WTPKkI%2o8|ZCpI^Am*Q8%UwSb$YcdiF6H7|RhZMGMEX&Gfix@lXd@R#n8YcA z6dVb-uR#7#@C*%B)kM=t%BR=xj1_qX4?fK{qjSBTvPD9>0ImV{rl>k|GLlfeeQkU&+D%5+UxAS&p!LqE?Y-SN9*rj_t^n%vxfM& z&0px|J2OzLhSmaq7k{_G3;bvMz<+lSFmvy$kpln!6hxD*mfHgVv2z#9_Mbi1SF5Jh zg1HO*X1bXT=&Uto?#%Iii*PLIf3rcP|1JH$dw9>RtwsOy<##^Odypiwwr~>v{wVH*+$`uo)zzAOm^(zk4a^Tus7dj)DB))}ifi8I;-+6P zXNRbX>(^-ERCkKkS8?&aRshHJbxqRawj#3yc;L1W*aynii35va(8m_-@mm_U{3F* zCaa1Qge*43vKw3+Q-nEau$pXej2B9}((SJGg^PRYxUog*XRjuPk-LTBE))xtNPw)#Ux{I3b(ijm2Di<|XEKZfa6HFHRWAmQJkg&fEDX zHOBlA@TZ(O;S0m%=3M-?H|7rRYLW-|IXfoO#&hv{C(KW!X*^;tw_y+$w+X=<4!G~F zI3b1Yj8_x5_;?!TK)?ofV4c}+zWNdukGO+*)GRd_cPUONVtC>^E`DB#xi75q=2LOP zJ%+#Nd+?Snur20!Gt{JcYMgL};jsc2HyMoC5?=23_&DJs!`7}`oZ^kyV7i(djgAur zTGIXbaVQrL+=|%)4o#EDIN?0Q!wz%tgG|gj0e9XIC)BW_BiFpo#lFRu`@l3vP@M3R zjhs=%#kFgDvPEhE8(7;XPUy%+Zqfm(#xc0Z9P?AaJKbUDXSi?}7xx;Ec?hg?xm%oY zj7=kC9v5E^#B2k25sVzp*4ZwKi)SWaz5~+;ag7rMw%2K?xcE;V=52uQPLC6E*v>zs zjElFv#rzePZktn_kjW0KI`wArcBIbwn4iOoA^`ShSf>XUpS8if2=Jq6aN1^gw*wbX zbHUsbreW$3Cp2L=e>oSwUx&FpEZxjWal+Nkbl=#qmy6e?WA=n2WijAiW)ye3&c%jm z%#LsjZk-q>3}YkfeCFcQzc3$$qx;8rcm)}DYw5*Xx{=11^WcmWFfLA*$Z*I0TwH30 zIlu$nCPu{xRt)F6bMcb7m~{c)9uOx?W_U{k7dPL5ITq%8qhFj5!>}TQi&L{PC&6lb zvyKyT8BQ(aV%t*8p@84_i4$%!JV)D`w;B)YV(tsrP>d6Pxwy_`%vS-M$m4_u3|lSa;@!(I)3=G=HgQ5J!}nvjxOXz<8?eqRdc+B_3&?a6 z*pxOnO@ z%*L>Ri>hLUy=>0Q?r`ykhnVX>QWLL>k-}g$a!^3ABHy+bFuyl%%=daF^&_Cu(POG+n2W*2OD56 zhB-n191Z z0hvjhu$+w?lfcDwQ!q~i9MB<7_{^~XB`!|BiFr2Qet^$2Z2gXl`+mhd8qOO*MsdPl zHs>Asb9qa5t2O2saHI@q5hnyPEEl-gV*uvq@S+&hjT0OgZs5wr+Osj&nxiH)e#Z*N z42Oks@%Bxam8EL(?r5aYlpQI(4|B2kNz7@!YI5gWtdPKt!7pkqzVHb1vAJrptTI+; z&hXJHE_SXlk1djHo|=?=j}@ZXJM33utQr?opF3lYfRS~7#tN4iJ~fPsH;lzx5AYC} zvp$=~&UsvHv>3C&3)sNjkwQyjdUOwo;^OQ$%r9Z&gXOV;2b;$394;Pn0rQHN@Sd_h zQgAk+BfFJx@rzfOFTiTtuZR`Sno?{~Z$58FTG0ga55T?N#tKIm4z%LpR(&xW%~zAJ zZ(@a2Y|c|0xcJa?%)u~n)azKmfbB@yE4X;@8qCvS-w1mdD=cG2io;$meslnH4cJ9H zzKRvB*%_(jbuM0f7qf@Anv8}ydoz6T6BpO}f!Pp7?gp#Tnc>iue!QhiY=_w!aOd~2 z!hJU98vVJr-w@1g0eAlzD?~AT(w&R*=U{e%Ie&s(bSA?~Be>Xe8|F`NbO-&46&|s5 z9-YC(e@|l$fm5yp99H!h4k_f~sHd23!711JL#*(c?fe6@7w}f2M;*+?fDK`<3t=Oh znsM>PZkQhcjxLQA+}Q?tjpkyf37FMzu6t4f@7?T0*|?C4zXW0ShBJSi$Fag=_EGwM z3>RCFZP0V>N?r<6NbU2w8-j5ZUvX4u;FS%Ix4)bTgH}YeJW(+@U z5#0tCFG*4;fgu`4xEuDL<&0@-n*KM zTdc?I4XbhRVys|?p9j;pIQ=l@3K+R`WTem)SK|&BkGPMy80I|wLaeZq;dPZ<{J0A9 zDY&jXW)~?OW4K4#g}kL(*a34N*!fFyV+Aj^fmMUJxWRDD_a3Xs@F9`H2DXb%_vYfX zd6?J2F_?NjR!C*LsLoa{7NanG0#3?{71pqkb2GVEor8HjTrtXS#0odqVYR=Qi@nM) zpN0dr**$n`V|Z-sMZDFhRS)w4I8uB8pJ4d3IT!D=!dw$xl+^37LMg*OI^R$6ObtA%h+1Gkcr3k-){SdolljX*7j>V?D!TE^+ajTGLo*H!C0cZk6im}?wRlj-la3*Xu6x=X76 zGmXE0A2keQOXmvzzT%SYLIu0pvuuP_1N&KHj)D!0E8Z^jXZVs-HL#u|;&rfen_q4h zQrT)um#PNdy$bP;!)jvwce~)taHUi=aKBW<`{1Q2Hi#6G*)+CFRRiC+g*fM^n)K)u zDGcjKUqQ3mST*phZN#>i(kBOZHNP0j^H3Yl!_oVRdC zb~uH(IUGMG%OZtq>=IljlZ(GT#vBRL=ocI*>|=P`6E0p?a|v6Gx3C(&Rz(U93|rK~ zsxfE7u9%m?D_98An9`2ED7U4mfsffEc7pvm%@5xG*)h0k9Czf=0hs6RQxmmEq;Qwv zHi2CHbT{VuNovx<6?P6U12*m(~epYoyiM;&HVfr#NncId0!WqW-o|IN(I_$?h6BeW(ju z$&49+SwEwYB(B;oCZAxZVKV?%E#cyzotPV%KO#nJQiStu zTmZWya&eP0m}@ydA~ma01iv7PYhK~v1Lc@Q=RP9tb5aGf^AxAOuZHK!Rtva+iuxWy%mO@c0~g2c!+i5ZKJhmU6DBlv2VCo@ z237~mhLL;Sz}!g}ex_z{n4s)58}Nw-Tzu^_=Akk7NciC}p{&#kaL6AC(;bO!pyw7J z7}>qmDz5;AJB;@TT(% z0dMiZ>@v2Hc(jZVhV@wlxQm|#?obp6xbsHLZpuRP$UZ_SI35J}#!d}<^7Aslxfz%T zeJCU^0B@PN0(-!_u8x3Y8Z4cB7ZN1 z3tHdT08Xrr^}l0qWS{kb*P3A-HKK@g>=`GFJG36KT~7^MJSGBg`!Sf+o<+o2*elpv zjR0JGss_&X-v;=^Ld-SR6p`XasluV|+W;R3*1%&Uq5zMK#T>A^h{Rn_6V_Pl1UzPc zHM}q8g3#?)9N@C^nCBfYB8q9*!kAjS0e`xof#K)2055-u`Q7;?qR9WK? zwnnce6%zdcHwDN32Ve-f30AEEGs+44BP0$!2{^4cW|v*XY)Y?xUBcvY)4Y>n7zP#iYr1>k;dF+0C4CHH4EB|EKN0oJvxhV>qFAXTX! z0pA#eIjnsdIdRs2xDi~`{s)qN)3?f;> z>I3dtjJb1M85yjyA^IQc1Gdvy`)@VA{GLEYyEX=Vz82i#3Qw_sOn3V2q4fxAA%t2SnNaMxRNZFUxfZHz8z_AyM z0Iv_ke7|)$@tNgLHdwU>d@Z&bh7%f@P}&i&Q3B@7hh=0#KOgem*c5P&+-ew3JEXo& zSHLIpFsBrikxm-}$insJfNQTpDK}2gW!0yAaGQ7eoo4~s<;68IPH?}Jxg?8Cw`||mKyUeSG;fzZjB+UbSD-v^9 zyCRY?+&l%i*)hyDx@D7A_VvWYZaIKkW>mwS9UF;T-evo%z8^RNik_EKAdm^ z@CH)})8lV!L<_Na%niT`Mq>W+`#8Cm-dsHK_%7hU(HeNC?_I!p3oy@mc$91v4aCX9 zL%?kpR>SaKAdZcA061|MW~0(0WPH8WqUo~7fOp17n4U=}h64bwcoy@>P6x>)yEdZy z>odUQd^NmS)lR%O>KWkM&oP%hPbFR7wH5o>Rseopp@Db5e*xIDK{#8a*Dq5@PXi;d zcGg?K9~xoRqNhrD`-gqwEnux)m~UDplYJ+QMb+TXfE{~l;Pyv80gj%Ex#f>NWc%X| z;+SpU0c$%|!@J*`!oE=nxcf@XdbReD8B02e`_B9Z9JpEoC(rv0_~L%d{f;FNlVnqI z>}G8RtaDm5Y^7^1rVrIt{Qc{A6SEiK65B4~m##Gd=iHVsedC~bn?X&$m0vLLToOw{ zy}F7zCA9%xtJJ_B_SXg+);fYM-H(uH^8Glrfg}A&!6Toe@YTy~=jR9Aj!0c7Nh13nO5C^6;1$;8I8is2!5sntX!H+Oc*tCVH z*IS8(mdyb-EY`p+Yc>bmqQ*wH8e>DZkShy%h?`Cr0KQWTs}|irI`YD827r%s#$35? z3-Ps$}9ynzwm7lGCA8~eVZmX;A<|2WJiQ#O!#S9^&qHy8uwghY&s)0wlS^|zbfVqLoYI5Y9wRrbI z55O^pHSkW~9)KZ4eXWO3-Fcim}i%)B7PgJMMbMVfUi_( zU{S9RV5fGQ+0u=AzKSfJYc1}u?+5t0F;=brTa9(i`vLws81tiFtH|a_)}o!a0JvzF z2A(=g031FCb79NX#7AK*n(Pt*&zmPi`bE=I@cm8u%Z2{Xq#cWc4De3gEhgkV;AmH(38d&ea zK)@BXx3JZ4{~JJ@j#!EPD+dEE(8H=l=S)Ywwr4Ql)!i@`ZCp$qwy+ZKs)qvhx6;7+ z=|cgxn1Ffxn?R~;^y&n__Z1r0D|-T9xvP{%FD4#?&BfgzlK?++uZHOxP~zZ8fbWK4e!6He z+0n3z_`<*eux*3}c5Uncc=ln;Q+F>WMU`ga=bR~k%a3c|=v`9)Yu(3Od44gmSzspK z89EK{v_cIGpI!jRRAGKlwwMTg&BPBE907mU+Q!xh?jX1k`rfU3&=Igj2h7*)=928s z9mQZW9q=|&4Xm)94mfWZ=B9tW$hZe4;?`r%fOn17z>8JRfSu-Hb}#WH6UUl}+ss@5 z>n+s49c#M){=NgVU4aMb*~~<|7~~2#Bc>XrS2B*9TmgsYVD@+PAdBy|7r#873E1kq z2G)Bp6L5zz%=b+^NL;3o_|w!4@VyERoY~e5uu^Y3Tcq8MJ;;q-MxwjBJ7AwiSlQCi zOSQ))?tmv+VP4$OgM7VZDC!1z01oV}fy3r_0Dd_ca}xs(vSMEw@olsx-~vYte8kTa z@XFGmM$yI zgUFH$M7x1LfPWfdWlKj#p489>@InRVw#gnur>lWD@F&H42Wj9X`o4f0yJH@i?LkKW zY9ZR*^aX6~T@BM~{uTukCx>Icl^K*&a2#{O8xOMgh`xBq zY#!jrnHu<_(LBKS3NVN1coOZN`l9CzivK*RhUw=N_>d0RS8E4b4c}&-Cs}LOSlrs*4{+r; z4cxGsA7D#=%#TD*()v>)G4D9V;ei^s{Sk_x=rG`~i>G$I6zDPQ#&}KVUO!%w}Gmq*>$o;_P6G>k8E{{R~?YL~-^s%&&Ys z$%BHr;<`MF=euZNuWX9PufjZVz9%_+Rag93b0Odsp&IzhZ;D^1V0M}3Nv4g}70>mj z_*Oa>uepV}*xQplHPRJ}Cs7=%u7>F+`ellRFmlUpm=Cyll9-pZ#7oO5?pvjSYp0F&Xi9tb4@%s^q&l+Q8OGigWY&Q_|TnA5L>QqyV$fbDTFbxdX9WZj~Y|Mk; z<^J3i@Jos-=5q1k&6pbw_ax(tYKjHlC|8*jPhvZPV$;1`Y;_THV1);HZTo|Co=Wk(Yg~NgHRdpQhm}44P8K*) zyzvtk&yYp4rR#dlgY?M#PG&k${Mi62Te^Q6_^U7Gi7F3r_~v&~V>-n<6kNQ?8T0nz z9>f!Fl$~REjC(aqZ^7Zxby|zL=>ZRN;N%yQ>lSq)}8xE9&D$0Tp<^~`GNUHqzB2K@sZ^1rue>A3|k|%8g$M$jnzh& z?IS$Mslgvf$X<$9nsRZgp_n5>JV?aIk7Rrr#YUsKIKv0C+fonGeC9{8=@7*o7FNUb zR%ga#x*B%dF<1F}kUkyW5|evu8Zlh_I16)-uLt?l_%*rxoZ^n>x!Au1^UB#CMe#jCw0d>e5MB(u- zOX4@3;_Io^FunhbSnCSr5-$(Z*1eoe@T1t^4i`tg$E=v^LH3U@Pq%^67 zoXVkixVHu_xJjq+bv@>p0UpG1M+s?KPO;urE)G9}c}1WH3EfpfW>iwVJ5vL@HV%N1 zO&?(Xy~KkYOfDho+Xn#dP+SeuZx9eGe`8Kr;X!Iod`wpNqPU>e?tjPNKRnI^b1WQI zzpaW$tU&P`b1r^49P@U#a1AysB!39S&&O%tH}-VSA@ea;ZilmIS^??eOmSEs7aQ!v z{AD-nb^ZmUy)VT}6S(-W3Ufe;2k~_+ASnwd*1E*SL(4HQIs$W^SwLznq&V@d241+0 z&bg#sJX<8iNe}YFr+{pXqWDi!tZYZ3U+W-V*aP#s(;h@0e)P*>KgFpwT-;y^=4hn{ z@%nw23_C>eSQjo%UV*s{VD~R~NV9Z`XN7XHVjt#En1(Fi4q1DU;x*}9eD6Bu!I^MI zvb{rwq){B8=3=kUm@Q9vkT>1#kdzdPZ~xN3@bwuiop!4PwsaP-bgjDHA&;(7>~D;f zEgk(j3UO?I%v(-)kSq7DlRiZhPaVd^mL8bDXLyh;hpv*j&nUh>my0h&VBQ07nt@4I z$kK9(m+jzU=M2nF$2`c|&R2+%VWXUCn0~{AbN*3?`8447(HF??GCFeCGA@qL-osYo z1kAa>@jSW0@J>CfY&HIk+|dm4I9O-f;pd1J!vn3jID0haa(KDRZ=NMh*=poW=Hkf< zF+0JIv@8BB$u6dI9==?{^hVjgX}pe+MqW6NEZK3EjC?}zr(`Z(bsqDX`~GBX!dWt$ z;pW#ROz)h~ucL73TE4^_W#>yaPRu4V*fiWeRU7#q&S;d#md@+&0&>+Ri*$QRr%|^h zR(6N#AGYg_dD)CbB-7?Jabq|{!NtXnm~}E1llfON$s2}E-K$~xtr*UE@oLOJCkK%C z12V`YhVO=Rag#L6Uy}n!^9ILA9kzkx$2IV}=7Dge?7fZI@lpW!pmUTo)(M0S99PK2 z{VOqd$`2r|HXk8R^(n5Uoy68iy49IMaO4Mun4Dh(i!~R?xw*_JZqu4Hni+g2a zp13oB1l39w>wbMe-3n4h0pO_JejKeZdhN=Gg> z55#r#i_gYmc3mDq25e3s?(-?Wkjljld6?s(LdYDS1hUzWV)xtC zF#U2adKcZm_ir$p$A=K@Cb6Vj6vc}xxp+g`v#)Xh|A9oS&REl-mVr5JBZ{)T% zn2RDqNaUxTWcpExlLm3|i5Zv;!$L?*$WCILLGd>)E*`lK^SNaqq=WNLvXkLETe$ee zA;B=i_LzNpg^&aKTglgSI`VjPE*@luIk;^IS=MR`aX3hE-Z%-ByrGb8(len7_3TClOJhq{5rxBWf-_4_~O$$MePNg_BVSLy753 zikDPX!*plDX*jk>VR+BSFmlo(ghV(~Ji{0(Te^SvgNS+Y!!S}lW)=B0o#Oh#xOm+x z%u#2;$jz}U$v1{S%;(~EVVDo>3nPD@1e1wu8UuE4an@1HE)iiwo)JtcXV7U(&*9?H z4>7m)4FMjR9UNe6R^?@Z?61Adq%wFo2K;{C{g&J^!m&cy?FVJ^^t zulY~SC*#a0{+P_gg=a8td%uB1JIyEa8IHRqVfs@4+d%*4m>;fKOYBF?C+isA|A~ur z8>F#C+Af5U9n^W~0nG-jk zJY!2Y*IfhS1=ZbP%%2Tb5%KJNl2(td#@p~}m|is^cHfUV?fFU)YdV`WsG=8vJC1Yl z?;DuSFRvum%V&{6Unu@wz{T6YV7{2Kl6+FTlF{!ePSiSpI}%;zf77sNjainmk~lwe zA)Vh)Jk*qnb8Rul#IGdD%U#IeR}|-s;^L{Em|yQ&N$h62z)vkueAi#X^ac4hjZYgf z_n99=EWBMvZUx0nW4Ji{1m-)n7Lo3&UC2F#JDlfYqeqxmTw6fK?r|a87>=mm;!K@` zY?1aK^dqOwxDa=Sn>E79u0`oj7~?BArZeVaZTyI3`zb_V8)({_i(iew9GgF%WU42S z6>RB}9VJXx;@`;27h#@W=}CrUjwAD5)72Qhnv0voVZN|>7U`H_Pg37fyg!wT59VUF zAK^;O751dnM~cVX=Hj8RFeh5O5MO7@zMY}C{U8a`m7xFN$a>Q;hbbqMVZ@%KouoL=i;I&( zq>-J+6H`Zf((4Gt_qK3x-vgKri1s98sXeK|ZYCd$P+d!Rmn43NuLjK;gCkYJKFz4bOgE0p#8bBtM z*^@(T8vDj^akn{`jYsz zBh|K~2Af8GeXLslJF;;%%-v!v$bLs#@`!CqA@O+QpWnFx*zp_t1?G$c#T^d$}1zOi-(7uP$C z*}%C0@$v0N2C+MVy>hrXQH^<4od%@M=pJO?VY-VRFO@L;m7IUm=vRe#?0}l&=TIwh zhT&;?NAVc^Uz~4@+4<{VVdpJN@`~YER$S~k4D;{Tzl3hPEy*Q@XH4eezjHBfH2oIK1 zm>qqJg|UY$$vTFIe&XWkddJuzt(aUSTs>z=HZq)LfE7;WI1PLs{A!8$W=MfB<$)z> ze3!l`lN4OMX)@;d4<8CyZ!F2dQi|WZNf_?cu?@tLJ1oa+G3Ju+L)(fBVizZ$!>eI> z&?3%C#ys|nO0b`9M(jV(kry22V*6{DTb#-g`pZm6zfTmmDCFWdA2GM7%oOHSwkPEb zFVs4YI}+St5&lhMr2*z9FZK!TDviifh8vl3aSH|JyvDnQgR70mD~3;x;^M<@n7bG6 z66#MhB9|F%y^xECg=6kiW2aC&)QEIrcxa4-;UciwoF5;<{I+ExShA}E_w!u5 zumH2$$6&#CQhPFiT_X*z;NtpP8ElcxL@X4nD~w1vyX^Ve5G%bhuQrYSoiGPKnJdJf zGa^md%N=da#lk4e`#1UswX%%JGKPyBB@8F>Y9r?_z#KEdUWiC+PYl^@@Oi7b*ee=y z@Z*7kqJc3{me76ULn;^Rp2J+=DGDd-j7e>F6E*BM7w>w3xv5uAA@O8;_`w=Fa-T{G z!x^dCoGlxkU`y9?dsE?|r7?+MBi}T{3QJcVU+#r@n^05OI@_4^WVdH$4dP&&eA6qjUo%}9d51Tv6S(-uNzCN?oW7&}G$A9}(~(c)aq-Z{n4`CB z$XxKd2}v}jc@uNv ztqm79u*cjk$@p|eBN-XOZm@TD(ZG1OXYXRn>Yc`?CmYB}z)(7}WhfVu-I%jI+MW(D zk`WuYg$>^wr%M=K?ku{_IP!xFnAgUcXI(dy5j%EIW~iEry@Fku?4Hc$ zUtFvs%VbNZ9=|T@dM_DK&!W@tF~&+yU)83ut1o7w+Z(g$3NrGEVc9S)?&XZx;O~~K zZMHJd=T?M;d|E4F*34+;YK+c7;kk} z-o<=>dQD~YBpGS2mTutbQZC-|1M~U*y2`WDWMsk)immic|KBl)bHRhC@!(&;_M-qyR6q!mclVOVh_c293%`UbG8~d@&q5udJ1#pJr@~qNTT@TGA@3% z4RiiqqO^6Dkrxc_Nao^IS(xiu4OaRC&R}@YH7;&dg85dXValE}Wn>(~tv+$_(K=ad zk$#*Vu59EcBV!ZkoK*%`>5f!w14nkpd|b;%ndu=TE!b*YQ*d#~1kBxjFH?qi$;kQy zI&v3xE?&F@vv&K{N^2h(nayy1I2Sic#Js=B8fDsC8Cl7&|8Xu(y^OiT%Qed7^JU~B z!*vR|SbUFJ=(Sc!{AA=H!|_^5+>zjds@iJgH^Z#gFiM#VBR66=#*~Za5X{@WuEvp3TwHf1W_fUu(hxRq7{gQixj11x=5(*U$}6yRYZx9C!^J(0VAdo1lq2TI zh%KA*)pJ~YZ;^-1-s4 z!&h^0ZWQKvT4$8gJY}S?nBv2!Ts&EYd4z7R(%xN0yh|vaaGQ(YmtnT}ctKeS$6z7D z4Jx^KZM__}NV~3FRF=YdBaPwdhFIxu+E&}Zjy*8XX_=?&4`-xa3~LYK;tU7O&L(-v zuhV6uEyE4Hx!8UM=C<|olvkZ(ue%#ROW zR6d3C^FD@)pKx*W&zLI$E-GgMe!{R#Efwxa|GOH8T4D~iy{PO7cniZ%yK=E@f6OE6 zUsRe>%r@}uI1PNTO%Uv&PuwvdE4ZLMG*w2f>IA_ClE7-1eo#leAOdqr+6Cp~cXi3H zrW8Mm=VILq%y(8?P}VzKi`;{MAN(BS6)xUWh&g-81*PYP8pNnQ#nx}RxUcpZwn)SK zUQl*hq(dfkptz_hR<qxPl z3m56S|N8Wmvi@Ti1Jn3StvLaBMyk;YJ zy3fVuDlm^YnyYNNT$@Z{_-qvyPj7UVEnVL3T;;Yk+T;jZ4Tla`HJ0w1HRfiUa+UKp zYLf?So!<`Q;&4aI4OhWxL}?QB^>n(|wO@_dXK}9bPhCBt97IA$(rwJseRGwU0veO?P85$QtA^>mfzv4ahWYgTT;*}oy5#c= zif8DZ`*#ff!z&FjSHYae1l1z_Tq!QGtcL$>p#C7t<|}fQ!Hwz@f#HzJT%7KOxo}Oc zva?$wV!^Q4axNCPV3vpFDmyf9LY6Zenasucr!cpLS1|iy6H?4@&ud)l{RH!Jom^!n z9T}m23Y?)nd3S~cg6fH5O$;l84+hvTu;Hp zR^u=W;knBGnKI(X=G@Aii!TRYo*$X3d~#k!>N6Y=&c(CiG22GxDlcA?k?{=c9_QlU z7cmcx%T>DO%7{LjbNxat-u?#j;)Gn~$s8Hk%J4?5+=81uo$VW&ytp`eDdq>m6O~be;F{l*z9?i17h5M`p6r;Y zlq=xE)r?~0DK5Tp1@j~CMCDjPM&cQEeZs{qA22TuOjI`S3%4vf(~&3F%H!=wmCZ4? zU6-h|w}wkKhI6`d@m3MD%Z@~4ZVwsR#IWl)F77l7^Wpu8%10J(Ey}QeAQ$Is!2B^Q zQR!z6pJCYs{)y+}2}d#ay_Kk3Y9=Ey**YiXaq;^Hn7fxID!;*vvN-k%j(f|+tN&pB z^A(n^os4v1_-xZlyrpZ^5%aU!Ny;g$;ILwNnhh5p8-e+Lvm|9`^Z&!2XJ}yjP&3jG zbFp!fa=1PmRyF7=7`l#&pYFuGt9z2NXHyyJ|A}6iyQOn+z!}WMCP}$Q1~?T+KcSpiGUvGsu zJ`7d^Uha#rbQ;!ux!A)N^Qx^$${&CY8Mbof;$I$^TSg@*bDGIW8-@$lXkfg1xpgDv z&|OK&bFhm(4x-bTd60{{oWR@`a83)jvA}*9&+;A@Uo67xz9UIF8}7IcV0Qv@e@OWM zZaU#Krs!N{i{x}_tMVd@Y~wB6qy!!^F7OY0d42nAr<>K{YFz4T2 zqb$&a)nFqp_2FWZMVK!|tya$d*@V<^r6d2^#>FRNG52y=rJP&RgdAo#KdTz1*UvcT zQMs7QQ&uW{?duZ1nRH~k5-u)(iFsn@mC7DvHAy^Mx-WIE;f_R??%&8O8e>j58?3w# zszVO4AC~sF;NoU|Fb7T#R`%@$AMxDjG=e8`ahen6hwoM>OPsWbu?NLhmT>Wa5X`-G zS150<{3|T;qjDeikk!t{>oKRo{q<`ve{l!H5$ z31=8Cc+bVU-!YH(4-oyX!>a2fwXEEmQy`r;h&HaQ;Y)4x2 zry8bTRpM$`*1o|OX+nGFEYWs=pu=##j#$|@HL#HqzGRMh(cliJ-`=e)l(7Bz&WQiP zt8H-PspByZ{8ipBf5kSNi}UE56aBdOTOj8BIfeaH&+6GcWFyzwC1Kb&8#)&pc|!u` zw8>j+2Bgcf#?GZ9$DjER*AU?UkcGIzCCpYIe%SQSiO;HJ2dv$53DcFJuOi}8Z!zbM z=qaT4?w~xwey!ko{hR;oNCMrN5Kqv@TrkZ^_)s`md4Y{Qzo&%h3qr3)5m(q?4i60# zdVh&mc4WBCR0-3ah~ED~yxawIrNMq-#HVY@^X&BXDpiu ztokBh`U42?6J-)E`i1#uNhk7dw?noo8`-V(t^byeKBQT~^NleN7ZqgS;HBAX*pZ?) zK*IFr)Zj<-CER2f=70qbq{)tL*{#@_e~zbw=}&dS@=18_T+AoU{fT&QfA(P*`S0Jp zJFvAF@G~l8iM}X1^gbJG{nPf%=cdJBzu*2vRf{sn=LPqF#Nmd^B*Pb zSBiN^y#vJl!t?CQY>%m`a~n6C{^}F_rn-b{>tQ~o$|T*s|H-yv3%akngz2yH!P6pg z@O4eF#GIXdnd}~4Kc_3h<0eX&{WGFRy>qU!U!G}sMZ)yy7H~*N z`1@7NMa>$DZDfOUy0G(9>kks9k4c$PK32jJA2H9EW*{oWi8=MzIy*JLgG&dy7d(Z} zMZ#tVn0s29h|O!x%K6AfZYoNcK3)l)Pa@&da?ICmSc+ML{Bu^ak@IFs7@i_4!oDcs ziEfxap^kNUMV*0b}R=kI_)}PE;3#zUhz7fvwA6=^Vty+rqBL{ z-~E&D(~+2OyRR41zvSfLcYD+QB;46?lh`lgvV<2cz+B_a7V*fw%Q?&0@9vAaW_gum+ zexL=U(}Ts{^+d=9z;hTx=F(DtV%gND^G>DRAXCw(boWy+gqrTiKVX$hA7rhz(_7PU`WGng7A0t&kOX(1{kEJ1^ zceRwKA$dL7tBkeOyy&er>Uw!X+1R-tEokIdEsYQ)ty6hdpd6Qruuvu95^JdjJmWpRk#HWTD08~Ld=T%@?~ZfRue={9nBP?Ut1UBH}I zV}N|$jzCqHOBCOgs+MeZe>wcDm4x+QBfhfNPOftjQnM2h-yOx#X8NfYSHItuZ&zRVVk~~14<{!Bm0J`EPhaYNRV*Lnv>-E z>FXqXcRFT2tLgGLM&T-7?InOsT_xPw!U+3 z4ktF%9pfc1XRU*nXFZ!E|M6~{YON{7wGT^pP}m$fT$@NZ>MmyMOa5}Jk|Kafu--7DeE+c00wh>)N0Pg9*0D2|MhF#IhDIh>3o+$jt5!)sgQ?FOZ* zF7~6?L?vPR#B6v@w1jh>Vm|UVQr_szQPuw56rU@TFnwb7%T7mCQ)kf^Wqh57Y&FdF zqvhjQoKSU{M6pvntXk2#cFDc6GbH?~8|DsVx7?}DX_Xrcp{u2~k}$mI%HP;$N_fo# z%*|&d%0Go>s}_1u9ONKjcw3VDyiiKmUa#D!C-zDhmQ4;%pq5r+=w-}y_tWK1H|MFIkED3ibqO!gPnTcYb5X)2 z?=UC)I3{0pe6*x>M}aU&3}JS#YG>lJH(v%t5(lOrOQ= z+W4V_z3*ezNw_ZeTUey}W}eLrw?z?#wHyS!<|N7bW5Iz(3|X^2ZBD&d&_C=Ky`IcBeMRdVB*pHCw)5?;F(v+GnX#k@;jRQ3!9rAZj>9Vi_7eUaYL4XK4DAesBNrR(XUG7w~UT_NFS@#@cNMdTe=8q%)`5wD6SU% zQhi_}j}aui&A^1cD0nGq>WF!%Z70PCyI-nLyXnXwE)s@63&Zve#L88elg-T(TOEF? z%#Kj34wW!`Hh?Gd{*;cv@u`>-O}Z#dSNu=~oThm3VF|zZ)mhQl0p1?j74fTEnB^VJ z6~;c_ReJ1l*5JN`;i<-oH}>BpyyhEb>yF(Oe-)J~y|Zl2RT8F;Acu2@bOtmqEM`l0 z#mrJ+UHhBLxQt@+4p_B>Vhcs$;BOK>G7$6Mx;+#>;JoqfE5-MQNqEg`D}`6~7YPsb z!ff)pr{d;-&#Fm(D4sA+!nZ1WDth+(Ea7LHF;Dtot=Jm#QMG`*(|p?@;Z5hQ74UbF zB)sSp=FK=Q;n_4E}=w1C3 za59!~a?Ph~H70Eo6d&B*s6=*|rBx5B7JXj%ps+U*R&>R@$5m8pa(SilVi%o>RuXP) zAu8ZKLBjX!F^@A>C}M0XROPnxeb?AQ!bLyiiX(m%(#4Qh0OtK4`YU$Vc&@tbPVvp< z5{|vlU*YclT*BJ%n7xk;P?+bHs+dQ9hywl$mV__MO4!obd>*QJG5nD# zVI9S>EwO6teh<$)Kln&hx|d#|I`_jo^Y}2u=iLP=A(f4+kgz&nnBriYLJ9wL#vCD^JKoTXTnA>oLq(TWA0cO;yB5A)=)V-+#qZ>Sv3QGByd!WWIkDr!!;DdEXK zFE3QH%mz?_-lqzGSlSQRQ;3OKB{gu5Mcf>Xf}3GbbV`BW2U zMc|nOsxlLbH#teT=*M(8x(`a2EXADYGDESVZi*_)g5q7PCA{8th64WPkA(9RG0XS5 zDEd!KR*BXWo25y(&w3Yy#p7gY1AVVxHY#;htaD0GU2RJ7$~zJ+zwN3>AG$}vIv+6i zX*)~tc|)vfsW!zezDszU!7N2F0U zaE=M)bbTL%*S*E6+ixg-W-ej+By@UP2M^c@BQOtZ;H&8H)mN4Hnqr^v5~fc=r#FnG zqkBH)Q#I!*W;na6)GsN16)53^R&y2b)OiW7-HAEn*IdP>nNF&Q6%>~xNLVPI3#VLX z3AZ|fdG4)wio@q7sOGbgoi9mvM)^Di+y|2I(Q?dZGUh8zo*$udenm&F@lL|@dF7w( zj*{@O`p?-SO%3)_6dDgyRkD#?^s#EuN08IIhPZ*HJunY(U7(n1W~1_CbFL#um_Ah; zzC@7l;whL{oBJzlBCJ$#a0b-XI^`l^`k-*QIVa&p!I+=E@>dLxGE*I4BVP%XFnydi zTqjAV+2tKtU2QMn{x>jJ^j@UsakaV1<0Qo&)Doso zG={&QBjNndm>(1_QhdJMK=tYX#gSDKrqA$&hn!1zPOBGe=^|z=R`?vP37_RC{$h+( zi#`GNu}N(S*RaL>v_^oU71h0p%$v zEMqPJ(rd+==jEm^nCjWV~hGAe77YVi~7YA=$~YWisKYa??!L653iC%aTK9vW#Y#XhfVX#8Dz{-Qps~) z5-z!Fn#rS+uCA5x)(mBY*`O|6#5|5Ao-#ldN&=KII0t>lQ&tr$`G=+!h6=7_1} zBMk`K9-C&GGx?a=!2_$&uPMuTqe2?iOeMGJPx#{XX{M8x`xxBiD0k|x3^J75gybi4 z3ESVEW?HeXsWRLJORl&ygN%uAlKplQUUGSwX-wg8#R7qaOw?hP@tKXM$&p;(I^pq8 zrkR{7yi_W{#euH@-pe3k-j?JYUkR^Eo@QD$3UZ)QZe#mO#t23QSaL!5jupr2X_?wm%NHiKgp=@lxGTzQ?Uk{@7nC3M zV;NKP_~~1cgZ&9Roc1#Q=(7n)sP^ZO$fQS&hn(FW;3mJbFIZUzs{rO}N~$(UpOP?q}$!ZkX2nOc3=B0kE?J+2MQ_#%eifTi~QW(Z;b z?*mN@%Y=)u-!OD*Ca{dJc+akdu{?h6ae0ju-7L{D`AmQsB z`RuG`0~i|u>`_7@Afsl58W%4$gW^Q3d{Jy3$LXtxBE-jG_jBA z*~9%J|8FeWKKDDi2emDIpgr$rIk^(ywD-MCb-x`Hi=@2Om1TIWnegkfROhMf33nOR z)3oLH5fLD(QKT2kotO56dHy3T7xE^Y^>%ktz@g)!pNz)InJmL=2Rvbqv%G6PVTWej zOjUx+B0 zOC3zrvYr$EvWZ?Zu{^C%M-!wNS>Du#aEr?AOwlxbI`J$QI@1 z9azQ>bVjv)!gAZrgjWUDGrfBJMEJ;(&v>)E`+XhgsFGQJ=1aKxhB~Iaf0D(pELifM z4J>;;t8FUPCxr(%{+kHrQEQu87*a$9Ic6z*ie(sr;Clnh`Ogq;5L?rfW#Kd7D_;c? zp0f-qaBy0h<(;nxXMI@RG+3vt;E<(R%K!x#(SgIOLsfUwi$%BK8XUy9=`Q64&n zdrW3hei{~w{b!APX!d?qE`2!n%VHpOICf6KkEXRE#yd|)->2#4aA!K473!_}WQN9|>(+cIwAkVKsc-@V>rko;ORIP(0pYOu5YmPh_LRYdI;cRMd zlTU$kvDy{oy?!hYh{-8sdL2JLm9YEnoTgk`(}Y3F#ka6rC@QJ;$Mp{Ls1S-WBFUxEV9*+Jo63V@h!5LPP)Dp z;c^8|>4IM=bokkBZ2Tk_E=>53gRQCNqF18PL@e3TnB|MUe_-*_OP2Q;2oHGjTZFBB zDZ(b9Jk*nAc##vQKfhqP=^(;$j(rzz&%O}Ly-{u!#4;>575IsCs>a;~g!_7Y7Jc>S z;;awKPxi44D;{wD2FsK76Mj(my~w#GRaEvxx%MrVvEkzy4k|hK9m1b?riu2Go{2_& zD1Z3DGS(M6Mv^!EA{;XOg>Y}0B7&!)98&HZg$_knNy>7)3WS@A6k$G>EWD?qY;dvix%mVbj#R;z)~!qUa$kxtPi_KB4i^MkTMY5YAidrl{EIfyib-IWd`KSbz)N zzKvlr)c1K1s}Xr@~K>eJNU+lA<+rKMNY(Kugx;71BPXO zcUd0bN;shLIq`1a9Z~xtmi(~?%dqAPS2_urY5v%g@PUG{qUh3F;*gYA&0ra_Q?R)7 z2Fr_P5?=n@BKi)vA^OT0{l*b2*B=lgZ~+sQTzWgOW7 zJp1Cs?5vo4IdX-I2#!4>AmztJwEIA~)XZq{!Q+zHo*iY=XO@3OM#Cb@ODsQg`XNJ? z-fo}pIeS5PooeCGn8w}=vLo1wgX3d@ZTFMuW6`&quUfpEgw zd7^ZlJtEeGa{OkNaTRHq`FmI%bc%4#E3-w8;GN>F5#^z0S%x%}I524!%fFu!jymlx z8Z?Lyo(7b=y=EDv;9$911k20w{gR>kaBiYFv3slVZG`fw0z@%W1FNF9vFuWxaB;U$ zVokP9qH_b3t2JgBzB&x+`8Khv_a)qI(jc+F$9i#1<}^w1(w3y9m2~_7L0BLPQ@azuU|5)vsM)DdY;4=U*k9HL9Ix z@qVdjEbF}RCd;t$Tog@Q#&XFogmZsuAzBw-Bs`>CsKq{ zRsKLRSXSd~S)w-Z+5opzAj|Dq5Z-^S9!!J;h&6RFbQ4;$JOkc6`UTHnIe8@E3qxy& z3G=3j+;vdCHI`*qfg^Bgh`JvC<%FZ0D~pADy+v?7lmk|=3`>k)wXP4#g^m$k;9Xke zv>7elKtGkkrm~r3oQ%XZ*HrSZB*G&ciVEi`gT$_nDDQm2GOYW82i_2tO^V z5UzH8#7~)8^~gaK)_UfLAJ>oNJ5>qK-JL^hU)M!^ld07oHCb-oFek3^XL({5!Uq@G zijTY9#SU5W$?h!UP6&AEW!c`3aKwX8#*I0fiat^vJDp`1D;OItY{n0d(9MLGZcjBf z%i2)PxP(8jOgPIp_YCv=EY~|rIAC0Y@o9VwvDu7r*hQA%`DKK(4$D_w6Siv*XZ)O} zk|=)!<#z8_h6kPz=W_WWUEr?_ozqXVam?=$ViRO+ppz*=6dIBWTbD|){G$w5|N<(p@`axvX#IE>X;7|k+tU$8~&y^-XeHwhPr9Ao@a zvuKd{{@!XvVrRc_e$8+%E)<9e2HuOV&|BRMsO@WGACl?A7| z8t2GreA8LR1Q+b6V0r2j!smw8Rs0XsG#aEFn#wXB77qWh?3lw=M&oDRK!e+o?8cb= z7`nlEiQ-`q2K<^fRby98!sCtEsyvQY6VOx)W|+BeyEd6O>3P zAL+v~<_6&pSiU=ru*>Rks{8bvhA1i53HVPQs=^-_sN`{Bggd_4tLE}tU@j`O zWZT!-Qs=s@Wu9E%6NPV<$nv1cLW{5b*-l4UwyPFofg6rxm%D^}Z(MEZGHs(JT(+2`2P{MLvcO(Jmi6C+ z|E>+Q98&jLTFU6p&yq#P$ObZo7T7w$a-WKXle!$RH2z!0svz5`PUVtceN*Z*;Ec@3X9KSrf zw(wSIEm_LZjabGN9WX7!a-rUYyF2C6YIbqf-bZ2RW)EZ;_cg*(o#kD#2#@?#NHdhE ztMdR*e!ug`gYx52^)ovZd zYBapbGA@R>=qp&B_>u6QO;xljaqimn6DU9W&N9rvY43KnV%fg9y$s#0BegZBJDs)J z@=@wpmZ%NxYlPiuEQdBF9N43wcH>?zt)Ge|=WNX~*4LP;C(HGQ6JFO!Xwx2eYQ<#9 z2gb6D`x?+AejOcE}s$ zBH=7Uu3GzWV=2oEV+ofiGgCX=aD|q0B+BYVmP68~YqYkB1A z8RZ?zZS&00;C+te!w%VH=$^F?)E-q@udVUKlAjeJYIAAZd~Hzvbu71QKzR4-h1%Ng zq1xzyC@(OwjH?9UYyyok_o@8|mtM3~%e8BZHbYK}wjaVWy!dJVb_Dv*CA`2TL@RtQ zOzS20X4MU5x#OVa8uX-Gvg2;T8_%uMy2NeQqUB1I(nnan`gNrSFWD^bx<; z_Vqul<&YV;t^-(xp$6Qrr&)IKCwzR_DXqZSvs$!_#)o+| zUe)P=W>@K^R#jGG=}MNLZojX=+#bux`v{L~_E^iFa!V^Cvxbf_EaN^yT;)$C``;p* z);2|pn{Y=vBcl=hm}Qv8)rw`k!*ZdYgufJfp(~Ulp5BXO5RnD z@N~yCZEyQT?U%eLWoxnwxgrf-D_J(V6aI1MtyW_HJ#EWJY<1_lvAnhTTiDqeqV1Ek>xHl@_`Ho}+;E3mFG#jm z2?uQcsr||OP%Bm$<#iWW#+`1sr<3H+WWpy_{?!KmdZ^v4g>tjEEJIEJdeMh0*Ugzn z2C4rZTmAdPN80#$C?6FsnLWFIhh-RA>X3$IS${`ZTa#BW z)8nZ&UgkeH{bm_<73$dXsN^0+^UBbTneL!3k9w-rmrtu!6^X)t%0b6HJS4v{65cl1 zQNNruMe8Z|ufJ@|GVChMATJm~c#U5{eRSaz?U|IvOk{cY`vMu{l8Xtq>t9%J0VR)7 z@S>Dn$MUD&g>*=Ka5WA^6F$(rsP5&GqNOxJIbLJgn5$?8xm^O`7d?yVP0FWehh;R@ zK4baMEvF3fvpg->M@S?h<^dg&|YNO=k{#}P< z7?n$z1}FL36Mp4bMlTG}pVJ%bJhL~;FnuO33dy@B5%$kkP7k}0tQkh3Tyi$ckl>Y< zo8;!}375=PLBG{7S-U?8<>?fG<+uMTG!wjk=*6_6Y^ zoAAZXHT9s;Nm?nHk7dctj<5_{5OwUnNd6U1 zcvj9j`mW0Nwc%2Jd7tH9k*+#+j3h7rM0m{Ox_aO5iP~r>ueHlh4N3K>tK(*OdO>h0 zLD+F$eZ6vAg7$t3{=h<2ScVy19XoT9^=5>Z`ZUz1cfYGOm&5p@ome*JYN+F5g5=&K z2#;ypSpTNo)*|J5il;BjK}8zt)q?J@oW6|k+cF0Ib^lx1H2DT}J(OiwpQ7W|e=2$Y z5yJhiE6_x5Xs1=I^TX3D!~BL0SwEIbJ|JwrSm%I3!1NedwfkZ9FW}&SCS%!1AfMW;$+- zBl&43!hJ8c(2E?rqcK1m)!If;S;0U>PuUk);>tN%x{*T|7@c}QjO&Y`3uO<9sJx*e_G&_)?Lc2DiXDU zjD`Mh)16;K!nr~_=*^Qg%}dt#QCpTDb?TtMnXYS;vB*AvaP=CU^b%uKtyl%Dv+qQf z;hkHLm|$Uf(>%f(4t3Ut6^qe!)I<6G29`Sx>a61qJx+b?A$+Qyhi+bZObd_+s=KFH zh8JEPPXQtM%5}n14|UaZeL1WhlBus5FIa~CiaMl5S@!xyIFD<0-O%BnRzhGke&s7j z_aN+7)a%y$|LuI=OEZq@q4(XgU-Or#uO0Q7!hS{lZutLi=L=~`cuUn@`uewfwW~7q zWgfsXtS;8^je_c2eGK7(JA3QXO}n*NnHf4dhh^BWs6)DrWqk$VAe+AW&ETEdHklb3 z63H^`SJd&XjY{rug0TPSe)_155!wP7=K|MQhNOv(C&ZAP{)q4hwZC5a(l*Ucrjgvf zvJ4AD;h7S~@`7xIWRSYs4Ah^V->jXGX{3jxh}yuCQ|OD%V6(=JIl`)HP7nXHZ*1*y($rxLFHW{|$6$7=0{l(&Si z3=43f`&z?t%2vW3s}9ktxUA6PUGZ`^I?ggI?S&p`CEqFj=LwG=I#j>>eVJA&FUpAz zSw3ERD0DKxEIYg*{Ce6jy-?s{t-ufL3WnJiriL_Z*f1U6>Z#w@S%~o9@Zox~1`D(~ zZ&9vWon@Fg(f{o#Y;GWY;J^qy_n~=OUAfyW)Pv;%lSV*S5XdFp_9FcBz(_r+Ux2pn z8J6ts&+>qnkvb#-IT~XZ5S|b}O5YzfO~vkbHGa8a7GtUV>XV$vl2#mGjQ ztGr=%{$zRGxJf!}^w(yM!VSi~a}||AN~r9u|2P2CvpuoSM-wT5ZCH zd)~TFgo{>t1j>cmuzdBaw+`bZmgn^(?6%ZL_xe#*t1|)RnDHz>nd$=r*9t6`m`T{L z)MS17S0_#NMp>+3d4_2+40}qzYaZ75XawPg`egn2h5TBvbttE*EW_j;+=B&KZgYun zp4Ps)X?_kZW;eTnD2oZM9iG-);&#CO%tW`Vi_|&_wv@t|@x<8jmcwAEDg2C(E#hN5{E- zl6MRxeCo>-eczHR7X1UtH)gO5+a{qQ-C$WPAsp7-Pal$?S_b?^d0GU^u$2hfMl8#> z4-$^v;HURIyvI_-ZU)H9F0l-IEOp%6SfbVpsPlwG!XIw<=}z}ISiGE3{`8(@*kg(P zGs{_Ripd}qbn(}V6D7P@N3>&L- zSO#K=n1I!&(}D22(f;}-`}US{BTzm&lx5hx2?N*OEXR8jPG0S=r);faN%Kc}#F7j$ z%w2 zWP@_?KFV)5WRNk3N+k#FB0P7Jzn;HzvQqp!%5kSy#)|?Id@L8gO89}%Ur%US(AXpf z<-spl#>)-U7O;o_t8wr%;ZI-v^Z_>-7>5IeU4;%MD0C=8Cu5{Kw<$?@_GLfa=-AhI z;2O#y^;yPNhY5KqIi)$_(o6jGreU*;KV>yc{aA(_dOGx^EKeCpcv3Szy=vhQQUR z%5ox<0pmKZMzbWsv-3~U=hr!BbeC7~Ogk{*N4sR1#VJQ|~Zr9C(!`A!g8<#nVa+^?& zJ;pL@6x4BZBgq%f5O&G#qc>RYB%X$%JnA9Kuu)KlqoG*#d`&pMv$x*1XgN`TGs+|F zOHo6D;~3$MzBJ1}90@dD!nf@sEJI6APH{ifxmeXz!Zk;wx|CZ2I6dHhXt#p=gBm-|j zEYJH+xUADSy`pzNk<}CBI|WNq=pfgI!ycAPlqI~f#aO-j$swZaV3b!hVfn+2u`o3> zh~=ZL2-hD!M$eHtMwA+ka$zr)<1dfVahV?dz&2wE`}&R6SAF#n4P@x_AeP~T3%p@j zezKDA$(5t@xJlE+ydxsVZCk5r|<%z-!)d;vK z3s@F42@i`Hrl&7lD)!bz`J+3_cGZT%T)`5SZ+9a+deu;UWQ`CpxHigb#)mm*Gd|qLne>qtYL&5^A6Epd#({qQa-7&oa^pjnC)51 z^2Q5<$1NSCFaEqi1Xah9yFF#OU+^FuGI=c5c}sX#883b3@6Dotls$5lrG|trVy60= zS&lDE_|n6H`ufRXVz`tmxw4F}c#x)K*-Ih(-gBTn`*FC)T?4CO?#VK~JmOklx`N*Z z5kBfYKyNX8hbSrK<1<)>V|4I^m*wDvgf|8E)AxVbEn3KGq(`tkYg9jcm1eo>0m6As z_0=mr+bga~Ip7k@urO3#x;Bbs?G9l}R3Cl8p#9>Cl#730xx)S4(4M1N?*5x_*O|R_ zL)nAkpp^GHm7~y2UfD~BQ%+eUOC2cP+P*S?)1=` zr5_WurTlOx%fYeTapr{O;u8r+Ozo}*ro;%7l!KPA+^canoReYs;9A1zS-R;jLM=j< za?L|5mpkC0+t{3Bxs68n*ennIdHs{3n!G3pi7daY+yw`&ET^OpzW1rK-dm3qlce0( zraVOhHaF^!d1QG?Zo;Nc9rfQy=R}gM#-qwC!{$aEPYtEPwnH7lOs4(7Z?;#&Ja}z@*Z)&2!!C8WyRWf4<}%^^lUwV>c3l&nUZGs? z1Ab7srTG@L!5ny^8I`jD0FZpnvRE;QZzz~5%$R8ra#zvOC(5n zetnkVEfeQ*S+3obaA4c!dgR(WqMfY9-@Yt|o@uJX$*e427)JQaoTj?gCP93Y^42*l z!;Tu5lSyQG;8Ma3jtad>Vxq{JhIMWk$ugWh2c67)mcJh&JnOllx9fRdm}KZ2uCWX+ zyEwtl^3r>RKNmIV#o`}`mT*`AoGg!WaJQn`%QQkO; zWjH+$QzYD;U-=O3w6m`6e(Q;7P#Bx2F@$9}mk={GEC*~P+$_pfuXQI`oO4Dw=W&){ zV1hXymW#y_ULRLWAH3kHIOK}5`$LvtWftbGSU&WEaQSOB^x{2I#IS}ace1ZU4JoEg zbsf&BWx2Hj;hJgH^k;8UghvyUuT^6ilP@s5Wcg8j!ge33=-y+WiA@HSr+Ki9X&v0> zM4h>BKf+hjob{TIo{1vz3G3|7a#F?08RYzP3AaeDr0>a|Dk5dc3%9Tgr(x>2r<2AT z5s`#z->#q+=#(m!_rq$`KgaUT4&^h*hHHe+z9^?V4o(#*V^DsS#3GNID@El+p^|Hb5biOrsNTQT zGjVb%mRvWA<>1)D@^aJ2Jnk6bC*Fniks55j-H7tNTP(LaS`gEeJlG!akZ`V{1$CR} zPsOi2DEIow@~=oo*+i-2&sm*ikgD`_)Pt)%75fjNY+IfvY-@MG%p;e)v>M@*HV*no zL$VOZP(I|&@`#YUm`r5Z*@JKaV_to_>k~2VILb4|vyAy}+^I&@F#8d{pD(xGxWr@8 zU&>|Iu#A~>>{O8O)+KiO{Gazk5h*XM&2s1& z8`Lk|*yY{4w;CHnzhpu|;0)CYM;o6QOYr z9LafZ5snOer!`-CLmZHE1^3^xjAxm`3LKUreh|JKCLsAnYr>nZKh=DvT^1vyd~YbrxX=T)5RyD{ z9N{8I;3I{eaiWiuXDwkF_D5=Xm;%W*s|lCibYF9|xgh+c{O2Icc zoa>ZWBxM_CmNB1+2fS0s{c90kyZn;YcC9APNO@lemN7*MtE*Z5)}3&{t>?9h`Bc$R zUX-8SEMwNO!u=C0FPTpG&F0hE)Tt*#s+1pZU>Sy%8l1C>Ha7Y36+C}RG(!`_u=U$B+oVy4sbf49kAakrhZ2G zeqWaH^iJFjNpjI4gge&QtJN+aDH?x4x#C=w@$^prmpfQKxQMVfTR>+1*?S+-1b3l9;|U$NvT$5@6JbPck2ERWF%KZshag}Vid(((#Ue#kPs`a{35 zgk_sl!s^u^ZTY>$qN0?G+1H?G;8C9gVivNzE)U@bm*#1`l0Cr|H^~xpT!LDWCOY8Iy828A2uZ zpH0~PtB)2@X118|4ojZAg=IV!6iVkC_R|i+zER_~v?J5RbvYr~^c>4D(}U~GSza7Z zc+BzJbr2*C4WrT0GZ>Ob{>Lc=cqg*+Zx2vEmp7Au{DWa^lVnS`P{0z#ypR$Y_S@3I0Bwu?; zc<-6w+E7bX(fv5e_jA^!h6I~PH8|LwP@&MWQ^bHq&+E3P3MfK~QS- zZv(>9E;wrOQRT#`%_zI{WEs9=1&d2dv%H}{;cwA-wcABYi?E3(FP*{iL}M-ucE7M( zV;Qyhgwaioh}?yf)ko@F@q!h+x5qLROUB^>+xn`Qspyy9L}tj1U;R|*|&M}m3_ zTCuRGG~tW6-dWb_ImEKcC>JoXj3>LoE+dx9w%BS%&vl+!e+0 ziP40Uhdj1S{%a%R-r)XUhBQ(&x~(7_J?Wk$zsoPS>6rx+ z8MOTD`EkO70&ZBgZTM(B_!>*@naDB>04?|hHIipNBJAgL*|IIq8>5gLaO`dBP&D8K z0}HIKX1Pc?zncR#q{)ovAf*3_xd@@xN#2; z<)n3t+tLZQnzqgIsAa72O$?k-;N%6Cn-n5EJZht5`X!5ThFp8;QJ-bp zI|vbB`C1dgQ{KU5!_CKxm*f%uS^KdJ+j=Z`kSJASv=`we9wC;Jdk-12OvGyJpTjbq z%?pREv-~HBaR0B1Ez{rZGcJ*fOY26mjC&qkbL?e#O%&nyu0fUxH+CC$jK`7_uCfei zRSSfVKx3@s3S?=&u^=`)3Qw zpr{4LN*?%2nwBJrCm!HFRF>z}CcJ-{Vp)@CzVWUJ zd15bPL3zYq*UcXw@OiMrnE7>mwU793O1zBK?kZr%QMo)Yid>| z+#%quYU$->ymAJs5!#q#cuJ@+L}K}Ld%}II#H$t0n~au2C@&hwGQ5?l&`eqO^d`LX zrmhA|GZ^3OLAhQa%g}SFc!B^`pqsDGg5IUKFP~Y5`OY@ zj~dsgu5tJ-lz-f08F#hgA`6nsJtzFrEnH2?Q^VL=$}4}cj0;(yO|z`#Z6t%V^XCTD z2k34oS1U&pPJ&>i{vlR*&$Joy*j!*>fDru#;gm>Lo;>w#%TmJ>=4?z+fDjo6yYm@egMwOEEKsJKjqN*>>w@b4)_)bP-3 z#sg!qDK4iJxQNnp2Tr^K?_*oezKh*W(BFoT_%y1vFeDwk0g*PM3BbuZu zPVz%tTi>w^m)i_gVR=}VCNf9^o-H)LSDq<8K3I)xMTy$L{b$DG)2YsXs}Q#P+SP0) zl9Ufp-fv_XB4LJ`R-yJB(wXpqQiaS9jklF6Yp~>AL;jQJ#^8wRiDz)*n^{SG-17-1-We8mp=nlBfiyaLzbh9`4H91)7h;nE#%JV7_ zwSj0DpgZ7_D>ous@JVu$y8ZSkJ>fG1uwbEmCYhpfYyja}^Ku$K?uk^s2BMtPn`O8t z_?dgIM#uSt^RBON=z1eusWlblz3cxgc`lr>v61D}J%qF09c`%hI8-Sl+eWvOEJLXV zJb8qw5qN`e+3=MHuYs$TIN6?0q*|2=eJ6b3!8Sv|OCbtHMNmV+Nc@w#7bg5`eS4)!;|fY$ zS?3j1t;+8Vgpb_lqC~tZtJILusL_RGyn1*QsT%VJ5mqDnDa+OtRd!1G+7zpDiG_r{ z(!7+g@&%P*Rq+R|*_=VfmPaKY+)sGC=MZJfp&Uw>l*^rE8Jp)nxx*d8WfI0Jdv|70 zHcR>9Ype2;UxaUupQPmJY^%6PxorUxh3v73s9<_O*IUzhS3-uXjK+#3Eyl!M{$3YY>1a~ z;e9M)pMiY`RpYjWaJIBS#W3QUAyvx#Zd#Scq!3PXU8ocpbKc-u9jnp&M<$v2y6m}| z${@9HTcmWXf7&pyBg&7<61Blj5j#hcH@XsT^5_avjLa{9vZg7+1jpeJX%0spj?saX2Qlk7egOK0)Y-DB`d;NcP z{&tCQ<9chA@q@M+>dWzlb8-e5E;;|e;17hS_F1pI_X;+oNcmchX4H_d2OGA7#${XKVm7{H%%OC|ige#ASH8b>+uO7{c61Bk*!M{4YI}_g3X{Ta1 zYce!Dj3w_fW|HZ3>2U|bi-t!k-I|#Uk8h*gb4Ugm#~dV2^C8@EQw&y|SUP|5!9JW}rCZB^blhj6<}hm`f#r#Gqd27ln|^;YF3k%a5k zKcw^@GP%iZ8M?reEaT7;2e0%4FJC2mc=$2p%!#{=>BAXipIenZzYzX5^@OtHLaD}! zWHn;)y3sxOza{@HNqE8Z80EXI*3ckjk9t<+RV@hj{uHC^`c?Y)c3J0yK33%_qX=hr zHY*GI1|7dEPc8`vuqs=Y6E4%xtX%Tjc)Yxn|Ln9XcRNP7eFL+i?A>(S|24*W#}%vc zn5lyAXCB9jl}#dL3UU<<29m%I*9J2dBg;xdU4r-z?=n!5L)e z>td*FJlah7uG49y(1iwA32Medy@(NaC)ay(#{Xo|rgg+$3Di=rCo2O_f7cJ2G zU+ADSH&e+M$`TegW0h_Voz1QZD1T{WRUX=!aLk2RB{Fv-^M+?AZyLxlzU=-h`P*2+ zH$I+IMs{p!ejsnF)`3<_Ubc#`|IIVXh^B7lHPDOx{aeXQ^vbnZkb;5%4cL`Gj!ITIZGck)zCCzEv|$`7kKJ-0u_q?2)al%5%CC{;(%bIqx>tT<{~x#m8BdOHL>3{vuB4>om{o zAn9N zGs1mm#VYe&C7CaIeLRG2G?!^h8Z5*Q%X!F^8T)sABsb^Jw(3EhM>M_c~Wxvfoc45g|`&gB| zhZ9zuW0aJ58+EOe+Xq;cb1fr$vT}^l?u@NEIuc8c+sQJIs=3bF4-@|J@rY8Uj-Bc$ z>pba-Rk`tf!Z#BSDWm(^sfFaz(fPAg`I>D98KjO^4=Nsm?9{JPeqVwp55fOGbi-W; zcj$Of(R$jc(`B5OHn%FUk|LxLtYZDwr!6h zp4+OklTp^QbfkuaC1bjPO8)FX_`~Ym3YjAw1Jkb&-m+-B5?!x=Iz-B`=~m_0UkN|(30Ka#7f^dh`Lkmu3f=#fT%t5# z`|)8)pSA_m?^52}$f~^Gjd1G^+muz!3#b9|q4{Z`Rk_t@!seK5N{0po)KDq=1X`7o zLI}I=*rxP$DWJZQ)o8dclT3NvDaQ%d58tMIEmlBX=7`zZ$~RfYDH04F$$1|UUgy0@ z*_*q7nj}yA^!Q;_4zuqpgEVcxM#c2UQEecT#J|cCg-`ZoELl`1T&ed4CH{k>T16(d z*SEGR-|`^*`N4Xn;Y&v~t`^q0$T+L=2!FyM+t({LPaM@nwNbXLvMOiUN_frk^-9fq zj_N@v_cODM(`WypvHBe0sXbRK^KLn+1El=o97K4d(^4fzsH0l7E{5(~m{qw#6ybFH#Y(^yM>Rmop%<;nCvFj*VYf)R zw%JiFFXiU%tjgVf63(|^q2jd3QSDO)t8u!B2Zio`>-@SLVTY~@l?qVjiSh@IGO`Rq z_zXXAwmadxx#ufyL7p$;TyTh0x$t*xw*|z zEu9zZJU7~^+*&34c}ReAI|44Zd{3#CU{$`KOt@gp0A=e=NA;+@yHEVFDo@PWRR*bX z@c<=05-y4ystv0|)COnL|8#wZbO$YrT9Ka^_G--t+y&)4JRBMJV|K+@(G%5(5=d&;t1DpnWT&XdA1z5 z&PrvOb0Pd_vwu(c^}3Nt9LOc)qs=*QH)=@#D{m@Fcy^zmN{%Q;^`?|>*0n0v5`-JH z8LT{pl8?zaukT}3K0kzTTIWGZG|1KED7R&RRe9)Q!j)3JloC*loKk+blVwaJ{kwuc zq6tsv+FP;P@2HlP^4Kd@<+TZf10B07D-JlSx|Gv@S(Tmt5`L1@S?PDjL2U<3^zYwO zmAcE&mAcnanVjUH(q~{tI1{z`-^z7sPk8RH4obo^2laX86>NWvWlU%OYl}BO5q3XYQR(^HLH#9Ha+Uv@Nv46t z&=Ngm=-d{SRkGRTSNj#m?(%9WqB3>-@3Hi^8Q~eLN-H_CGDm}6)zq9Klqfzf;eq~Xq{Az<57!A#yC?xTyWO~vp zu0ptOK?h}OrTl85oDnNj-Kt!sGvPyB@+rm|`PF23&)@a1Dj)SF>{BM6vbb)3bx;y^ z@w5F|hL@2Hm%GCz!V7%um8OmItCMe_oMme!nO;_3oF<&m%2vsyy^F z*w-$<8rT5k!%Z^Dl(TI)fUqIzm*HjC{Oa-F{vh}9Vi|MH_<9CwHKAinm`8Z~;@5`m z+p??T7|Mx38DwnFaPSex6ZQ~}Yw*<2AWI%K$0(GiMrDw(WH`$R5ATN;Xm+2!zH@R3b_&Qf+hmgAcp{Jok0I=_G0D)r@L%)gi74+G zpGk(}i9r6df^eCV4-KQQ{4uvk^#!@lnoKh61Oj=*3BsZK9vW6?f6Ontq3mU08RpsK zMS*kMK(6wb@b&BQhIMg&%)?Jk26^q%Ofn3LKt7qRuZ+g}t!EAX&;OVQS4DYEE}}RU zB};}Ahd}OIgK)3Qrwqd#{+gFe@WDE}W|HB=A&}p8CH%wrq#@e$*St2u8|1S+Gs&ut zH^_lg371%}8&>%KH9KCL1ai>KOfr1g4&+kX2)iuT4HXXkHDCQQ5#);7Gs*K`PXzhc zdBVBR>4w&y{+dgdL^wT=b-2O$i&dbh8N{dwj?w!y!T-KP}WxhVIRT zlZKm$je4T_c#xBvi2fHkI7A5KsRqKSmrojY^|Mi(dX58mmWgF}!Ip7`gBC$9G>EX< z@%@H#{x<6T&SOC?J}i^mBi~q%cP${?pw&*p@>MqKp<-h|Ua=&T4CexYY}!wFwk!O5 zdu`O*??!>#<4`6U&IJPb?rp-QJhmCOoU&1SUKt7U-^5HZoPG)N#9xHF25&X&xn-kv zTrvXW?Kb^ojO1sm@a~2qCqcHaKzM%Nt%jgyHtIsdaFDAyXOiKlACN=a5MDigt6}>m z8#VRmP>^qT$Ru|I{P%C&350j-*lGy2vsIf04FP$gPbRrkpCKS$Swpye`c}hg2V2!C z+hCBJZpg4GIKrZY+^uN$u^c?_lHCMvzONSXIm~7R+r~N>- z)XyY`r1t|^>q&TX|1g7VTU+&U>%Jg+^~)r~Zak2?&m`==D$LNLtF5{ys5i*Yb2G^s z*7pWEJ%X^ynJ~ke-nQzAgq|Q@h|DA>Ug-&P&?Uk?Z^I04``N1V^Y;LG{IyIn?DGS; z#0SEKiiR7U`rE1>m2M!v`jSb8Gj>2e=rmAiAU!&d#hxHHIZZkc2_BpKwCp@i4Y4>v6AY^%;%))C~$QJLhdJvxHyw}kM( z$Z*4Si1XMP?LqDol1YYRb3k@DM0m}maKpV8wrWsdTaZ5=%OwAp*%ss-iG=N6ha0jO zZPis%-9f(bFp~@?SA*Ql##2UPcJ>Iv_Xf7=!ojUTo@!6@zi12_)(Yg?l?ksd7h&jF z$5#E?+70CL)icQ}o!mek(}D2c1`&qlwQSYKIh%vL&?A%FHcxYqv-l7$)@9FkAt7ftvy3;pZ~R zu%8m-i_Zxswumqsu5POqbZ886f%Hr=oWu^YXFe|(y7Yz-218|Ab>-OxARj46^uN$m z3u*xJk9vgPl#ehJDQ>F{=~NHo$xSlJ@FoQEvc7~5+D917*=<#?R9BEIcx95|yc&=z z&msKvNw}fbI~z50UM-O0f-=cf`qcti-9`A*iEu+Ibh)Fm)&RLuYgJkH| zGz&Krx{+%BHoFqYQ_B;Tp~I4!dsYIuSPQ}x%Y_?q8k5aiUzP{isZA#N*|qW@A0A0~ zf3|SLv{#SJHM*1q`Skcqa)G&JL3UqGc)|NHL+F`@=JCH(nO zn4xi#hvxkrB|v_yW|FU$F9EV|5@G#Hn4$iUB=eoEP9QITnn|9#(g|e8tb=7Vy2gYV z7A7W{Fa9YEa@Sl$|BFVktVRB>t^1Fw>HY&aUMfx!<~FN{YE9<%c5ZXKpHC{qn6IBR znME>%NLwqFAN`ONqUG0!r5Yu}G79KhTAV2;VmB6cSL&(r{ZJxGP&9vUzmkGUctizMu;mQv1l2AuAr z!qaOz1HKf2xyPI=QvYMMB#@4P9imlukyS^)^V2aqjmaWOE32jB%Pj!^vAq?un?QC1 zdnQ-_Ha>~jCw)IjiKv$P-4g&Ol&NsZQvvYi2bi}ED=OYQ^lfhkZy4 zKXL^;sLM=c=uX)GLR^i`O7d0{z^T?)m7!xeZi5NnGdj!-vv-oIo+Z-pH%5S6-CHr+ zXNKXIynv_qVV*tfAh}h4RJwQh)eyKM1*&jN(5oS`{4@cxTj&u|bEZ%#3w{Q8R&&GDgbnC3}JCkLmzVu*bZnp@bA#Nz$;3HGo~5RhTV^CCm4R zV}8{B1QEMSQj1g#`1t6zFdP{6LlVHtf-#4ioFI=5=Sto)t^y7UQ(?9Wjx1ZR#~gjL zgd8->l)e}MPoFok*rLMhq4cu+ivjbDoDw1(+A4WXJP){{NQK#IaI!r7Hs+|ACB!>B zO_Kdi1CFUzVfOrVS-#yaP#L6%?j@whzRgm^v=e}xI$>3Yj=ezkNOV~aAAotsg<^8n zd$Sbha}02niweU7831?q0`s=T#l+KkvsAUg0C>2s3d3)00cS75oa9_JCmGct(yh_yY|Gv%%vL&)1W8PI8s6hr4ZecPV^VB4F2kD$JG`k!8bYm=k=8$=u;ovU?E^`22)cj2A|4$;c=c@WgL1 zf0D9~#J$u@JG;RX<&9=XsWAK(0&x8gm<_hMq|ai#G-7ll;CtIt7#S zC2mHNEcyaIqQUz24V47Ti~#oj7_%+OAS11w8)6Pm0_?9>Vff)H;Omny{~VJ+!m1w| zCd?lPxVOIwvsHd&`MVg*_B%32H?w9#lj}&pml9Q&JziXvEweE{Fk}#0za~TAyF&p- z?^R)!X?nn!XEB?XWsoUTnhafD=mA?@QDJyc0ASr?%%5J%Ab!6z8E(~xfET`0Vfc9| z;BuQFW#}f~&mc9rX2Xz*et?}EvHml31FM|?2YFy7E$}0O>SjZ8$p?VzN2oA+7CHRW zDG>7%IfD#c^VqQVKo7thL;i*14eTNDvbEG|d24(OvC!1%b{@+ETos_gZ2bl}yW=tUs*NE|P8wIQ*|~tH zC97}*JlG!Y%yTi%>lRDg&i8aZRi6pC>wXo6uT=mJEyvv1J(eU^IJk}v-U_&=QiWlS zE5PQ@FgN(elH$pBuHkhX0cRQoD`WJ}Xu$FpfHUnd*T%<^Ne`@CLxR=<9_g&Y@S!|l z_}!1PjkK&-vc9*4tH<=!fNMspFk6#BmM;Wh4m=u5db_l7z2mSFaA;U7hIcB$4hpQ5 z0XQ%f^R=gb#ARWNZd!37;7(gqTV@M5$nxs~%t2<~lBx@hy4~jz0PiVMVK`d=Z@Pim zuOW)q+Slo7%$EWFpk9SxjVr+Y%;qaEFy(MGxs-NScgA-q;PQ@G{~0>A+Jh{Y^u@gA zSS-nZct>Y$@l>?TNsE_aI9+t%bHi_rr zq-~g=r7b0vvl?_yDj6P?tHSsKdzNCJ`FtrUact5Zvxx(2QO?B$jhLrTh$mH{&vlXT zfS7-Ge!= zXa~t3`&8#Rk4+@&LtH%cGUiv2*+iSvpu5>_Ip7mFR2b)T<$p1sx|U7Wr&jBt$FTW4 z&FmXI2iae3@Z$7{zj44^Ut2)FD7V+Yy3TNOUoLJx0`su>$H|R5GxU=zlK`)pz{TnF zF`wFYg0!rU)8BfB;oebP?6Lv#ADc_bS+^DX;l>Q#-`0xZ?cuF`J||&*GxjR+%T3mw zsAKz_TFS+$8_%Ccia3cBqgt@!Mn6525rw{GV=7#-VF8=d0=Jvfzs7=zJ`l(55*8O&w zixd9BY;I#plNZ0yuN=hij+ZKoXNtpnp~}$ZMVQi*_9kTFGj^toe;+GczSs*iVMh@z zUkBVU4_#qO`<*c*IbSjSd}J$TpGq@~XZL?*V%~Y91N~u*8A*G^E(KFVxVUyDX6vTT zH2azvDHy}B`9>~|*@wBbstf($ju{y*vkPP45f#QuZs)6*UGgl^;rF&$#aunvy zFE!Mm!h|^8T?Dx2WG)U0#r(}58v2dgh77p95b&XBE`GELv)6774fkk6G>aL|+Rnwx zk6{jr(a`JJ#-#phhVPZNV)p$Fb_8*s9qwTsTHK8;8DdOc1uz`b%*6*fgeim6`({tN zq=PXz>BDe{HCDKozrE#ABIfIL4)i;XG3n8nVOMu9uK5zPPn{zjG2WQ`8Xg7sLBLy> z-5J1#wlL01Vlh9M`9AHl@O@&pasl9!WEEyhB*}8;9L#67zfTRK3vmhv1#G#$6|=AF zur0GCl4LpO9OkVb_oIW$hmcpl1_S=3Qia(PN$_Ff6UI z{H!--0=rS`WK7zOXV}k$i`S0DY+jNE`D?$b3(e7RyYXc7)%0K zx3qII0#W#0hHVfBM+aUrm^=9~F0T+i~#Ox8QrCZ@ygst(O^|gq?7$H z7xvRqUn_x39m$4Hqvzu3pJR6JrKRWJ5y%+@7ft8lCsCM>_tetFP6BzX;K)QSUX_7) zosE`Wv=qoC1v~HMV#iahSfiym9pFq+@U_caeB>eKeU@5UX(5n-3SRP(i@&g1s0`ho z?X+|d;Ef74am1<`x;j1Paj;;}=Jo}MkF z1Ne!8+im3H-Fq?jXcp;Wz(xw*SIEWQS1>Dw1Vx7mhdK$y)|av{USXJc#?vT_2S}!A(&_6iL@N>6~cxt zX*3s)4!|6=N2HN}+bZ~zFfOiNg?Ym+kv@YLXr$nqXJ0z?HdN{L^vF zIU7Ve3U=c&Wy@pAx!9!+v)?+A<^vWKT-U%?U_P2G(kwVr?kRXv5ErM$VcxS+q)%aPBq+P_X(|`@-ibLS zNu&vI3sIopI|W>P>^$b>%SB3^1Ts;Xb$&Ov_^YRw*Dn*P5!}f*D5sU9SuAfNJ?e&e z$5N3tIt%22vgLDqxj23(WTPKkI%2o8|ZCpI^Am*Q8%UwSb$YcdiF6H7|RhZMGMEX&Gfix@lXd@R#n8YcA z6dVb-uR#7#@C*%B)kM=t%BR=xj1_qX4?fK{qjSBTvPD9>0Im5X%Y*Q`6HhK@eAN;#IUm(BskJ+31@?004NjvU(;)4tNZ|TjcR* z72Rx&@Ms0}9Q7=1Oz^n5A&jgI|LDl}F9U>J9Yquz^&E}xnEo0hY-8<+$N1NGSv^Nb zBYSH+=09E`Xl3nf3>1tU@iczVBPje^zLBdV9<7+w?>YJZ@f7&SQw&cFk5<7{&(O@; z1drvf;i@wF=0*mNc&vX4|L1b(|8)a=*48$T4tVr*f2}~^_iBu+e>brI^)6*(Xr{++ z8D!EassvDyF7#UJYV7e)Lb^l!}x zn_2$eD;}+|P>|Obz$#jn@=d5zv6Ujt@i{Pu8zrd4!wrgBQIxm z;!XQsqrlk1Ud-m9{L~V4J}`!kAO;@R&B}T{PXzeWXY_S}N6)h>mqGvwFga1`u`uqU zFZYbjFu&XjXg%bJM_yP{Bc!*}dbQ3NhPjk}ue3T=NNXx*PMg7!7LpyB)TMfR!kAXXGs-~c zQhv7v992<{o7sePU)kC)FY}?JI`I23NI=^|8fp2%FVkw)STX_r5Cxvu*Q;t5hC%A9 zcBCpACG_vV99hD)l{=a9hd`7W_+dFQxPy7_Nw7&aTqzOMT1K?VgkzCkymj}1(;Y#l zCR4E!%&J(*B=nP9GS&C#02x{zYn7%Q7%Ht$19E?x=HHn32SWb?6ZHRp>AwNRAHeuu1jV0H|DO84Ma7@E{sT_`M1@kH z^>0*ky-^+^fD~$t4D+6e` z+M-C6v~&$xqP=qv`t%ffLO+zobsb>F@Q+$-gH?p`_@BivATMCLQlf4wLdN2emrp zb0)(ICp2s&*f_^E)K0VjutECgfQb+}p(umMO%qToqdA~%n6kVQC$FLhL*#fj^R=Zf z=LCl*n{7d$lNx%qkL&_n<;tjNS*cTK=h#fyb9E<>$+mw6IM;JN2wL5}ddCk3Mzu-` zOB&=pU;)Lw>(Vd@tN4d51?Qt~KsDWQ|H=SJ#TA6o;?e{1T0DF++8~vURO@z`afvWP zl!uO+*)8T^e^;z_)LL1ql7-R<(ML6Ky38vX1gj_b0lmnTE7pPw zi{-kap`KDIp}*zeUvEcMh@_2r)jSOB7>A;eH0`ID zY$TYbVtzguzi1>gPT{ksw*CajjRQu&4gw3nd>)FHM!@vtO(4?03z%AlhOKKnrDvNZE-dAtH zhp$h_X~Gwes_D991cT<`w#hc8Fz#m+8=0K0Ozn39X?jW8p5`$3my(6+l9+xh?(9#x zuJ^;!V_F#gL2+Q7%I<4y`s0F#<{KiE#F?RRaiXiR65YELoo?|j2`?dQ^_1|zT)aTcq|s?4<>qI*jYWK{7x6f zy1GeNH-NYs07Q=sOGSB0K^l#op9@n|g>=1|AEf4A%+E>d9fvZ2`|+`Vde~9|_=%)$ z6K`>=Qg!`#^7EJkNJ%xy%F4d(ZaTdc*zDw|+DicQODtkfXZ~Otvm;l|`89H@RsD6H zf>HI$`1}?*3a);Jz(m<%{<9lbgVl5rh&qMAEyf@1Iu*Ek8Ve#<(mT|B%t~w)MZom2^8zfu4rIB5-YNfa|Pt4AB*9U^p(YJ5xv0 zrx@Gs@V~)AKj|zhIg}9F6PZH;+@Xgc6*ku@+9wA~#LOV4a z`WA+}j#xlqab6at`A~!BkE}O!>BPHPNWE$j7eD*OOV+gwy@j(#dG1FV&HO5RmJ=|8 z9^-sGU0GS+zOtW7P_Gc)@Tesk2xy{hMbRLtEf6R^S>L*?Yfp}czIK?)Rm}>8)E;$< zrk<$^C^Mx~uCca5z&sX`e>`G;TJPj4-DerzD1p2Ax)T zX+?wJpPK`%5CrN#7=0P6EC&TiSVN6cceJ|KJWKc!8I9e2E#(NgLJvZc5SvSQX#S#U zl~cluukL=}8}g)Ov$elhr0h2)$N2>Zqyfl#m)b2-m7jP^8!EGi28YoQPsnRqrURBr zg?_{4j5DkEh5ZY8ieEe7oEL2qb0vHraK7`XL)nxaFG9~W6sHdO8$`%f@|1QX^$cDb z2q<;s*q)#nsBLFp@(&hQn2@H97LqCE$|Q{6 zWE9Lvkj$KKATF?Wg%K+n8a0m*cx1ZuTLU5^%lM7@hzClJX6xQ2foIK{M?|P$03UuP zzR}vigpBCRa#ho zb55BU-P3N~B&({c-%1+%+4WQ!tOKLQ7;9(mq+zwZyqLXEW4|X|yxc>+=UGs~!~u|t z3uE{plW{{pl2ly#mNaNaC{riOoACqG1h^gk;Rz#Sl0UN{y8(JpiZ6#2MHugJ7$Xv5 zr}J3gD*N|_fmq(Uxb=A7TXjqt4!-j_M0RnD1NDLPNT%6EMl0|wwP0Wa=mSMnf2s%L z0kx?{d90BH{P^!c7I72Vt{$y6u_8BCWxY-2)QDHqv%}cqT*ni&E>1KbPgiYB7+dz) zUS=!+&z>gK9OD|t*2Vhum$~3wktr)3i8an+MjE}{pXVzEFYTrb1 zATSmBG0mw|esuiBbCtx$ubsB!?i5MJ3)gw;SRT%jMQ*(WD59#G&#MY%nvOf*fzY2^ zis__9Hpnt80oY7Q1rL|%n|U@B^P7@C0!-p%Bz}}cF z@JOj|}WTl&dagdS*h<-aKLc8BnOYhwm4*nLeY!Hxd zpE!tVc@@{HWM)ljr&APGw^jG(Q$7zk9n8_`i;ZDEDf-&;MFeJq)%o4l)8f>6xZ0sY z*e$WY!8h3;(cQ%vSJs^WC9E(VwvS=CjwJP&aV+IW2pdi%6;h1z)%Q645|zl^^jZ%6 z4N~Ui4)xU}`Fkw0lg=iIh9eB+DO(U2G4+Bhq4{-H_sELvUh;aFGnlIt+~aZp(Mn*1 zi$%78Irv!2Yv2CM(T^Fjm3P|vH^edKI*NI2BM3|X+dY4^(qLhnm-KXmZx=+i$82ZF zoC1;T4IlbMEK0zb+FKq^QR1d~;gpq#r>?#e`&t3&@nznAOwl{9mE?Xd$zu!2cz_1pz68p7|Sj+pXZDzNrmfLWWo|_GHyF)ukgPd| zJ%B9NH6i)bpi}@(IeRJJav`@l;vreRb~=t`HQ@#Mh10~_0(0Py#PNdz6279u?=pvW zfbBJG&||Fo1EwNyR=*;MvtYH+we={|$c`>=rzmPPPKth%QuHsN^1GWd?^k%ErKQ35 zFJ0Z3e(-2K0S@fh4R0$vI!eHs;E#q$i59_;xR*L&a#!>45xA?NDM5R+t64W z>?Q7j?1SQyucEWTsFe1T)i#2PI6t;ISvpf1aX4V>FqNu1o8P3~_7_kWvO1K)gh5E|5pqF7<8^>KX@7$jOfLSxe>ZB2%1;gwE0U@O<=(IMUDs~2(;L=|TO zqVeNjO0G(=oJkt6Eso}I3uEhHyOH@yhpd{kaHp*Zdc~I7#t)I;(o@%+zk{r*Wq9#I zUA^e!4whgWDnRt>Kk4M}XUlJfOhQD%ot%P%U@ zrrM8CRX>SIlG`ThIXtr08Z5_CU&Eo{x5{e`g+TQyV2{LFP}kHok`vAx>kJWUKV(I) zg>NdA+O#_W5uq{9^I(GX^0ALnj+<;vc5r7BN>SdAM7utEPO5MhHNgUpQc6?`2K%aF zO%E*^&!zS*yY7_70bcS0f!ub`z>XY|&786jW`sViI)+sF<_3EPIlRSr#ADt%6up}=de9|&#*zWbC^tqL@{B1cv5T8skm0|C3Y*pC(KEE|o?WPI zO(wziZ2BO-_PU3i?*6nt+hFY@8F*Jp9apO_+YmA3uv9|oAJP4$R3C=mZQ<{Z=j!sj z8%j@G8l#t?V}Ta!^do&_v z(kKzm1R=Y5+WF@%Sw*+djulMPk7#4quv*wspE2{Twqnx9GRiYOnn*E~2*Cbn_?>~h zU|L~&$00f5&^jF)7Y8GsSPA{tjK>?XZ$0&0?d7Ay!6O9M_&z+)aurxz(U!5LF$j;X zZ6l%W?TM{2ivji1i11D2(*v{L$zSP|IKSf(pP#+%a%;ezvC0fA=hD^$UlkYZseM)tC6l69&05(m>i+gZ#mlKM7hORvin9( z+PeX+z*@L$4$x;ebnSc$+>$HNeIlpr?IeFTJ3({Y$R0uM-N>~+LH!=G6x54((#~f{ zQ;_sa!R^J2WW~xrA<|VVsPpkBJhn~a9>ezVG$92}jI>9eaM3Nn2t54tz|BAf);e7d zB+vOZ;d`WVW=>R=$n&XxK06D}N>P@KkN^~HXr?k|?*`Lkn;{$9$@*LV9*>F1A-JZu zPKu9C)O}a+11SQlP}H693%7ChoC?k*aPh;@@pty=ui_bf01Q?UlU*9A+NZSb(S?aI zWSQ;VUS}l=jD~F0opg78y*|uZ{@-j^ni~zwOl^cbG;wWTXA69tU-~mKXA(8*{Lxos zj;FfLo4LUu&g?}e1vH6_GNg@Nt`=OW!oe_c@EDw`y45jUWUfO!V z#U+yM^dChT?W+VYQ#2g%8>juOEZV2G#6yckkvFT~>Q`^xt{x1bmWtU72W< z_$?GbnNPa5j%pKbR~tZq=LH=OmD>{f3lM9RZkLwLyqR&~=HlpRhnpJq)SHT#*2L^1 zoSh}CC@QeS@5qwFFOr}j(S!(Su@H{jbYc2*f##f}MRrs7=wrE8EY=kTP76W(4LYGuhjg%ZfsOX2iEk z#MzR%hM~!HiE1+qMl^?RqV5>bL_#nd3OW-iDgq{Crc{q6k5!}tm~-uh7&gJa*st&dXYVO z;23W5H3#}H62(VwLk!@bBntBB7Cfs5Yvlp&(;B{HF4TIxC3SFw{S+xhqeI)(Mj@XiK;TRxc z%=be#FLAV5lD+RwM-u9<6gI9rA2v=^aAnd+d!Fv!TzE zgzlfD=%0ixBMZadj4s0;mll6hs{deg8UAr$`5%lf!yi|Izi;jS&ojDzO8$HL|L%5! z;ji14{~x29F42HB1RwPCp3)s0vgs`DQQhB&(m#t=j}{DNu&H+xAuyJ{*{7=~L5b@p zzSb16Wsp>0VOn7^2PH14jPc_>DedRyz)}Qlj(7LRRmH;oxy^4H)Xrlp=enh~>tLov zV>A2i_)TGF<2+%h)`h!EJ*PgY>yA2;=i|`v_3Gi7(fcmhNk)e2GS5aXLMO-m+(Y7i zqhenJ#)@_SP1F6e-I?Ks87@c>0mREliG)4JkZwm)w#AnFcE}Jsri?iLWwOU9plX>5 zDT2Pi48jh!$~i*g?6oLqIX0$S zg@&Zw%#u3}hbgtkIAKdYv4lqr$~mZG8myENH%rw*F)U8Y5LfVa|0=>+iS7|fw@BVw zj{(<1m6atwCWk7eD7yCH+sV z7ET@O%7~&%{6qlNh+awJPt{76PYSyZcdys?HUg&>*}9c`o*bNCe7ntDzpfs}c(}K+ zdjLt;QX-en1d|}Qsy9uvJ52b-&7E}zog)@H3{S@NLpwNK9TTkG2R~9!$_&o9&8-)D>07weE(?Vw zAXlCIr+tle}HfS0w=B49D=FXGVw_X&?)iCR*j_Ad=L!*q#()~G;8c8Sf->L0r zpV?fgk~%>l%^sw-XYh~ZSEQknUPGC!b3uMZrYgr4$`!gbmg9z0o0KHidhutv+Lm|4 z)UjZwnnCTO1Ez#`H`h%AyH?Rc3w9kRm|f#x6~prs70Xr2ie!_M>*ma96JCW?&I#Q} z^snX|Y|^5>!uH~y+m^kOgPlggTwa1gT|-}I;L$L?7Zi`&D&(1gve=LwY`pU+Qo z=eXYQhnG(WC70-82P1ca?FsB{3N((=L!8FvLTQK&cF*6(z!_s>0Bx?4d1}|W`UCKG z19x2CupMN>aNMU6xTo30L_k2&6)6m4VBqR@UWaeTi+{TVFz=Vtu-Wew)Uqe*#=a() zhIY}p4+1f1-0_^?;&4f1$jVUM%JjjjxyZo+_sXx@AW8do>~?r)$Y6IcU`OF)_QZ~y zqRu}vcb{(ip=rH&HJ@^3D+UWVBO z#=6XJX3eteX+8kUuJ%W;@BkXLL_vp(czL2*DX@Eu=7@|c~qOZ)MhG|0y8X!FV~ZON1<@uH!)8^g&e`?I#Ex zYy-zw{Y)abi?4$BS$RiAI}J?P++u(v4Fs(sabo@JFOWizx;gs*tQ2_n5DQIt7H%r@ zA2Ogmlok~QPC&q*MX`J`cqS0PL|VGH)Kd;SGVvYxvk_qgqxykg-2Iw9?tjHM1@Rxt zN0f%Au8UGUm)F6|Gpp5^_R7LVtbW;)g%hV;GJ7a&O&uhOiy?%|a?JtNprm$34zN5V zVn90$kuN={WW*#Dj>{tZVhHrj@X`>i3B*CYmw;-kQ<}(}Meb}z=BZF`+9LN_HYBmj z6(;_tu1_w!wVxiFOFthHAE6I1`*H)K4R zyvivnqWNU_h)GBq{5uYTqc8ry@LKq)%<&y;7%}OU&g!4D>9TBDV0BDkP%y~HJNYgq zXh=1LI(T7`2J_evg_2E)+2=dfoOP%hW8@+1;4KUJ1P=}ClSnx?h8PXyugckb(TE=J z=soV25!H#NAzMK5BSUw9U};})4^#J+;n;%Y7_WuqZ7HPR`sM%(dF)H;Lkh+qQ0Xl= z)H67FF_U8Mk*JWL0kH`OmF659ET$v;7vo`(?376vy_n|1Us5LgL>T-N8ch_5S2N}* z$dS7m+7+*G3oFb$N9?mjzJxR9NR^r>kcOh&&5yo-qM<~a8j?_BKxgn$lcw97(=#9V z*FWVX7J3Mi{7fv=#e%L^iZ2EUz+oHsl`lRYWz(|kH{w{hr>d(Cyv-|u7Ju7wDKGW9 zQZ6>OSiSysHufu@qR+t;w17ikFT!=u&TOiGaX@GzRKwj1q7jZYxDyo&^kk&uTb?=) zUtVx%t@1uTT4K`fZM7e=RAtytJ??kqs#oCy!6N=z1%Cse+uK!eabT{m=N`e`1=>28 zV>h!S%_eZGIaqP?TL{`2<>&|L!#`I+mFNi%a0^Qu&6wzZ)=4kVDQ#Gee4yUoXQ?K@ z)I(ft^z|5!+9!WGniJGEwM%T0lkX(P)n9~RJ2mv*l*SdMfu>;P8nUY|AR+hF<4TlS z!#ZL)uSP0U)5$p>1W3MtC!-r zV-{5~hM@j~q09N&zY9&ySdqOXL$pY@KBD!F&h_S2%0YgX`IW!JI~Y{TIJU&=AUFA_ zzFYR;%fnZ;EY+gJLA|cyr|$31(cO=FuOv~*P%wFHmxWG`dePt24NNm*GdbsDxCM3W zCd5-h+666dZrAamM5iTQpF&P0_7*(*dlO*+77u1Rck<4=SYe8Vst2HnEYf18ekf>3 zl2R1sQ}&S`TXu6>Fh|AhHqDqT-}gG<+8<|TXq$Pgc&zVvhw$N_sT^m-zCgfK{lbV{ zGZl6p2hqPh)M^9}=a#FL&E~WJ%2VW+iPyXzV>oooJ)+W{EuNM{M#@e*o|UiI#i@Eb zqc5#KjU6~Be>tlZ+o^-BVgp$`OuufrzalPw4!sotF8YYaGvm%lET%YSqjW|cIFB_C zPG{H<$yiVYq9BH)g$SpV8e}_=MTUOAWgNmwY~$P!6bH-Ilad_|Q-~jM$tSsz@^YD^ zrgo!GFl#TiFpysH#IzT^nPW!B2O5rF7>cBNf4ItB>ON4^f@Wi4z?TvR;7H^kD2fWN z(5=dA+mGW&1`>T)XJ5AudljFg15}j`S(S~MF)zu__XeA`zKe_5OOn_wG0RYOt*)7; zo42RZ;H~KyPR1`m3d#8aVCczm-Vijd4_C8yV$P2s76tXL+e-K<39bMg_ZCrdIVl{0%D?9MD<9x!0_j_)G_1ld0Ds6D& zK5yHx-~wgi+FR@a6;%N6qkzrZioed>4klXMAZkHXfnA1rb{6u5PDlVEH47QxPVY>W z$C(1+N@Ek-V5R47oX6|*A{DSbw^LN=8H%Xcl~D~+@0814?%Ntu>u~PA`Zc|1hDxQS z=#EN-vHkSZJ4!-~Z}8Ey_qMH6p-LEz_xOVK<}k?JMY#!fsESkm>egak#}NX=JsA=w z=>*m^A8pW==r}@O6>|*ZR;XZVh8q=woKg zC+!R8hA*~=$EPSq49OTm9&=N$+aL)q%BFQUSMeiv$853^i?~#F?2wF@8t~r$A{tV`amSxXgOlM^#b5rNO>r4&L}s<;pW$d>gN_nlMc#{cmE|Tgzs7 z1Oa$47?OyGjBEzTmSyk{9!#-$g+|Qbr9b*l{r#V8ic$Oo;g#P66m&d8>pZ~}%R_*Z zmzHTfA3AcVHmTYVCd`J?jRn)ktudbAG>B)AF!t88CUM;s&^E6>nM@N4j_rG1oY{M4 zg*BGG_?$aKwT%%od0UyI>uKOX)H-f`UFH^HfA})p??}w%>Wj%Yx-~v&3Y}=m_{wBV zd2>UqLL9yQjX#$x-N{%}fotUWsJq_+Qg*457@Fe!6@zW5Roq@{^Pq5Fxk%7z;n{0D zq0Xy7+25IQ4qU-kknEf3b^AT8!>F*k?rkc7fv?6bNaXO=Vt#K*vSL;SR}(~wD86M1 zxU-3ykd#uN+%CW>czItFRi%lcSsbgI+JRtYQTFi&dHTIwM*pked%JOsZLZ{P?Ti>r zU8OoN=ggRdozXY#19@{uYJ2;|Jm!3a6}12a?PAMU1E53REZn06$<|SMkpp}~EzAUD zeWk(GcnABUTK$!JYtWR=MB!dboK98dmdDNL`-kX&8=aMLgR!;NvOEQ~foeUf54Yr) ze5J}4Qw7|)khzF^#jRI0P5n!P1|#!td8x@u43R=;sYbk(>RY3Ggj@JLoC-D$8KoT# zly>8{_F(s~D~=`BXS9q;A}&S?Y7beSazV?Y&?sppWK2?CFX5eRd=59`1f<)V1WQSF z4_b>L12_i*7b|XSR%PesdDW{!y%nRsBKH)rm5L%0GkK*V=Yd7KI{Y&`S#0E)oj|G` zk739vuBh*XRPs*g)=oPqVu^8{c95$whP&*Q(9P@wuPZUrj;cXc7QUIw`q52krv@AU zO4!L~yb%Gj{wjdsXHorK3P=0XNe`2>4;g4Oym}WJrgV`D;RM~2?Bujyjipnt8>GMu z<-(5$cdVuadljUG4!zdcUY1vsW>HJGAleLRHUn&QkO_=s<68|QHZyoz8{kwr($|Sz zn-0_*x71f?{<~XY)jbDX9b1&IX~_Xyv0RC!!d1Cm>%oDN{eFbkIYo6Vix{B*4;4G_ zOZr5|cZn$=9RUvn`6RFP0Je=-v<}Rv#1C$= zK0Eic@2$iIiYNXmU|j;d$7zA10ya@!GL6Q>eszLzO!+h$aCIeaKi~}k)faU)dUT(z`GA=QHL-X1-@3COspz2M@ z)rRs)2&tj8RvLKaOcw*sV+9i~AzJ+@+l2#1tPi|iET)TDcy?Q!<$>3su*`=D=WG!u^UU}a{VwgKH~bPaCtsBf z3=8%Hr4ATSOGGN10?-2TF=wF1Ska+;K?YR9kxIT~fLq%K`q18%uOGwA>)qV7 zhU1g`xP0|8blFw2(kzpR5U*21e|Dwy8Ro5b7_UNu-p(hcfY4>erYy_m&`m8Eb$R9} zK=AzvS9>eYd}Xy6Q$}_yt3&hLE?J9OX~tirM7mpKWrynG$YQ!9rzeNi&adL-?Ae}s z^fB0b6|=c*{`~0L?d>H1@#yjs{QmUpQp_{e@ht>HCn&9zvE+-3w)@~t*xaQ{6OD9sM>fSeP1jATRJc- z{=4h@s+x<_OJUljbZ=pOoIbV6Y*bXtCrhjy6`7~%gjmzx5xAf#l>tx~djEHF0Ulk~v zd(=~JXbVu($1ZFu&=lnK+0^hsTFszadf&VkY<%c-Fq<%68=W|mEwvY!d$cGw5~z z)Cobck14}?Vw>@H$MyN;`Rey8aW#_xp{7J87{4tBM8sfoNGqsloEpz4>Y#AqWISUttqL` zE3K_@X?=K^mF+fPScgZh;VVZc@Q%mys$yfQMtvt>}?LMKj|oX20eC+B{mbxbUc4dXcA5^6MZnsRKqKc{E?2p^y# zf|!{4L&@G*=R9p3lxH4^nk52j;eH4CN!IX`@nz~Tkw$zw?G(n>^C+6xzY zSFSqf7Q{1l;Oh5Q2N+&Squ>o{?AP=$VetrV^i6^3yp%L9(_kiK8 zQnDLOk}n~5qVZ|O+e6W|&Cn%tFUA)DuzXq8_(PnNfwlYjZ*kk=5EFWOPzAKDDz+a! zn?p;-iE^AZt>^wcqgpFR$sN{ITZc6M5j0Jzwc)Z|BU&%bDC3KS=u*3r5Ur&|t-IMA z&pAB0*i_yffQm($oKsV$kCo@Vpm~qG+P8mi=S&SV zp$4H5f$LDcU02&yN&8H0D(cMOgU)T)S*u;QZxSP~)^(Ei#z=D@BAyzk*?VY*bOIll z8B|3<-M<4-I2dqVa+4Uf^TmDlH5DyxdmYTRmJ!1+9olx@wa#x@&PVLX%zWT2O$>+| z4WkjiV8fGiUKKED%q%G-^^S!>u>j;XZL5Glpf`Wworj>)u%L#B^sX(4ubY__bXeZx zZcAvmnn-+G-{~F!GsuJHxs~g~svdIOVVg&R62l#)gb78Q;Y!knJfL<;PimlqL z9U$LH1HQ6~q`y_&Uu#{`^Om{D)TpxCH5*i{*moQB1TgN(BNOPt04~_%!;^z=_+9S` z4OqVcd1$!89$%uRV3FXo>QRDjJ75m|_TsS{ekLzodm!K0Z5k5Q)txq-9C-Fw_Mm{T zx(*C-mWZ0TEY%y3neRNs^@J5F3K9oAFAHA1FgFTG*_vexhX5$jg18+}%qu5->%x?% zr1w1>0j&w9mlp?usmvo>Bqc9kkVmS+gOHoXpfDg5wt*{PZ&aOf{s6awRl5F0;EeCl z^MJDNacKMflt~28BWCZGS0!*jO%DfjmMm`k3E2DLXMt_md)-u7g!(>JBU*YJu|lP>F)uu))+DX{=bKub)-uoowIf&D!sBW=Ig8STEL z13I?A=!MrlhgGDo+e9w=G&^CuCB$fyT}4;XNRFCV9Bx^VTM~)YgH*al($rv)IfZ(K zk3iOeVw!Xo1~(0zk2;DYdRaAAe-x5&gClSg!wP|xcuM55YR;1GCQ0h!I`*r(wNAlB z-XRz(8>Tbj%5A_`CuAT!a813GWKykIEEZwnmPc!#WEw_CJel{9xWe|zS$GZ#}AD5Ig~6|=8bYQ+Zc^F4TW&TY7f!0W4|-k?zXS{ys)+=WgZfG3~k6Y zi3Ci#9A#}S{B(TYt+_}Dkd((fc#UKo~tuHn}@wBZjt7o6_S+6eJKoL3B24q>m(oCkOfjY!dYo{ zMP=^El-IyDAPhRbV$fIs!8MA&!&a8;XpQd%g-148AVpW6qLD6$*uhQwzzRJ7Sdt2M zkAYKq%fLoIk>Gfl%>|tMfTlid2ammBr7`nBVNl54xL;=}4QhL2noQgcFlMZY4^E=l z=1400T<(_6E}g8jf=(9AHodGMzX>d=6P>thJu1i!ci1H%Gh~)cR1F5C>qrFASku67 zI?HaGGM)Eg3lJwTf*w`#S2vq@WD9>zBw>B|-t3e*LlKWax6JOKhKf)p)e;na#0NJ& zIF}elhD-x9J#_>kt}7;OQzrV&M1N@ii(i;4LBB~+kjRIy|F<#=sW~o19I6^JLQCDk zDYvdDwKJp&K{~0~WI&nwNw!`9A;HQa)-CkG)V(J((T>q!!`_-{-F2B_NKo2#R&w~=TCAnyDXC6j z8->zgSA}{-x>u(5lVw(FI1mS2$X^j|q*4XItpq-n^J0KcxDrEdWUI*q0!D!Lu2Pxg zW{gYvYbZCkU=Y-{yy)&blG0b~m=0}0)0BAPCMDFyVz|O@^`jQl){qUZ$jIhb)(Td| zmP{)76y^^#QX3Cc57-so_dp2z>WRy~Xc(f-8%A<)1yv?S;4^x?`EfPE%-A6C1`%DD zC8=798_#}|*A}ezCzoh)K<*V}n90O|O@Sf+eoU)3bWcy0dTgd>8lx09Dv`T6L?}|! z?9#%6&Kqi03|=Q8Y!Ed;RhmPj5u=X_1q14=r<^FsDrYjOX|UrLuCey#54c{kZ^ar> zQ}DJ$S`HP`Ki59mGE-Dcr2IOjTYoXDi$@ zUTxMHpO--0@wExq>YORQScD}p^dqsET*@g z^qTou`FAX->{-60^KyxywLu~VL3=Se{e-h4WE3SjMCw;pE_0~4{P79fJSt|X95L-y zXMzt+Vlk!xwQ)={QVhT~W|1GH5SouNv3NFnO`0sEsERn(Sjv`^90TFE#AsfQ>x+D$ zA!=kp(TApYhuee*9RFc8H02j3h+APdN`^LkYOIwjxhCiY3@+ ziK#GB3@8PGYdLL#uO*4aZTT3rrvyWM5U8X-MQ>u^lSWNHm&@As6z~rDlU%sg$JAl7 zN@M#C0;2~ls>gs67B0p0aERaq(_0nsc0`NAbvJXF@>z?(Q6E{*3co6tgfM3D!$czq zz%zvJT`(tMF4~n3i}6jvG@OYI;3@j&vz3PAAK&dG=GSVZc=PtwhW$KFAbQ zyxSelg!h2_kO`!~3#zcIAM>Z+o~@PFGH!w2q!3kM)H2LN)YM>XY`_Q=RK`=+QhW#iC9befST(ke4RLA;PJRGh%68Y{-*4IYH$Y=dojE%IxV* z9~sQamv%8J`jI8}WjZ7IOYL#CiQ?}X>(qoQonM;^QY%~1&?5b0ryK;+fMM2WuP=1) zd4ND5*Ft;@V@-mQ>sZlfy6B#`@M~ zk7{#LVkJ_o@h%ju-~g9!!iF#K$lusGN|1;Kvr^0~A9;<8(7ds7wvi72P)%1^E*4By z)XKwaUe?R6jB!!S1q{-~#A`pD#yzx}S9Md#JwkA8WE#(D6E-tbB`bru^Re1p`HePQ zr~@g3D^P{f70Sj>?9!`A8dWNggl6p4x9>5_h;@aczm5aVNKGL>Wm=UEqpX`=kcyE& z#HcXjP#K<5dsRVt=uH!qt}B)&caY*Ar*mbIN|~i|$H`l^Sy<+s$$WFfohmy#p?+YO zNjjpH3y40@Ax3L3NI6mg#V8a$K_Mf`ChKnk-;-`a6?s(q1aIDaOu`-!sM&(?Tr9kz zBHuq<1lT;j=0Ghr^};e2);5ElbrC5;KJTQH%A3rh53-Oe7|0-_}IO&j&+ zaVu`Mj$$2{EXuI&*`Uh{X7)P`c#Pxu4#$}hi-MKOtHP>a$Gz$ce@3xajm=!ldih?l zwg2h`g%A+HG^52)ifIAkj+R0+F*zQ46*VGnl5{ISE?I^`Cx@10p4tQX$@ku0vL46F zduvu%(wG;Q227fBtN`>n_=p`d;0>*$CcZN4tUSpKHHJe-3A zRJ!VOy8l-F0$@qAzUFx-RW*71c+q9nOPN{i24jgWbJon2tGG4ooa^8CHR{Zrc_NyN z291N$nWx=;+ivM|P2)uPYm|y6o1G_=cfxm@doPYt-OCg9MdQUbFNE#~yPbhD;d@xG zxa-aQS^p-M5rTW-zJB~eV&36VGb}&gzC)+-aqxv(2wn(rT8c(&=c9#;4VO0e0#~<~ zw|3OQ6k67=fqR59R_U7pLn_=+93FAKl%}Za^NY7Rir~4O)?Gwigc@`^WcoG%PU+KitpDybt$3 z7S6ZXYv+FoqBd#e>@5WR9wT9ir3xm?x$y5 z&m?WwKmp!HRC?}~*x?g=RHkDy;HEEIZqBOG9{QdRw632WeolBCkI?4uc)ZSB`@GLg zrLao>0`d77L;7!stG}ybFfp^R{~ff(_-{&7F#hKf6%2pmD*xA@wLenv|2NX{|CIVa z30PzNH$^J`UpoH(OUM6TO~?P!p8haA=6|N+GyW@s`VRt^@jsWPVEp%GDgFwv`*?w!Krd2}KRztj~J6RVXI5`e=d8@CFBA9_L;22;xgSOGLeQdb> zR;_qlP@eAgftP<;E|?S_eJ8)zjm1zlGcVs{c}ABV7}1W3!#JcL)6W?gTyo z`+PrvkWzDVTvOs}b1kjjzkYLi`9yA}{r}N+PC=ptQI;*dvTfV8ZQHJTW!tuG+qP}n zw(WV{F+CsC{V_lDoslPQ+{nm#4>k{62oVaQr&r+3drf7!r|NV=YzLT5k=&TSxT^`zenJ}4Q6a~X4Vg6owo8qhGqpj;r ziycATJIYK?0{xMyq%H+lpDLee=)(lmTtzcYdaue%eLhuANBE zeBH?B4cO<)@g3zGdfW)WQ(Rr0qWVZkQCrTUl6#ivT1ux&SL=h8ik`CSTQB1NeOt;$ zlN-e1)$!%-{{6Yg*URf|E%XU4FEY=PQsvMx5cp*}S2O1h*n>Vvsh|kXBGrv6r12=F zuYQ;z^jBl%#B3O%LCv|2?HR-<;5zBddXZcX_T-lHaZia3~cb91~N!%8=3V z+L^2eV;~Zf4sh)flX+CpvVAylc3>YJdyYUTY{;{sOn+IPSZTU)cf8~^vDdq!>t{b{ zg*N}W1VTjhj?{BC_siTC(U6j*rEoku<#mO)7LoJr7S8;=k>x#2s>eB=h?GoWQP%=5 z;1cx%kSA=QJQgCxYJ5Ek9wl zjCNQhDU)8ADgpigz||b>VDi^0K7VvW>a*_bA7TK1`>!y}yM2LFi?fJtJ2P@?`XbdP zABr9&y%qRI8S9T-&(UWM>dB^{a8&CxW+zIJNn$E&88Q@VaSgek=JSh)(&Q8x14Lzd zR>e3Is9weRVg+TlYpM`Q1K1Ht;-IQ%#&~>i-5hBuOIQIvoBKqX93zLMY&A&-?l}0b z;X?=HLx-s=-%-$vW7L{)G2| z4HaksJq0yviK4O$^dcRJ*bV9)A3+^&F}6CO-&Pgoa8st`xuqmIt~wgoA3o@)vq-`b z{c0MZys2qB-pp!3;NzJ#A$Oy?ryOPl_mXIT6jlh7^&p_dREDy zTF}X>c^Tn|ux2sTem`r~J6Qfa!$`&Y5S$WGjtaH4*i6_f@O#LeusCo4tr?3(>pQ8Z z;=g)9JH#=vVmhi7cTEJ2X*8Ko{a@)ES4R7U&669DsDjc_eRJ^j!$%<9EU9K?;k=lDkdWHa zF#xKOjD7+;7<~ofRHZu}EjGz9mk#KnHz(@orUi!?xPJirU(2se_K`_C(>mF%pB|%F zLN%GDgT4iaY+Bjb(FGp%`+gC)I{atn)H){-%tZF1sqy|f!$nzm!WzZZ{r8B77m^Fc zkqW$qy)bU~5Ub|2Vfp9)IkqbzXM#>0_@Q1em!tBH(n;~ zyv(=$jfq5$MId5&D+*ey6KH85^kGz%l@LdGf@*NhbxaWjwQ1ANY9a!t)za(;JSJGz zHep!CLsd+th32VCX5y6m+^2&usPG3N^y1ow4vDT_Oe z_}!MX?fIUqzt{z@jDLg73~x^-EF;_^n0lF(2J=T!4-f>Jr_w6f)z(MG@ONIi7`;Vs zJZzL#UrcL7^v0flMqUBVkcY01d3xs)F{rN#6*#^@`UZf!)X2yDTWp>}wCzOoSM96| zU>76UnI$9^ca4`W1gx5Q)-^BFX5>FVVKc}p%jmowx}R0(uuTihyYV(1D1%f^x_x(1 z109%yViZ-U!*_YfC-1OMi__@3EA9}3>Ho1XN>OD7VxN~>0uk%9SdFin{|FRjhP?8O z-y}wnb?Nf%gv^0r$l^d=B%rD?!n;v{7T=M^^Kk|D&yqUfu1UF%1Zy>Fx_m zK;~GF!mQ|vOh!&$d7(NL&1h2L7MarEASgS62BJ%)s04PC%Mf(G&G$L|V=vv9@pne? zHyFK!D5^x?Y}+CKn@zLYiP{*5i6e7KxQf$My;|a<+h%&}2@(@fwU(6OL(G2PzAP zls4B$OnCxT*>K5kz!>L4C+NrW~agO`TZ!9@B(k1}bO*6{bJ+fq1Qaxb*{=M^RDH z7z8y>q&1`X%z*(}W}=;K30Mt`pt%8sz-l4Ksy1^3YMfEwo0LcF3E@iq!B^6Bpi389 zobk#RIQ2m~rb|OJVq|XmH_5D7^^iD7EwTz<19nCW!`lU&2t@Zr5^nne;9(K5y;cq}E@{z7tPcFs43F;Ok%i)hW;?NY-GO2YtpC$A|Q zTy4p^b45vkS7jcr2l-(DQDMWPeZOW$oQGGnR6G#{G67k6m+G=DDgM{h#EPrv|QwrLzsJhX}xknNY zM8wHV>5iunwTc#iUhSV?A$ilEL@6F^1h%Rz?9f||A)s0u9b-&bFRq)9FOOYEYpJFI zQQ~NljvFpzq8d<$u|Fw$D%%h*MBmOjrpLJr^hMH{nUF!aMB!%@d;cLh(oq&Rk^Ka| zwSmB0@BboW(8!y)(Cuaf*0LM22{xhJGOQ}ejtBc8)MYWc+!Kg)n3|0^%qJ9&DsHb( zF&rF8cmQ2XOvBz*(|eHiJaaqesCAj(`sacR8H!|NmAxX!-Z*V0x{5H&9EF2m zLorzlH2znv&NpB(A5xl$7wgtn!R1oN@7(JOkkzph$}Sd_$JPnP(?c7B-RG;W#qtKI zt}MR0HqZfY=upQ`zzhBzxjn!%R^A7|9&Yrs6RHn+f{T7^;`3k4rd^OU;nf`w zeO5CDG7lHd&&pdMazW9!?<1?zN3JFGQG1?O z-x|<$vJbCZueJ>hvn4prRZm=b(1-7|g|V?+$XSwLIY8$h;b%t8*a!95pcR2exJ0bB z*Ub5jygP}e8Qel$(MyGa3->up@Mj|jqDdbr%~WLG;Fb5r#mT=s6Dxd3nqbbn(l&dG zwxX8-17!1@p86gb)uZn3r~a1s#^ZdUgeMV>Gimv!1wRbsn}Q_Jjy|ExK~rzu4FA0Ae&8Mo->+pjZo0M@<(V*;%ts zp+v+zcmE3;qh^ufLo0Y%k74ehWh_2xN~6DjU6__}>)Jp0jeg~IUjtE}@c7Rv zmVxGJ;~wOh_EM7-srgxc1}PsD{RoG%LytyEaE@wO6F?7^Y){RlhtaHRRT77oNZE`E zyrj;AYpT`?g}BJDGc2B0I#9XXDT#qS8o4N3%E3QXnNOH{Gv2Bq40SAJk6<+qu@We0 zXSVE@w^C&r_&bqeja3BkW#-*c|JYgKhkrIEHP3y;-Dh7$4YjaxC5_daltQVfmb|M| zoM=SjG$%-iz`&N4r17G<1~d-^U~Uh&AHEl?sJMsdgHZtJcr9@oEdelJ+ZCDeo#Cmk z&LrD&F3!+(LeokZRE?f*4cE*oT*MeQu8JQ;J#} zqOXbyCivM9OA?r(8G^mXx4Gi_xojj^B^}()By2%S25^PMiFNZL=FD@V1hR-7UJ;pF zmo~%V+AVn7*(TcL+=kohCEf%Y3PDHYw>>LF{rowRW>6iMC^`%#L89B0z={U6>>Ej9 z{w&&zkucXzw7^YxnbXQrSp^L|_tIsu;62Nea11p?=Lpyh~z!|a!oz)+5qV~iA(vqqYUAs#qC@J1QSt+h11 zqO|V}Jw%*7#e81@fMl8N%(f;?b#Yq`yA2aZX*JcI>*4fL}5t(`Lky(_?^x_Mn_Xt+Y3Pi150m7q7)>9+c=?LgC^dFMwmLe=>H}mKW64YAB}MQ(^`ebf z@DSLVSLgKaYhTkOO=FGk_tzo_lAwN*;%_1!?eD{Rf}7T0&(G7(XRr6~V(e|{_u~04 zpeG6u@P8LKnEnr9m5G(*|A-s^17nrx|7NT*{eNSu{%7U?m!>ZB|G-%N=gKt^arob^ z+_mJ`u~m4?PGVDL63@8{K*~ipWf0IUo7R6L`6%h_m#Y2Ur-V@J;>)~bUA8w=%*Zm-wRa;DziC2UGVZ;3J-l^@ z(qo-s28sxg9%AWIk6j}BWi5GDJ)XQ^BZ*jdk_0(vUKiZ8s?EqzjZEi|4=^;ZQDc{$ zQ&lwwc|Xj{TaCpa52>412p_K-vFH-G-t>IScitxh8@m{1GDIz(!zi-aHD`sOs*k1J zk5prf&##sZy$xv}i_520OPV*HjvTbOjm~JIh#0<+r?v)TrOy~{?@rKiNjbQ2^!BU; z{jxtgSs&i;rG1vUZS)Wb^ysHH1XUjbSJVa1O`?`!zw;8@EvYs|3R*T3qa{gSfzO$PIuE{!U~K-sv~wKe3!_S3nH5F zC<41Npf1&^Xnm>(;s{F65WMOMF!P!Covng{7y%Q#>S+u>i0caBHx{X@}^;lZOPiGoXaAjSj?a zvpWOgv$^pK&{4wIs-jO$@)6c}n897m%$6r+F>V_^Qq1rIKqvQnjH^JbnHFA-V-Bn@ zJ1?Xe6&{{1x2|`-_M1O7I3{P;=iNuO=-bibzYffY-p|YO>hAZ`_-3!qYin-IY%gCA zvAdT@4nLl;^o^N5Vj<;>nDunRN?K$=LJ>E39VuE=r)5-8B7%8!5++>Nj%e!+Wy)!F zebBCHH1R(96bTLrD=~QC8B>ZNYvOk(cySGKSEFzMXCP=d%*z8kK;vl~7{|jDOUdqE zJc!}B#(UZZec=HmDXU?j+&0?ps$_NFB>tW1c|4Ydz#~BcW$lnr4+Rgewvju1^Zou8 z9tNfGzzyo7z(3MQ$`4^!eS)9}*8m7&x7{b7O4foQ@tj(O5mmt0xcGm49SY!H_wK_> z*k{l!YtQRkP!sag6CvEtkP<j!Su1&2pL1&ecnQ7)6FZ}r% zx+RR|WdZMDCmuRzkt_$-fW2;f-y?-IAqoU=hb;|TbxC4Ok^S^^(|XE*g6mHQsBOS} zZZK>fm3B#l=|MTVXh?V5qn3z3zLIxCZ7234Ye>Fdo<3qWa!yy-tw%LMX+;hVpm)5Q zAzr@GiM$bLd&>i6nH>b`L6etfYlX8&-W6BtD!k73qZiQt01ns-5h@YpPrZH5R$vza zbJhVTa{c#YqBwg9D|j$oq^aFnB4tbv$sCvBQFpAJbL{vJIrTIBzO)4ji#fZxOmMPB9sid&;)pD__{ky1Lx@&Ds46ZXBIfr-U>)U zN?hY1ZP7TEyaJ*!NAT4`u-mZ?zy$nIFy;hi>1UKY=~<71X@G$tA$T1BjsPxDER970 z^bn9+B{Dvj@ZXbHlgJTt&=s|Owhd=vnAACX1nUT)dnzXNn za#@KZY0_0C^g3?iN9MGhuqOe6dY@xcj;M9R^jb^p{QcK2G`WW)+Fd4v{HwbgSbU>1<@^1rU z_&kMHvBU$wkCxB*h~*^@6r@eafD2Z!NkKO<46Bb4F2s#2h&^glgaYn$v1yV-9C|4e z^6>m{VF4YX6Oei-vy=0eUNfHLi-CwzL1c*+j*3T6LqM#8u73_A(^eyZ?9j>zo}Uh{V2f$G(yX=*MkP*C=6eES)a zSfKt>VvmMV{eU9GBZ~)5?t6J7kcZ*F>zaM`qT$*DU6v}oav9ioyK1Evqo7TKBGHx4 z0RBi<)c~tkd%w82OL68h2?F_0DR8N{NVrS$gRs2yz}Fa0d8DZX@&HIHB^C|J%;?2S zII}CKGAZ0bc>@ zmQy7e3sVWfH)RQtfK+4>N8$kFfY(#ar4ZtG3#_mqVwnX?8u8vzQmoz6ZM+z;Xy0;_ zm%rb+c)c7y&u=$rlN7K)?1g1kC{`7E9KV)qbTC}a4uDfWzXYN?a}!I%x~`RYFn+Hm z>2#lYEfqGm(FaqRziU+aB`)NhXb$7wH9FR(2QFKwrj-k$az&6Yki-do&g-6JjFFcf zeG^(m5;!h|&gQ%NmW)NI3hano3Q#zHPYq`3%42x(qzL9c*P>@_IE)2d&nsb9&hl3A zm&hNegm>*%4uFEXGA9A3jo-S6(w5PCTDr~tewl_dPyl0G<%~3+_S|Wtic%J>7HMXx;525|Rr?BLgPLv$9eEXcqOi$h-uCL;SsYv z;fL#XAp`I5TnNE%QeU(b;0z!4n|0cBBak{*ilA@3wR;Hq#0(xP>;uraEiEh0^MrIr zp9J7c);;}4g5%Q1B-)#)973>3xN4`(`QTK_9pPwluLQ2S79{iGWo>NFwlBNMfi0(J z--3F1bmE~!XB+u;5?|@V4KU^9d=xvC%D3xB2O_7h!{$v7V{j1g^~Pn-;4|emoGtn_ z6E-U$w@Rl~%&;?xFTCh7OR{064Q6r-{T5Ce%ou9+T1g*GsKtfmSKk$j ziibFy|K#Gic0aAd7M=DBHl zKDTY}{k(7dyUIF@LIhR)f^6&w4i8_VpfzR1i4Am23wW!CD-vk0CAjirik>kzI3lQS z)=+f3tx?exH*q>4PD(XS|F}-2TQp8-L`*Ao8;KP~)hEV1{Cgi_c~sN(;{GiU!q-R< z`RCI%s&rgl%HQ3_r88AKFnAN%)JN4WlMR9GCW5eDMu#~%r`O)rgkGv6i7!Q4F+fo8 zjcif|n_OG#qzQtmT3SU)G_uQ~f@=W1)?8FcwE0ts53Rv_^0(wChhcFLN9M7*-Q{#t z&(jl@+b-rMXD;Y8v?p`+mh!j4FZk~CDcy0^_;|2LtNG(8JZJi??2Gb_8LRc2YW{GY zwQTM?ld=1 zzW@DGEko7Lz{*$$UHv)hEW$KF*)Rv?FfE&Rwo056_J}rts}S7xozO`zqNe+c7N|^P z4vR~W_kgRbf9@&=@XN{p;%FpXS>wO3lT{jB8ZywS)qS&7v(4UGhmdsq0k4 zc&$;FmEw)O)aYKmmFBZPBY@YcLdhgsHktgVkWv|f3nxG(CG|3TShioxyo-@dvN@HW zPE+}y`3C1o2>zx40UL@7-l<}@Ky7^q(OwY@a9A)?lZ6uqyoH|QgCK~tBJBoZswJ4n z=fy>O+-E)CT99G;EZwF2Lu#UsHb@k)l~^%W>%-MW*h2B;;F^DZ`S+~D6W=q^M3xsA zr}{ie!IWe%-ZGOkGg zgk$%uIa2+IvQ_D-m13z3c&^-;hfg#OP!Jg>o9hh++~;7l_zrso7FV`=n{#x&sWC1ga*WxTpl<0ZibAy3VSjsgbFW845-Mt27* ze+-+IGf2?d^M(?hbNW!XQZX%lC&p;sX#}}qlzfzXNnp%Fd5LAA(dxSiChW3C8=1`CN>%jjORDwqZ)tA=i{OO?@{8E8>3UYD6{(#QlTg31&@EXObCX>4cx+vtim<#Thq6gYeBxZ84DL0v5@VJ$ zf`GrU`(;H3lOo?|DRPb%@?O!ptvK~%oBR!ImNUj0(8_BQB|zeW67fa`Gff+k4bj@z)(5$etGP3F6^Oz+|_ z=YrwY=O*2$LkYA=I{!`#wQj;%yj%79Ni>mLX5HPnTQeQ3woB7$o|~@7Y|DcjnOMvp zdd)3bp}ThkJ=Dl#n;%twWZ}H=Bl2dD_;wwV=9(l3@B&RaOCzN5@VU8aCPfUH6aPN) zzNQME?CWNFZ8=2VKXim%8~cGbI+fVi{tZR(H6MG0^rQX`9vg>gnp2O|&S6B(=2N+$ zsHM8W`r|)kh00(h=%({rf2smrICB3PZM)$2Du7(LB4!(VFB8IZ)l01uVVHi#dX>s6 zaLn3~_r_h}u@#BMbtlY=@@0_A9WvgT{k2kB#~MGTiO&(2=Q|h;kx=()(gN8!ot?NZ zs0kxv5fYz9t*8M-f4W>5GK@=?ur*8^HCUN{=33%_9~Q5u&mzDZ=Ny)A1lC_+R#e)F zi>quBjzK1%IU_#wWc|a!IwCLfC+%{`sez$2|CDxm)OQw8>!3**o2^nsUMQ_I)I&@R z;46Jf{Nsaf19aelG3)$^s_5GPdqya815ZqO_ZXBt1=`*QAM{{{qXfjVBzBJkneFeo zs6)OUZ@!E)|IQ3`X$BQ^?q+&^Llj6QV65gi*&LrCPNbS`If;80Eau+i!pSGQ7Q{?O zRv}hQDL9h#X~kP_9>>z3xLxC8{W5MQAVX#TV&0ISv&~^l;v-|f!G*;XtAi{alvFbb znF!cGf1NR9Q`biyL4jo;tB8$U!p@jc~rp_DwD&*zJ6TJnjIdKk%U6>nBLfC zR93!ua!hlJ1@tdBBR;L+LYjgrvy3*um^x8zhdYr6-(19GL)&jRU)U83j3qI{TF7T{ zx!lCe4Iv5)0ztdqtMN19aqF{e0Jh(v+F7-qZuQJ|3TdIM<;!*D_r5jN*p4$I7$UsWhf& z!4py@dp!N-(!OlD`>>RaMu-IWd4a zU0-;|PNjNsm@@^zq9VHFka`zUCwO=^fF+wD54CjCN_UGKX~jZC&1l`;5G4m46q1aXRy0mFrl_!F7Jf{~WPPnuq(6Tm4*rY<>dg~0afi5I_9Q)2CrMy;-W2b& zJMw`?{l&pIf%7;!Qa3Sxb6im*R}HPB)#A=_=A%tejl(o(Ss;{y+Hv)HOYw~+Eq%h> z!myq`i;%iOAetT4asw6Q^MW>TdBs3t&=SGCIj7^pdZZFi%?gO2PRs0Yzp|^{nw`J! zLNp?w-AQ$V^l9e1$kxw7e@q(sV|w+=MvrZHfL}Ba(fd8^zTP-fTsm3z^ndF#_b64mCL# z$ssQ_fncO@Av#jEQfj(|)G=;Tl~Fo#O%6jm*}ez|AYF{}O5twPnM0=-kO6(o3KMMPQ! zIUPA%ecgf#Qzz%q`t70AAj_>PEf;j6Hq&{4+D12DQ$_=;to^*xO#KypIILlJKWWsi zF6wA!**GFgv90UCo`5$_czh4IVNOAB0d{{BVUOUClKENn}c%VzmQ*DNtSvE`!; z)8$RY))gbR)fPd(f|JZ4i$He_M7c<0rPnecYR!oKjBe|=O~qKPK?rTG91L*}<|b`b z3hMz;y^nKuc#~oY576u?dk6Z}VI2+2g}yJ3-t@beMMj3{mA#YQjgD}+8uM9>ufug- z3E06~|DAp~NB$Y6)aJBHf<(dy6Bb3ccX(8K_j^%-DV|o@o)VQcE(E^I;|(wyPWDtG z&>Q*E<-4h~^YXkyr@tlV@_D8GR^YP}k6b|Q3c0UZEwk;otwNhakZ_GnTLz^KalKkz zdTN~R^|=~`Io=ts4O+s>dRvgOVx`>1vb5x8Rm$m2s!Ox&qOp%urTJ4(ck}wsQZ-WM z*Ikgt^BZUBgsiaZ6@JnsWVUO*!y*rt%_}v;PUuGU*XVWF$htEKmI`=@r^}1Gv;XrX z;^wp+_~9L$-n5tw@tv}Mm~OpkYo}z{G!nR{%0O2e09taCvN!ds zW-6=RI_1-ojty6y7^p7S%9jtjH0_t04OJR95$~PM1u^CQ0vTcx#dg-z+7mTYCxZ)4 z0eN4M-d)9Do{5kJY8jfb)a(lGjT!tf*CY2~f|lh=@2xCnat1m{bn5w?>=$F}{VsKa z`IakAiIw}#o10#MQywmJ=8b8?MeoGxnLd6-)?QtPX_ zTc>6@Y}hqq7AwBD80jzfA1{3cIiY$$UXT9Gqki~YxLpLr&u4+|+AXV=6{-8v)s^dK zOl?uyU+I=lm!B+QSY8>nFR7LUx1dkMym!-<-)=8xK9lc9)|rR*o2;#?eA`RUO8eq9 z9-D{P)z{5BKl%c7DM873FFFyHfF= z&Hn#T1z71h=>JQpVE!N2!OZ_RJDB*r`|W-|iT3qsOExNZD_h>yd~a*p z>KjQ>8=Sj!y!+$B`ThKKq2zN+mh*X#^m#FnaG$G0KQ zNBs$C=xQk^MQ(3he{wu(oARsPqowPO`7}`XwY5nqe`S$x@`{ARuv}I(YgDPrZ_McVV{C({4Y;-a=b=8;sd(*P&NVQa9 z`&nz_qh@As3h_v528m)HF@_V(v}@!|b-GPRV>TIH9mgvYxcTYGG^xn+gS zQ9Cab`g4naHa(e7UCF#%VGG*xf+wj)7_$<4S|7x#K{G_jygrEj`)v z^i!l7SxM7~7-8Am0O>6*`3B}CE7>rr^0qo@i4w{qKKY^cSgQWHd1%Ko3(W-tuW{i& zo>S4fs>6d^ftD_+?Zfh2F(TYw)5ZFvTg))v36u9fddrkD~%$HYJ*Vl8x^0gU_=Vk=>RL$p!%oD#RjRBSQ;bY7s%JoHD zZy&C|6L*(sBKJC8&qHXmuDLdcSnLaS+5Y?8gzMcYDQi{x<&b+iqd>GlcDg8b4*z8) zG&T9=NvnFxNL{rX6iw(ZQ-o{}A@ODegLOOBX|s&ixZPHog!5NX@CmDx@(0f_uhvd0SjA(Luv|1(Lfb!@_pEP-yd!`AltM+(=z~0<$sl=gJ=GF3j5H5PI`U ztiw9fZ}b>jX=<4V#^}|D?~_G(a7U3&lb20}bdO+h>d>lWJ^Cri+%6MQ(w4RzKDSwB z1C0XaF&q^7274`y1Z?0_Hv41sw~#a0n#^5{wpzamNs4llFPX2LwiVS7*8Ba?J~5tA zd|2MWcq6)Akjh3pYlOPO&|_e?2N^DzZH4RYX$OsmZ~w})b{}@87kEHNF!r1_q{vbs zyJ;}5)y|9kB7 z4tQIVW@lh-wJ*{xNyX-y`zjv*nxoA=EN}NK1NWWoZm!!VLhstCJ-1kHuE##?tZ~cC zuQxnyMkw7@ztMz7z&o%Vn$F{o26wf1f66yg+bA!s^}Pd@YqL|XUc{gR=hxsKcJ?OY zH4Hod870SEpq-nM^YzSQS(LRxY`>Z=yqcbl%(;QvsG!Xu!>8_Myht~At~!Df>icbO zT^Y{JTVS<=9_A{db@NIW$_Gx4&~vJDH=f*4{|VA^xnhTBsG>cHlPJey zGgEGbl^Q|+Iz5OaPS#lno%A9Lo32*ZMszy*V{p^e13odm3!aw1p@&c7qa1py+1(zC zlxdtt#UOCMRt;{zjfy^^E{mP&rS@Rc5tdUBRwN~L3JJXlX^$dA#-*Yj%tDmupO<#RPz}flh+;%7tVi>(@~zCAQw=8CKet26f-ajHLE(KMyhz+~3e zdusa>2HbKW7uzJ!gEvB^p)Aqhsl;%vb#G%eYn}ug2$_@6Imt@<5j?wt5oGKG=p7Lt zQcW?sXC~HGQlw1mCHx(@(1oqbpNcB)*qM{CWSMegUqxp@pUJ=qA<(OB78iG!xO-c&*f)-d@5 zo>TOh3@kk+XxN^)cwAVGL|hmXpxr>}sM*8c0S=(}gp--TYpGER2-y=9>i9hasS@Vs@6Oy99;vL>____!8jNp{+Z7In@Q$ zn9&(x*pZ@-F>BC!DgkciJDM@C;=Zz^7X+rA|V)3QIH`K*N;^?_PcqevDDchrZ_O|8wK+v zh}aR`e)^CSLrDtWvi7G)w(iZ}OYh%pwiSWZG{6?^q-m_%5$(EF-lk5r)uxH&SP zS~d$SO^3TVwyT=zR6jnprNlmh|}buc1phgNPA_Yj77-)9j`OcM0-dp>~b$ zhpvTampxVw%`gY9i&3KMPBx(DIcX3h6elS)+%8biuY*{&k%~~z!se5fNX?A5r0x-B z-j`hGK!TLVD5Uun3PO^3QG}aA2L_fO!%QIs>%m|}t%9InnNpo2!I+*L^(;|WE7%UI zd&?&`gKpAVm*5-5MN-=Eub1qARdr+|)yJ+1vVdoI?GxAXT8KS!zA~$OL(ckEt>_Qw z&a&IuO-rik>uK%iJe-((~Akc`P>LI5MCLPg_N^2@-8%zj}hLj^I?2M*;{Q0>1@8lks$>=B;8 z2TXXl_j%a7gR9rli2ydsvWkVyiVidlh|G9q9Y{V1qBFF%J4l9HyWm9^L}a7#Fh=7d zi1*nmO-;kh59xoC>8iaVQpy+_Z8JfB`_ohivacah9*Phc2ITxgANxk9;r3^ig&=Is zP}M|g-wMrMCK)ZC1j1#twJV`0%{}K!s@NwXWauvx7Eej7qlK8j5cDu3EQRN!J#>zV zX#zb&H(9TVa6Q3UvAx3Tw|FHXoVqHGj|uB)D9b)My;^hX5J$e}PDRjy9o>A1Ml?n{ zea92zTnE7-`0Wy! zmg-U-$n}&b1#I}LCgZ=5B*1#1{uwZGu0nXMP&0YEc+e6)%K9Rx$Wiw+2I7fWmHI^# z#qvtxx!E8>tSKP9%duFyp}>pgu_(KT8YT&%0K_U>JiCYL8JU0)f)DbpK)!w-ecJ?s z&-0?c*O#1j+@6Ws3xi1#vqZ%uyaSOC!+hjZ|4ED_ zt|*~Q-;=?r2TkTpv^-!Revb}iW6r|y5V7`c8Y5APP9k1zYhJMkT)R~_Te?9w z;j3yYP71t$PFiUoy$x*Iyc9QIBww230nZZkSC{3Xl-zU^xwS*-*kRMjHd#@vmwFF{ zrgFCP>WT8c7=KKtNv&Mmp?=1um}YQoQ-W;JssDQBS^k=)vfMxf3a;`Hzz@E$zsAWVZM2-dqXlWnvev6_v zi;h3R69dwIm16_P1Vp4hDBmrJd$%gDW28%{85CCFECkxjSGi{i&>&GFNpunTNxFif z+yKat0DrS@{M}!<7BsTW{l0Lyzb9U}NwbqFs%=ZRG9X^$bjd(LTVtz&dQ|u5TGz}9 zyn27HKHSEbh06s8b;7gSzx&Ur%Fyqc(}H;Xr^jVFy~ODVJ0-Weg|=+SUHg8$f@a=$ zqE~~3+NjqU5j#Z`Fd>xVgHXz!PQT*}b%!S44dZ5hSm6E;v%Ul@H}OI?LELj=kj|w5 zbV6BCM?k{O6AX8vd8%5 zRioj-J_*8TB&hyE8fhpy8G~c=WgzzuH(Liul~ceB7(I;(;Py~7h)tMe=%6K9;)SAd z1B=P?g>o;(tE*Z}d23M86+6_?94gC0BSi|tqJAZ_nND7H3{ro`p+X2XgE!>U8+bvP znH%ztueWSyAnZ?GN?eMM|0Pr;k5geg7&NesWFSH>-^6eg+z?=+z|rxMSpxtYz-1`LLD@bCajEF)Z~ zheFkADs&D;qRrEt!Igc3wJ5;`RiM1wf14oxDJ|QcmJ^7fm5(&jjoxl*hF!F|7HEd& z9`~L#kM&@y)?9 zF49~!!@)h&LWnnXkR|K_b*v>-(Rcmz&(|?$T8WYgUIY`LT4uI zMf^&uvfi11_PDe)@|mS6*&HiMsa>S*PgFE-V3F!!v^froN^B`pY-@TYs=d_d+*Y(e zNH^3X>gbdl*i>dzlt+msCI=B|pk1G?Gun2(B@k`VNg|#gVT8+h9)8hNfv1!Gkr1E( zU6e~12}f9#7_75c&Y##Lze%(gugXH>Y+N18De8ciSq6-q9ZF{D@ds%83)GAvF0;+{ zQmP%f6FonmWN90evLG*5jto@gp(&33#TsT$eI6#XX5^0)*U_~H13iUkwK7ih84=T= z7t_|1e#+LeTI9;NUz(}XCKhu%WI1C?A+Al~)ZKH0A0|G>dO6t6`5J5`hoK|9@@X}T zKy+2hvIW1Qk8oXfNB?wiH;u}`p5Hum?NJm&adw#-a*JWKF_(FyMdtMeoP}*-B}uj& z=Y>OqvfVv^OAMrHg^7Cen1U#AI*#X(HNJ5=xuvq_qGswzTeU`{%xbj+uX#{1WEs*S zqTEU-pid-nL)cRNUltXz?869)%jaUa8ihC{q8eiIh*q1RV%Q(=KMpiS1wE;dlAudN z#)di6DU)a8P>BtJ=EdsX7or`33ZgqT!bZb^>mPaDyNh21sAzC-Iu6RvfJ z>2KC^l?@c~ac0eqX9*8e5kOZO&{D5IB-u0qWqFeyM7@<7UJ7h>3~m%^RQx>~Tr65V za5nWPbXZhF=`PS3{C5OpG2qT)^BToN=V4)voa~HD$jU4S)emiERFJQhT7b|%i@oBb z{#Sc%9#7TR{tsu$7@3pl$Q0qshm$#ThRh+AdC2S>k|wi+%tT6tWR_?$mwAdJk|a?S zQ7NRsv-VM++jQTz@Avt=p68z*ul?HlTzd`ITGzGKdavQS_Gi}y{lu$}$%hm)wE7Gc z6Xdu=zkPV|{F5q%kT@T+|4Y<4O`2yeUwq5@3(c~)4;^QVu1Gx`Ux77fq5oDC)i3pS ze>8Wh^2xq5!@*;BsO@X_;CB+6dm^?SVV^E}{}O#9O}#iuazN$IVP15-&cnIMKBpd@ zAgthoX?e-%gvcvjA}gyUU0W&}>qI46)v80HT*i#$3kIF*qQ*rQZYt>2JWNezS*YDt z|3;9#;eE}1uV#v|FclMFOmLdo^wV43eGwx8S1Rj#S_yZ$ZEp8V4Rv19PzqP=Ou5@HlG^{%ae}V-+1O}sG4!peSAUs zU9QZ1>~^x)!Qsnn!!X7lpG&eA)eEv@eoWokACfzsJNC`8lrgjNN%&B8)unD?{&)X{ z39d7hy?J^L@%}O|KVSJYJX}4@d-urVObPGB`**?7TZn`g3Ux1)3!k0o(>*!=DrR=3 z`snQ58n(KZyu-tart-bYf_cI53Sn_rT#Scg9Taa5H?M zmcMb~(<3N+AFiS>4|*pjzigU|2HwAM94VI9tBx_S3M2zcFSi?Ni5@`Qw-mf>l!kQL{f3 zzASzIHCmcvbN&15b^m+IvU!WW6U)s79TY>Qa=(5Z&S?Jp7_AUfYfnMYDH7V|Z5CG=Fwh2Az^@O|{b??c!7i}t*4Qsz7z5&1@? zxt-tG+wJFH`-pH(cHxHUKh4{58e}CdQ}x+Tp`vSk@stMd^1SwTXs$aY$+AVR^rXiP z>7}ZA1=-pOsgp&kRY$I%w5p1VVq`|H5(Qn=UtK#Px5u?~{@K+9pC5_7OZ!c~ zr=%9{v#lfi635LdUOc<->q_bJT=U4V)iZV3%pZ({GrT&-2aU`PL<{SCO9 z_SX^BDjMlSiRf+O?{8Wb=WrywVll~4POn)l)G(~>6fRX%j+U_@gDA2ula1?p zQR{BWud$&{kG4Es}IcMI=gJ{>(lxJ49cEIjG+Q@M9B_%Lg- zlHxZ}7dg4Ucc{MH&xTi~Gy4-7^1P0nVCUCu54Wf+&E$BT`EE?5>%#p$iF5g-R;(5M zJz2{ZOb9#Iy*^PwJuQrHxQ3knTytZ-}H5g`*Xibz^iOz zs=!GXZrkuA0oichyY(kzrM~O*f1T^kKRd-1_LjrAL5A9stq*n2!Tqq_T=9EnZGLTy z=TYVIyNakK%wk82UX7jUA6WWHHJ=@FXrq2%|EiLl91Q*+#e$MqBNl8t-rWwlQ)TY_ z#mWG(XSr|X+!#b|&1NhaxKZ!8EzGX=rLe*6a@AQsix_M9@Uu$<=gPB+cX|tQ&&oe* zDY$2H8}+cP$aH9`?W5_>+w`vBtkCg8MQ6>~MEh@h>ghPPNcTQ_7n#%=c?v@q)QJo< zbdNlx|FtkV`J9CQK}W}{kutl6ym>4|9>1ZSserrP5_K%FniNynd3aK`LXac93#a7~ z^r2SbVA<=a543Ed-hNVZECqG;{I~U{dx;!hBY9dU_SrmwxV6*iOzv`=4*4 zI2V}7wXke{cl+RwXUJ6tW9115E<6+I!dwVqWa&mKCH%z^qJeSE+lUh0La7nh(WAFx-7?sTQ zY<|tPU~OU1VjssF8q#%{)Ib zb<+#=h@nbC#KEfMVyUWBo<8{pgD*}F*{@IJ2GyQzG)?`+!AYY=E+XN$?{@}8?-U0w z1IOi$(jDb;^K`vLiO$nurtc0K?1Qu8x4Npg z{$$G;JQAC*xq27*KMDzK_^#>9VvvlD2pY=M$IAGX$X#83UQ5r~cV^jxsYQ#f(Mh@L zbpy<*(ERC>oO+iQjkXg3M?VQBY&T_fx))-4-A61_#_4^L;7+$AeO3HlEA`&QX*b0e z$oDPfUU)mxvrqk=Gg-_v{9x6AE5RLDE~-=+u|wwJdQZO&+VSZ}3Z;0tbgRt$a(tTd zSaBDbl

_`a6XDx5}46uPGEZN|~-+iH2gf_7M}C=|It0eKDx=xpPh<7z7x3_J8%< zZu7+u&RYI#v0Y00b$*!=Dma&wocqzdI>2s{k#216pTFgO7QC&G~6!^3bt82l6r z?hiW(gBzdn1Zn=00uU+aEWHUtC>NlyaEP4)2R!^hT9QZv5(kq+W05c<4mfT^B5*QL z5>OCTdxEXEvnSER8-^kImjlTFvaU7J+Zl?BkU}7!_7DF5c>+;&tpDVM!eZ&*de&}$ zm;X?7BOe6o^k3#zYV5GH9nlHY3F!+dbf6se?sianBeCaNy~1Q;H-Qiv@S|G#if2iGE6yE@w{yF0qtL)qzC z`;qvCA<;DX_>I2dr+2$R8~VbY)h zNy`8R5a1cQL+^nbM}SCS(jY#RCSC>)?khCtPAUvqnhv@{OhAQ#E*ug~ii-sWUr7Um z1^JSm0q{df%aAUtG@f+FO9OrZ9fw4L0{oe1$P-xSU>BBH&^;*0bfqyg#1-wP@^4j}_%2zZ5bV3P|E@*wF2=!J2suD?3*_YQOc@Q0xz-J$1I z7fIGD@1ZdNT##NsQibmSOqoan!{0v74Mv)w0Oz{|P=lbC0Z&9A{OHvil0f+Xil`S%fX zu2yze!v!nGIBw^98tEA7<(*_WaYLF{c2c5}i#g_>lQ) z`A(PtoPy%{bD`OX>Ou;Qu`_!QpK1Sq>G&jTKHk)QaCE%p0$q;yBRXg5Zf{dG!!_8p!hE5bBKWiCZKiR8~N2VVPD zQ~P_Himvg4P3mmRm>jom?i%}$Sp{J7S<^D%fB+@=HaqXdx@8xo1WP+!tA%{oz*vKD zbc5rYw&30}jHd^ClnYI%;8z-5u)osyFwKvFp6sS|oUPP|NwUe!q>{AgYXdd5%Fmor zushsd1b!)wQGA4bmHlb=G~WU0vb{uidkgwhGdY)Z+0N|FiF0~GC*^k)=k^szdk+rC z@9*f-KW6bGx$;lfrHlf=lDp=m#1rZGzChRk4jFH|!nVJN0Bb zu`o*|g$qd?RID9j<()d60TL?OcF7TC0|HsNWjcw1U}4NutUhfuqsSk`$+BNM7WpI@Nx^jDpv>X~UY&9wh*&m0}rdFC^L zztg`ymC>(g)!}k_QC|C8=s|FbV4`T+(?XkX6KYJu{B75EF>J!rR^c)dj3TRB5;Rk5 zfH9~nq#w}Owj3~5(fdB=<@qBWsl;G5+YY$uVd8XBIB*abz2IbfC`8ioEpfM=5m!uP zmBZ2N9oDE`kLt7s^~Tn5&!)4Mc2#H26*+{LnxK&((y1)Ft;A1yGkyDZQ|9APe5~tX z>z=E-bIK8&aX;mE8WDO37vg>j9`|;!?n!;e$thXLRcx>GWZJsGRg&RDwDQUJZ+-qH za|q_yIf@Zw1-ng({1;CBw;2Ko^!@9K>`f`~r^x3=<*pv=%9{8+)H;*u8e35Rh1H9P z)p70uO%Bh`B5MbI*6Q$3m1kD6*Qe?omGoZkmLiIIX1@p_oVnU?g)Z%Wc#G>D&7!Ms zbp$>jM6_HdwOVnHoxI1=Ultg@(s8M2esjh9WL3M%i{wW&;q6N@W5)PGahEt8bE=vP z_d|8Q>08~|g-#vj;xDD6bdRzoHC$<$F&}Pwb8)uRa_pJJ!_I|qf9dy4;7n*3zRvm!Foe^leNh^D7cA6S-R~@I)+j15O%Q$jbc8OaD$e)r^r}{+*6d05&3Lioo z6a93uMlL#|r7G6qlW`9JeVp6aFSBwHx@2{U(7~2ke&KPy6F<4h5~ z^-pyBCy0fQ1Yq3s_=UBYvZ$(#G+ctyqcr^u8{)72yj4PF%9%+^u+J=RO7DHPc!&IUyFjTK_mIa`6g|qOM)`&_ zQApa0Qr6UNbwu*v`3E@@I2ftZLFBB_h7yhY|Bv8Jtw${bXLzQ|I;)cx2~&0 zV~i2{Jy>!UhcJ<=<7;SDO6^#@Q$9Io$V+b z(hz~cP~Fz)iq5n_L@SwV$13CXf8i~;ESj2T<7b< zO3_La4`DirqqrpaT1t&UFzO1WmRpoU(Lo&&%4Mu(nN1TpRM;nLk+{u zZ?0-8VuZM7AC5OXrguqp*t5WIF+k+sr0%y0sifDg zHKFff^norQjC!yboH61y#uOoq*4IRilhXy7J+MTS@gO=nSsGCoX%(CIXh2_Ilq(-G91mDW5}a6K1xGch--y5J+!CFjW0u|5?AS zf2LZr>3aD5@_=DG8;z3i-TT5ewu0nv74JR+hjCwA-b3dYLyU%ln7ZJ4rqve8zUFylb11w*k zic_{5-5q%!#Nt-CMEFre@Al&btDf)a4_a?oFH9sC)!UD;Cp4LDmp6EzjXWFs!8KDf zvwCkvu&cs}3#uu59bZR0e7LuVar(hW$2TSdPDh7ty4mKbA8hHZ+o7u)PxD=s*6}W8 zhU547ZZI48!K5c(%)Cj3Z54~HS0^0qFhU=Jp^Q^k-%gjSWO`A6Q?tIORaGE`UWmr# zZGbs|r&%)8B_iSbC_1-0hvre2!9GMwMrVpMOI&b;I`o^ZoTZyEv{j@876;d;6Rra2 zH$oaxCyWUKg#yf>41j*4Fc@ky;ek~U-YPkQEY_Mv=;3al*A|5O{jl5m#Vh@sR~C!o zCcJDFgrLCcz-nf&hw$+LwRM~dRX~{R8d9pedGjvr`Sz(b*fsIf8GalRA6s!pMC0YhVWWnI5p6dz65AEs+7s#aJ3OJ3V0rM`j#XEtqe{y# ziYpQIfiKs0&)Fim*6jV0cDj#?1XBll4-KU*@_61m{=!Z#sfEbbxtLz@I2g}fxiA)i zqt=anF*&`!>MRa7tm3t}dd`O>X?WMfE|wI>^IRi#%ipPghg!FPTQ1~3&Woy6ZB#g&%~&{Gej!!e9V``FFhvZJ@jS~r kKQ$L8`dtOW_Ph6giFnJ8ZbGp< zw$jF1Wu}a2ydE<5VJ_i)aQ`tekUy#4Q>S9;TT7VeS7Ko+5%h+wg(D_`-O9lJ{e*fQNyu2j-?+r6tfYy ze8@8cVZ;+HcJhmDOn_J735lCde#f*Q>o#yoo@AB0QJj*%<#B%|WkDm!EpCTewyH#PUEpV36EcKfLVht$fFS*g`&`ywmAQX>+u-u$i9JRJi-vhp zHV2Mg;O@?3{v@C2!eU-l^BFIZol2;s<`2D3iOwXmJ*$O!koPW0fK`vdhlkN3=h1x^ zn}#%q+0RQ(rYTmTPqe?8`5g~cxSXHrI}?Ave^gg?PbVK; z4oX&X-<{KqAKU|%6gvz*{c2lSXCFWQKNYmyMNa>F8b@ z5=j6cC3+|7jMW6=Ob8YI-BarPR7oPo*v+U9+P>6}QK}jBmTY@T#pEe^{zZ>*dUEec z=Qu4Bv6ne4r~1*Uej8+`gIuP+O^+$AS@^}ka+0q9+jfppBQhUJ-Lfov{b%HF)c3IMbXo7 zd2AUkK97}sRnHw{xA->mjz5M z4|~%IDNou-8aiM+vNRso^5DGgm?V~;Um1YPhM?HK6`XhE&AfGeM$!A zNaL#@qV7Qx0Sp;S7zdbxJ8UN{H`eAyJUAf5smajT zPFBtkP$8Tibipy;GR$pf6O2Q(EH#2ll{cL%t^=9}2oG_zZNkr1ktA{*Skk=&x;X&` zirMNt{7QRVHCs>LwfJcLW7&n*u;7{;>bciFt!Q!XXRo6C=u&b1US633>a#4zddl;b zwhImJ86qPOW|pJZ;FL{hyJuw7{Y7?8=*vT;VVI;=%wGA{?L;b3g>2@850|xhN@kCq zwCa3Zru@J_P5C$Vci)sLio#uR@=eOJRS>#vLtnlV&k}&3q3XG2^iwdTbG8j>{z+v`0Qz#_f1)hx1Lz`xSCfFqcJQg6$OIY}=PE zySwjC;!S0_so2!^UT!m)EF&+JHEK+Ci8wK3Yd?O!S9Uu%iE*?2J9Lmr9r2UM1k+^L1!PFU5WPIq!R-~dsTaI4g;KE z(6M)SBszg@TsrtaCl=H_yxsop@0%U6Ibm;0TqFK56b500z+p{V-=d^(z1(#;C!{Zsm02ILsbkar}Z)g7X>L4x*bqrxCIZ}=dOnJ zy=JiBD%POB7eNt|LE(3WhpA?ZDIINpzQ?&^S;i@S0!(wpoDvPsK4@}IB7Szl5%$p+ zv+_DH`X^>{UEjH%{nf{;aqrxj$KO>vza9TpXEThy5)s(e&P&tv!RY08oNQKQW!vwZ zmX}2X=k`sTSUa0*chKIuTIHZb`_c&iqEKFupKkyB#<~wpkYUeJ0)%-rc=Lv_Jp*S`*UJUM&C~R)@YX6z!M#fWNZ{6*1!s2T1 zgj>Q3J#?SXM!aKN7=D&qu7XK%!k?o@ix+V7_G;tOJjGcnufJ?SFYRz6QkaJGl^ucg zdg?YCy?P7SC${M+c;h^sJfW*6+!cbA3`+A6jb3Snmon>IJa2Tv z--;SN-=vDRid)w8i)#OD(^^rU6PZ^4F6Up>?bs>oeqVH0-jbI#Rm>gTptAiMgGAU- zufVU#2zpBm{YzJ;v#p=iexQv0mTNdS%anL+y68>V6dCz}-J6{E1^d%mlpcER+*4P- z%?(KJM-@0lP(R62#YY_}cl+0Qm3G?r6esOBnO_o*B)8iy2;x23D&MMv>m@mVaqsCW zE&H9#K<>M&Z@jZuxa?r3-k*?ynKp7)9czL!TmbSSUE zBMRjoGsf!OZ!Z1NE1M)l5m6aCci;xy6knfkR?NPk%Z69=B;W2z$(THS=F&F#rdQD~ zpR{yvMycPC%zJVoNrnl*YV;(@t1vDwk#)O@qsCzj{f*Xk{{z@Z(fG{Nng&lRijMM- zoEyc4)lBweljKKV>>tA%47#-K(a7GYZ%f+?ejXzog#NQJ{b%PLzf~B41e^P7wEhqt zETA(C{h~Vu3-B?!`zm42WbE(r#go^0DVeYPwcgIQrD8+|YPIl0q*U<##6&Ae1g8o5 zA80~Ic;d7I!<9|74l5i<*Aciwbxd=ypG}Ti*DmN<%LU&132l=UvxY~?d?v|0?lciP zTFziwR$S>RZ%v79@@Ied4PhG*uaRM*Jw-;vy7=__`5E_F-?L;^O$gEfg>}W-GAaQl z7FHJz8`H4^6i;O~Er_17r~9_tp^MkUiOVj+H>nsdBicjXP@^-_x)n;Ojf?T`x>%jn=W`?;c{O5HJc-S^!Q6Z#IsFW zi8a)|EeJ6Bg4q3fPc;s?Xi z?Q{usOA<%kDp_} z8q!^E6;L-| zomvE>lQ`KH216ezjD6IyYrSs6doXIA9A-SuI2asPeyuoH_6z=JV)xseZu8>)vTqR* zvC3q;v0icpfl~RJ1G7BoZP(+lh=fP{aX}doy1K4tvm1dLLE52@i{y~c%b#qcX7|E- z$>`I1U*8=(G=C|hCHLBSQ)1{xFTBES6U%H9S>FuxCW^F=jVF$K_zoK;&5WFqIpXkD z{!PuNuI>e7o@b#_wv_)=?MeP{mGi14_fOD&uK&p1-E}IIH8q-*_sQoa%8LiKvyX<4 zRpIFp!}33G_Y~t zGruow-bB1xMSJVC7rn9?ia}7vtA{Bi$3+}~)@QdhcD@aweYbjTHhABTZKD-CE^m_c zmJuIt4Yj)E=o(ZNgH4_(`A`lSu*Xw-O3Kf#$$lA^lTMkhs=}t#)?id=*KU3Gpt|NI zDJHkw+OCyy(g%#fF9zkiM0`jrOwH{ylF;p$du3koZrAJ6CenQ)UoRXZk244|u?}R6 zmA!AZIOrncYCyjS8K#d8aDGHbxX*&5(KJ&*$E*&$UOI6RVzepEWr9?&wE;nupw?i>JxjxsM*(r0!Nj zy#IvZz(J_hRfk5Aj)Gu}5Xd`V{ra9ULi)BbSi>f5iNxA5avHN=CX4R~ENoxdkr6t~ z_+*pZw+`CYcIj%dcowkWL`kR#64kT}S}5wc^KfZ7pSoWo>peM!r;>;wRnU(s<<3F5_z1;3%!dV`?ugkRN}mBFebtX+6|Ls6ryj@&{|X zt-?AN=mun3=62`=Nl$GoC^*@-#X*0)ZH%O$ws#YZVTeF?^g4QxdR*>3vCCS$ zsWV!AMZOJ-IC#b!b}zfX@m_SNQs`)DVP|N!=1}YY3mxDiXz`Mvr&T4!k&SYVL9>OQ z`S`vUb+(mLH^T={GVPo13$Yg%YvOug&E8_oK5ll)N1))epHWUjzR>fr$Yq5lf+VHn z8TFokmkB1k>eJQ5BBqQQ@72RJZCnnB4-PI zfPPFE-P>!bUcupu(>!76>T&6p*}{<-Zw>9PXSF?e@;<%cq$wbJXtX!IxaCNj7&P zUSX}y3F&UuJET{87(FF`XQ$1#u{iwDnJv|Zc8KM;k%3W~KiBUcUuHhbp8HKEK{!L$ zOfFl+iR%vdpwT!ZXp@qhB{w&0lk))*oq-a9^s&i2QY!Se2sazo94iN#?RMrcB&-tJ z6ug|qy2+P!kch2fLo_(OzPdevLDHQH43gbq_mysZI`nw1pdhjqtg5rtuC*} zPql0Ngokc4j341&5H36LDh4=YHEdeoC}-=IEY;{{z9&gXX}~IPmI`Oz)7SlVa(|xZ z!HmGeH22uJtAn++1)o@?=DUH0=}#y%SJ|KpDT0Ka6P&$hBD_T+&gWEL8xbwe$^0sB zp4u^zpnao-tfx@7Gf=A5@J`nL1l`;A>cYyqtmtvMpd57vYvgB{IQx zL%6e%ZU3zn@@j{)XC{+YkNCpHq7KuS=kd9IIl`Kh!&^MYHHdiCfiSYk9KA)=_s+&X zXy)x0w)D}3j|K@x8$4%{yH3(Par({8(f-<&Jw8C=W*N&4XPNp7_1BKcG##5`#WU7l zu)Ufl!C>noa?}4(M19Y-@*CF8EqoT==9rA%p9$YgF}930*G{oW<5@rhn+iDT#`})K zaI>VhjP$_NdbN<%z)28F$o?li>r#CS|AZIneJEl1W588+R$KW{?~aqScfS`fgxhiZc9PMJ zOSdAk5i#=>uIzlrvySZXiB}A66ol{E3)={4jGbmv*K(O*r9>D#?{5a z8sgo-d}itw-C0tJey5LmEOZTQnni2cr>0f?$s8g*l^<}earW|WurqXOle?22&)jl2axU4qKE^L3eP6$1iy4(6_pr>ziwl|HV;5euJ z`MO5*+4)_@X0Rt8d9*yEBJ|?|d;?!-GT={3_!{tkMejwjPQKt)d#M~K9Df<#R7w0g zve;90{rB@I>AL;m?~hoR+dfs`{+QS-fqL(6_LVr--x5rZna%n+@r;25V;>#gOkMl} zAC{GBVCr{IC1FPwvPEEy@md2H?ZG8Ewz?Q$R^G(c5yl;v=a2JcN2TLlk-y7QbYrJx zd{f?V>_H&=K~9(W1+sjd$-wu^rJwKA4uEgJe+<|JmI2e0Ee<@Wb-+y0K+Bs#nWn0H z-`5a_nI%*v_r z%v#WqQ85)IRY8!KhE1rOrC7(ho9;%lT*8EE3WOG1$$3nv%o0_i9*y&6`*8yvLku&C z&O=TUB;Ag8>&m$FOq&&b8BgRp>Ln%02`}RL`VB|HY2aM+MM<;%mpjup!tI0+KkbRf z9KB{MyTOGNunTl@}VIqMs!)g`Rjn!gQ zAsvc*#F-a@uAh*rE2wmutt(cc_6hts4)c_g>+uqjBHB$xUD|hrXRN*)X8Y!e%yQd( zg+`?EaF(Q5if_wcCkx>b3Q2xfy=_n~tDdRFl7_`Dg}=5Qw&!TfchfoZgs8I~?$m zmwB3)nb|fj5r=pB0++*hq->1{*U6OBnscpo7bu4BgXS7Zu`IKj@br&i_J2FZ2h3$w z^MuuXz#M>p<{BFHF`Cs(Ee0XKj!cJOlJzo}+o@f~$%00s;R1_UaITO$^i1MEG>Oku zcQ~>Ou{M-Sd@4w1cOwY14w~y^mn(OCE&k{c%vY&6e2Ir{GY+>3X^`s%cX+aRrLPkwo#!yJ=_Ip4PjPS#+sfA8@nvBH7N;8x29S# z-pF~%s}bjKBeTnruY&v1o3hCz=BjvyvpvlRDutZ_P8S(Dzs&VwZREvLeGvPQo?X53 zK}Npgb4>g&raYc-e@ETvZli(an}yXK->GU&O8wrfSX+fgC}3E!rsfUs(5}t&0fz&UC33&o34s@QtOe9xG5(4hut%euJ z*GD*92!7~%`94{i9GS|%lRN_zPQISL8%BF?y`)qC9#@!#ZSMr8+!dIJfZ6Qjl2Go- zS7YUH>lV$y)`6wYS1BKdTa9isC+`Z}PG%~@GcY;uDM|j2$P*$vs;>~+v5S^fZI9gd zOS#Wjrz|i}Q7nDU%ta?Cs%3v6^tNqd_39wE%Q%==KHlh2_O*Qb;icbX85+jP8!HHy za{X&r@n80n2XqY#*4R(3wwnYyAi%n1jol>OI=e}5${SAbw6?W}0fRHRr@c4HIuNW( z!o7Svi1q|vZ3!&-;GWjN($dx50a$F39=%ESgcuAAZtLOZW(^r1LXn+4>>y)JxWB!( z2Mq4v4q_5df+wPrw>@}v@bCd!2oBD^;F$o-CE)~nUwd~Le8oBuD?cA)o2G@guEq}N^Oa^dm2+Rq=Mgt6P0)v~vfH@A_#@pJ~#hwVU zNe5OF|NdU#6&zE6`?%ZLdlPIuyzOClkhnDr56Wo^gWCZX0ADb;Be2l|;hbUc6EL_7 z4DJeSO6lN$Lr?}!P$e)p;Gbk(3ipA*eODQo9;N#qT9|IW%d*zO6r2<$$?tz^VG1gW zWMR5NIack{{Cmq%ECl%0*hHRdCl&u2i&9egAfvJW zYf(zFNc_JRrT^8U6lmK2S&LF&Kl#76CaSzUrLM-^DBuF%wBI0&-xx#$N=8Z zk)Y1XgdD{30m1%ou?lt|5r4P<*a3K~ASDR0BF#EL3a7y19~MXu3JDCMp)dgN{@Epk znE0!n>cDdRPZsJZ7|FrL>Yxyle}gI`Nj@`FlmYE8Q1K&b7!j?B0QuNjgLO-g2V5ET zHyD6ZD?S?3HVcOS8w?=@P}ybyp%iio)#lr`3kwFL7cD5tA5Lu~tFuj1P9JwML)QZ$m zEAp5`^?Y5<_5={-<>M){ej>$-nYM0!#T-xdLNsqO*s)Dpd1(RrjM1 z;6M!6Zb70TuOs^qC{YALRE!R;0)+!!M)m^NBA%`uL|11Um@iriD}|JRIT4ATg#B>1 z+dr?QJiHx2B;YQ^&c_y<(^(zM)6M~A10iE~yFV$2t>Vtl+unf=I7&cb=zx2PKYyU_ z!h%9N!2Y2DhbW|XF!w(+EEWgpH}toPhJtE*9SsfD+BzC`lk~7)2C^X>)E}>j3w}Ty z>pB`5a(1?chQ^_w-e(OBfj~j+ZygN}^^R+4pcMkyuA!lUV=E;PcdrAeb8&ok?2kk^p4G?3l~c_5`x8}pDsKy7YqdNPm!_F5Vm zhuI(xqznRTjBDZoKQ~a9x{f9d4eV=ZAiWLp0CBKTob*&s`_G~~u+U0k5f z8|q3Lw?XgG(s*bTgZ}>2AE2=iFj_|g#Pu|kG?*8z3x~mN=p)descxtPJbpv}f&nVD zo@WdKv!R`XqbR8L`V6#cgDf#5hfr(z!ywTcc*Y<>gIiY)AhnI@fxdpdUSUuh+Ytr@ zlw*B*C}{{1uBlTD3J(E=wKTxq`u2+f+nO80VK?%EmVx#a)~1I+0zWwGY1j>VfWgQ> zcxY{0EOJBJ!T_~euNxSw^oBN#!OB1`T-K(CLqL=Gbu>_^8))bax{JXKTiK+-I%j4~xWa zjEmYRb1Z73j$=`njd@_DSC1(~Z);~)dvB75LM?X(4*-6ECPEWALk|xC?^m9Uoc-+~ cSOj4u0@2!=NJ2_jtc(njPFPs&kUHJ}15r=hE&u=k diff --git a/systemtests/SDplotting/reports/figure8.pdf b/systemtests/SDplotting/reports/figure8.pdf deleted file mode 100644 index 5708b1b71c2e7ee42480994f76dd89c4cd452ccc..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 58225 zcmeFZW0a&#m-pM%)n(hZ?JV22ZQHhO+qT_h8(p^5<$k;G`*~)bGc#w-taIM;?fsA| zGp}{Uj)=YDckRr7>>VU>LLxK_w9JqsRh#&g9gqz8^!T<07LWh{KAoJtsj(wIK)0{?gy{KvaEzBWFcqM5#t zxs544>)*}QWDP8g4W01W{xbgW!(sT>3Gmz4*g84lGtmD%0>R&-F}C@Af#dJ*(#A&S z`U19YzsKFdFm8ES9>EXNI zR3}Lw#X4a}ypC3{Nat}?wpd$RBH+(P^%O41Oc^dic)K%g!s9rm1VN>^X8KA7b)?uaL6=Qld6+u zq45F8F7>m;uIQCN4(H-t50t&Q4QrhmgB~>NDTHrgoG85sQyW{qyiW{DMSmZ>^p-^0 zl$2Y@6x^M+ppUl*Ec)Xm&rMtmjchvT*Bfy{4C}-$7XOz; zhs}Gtel-Dk(`-=ed)Fr8S3lW%0cwJ&M(+95D2EBCRdceF8{;|HN;o!`A^>1-; z?LIGxHZ8Vyouw}{ zA|0-Esfi>imXWEpr@uI@=_#dZY8Zj;DCRU&Mtp>GzPkdF9l1Ok!!Cug(l%|MW%(#r zj3$T7kIg@&`n+qk)FbK`u_VFnPyyAty*hENO2m5sZX#`E|HI!u7SKOP{A*$TS%EC9 ztpB8w;SX*9T$TUC;U94R8x9QrAoRcB;SUr4FM0UO>OZ^wZ-Mv==|3d>-vJRbrHVh= zk}2k?=De}FPAQ;AjsOHHv;O{uLncjxav>CnfiZZqJ?Vxkbv0BYHZ-^gYJ)d+&?Uh+ zpdXzA9LTcHWv7;R7_@64xXCwlsIQ`uu<$M+77~e_y<&EK(!w_}hBd(OJa$up<;Ub) zb}Zv9#(H1^k;nlyt)Gr_lS<+K)si^?3=0s;xMCQOiA_DXSRFL?Jp@hdle9PG;M(=T zPyXt`KUAxm0w&aJh93Y)5lMM%0xGalN($ab6m8rk5xES?Q#^SeI|yb8YMku~YB!pn zUoWM5qb?tTVI6I&P0txozxAg^fXO~#A~F&`W-YsV*d(e4R z{g^*31p{cd-kWO5hT^#kj>$Ml_mVmjjVq)Xn!S4PcDukz6Py^AZa+ zU;h^X{8>nU0l-54Zvg!3WBH!|{NpkH?*RNAMd|ZKl1jvKfbQ$da-_7R4zn5u2i~~ zvU^AJ`sNHg(0snL51&H4zuZ&otZXEjrD1(OnY?JGFjDyhPyG0F;Pm$PxTU~#4|UPa zvdC1-NqA^aMQ&aYgCM#Y@xyjXN$`~X@}3W4uFGuf=;k?s)fSgknM9<*v8lb>{I zTU+`=`iC?fkMxB^hEKS@p4iDlY$?4ZT)kzPG<^>ZaQ7qw%T&kZBc$!C^Xu8e;ltny z3(%yt&fqQ5T5DPmDjKUyuKrgaz=xl2=xO2?&+6&=6hy<8k@m@U=5U^8Ra@EI?kt^m zLKy}ry55#>kC)Pg>(bZ(Y@VD?`tJ9`(_=bWT@5zgFW&M4*d)U}I2Vw3CAKSju-@o% z&y|l!i}0%@+Or4msAoK1Qg4_#5}ShlNxcJoYcB7Zo{#Oe_9WHm91il zuvl^P8#)#b4*(ZCG3u%rR(YonXIuSE^&rx2AP@r%95vM~C0PtcK^|;zHS+apL9lv2 zi2xU!Pdw@%-p9xO>0xUr;3u+%ZGz>kYW4N!$MwyT zFL6k{T?Iq!EKc0H=hrB0)(zM7ipDiBjn>o2AR3g0x0rjJ zqr7=s{vv~~sj9Z-dx@X!=vNfsHfjll&2?Fn?n?tvFuLB{t()L(DgCNNQu6Gd zAXVQ!{1(9~?X@3eJoBskSzgc_W{m6cbY*3M=gMI&QKM31!?TWfFtC}f4ONr4u28V# zWPR(lz9S_8=Gt*CPc1tPO6R+K49!e+V7VE+O0A7OBG$36!s8Lg(|Q+o**@#YMk)Nw z*PZZ4UCD7qTu+?4b*kI29+YO3V0-k=G#u3Xw8F)+yKS9WkUfkZwfZ3R?WV&V=u`}< zN~QVPIi7MDDv~a=P0^ibE(mlNE^AuEfV^B7#b7W;qL|AN6?teVqFNf%`lHpomRX{o zDCis>YpF*lmHLoUL^#|c!}Ax-t6Y-i{Pp*P-%uv4T5JNmqvXCZJIyaRA`e2{yVh-y zss6-Y+EATEGCYidd_q~GS^#aq^c+&gq>D5%_>Yj=WfsJ@+vB`{P{nU{+osa)@40n?4aTRbyw zh*}a04i+hHt%Z54B%er(MVD2Z;VzszCyDBnt&`BGF1n<~FcOz7jUE+4bae7+1v`MS zux3(e;-(y3Vf_@aH zY$QWiyMu(n5F*-oIwKULgW_wgYiLiD@@oiFlhNqz@yV`-x`saSjTTP zMm9pkN=D3}ZpMUBIhLQMJ)=Ec0H zbRuVIcCzy;)2c&QR&*latJA{=T5`+9>7RDdnN1o4lcnQ3wq(FE!ShP zqnKwGnXDnU)I)#`VGfkk0;nHM2GysU6tG7V2@*hoEaN9~+&tTC<3w+)%ln!wXppXG zW=C+wxsNC6T%Bn@p03)NF}ECYyvsPpjC9zWV1xI!TB-Of%8Ef|Se4eiuzI2!| z7PcUviaMGKN9ehS0Gip)zqE-2g1}Z9#I~eS`_l`Q%vF&bzjoPCcu*#rEL`WWV|%(t z6}$HlqKc_$J+CU7YdP&e1i^fAD`k)s+oH&_2I4R$7d~8SZ06fm&TmTn2sBNQmHbhW zWhKf*P8kZZ+1f6;t5V#aJ_r^|oSQVr&#@Nes-zU-;1)QA16!+jNQ#B8u2oH268v1Qs#W1kIA!!K9>MFiX+1!TAUbi^Beyje`w_+Y}I+Uy19~aAV zQv9{|izw_Uo6EbMm*uI=NR4Bqh5F^ddhhoV@Ruj z+r0qwvJes6my8U=Zx_UN$Lwb)T!K*?jUNWYtjfSxI$NGk(Gq6)5ma3I(`j%tA(HXP z*vIzLSEyD1e)D>cobt+5aa1_wN)s-7V&m#k!mXPm4Hj!+RB9&_=kER!hdM!;@nx2K z`t)UasT;8bw~^<#&yL;dTcodp#A6;zKtk)!}j7~b0`!}aXh00Pw=jti)BofFW z_fJnywFtVEDhD>L^QN@B2~7&MU*)ujxae73dZ`VsPdZ(&u#%M zZuCrV5MYBIW^iEOLg)0clm@}$BNNc0WK56<4bW;D8YV4el(q8u9B_g}u|vq}^gRSG z8YAwckC^j?RYMhmr1S4a4#-!7)3^J$RRVQ0xyGWLOG+A0X5uj1AG*q<$|o@vbj`>V zkRA%{B1|ci$2+iH1+Xzw`%FM;BWx(S!Il!r#mfWVvf2`tnOAUEK~!g$i7IAs36>?6 zPAV{Yb^12u@Y;lzlA?@!N)zO`XGI|s+|g3a<60xc4B2)aNh*!Bh1kas5k|E_5VT01 zE$cG|RDK?+7m?xFT&)I_Ocj`H0Tj!)*l-m z6X`B?>?e`I8%%))pQ$ZP&GviB3iyP*Wh9IbSLtL>UDi==jQRK+fbW zHVuP;#v&O*i;(2uZ}t)=2rmrzfWo^U^G#bxvlCC+0KY%RPHzWJjqE-Shjp`Y~?~_%;|`u z%Uq`6VsVppJ5Wed#O7EA8!F9kUme9NM_psWNMu+qhH8zY-p~C_aEN&I2%X)4tStq) zl}{%5fW1P8SC?#?zd_ht2u*?+h}K_VDWy8qY9@Kmt|UgFJ)FIl{YLgHJ&IcL!kvy1 z*cE$Py8vXOYj1r|!48U=w$a54P0ebpg~vMO2;-@rDp{fdH6!LqqCqYo$ftN%13|Il zSS_OdduURlwX~o2iV6o@dO>lq4)uPdn#M_NvivrA@8OYy_D}`B#u_fIfOURb7$lm1 zAx9MUf`*o!vAjsuSXZcU#~~Y{9YS-N^rrm*h$yW^z9%!3x35FAO8jJ7ilYa!aH`6F z6#Dhib8@AJm?<_yv~rSi2>4f38wMD$1a9?rxpn7!PKeSUh!l21hV~Rl>=sl-u%is= zHL+wWH#aylC=snLqt;_XX9l&GY9Lw~&DVYoMWy+f5tC*)Oyq-6vLz(Bl~L@nPxfEb zzgSw-2tugEZ_&U)Ef~3`)aT*bQLnK0`1RlCnG?Z`j>P7yGpeVD$G$}54i_b$0b!j( z2S9atiZqIqo8n*`0+~j1ppOeLfzWCNHtvcMoW&5m>wr0fZWy9}mrFqkBYHu}sbWQS z$Qzq9R91K+{;CXi-gdGG9+@DbKRr$&B*#KoZ*_2#q+ElXp;gp^IFEOF^+PHc{`G%+& zrMQ;k{pO4f|aMf+&N3Kr-SE6m=5mZ6Ey`Oz7TgCRN1LuXw)QgXS zeu(V@^MtJnF}RLHn(|q1=vlMPv#T;*9j>oE`5CJEDH|t^)SGht72!?Iz5GOezqI#p zbsE1`R)avE-=LY{?CW_I@5AQGl0}PhB?{Zm)6GAB$u7QyajImVencO`fz!s3{*0Y( zvlEv&mQ|VQ)k2P~LIe&-C+G_51J@4UI}Xj2fYI&byf_&B#7-QzW;))8d+TlJ?x^@q z5;977P2kH5BVUQ#9b*+&7K`}U);=26(UH_9yBOFojfBu#F+Dg7O7Tjs%ms=^a(?!@ z%cBW*#wI(soJUt1h$VbnXmyF<6;*v68S-YuO|HX>pjnv!fVPQCg==g!ypeCIsX@MK ze5{lDV0MDZxaI7S7vqsw$>|?G>F5Et0c+#2JHnjZ(0A}N@<^@3^oyQ$bddga*%^lO zM(zlD??%4k3Ho=FrQklSlMa3(+QQ^titaDwq$}2jicxOb!Cj9(5pZmq_87NErimzV zV`V)1MT&0;M-dRN2X6)|vDfKyp?J@)iQc1BvT~!dMW0Ut3OHDCSBkS`g$1GE!m?Db z`Zky++l|=SPuAZG_IOQA4@^cgro07UU*D$=2USnflD5ajzKx5 zze;5G12EY{O?PRf>z>lLzb{OTp~!CU_PHoiVm9We?PPce==WpQ36RX_rMuI@&eTOJ zz>w7SceNta`)53pa3#~Q%^!VL;e4v^x|tgq=E_-gRz#P~EJxnh4!v9QB;z zu_N4^)os0J&j8A6FX)@X=f+H{EMTb!#&XiVbySylyV?i_JTK&UsM4M|P>58ke7m%4 z?!$ryKNn9=H`3g=r_o%(ye94t>Ea@3O<9Q(aYvpKaghuSg)U4;hmCmTt_Rz%2Q=pr zBf6WmuRstL69iI{gCs$_>|vid9a-X+>0gIkg@AjS_tMaPrz43BuNFaAgr#kXa9 zcODjvqzzNTx!a21zP{mZCry-Yk=K7gRWS1^FQJfXtcsCTjb&UgR*Tv)P0p|ZQ`K=s zj-2U+JR>+anZ?n*TwWaZGc%z>GTx5NEgW68TTF*}D6%DN6K%(kHVTr(NXUgG>U6=P zWY_ox3zEfZOH=3SNf_7s{>!M0sbh^PkbV35XbiKQL(gsNNkq`)`a)CuPqT03bvepi zaump(z2^nVguwQg3P{$QBnonbgEpspw%>Fdd7QsL4x>@-;wDA9eeOfN@dS`9HUWPAhF*_x_-B@1Ff=i+4ESIU}rAc<5b`B z8@QFQn$_F0s({+8r0`q>V-Vd_0FLFMSaW3fB3W_-KgH!##J`s5t<8021|rl@%nm z?-~pGvIQ4W7*Srwq`A1sC{n8kg$k;UR*qearQJxtyoT{8D8iMpAL|}CMQSdDgOqLp zA_4iDS&|V8qV^|RiP4;HmGd6=b|qB^Y-BYVT%YJtvNN31%TG{ z-06fYq&5S=}g&817~d`?DcLd z`Lff=EC^R68Jgar3~inye&yq#t4=h!-PNf&lX__5Iw00#VtFB)1bk+>x`@Y;gvudB zLgYZDIOvw9b)?ztW+m6;C#utoP~u z&GpCoN9J{}XY1N?_9v7M?vKX*Ea?6vivA_&GO;rLQ_*Govs>{`N%bF!F5^EoDgRB; zW&E=Z_C=Iu4mJ0EM+}N%Xz}gtO;qOoNuWJNVihbMRFqy+!byckCTsGzPe%9oIk*%_m+RB> zaaFmne{TC*2DSGb%e`)`>pqyN)!fXvJAPB#**H&Js&nP(*2ry0?!KeR;{7;udcAsh zX7ag9ah8?kzRb6kkJQa|IQNvi->BTzgtcbdf79~#>~LZHVU7n$fF&zIaGBzH3aDP@Mvi1?G>5c@t9FUhJbNupUXF|H(LAGBOBq;|tZo+b zdVL=XG=lwn3O!4|{*kqxT))DsQK>1VKeOb4%V|dAIZo8tKqBc`i+T>`lny6t%)?r} zPy&bBI?NriJ+O*+R;qV|+9R6(RyCN2=bK`5)8y^n3;_gqti*2Lf=K*PGokHWL1$Rh!Y#n{RK@TUyOm4VrYf@dk{}5{J*r=t^i!>h^^?-R)5H7qy`9jx zRjz*Jo;Mfw7yoVx_phsmFNlRD#LD#6IF5{C4 z!|)Dncjp9K&%w_b*%_G$H&5eHdBO9i8XUt7OLB(e>fK5MY+;wE7Nls1+M$SAY9U24 zFLUh;?XYN*@{9nkf|mkDDwyD?HPh&g%uf?>(TQE4i1 zMe;@NO%-^dHKwI0b>0G5Zgv&jvGuH&YUa@U7=S5}-OY8gpzc-lu)r zMF>y6p#6&el28N#b+B1Qi9I^ma>;pTyvhT(1(5Y@^YoVyG~Jy(O+CFs9S&hN5Sab6 z``A5eW_5o!7@n~G^*o{as3Vc1U6IyFW|+(5TsR%c z(f%2941y^x7SQe{m9KuCXE2ChKX}Le4aZR~9M@wSk!PAiToeQ(Ly6K*78bsK=XK(#WH}NyYGO~}!dk~CG=Skp#kbqAnM^S<1QDF#K%|i(hyjOYE z0ZHD!Pwfl5C07K`)r}-?P|5Fd^G>x2ps~Ja6h$=nw zYkXlktiAk(MDaymc0fy+%`)sJF!p6Z3tP5*Z_5FAPE7!!r6=xbKSc1Es&@X;1eC|lo>g{Kb<)9AEG!2}(?QTHlP1=` z{sJiish@KQ#7;%<2({EwVCA8<_#q4COJ!ME=nMo5RvgDKi*E|~OSH9TOC$BLGmF4U zAO{InD0%?+#lye(lt8OPVn+1SP=&ICDkdy4k@#%#FGfJ$j4qAPn?W2k`Ut7F zx@3qgSmn=lWS@%kr!DiYiOm&*!b(SyAJRp^Me^wQ1F7S4>j*Fb$i$f zdLf*0f|g8ExRVbKc_^O)NjSxfgk!#Q%|(}{DOLf}9>J=J zU+B=NA(@P8W0=WE;i`h851sh&j=}SO8A*e98mbkfAS!GJ2#)Rr?=Wp|8J;~@p6Ob6 z-i}h{t$z-{n9s4aKCEa00-e!{OEZI;A3G`T5rqcz85oy%P-Vfn!D==ta4{Yp#X*&v z*@tB@@+Eb`Uz9N*vB^}4WHoc1k^-f>u|w$!uc*?(Yt$h}^h*Rwu5_8HB3T&v-Te0# zFm%)yGb2(OOqfhQ8nO%r3kH^hfQF~sq#{od(w|91de|@x$_XVPfw=60zX~MgqitK4 z{YRaO_SEz=fVcTX(GzZaFBPO;S1QEE7Hihu&c=QfQ1&~TffaHJ?nSx{*_%%dEDj29 zglT$sLpH&)g><2TgPn|)e#_SY;?EBWt5ex0Ku=2Ey{+*_k**5=sn7GSQvE7&AXF?+ zrx;)ebbGrBApy+&_1rV0r%*>1YwTurw8a#DH5WU6ehX12vjXEFW8~*5m@)&=0bWt5 zlQ}c}&w82VIpqzj(GRp6f^4-!*apa}js9LkGKZ8eM{`0tX7)+V@(Nufcm|8G?59Qn zn=*J}v@n!x+{5+_g`^aI`rJvfYuHDu=QYSBPZjPnm^7&4hlf^3>5IfB-=lfL^(^75 z2eN;0t?oFY4^+3CQu&+n{OY58?wmyviY09LVC;6e4(LXgH&Nm!%@ixvYlv)nqj$Tx zm3CB^WqB3o^a%lzHi;|sKFCWsYUq)B`10_TJzK5#a7e%V_^Ai$7#400h=8uY=EG12OKIIVgv1LEE1$$J|VcUYW0=m})-|;vzL)XG< z&1-YdH%x%=Ozkuy{sj`Y`WI&0nwf~lIEcaRp>`91B(Flfe71n&SH2SGOoG<^7~`Q+ z-VwFVY{|3~3UW^R@vK7SE^hVP8ADmkY24sJ#miZh_)a}kH9N@SVa9dy{S`^YbJ(pY zaPdb1zBx~BQVHcTJCzIC;CY-yNCxAEXy$?%5G4s59b^QR^bq@j916_)Ez>Z5Qajg< zkOX+1zO>wUxMISfYXRw%w72Ud4UIcPqIpM&rJ>A<7nXzA%^V8`0nkXo!f+Jz`@>b< zQqO^sHViv6BZ0IC09P^>QAtc>g??2*$6*{-Dv0>YI>)+0_^ZSuJ)pX5*t&eooMlO2 zzAwbA?Oj6LL5kFFiA9#Wdv(ns!=fXN7Jp6OXfk05N?6_>0Lwt0`-Z4_eYlz}B5j>B z;n?baOgyquPBeHJbRgw3R?aM4F0d~awAvt3Oi|Qru9#Cr^MmlZ_~_~medFQ_F`HS_ zS^0sVJ=YTfg8y?nod0HwcUhwo&w2ZfB{vv5_ugVJn3y6!02O@RPU3aub|}g621y&b z8vHWMtE-4VY(f$crB%cPe|l%8GR_gEQqJJb^D&0~Nlv2-)v?F0?nR1b<~WgscxT@X)(o@q zaEPdxi05+vIjZS-g0R+OM84)G{4##?!K&ZDTL4E9TS9hatW4oFjY1Fh|g+}dsGt>S{mw4;p9sQ zQ>i+`Be3-@uMO97Huxrfy|rwfPZ)?Fiz$V4$i!}lVpWdt;K>}9Uu4V@QTAitG$7!~ zwglB*2tnmdP*K+_tlkS;sUj3OWoen#>!CB3dXu{2V8VPj!$c@!+y?U*UXx@78FOz< zdlJum0e$oOli4h(@YtdE#f779Rz!2@i|@G$bo&?yvyZg}hQ1~)WS!I2*JU12j)yPP z15PCDZhlz&-?zpm&0vzum|mGpsBUg3R7qmCzX{}#XE>W^DRPe~k3p>ZT!S(JM` zLYaQ=kTv)!^xk1oYnLZ=TQ?(4TVJKY$2Bu1X>a^Z=Rm;%ipIfVF`uOXaYa24QK!V} z)ez{AFB|VDQL62`g6IK(kv3K$ih=UbYJ#Ifah<_RgAG_}SCUAd6>gUrOY7ri%>6@5 z;EnFexZ&7ZTY0{s`e2Pd^@n>(Y=Lssi5NAcMFEgBL6AYu4rG=lM0O!+n+Ce?{#n;V2hJ zC1vqRN6iC^c6SD3b+OtiusDO%I32^1S6&CZQCL9)s_IALjOq8E9gAP5I1zwq-@I0t{QT071d_8-#pIPYveTjUjmf}@~ ze%rx;vcrC)_c>)v8>={xATKos-%G|sC#d8UkglL7qC&FwdLVn|c_O6$&T^#n-9#`2 zTv3h;7xJ_5V!MtA5qc-qRMH0zdB43!I%pe7q0&i!DtNab-*I}-cR}0eFImQ8;=j7U zIj4ME47t0Lwjc0^ff|Z?S_oiK2nA-EDoSxBeK-#n;3b-Fo5%1Kp18i0ZQ3-I z%glD#V27e%HnTsl&84@MryaAdRC*Ke2D`k9`8zWi6_3kFGM~7bbQky+ zfdQX>Ln$BD2ZF>fr8gUp2rgsFN5Y;)S`nn@?3NN4kw56t370#em3vEL>>vjFqKp$^ zghG$(2i+=tU#0_rz){nCIrqAVv~o&=(jU`1L3H1#Wld@9*p`)mXreSGES%nQDv;oT zKuQug1M}E?q8Q>4Bs{k0CgQ6r>cDOqo_Ha|@IY>%F+?u**ub7Ru9xnB^}L~|jZ)~0 zK+D}~P_{O5ii;@-l`;&qgHud{S`?mmF4&-kdzx4E#c0tXxe)%WKj5b8YS{?4D`BBs zHb1ZO2?dWtps{7`n(tUBe@N}7^lC$8C6vraMmrs%YNnf!_py>04{Fro!Fx+iclS$o z-dfo)Z4zct*_1_NrAKaaEM(3>W8_RIk1(CVl-^xwD_@2Bsy)fpRA-m=zK=ZXsA9Marj}%>heq_IUJ;y3kNz z9nM`9+DrivV2%Eo+l%{42FcG;H;l(FosfHK>Alg>6QMw^ZlvM}cnR`j5qZ_osrCr} zYfGW8{Q1<)XE@3HlXnPk_;oirIB*}gdnXq7OTTE{8#_2@7_4_JTx8VpYmYNjor`O0 zSJaNqN%!So7-{0aVrU!wda?4awYjvT%3ID2qYcx;IGow#IEFy9W+|( zo#L9$yb~x?&ut}PN6^+39Uw2t*bW`L_j+;9k%rwTZ$mhAaHGxO)>6=?rX3)EFq&R% zpJyNPSfyt9{MtNGFs`2R4uc-Q;qVO2aAY$jcL}qE>ZUzk(Tl_*CXmtewnV_;k6n%N-BuEH)g{QL>Z?Ur4f+Z_Amffj!Zl9t}qdXI!S}M~c zy0Sxkab!8&ncJJoX76A5a`x=N^ZhZzXBDfZeg6FD+WqY%5b5ah6XO2#>{8q-?sAFf zEt9HNmS{Vri!<6o^=>-s*4#hU|Kqwnw!%D7{282?b#l9%HrjuFqe_r0|@S4KA*w|7)jr{Stl@!Ye4WR10 zzmvt3<=Xhfv3#kc*ut|_r3Ek7+IOpG1GhJ|DZ0sf5`i5S>+=QqiBkZZr74GFX<`ruAYXU4)zyvb9d^1?-RZ64{NDEy1gFuGOv9++P!Z+p2kj*cvpX|PRz~oNXT+)zZ^k& z#pPZzxuljFo_M0O*B2+e25L`9e_m;CjmsDy$gXU+`@uOra*td&IYV?lW>lA$!2NW3 z*#dKpu%6l6TNd{ zX>0`75syf-iOY<0)8jcK`$xneH8JemWyMZU8z|mE-CNYwX&tWXd@pgq>J|RR%{jq~ z3wFxAO<~kx&5Rom-cg-r)Yc)rWJ_xjFfJ8GPyOJyW^A3#&vgX9$JZ#d8-3W$(ba6& zN|b_#MMBFL*eB0n{Yz_6H5qR_m|gjr;9C%{xWTL6QypY{C5uKdtcyR-ba_nmS+L8?(5B;Mc^=0nrX2nkhdPrWTyOo^Yan}u zU84fzqR06O)F-~EZl-2TPyGX?k80^|3~7O+{E6nLF<&ob`!-{@?7cXDAi(NnS@VxM zXG0s0^WWySB_JpC^`Q&t+End6d^d-ej+5lMYTM2Oc)x3}9Hn&HP;VX521L>}tJOuw zb&qPlw4jbJ5@AU1PC~Yo5x4E;a6aeq>fuoPbOI_DX>(7_oIh5c^MmI-@9N$jmLhpc za8syT#g1I9g8NGs{UK(CEM2lR&4n9kW zzS`7F-J2lKfrxr(qUG$NAJPkcWMxtp2lxC=MB!w_eaTB^(kYPe+t*UEyzO(e&|XFg z$8v1ndDlL_Wj!CYCpY&+urf6yX)=mI`htT%+I3aPtU0r!oZL4S4$TTs(6Xxr0)g55 ziGLo7LCcC3D%!WUAhB+4Uf5}MleaCY>1HbVZGER_6x=W$hWA#!AG>DQX@`9t6|ZGWw8N#95IB1^N{e%E|RsdC?a z$P2)7vJ2IQ&f26udko{CM1+on$iw(W>D{5y)rZTOqM zc<+ILa@aN|X=pfaIy>_2v+h9yUv(cC<}ML8b6aUNqOja~N$86xRu(1=dR-R2dSh)A zk+HYP8Vv(bWrXlLp;=Z=`qxFM(8%t4IRo1g%`Ptvgwj|>xk*c3z@d)RMuwm^O~7D5 zDD8q)z~895o$5hw= zWuPTy61a;K{Gfqe($V(c>Wof*@&P@2P|U(>zvC)$_-zumL%O{P{t{9Q>aLQTSQKY% z94?O>$StYl>OmU)BUxIA=$vAM;ztnMUBHu8qwJq}*N!2#st1}9aK7^KjY6_Wl95$;6N$aBx zPzo)R6Ta+wXnave)hq%hB}(q&Gbv(w(n$N*+~G~hL;mP-_>$nLK)<}OJ|M%u@>!h* zQww1y8Aha30aO+@QW-h;ytSs&zt5W`Vi3QztVOQal06LtF&t;yzM4=CTg6N>kTk-?gTxjEB7fQaJbo%N5;tpfx_(4rf`ZNFFsCj%B05+%8r#UQ;mwsm4<* z{n-D^t*8C#J|CQ&X}PDQK4UvdZ4x1~9%p%bs{lQ}Pg@=`;Z8ccEY|HNBlkr(2Jr) zECcIoiW$Qa`R?hI$&L;h?yTre3R`+kzKKvm81~o@E0zsLmd1$CkJ%8=0q=d=CmEP2 zjl}`fI*NfkgpMrTVQUqJsil1n?=(vhdYTCy|GGn*B&hHduJ7hT!0zdwhF7dLWQ{Cs zdS3>MREi)!&o;>qKWvGdfp}JyQ(2XFGUYvZ4G4!xs2nm8M0ATL^t6*BKU(9zLFJW; z5lq!nplqTKCUJC^IIxB&IF_P@+hgRC*)p^>NFqF5W_N|)IiPI_-@)f-TxrTWP#h9= zFd5KYN{8MaohFxX2aK6$5kQb?wL6i?Jy*DAaLA-6uV9eJuum^5Dr^Fa>Bb~2+k6+| zfIsY(lpQwDA+7-j(sLq)Y^rS(Fq`GDOP$Vtu>(jD8pC{757025cw~=wP9kM{0c~+k zo1siVq+jN6R7XRsmu?M?IpT+(ADT;wCr6=$ot`=ZkQ5c`(laY#6g z-!*$;Q4(0uYz^A|8)}9`dR#{ZbWBdWs8XCq02j7cn&(~^n7(W_WO%5Tjq{PSvNP`I zh$sy3cp)X1RaEA9;(XqBKg95h1TE%)8OL#@ZD!k*1EuWnDado~q?!tj>BGL- zX}xvX5-2db4mJve-8$^0lqu;h5nIKw5jVvKCHhz9j+13J8h8*#J*Z!i?qt%1z-@%S zR`cS3Pxw+J9u(`z1wtl(&aQH~)Ml(}#%mZ4gitW_wu0F1JF@auoY+nsA+yv3l4fPJ zrV{v~Zw=oqX>6bx-B3_0u51*oORShx3n(ofYNaMG`Q1zxi`F!Oqws@&yxLm?x`QNtn!jQ_vA=2%wN`c0}nDVw}msgiD1c1b$3! zF!IRAkbZ2TY#yVMFfNt9IYca0((2a6hshsqQ3_cnC2ABiMN^(bq7`R|4+974YM`1Z z&8}cJt!=ay5UI5Z5D2_pa%jUIRaf+}LtYLOHaOQg+A>#CN}~Eo+J3g{NLjyQmGMPr zD$q05BxjZo;;Y~{n=}8xc{fsyoJC{N`pE5$cBbL9quK-*8Q+&6z45gPxSHH4{y4;8x|aBsrpW$A07wCv zMgIP-OA%ghLZlJBFp;f=k{p(gzs#D&Sp_Jzbj~dQ(s_mC@Y)bDqmY9*y+PvH5elj@ zJrd2U8@C1YT*3H+T|PC7bgsBgn+xHG7Ku3Xp!ztLITUTT%=k=k-N_@GuREk=R4?yW?$QByPZnI=ae>Gh_*xs-yr~wY8n# z5lm8n->1B%h>;}xTYIsWJmnHxjO0`}878!%;I+IC;n&inlJ)}3x>Leoen>R3pJF$0 z2+7~gK9|co_7w3C1(IF4*T*#AvdiKI41;2ZENjMq6BjNe^l^z1gfiNc@OQ*YBJ?)% zm|L-VV=dZOjEM73!#19Y58^8Y6tI_t798L0 zBNfzXruy*p=RMNM0?JIC-o_CR!Y5YqAuxyQ+N=noo7}{}PHBp0gU03FNnrXbcob<0 z&Zt)odN4Cg8q>fyf!rp6Oq-FBB0)XX*y+vhi+)$f+CF$=)&ic>LQPuEh7ig3t-%pbP5otKTJl5MFIn*Rt+G-=vY$ zVAV4%Le~VchV!nCiN$62r(4s7BIAFLhGKG>hOEi%>D_yFJnrvWRYXR%RnstMw@ospN!^bjCp_^eoueIZBj_0k>Al zsu+EZiqyKXcCl3m1W->`TP+q&R@NyXXk9iatc-C}&IJz9$0q1JoyI@3SycB>%RfSL zZ)BOw=@7NBP^YMXd+@W_U-^G;ywCtrfl#Clqc4(6nAl}dmolzWBn`{lZRprzkrnR_ z!+0GBnvtGDdCIab8$n$+yC4%Mg^X2Y%%wIurSYzY^36Dgf~@wctZ2QA)9$O;PMNP4Px(Kj+e9eVkZ0>_&DXMEJH;g}?vo|1+iccOB zT(@M#h!Bz-z`mV5xCKN@6__;{%;QzwY9GZpGFz78+_S?}6wd5-8Sr9h-FTPs~p=3&J!bzWNLam_9|vf(JbX& zaa_6#jX?n;$1=4C@{|94pmaT+kMGvJs%qu?R_u2%OF!zaXD2y3E9V#V)7?SmXklh%Y^c)H z8u!Z(Ynt=DK{aE{CC0Ebo2& zkzyC|AKFJp4CwRqnI;N19TgFroM1B5pVI@k8W#X7+VwTBL+R?tYB449bwb<>wpnVcSZSTD~ zPxUTOI2KJ7+r1Hc9_)7p%SG~SByg} z+(Pm}O3+a@;kXC$Ip?gfxp>(-j(xKEnMf(u!cG-B} zsaA9Q%p6skb;B>6pX7d^-@B5^Jd7O_j?A5R&La~Z6zY`W?kMrgcd%sh^QSs%38;d( zfV8wkYgRI^NZd~DQ? zVz;|^*w{b5x2I)|Rs7*`UhZ?a|FLks&2HO!7=0furV#p_v^{^fc0@OeShEHJ+13MP zH^aGix9!KHaA4&%Y?(y;{qBB7=JibShAlMUZB(`QZixdS(N}dkE)#zGvi0VyI{l&l z=|KDX+41Lu=kX|AF0be7%(d_P%v36y%r6k%pRr{Bg>d!H6ET=sSULWgw8r#b981CU zACIMA{8Ov^pOe=9)ZqVrsKfuu>i;BRjp_gKV2b}!hyQ=-@c##O_=KP!&q-|O(1 z{#82thjPpG9}l8n`mYb7_}@^6|Ci36g_~@ zZO{8vZ?EtD z7GBS*!Aq&FOl^#@R!HkHd#E$M*y7b#Lc!Zx~~QOG{fs&%y+3k$%npMcX+Ai55gzw(!cfZQHhOyXuu~ z+qP}nwr$(C=XJ+Se@yqs{LFVop15%%Bkzr~_gNdMNM7}tq8ZZv_b+1lPHw8BvqAuM zd1&)x!eoX~6bzq)`Frhcim#TBwyrlVb_8|rC^J0?^hc_ax)fY}s(hxQ4--&x70on} z%RF<=B3o%~YOd=uVAyu~X%~gNb|N|Rbt9iQV4p9?ca(4FaU%dvadmZy>LVdVZ8?id z?pda5DV;7|tq)o%ddjMAy@>nwZ7Cm3ZV-!C$CtbN_va#CFR!O2EnRf)eI75@1 zbpBzv%X5{I{B~V{L#Ytqn3&pChK!Ea&SX6p1Cf|?fNPhS%%h5y?Zb()1N-RMa|A+R zL!K37`pfdfO4F6Q<0Y?&z1|&NKl@25wE52^5F)B~q@Js}U*@)mhLkKVh2z;NuPem0 zh@5w~aOUrgEbnPjJ_$Reao~{`)_wAIKDss`rzMp*Lc4_)2)0xzgOF@d_Ujc565zot9UrO z5$(e}gE&2*d!$}sJXk%6C7y4Fp(=s>q$+?c10L27M>TsOK(jrrgWyIqCSvCBTLBA2 zqY4=;JpPER0G6oG4Z&ME5%i93`3bXSw8JV%ne@t33GfF1uI6Y5lfPE+`J)?BpLJ*d z*aG<5e}!S*?F*z@oJD-wnUP!57pXS+Q1mG2t-v?RSbyw#jy`KpPc{XGqgt;qJ5hp6 z5>sKzkfBhEYsdvPpI=0jCa2ICAS%W^(w{}D=52NQ-w$xz>ZK72USHg#^ZzQ z=15an!V37=+$YlH7&#4=d`0%OAb!1%jjT%@lk`XIfg)q-!j#QQRHkLjcmS z2=cpXx(PV}izK9Ls6Y$oDX3vf6qRM57wJgEZcz952ymdAJ4Q2xf|6zz0@TjHn{U7 zcBa@gs^~CXc0QiC2lGA2>+lRnM39Dpy!zo~a;FO4R zRH&`RX2M>9-$U+%#eoB8%~&*A-$^|c|J4iHA&!w1(^0LsYa(z=qsfHo|57Ihmvdm$ zZXL0rg)|ZwK=aw3;-aSCaPyP6(AgINfF#j!((02W-wKQeyo}qMjo)UxGTJ9>p4@;$ z6_k$Zn}e?(J_6}xNi{1A=fwnsgw&Rf0Z@%(^b^>@=qnhfD&6sDu}O}(bU+uqIZ;P9 zEjY};{R80tT7GS^k4(~;*2#AL^cckws>w7R^es4K)5^|{F7UA5_lv;Q;Xga4);Wn_ zCbAz*jrY$IF3Q3a)+ny-zehy8kX$g1RNyu2g>k!wST&~&%SQ*uv0V{46Ljjp5A}Mv z9F=dJCc((@Ky8&9DwHg40KI-BE)oq0?NEgUs@$dtkrNq!g)w^+jca{<9zhY|u@%G> zfnlx44jbUe9(lVJB2WyP{Rqg2bc9|Ws<8q_Dk3j%WTUH%q71rzW5m;(wB`c0;BP%I`y^uPn2-a$C$Wxn-qOeA_N0uj?&QP5(YKuZIm52LcIggC+z zRD)}-V~QxKO`CRB6A?hImS#ubF~PdF3BxiT%1U7Jbz8OP9yspDOw7&hHeZKWp=He1 zZ3YaVkNRfiY$95Cm9jedkKv-7>OqiO;EmS-rmjD+J-;k|b_Is~MvclHnTFY>h zGCjoN&cn1hJR0dt6u^N8n0@FoeiU3bfvT-_s6WmC+b1&Y{H9WVt$I6a*!}p%wzC5` ztPU+_$oGq^6I-{yJKzux_HLa0`@xfZcAJ-Ywp&2@y>z>Jo6tBCrPRm5jIgcTb60XY z;40tMWv?|tNCn=HIbXmaxUZ8-S=?#F@3x$6&-ZNo#V&Yd{2OFuczZfw8Q~Ve)XTIq zm_L$wfFRI3l~&2Fwmve3zw^??=q-ZdVWYhIVp=PrH}?E9@(OTtGtL494Q z!0`>zHvr_NMn2}>V)GQDZ6~U~YG+*lyBNXFEFrPDYrJ$JVAagCu6da@Bmemcn?YV# zM(6d={j5TVZCYU7jkoDQ8KiR3?YoN_=)fElqo_I^zROEKd53jcoJQAOafcX8|Br=H ziYhY@`@G~5h*+n^YJA=NN1!k>#oh_nqPffK{FqK846DjkNDOAU~2iarQ5UpR#sP?)2yO5Be)k ze5z_Wc?}lJQ~!)`2S%ed-;j`0QI=no;#IN!cGFa|ElN8GynomTxG&b>bC|bX35uqr zjT!?#vYO}oA8l>)>TdUpX+Qu?cVA!vGRJxpW<_6QGIILL3)QJ;Mw1G+$dm>LLD>;B z5M3%oC9s=ZhM@axzR&3&d+ElEzcY%z!RR$aQ6>6j+Yb5PY?{?h)W$$e9GOePRh*{k z)e;}wHq#5&>U%PZ(zQKpQe^Y&hQmB!No(UnY#-VzCW^qxZQoLvWC9MzEi9kPBZSe0 zAeeQ8sxvaf5%QP9sr@w!S{G%adQC2y@7%!E)38nWnDU6qjx>P^|`S8mkHaqaJyDWqzcljljtvTce2A_gNjJp`+ z$d4QLar=^CM_?ms!>NUK3&co(5Y3B6B>2OS7-W?-)cXxDWNfnw>OcrCb zm?ji6P(c%@F#V|y#B1fltslTVii(QHAgFmFtr^8<4h+aL6YXqEz-nLw%?&67Rtq^+ zwV5MOIRKpWPu z=faBy6(+NXs6`x(U9s412mi)ax^yUsTE=M&mDxAfURAY)@N&)mo@bV>%@lD~w^)b8 zV=2M*7m_QpbG|W*iE1%lMBC=dGos}_AnP<+HhPgbN$g>)%LRnQnwrs&N|Bd>X3P@E zQ1&rlK#ZP>)NIBfH(;ECIwlD4$XL4YvCDosEVBvtDN^o&+iL&ZyIgy~TsL^hRRA}% zD-K2a1_tDDVa}Y5hp1#Vql*V#jhbN7XmeT*a|*;CJ016M^dO%{HOg>=J`ZCiyL91f zC~8eS@&YZ>tr~DdvIfIE=rguRmW~T&{EMAKZn6x|Ej}nD#OX*u0dxF*D>2-^p51*r zZOXv_q5sl?BJ^fDz7Mgnpc$@6+PZ<9Mp)^{m|(W9*h1eWAPUm2khqgN$533C4S&-s z$r#y$td>Q*X`ZPImEXi6h-ZpIVMjy7NiEiZFvd~!NS9IH5fx)_|D05S2$*ob#_TQw zh??mE9|@t3;D$7nh!{Bmrz;Hz>7F^~YD?CgD@qEyD)V?f$PWXE3L6&f`!zfAB)Vdn zzo`(_o)!}~OUdlIuM@BNJtDDCwv0S;Dh6mYCf_O!K)R5Zh)-_N zRwHv5Buu|&`HTCWQqX=y)s05ZJ(74JB2H#XcRY=#RkQ%~YX1Za$(#NpO7UnTuvKkg zhu(4w0oCH@7-PbEaov1;dF(n`OEnFM5=WDC+;Axq)qp~b{YlwV*@k!_`gYbaJ?iQ84Fv9b{}&m9M&8VYZZ{*amfes|unFasVO2?X zJlGGRE{oCSoJpuzDuD(OHs=UCAC9gQk1(wbZjYASat;+=0 zKl@wAP$VO(>=i-w#%VLrRfJ*YC>#VEipgT2@xO9)z5$c@kkU-NShv0kE|)rf=U!KU ztd5;fcCn~DwoWjf9@-e}K3{b$mN!6kW%1p$fev^>hdO=&Uhwb81@fXM%#a3WT9fy* z0GE7L0o)a{2P29-(5`@KH!UrLeX#pJX!`Kcu7IHRi625_p?h=9;R6h}GEUOA@;(6e zaHFT4P<_Y~T=ZiTpZ{t$?SiBUukL{8vzjrGdAM+XR^9@U3yQ{lA6fmLv;x%m3e||` zu(KZGiI}wlyx{SHefvT?axI~c+Vi~n)_|^)eR$=1wQXpaEx~cFdg981K76MwjE(I= z&XNSn0XqK(KQn5^KB&(Itq3&2C1SO`X3lry-AOdf;1=qNUMdV+xX)pNKN~p^P5Mx2 zrXuqOue>)dPX6VYSm8s`1asz>6}=1?Ae-m()c3%s9(8{|^|!}=E3X+s)@z!fW7e~w}kyS8B>>|`bw<) z_&7%u*D+ObsxWSwBw1vdNfjk zb5zTk0D7=wdulE{jAm7$jThB5pm`_&b9>1B@V#I~ z#XUqHi~>N%Yl+)v34r<9uE><{3{QP^CfS~IafYrVIxyC(&S;}tr6l4yO!PY`Y9Yh$ zZiEAXREt&-#F$dXKD?akb8~E;QqEM1Q zVGB|+fGZ?UteY1xXPy%!kVWk9ipbo$v>6uHZo%8mHqj>MHr!q>@g~qv2s$Fa?O7q} z=g)~WgX*|M(P1zN65Xx@Ry3ex-$)YkXVGSigt>O21#ZI2oK}{~Drn%jmoAe9?^&LN zW2h-QN5EbYCMaa-!Q-UD^L@GAi zxJuI=GTv}>t-SGq*Bw%#Deth!Rc)ea5@YZz)MpjOerD9;x^#@1+hP+EN7i2-X1}Ba zhH|7FW2B&*HPTEB@xb|kH_BLUt)=l5rG01UA>#BY=KBf&B+G1Pwl!(0i`#P8ZJ0Pp ztEuiR=lK2kB`>Wn_@t+kA7fhAYSawkvR=uN5i1z=L44F*_^@wy-nGn*wmq@ppglUo z&R#%K@ja7Be$lm|Fysh$q*Tn+nb&}j#BN-gA_uo_pqJHe?VKs-T>&Q5&Fex#!+j!! zqyeb$8yhvKFXY@k0#MVP0{#wVBr1NYF!U5=P3RxVFglrL#y|=@vl7#KBn?bm<+nYV z%6abjbl{w0!D5qIO{MW2%&;YXNeDyKj0<36(TlNiD{L*M0;zhnXnHqf3wXBr)HzvF z{Ido9la(!?la0fw54Yg4-+rjCjWg=#t^&g%uE#QVnI?NUIZ2yi!kFwKV6X}-1cu!4 zoL0Awt(QECm|UK!Q_LU#;*eK|toz%Bc=t6EFf)E94W1$e)$V0+j<>=`oo!lW(e#^| zcISRisFgeP@$A2+m^Xij7VXHK2KMH{h+_VOJex80ld%b@bV{c2p7tenIJyD2&|GTQe^j~aMCRUdJQZ@buxGK~C4OeCQ z{{~n6&&vNVOW#x6als%j4MewdfH8jC?5Qa7&G_uL zyiW!;b}`Omh*~~}QDn7i&I&Ivx|LVsC)GFJes));SpbmoXnVdX33@ zMLc@yFAX_X#fh?mCNPXwk^N@>rX+fGTdXMiJACvtEeQ#TCg%Cl$;$-(gIom{fYOz) zO7lFN?xw|r6&Qz9N9;=YE|Do0L^R`31a@OUU8+;j0J9Q}IZc!@Z{o85>l?G%u>6%7 zVb2SElCl>x%^y918OU*<7*w8(;lB5v?H zQnaW}%c!D61oP@7Ot`Kc(bgTxl+)_^pk32w;(hWd5*!p(V(`K;u_?x zM&SU?K+tZOmj`-)#?v@3j)y6hlHI>}5W{ng_p}ZA!UIZDR>MNMZM5H2$?CpI{5#e2 zcq|KnM}h*%+99JJ3LaisMC?+P?0IZ8L=ywk}wW*nH*6Wj_&@EiylO-Dg-@tQS6C>e60 z3GmeLb$6Nu&eJhe+H3&MEO4m36_A9KxW+@;qH!#F1w>_z;H!mTw__cE3HYI4%n8iW z&nS7)vmOW200Top@HqY*0bHP18jAwxAt1L(WPC2+zbCIIkt67!D{A>{8_vcssdMxQ z))7MYR{8>m7;bw*iU=tcXX-IK*pT^9Ros#HS8N1b%*c`}=}4QEUJ~0TRW8H<&4y@F z`oitKqJ+f?UM%X|70_VUU_>!|l%eV(F_gGOQLet> z@`PBUJ;UhWsRe?hdrU`@i_lNpRm6Cf4Ka`87-3uy4l>Acgq&qOD0h-m2)DCIam5*B zNmWDJ~hK9(BKrmlrUW`#Ii7elk1IR zON7V8K{8aof$0h-3M$&jX^fKCYxD!~c?zv!i3flmEuZrd%S#?8NSlxW7p!8Ff^K9O zRv#r?h#OfDd(@~11>Eam(er09u1@V0Y!*M77w1>_wq&{55s@gHT&#E z!?g#xELD8vGO+P>)k-l&L7N0cqAQ;P{E@Dz0amZ}esOV^;>=|d1oEL$;8JmsaF^x> zVR`F;uQ8tTNK*;q0gzToEE<%V(TkUGW>-#SQn-ck1VSU^B62ZJ(edS$O7FAG)2qE> zj0j$|A^*urIFM7&vULad%vUd`GAxxWr%EywrV@g0$`T?0smLUb!~w_wucw+zA;j+% zSYboNG7FY8;=QG$Si7g&crjqnzU3${f4_6_dO3cc-)_<-DPV)x3(KrftSa<4el6MP zV7Qtc0H=I@2}F11CYFeGT`Tcm{9aGe=|1yXDr|0}52iAI*QoMKT*y1o9LB$EbgWMg zT((k8D;GxPiXdMgi4**s*FDJ?BQHJrCbWtqa9jwT&3E-J8H-XC*b%!Fpm6-28qCy{ z$ME7w5zKq8MbFxB7z?_dSHiBG<*ni`kv~ug@7k{%00nhrP6ALHzjYC%Eu;6ebesMC zG7V>-0LHk=8EHQ4xzk9?;aC!_dE`n&_lX&R?xUMECEdoElZnaY&@E^pG3((I2jo;} zC`wzds)9F+S}HDv%-PVc|CnlXS72^5yfP8CIYkuV0$s&DHWbo{4P=s9P<}Q~^#iYU zPFInRG+hsSHqS|$oo@JK@i2(gaPGhmZq*h?Sw0Aw&solR^VKdx`bVe(_RqgOf)LPS z`x&hFbd5ZkQj#sNl2NN-ZRg^VVzbFut?8nKivc>7@drMOUU{Ys;O^tt!LR3r=qz4Y zkbxT(hrSe04#cOv6yQFG9eZHHBW8QT57+HN2HxSh5Q5>PzGx}H89wee>$K@cAa$-3 zLEn07_Ym}n89Y?j2cU6VT2`Lt3F(kN3BZ}Gd-{(A$EA-+v^P^ZgkY0!)lQr9!Ksux z!qMbj30!k6Nan-K+Ss0LUv`rNTTaiu1@-di#6yeDHuCKxzS4&qV9Lw+D0V89Z`Y3w zL{49a&6^&^;2_}Zjmw_FXUc6jTl8xtY*s>Ul}@XeVP_Oyc+q8+WW!7w%;XsQEu1!( zG1T(ys#yx<2^ER7l0KSHiwn)KzAF|L50_p86cQ_CzKDyyn2?!Rx3$NveT*o)P)9Sa z{s9Vd8P(NL%*Is`Nz7qQByOK>#e}p6ygGED>VI&;NS5wh+h^b^LSFSm@Wf)sZIUAc zYo^^G-;9aV-BHkpKlzg3$Xb2ObJO&EZrk4bdEfYVm30_}2&(!8+1L{t9==3DYs!if z8|au8@Kz63B+y<A1X6a%NwVrq`9@D{QXy zgL>6MzmG`hkdzAKBiRI<`4``P%i4-5gHh0wF7`k%2);R_oB!s76+LQ~)sEF{0@BpJ zBP%E+9$^W@U#R4Itet_bDtedQX>Ou?|NEy}hN_)`m9Y-G`g7JSgq>Y`>U!7bBZwb1FTZrt(4a4bGJi{7nM_HWU}UQ^jt9+WHcry&@Rk zuwbSp3nvhG3q8jNK@e+2+6}~1OE8hoi;MKQ&w9SKAj9@qx=ZHUIkZ?^%Z@zGtL~EH5xl^?8zlDamrs+7(HoE9LWBS)-7kY?;KoL)M}M z&CHqTDircp75{M8hqDctx}fsQ*vusf$L?Emr1}wMtI|~~#ZnpYT)8t3pJ*DOAV!?l z!ZiR#bpnkeI+JbKn$t<1Vy3=;dmk;;*^ws>%M@h6nPy~6&k0V((&!(JX~5k}$cUKB zcy*=5OM(kRo|+LI1q_9iWo8{{(a6 zDed&A?<}C!L6bB#TcwJ;P+DiGhnN_^SNfFr2L|5;=)ePG*7*}v(Y62gj8NtVo|y9P zF(`Wqw7m^J=)n$035aD$>>dd++uwCjhkQNWd>Lu}of+!V3@Yf{&Gh_+D3D6PSj};= zIX*+2NHyDX68A1x%)QBllTUUnh?$J6Ladlla3t%~inrc8j-@|wyT-@*W!y|ahRXcK zydghlo5PsIN5+1G3yUdM2U$EQsb&%~5wL;&I%CSp(XbWNuf$|_>BQ*86W|@bM2C9v zsDdk0CWnW8{kWVpJ3J;M35Db_y|K-xtbFt2nC2D>=wDz)d|JbWGzC{?8Et|wb)wu3 zcOnnIxroVzw%=~PuqzfAOJat#kk8_Bxrvz@LKGMTWZ!Y!m9dH5R)0fBp_|h>u872wyhoQTuY_7A8CnOnbfMVLg2oA$5a5G&`*21}ezs1#RH+ih;zSC4zZ# zPRED!NF|_}6%a$6mf7KcWmmg3JAdJYXhcH0lj;QN;nooarg^LZ+Y_D(X12;R#W3em z`Q;{X3Kbm1atzU|<`{BKPxY;xc*josK*gj%#z1Q$MfoL|t%60kb-;ISIL?9+3Ygkf zOb+(QouUvalqSoRxg&KRfd#5N#p331@t68*bI zB>Ox!imMyE*@`|FGOev*1jsQRYH~1=LtbhE!ARpmbfjvf)N~7}W89`Hqjct)9ENzZ zeGv{ox)|q`!ri7bhfXmd1Nxd3Ci;pk`6F@GBJU3ciGedTQoryW*GYBPx)l+~Z_2#e z6~{phPG+(z1l>coUHQFbC+-Z z{fo4hjOBA#*p@Dr&GLt?Sz>r%%SRig%bSX=D@JUqErNgrCz(SQf$kWHa*@bNuVq5i zni2aM-PUoNim_UQ5ZYWh7~&qxP1>py)&rt?ALs7yCdCpSpxIUS4)m+TIvSP>eP15E z>31=Uj11E&dndaa9pQ2{=Cd4MhwHo&u!Fb$JN&1pOE(OH@=o4;o*o#SV&t5TSu+AZ5SA?V!& zOQfRTedpOa&lB9Ez``!68qwZaV6_O+yTJJD$C!0tOGoY*|PX)zt*J7xVa z-Fnm3PRX)qBydlafvz?HwB#sdZ|YagR93xp%BLqC8?HPtP+hK-FCTVk+AlX7sx)pQ z-aDBKV#@mkGQ=i|?X0P_Cu*op1{a(H^1dRyyNba)6Cn%KGBjhU*%jOyGx%YyNAAM} zEz6hQTUpNJ40Mv{)bl&pFUHpUUFrn$EmxcpEBBo@H^ZtgCKYtCcrpL-TE0Q=KQJ!V zS7YUEbsE0rn16PR(-IuxrRHR(x+U(qHaBUiu1hLiK>W9{rm~ z{qVVPy9kP(&jQ`GTUISAQun8;E7#AM+M>3<(k-7ZKUu=CyfSQGQY{H?L7#?s@1`xk z-CodqCf|>&GY{`KSzA~6wwIoj_Qh*FHV?0@hhAxHZ3=zUn@!T(wL z|4FI%@6h1oEU84|;pE`gcPc{&sDkfr^#F8(5}X2SQ-Vbx%Y3jE7~rUo`QF@H?bxZO zu#2iHD=d1@bm9xAq|ndjPxjLevEGlb%-^5UOxvHgVYA8G9?tHLpQn@3M7^HlUSF-P z2b$k+_xnk-uUA{LQMp^$^0wxCTiaIONQ&Cv+^yr?A0N)|=cfxLpJTF|&x54Ti;08- zP3<5Am`U-cd>U2n{%fx0jM zaYp-+7p7mWj>qn{4Me8(+QtwT7BsD#6PIDyM0RiI4~O@C?w&#V#kVxjqZ#?}Y9H#C zCybQu_b1@r%M>|mqT`N_18ta@_l7^J7nqSAk2g>2m&ePu-v`?dAGM_|BO4u5Q3JF8 ztm@|PV~=N}lewv@zU<$dmQ_cpr3%~6dOKZ<;JIG^EYf$$aWc=Itskd3?rdtt(%d%~V8f zx{0|s)?`)T?{mm@xTZOsOjQ()zuRHp)8?B8nG-$hu zSFy(+ts%QrzaiMG7fOW+i!Mz7cDUwfpDGv_a<&5CAQ{KmoV z25NTtFfUojhEbKb)k#Z~ zP#*Eg54Fcq_0P>iJDyo+E+BY~3;*$)iq=&f9^?wNbWv>|mhXxY;r^N~)+gm^cLY@1 zSXUfW#eIt0pc6DHXd+pBN5w`7k&&~H_#Y~iag?CIT_4_SqF-meyt=x+o)ea@&1gI~ zBfzI>K2Kzx_%&$^sH_hkVFMU$D#e-|r?| z?@mcstJ*Jz+|wBaq7AasMX_`EFEgR3$v010)mujDs@f#fajgdcB_DFYO)-H$8n^$5T)|q~z$Jk0!%RDefuReUAEYgEJigcR1Y$~LC z1dCILRwe7vPf_M}nTV3MwC(V@%`zKk6flqBpwKtiYiT541D~?lAFIEGoXOT??qamn z`c+6$l$(6XeC4#QsD`lK?}zq@@r>fb@(#uu(e;8Y3mI~QTgL$oXUhF41pY{ytr&7>zs2ZwhP+6C-xQJNG z&|(<-8FKdA>C_%zt{}a#d&&0*`R^1tg-)xD>-;SH9+cfCNu)xf$h+A9)C2rtHt|MzM0xa zd1D&BXCBLaB_s6Q=Pl<RFQK_qdq&O+#<7g^YJwYoN<)6pM; zo30-4iRoSNv;+=4d>S9+&|}T+_E@A$<2)(`f%~;;a06~s^bvJg>{Ktc2b+$toPw|- zDXCLP=uJp_6d^LMt^J2YKu@dNm}B-D)*J8}Ggcu;K7nu}(sP2961!W7?-dar_Nvw( zWX>=P$#f?+MpOI}=K`c-1tGxMY!j;z$au$x#tUz~#Sh*H&W|qD=q1v=fGE zKu$muBWhtinunEdW#*i!v@h>Zyy+yi0h*4~yw#JmIbZTva*AL5LBmtUzkV0|Q9~Ma zS&ueXWK~$5x!;IW{ppIPDWwJ`v$oz-+ov$#mIJxiCW#)r5i$*Bi3U$4hI_4h8>?CK zB;Y{EoP^FvR@#r?*&U1^V;?~8hyamliqSnYv9^*TWnwSk@4$sFY+e3TRC&kFoP;II zlq35pIt%(t{;gG+Z6utMV|;{?bNZ=L3se!&r!<-OW0wj8MVe*cI%t>Dy?oNFGhI=9 zus3k$tZw+i^w#&65bo9Bp{hZjiea0!>Mz6PYm6=?MYI%uYN-PwDft&cLLx1X+$Y;W zP-J7bcwmgi%Faq0G|ly<5=yX!$tUofqR(Vt=`lgW_RPiO!fGVq!k7T<21-ZG9{vt+ z0L3Sq%miLbjZ#3!o}f_wXDVFYUpI)swo9fMpp~#r9<81%5QAYtB5XiiyOlf)0d*C# zvqaq`D4Zwq5UjwL0Iv>h-QmlrF0jUo&Je?n6n%_YgWgji0E30WjJuKgC@;z=6YapU zDl=Sdd*3d*uRb(+hl0`$`vJt98cT~mrh#8~Xt7L5G9x~3Oqob4I{AejH_R6a!H|lA z42igYtkSXH%`=Uq&IU2Xfob0;m@h%Zj_CH&hm;sfQt+0wKSi>2Z~k6-56>rArDaL% zqyW7x+7ul6jLp@;RNrAyky#zrzN7>kIbm+8hhEB|xW6a|driuk@MBYpCqh^cW{t*j z5<;ukt6#$;!m5SdR~37t3Pr%pk@?iJSy*X0+|99F)l{eYG4dS7bOqAPa=Epn$FF}4 zUCJ3mj5u6_yP%q8H#N9RkoO9;YkWU+EkwKQv3h8RIdEN!5?yz)0X@%2gBYPWNvYv> zfr5S=#IlW4gn||}pR`13X1pbJk1+GT2Ti3Mp6* z1}kb61O>~K>KqBi^yH{#iMm?Bc2M10KDilmlh(Qf-!Lwc(uRM%WCyIOBO9qcc2$rC zJiBY3xR%#K?3weGS=}3Q*0*X!e@J(h-PUeeQdM71Yeyd^ugQ=ER%~X)lwh|pf4y=D z<9*R!Eu?WrQQ7t$9-2e9a)>~WXUTfM`>hPsO*J>R$$TVVz8od=RVhLpd_Mv9O`0x< zN=iaz`pP7f2~WMYyrd{9`EJ(KiV_S-($mYdZ9t}8cH$;L1}5v>`%jFb=!_V)B)Ki^TC%aKCSm5>)lmB`kjk!b*2HzLF(zhtT>a8@Y#MOePZo7%>$p8n=>P21aD| z3riU)h><>UD7S)Y|9#R3y}e_P@B}_!!o$7K!{!}ay_QY{uvwN>EOb_MplLv4#xv_c z@<9-tp|#yXGUVC?FS;Ni8x#?G=$y#?WY+3G&;Yrb3W? z4UzItgupN$=NJ0eH#!ZsKeH?ZVRMG6CQ|!WX!bJ6X!#@%E~~9w2}Nn{IbTx6J_#X1 zf1$8=N@^V~!~}+*hZ$ihJSXj;b4*MV=pnkvdQF7u3C@b`6;{8+D+%G$RdIYwSXVKRvAQ9EfuqnBA5}g8`@=A!$7m~`7JI~1u~fZ zF&XU0#~ZoJ#A+|D!bSlC3jOqLH*BiRoz@GyK0iDI77Svfj_aCrgHPXA(PL>6L_TFkLVVa6K49qmmk4qistls!Bs{`fJZb4a#LUHCBj;+Ii!i0| zN|$E#R074YQeH%eAdc8W5Et>M4oZI#Dew0x=RKzu?RTj~9g;zN#2^{llsocP#PS72 z9U9_nX97s4O#)c+ibdest-9IL4Z;auRa0?N;01KjN(1R_VAJNMxcMUa(j*UfmZ-nF zEDxpRrklvE9ZJUzn@+aLifX;odnh!Ovz=E@l=sE>V?s@8<>C(YGd9IEgKL`-WP?uq z*E7%Z*EE&o1|m>!m4^U+$dc)bvjQTp;kgriBmoe7D8t6#&RH?!B8hXE%ks+Jn=xS> zH~wdLY4}AgBQha!G%!F*`;hlr6unt={0W{IkoKz_8#pE)BK1M}Zb96;Re2pFT|&*E zumWcx&}P2MJxhQFi4sYoi@;CP6%^$LK#m0Xn|rtWk!|kxh0Fat@xo1-olH?} zTe_72@gk>71`665TNTu!x<}W#W>(xDWZT0p&TECQvP)M9cQRJGy!iI zH}k^+_lKDEC1AOU7qSWBo*RR7E(M?y%8EJy680~3vGS}L_~7^hCH4gw)>DUejuihmVaF+pBr8%Xf9{e!#y77T4G;E75Jn?G^%v4eL)pm~9HTD-xreyfI!LOV z0%pMIXM-b1)KZp6(2;>>I2_2{xz#<>mg{1o=;C z+4i)YKn$&Xq?vB?c2hI#qRq8HGd%Zr4SWvgRJEz0a-=~o2jn8EQ-nlzpTr3IX{}@h zYa!{ReT47<{n^CslCB?8#WIa=4wi9|=CT#u*dX5mt1 z-KD7bxRM2hrGp#0b6tQ0G(KZxSxraop9(BFE~x_p%zg`r{utR?V$ z2fWNOVC?KrGE0v?K-*uSW)yLmZMK(E?Z}#{rgr-Qp`R0j6^=BaCsq9BU1 z%iNG#45N*?%p)x_uQ%W$Rzd-NB9R-ymg@hqsE}nJMp#@v7sJ&k#32#Y z5R*r=+5{ED{&@d!peZWoNrjXIT^cer%%M)1JR2vkb1z9pRuFFyuwC{Xn$2F}tMr1h zULEo*YMIBHiAAP($0nIE8#eBrCOvx;$-Z0K*d9x$qXZ9r$`{GYz|ndM+L0uc06pU; z3Z|i>5?>U!+b_S^5WN;_G{P~1kqmAlnoKdI+>+{yvf#fuV&ol`7t?%RxAT5XSdQ3& zke}}oMnuWXeZEi*boo#fGlKO=89=D*@Jy8ckz>?L_s3i>dV6t8a!h~Ph%PMbt}*r< zT2~rRHD<@|%T!j1nD-C&9x;|?(vbeBTG5feS+7-Nn^^i6P0key+FM?$p%M9vLY zuR*s3b4V_eS4r}C?Sxe0ljoRltusu2v!1JLppcI;RV6$Uzqfn#b@7dsD(c*!#sXw8^q8dtff!5%^BPfdjcOIM9C>}Zw3v=XT zXJkTFW;v*SXfvaNe6`d9ga%sd6(4nPH7K8yJp;7KD<-j|$d|~CLH2yHv34iS?3nZt z%lQ!HBM$z*+WYc&s=oK%Oc^6{G98&BocVAvXG-QVq%segokP-OmXMi9$&kpDXfl_1 ziXxIEQ4~=rq`_VLsJ^D}=j->q_jT_-m)Cyneb!#X^Q`r(^}N^cJo~B3XW!Dk0<$b` zy`yZ=<*5hb%drN{^j{03`lR0Mjpj~OKHi&VIB?`PwSCPl{B~kfcf^)M>{G?>UZ4-9 zsTV~__N&}J$cwJielR=H>(tE?gcTe&Eh|2m5P9iyWJQ&vYjZ_It*B&+T2)At%c!yZ zjREJ{s4k7Kn4^q=v=4rq z=+u0xvXk)0-L<0PY@x|<^08jF+{fJaeVHqYn=4U|rUFf#_tg31DdN;L3Y34m7fQfSCg!?u9Imv6Z zO=m{K@}%STHk^7As%G4H4}T;54p-(Lb~{<@z|cjuAsFNLPsP~_>Nm1vzE9rV8majsJpJ$bqg@%}O|K3)1aG*mUjd*{%?bTRMwdw0Om zTPO%G6zX0g7d|uHt8;wrWz5WU)!~`l)oisdc!!1*PckbE`Cpors@bl1d~xo0oBK#l z==k6Qv40A8=Dx#e?u_Z&p(c2L4S&P@@fYr+DeYEwKfRkCbURhau6UNohqdO&{j)oU zhYBmBj~3sO|8+`#QQ=IyCs=@a8KdXebN5rh3BJ(lE+Nt*?H3d;2yQb{IOBJ-xg_<2 z{k^?(V@an@%`l#QJgX)>@}7Dm0qZf^44Vr{-`9_RWI}_jf9upD9~#`(aqk z-w-pI_Oboc+)>PX!OF@0sG08ypBF#<94Se%x%zG9s{h?3*}R3G@uj94?G%G0azB3_ z%xL=b_*xA`Z+MF0pmFojY#(vu46|I+FOGoY@9W;PAUa-0nMYDH7V*_{C3IKGh2Aor z_kH-@?|tXH^Y*;2Q)WFK5&1?XxgB5G+wA9F`G{~%bmE5SKhD{48e}CdQT5tSqN1yR z@{|Pc@VxS7aJDNY$+B6lBY)A1=*pWb>1gNsFOvjREIC2G%E`WV`PRe69rw> zUtT#Tx68F;?&;-upYMsji+fGKrKA?@v8^Ti6vxddog)KWJzr=o%d5*XQ*8GVD);-6^<( z`FQvk;U-a}q2RdB59OYP;DfBmN{U}aUF76?-=cbRKN(({%Ir(1&+|HRjGbSnE!?7_ zB$MM&=G#$~&U5#ACC=oRSh1G(b!RPEFd^(*cl$&Mb<4aer_Q{rZqQ_)o9&P>H_d+U zZGSvoWj1>MyT&h*+@Jbf0$ye#Qw5H@aNC9_3CM=~-l;n#EA>sg@5^jo{^?1!us0mW z^)l3+Y`v(v4(GoJc}xm-%&^{VHP`5_;U1AU;p9{s=4eCz4h{i{Ub_p zaxnNmHVaB-RkL8@@$PoW?JBcp&sPMHJRv_En#-G&js~v7b{Qu zS;Sb&ho4>~I9Hrjyxnsn_q6=e<{NiSZlNBO7Mc!Dwtg`Eaf{v+oE18%S9sc-O|?eRvvkkXw~TM94WJ7(3{6n2kQ+ zO;N`iRuf_>+Ye62mJ4#Ecj7cXg5K9i94LJi^`4e3)Z0&LmgPpRJ^wA;C)N_~COcJ< znJ}N!oSs}p^`@V>8Md8MZ|}1$6lVf6x#pM5?`$0y^bEP|V5~fj>GB)py%*J;O2K~2 zw81j|p-#^EIRD9}3R_J+-RW9<&gU1JXuRp|U4v?Fe7;0gDo>yMy}@TEhwN9!a)WA4 zH<+e=<=~`IBNvfy-194gqGytWmx1Hr2kG`QxjDKXqD05ZuoFybf@ikAv2eGtFAB~G z<4v2t zteJDlu^kIlyIrgfh`o1q{90T2#-D5{gGXWmGFR>*|6?P84c}FRSqze~0YO7~@<=Ja z61l7Ek1Od}drmERFg0t^H8?3(zN&{=6_`JHoKxr0tkHTb;P6MmgsrBmPIp60ulk5( z$~e6%6x{B1sJD{;ONH+1IIYI`8}hx2x#!+YckfZZ>r57N1wT-^?^19(mWwJ?MoiB< zT=&VB0XshZNTC!jmoAmrpN>yb9x3i1lhWCMt3N8_KUKaAdKFXHC}p}jB^rvEnuknm zru~Jd^~Ipd=gv8aU=U#B+55$FtIcOaIBVI{g*GXzSNWw%sNh^ya_)z_cRMpt8+8?n z#Z0A)Tsq^^DmYL5+Hr@-deSf}zxT1vnqaT);ZB6XHB=6oshaLlwLfNU>SJW>PLR~I zadr0cv4_D`oUFa|y*+FRFbv5Mkq)lrZtG#^?CuDI*i&_OaIp8bcek}Czz)HX2s{k# z216pTFgO7QC&G~6i^Fg~82khb?hiW*gBzdl1bP0=0W>KXEWHUts1zWvaEP3J`#k(W zUXn-z5(kq+W05c<4tQ)tB5*QL7ElybdxEXEvnSER8-^kImjl^=U>$3sw= z-45z+By#?AJY|BdJ*Zwh@E8eKvG&|=@9gMAgxG}Whu%n{fEg%U-PPKW0K?;!nb-vT z|ABHkxF*rs)!A0r-O<$^Do)4Rk3=sFi3WNKZbYUBV}M1(7M2hAxs7s$Kud9Iy_)YS_T0_Nn>GXJn-%bE-c6&dJn}% z5i8M^n!345(OAsE*AsJ#e%PI zqw!EW3=9kIGN7`cJLy6}@o=O{fbLNFq(*}(5YPZBmJTWt3(}A(Srfbu_L@Ta-{+(DDk{UL;u z14bGN5-hhPBnN-Wfs@ zKrSGeSaFf$0g{P77fDur%LF73D=&yH(r=IlBpZJ&h;tl52DBld6_SAsE<7lMBo|;5 z#;v&i$i$yJkOe>=hK_WHo>yF?wqAY@#rb|pZq}kEkB)rVShU(^@m|0g=q-s!r!APcC(Wl{AyT$jjG&MhoDhCnR}0U zK_*~6B8zSAm)ki>&KL6UB4%B!>@J53mXC7W%JnqTHq^~K&T#CSG_UN0aOY1lFW)gtu<|))OO5t-h#t8K+WQJS zylk(V7u)Qg95Sq~>HnM|-lowvBym@Fp!dK~mgAJBrSB0vH|L`}eAuL^;u!g5tEj*2 zdMhEdH_m zi(e_kG(}}DMmve*&nyLA`C47`Ym17G@%;_zY}1$=w`T4d`+!*mVDcH$QsICACHYo6 z?}geW7o`MCJ6@~#eA&QQgK%`cGjb2YZwYO^M(a8Xd5|((oY7kAa@-x^x`W5%cNFFJ7D{^$^vmyU@6|tI@jc{`Q~6KPet0GF2!ALWo@N7PHw(d~ajWD5 zjg>Y*=-({g!jc>ImhP>3GM!kMrINzAq;@LScCxY#?T!Em6)n5uh*E)AdmHPp1{AI| zplz4gR;8V;I*c7(c#0W{FlTvQv-v{}3@Exn2+Z1e-DUr{V+KcJBb)t}41q44Bq zt)%LyDKyQL|1HlPZPq#FQ-QzIzdVuAFK^N2a(Z4?^GxV|aEf4}Xxftko3G<)Ohf#w zS9UOLK-6a8G7@N!l|2cXsnx?6ROZw7X>3^vm@V&l7xd!nq4rc_Fq>^VT=gJvDk&T| zh>Mh=$?S7rHb==dbti>HwnX`os;Uy+$WQcSs z%T6otP1}y)9Q~zm(fC6Lx8kW5&1%9)9c0}&- zfzGV)UxO{vsjjg%>OQl2@vu71o}o3uz-3xDay}iHi@*8b|_XrV9*9pxQ+#@IN(exKLj9+TIR5!i889{z(v6XMO!+Cl~l6W%_-e=SLVyy#gT8R|cxaZ+Tzr%wUQX{-pTw;2`e?74~Ok?LSo*dd)-;Ybg8Vk}}O?tJU76?l?a#?nX zoBPP0kW;7nMF`w5C|(fOLmUzPc)VIJI-|KV*5ada4*xxz+vrcTG7-9Db&1e{<{EzC zF~4I!xXI-?ogYSNt1}8wc-8iecljrXg%1Z{+;sVcHJP%gDi76PfYYP)`y1BBU;c5k zn97thla^qsBP4j;H23YdXK2eNR$HOGG%BHYtn>Ln%+5`=5Uc- zkt%xTZ|$xt(;640Z$TIK*C2Fz)M<|&tEk>H_jR^IC~A<$*YrT{13crjeF8qnu0&SE z_2KCD*_ZM`aTld)BPE0Oq~QDQ7EAfnxZef8UQ90#D`OY_p^_w5`g-S5#_;!Vvp;@O zN9{f%xIyczoK^nQG#=+51&zwtL!{V1iTyhvrkAL=#Hiu>C=JPsUFX#=B|XhL}FZhnpw` zhRzoxy!1YJgv?#m^Q)^y&#yVIV+kQc4RIF@&(Qe|Ek4FYoDVxu9O@r1jWrWX3n`?U zD&5vm&T?#+v9Pagc3^4e@TYGSR;;*%4Vc_4I+9*Jc%aJ=20*iHu|X5iR0Kh-P&O4Q zL3;F6C8-oDGgx?gclY)-6b@;Kz+k9uX?I3v+90Bp%(Y^b@%lgUmRy$3TZkx@%=Pqu zVR>^<2#r{+R^;Qg+$oS?G*bwb+FrLfaAh`Ucg4k*X9q=v-<{_f;7~i3T%m1l#21T6 z2s!)iqi5;m&$6yv4i2v@vQi@6B#w8p+e~Mj8t70zY%bdPKEz?~-3bFcCpAvzMn-|e zwIL}##(t42hvt|StGci9^eVsr!>)z}C;8=$sG3Yn zP-{f&vQ6O}A62G(ci^Fu#kr*8Y81-TpUc}$(oPS)Jl1lHI{)G$Suuy3lSD%)cg}DD zzLw8+y-&)j%4n~e zjh(J{p>w2(?z}!*&;9yphV5Tn)l|d?aZleLt$#%ClI+UicVLl0H-@)huSwI+dV=*{m#4U^|LK>~VA2~)&7if0h5>d*7 zXzyTYKw+d+Y~H1D?X!)G_UZt|7QP6Mqzwq#EbIX@sg)h@H$j+# z%LL(os4f!}gd{wWxarEssm&W=ztv_3R~oFeBcLfzc!VLA3-8(EeGhf-$(F@@4z&%4 z*(}~!t7jpQ-hg1J{LcQPZcE>Em1yJD@VTXa!!|Y=CE+{wgl%jE$>GQa{J9qk@z`vU zGmhQ|e@N(sYCJ4@rO6hUGIGQ>sGYmXUXc;aUzK9|D5oibp+yZRFUO2}CcJ$wqH?Rx zGl%C9H3B1Lf`*;y$vyonU!I6lwi(?Seiy{zR(zW9PS`OAAzBaQ&-gY;_LJqb`NLkCu$i6laz==L!wz z*IPJCHXvxTNC_+st`a9)IgoFJG$c+K69ftch(j3w`9@(d)M&zet025pas*kdHI2}N zoj|TF2z7g5xAcpa$2qSo7RL=}*(?Y_fz^SP#9;OC@c^~8p9obznCuu-s=a>w4({2v zvla2Fy0ISxT6eF_PXoEY7p9aMbk;xE3yi=bD zBN*p=X}y4YJ0TM%dL?pZZcxG(e}-|A9v3aZKE5FCAA}3enmREG043pIYUF zFpQg)qtC!*I{i(^(Q02J-|gKjgnensQmg`<@5FPrr|B1#WnVQk@XS}ZK2ex)_RUet z4YpvwBw}-V0R@%}R@RrizU&260ftF@DEy<)XF*Rs^#VzUnc-rJG%jUdu>qQ*>)f zq}%K8m{Nk}{wq6H9hvq@O~WXzMAUn}T;E-%3*}m}_fFX9JSr4S9q7>;OkLpdynFPy zoo-Syk*{MRz5G!yp1opzGy+Gh6a9Q*YM#|u9Bx?2YjOFE4@=U}j`1BVDUN5khV7QV zQU40J*tLPgZ5Ga;!J5yi8Z^{$Z&acg9A~q<`sCxKt`mkPLsj2BTvQD6#j7HaO^DNN zvG?C-9cJ+gZM}P>_>f%gDXBvisVB}=Mn(%O+BQL0piSK~81>aw_MUgwR+ znG5@pL#bnRKW5TDJdOV~3J-YDe{nisg}&7Tzi|WmMzUpt%ooG4K6*kBEW%NqwH$<&$SxzUuuV z4q9~jRC&{6DZSBA{#eOatX|sCfKs>|E#{vkadT%{l{)%?^>*gI`T7=$oj<*+wqvfl z>?$|gb?LT^YV>(mf_yb)pY}{6zOSD3q3g`$zRX)_w75Xf^NO%zlS;m2HM5>~G8EAh zS#BG&>1NRz60EbXY*U>WWkw1l*d96&nxOTHTtK_w! zlmsr1d($cN8cA+(+tj)w>G$=!#(zTvQlHv!QNw4{`C9YP95|@)W6L8~jOKcVz`FZ? z*UfbdG|y82B|FZ(s3dSCq3XIys>=9Me;Z>co|3jCJ|X#{89fs+gkM5_Ax?lG{geAl z)@G35^*?I zl=&ly58GO|Sy=Vwa~nhk?MdvTC1#m6+~{~!_O{PgT1E2ntGv^n7M)B}tU@1aeKqqt z8me$HKh<|SexLt{j_j@uKDr!~tmK~CCmY_o2QDhM8-D!RI={eM!qoZ0GJS&@+$@O0 zuU-~Yi+;ci?ba?CE7Q`^J=YUS03aoLJL;6xIOB8(75$wP>ikqmB1hQGs1Mk_(2r57 z9`TlJeL=lZ7#&4o^G-ary*y8E`(03O11dL*?AFe~ z)xcn+iliB=HS!GHKavtVTYdvV`G+oPKka-)Yvtzgi8!5{2Vy-SPX9F{Yu z=WUv$0yqlCYaTFe$-B;4PSwKod>SX_w8f+%QuAT1~O@74veNvqJ85-Ki$`}I5h0}x1IR;#WxovNRaj2H2MsTU}rjy0BL-PRP zL5|i9=-DiiM6Ll#Iv2n&C%`~4Q?-j9=Hxc)XRb!2ha%OmM}6q7kdM3L@)_(dg5rbQan?zXLkS z74-hSz4bD+cx+nBiOFmIw7e-{(CL~W!GIrQatR0Qk@uHy+aB5B zd{gp%h8z&gWsw+XJApXe`nl8Y&b#AyQ(0~*HnrUsTTLcP$qQtS8d6;%j!oLykKOB$ z-3m^k9LDF{d1XiW82gBOYIh}lH5mHlYo2&ogVCPuSs{VP^;Mf&{SHy}OGVR+^ARvT zQ6r7U53qrc)S}U+lM42DUUr>(tc75t{JD?y;#j28Btu|Rr_q-&mZ{NE-|;{zj}y%M z2e!Aw3GCnv^1W=i^t$g`^^#YZY}akBVxF1T$1nEzHXpT#XD5(Fz7WeBcagH_=i2)+ z0o^>7`#tQ@eXEqpVC|W2ihW&+zbN>`92Pfd!Ic>AUz`76-%}C;c8!tJV9-aR!1wl` zvk%U$M0;=2i2}`pwntv39 zK^P%$Sd*4FC}|vdnRlIpAVCmDFBEB|Y=;K(Y4%yVQyb8_Y3u?hUny>Cv9jP$6@$u2 z-Aus+K?;Q~2b36Y-oy5pt6^P_87#PxHK_M_P{c$~_#NRPs+l56N82CoaPC-^F-o5R z)0|PKM8nhf8=aGgpPX=nJ@iGaybg^1iP>CNx9??t`5|k}J9qlgHxn^jTK`YWgTMPdJ$JyRyu&gNR}w0AF8Iw;Y;Fv34CkXPiV+dH?O zSFjzuNf8Ho#VdK0*S{Z4iDYO$9J{i z&5d5}J(b+Rcp~hLyB$tgTn(OZQ+U3c?$harw`}u6Pm{}3Fey&>GxTWj8{E7-TDUY% zan_2fFY3{Y+uVp0rr~_0hhW_~R{eKi-px!q7#^guM($!bptE(U*gGcUNF=vH{U;T+ zxOm35*d?={p9$MajABIN+&yYuA4$(=q+sTWPpc9a|*!a{L9*H+lAfl zi4MtI^3tY?xufegbw;qp|r_0yX7l+j;v4QFSV60b}Zz7Crt zBj2}kgY&*%e|nRxhh9DR)X{Hs1FiSH5}YEao8YPBqmGoj_4BMs8*O}wlh*6Z&xwbU z+wA8B@gA)eZ&bo{lbk=hcXyVQ{>o+`_g&IA-d-eJdZ5GdiF+wV6FyKc6P@C6`@(qs z$q@5wzmKEOdc*?X$)g@PlvU#q1@ey=V|DK}mAvnfO%kGrsED22ca3h6uU9xLX3yY7 z!^^soZ+4_)Oq@J*VT*j@%jg%6o7*{~)Nf1XJwBEs!-QZpdYt4{5Eq!px>dzd;~<9q zT1%V%KJ3G2d}eBOy{8pLds#@%wIahRCVR38^25*fj$#f3UD)z)cz4v-#jQ7f93dTq z{=G5%d*>a$Sr~x?oBOMzUJnlz&>04Q(w%_?_?X>!nXqdj_Se~>iL1Pn%vb$dZe`n2 zF(Lysn|UHq%K3j_qLn0q(**tZH6kQDahieQ%BGqJ6%M6q3*4qUvVWnEO^#c~F6c`0 zIo^8-trHY8hKEXhCdfW)HxW8q#$a1oRN*OaO^I#vXMg(@VH**zkzt}WNk+xG@Z{Us zY4;i5(_~hS2+{$CHSBE~m4FiqE7`-wv~L6Ksm!DW(NlJJ-ICKge>I%A+iL2f?TE0kUXg;3;N1#M{Pui(X-YjOZ3c9Dj@GNBcQy8Mcm421y;PTD zTZYWtFsfXga$(umr`UBD;e>>|Brbc#mO`T;-Ilf>_KTdo-ost@io7#f`R?qg&ysCC z=Y5IGdEw_wj`ZQ9FZ>WsH|UX@MJgD?>d7V6Q0tZ;!07X0_v(yOV~`4Zxkswi-u@bl zyLmG1Dy0ymLzjTc+eF3ph9}$T5^5JE4!zF(Jkwgu{pP@@Qencmr-@w&%r+5G*LS?< zx*f!|i>7p+26kKsMy}nt+nP0`tIR5(w%^9rP4Q`{Z%#^a@}wV1$w92}rdH`A{rU%) zLT+d6jqza?1v`^$?xj053rHt%vds^KK2R9_plR1~)rR*#)Eqg?c#Lr%IIiqU zQLgM~{Ex)0H#uGAMSZ1TBP3##$#`SE%=8<`x1xndc{*yJw`NLJtsutfnM*peq1AABJ ziBQ(mXjb0GpB5?4@7u~g5)lfg6_>&r+K#8;=Sk*44KtI zJLjM`%^Xxti9wiO7ap4Y_(9G5uB2&$=G`pXTO+;b<<(FOf;wJ3Oer}oVjr|VyQQJy zO%Uzdm20!Xd$w&EDc^Q+gQ7Q$_<(Dul|4ttpt1;T@=VHya>#%^o|+R(d9+_g|1=a@(opS|KOB&nWzSP`*pV`^19O+zulNo$lF}=EZM! zygF$j-8=l{+!69PgCG;@K*m_vdsYhrE+Vc5^t+H@`se`XhjfH{EJ#YOsN0S^62%#G zpLU5K{0_fv|4jU*AL8;Z#an4k*N;~4_)UsY?|b$lsnTCShh{o@t8IsbUW-1Y?9i-UjQ}ca0I!w~WCWHfc*F z){c?WnEfJIe0yL)+wzW#&_Tw>8b|0kciU!ftoI>u#S1UewpUkZQ4Q7lj|7;C;K+3^w-+PNE&K+H^LYO z33P|Aq8F&gB$wL9QWarr;AF-?ze!)-viQ_`q?dJ#)Pw_5!1gT+gl9o2}W$%x?M! z+&JlHlvAHC^lUV8NuiM-Nhx_sy*uFOSVqZ(SKs0}oaZmP^%VQx)Rw)GbCbtak8nif zsD1xu|)2%s(o)o~d)8^Y)9DLx+mTE&g$a2)k zz$ne1>(}?s)1PF|{34SeoFZ)0E}O-PYYzCJ(KsV$laibzH#cm9^8peaff9oBvB^AA zD)hDpHyhU+D+imccIGf7tOD8;yqLzi!IyWCh|OX{G&sG!vOfYP=}rZdWS7`IrE4Gc z9?jmk5m^IP)mf|AwGmdMVsP^(S~b1GgV*ZE4)Mk4$Ca8YZBT|3K|;?6 z&R#ST-XalabE>Wkix%Z%evvm%Z68k1y4KCBqdP&?*w(0d^|0o*tEm?csK%#Eo-W<@ zC9E!9PC*0N8Zd>6aLb|+8Rxqu+|j_c_hvJBl|$N7lL@PbeBokI2kFc5_*_39Vol27 zEgIz-K)h^67};cw+@$J#YhxcY{bm$f^6=aTgM`ENp3}*l$7vor{o>|mdu7WWAE0r) zlx3Tuyqo-?tdYouKP;aHS4BkK8vrjOvdj{g>NJn zn?{?fr&uI?7EsTo0#3T|zNIkSDC6dX0BlDZ)nQY`YODzsa@d3Rf&&5n&M#s z`jHoR#!1?{-whbVZM$_V$>`dJn~~Xwn7MLScD|!ohj#hID+V`+!(WV6@U~p*t9+Ri zS#vgr3`x5YJDUY|XyC4KB|BI{ygQiBO#Y-h4GVA|oEd=akNZ)(Eq{QG!i#8_C~INt z+a4Zje0z%ctvu;Di}cuW`_Km3)&iCfhGF~js!Ro*&ZMGB?qVG&TMVx~9LpK=Y7J7X zzjmFz`P-e+k~b~9F??q1f|;sysK$ngoym`;Z#o=0lk8j<;}?>?r%$rkjLMLENan-& z`AqP!lC9^eQ~U8t{KX z??$ptJm*$>p&Te2e-YnULHshj&|P}<*Rv?;+P&iM4q2GnK2hNQkk}-FdgpKUg*e;S z988ay$@($=lz|0fA06LBUGy9umX&H?>UUQqVOuA%Szwm&NeOejxh+PM7$3vV84{z;{a}pKjOmgKxio2-pCY z0n?OCDjw7tU?ypx=}nFeRDbEDs*O2)^({h&B% zb?DqiBEDIKi3G+BD@9xB-t1e=Srtv1(!GNC?&4F4Eza8lrOA!~gWexuv z_*(7ULqGry zoKtpCr^^+2`}dr(y^|fC!y8X7^E5Ftvn^aA4sZ1ZE{5?)*%}e9k}0V*P*wZ25+%s09vrJQGCnWyxw9}AyeDiPGGr1vMcjSB7V=Dv|u zA7*uFwDF0svC9Hmqmr<6OR5#)wVWrs8gc$MGCM5!%DFGRE}d9pu8em$-QBdWLf9$b zWTBDsi(D_(23{=Hd$ITF*;U)`XXHCR!^96^%Hj$4w$+~OGU{KtUQpHkjjH;%)US=$ z+AK6e0mG72HE)22c5SBSfmMT06x>fQYj@|b+RmuQrhE@9!^#r{Qa>9eHr^ zTwxlry&afxM_@bxX0w}1Lb)?vjg`Z#OEd>t3zj-xrhFJ`F}l{2yd!WcnW+p<|3v@C zBzZlN$3%8iZvnP_2Q91GF1c?Pa-XtJT40`_SbCe73y)D$$^Jy>ZrQ@>)lP1gaUij5 ztihx7OWD?gi@(S+G>ntiR}e7e`q#4Jzw9UX=@=NSvY%XOHwkt?fOX3%yGgn=c9Yh7RQB>fsJ-*I;mE7!DAm0xT9`0Gq?rfl(3+t_uTO{&0Pm44~Q&m=l7H z1{mA~1~-KPa~!yhx3#T{JrN?44y-2r`MpdlIHm&kaksPgCfIs-+r#i6b88qL@M#N! z+W`^)T`;&Ku+akXoMG@|Ft`g0?h0&5>EM7uz=J2K5*QrNPckos`@rD7D~wDJ)BO)E zOgG+TS#4noP70IS?|*7x3Mz_ZVY*H@R_xRKd&^QR1o&3jM6JXa|0By%G-|D7>Az+B z-%|YVElPotivPxP8UNg=D!|F;&U*nhSt1tb0cRf|%R%KT$dstl}6Nn;_9|r6PNnwVN79)+`MlfJ}LJBj6bQ04|f>dca7#+W?e6=m2PKQm7~JRPg)hFVG04K|fb%20nc!UJD z^Q2V3wFKff9m}u=f(+md9SQ0zPsl+k9}w*~6)Ru|67ib~fE|Fx3Q~rkDAKG0hToYPsE%G1sPW&6sxXk>I(`udJT!u>iiZGeL~Ch5AZ4JDa8*1saHOz~7Nj(!W>&=mwn)J5#M&?n zH14m82l4}cDprSqw2)VrRq>F(3}r3NNE8+tpI5~L`9a{N9dmyEOJDfG~kTM8pcwLniILd6TS#QRww; zgvMdkwFmH#1NGh2Y4Lby&2?268i9ZuNvsaTVb-+=3Xg{dk~Q&wrQ6yt8QgmLlR-mz zYjs)~#JcuH<8ctkSRD_CS=W}JHP+QV8nnkc-lVaRc3PdEG!DWMYr*@e>!L?~I!0Ku(%@_m*QkJXA07p?E-MuDE zdR<#$KtErX7KvU*GX^QWZk)s*W!C2hhM~1`g+Za#$p!|6gD}Ku`hcgQb^M}aAhfhP z9vTTDo;6`;NLj53!>p$Tbl-L5Vn~2xby`rR>*Gm7_-}PQAVTYC!J;6vx+WfOU7yBa zWxyKMns~sG(Yi8l$aV4uPO+|&T?`JlZv4aGWY+a_j5K1MtbtK?-Pn!+BDqe6fJdlx z^&*2@8xQ#VT363_XnwaQKRkY&UIjjfAbbz~ z{ne{j1O}QptO>)e8(**p>2+<1MFOR_HZ2&&*Ybu1I&Up~012#5i(232z=za2ez7Rb z`ZBPfG5f<+KkA`q>;i6o>1 QP!A48CoHU{r%w030Dcm;D*ylh diff --git a/systemtests/SDplotting/save.py b/systemtests/SDplotting/save.py index 834bc70d0..c432d69be 100644 --- a/systemtests/SDplotting/save.py +++ b/systemtests/SDplotting/save.py @@ -6,7 +6,7 @@ import yaml -def write_info(): +def write_info(experiment=None, ros2_ws_path=None): # Dictionary to store extracted information info = {} @@ -15,6 +15,11 @@ def write_info(): # File paths crazyflies_config_path = "../crazyflie/config/crazyflies.yaml" + print("cwd : ", os.path.abspath(os.getcwd())) + if ros2_ws_path != None: + crazyflies_config_path = str(ros2_ws_path) + "/src/crazyswarm2/crazyflie/config/crazyflies.yaml" + info_file_prepath = str(ros2_ws_path) + "/src/crazyswarm2/systemtests" + # Read information from crazyflies.yaml try: @@ -33,12 +38,19 @@ def write_info(): print(f"(save.py) File not found: {crazyflies_config_path}") exit(1) - experiment_name = info["experiment"] - info_file_path = f"systemtests/SDplotting/info/info{experiment_name}.yaml" + print("info", info) + if experiment != None: + info["experiment"] = experiment + info["trajectory"] = str(experiment) + ".csv" + + experiment_name = info["experiment"] + info_file_path = info_file_prepath + f"/SDplotting/info/info_{experiment_name}.yaml" + # info_file_path = str(ros2_ws_path) + f"systemtests/SDplotting/info/info{experiment_name}.yaml" + # file guard if os.path.exists(info_file_path): - print(f"File already exists: {info_file_path}") + print(f"File already exists: {info_file_path} It will be replaced") # ans = input("Overwrite? [y/n]: ") # if ans == "n": # print("Exiting...") @@ -59,4 +71,4 @@ def write_info(): print("========================================") if __name__ == "__main__": - write_info() \ No newline at end of file + write_info("multi_trajectory", "/home/jthevenoz/ros2_ws") \ No newline at end of file diff --git a/systemtests/multi_trajectory_traj0_ideal.csv b/systemtests/multi_trajectory_ideal_traj0.csv similarity index 100% rename from systemtests/multi_trajectory_traj0_ideal.csv rename to systemtests/multi_trajectory_ideal_traj0.csv diff --git a/systemtests/test_flights.py b/systemtests/test_flights.py index 65adf75ee..49e0e6c2c 100644 --- a/systemtests/test_flights.py +++ b/systemtests/test_flights.py @@ -89,7 +89,7 @@ def setUp(self): self.launch_crazyswarm = Popen(command, shell=True, stderr=PIPE, stdout=PIPE, text=True, start_new_session=True, executable="/bin/bash", env=current_env) atexit.register(clean_process, self.launch_crazyswarm) #atexit helps us to make sure processes are cleaned even if script exits unexpectedly - time.sleep(3) + time.sleep(5) # runs once per test_ function def tearDown(self) -> None: @@ -120,8 +120,10 @@ def tearDown(self) -> None: SDlogfile_path = str(self.ros2_ws / f"results/{self.idFolderName()}/SDlogfile") pdf_path = str(self.ros2_ws / f"results/{self.idFolderName()}/SDreport.pdf") print(f"SD logfile path {SDlogfile_path} and pdf path {pdf_path} and self id folder name {self.idFolderName()}") - save.write_info() - plot.plot_SD_data(logfile = SDlogfile_path, output = str(self.ros2_ws / "results/test_figure8/SDreport.pdf")) + test_name = self.test_file[:self.test_file.rfind("_ideal_traj")] #strip the end of the test_file string to just keep the name + save.write_info(experiment=test_name, ros2_ws_path=str(self.ros2_ws)) + plot.plot_SD_data(output = str(self.ros2_ws / f"results/{self.idFolderName()}/SDreport.pdf"), + logfile = SDlogfile_path, experiment = test_name, ros2_ws = self.ros2_ws) return super().tearDown() @@ -195,7 +197,7 @@ def test_figure8(self): # assert test_passed, "figure8 test failed : deviation larger than epsilon" # def test_multi_trajectory(self): - # self.test_file = "multi_trajectory_traj0_ideal.csv" + # self.test_file = "multi_trajectory_ideal_traj0.csv" # self.record_start_and_clean("multi_trajectory", 80) # test_passed = self.translate_plot_and_check("multi_trajectory") # assert test_passed, "multitrajectory test failed : deviation larger than epsilon" From 5cb175870fb6b47284bb68d784f0e48c80ad98ea Mon Sep 17 00:00:00 2001 From: JulienThevenozIMRC Date: Wed, 3 Apr 2024 17:18:35 +0200 Subject: [PATCH 117/162] changed cf.yaml, added logging to infiflight and m_t ; still experimental because CF never flies --- crazyflie/config/crazyflies.yaml | 12 ++++++------ .../crazyflie_examples/infinite_flight.py | 3 +++ .../crazyflie_examples/multi_trajectory.py | 7 +++++++ systemtests/test_flights.py | 2 +- 4 files changed, 17 insertions(+), 7 deletions(-) diff --git a/crazyflie/config/crazyflies.yaml b/crazyflie/config/crazyflies.yaml index 889e66612..2d91ffb89 100644 --- a/crazyflie/config/crazyflies.yaml +++ b/crazyflie/config/crazyflies.yaml @@ -94,12 +94,12 @@ all: stabilizer: estimator: 2 # 1: complementary, 2: kalman controller: 2 # 1: PID, 2: mellinger - ctrlLeeInfo: - experiment: figure8 - trajectory: figure8.csv #translation_y.csv # yaw0.csv # # # - timescale: 3.0 # 0.75 # #0.34 - motors: standard motors (CF) - propellers: standard propellers (CF) + # ctrlLeeInfo: + # experiment: figure8 + # trajectory: figure8.csv #translation_y.csv # yaw0.csv # # # + # timescale: 3.0 # 0.75 # #0.34 + # motors: standard motors (CF) + # propellers: standard propellers (CF) # ring: # effect: 16 # 6: double spinner, 7: solid color, 16: packetRate diff --git a/crazyflie_examples/crazyflie_examples/infinite_flight.py b/crazyflie_examples/crazyflie_examples/infinite_flight.py index 6aa94c6fb..29239f053 100644 --- a/crazyflie_examples/crazyflie_examples/infinite_flight.py +++ b/crazyflie_examples/crazyflie_examples/infinite_flight.py @@ -22,6 +22,9 @@ def main(): # pm_state : 0 = on battery 1 = charging 2 = charged 3 = low power 4 = shutdown flight_counter = 1 + + #enable logging + allcfs.setParam("usd.logging", 1) while True: print('takeoff') diff --git a/crazyflie_examples/crazyflie_examples/multi_trajectory.py b/crazyflie_examples/crazyflie_examples/multi_trajectory.py index 57b5caa7d..ba41ad3f9 100644 --- a/crazyflie_examples/crazyflie_examples/multi_trajectory.py +++ b/crazyflie_examples/crazyflie_examples/multi_trajectory.py @@ -13,6 +13,9 @@ def main(): allcfs = swarm.allcfs trajs = [] n = 2 # number of distinct trajectories + + #enable logging + allcfs.setParam("usd.logging", 1) for i in range(n): traj = Trajectory() @@ -37,6 +40,10 @@ def main(): allcfs.land(targetHeight=0.06, duration=2.0) timeHelper.sleep(3.0) + + + #disable logging + allcfs.setParam("usd.logging", 0) if __name__ == '__main__': diff --git a/systemtests/test_flights.py b/systemtests/test_flights.py index 49e0e6c2c..3d972deee 100644 --- a/systemtests/test_flights.py +++ b/systemtests/test_flights.py @@ -95,7 +95,7 @@ def setUp(self): def tearDown(self) -> None: clean_process(self.launch_crazyswarm) #kill crazyswarm_server and all of its child processes # print_PIPE(self.launch_crazyswarm, "launch_crazyswarm") #this will always print all of the STDOUT and STDERR since we killed it beforehand. Not smart ? - + time.sleep(3) #give some time for crazyflie_server to shut down completely before starting the USD download # copy .ros/log files to results folder if Path(Path.home() / ".ros/log").exists(): shutil.copytree(Path.home() / ".ros/log", Path(__file__).parents[3] / f"results/{self.idFolderName()}/roslogs") From 00684bb995c292be25712c6cefecd4708bf459e9 Mon Sep 17 00:00:00 2001 From: JulienThevenozIMRC Date: Wed, 10 Apr 2024 12:06:25 +0200 Subject: [PATCH 118/162] changed takeoff/landing detection in test_flights.py ; other small cleanups --- systemtests/SDplotting/save.py | 2 -- systemtests/plotter_class.py | 4 ++-- systemtests/test_flights.py | 29 +++++++++++++++++------------ 3 files changed, 19 insertions(+), 16 deletions(-) diff --git a/systemtests/SDplotting/save.py b/systemtests/SDplotting/save.py index c432d69be..e20a32b44 100644 --- a/systemtests/SDplotting/save.py +++ b/systemtests/SDplotting/save.py @@ -15,7 +15,6 @@ def write_info(experiment=None, ros2_ws_path=None): # File paths crazyflies_config_path = "../crazyflie/config/crazyflies.yaml" - print("cwd : ", os.path.abspath(os.getcwd())) if ros2_ws_path != None: crazyflies_config_path = str(ros2_ws_path) + "/src/crazyswarm2/crazyflie/config/crazyflies.yaml" info_file_prepath = str(ros2_ws_path) + "/src/crazyswarm2/systemtests" @@ -39,7 +38,6 @@ def write_info(experiment=None, ros2_ws_path=None): exit(1) - print("info", info) if experiment != None: info["experiment"] = experiment info["trajectory"] = str(experiment) + ".csv" diff --git a/systemtests/plotter_class.py b/systemtests/plotter_class.py index 5833de3b9..42a8307df 100644 --- a/systemtests/plotter_class.py +++ b/systemtests/plotter_class.py @@ -146,11 +146,11 @@ def adjust_arrays(self): landing_index = None i=0 for z_coord in self.bag_z: - if not(airborne) and z_coord > ground_level + ground_level*(0.1): #when altitude of the drone is 10% higher than the ground level, it started takeoff + if not(airborne) and z_coord > ground_level + 0.05: #when altitude of the drone is 5cm above ground level, it started takeoff takeoff_index = i airborne = True print(f"takeoff time is {self.bag_times[takeoff_index]}s") - if airborne and z_coord <= ground_level + ground_level*(0.1): #find when it lands again + if airborne and z_coord < ground_level + 0.05: #find when it lands again landing_index = i print(f"landing time is {self.bag_times[landing_index]}s") break diff --git a/systemtests/test_flights.py b/systemtests/test_flights.py index 3d972deee..338b0e480 100644 --- a/systemtests/test_flights.py +++ b/systemtests/test_flights.py @@ -115,15 +115,20 @@ def tearDown(self) -> None: clean_process(downloadSD) print("Downloading SD card data was killed for taking too long") return super().tearDown() - - ####try to plot the SD log + + + ####try to plot the SD log SDlogfile_path = str(self.ros2_ws / f"results/{self.idFolderName()}/SDlogfile") - pdf_path = str(self.ros2_ws / f"results/{self.idFolderName()}/SDreport.pdf") - print(f"SD logfile path {SDlogfile_path} and pdf path {pdf_path} and self id folder name {self.idFolderName()}") + # pdf_path = str(self.ros2_ws / f"results/{self.idFolderName()}/SDreport.pdf") test_name = self.test_file[:self.test_file.rfind("_ideal_traj")] #strip the end of the test_file string to just keep the name save.write_info(experiment=test_name, ros2_ws_path=str(self.ros2_ws)) + + if Path(SDlogfile_path).stat().st_size == 0: + print("SDlogfile has size 0. Maybe the CF failed at writing the log on its SD card, or the downloading through radio failed. SDreport PDF cannot be generated") + return super().tearDown() + plot.plot_SD_data(output = str(self.ros2_ws / f"results/{self.idFolderName()}/SDreport.pdf"), - logfile = SDlogfile_path, experiment = test_name, ros2_ws = self.ros2_ws) + logfile = SDlogfile_path, experiment = test_name, ros2_ws = self.ros2_ws) return super().tearDown() @@ -194,14 +199,14 @@ def test_figure8(self): self.record_start_and_clean("figure8", 20) #create the plot etc test_passed = self.translate_plot_and_check("figure8") - # assert test_passed, "figure8 test failed : deviation larger than epsilon" + assert test_passed, "figure8 test failed : deviation larger than epsilon" - # def test_multi_trajectory(self): - # self.test_file = "multi_trajectory_ideal_traj0.csv" - # self.record_start_and_clean("multi_trajectory", 80) - # test_passed = self.translate_plot_and_check("multi_trajectory") - # assert test_passed, "multitrajectory test failed : deviation larger than epsilon" - + + def test_multi_trajectory(self): + self.test_file = "multi_trajectory_ideal_traj0.csv" + self.record_start_and_clean("multi_trajectory", 80) + test_passed = self.translate_plot_and_check("multi_trajectory") + assert test_passed, "multitrajectory test failed : deviation larger than epsilon" From 55e4bf82c24279db8aa7d14d62e413481d9d2433 Mon Sep 17 00:00:00 2001 From: JulienThevenoz Date: Wed, 10 Apr 2024 15:35:29 +0200 Subject: [PATCH 119/162] small cleanup --- systemtests/SDplotting/plot.py | 11 ----------- systemtests/SDplotting_save.zip | Bin 10078 -> 0 bytes 2 files changed, 11 deletions(-) delete mode 100644 systemtests/SDplotting_save.zip diff --git a/systemtests/SDplotting/plot.py b/systemtests/SDplotting/plot.py index e774b4bfd..9c1c89f57 100644 --- a/systemtests/SDplotting/plot.py +++ b/systemtests/SDplotting/plot.py @@ -36,20 +36,9 @@ def file_guard(pdf_path): def process_data(data, settings): print("...processing data") - # print(data) # convert units event = settings["event_name"] - # data_fixedFreq = data[event[0]] - # data_estPos = data[event[1]] - print(data) - # print(data_fixedFreq) - # print(data_estPos) - - # if settings["convert_units"]: - # for key, value in settings["convert_units"].items(): - # data_fixedFreq[key] = data_fixedFreq[key] * value - # data_estPos[key] = data_estPos[key] * value # if we have a list of events we need to iterate over each individually if type(event) == list : diff --git a/systemtests/SDplotting_save.zip b/systemtests/SDplotting_save.zip deleted file mode 100644 index 1a85fddaacfb400332b82a7ecd043fa1e792d136..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 10078 zcmbt)Ra6~YyXD5+-3cB%I0Sch4K5pZcMtAP@Zhc+4-nkl-QC^klY9Gg|M!l29{%pH z#*%udIjd^D%rU>IC<6hB3HVcN9;GXOiTxj$K)7;t1OqOn z_dz3AVoD^g6n?$V+s&qN($N9nLK%xyJ6uvLG~&BOG};EW+fgRNFG3THHV&WkX%A*O z1QBj0vkUS+qf}a&zP*8<bDTB)p*pNt8nT_birEx_m+o-d%K6;WF)42GR9$VKkgX!$*6W;%mP)f7x= zt+edqx`+=;XRSAltDR(rv9(Txuh6$TR6!K_wf%LJw_ptZbdxN5BAjKk8;_&<(nBtb zsYDG4hb^;1pvu`Jn&~)s&aT}toarPPVZ(h7ULap%UfzN{$MCxTm6Fd`DZ^8)#jPuj zBrKP_psrA|jb+(-3Jo+Purh?&1c^KYv&J*;xb=m1+pS+5VOkT7hj<8Wr)T! zT#zW%gb0|dg(drRm(a^H8$}dbNL*Ec#aZi2;*2=*j^m`s*Zq!bxfzTk?8e55U+_MM}dS4?3h(>IBzlP$9 z$CoM0r|NVzwT;XsDH)7p&-WNc_bNN7Hp!gT#WhWam#t32x|1ztVPLl3!Tt~uTCIz>W&KX(9n zabt0o>a5eh6IzA-m}Vu_w}B2{wj;*68Vej#d2j>}m$v!EOv}{++m2d2j}Lg3FaB*G zHe=o#us&&hK1CkF=w(1!KL8Dx8U8y+HV7lAoFqMMK32<-m@tQEngLuta3cijd=%>O zXB z-Uv>119cg&joRsd3gZ>%%dQ4@NAR!*G;i9deFH8%r3W@7eED*!WY(q|7Ox#wzY&0> z;%VS3PpXA4VQuisDXq>Rh8=Ze+6YM;$x9_UkvV1tChj?pD|e_QEu{CRKx@!af&E8( zBk?eT3SGdZcX_P}Wz7QG36cD%SS)w6v3#TM` zWF^wo7wVTyKqc8(i1>tBa__R~MZU!ixb|oVf8p6TT(m>@M2r8s{jj`P7 z@Wb$>)_bez9kU-qI3zQ5HG{Ldd|t>rNRv<9Ls2C5p)`-qkscOn{s05?!d}7lLNCpf zKA{doiM-#Cc7cJX0vM2Mx0Y6+HMi~ayyU;}I~rn*uClrqctSqV)&lTrX?eLg_;}pTKg-W(^Lxj5=j&Y3 z9L-wrM=Uols2DtXj#cBPJs(qs+{1NmHxiQ3GL%O~kXU#(0fLtafe_^vJZYLk$6f#>Ay^q+F5Gj85!nASW%{(VP~Wb*Wgh4|WfJI&f(lkVDX;0q;GIf|+4ug5`Dkdf0vp=@-l-o28MlnR?k*dXqx+NbT)$+@1{Q z0V}}jvc3fO1nXyU+&*WtzMMupj`etB{D=VczK#372kvKqsLyoy7j8A?qsG9c2K=j) z@nd<|g3@c&*eT*H`&cZ@-h_h7UH$sf1j1u!gPtD;!-?_v@VI$ZmsmOLLl_<+F(UO z;W@eXs^itbdi6wOpkK=mY+z2ERtUWo*=||auT%eP^ywXr0(m`u3YFsTLpDc}-+Yix zDs{sX0N!3md#oUTcUh^n4r38K1tK0P_}yPPVHWs4ne^KQY-? zAVYVXOE&P`WkdD_+vHrF(gR)HRTf_qs7T<5mFADRiONSPmFSKf5Q~4f(1j-U)YS zJT%Qpim_d7Dda^k&3~W7_lTcGI``d0Z*V>BQ?TRu_y#hk;s>016qQR9ylx)WH}-P3 ztOpy*jz=a%85r1w_hqa!H~`>}?)y)f`QH`c2oeCm^v{aW*wn?z#M;j6-xY-}>N0ja zgJ@KrrHjn9d}Gc$C=MMMtpttFctYu+*ZT$&c(?mg2&LACaN!^$))KgjB<1Sa^$0Lg z1v9k$*GS@md`3U}k#+_z?4s&FG%rP~%q5+rgBhj2l~g^K9b4742DNaj1a$hn?U|V} z(hdtG$G$6Hw)<0KPAcwc=F!ga-f4d4-?Ipsb&!@bd9G!AxpfFRW_zo2oP~C@Gz};&3Fp;Z12Ke>V{M=nNOG~vY05s>Z|x- zH^_wsmNyDVL$15f^u&D?=$oU2&LV)wmDgA!6$=BgZU3^}e$Zl_k=e2x9Q7^P445%v zhP9t*n{G;n>k!IEO)ZSrbI@l*k|e&yK#hx88D#3QagKdKnti9k&sEP&=lUyGn{YAD zpq(bL3n4N;P8e3KI2ExmN?>n;0)sR6XGhfC?zKabyWR1 z_mLBUq6Ju;SrjDScIIOH1pFYbCK@RdWKb@h^@7_Qe{DEKe0uI@c>oonC%6hEQ2LY^ zk#GT;R~W*K&0jDv*RyIs_&S`+&?KK7w75u5v0~&^bb_JNrkgMeLoURH0Ody1OM|-L z){fSPYn#gFwkgk-+fqQs2Ih<@42^3RfCzqkUt`8nxm9w~vLzLuh?Cbw4%UtOJ>da- zUn!WA46;a0(EgKc`iYOTGK>fbS)P%!QdmMghWmH^!Cs`X^{|)C1StZ10C0MTU>`Oq z*OTe8eG^f|2|TAYP3du!ZKcM-V>#a&YwHssQMlw|n4x&@A z`c03Aa4i&^V;#iDg4lff;PB(JuE|Pm+VT{npZr732sCI|e+5!2RUZ^Dg}R9b_W**d zqVqYxqD@QJedX}I3RL~%e68l_pp@U<4C|LIsUXO$MGUfIwYTQxe3Cc4r4DB0rh*lO{s0wh&g zt6v&u-vl3@?D|k1PA6H`u3v`?U!crG^Q%I-96FaxPF3b7d9|e)W?m=yYwC)6evCyD z!JR8c5!7JaQU|LK5L5=GZ266W!lZhMizZEyT9b_ec5$v84qjP~e-Tab_mfh&CyXTR z+%&%dXcAYYU2UDEx|VT)bB^oG{$ODx=3c3#zc`BWMaG=Wr9w=)fG?QL=f}28yf}z` z&qvF=OEbDbpyyRNuau5`>d5eF?nDPF$;z5>ntaOZo||i&g3_H8>qOIjCrPF=oOQGq z`)%J2o>TB?pgQ6bu6CQi9b@B*Kr_uX>FRmr_rAEVQb44wJwj`o9;cEb2rwuz`bJt2 zCRFf_oCgHU%(L6{!^eC7H~5=w3>gilvb=p;Vhh6Jm}g?RlS|wt3U7F4Sjs?E>Sec< zTKv+~V=UB5czISLUkt8J?;Tc39qu3%7{BT*v>%dU%c6aWlIC2>SOritGGNhSc}lw3 z%F;4uJXMoy=v+zzpW{15ClLpyRfU$4?_pdjBuXV=Myk6U#ee=x0sE$9DGzFJ@XQRK zW<&5qeAYS@62K{>UY=bT6~&tvoX_3oqKl$oRiYavfiYGg8yEYQ6kX@+dba*RKkk?B z?~1KKefSxMRWRK2=W5J!D&KC(hSEFJ@G1j*7RkZOusgB$gwzJX<_ochVP-V8e=Jl3 zAyctfSIj4~ToXgB=`A>)#EAnYtx4+2vOZ zZXr+Zx$LPv>FqV{O73v7%qLq^pqv}c_1EtJlMEW(jfV=LU1JO0k5&E7$lrji@0#(h zR_3AWpU#ubzw-wZ8;=OCPGg(I64N%_@4z&n4_y&Pk%(lYP~qFx0}jh~*av;S^Lv!| zdt>plvVQBS=+xNob?6knaRlON@Q-r8HVsO!rru~o?0Pw52F)GCY<-nrPv5{B?hu^y z{fX3ivQtXc&!UHkkQ&+a0;ny2@B&xIaPOZ&^uF&b8Nk1w%6S*KoYCjM?wLYWz~%bx z38o|3J9Cm_YinyX*Xj=L0ylg+a!{~J-}4(*0wdD^(m6A+xK_Q~fnI9C!n#INx1v4v z9$8+Ot1-LZl3^U)4e-5-7|~DFt;!Gj_2fgizI1@c_syY*6P4k&aSsWS>qMSu?~)sb z+Zp4kbd^i6{Ml^9$*A*fn^gspj~1q$_d}qu;U-G0NAMUvTZT+6F=9H&N#+upJW9(+ zq$bXRJ)v=h1GFs;xkPVzyg);iN{PFDboh+@$}y{!=XMkyBmkcv=8QYf>-TmNjDIPD z8}5m{1X#0*D{=o1fv6ddgZrm_PwP!N>HUIxE*6a9+#dtn_hYD47*VeF9ISg(*`eNF zH6_Gg$PsoBbxJn3aVMy{&pieT31?#F5`6bjcVa4o5eh!(LFTC*b?J(3 z5A;{k;7M_$C~-1??Npr7YQD_5)k*`06n@ZiG-G9G`gDG$Do#I6%+P@!2AP($w#I$? zK5bKSQVKN}>>)l<;z?V~53WT_F(j!`+k246!bBoBle;jxsvyG}@(jrara`uK0cTzj zxL4MC+0(sU2A}3P40g<<_9m_{6lRn^gV%M|G_$2WG(X|YW8ZlO0NQI1FY}tz`fj!8 zw%mD(m?Ad(POkI^zv18%O^9;Y_6~p8gL*<8^T@=b@)<8`FjiPFQjvBb?&oP_0dKj= zTy=Q(6j@sf;kF(>(9wIr>`kV?x8uMl#RW8pDgwjAO<;Kw_<;DMmZqP3hihR0fIph( ze^yJC!~g)xKdYrbmY=?*i?s#N_TLpug;X&+w> zF5Xvt?kL5csP{(op*O4^Ur9baxqPSl3U8)!R+rtHUmHB{=A3Tk%EB^nZW3>`rZchl zWt!uONM+yYSGWA9JuI)nEOeEQ3i~Xxbq)7@#kF*|5#F}qh!^wt6UJNGugUA%<76tU z@SN`NXe*_yb8Akk&Z&=tOuT`}bvmLgY@bOONa((@yG>QzJf&i}y(=zhIcUVFuPvYB zciarnvMFw)=;sr57AwR8-YJ>Q&-{IDw#WLCfGNwTXzlW>nB=o-D%M6^q6lv?rm&}ZyrVt za#5=reHo7FXRjg;1-fH`g+;XPS5prsLqn0#Ub8BM|(n)_kEzfxPmEG17iN|OEqSySH*Kfr4(C+zX%je=l z0cTM=s~M7~fE5HCflJOAhp%t#86 zrkEZ6cD6q+fwQ9Yfi}m|M0(|P#x_M2c@+~$E=jDcdx*nJ>5kZYtFqjob!apa^wVT~ z!wn!~j`0ykj$yG7`V1w07OP=*#vdzc`7L!UjJe-K6k_2A5E&v^(UBzS$C7SnCS<}3 zIY10Do_f;=O5ET4ccoPWcHt?Qkc?jV#Nr2253awr?g63Py(^Jdg^|{nLt1lyVXQ!vP2Rwg1yuVDgw-)>M zLTd4cPJ~4aoLVakRR?}pyiE+fFU+_;O&sQYjK0g%eZUl-1rSq7@mNvo6|~&!sR6zD zlX*GuuF`~D<;HKld6a!vri&%3-!G<1^+O)%W*o{IkV#$cMsd?|Fy-RwxkJy|8;LR+ zj3L@CZdYqgVdOVE&S8iMjnBvXe`91$VPrDXb3jZX5l*>696OeA@#rG3Gbtv-|MH50~JCIk4816r~ufyPKuJAt_bsBiYe10ff~ z7~`=>#dwHWRX)sx;wrRJH>-DFyZ1`66Y?=wq7J~fPM4)#nn@8XfYwEnn%v`3%Nwx= zZQAz`O%^D;ogz4jys0si?TnDJkkpi;l_&DSIEmAu&#MKJ+tCGpr|+sACS4937i>XX z3&a;ww@q^$TnGDUT^k~1+}S5vTnE$8 zO=9YF1fazh7%W*!eg!O7R22Rir2=j4hY?JLbMA3Oon3w_pK)O*rqcqs>GxI-?wRpQ+~s?Wft(3njmh9&ZT|0e6tVnMsC zzSzMI>tqmBQUFELP${$HkSh|F30wh*vXD89gG@w6c*0%D-ri4s!4!&vU{SJ}{t)a? zP_zMH4h%!Fi(eQg+xG0rcA_95H^l%jN{wZ*(p<8sWYKgYV!Sz*u>6vPxpxQP?9=j2 zD05ec)YF#31-C3M%H5cO8E8SQPAi5`*d(ykN6-ALpMD!#Zy#a=$Z3n>nhY7uob;Fl z@If+Piv^rYtXm%jUXry#EbjG;X7O`;Ip7Gl*exJ{T++xa-W{o{Y)3P)nIP)Jd-OTX zUJLlHO7eNHX|RBu!al~dBt#uZmrH9cRapupHxVpDeV%^y7#!q?0pmb1q{|6iwqF-~c+ZtWofuhMq?sIIGx2Q-va^YQU2jzgfUI+8*t#Wx=fy?~}^R18=5P ztp`E7zH1wVMsFV*v%NqMlHD*u!Hk_ptvrsCwc^*d3x3`<316%syTl>sa0pGI$}*_N zkbGNgW(D5$(a|(-41L2^YQ>%<+^t2f5jB6^JxM9`?Zq%y&tVa`axDRhl1Kvx0}NgZ zX(9uS!a2l;QHaYQyaZ$MQ{(`B3*R9BfyLF%(HsBY_?#H1vcGyjq!?I_t9j3c4myZ+ zT-$(z{zAJhF&^Jg*vaR9r-%lJ6m?Fv_#SB$c-i=Q1H;>P&0*xQT8rl1IL@V<_93@(?Lg=NAiq^T0Z=RXuGbMRYN8N-!XFnMTY{$fOjco76A^8H>+*?DhzNQ6J?zoj4*d8Yt zlNcFrOeaZxV$ooBjb7-#Gx)?Jc_Ts<@aiZ0g5_QAKU+SDB={0=9Z&m?e4`&A2UZtL zy#i#1`VfE?tl084+Adb&D?0=BD&Rf7k$_=W8Aj>~`Vv3&9rE^fkPb9b_$W=MQrJj6 zvn=ZguM`JL-(sqFCm)h^(hFS)Kz`5fJA`K() zs)O`e(k%Ns@BTBw>rE^R+x^tjX17$VNPl_ph*~h|?><%r#%$Z#ioq4@w?XL_?1@2I z{!iuZ;_6p$TB*|=oD+ksPr(%#W+rRA3<&eD8iVCx>PCLU`xHC-KY{$+%Y!AZ>&U(q-g%o{McmK0jL9R0p01 zOz18N;~4v0I9V_UZ~e)yV_|ZRBJn_PbvYNOrbd!7auUY^ofR!*gA{f70lZx7YMMc2 z@Iyu4K7DBM6%3bWmQU^!|(Yg4nS(n5fy?e@P z{3YsI)QivDgqz-e3FLN?bUeE=mQIEfOyqge=xm59Qq?Lt&MlbLBth~NRJ*)s?}T7V z@@+>oWIf{R_Ow8>ovijiWfRDSF;iaql7_(k2qqY}aTp<4Cx>`)xbG5A3inRh*Tuo% zN9lAgKH=%GdV*+LvWVV&$wAT9d^5ZtHa!MaK#UwYS(!X#anyt|$w=9S9dR3>912~y zKHFwWInz+ddZD}vC#BzHAg?_d9?@Y8GMNa78wV6<1{jOMuipHjwyZ5A4 zw{ygu2=;MZqYB6wz?=>vOQ0B3_kFb#!SccLOGHNb%G>v7(VNS?trF` z7{*p>cN)~&n?Nk}?R3c1W-6}>HOOsjyT_tKWu~ ztbDTl5&4ast5q& z{mnbMs8bG!mK8~~Zlv#^u7UdaFisAd$}|ktcA% z5jGql6~B=t4~p(wCFt5Yaap%%L%gDNo7Y{his)k9w&Ly#LK^ktcIqcl{aPAP7?b4I z?L7N!VW63Du5#U|3c||Tk7W~1WUN2=Z#i9 zQ}$UY{%%cwS9KxH$TT=K)$n93DY|-k5!pWYYw8|-P!!Y1@V9Pl;mT(zA?nrw+q?~I zPt{rY{G4|?({xV)OFW*mM_~GJ-G>XiSNc(ojv968Rd}fq14wI1(kTiu2CP!9NcfrqQp`W7UQ4o4rf?knEFR_%^iOlWQ8C|*VvB%={v26zE zS*L!NJ#$pOgM3>~Q&rNiPpcUz4ozI-_60jdzFj7|iGa#NZl>mJvB3tiR^*3}PR-d{ z-i(~3sI4O^HOz~4Vw$QYgRlFy)Wn)(b=mLgl46WFPmY%fwFWxO(!*Zgv9uI+5@{Qw z+sbY!r~1FFqxchhXPP|OM4{|(tX)nM9Wq=@H`ytCfc9@09stzBq0e1yPJ}0_&d@`N zCZ4V#8iUX1{BrL^FlZ%7T>bF8k+Okw3gBRG{DBYdjC{k^gjriM3bzVYm0z1SYV4!5 zQL=mm0~3hqxqSj7U0SOMaJDmToT}m47&q|?wpz2i2!i6>^V6U zJ@FN{NWdBj$Jt)T^u=?WB8dl99lBpZcG}2dr$0J*h>p(=4!~dC_eyOu6;S7%3gW*r zg+FLq@5|#l1XKx8-y!pbA_&5kkrgq$r!0@JG|s@FCw;)*eOc0Joln5JUPyW!Gpk5m zbm!LcszwdDu_GO-6Xx(hpdZ9R;dxAYNP37O0M3~V-PoyDvb=44!2B^y-Y=p@L8t)0 zA8SNW1`He%;-5oNe}|;rg#PUQt%%hB1^(AO(;t{WA*sLXO-Smm?Y{v3dy%RCB>B5V z_OH#eKcT6=t05r!pGp3oB2<6>x4)VH)rk7jocp^P0&3v@@$>#)TXp}P{9h0BkJt5g hH3Y0<{3H4Qhx4T<0|otu1M07f9UK6_p!{?9zW`Du*3JL` From be2b630ad9820750f4384819026bce45a02c475f Mon Sep 17 00:00:00 2001 From: JulienThevenoz Date: Wed, 10 Apr 2024 15:44:18 +0200 Subject: [PATCH 120/162] more cleanup --- crazyflie/config/crazyflies.yaml | 6 ------ crazyflie_examples/crazyflie_examples/infinite_flight.py | 3 --- crazyflie_examples/crazyflie_examples/multi_trajectory.py | 3 +-- 3 files changed, 1 insertion(+), 11 deletions(-) diff --git a/crazyflie/config/crazyflies.yaml b/crazyflie/config/crazyflies.yaml index 2d91ffb89..4040d9a87 100644 --- a/crazyflie/config/crazyflies.yaml +++ b/crazyflie/config/crazyflies.yaml @@ -94,12 +94,6 @@ all: stabilizer: estimator: 2 # 1: complementary, 2: kalman controller: 2 # 1: PID, 2: mellinger - # ctrlLeeInfo: - # experiment: figure8 - # trajectory: figure8.csv #translation_y.csv # yaw0.csv # # # - # timescale: 3.0 # 0.75 # #0.34 - # motors: standard motors (CF) - # propellers: standard propellers (CF) # ring: # effect: 16 # 6: double spinner, 7: solid color, 16: packetRate diff --git a/crazyflie_examples/crazyflie_examples/infinite_flight.py b/crazyflie_examples/crazyflie_examples/infinite_flight.py index 29239f053..1fcdb76cc 100644 --- a/crazyflie_examples/crazyflie_examples/infinite_flight.py +++ b/crazyflie_examples/crazyflie_examples/infinite_flight.py @@ -23,9 +23,6 @@ def main(): # pm_state : 0 = on battery 1 = charging 2 = charged 3 = low power 4 = shutdown flight_counter = 1 - #enable logging - allcfs.setParam("usd.logging", 1) - while True: print('takeoff') allcfs.takeoff(targetHeight=1.0, duration=2.0) diff --git a/crazyflie_examples/crazyflie_examples/multi_trajectory.py b/crazyflie_examples/crazyflie_examples/multi_trajectory.py index ba41ad3f9..f0109e12d 100644 --- a/crazyflie_examples/crazyflie_examples/multi_trajectory.py +++ b/crazyflie_examples/crazyflie_examples/multi_trajectory.py @@ -40,8 +40,7 @@ def main(): allcfs.land(targetHeight=0.06, duration=2.0) timeHelper.sleep(3.0) - - + #disable logging allcfs.setParam("usd.logging", 0) From 44db5a3fff1ce01c8c3b6d0d6b50689bab8e0b27 Mon Sep 17 00:00:00 2001 From: JulienThevenoz Date: Thu, 11 Apr 2024 23:39:37 +0200 Subject: [PATCH 121/162] cleanup --- crazyflie/config/crazyflies.yaml | 1 - crazyflie_examples/crazyflie_examples/infinite_flight.py | 2 +- systemtests/test_flights.py | 4 +--- 3 files changed, 2 insertions(+), 5 deletions(-) diff --git a/crazyflie/config/crazyflies.yaml b/crazyflie/config/crazyflies.yaml index 4040d9a87..dd120fcbf 100644 --- a/crazyflie/config/crazyflies.yaml +++ b/crazyflie/config/crazyflies.yaml @@ -94,7 +94,6 @@ all: stabilizer: estimator: 2 # 1: complementary, 2: kalman controller: 2 # 1: PID, 2: mellinger - # ring: # effect: 16 # 6: double spinner, 7: solid color, 16: packetRate # solidBlue: 255 # if set to solid color diff --git a/crazyflie_examples/crazyflie_examples/infinite_flight.py b/crazyflie_examples/crazyflie_examples/infinite_flight.py index 1fcdb76cc..6aa94c6fb 100644 --- a/crazyflie_examples/crazyflie_examples/infinite_flight.py +++ b/crazyflie_examples/crazyflie_examples/infinite_flight.py @@ -22,7 +22,7 @@ def main(): # pm_state : 0 = on battery 1 = charging 2 = charged 3 = low power 4 = shutdown flight_counter = 1 - + while True: print('takeoff') allcfs.takeoff(targetHeight=1.0, duration=2.0) diff --git a/systemtests/test_flights.py b/systemtests/test_flights.py index 338b0e480..a5de01f00 100644 --- a/systemtests/test_flights.py +++ b/systemtests/test_flights.py @@ -80,14 +80,12 @@ def setUp(self): self.test_file = None # launch server - current_env = None - # src = "source " + str(Path(__file__).parents[3] / "install/setup.bash") # -> "source /home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/install/setup.bash" command = f"{self.src} && ros2 launch crazyflie launch.py" if TestFlights.SIM : command += " backend:=sim" #launch crazyswarm from simulation backend current_env = os.environ.copy() self.launch_crazyswarm = Popen(command, shell=True, stderr=PIPE, stdout=PIPE, text=True, - start_new_session=True, executable="/bin/bash", env=current_env) + start_new_session=True, executable="/bin/bash") atexit.register(clean_process, self.launch_crazyswarm) #atexit helps us to make sure processes are cleaned even if script exits unexpectedly time.sleep(5) From 40d5e4aadab7f5d0fcac6e6c4f4d95d462c82e1f Mon Sep 17 00:00:00 2001 From: JulienThevenoz Date: Mon, 15 Apr 2024 12:06:39 +0200 Subject: [PATCH 122/162] flake8 formatting --- crazyflie_examples/crazyflie_examples/figure8.py | 8 ++++---- crazyflie_examples/crazyflie_examples/multi_trajectory.py | 8 ++++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/crazyflie_examples/crazyflie_examples/figure8.py b/crazyflie_examples/crazyflie_examples/figure8.py index 1e7199826..4a2e5c300 100644 --- a/crazyflie_examples/crazyflie_examples/figure8.py +++ b/crazyflie_examples/crazyflie_examples/figure8.py @@ -14,8 +14,8 @@ def main(): traj1 = Trajectory() traj1.loadcsv(Path(__file__).parent / 'data/figure8.csv') - - #enable logging + + # enable logging allcfs.setParam("usd.logging", 1) TRIALS = 1 @@ -38,8 +38,8 @@ def main(): allcfs.land(targetHeight=0.06, duration=2.0) timeHelper.sleep(3.0) - - #disable logging + + # disable logging allcfs.setParam("usd.logging", 0) diff --git a/crazyflie_examples/crazyflie_examples/multi_trajectory.py b/crazyflie_examples/crazyflie_examples/multi_trajectory.py index f0109e12d..76d10de1d 100644 --- a/crazyflie_examples/crazyflie_examples/multi_trajectory.py +++ b/crazyflie_examples/crazyflie_examples/multi_trajectory.py @@ -13,8 +13,8 @@ def main(): allcfs = swarm.allcfs trajs = [] n = 2 # number of distinct trajectories - - #enable logging + + # enable logging allcfs.setParam("usd.logging", 1) for i in range(n): @@ -40,8 +40,8 @@ def main(): allcfs.land(targetHeight=0.06, duration=2.0) timeHelper.sleep(3.0) - - #disable logging + + # disable logging allcfs.setParam("usd.logging", 0) From 76638d23b9f2392cae7903208d48270d23d1cac3 Mon Sep 17 00:00:00 2001 From: JulienThevenoz Date: Mon, 15 Apr 2024 12:16:34 +0200 Subject: [PATCH 123/162] flake8 --- crazyflie_examples/crazyflie_examples/figure8.py | 4 ++-- crazyflie_examples/crazyflie_examples/multi_trajectory.py | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/crazyflie_examples/crazyflie_examples/figure8.py b/crazyflie_examples/crazyflie_examples/figure8.py index 4a2e5c300..98e3611c4 100644 --- a/crazyflie_examples/crazyflie_examples/figure8.py +++ b/crazyflie_examples/crazyflie_examples/figure8.py @@ -16,7 +16,7 @@ def main(): traj1.loadcsv(Path(__file__).parent / 'data/figure8.csv') # enable logging - allcfs.setParam("usd.logging", 1) + allcfs.setParam('usd.logging', 1) TRIALS = 1 TIMESCALE = 1.0 @@ -40,7 +40,7 @@ def main(): timeHelper.sleep(3.0) # disable logging - allcfs.setParam("usd.logging", 0) + allcfs.setParam('usd.logging', 0) if __name__ == '__main__': diff --git a/crazyflie_examples/crazyflie_examples/multi_trajectory.py b/crazyflie_examples/crazyflie_examples/multi_trajectory.py index 76d10de1d..b6c81457e 100644 --- a/crazyflie_examples/crazyflie_examples/multi_trajectory.py +++ b/crazyflie_examples/crazyflie_examples/multi_trajectory.py @@ -15,7 +15,7 @@ def main(): n = 2 # number of distinct trajectories # enable logging - allcfs.setParam("usd.logging", 1) + allcfs.setParam('usd.logging', 1) for i in range(n): traj = Trajectory() @@ -42,7 +42,7 @@ def main(): timeHelper.sleep(3.0) # disable logging - allcfs.setParam("usd.logging", 0) + allcfs.setParam('usd.logging', 0) if __name__ == '__main__': From a6ca61fcaae8cb03643bddc7072b5072a2457589 Mon Sep 17 00:00:00 2001 From: JulienThevenoz Date: Tue, 16 Apr 2024 11:37:08 +0200 Subject: [PATCH 124/162] don't try to download SD data when in simulation + addressed feedback --- crazyflie/config/crazyflies.yaml | 4 ++-- systemtests/test_flights.py | 6 ++++-- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/crazyflie/config/crazyflies.yaml b/crazyflie/config/crazyflies.yaml index dd120fcbf..1c13f9ebd 100644 --- a/crazyflie/config/crazyflies.yaml +++ b/crazyflie/config/crazyflies.yaml @@ -8,8 +8,8 @@ robots: # firmware_params: # kalman: # pNAcc_xy: 1.0 # default 0.5 - firmware_logging: - enabled: true + # firmware_logging: + # enabled: true # custom_topics: # topic_name3: # frequency: 1 diff --git a/systemtests/test_flights.py b/systemtests/test_flights.py index a5de01f00..9e59083bb 100644 --- a/systemtests/test_flights.py +++ b/systemtests/test_flights.py @@ -12,7 +12,6 @@ from argparse import ArgumentParser, Namespace from SDplotting import save, plot -############################# def setUpModule(): @@ -98,6 +97,9 @@ def tearDown(self) -> None: if Path(Path.home() / ".ros/log").exists(): shutil.copytree(Path.home() / ".ros/log", Path(__file__).parents[3] / f"results/{self.idFolderName()}/roslogs") + if self.SIM: #if in simulation, we skip the downloading SD data part + return super().tearDown() + command = f"{self.src} && ros2 run crazyflie downloadUSDLogfile --output SDlogfile" #if CF doesn't use default URI, add --uri custom_uri (e.g --uri radio://0/80/2M/E7E7E7E70B) try: downloadSD= Popen(command, shell=True, stderr=False, stdout=False, text=True, #download the log file in ....../ros2_ws/results/test_xxxxxxx/ @@ -169,7 +171,7 @@ def record_start_and_clean(self, testname:str, max_wait:int): #if something went wrong with the bash command lines in Popen, print the error print_PIPE(record_bag, f"record_bag for {self.idFolderName()}") - print_PIPE(start_flight_test, f"start_flight_test for {self.idFolderName()}") + print_PIPE(start_flight_test, f"start_flight_test for {self.idFolderName()}", always=True) def translate_plot_and_check(self, testname:str) -> bool : From 6c79682d61cbcb1ebd09ce5be43baeaad79ace90 Mon Sep 17 00:00:00 2001 From: JulienThevenoz Date: Tue, 16 Apr 2024 11:37:40 +0200 Subject: [PATCH 125/162] fixed crashing when trying to set non existent param --- crazyflie_py/crazyflie_py/crazyflie.py | 24 +++++++++++++++--------- 1 file changed, 15 insertions(+), 9 deletions(-) diff --git a/crazyflie_py/crazyflie_py/crazyflie.py b/crazyflie_py/crazyflie_py/crazyflie.py index a1e39466d..0e252a7e0 100644 --- a/crazyflie_py/crazyflie_py/crazyflie.py +++ b/crazyflie_py/crazyflie_py/crazyflie.py @@ -955,15 +955,21 @@ def startTrajectory(self, trajectoryId, def setParam(self, name, value): """Set parameter via broadcasts. See Crazyflie.setParam for details.""" - param_name = 'all.params.' + name - param_type = self.paramTypeDict[name] - if param_type == ParameterType.PARAMETER_INTEGER: - param_value = ParameterValue(type=param_type, integer_value=int(value)) - elif param_type == ParameterType.PARAMETER_DOUBLE: - param_value = ParameterValue(type=param_type, double_value=float(value)) - req = SetParameters.Request() - req.parameters = [Parameter(name=param_name, value=param_value)] - self.setParamsService.call_async(req) + try: + param_name = 'all.params.' + name + param_type = self.paramTypeDict[name] + if param_type == ParameterType.PARAMETER_INTEGER: + param_value = ParameterValue(type=param_type, integer_value=int(value)) + elif param_type == ParameterType.PARAMETER_DOUBLE: + param_value = ParameterValue(type=param_type, double_value=float(value)) + req = SetParameters.Request() + req.parameters = [Parameter(name=param_name, value=param_value)] + self.setParamsService.call_async(req) + except KeyError as e: + self.get_logger().error(f'(crazyflie.py)setParam : keyError raised {e}') + except Exception as e: + self.get_logger().error(f'(crazyflie.py)setParam : exception raised {e}') + def cmdFullState(self, pos, vel, acc, yaw, omega): """ From 081d782acdda1aeaf8c829c4788018a0bab05ac8 Mon Sep 17 00:00:00 2001 From: JulienThevenoz Date: Tue, 16 Apr 2024 11:47:18 +0200 Subject: [PATCH 126/162] changed setParam exception logging from error to warning --- crazyflie_py/crazyflie_py/crazyflie.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/crazyflie_py/crazyflie_py/crazyflie.py b/crazyflie_py/crazyflie_py/crazyflie.py index 0e252a7e0..27e9d859f 100644 --- a/crazyflie_py/crazyflie_py/crazyflie.py +++ b/crazyflie_py/crazyflie_py/crazyflie.py @@ -966,9 +966,9 @@ def setParam(self, name, value): req.parameters = [Parameter(name=param_name, value=param_value)] self.setParamsService.call_async(req) except KeyError as e: - self.get_logger().error(f'(crazyflie.py)setParam : keyError raised {e}') + self.get_logger().warn(f'(crazyflie.py)setParam : keyError raised {e}') except Exception as e: - self.get_logger().error(f'(crazyflie.py)setParam : exception raised {e}') + self.get_logger().warn(f'(crazyflie.py)setParam : exception raised {e}') def cmdFullState(self, pos, vel, acc, yaw, omega): From 51d4b9c0ada1aa22c003219639bfdf825d5cfbe1 Mon Sep 17 00:00:00 2001 From: JulienThevenoz Date: Tue, 16 Apr 2024 11:48:16 +0200 Subject: [PATCH 127/162] added end-lines in print PIPE for readability --- systemtests/test_flights.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/systemtests/test_flights.py b/systemtests/test_flights.py index 9e59083bb..eb307cb49 100644 --- a/systemtests/test_flights.py +++ b/systemtests/test_flights.py @@ -51,8 +51,9 @@ def print_PIPE(process : Popen, process_name, always=False): if process.returncode != 0 or always: out, err = process.communicate() print(f"{process_name} returncode = {process.returncode}") - print(f"{process_name} stderr : {err}") - print(f"{process_name} stdout : {out}") + print(f"{process_name} stderr : {err} \n") + print(f"{process_name} stdout : {out} \n") + print("\n") else: print(f"{process_name} completed sucessfully") From 639eb88e7e4105507e22abaf93d1f7d268005fc6 Mon Sep 17 00:00:00 2001 From: JulienThevenoz Date: Tue, 16 Apr 2024 11:50:16 +0200 Subject: [PATCH 128/162] flake8 formatting --- crazyflie_py/crazyflie_py/crazyflie.py | 1 - 1 file changed, 1 deletion(-) diff --git a/crazyflie_py/crazyflie_py/crazyflie.py b/crazyflie_py/crazyflie_py/crazyflie.py index 27e9d859f..006dcb1bb 100644 --- a/crazyflie_py/crazyflie_py/crazyflie.py +++ b/crazyflie_py/crazyflie_py/crazyflie.py @@ -970,7 +970,6 @@ def setParam(self, name, value): except Exception as e: self.get_logger().warn(f'(crazyflie.py)setParam : exception raised {e}') - def cmdFullState(self, pos, vel, acc, yaw, omega): """ Send a streaming full-state controller setpoint command. From 48803e1658b4e61559af03aa34b84f3c9a2f0ecd Mon Sep 17 00:00:00 2001 From: knmcguire Date: Fri, 19 Apr 2024 15:46:46 +0200 Subject: [PATCH 129/162] fix yaml handling --- .../multiranger_simple_mapper_launch.py | 36 +++++++++++++++++-- 1 file changed, 33 insertions(+), 3 deletions(-) diff --git a/crazyflie_examples/launch/multiranger_simple_mapper_launch.py b/crazyflie_examples/launch/multiranger_simple_mapper_launch.py index d8e4b4952..990ed7a9c 100644 --- a/crazyflie_examples/launch/multiranger_simple_mapper_launch.py +++ b/crazyflie_examples/launch/multiranger_simple_mapper_launch.py @@ -4,9 +4,11 @@ from launch import LaunchDescription from launch_ros.actions import Node import yaml - +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration, PythonExpression def generate_launch_description(): + # load crazyflies crazyflies_yaml = os.path.join( get_package_share_directory('crazyflie'), @@ -16,17 +18,45 @@ def generate_launch_description(): with open(crazyflies_yaml, 'r') as ymlfile: crazyflies = yaml.safe_load(ymlfile) - server_params = crazyflies + # server params + server_yaml = os.path.join( + get_package_share_directory('crazyflie'), + 'config', + 'server.yaml') + + with open(server_yaml, 'r') as ymlfile: + server_yaml_content = yaml.safe_load(ymlfile) + + server_yaml_content["/crazyflie_server"]["ros__parameters"]['robots'] = crazyflies['robots'] + server_yaml_content["/crazyflie_server"]["ros__parameters"]['robot_types'] = crazyflies['robot_types'] + server_yaml_content["/crazyflie_server"]["ros__parameters"]['all'] = crazyflies['all'] + + # robot description + urdf = os.path.join( + get_package_share_directory('crazyflie'), + 'urdf', + 'crazyflie_description.urdf') + with open(urdf, 'r') as f: + + robot_desc = f.read() + server_yaml_content["/crazyflie_server"]["ros__parameters"]["robot_description"] = robot_desc + + # Save server and mocap in temp file such that nodes can read it out later + with open('tmp_server.yaml', 'w') as outfile: + yaml.dump(server_yaml_content, outfile, default_flow_style=False, sort_keys=False) + crazyflie_name = '/cf231' + return LaunchDescription([ + DeclareLaunchArgument('server_yaml_file', default_value=''), Node( package='crazyflie', executable='crazyflie_server.py', name='crazyflie_server', output='screen', - parameters=[server_params], + parameters= [PythonExpression(["'tmp_server.yaml' if '", LaunchConfiguration('server_yaml_file'), "' == '' else '", LaunchConfiguration('server_yaml_file'), "'"])], ), Node( package='crazyflie', From 9ea5373a0de400a870e8e38ba2a0ea67bfea924c Mon Sep 17 00:00:00 2001 From: knmcguire Date: Fri, 19 Apr 2024 16:02:33 +0200 Subject: [PATCH 130/162] simpler solution to fix it --- .../launch/keyboard_velmux_launch.py | 10 ++++++++ .../launch/multiranger_mapping_launch.py | 10 ++++++++ .../launch/multiranger_nav2_launch.py | 11 ++++++++ .../multiranger_simple_mapper_launch.py | 25 +++---------------- 4 files changed, 34 insertions(+), 22 deletions(-) diff --git a/crazyflie_examples/launch/keyboard_velmux_launch.py b/crazyflie_examples/launch/keyboard_velmux_launch.py index 8fee2f797..76b7dc8af 100644 --- a/crazyflie_examples/launch/keyboard_velmux_launch.py +++ b/crazyflie_examples/launch/keyboard_velmux_launch.py @@ -18,6 +18,16 @@ def generate_launch_description(): server_params = crazyflies + # robot description + urdf = os.path.join( + get_package_share_directory('crazyflie'), + 'urdf', + 'crazyflie_description.urdf') + with open(urdf, 'r') as f: + robot_desc = f.read() + server_params["robot_description"] = robot_desc + + return LaunchDescription([ Node( package='crazyflie', diff --git a/crazyflie_examples/launch/multiranger_mapping_launch.py b/crazyflie_examples/launch/multiranger_mapping_launch.py index 7ff246f83..798fc3c08 100644 --- a/crazyflie_examples/launch/multiranger_mapping_launch.py +++ b/crazyflie_examples/launch/multiranger_mapping_launch.py @@ -18,6 +18,16 @@ def generate_launch_description(): server_params = crazyflies + # robot description + urdf = os.path.join( + get_package_share_directory('crazyflie'), + 'urdf', + 'crazyflie_description.urdf') + with open(urdf, 'r') as f: + robot_desc = f.read() + server_params["robot_description"] = robot_desc + + return LaunchDescription([ Node( package='crazyflie', diff --git a/crazyflie_examples/launch/multiranger_nav2_launch.py b/crazyflie_examples/launch/multiranger_nav2_launch.py index 33d834242..3e45897ad 100644 --- a/crazyflie_examples/launch/multiranger_nav2_launch.py +++ b/crazyflie_examples/launch/multiranger_nav2_launch.py @@ -20,6 +20,17 @@ def generate_launch_description(): server_params = crazyflies + + # robot description + urdf = os.path.join( + get_package_share_directory('crazyflie'), + 'urdf', + 'crazyflie_description.urdf') + with open(urdf, 'r') as f: + robot_desc = f.read() + server_params["robot_description"] = robot_desc + + cf_examples_dir = get_package_share_directory('crazyflie_examples') bringup_dir = get_package_share_directory('nav2_bringup') bringup_launch_dir = os.path.join(bringup_dir, 'launch') diff --git a/crazyflie_examples/launch/multiranger_simple_mapper_launch.py b/crazyflie_examples/launch/multiranger_simple_mapper_launch.py index 990ed7a9c..a5dfeea84 100644 --- a/crazyflie_examples/launch/multiranger_simple_mapper_launch.py +++ b/crazyflie_examples/launch/multiranger_simple_mapper_launch.py @@ -4,8 +4,6 @@ from launch import LaunchDescription from launch_ros.actions import Node import yaml -from launch.actions import DeclareLaunchArgument -from launch.substitutions import LaunchConfiguration, PythonExpression def generate_launch_description(): @@ -18,18 +16,8 @@ def generate_launch_description(): with open(crazyflies_yaml, 'r') as ymlfile: crazyflies = yaml.safe_load(ymlfile) - # server params - server_yaml = os.path.join( - get_package_share_directory('crazyflie'), - 'config', - 'server.yaml') - - with open(server_yaml, 'r') as ymlfile: - server_yaml_content = yaml.safe_load(ymlfile) + server_params = crazyflies - server_yaml_content["/crazyflie_server"]["ros__parameters"]['robots'] = crazyflies['robots'] - server_yaml_content["/crazyflie_server"]["ros__parameters"]['robot_types'] = crazyflies['robot_types'] - server_yaml_content["/crazyflie_server"]["ros__parameters"]['all'] = crazyflies['all'] # robot description urdf = os.path.join( @@ -37,26 +25,19 @@ def generate_launch_description(): 'urdf', 'crazyflie_description.urdf') with open(urdf, 'r') as f: - robot_desc = f.read() - server_yaml_content["/crazyflie_server"]["ros__parameters"]["robot_description"] = robot_desc - - # Save server and mocap in temp file such that nodes can read it out later - with open('tmp_server.yaml', 'w') as outfile: - yaml.dump(server_yaml_content, outfile, default_flow_style=False, sort_keys=False) - + server_params["robot_description"] = robot_desc crazyflie_name = '/cf231' return LaunchDescription([ - DeclareLaunchArgument('server_yaml_file', default_value=''), Node( package='crazyflie', executable='crazyflie_server.py', name='crazyflie_server', output='screen', - parameters= [PythonExpression(["'tmp_server.yaml' if '", LaunchConfiguration('server_yaml_file'), "' == '' else '", LaunchConfiguration('server_yaml_file'), "'"])], + parameters=[server_params] ), Node( package='crazyflie', From 1e93249a3c4c9a1f8992b0ebf72346c4b750f8c9 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Wed, 24 Apr 2024 09:37:00 +0200 Subject: [PATCH 131/162] autopep8 --- crazyflie_examples/launch/keyboard_velmux_launch.py | 1 - crazyflie_examples/launch/multiranger_mapping_launch.py | 1 - crazyflie_examples/launch/multiranger_nav2_launch.py | 4 +--- .../launch/multiranger_simple_mapper_launch.py | 5 ++--- 4 files changed, 3 insertions(+), 8 deletions(-) diff --git a/crazyflie_examples/launch/keyboard_velmux_launch.py b/crazyflie_examples/launch/keyboard_velmux_launch.py index 76b7dc8af..dd4105c1e 100644 --- a/crazyflie_examples/launch/keyboard_velmux_launch.py +++ b/crazyflie_examples/launch/keyboard_velmux_launch.py @@ -27,7 +27,6 @@ def generate_launch_description(): robot_desc = f.read() server_params["robot_description"] = robot_desc - return LaunchDescription([ Node( package='crazyflie', diff --git a/crazyflie_examples/launch/multiranger_mapping_launch.py b/crazyflie_examples/launch/multiranger_mapping_launch.py index 798fc3c08..18f0597bd 100644 --- a/crazyflie_examples/launch/multiranger_mapping_launch.py +++ b/crazyflie_examples/launch/multiranger_mapping_launch.py @@ -27,7 +27,6 @@ def generate_launch_description(): robot_desc = f.read() server_params["robot_description"] = robot_desc - return LaunchDescription([ Node( package='crazyflie', diff --git a/crazyflie_examples/launch/multiranger_nav2_launch.py b/crazyflie_examples/launch/multiranger_nav2_launch.py index 3e45897ad..a5944a117 100644 --- a/crazyflie_examples/launch/multiranger_nav2_launch.py +++ b/crazyflie_examples/launch/multiranger_nav2_launch.py @@ -20,7 +20,6 @@ def generate_launch_description(): server_params = crazyflies - # robot description urdf = os.path.join( get_package_share_directory('crazyflie'), @@ -30,7 +29,6 @@ def generate_launch_description(): robot_desc = f.read() server_params["robot_description"] = robot_desc - cf_examples_dir = get_package_share_directory('crazyflie_examples') bringup_dir = get_package_share_directory('nav2_bringup') bringup_launch_dir = os.path.join(bringup_dir, 'launch') @@ -84,7 +82,7 @@ def generate_launch_description(): 'autostart': 'True', 'use_composition': 'True', 'transform_publish_period': '0.02' - }.items() + }.items() ), IncludeLaunchDescription( PythonLaunchDescriptionSource( diff --git a/crazyflie_examples/launch/multiranger_simple_mapper_launch.py b/crazyflie_examples/launch/multiranger_simple_mapper_launch.py index a5dfeea84..e0fa94521 100644 --- a/crazyflie_examples/launch/multiranger_simple_mapper_launch.py +++ b/crazyflie_examples/launch/multiranger_simple_mapper_launch.py @@ -5,6 +5,7 @@ from launch_ros.actions import Node import yaml + def generate_launch_description(): # load crazyflies @@ -18,7 +19,6 @@ def generate_launch_description(): server_params = crazyflies - # robot description urdf = os.path.join( get_package_share_directory('crazyflie'), @@ -30,7 +30,6 @@ def generate_launch_description(): crazyflie_name = '/cf231' - return LaunchDescription([ Node( package='crazyflie', @@ -54,6 +53,6 @@ def generate_launch_description(): name='simple_mapper_multiranger', output='screen', parameters=[ - {'robot_prefix': crazyflie_name}] + {'robot_prefix': crazyflie_name}] ), ]) From d5daef3145fe5f9bfb06253f50779bb416ddeeda Mon Sep 17 00:00:00 2001 From: knmcguire Date: Wed, 24 Apr 2024 10:03:08 +0200 Subject: [PATCH 132/162] single quotes --- crazyflie_examples/launch/keyboard_velmux_launch.py | 2 +- crazyflie_examples/launch/multiranger_mapping_launch.py | 2 +- crazyflie_examples/launch/multiranger_nav2_launch.py | 2 +- crazyflie_examples/launch/multiranger_simple_mapper_launch.py | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/crazyflie_examples/launch/keyboard_velmux_launch.py b/crazyflie_examples/launch/keyboard_velmux_launch.py index dd4105c1e..bd909f750 100644 --- a/crazyflie_examples/launch/keyboard_velmux_launch.py +++ b/crazyflie_examples/launch/keyboard_velmux_launch.py @@ -25,7 +25,7 @@ def generate_launch_description(): 'crazyflie_description.urdf') with open(urdf, 'r') as f: robot_desc = f.read() - server_params["robot_description"] = robot_desc + server_params['robot_description'] = robot_desc return LaunchDescription([ Node( diff --git a/crazyflie_examples/launch/multiranger_mapping_launch.py b/crazyflie_examples/launch/multiranger_mapping_launch.py index 18f0597bd..67e0dde9f 100644 --- a/crazyflie_examples/launch/multiranger_mapping_launch.py +++ b/crazyflie_examples/launch/multiranger_mapping_launch.py @@ -25,7 +25,7 @@ def generate_launch_description(): 'crazyflie_description.urdf') with open(urdf, 'r') as f: robot_desc = f.read() - server_params["robot_description"] = robot_desc + server_params['robot_description'] = robot_desc return LaunchDescription([ Node( diff --git a/crazyflie_examples/launch/multiranger_nav2_launch.py b/crazyflie_examples/launch/multiranger_nav2_launch.py index a5944a117..17e5e5424 100644 --- a/crazyflie_examples/launch/multiranger_nav2_launch.py +++ b/crazyflie_examples/launch/multiranger_nav2_launch.py @@ -27,7 +27,7 @@ def generate_launch_description(): 'crazyflie_description.urdf') with open(urdf, 'r') as f: robot_desc = f.read() - server_params["robot_description"] = robot_desc + server_params['robot_description'] = robot_desc cf_examples_dir = get_package_share_directory('crazyflie_examples') bringup_dir = get_package_share_directory('nav2_bringup') diff --git a/crazyflie_examples/launch/multiranger_simple_mapper_launch.py b/crazyflie_examples/launch/multiranger_simple_mapper_launch.py index e0fa94521..e56df311f 100644 --- a/crazyflie_examples/launch/multiranger_simple_mapper_launch.py +++ b/crazyflie_examples/launch/multiranger_simple_mapper_launch.py @@ -26,7 +26,7 @@ def generate_launch_description(): 'crazyflie_description.urdf') with open(urdf, 'r') as f: robot_desc = f.read() - server_params["robot_description"] = robot_desc + server_params['robot_description'] = robot_desc crazyflie_name = '/cf231' From 0ea80748c6072ba8c46d7a8fe67e3b8c5499ee6d Mon Sep 17 00:00:00 2001 From: Kimberly McGuire Date: Wed, 24 Apr 2024 10:46:16 +0200 Subject: [PATCH 133/162] Update installation.rst --- docs2/installation.rst | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/docs2/installation.rst b/docs2/installation.rst index d9cf15381..aac92d566 100644 --- a/docs2/installation.rst +++ b/docs2/installation.rst @@ -28,7 +28,13 @@ First Installation .. code-block:: bash sudo apt install libboost-program-options-dev libusb-1.0-0-dev - pip3 install rowan + pip3 install rowan nicegui + + Then install the motion capture ROS 2 package for your ROS distro + + .. code-block:: bash + + sudo apt-get ros-*DISTRO*-motion-capture-tracking If you are planning to use the CFlib backend, do: @@ -44,7 +50,6 @@ First Installation mkdir -p ros2_ws/src cd ros2_ws/src git clone https://github.com/IMRCLab/crazyswarm2 --recursive - git clone --branch ros2 --recursive https://github.com/IMRCLab/motion_capture_tracking.git 4. Build your ROS 2 workspace From 993c674830bc01a006d64b81ae637f9a98f0e063 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Thu, 16 May 2024 16:49:03 +0200 Subject: [PATCH 134/162] [server_cpp] add arming support --- crazyflie/deps/crazyflie_tools | 2 +- crazyflie/src/crazyflie_server.cpp | 31 +++++++++++++++++ .../crazyflie_examples/arming.py | 24 ++++++++++++++ crazyflie_examples/setup.cfg | 1 + crazyflie_interfaces/CMakeLists.txt | 1 + crazyflie_interfaces/srv/Arm.srv | 2 ++ crazyflie_py/crazyflie_py/crazyflie.py | 33 ++++++++++++++++++- docs2/overview.rst | 4 +++ 8 files changed, 96 insertions(+), 2 deletions(-) create mode 100644 crazyflie_examples/crazyflie_examples/arming.py create mode 100644 crazyflie_interfaces/srv/Arm.srv diff --git a/crazyflie/deps/crazyflie_tools b/crazyflie/deps/crazyflie_tools index 32218e742..a64ff9363 160000 --- a/crazyflie/deps/crazyflie_tools +++ b/crazyflie/deps/crazyflie_tools @@ -1 +1 @@ -Subproject commit 32218e7429651a681edf573d2ec24006fb07591e +Subproject commit a64ff93637f9c8ef7a909cada68c5dcb95b60e63 diff --git a/crazyflie/src/crazyflie_server.cpp b/crazyflie/src/crazyflie_server.cpp index a31a5e5e1..689cc542f 100644 --- a/crazyflie/src/crazyflie_server.cpp +++ b/crazyflie/src/crazyflie_server.cpp @@ -12,6 +12,7 @@ #include "crazyflie_interfaces/srv/land.hpp" #include "crazyflie_interfaces/srv/go_to.hpp" #include "crazyflie_interfaces/srv/notify_setpoints_stop.hpp" +#include "crazyflie_interfaces/srv/arm.hpp" #include "std_msgs/msg/string.hpp" #include "geometry_msgs/msg/twist.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" @@ -34,6 +35,7 @@ using crazyflie_interfaces::srv::Land; using crazyflie_interfaces::srv::GoTo; using crazyflie_interfaces::srv::UploadTrajectory; using crazyflie_interfaces::srv::NotifySetpointsStop; +using crazyflie_interfaces::srv::Arm; using std_srvs::srv::Empty; using motion_capture_tracking_interfaces::msg::NamedPoseArray; @@ -161,6 +163,7 @@ class CrazyflieROS service_go_to_ = node->create_service(name + "/go_to", std::bind(&CrazyflieROS::go_to, this, _1, _2), service_qos, callback_group_cf_srv); service_upload_trajectory_ = node->create_service(name + "/upload_trajectory", std::bind(&CrazyflieROS::upload_trajectory, this, _1, _2), service_qos, callback_group_cf_srv); service_notify_setpoints_stop_ = node->create_service(name + "/notify_setpoints_stop", std::bind(&CrazyflieROS::notify_setpoints_stop, this, _1, _2), service_qos, callback_group_cf_srv); + service_arm_ = node->create_service(name + "/arm", std::bind(&CrazyflieROS::arm, this, _1, _2), service_qos, callback_group_cf_srv); // Topics @@ -711,6 +714,16 @@ class CrazyflieROS cf_.notifySetpointsStop(request->remain_valid_millisecs); } + void arm(const std::shared_ptr request, + std::shared_ptr response) + { + RCLCPP_INFO(logger_, "[%s] arm(%d)", + name_.c_str(), + request->arm); + + cf_.sendArmingRequest(request->arm); + } + void on_logging_pose(uint32_t time_in_ms, const logPose* data) { if (publisher_pose_) { geometry_msgs::msg::PoseStamped msg; @@ -919,6 +932,7 @@ class CrazyflieROS rclcpp::Service::SharedPtr service_go_to_; rclcpp::Service::SharedPtr service_upload_trajectory_; rclcpp::Service::SharedPtr service_notify_setpoints_stop_; + rclcpp::Service::SharedPtr service_arm_; rclcpp::Subscription::SharedPtr subscription_cmd_vel_legacy_; rclcpp::Subscription::SharedPtr subscription_cmd_full_state_; @@ -1102,6 +1116,7 @@ class CrazyflieServer : public rclcpp::Node service_land_ = this->create_service("all/land", std::bind(&CrazyflieServer::land, this, _1, _2), service_qos, callback_group_all_srv_); service_go_to_ = this->create_service("all/go_to", std::bind(&CrazyflieServer::go_to, this, _1, _2), service_qos, callback_group_all_srv_); service_notify_setpoints_stop_ = this->create_service("all/notify_setpoints_stop", std::bind(&CrazyflieServer::notify_setpoints_stop, this, _1, _2), service_qos, callback_group_all_srv_); + service_arm_ = this->create_service("all/arm", std::bind(&CrazyflieServer::arm, this, _1, _2), service_qos, callback_group_all_srv_); // This is the last service to announce and can be used to check if the server is fully available service_emergency_ = this->create_service("all/emergency", std::bind(&CrazyflieServer::emergency, this, _1, _2), service_qos, callback_group_all_srv_); @@ -1209,6 +1224,21 @@ class CrazyflieServer : public rclcpp::Node } } + void arm(const std::shared_ptr request, + std::shared_ptr response) + { + RCLCPP_INFO(logger_, "[all] arm(%d)", + request->arm); + + for (int i = 0; i < broadcasts_num_repeats_; ++i) { + for (auto &bc : broadcaster_) { + auto &cfbc = bc.second; + cfbc->sendArmingRequest(request->arm); + } + std::this_thread::sleep_for(std::chrono::milliseconds(broadcasts_delay_between_repeats_ms_)); + } + } + void cmd_full_state_changed(const crazyflie_interfaces::msg::FullState::SharedPtr msg) { float x = msg->pose.position.x; @@ -1450,6 +1480,7 @@ class CrazyflieServer : public rclcpp::Node rclcpp::Service::SharedPtr service_land_; rclcpp::Service::SharedPtr service_go_to_; rclcpp::Service::SharedPtr service_notify_setpoints_stop_; + rclcpp::Service::SharedPtr service_arm_; std::map> crazyflies_; diff --git a/crazyflie_examples/crazyflie_examples/arming.py b/crazyflie_examples/crazyflie_examples/arming.py new file mode 100644 index 000000000..5eb12a985 --- /dev/null +++ b/crazyflie_examples/crazyflie_examples/arming.py @@ -0,0 +1,24 @@ +#!/usr/bin/env python + +from crazyflie_py import Crazyswarm + + +def main(): + swarm = Crazyswarm() + timeHelper = swarm.timeHelper + allcfs = swarm.allcfs + + # arm (one by one) + for cf in allcfs.crazyflies: + cf.arm(True) + timeHelper.sleep(1.0) + + timeHelper.sleep(2.0) + + # disarm (broadcast) + allcfs.arm(False) + timeHelper.sleep(5.0) + + +if __name__ == '__main__': + main() diff --git a/crazyflie_examples/setup.cfg b/crazyflie_examples/setup.cfg index f387d09cf..5a796d668 100644 --- a/crazyflie_examples/setup.cfg +++ b/crazyflie_examples/setup.cfg @@ -9,3 +9,4 @@ console_scripts = set_param = crazyflie_examples.set_param:main swap = crazyflie_examples.swap:main infinite_flight = crazyflie_examples.infinite_flight:main + arming = crazyflie_examples.arming:main diff --git a/crazyflie_interfaces/CMakeLists.txt b/crazyflie_interfaces/CMakeLists.txt index 0e92f4d09..1fb150d8a 100644 --- a/crazyflie_interfaces/CMakeLists.txt +++ b/crazyflie_interfaces/CMakeLists.txt @@ -39,6 +39,7 @@ rosidl_generate_interfaces(${PROJECT_NAME} "srv/UploadTrajectory.srv" "srv/RemoveLogging.srv" "srv/AddLogging.srv" + "srv/Arm.srv" DEPENDENCIES builtin_interfaces geometry_msgs std_msgs ADD_LINTER_TESTS ) diff --git a/crazyflie_interfaces/srv/Arm.srv b/crazyflie_interfaces/srv/Arm.srv new file mode 100644 index 000000000..e659ce1ff --- /dev/null +++ b/crazyflie_interfaces/srv/Arm.srv @@ -0,0 +1,2 @@ +bool arm +--- diff --git a/crazyflie_py/crazyflie_py/crazyflie.py b/crazyflie_py/crazyflie_py/crazyflie.py index 006dcb1bb..4c9a8fec3 100644 --- a/crazyflie_py/crazyflie_py/crazyflie.py +++ b/crazyflie_py/crazyflie_py/crazyflie.py @@ -15,7 +15,7 @@ from crazyflie_interfaces.msg import FullState, Position, Status, TrajectoryPolynomialPiece -from crazyflie_interfaces.srv import GoTo, Land,\ +from crazyflie_interfaces.srv import Arm, GoTo, Land,\ NotifySetpointsStop, StartTrajectory, Takeoff, UploadTrajectory from geometry_msgs.msg import Point import numpy as np @@ -133,6 +133,9 @@ def __init__(self, node, cfname, paramTypeDict): self.notifySetpointsStopService = node.create_client( NotifySetpointsStop, prefix + '/notify_setpoints_stop') self.notifySetpointsStopService.wait_for_service() + self.armService = node.create_client( + Arm, prefix + '/arm') + # self.armService.wait_for_service() self.setParamsService = node.create_client( SetParameters, '/crazyflie_server/set_parameters') self.setParamsService.wait_for_service() @@ -466,6 +469,19 @@ def notifySetpointsStop(self, remainValidMillisecs=100, groupMask=0): req.group_mask = groupMask self.notifySetpointsStopService.call_async(req) + def arm(self, arm=True): + """ + Arms the quadrotor, i.e. for a brushless or Bolt-based drone the + motors start spinning and flight is enabled. + + Args: + arm (boolean): True if the motors should be armed, False otherwise. + + """ + req = Arm.Request() + req.arm = arm + self.armService.call_async(req) + # def position(self): # """Returns the last true position measurement from motion capture. @@ -763,6 +779,8 @@ def __init__(self): self.goToService.wait_for_service() self.startTrajectoryService = self.create_client(StartTrajectory, 'all/start_trajectory') self.startTrajectoryService.wait_for_service() + self.armService = self.create_client(Arm, 'all/arm') + # self.armService.wait_for_service() self.setParamsService = self.create_client( SetParameters, '/crazyflie_server/set_parameters') self.setParamsService.wait_for_service() @@ -953,6 +971,19 @@ def startTrajectory(self, trajectoryId, req.relative = relative self.startTrajectoryService.call_async(req) + def arm(self, arm=True): + """ + Broadcasted arming of the quadrotors, i.e. for a brushless or Bolt-based drone the + motors start spinning and flight is enabled. + + Args: + arm (boolean): True if the motors should be armed, False otherwise. + + """ + req = Arm.Request() + req.arm = arm + self.armService.call_async(req) + def setParam(self, name, value): """Set parameter via broadcasts. See Crazyflie.setParam for details.""" try: diff --git a/docs2/overview.rst b/docs2/overview.rst index cc413fe1f..b504d7bfd 100644 --- a/docs2/overview.rst +++ b/docs2/overview.rst @@ -101,3 +101,7 @@ Support functionality with backends +---------------------+---------+-----------+---------+ | - LPS | Yes | Yes | No | +---------------------+---------+-----------+---------+ +| Misc | ++---------------------+---------+-----------+---------+ +| - Arming | Yes | No | n/a | ++---------------------+---------+-----------+---------+ \ No newline at end of file From 67491378446113b4316de926d60eb8fab21378c9 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Thu, 16 May 2024 17:01:03 +0200 Subject: [PATCH 135/162] fix flake8 --- crazyflie_py/crazyflie_py/crazyflie.py | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/crazyflie_py/crazyflie_py/crazyflie.py b/crazyflie_py/crazyflie_py/crazyflie.py index 4c9a8fec3..02f391f1b 100644 --- a/crazyflie_py/crazyflie_py/crazyflie.py +++ b/crazyflie_py/crazyflie_py/crazyflie.py @@ -471,8 +471,10 @@ def notifySetpointsStop(self, remainValidMillisecs=100, groupMask=0): def arm(self, arm=True): """ - Arms the quadrotor, i.e. for a brushless or Bolt-based drone the - motors start spinning and flight is enabled. + Arms the quadrotor. + + For a brushless or Bolt-based drone the motors start spinning and flight + is enabled. Args: arm (boolean): True if the motors should be armed, False otherwise. @@ -973,8 +975,10 @@ def startTrajectory(self, trajectoryId, def arm(self, arm=True): """ - Broadcasted arming of the quadrotors, i.e. for a brushless or Bolt-based drone the - motors start spinning and flight is enabled. + Broadcasted arming. + + For a brushless or Bolt-based drone the motors start spinning and flight + is enabled. Args: arm (boolean): True if the motors should be armed, False otherwise. From 67d4b8fe3fed454edbe743b79193e9476c279ea0 Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Tue, 21 May 2024 23:15:34 +0200 Subject: [PATCH 136/162] Update crazyflie-link-cpp * Avoid compiler warnings related to uninitialized memory * Improved handling of broadcasts --- crazyflie/deps/crazyflie_tools | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/crazyflie/deps/crazyflie_tools b/crazyflie/deps/crazyflie_tools index a64ff9363..5f6b39cc5 160000 --- a/crazyflie/deps/crazyflie_tools +++ b/crazyflie/deps/crazyflie_tools @@ -1 +1 @@ -Subproject commit a64ff93637f9c8ef7a909cada68c5dcb95b60e63 +Subproject commit 5f6b39cc50a7e6432435e0a807b7c07dbe5f5da6 From 97ed0a9579a4921ad62d19549bf058f83b279b5c Mon Sep 17 00:00:00 2001 From: julienthevenoz <125280576+julienthevenoz@users.noreply.github.com> Date: Thu, 23 May 2024 23:30:03 +0200 Subject: [PATCH 137/162] systemtests: add support for automatically querying timestamps --- systemtests/mcap_handler.py | 29 +++++-- systemtests/plotter_class.py | 163 +++++++++++++++-------------------- systemtests/test_flights.py | 13 ++- 3 files changed, 98 insertions(+), 107 deletions(-) diff --git a/systemtests/mcap_handler.py b/systemtests/mcap_handler.py index b5945a214..ed68d720c 100644 --- a/systemtests/mcap_handler.py +++ b/systemtests/mcap_handler.py @@ -7,7 +7,7 @@ class McapHandler: def __init__(self): - pass + self.takeoff_time = None def read_messages(self, input_bag: str): reader = rosbag2_py.SequentialReader() @@ -36,18 +36,32 @@ def write_mcap_to_csv(self, inputbag:str, outputfile:str): '''A method which translates an .mcap rosbag file format to a .csv file. Also modifies the timestamp to start at 0.0 instead of the wall time. Only written to translate the /tf topic but could easily be extended to other topics''' - - t_start = None + t_start_bag = None #this is the timestamp of the first message we read in the bag (doesn't mean it's exactly the start time of the bag but close enough ?) try: print("Translating .mcap to .csv") f = open(outputfile, 'w+') writer = csv.writer(f) + writer.writerow(["# t"," x"," y"," z"]) for topic, msg, timestamp in self.read_messages(inputbag): if topic =="/tf": - if t_start == None: - t_start = msg.transforms[0].header.stamp.sec + msg.transforms[0].header.stamp.nanosec *10**(-9) - t = msg.transforms[0].header.stamp.sec + msg.transforms[0].header.stamp.nanosec *10**(-9) - t_start + if t_start_bag == None: + t_start_bag = msg.transforms[0].header.stamp.sec + msg.transforms[0].header.stamp.nanosec *10**(-9) + t = msg.transforms[0].header.stamp.sec + msg.transforms[0].header.stamp.nanosec *10**(-9) -t_start_bag writer.writerow([t, msg.transforms[0].transform.translation.x, msg.transforms[0].transform.translation.y, msg.transforms[0].transform.translation.z]) + if topic == "/rosout": #and t_start_bag != None : + if msg.name == "crazyflie_server" and msg.function == "takeoff": + t = msg.stamp.sec + msg.stamp.nanosec *10**(-9) - t_start_bag + self.takeoff_time = t + #the takeoff message in simulation has a sligthly different name than IRL, so we need this to record the sim takeoff time + #BUT for some unknown reason the sim tests seem to work perfectly without even recording takeoff and adjusting the offset + #so I will leave this commented here just in case the sim tests have to be worked on + # if msg.name == "crazyflie_server" and msg.function == "_takeoff_callback": + # t = msg.stamp.sec + msg.stamp.nanosec *10**(-9) + # self.takeoff_time = t + # print(f"takeoff at {self.takeoff_time}") + + #write the "takeoff command" time as a comment on the last line + writer.writerow([f"### takeoff time : {self.takeoff_time}"]) f.close() except FileNotFoundError: print(f"McapHandler : file {outputfile} not found") @@ -67,5 +81,4 @@ def write_mcap_to_csv(self, inputbag:str, outputfile:str): args:Namespace = parser.parse_args() translator = McapHandler() - translator.write_mcap_to_csv(args.inputbag,args.outputfile) - + translator.write_mcap_to_csv(args.inputbag,args.outputfile) \ No newline at end of file diff --git a/systemtests/plotter_class.py b/systemtests/plotter_class.py index 42a8307df..96c632eda 100644 --- a/systemtests/plotter_class.py +++ b/systemtests/plotter_class.py @@ -2,6 +2,7 @@ import os import sys from matplotlib.backends.backend_pdf import PdfPages +from matplotlib.patches import Rectangle import numpy as np from crazyflie_py.uav_trajectory import Trajectory from pathlib import Path @@ -24,12 +25,12 @@ def __init__(self, sim_backend = False): self.SIM = sim_backend #indicates if we are plotting data from real life test or from a simulated test. Default is false (real life test) self.EPSILON = 0.15 # euclidian distance in [m] between ideal and recorded trajectory under which the drone has to stay to pass the test (NB : epsilon is doubled for multi_trajectory test) + self.ideal_takeoff = 0.6 + self.ideal_traj_start = 5.6 self.ALLOWED_DEV_POINTS = 0.05 #allowed percentage of datapoints whose deviation > EPSILON while still passing test (currently % for fig8 and 10% for mt) - self.DELAY_CONST_FIG8 = 1.3 #delay const used to temporally align the ideal traj with the real traj - self.DELAY_CONST_MT = 5.5 - if self.SIM : #It allows to temporally adjust the ideal and real trajectories on the graph. Could this be implemented in a better (not hardcoded) way ? - self.DELAY_CONST_FIG8 = -0.45 #for an unknown reason, the delay constants with the sim_backend is different - self.DELAY_CONST_MT = -0.3 + # if self.SIM : #It allows to temporally adjust the ideal and real trajectories on the graph. Could this be implemented in a better (not hardcoded) way ? + # self.DELAY_CONST_FIG8 = 0#-0.45 #for an unknown reason, the delay constants with the sim_backend is different + # self.DELAY_CONST_MT = 0#-0.3 self.ALTITUDE_CONST_FIG8 = 1 #this is the altitude given for the takeoff in figure8.py. I should find a better solution than a symbolic constant ? def file_guard(self, pdf_path): @@ -74,6 +75,21 @@ def read_csv_and_set_arrays(self, ideal_csvfile, rosbag_csvfile): self.adjust_arrays() bag_arrays_size = len(self.bag_times) print("number of datapoints in self.bag_*: ",bag_arrays_size) + + + #since the rosbag doesn't start at a reliable time, we need to adjust the ideal time array and the real one so that they aren't offset. For this we compare the time where the "takeoff" command was + # given to the crazyflie with the time of takeoff in the desired trajectory. With this we have the time-delay which we need to correct the offset (NB : empirically modified by 0.15 seconds this + #time-delay because that seems to be the delay between receiving the takeoff command and actually flying off) + with open(rosbag_csvfile) as f: + lines = f.readlines() + lastline = lines[-1] #get last line of csv file, where the takeoff time is written as comment + try: + self.takeoff_time = float(lastline[lastline.find(":") + 1 :]) #get the "takeoff" time from last line of csv + except ValueError: #if no takeoff was issued, there will be a "None" in the lastline which will produce value error when converting to float + print("Warning : No takeoff written in the lastline of the rosbag csv file : offset cannot be corrected.") + self.takeoff_time = 0 + offset1 = (self.ideal_takeoff - self.takeoff_time) - 0.15 + #####calculate ideal trajectory points corresponding to the times of recorded points @@ -81,23 +97,21 @@ def read_csv_and_set_arrays(self, ideal_csvfile, rosbag_csvfile): self.ideal_traj_y = np.empty([bag_arrays_size]) self.ideal_traj_z = np.empty([bag_arrays_size]) self.euclidian_dist = np.empty([bag_arrays_size]) - no_match_in_idealcsv=[] - delay = 0 - if self.test_name == "fig8": - delay = self.DELAY_CONST_FIG8 - elif self.test_name == "mt": - delay = self.DELAY_CONST_MT - + delay = offset1 + # if self.test_name == "fig8" and self.SIM: + # delay = self.DELAY_CONST_FIG8 + # elif self.test_name == "mt" and self.SIM: + # delay = self.DELAY_CONST_MT + for i in range(bag_arrays_size): try: - pos = self.ideal_traj_csv.eval(self.bag_times[i] - delay).pos + pos = self.ideal_traj_csv.eval(self.bag_times[i] + delay).pos except AssertionError: no_match_in_idealcsv.append(i) pos = [0,0,0] #for all recorded datapoints who cannot be matched to a corresponding ideal position we assume the drone is on its ground start position (ie those datapoints are before takeoff or after landing) - self.ideal_traj_x[i], self.ideal_traj_y[i], self.ideal_traj_z[i]= pos[0], pos[1], pos[2] @@ -136,44 +150,33 @@ def no_match_warning(self, unmatched_values:list): def adjust_arrays(self): - ''' Method that trims the self.bag_* attributes to get rid of the datapoints where the drone is immobile on the ground and makes self.bag_times start at 0 [s]''' + ''' Method that adjusts the self.bag_* attributes to get rid of the datapoints whose timestamp don't make sense''' print(f"rosbag initial length {(self.bag_times[-1]-self.bag_times[0]) }s") - #find the takeoff time and landing times - ground_level = self.bag_z[0] - airborne = False - takeoff_index = None - landing_index = None - i=0 - for z_coord in self.bag_z: - if not(airborne) and z_coord > ground_level + 0.05: #when altitude of the drone is 5cm above ground level, it started takeoff - takeoff_index = i - airborne = True - print(f"takeoff time is {self.bag_times[takeoff_index]}s") - if airborne and z_coord < ground_level + 0.05: #find when it lands again - landing_index = i - print(f"landing time is {self.bag_times[landing_index]}s") - break - i+=1 - - - assert (takeoff_index != None) and (landing_index != None), "Plotter : couldn't find drone takeoff or landing" + #recurring problem : some messages recorded from /tf arrive way later (2-4 seconds) than when they were emitted, which makes a mess in the timestamps + #zB we have timestamps (in s) : 5.1, 5.2, 5.3, !!!3.7, 3.9, 4.5, 4.9!!!, 5.4, 5.5, 5.6, 5.7 etc. This bug almost always occurs in the first seconds of the recording & generally only happens once per recording + #and only concerns a very small percentage of datapoints (10-40 over about 1800 total), so it is not a big deal. We do not know if this bug stems from the Rosbag recording, from how /tf behaves or from the radio - ####get rid of datapoints before takeoff and after landing in bag_times, bag_x, bag_y, bag_y + #Since we use a lineplot, we need to get rid of these datapoints that are in an order that doesn't make sense so that the plot can be readable + self.nonsensical = [] #list of indexes of datapoints who arrived too late, meaning their timestamp doesn't follow the ones before + time = -1 + for index,t in enumerate(self.bag_times): + if t > time: + time = t + else: + self.nonsensical.append(index) - assert len(self.bag_times) == len(self.bag_x) == len(self.bag_y) == len(self.bag_z), "Plotter : self.bag_* aren't the same size before trimming" - index_arr = np.arange(len(self.bag_times)) - slicing_arr = np.delete(index_arr, index_arr[takeoff_index:landing_index+1]) #in our slicing array we take out all the indexes of when the drone is in flight so that it only contains the indexes of when the drone is on the ground - # #delete the datapoints where drone is on the ground - # self.bag_times = np.delete(self.bag_times, slicing_arr) - # self.bag_x = np.delete(self.bag_x, slicing_arr) - # self.bag_y = np.delete(self.bag_y, slicing_arr) - # self.bag_z = np.delete(self.bag_z, slicing_arr) + if self.nonsensical: #if self.nonsensical is not empty + self.bag_times = np.delete(self.bag_times, self.nonsensical) + self.bag_x = np.delete(self.bag_x, self.nonsensical) + self.bag_y = np.delete(self.bag_y, self.nonsensical) + self.bag_z = np.delete(self.bag_z, self.nonsensical) + print(f"{len(self.nonsensical)} datapoints were ignored because because their timestamp wasn't in the good order (delayed message problem). They go from index {self.nonsensical[0]} to {self.nonsensical[-1]}") - assert len(self.bag_times) == len(self.bag_x) == len(self.bag_y) == len(self.bag_z), "Plotter : self.bag_* aren't the same size after trimming" + assert len(self.bag_times) == len(self.bag_x) == len(self.bag_y) == len(self.bag_z), "Plotter : self.bag_* aren't the same size after adjusting arrays" print(f"trimmed bag_times starts: {self.bag_times[0]}s and ends: {self.bag_times[-1]}, size: {len(self.bag_times)}") @@ -200,15 +203,11 @@ def create_figures(self, ideal_csvfile:str, rosbag_csvfile:str, pdfname:str, ove self.read_csv_and_set_arrays(ideal_csvfile,rosbag_csvfile) - offset_list = self.find_temporal_offset() - if len(offset_list) == 1: - offset_string = f"temporal offset : {offset_list[0]}s \n" - elif len(offset_list) ==2: - offset_string = f"averaged temporal offset : {(offset_list[0]+offset_list[1])/2}s \n" - passed="failed" - if self.test_passed(): - passed = "passed" + test_result="failed" + passed, percentage = self.test_passed() + if passed: + test_result = "passed" #create PDF to save figures if(pdfname[-4:] != ".pdf"): @@ -228,14 +227,19 @@ def create_figures(self, ideal_csvfile:str, rosbag_csvfile:str, pdfname:str, ove name = "Unnamed test" print("Plotter : test name not defined") - text = f'{name} trajectory test' + title = f'{name} trajectory test' + if self.SIM: + title += "(SIMULATION)" title_text_settings = f'Settings:\n' title_text_parameters = f'Parameters:\n' for key, value in self.params.items(): title_text_parameters += f" {key}: {value}\n" - title_text_results = f'Results: test {passed}\n' + offset_string + f'max error : ' + title_text_results = f'Results: test {test_result}\n' + f"acceptable deviation EPSILON: {self.EPSILON}[m]\n" + title_text_results += f"percentage of points > EPSILON : {percentage:.4f}%\n" + f"average error : {np.mean(self.euclidian_dist):.6f} [m]\n" + title_text_results += f"median error : {np.median(self.euclidian_dist):.6f} [m]\n" + f"max error : {np.max(self.euclidian_dist):.6f} [m]\n" + - title_text = text + "\n" + title_text_settings + "\n" + title_text_parameters + "\n" + title_text_results + title_text = title + "\n" + title_text_settings + "\n" + title_text_parameters + "\n" + title_text_results fig = plt.figure(figsize=(5,8)) fig.text(0.1, 0.1, title_text, size=11) @@ -249,14 +253,12 @@ def create_figures(self, ideal_csvfile:str, rosbag_csvfile:str, pdfname:str, ove ax.plot(self.bag_times, self.bag_x, label='Recorded trajectory') ax.set_xlabel('time [s]') ax.set_ylabel('x position [m]') - ax.set_title("Trajectory x") - + ax.set_title("Trajectory x") ax.grid(which='major', color='#DDDDDD', linewidth=0.8) ax.grid(which='minor', color='#EEEEEE', linestyle=':', linewidth=0.5) ax.minorticks_on() fig.tight_layout(pad = 4) - fig.legend() - + fig.legend() pdf_pages.savefig(fig) fig2, ax2 = plt.subplots() @@ -264,7 +266,7 @@ def create_figures(self, ideal_csvfile:str, rosbag_csvfile:str, pdfname:str, ove ax2.plot(self.bag_times, self.bag_y, label='Recorded trajectory') ax2.set_xlabel('time [s]') ax2.set_ylabel('y position [m]') - ax2.set_title("Trajectory y") + ax2.set_title("trajectory y") ax2.grid(which='major', color='#DDDDDD', linewidth=0.8) ax2.grid(which='minor', color='#EEEEEE', linestyle=':', linewidth=0.5) ax2.minorticks_on() @@ -324,52 +326,31 @@ def create_figures(self, ideal_csvfile:str, rosbag_csvfile:str, pdfname:str, ove plt.tight_layout(pad=4) pdf_pages.savefig(fig6) - - pdf_pages.close() print("Results saved in " + pdfname) - def test_passed(self) -> bool : - '''Returns True if the deviation between recorded and ideal trajectories of the drone didn't exceed EPSILON for more than ALLOWED_DEV_POINTS % of datapoints. - Returns False otherwise ''' + def test_passed(self) -> tuple : + '''Returns a tuple containing (bool:passed, float:percentage). If the deviation between recorded and ideal trajectories of the drone didn't exceed + EPSILON for more than ALLOWED_DEV_POINTS % of datapoints, the boolean passed is True. Otherwise it is false. float:percentage is the percentage + of points which whose deviation is less than EPSILON''' nb_dev_points = len(self.deviation) threshold = self.ALLOWED_DEV_POINTS * len(self.bag_times) percentage = (len(self.deviation) / len(self.bag_times)) * 100 if nb_dev_points < threshold: - print(f"Test {self.test_name} passed : {percentage:8.4f}% of datapoints had deviation larger than {self.EPSILON}m ({self.ALLOWED_DEV_POINTS * 100}% max for pass)") - return True + print(f"Test {self.test_name} passed : {percentage:.4f}% of datapoints had deviation larger than {self.EPSILON}m ({self.ALLOWED_DEV_POINTS * 100}% max for pass)") + return (True, percentage) else: print(f"Test {self.test_name} failed : The deviation between ideal and recorded trajectories is greater than {self.EPSILON}m for {percentage:8.4f}% of datapoints") - return False + return (False, percentage) - def find_temporal_offset(self) -> list : - ''' Returns a list containing the on-graph temporal offset between real and ideal trajectory. If offset is different for x and y axis, returns both in the same list''' - peak_x = self.bag_x.argmax() #find index of extremum value of real trajectory along x axis - peak_time_x = self.bag_times[peak_x] #find corresponding time - peak_x_ideal = self.ideal_traj_x.argmax() #find index of extremum value of ideal traj along x axis - peak_time_x_ideal = self.bag_times[peak_x_ideal] #find corresponding time - offset_x = peak_time_x_ideal - peak_time_x - - peak_y = self.bag_y.argmax() #find index of extremum value of real trajectory along y ayis - peak_time_y = self.bag_times[peak_y] #find corresponding time - peak_y_ideal = self.ideal_traj_y.argmax() #find index of extremum value of ideal traj along y ayis - peak_time_y_ideal = self.bag_times[peak_y_ideal] #find corresponding time - offset_y = peak_time_y_ideal - peak_time_y - - if offset_x == offset_y: - print(f"On-graph temporal offset is {offset_x}s, delay const is {self.DELAY_CONST_FIG8} so uncorrected/absolute offset is {offset_x-self.DELAY_CONST_FIG8}") - return [offset_x] - else : - print(f"On-graph temporal offsets are {offset_x} & {offset_y} secs, delay const is {self.DELAY_CONST_FIG8}") - return [offset_x, offset_y] if __name__=="__main__": - #command line utility + # command line utility from argparse import ArgumentParser, Namespace parser = ArgumentParser(description="Creates a pdf plotting the recorded trajectory of a drone against its desired trajectory") @@ -384,6 +365,4 @@ def find_temporal_offset(self) -> list : plotter.create_figures(args.desired_trajectory, args.recorded_trajectory, args.pdf, overwrite=args.overwrite) if args.open: import subprocess - subprocess.call(["xdg-open", args.pdf]) - - + subprocess.call(["xdg-open", args.pdf]) \ No newline at end of file diff --git a/systemtests/test_flights.py b/systemtests/test_flights.py index eb307cb49..619153df7 100644 --- a/systemtests/test_flights.py +++ b/systemtests/test_flights.py @@ -141,7 +141,7 @@ def record_start_and_clean(self, testname:str, max_wait:int): # src = f"source {str(self.ros2_ws)}/install/setup.bash" try: - command = f"{self.src} && ros2 bag record -s mcap -o test_{testname} /tf" + command = f"{self.src} && ros2 bag record -s mcap -o test_{testname} /tf /rosout" record_bag = Popen(command, shell=True, stderr=PIPE, stdout=True, text=True, cwd= self.ros2_ws / "results/", start_new_session=True, executable="/bin/bash") atexit.register(clean_process, record_bag) @@ -202,12 +202,11 @@ def test_figure8(self): test_passed = self.translate_plot_and_check("figure8") assert test_passed, "figure8 test failed : deviation larger than epsilon" - - def test_multi_trajectory(self): - self.test_file = "multi_trajectory_ideal_traj0.csv" - self.record_start_and_clean("multi_trajectory", 80) - test_passed = self.translate_plot_and_check("multi_trajectory") - assert test_passed, "multitrajectory test failed : deviation larger than epsilon" + # def test_multi_trajectory(self): + # self.test_file = "multi_trajectory_traj0_ideal.csv" + # self.record_start_and_clean("multi_trajectory", 80) + # test_passed = self.translate_plot_and_check("multi_trajectory") + # assert test_passed, "multitrajectory test failed : deviation larger than epsilon" From 1a3a98104dbb6c6bebbc025b2332abbce4610b4b Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Fri, 24 May 2024 12:21:22 +0200 Subject: [PATCH 138/162] Fix regression where teleop node would crash due to missing configuration file --- crazyflie/config/teleop.yaml | 2 +- crazyflie/launch/launch.py | 7 ++++++- 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/crazyflie/config/teleop.yaml b/crazyflie/config/teleop.yaml index 218efb498..a9523e2a5 100644 --- a/crazyflie/config/teleop.yaml +++ b/crazyflie/config/teleop.yaml @@ -1,7 +1,7 @@ /teleop: ros__parameters: frequency: 100 # set to 0, to disable manual flight modes - mode: "cmd_vel_world" # one of cmd_rpy, cmd_vel_world + mode: "none" # one of none, cmd_rpy, cmd_vel_world cmd_rpy: roll: axis: 5 diff --git a/crazyflie/launch/launch.py b/crazyflie/launch/launch.py index d5df4b37d..be2ed1339 100644 --- a/crazyflie/launch/launch.py +++ b/crazyflie/launch/launch.py @@ -73,6 +73,11 @@ def generate_launch_description(): with open('tmp_motion_capture.yaml', 'w') as outfile: yaml.dump(motion_capture_content, outfile, default_flow_style=False, sort_keys=False) + telop_yaml_path = os.path.join( + get_package_share_directory('crazyflie'), + 'config', + 'teleop.yaml') + return LaunchDescription([ DeclareLaunchArgument('backend', default_value='cpp'), DeclareLaunchArgument('debug', default_value='False'), @@ -102,7 +107,7 @@ def generate_launch_description(): # ('cmd_full_state', 'cf6/cmd_full_state'), # ('notify_setpoints_stop', 'cf6/notify_setpoints_stop'), ], - parameters= [PythonExpression(["'teleop.yaml' if '", LaunchConfiguration('teleop_yaml_file'), "' == '' else '", LaunchConfiguration('teleop_yaml_file'), "'"])], + parameters= [PythonExpression(["'" + telop_yaml_path +"' if '", LaunchConfiguration('teleop_yaml_file'), "' == '' else '", LaunchConfiguration('teleop_yaml_file'), "'"])], ), Node( package='joy', From 314f089f080f9f764e15c3bacf8b2af899fc983c Mon Sep 17 00:00:00 2001 From: Wolfgang Hoenig Date: Mon, 27 May 2024 22:23:17 +0200 Subject: [PATCH 139/162] teleop: add support for arming --- crazyflie/config/teleop.yaml | 2 ++ crazyflie/launch/launch.py | 1 + crazyflie/scripts/gui.py | 2 ++ crazyflie/src/teleop.cpp | 68 +++++++++++++++++++++--------------- 4 files changed, 45 insertions(+), 28 deletions(-) diff --git a/crazyflie/config/teleop.yaml b/crazyflie/config/teleop.yaml index a9523e2a5..4b072aa36 100644 --- a/crazyflie/config/teleop.yaml +++ b/crazyflie/config/teleop.yaml @@ -53,4 +53,6 @@ button: 6 # 6 back emergency: button: 1 # 1 red + arm: + button: 3 # yellow diff --git a/crazyflie/launch/launch.py b/crazyflie/launch/launch.py index be2ed1339..9761c5535 100644 --- a/crazyflie/launch/launch.py +++ b/crazyflie/launch/launch.py @@ -100,6 +100,7 @@ def generate_launch_description(): name='teleop', remappings=[ ('emergency', 'all/emergency'), + ('arm', 'all/arm'), ('takeoff', 'all/takeoff'), ('land', 'all/land'), # uncomment to manually control (and update teleop.yaml) diff --git a/crazyflie/scripts/gui.py b/crazyflie/scripts/gui.py index a0f221b71..54304520c 100755 --- a/crazyflie/scripts/gui.py +++ b/crazyflie/scripts/gui.py @@ -194,6 +194,8 @@ def on_status(self, msg, name) -> None: supervisor_text += "auto-arm; " if msg.supervisor_info & Status.SUPERVISOR_INFO_CAN_FLY: supervisor_text += "can fly; " + else: + status_ok = False if msg.supervisor_info & Status.SUPERVISOR_INFO_IS_FLYING: supervisor_text += "is flying; " is_flying = True diff --git a/crazyflie/src/teleop.cpp b/crazyflie/src/teleop.cpp index 59ce47538..e07d01e99 100755 --- a/crazyflie/src/teleop.cpp +++ b/crazyflie/src/teleop.cpp @@ -7,6 +7,7 @@ #include "std_srvs/srv/empty.hpp" #include "crazyflie_interfaces/srv/takeoff.hpp" #include "crazyflie_interfaces/srv/land.hpp" +#include "crazyflie_interfaces/srv/arm.hpp" #include #include "geometry_msgs/msg/twist.hpp" #include "crazyflie_interfaces/msg/full_state.hpp" @@ -19,26 +20,13 @@ using std::placeholders::_1; using std_srvs::srv::Empty; using crazyflie_interfaces::srv::Takeoff; using crazyflie_interfaces::srv::Land; +using crazyflie_interfaces::srv::Arm; using crazyflie_interfaces::srv::NotifySetpointsStop; using crazyflie_interfaces::msg::FullState; using namespace std::chrono_literals; using namespace Eigen; -namespace Xbox360Buttons { - - enum { Green = 0, - Red = 1, - Blue = 2, - Yellow = 3, - LB = 4, - RB = 5, - Back = 6, - Start = 7, - COUNT = 8, - }; -} - class TeleopNode : public rclcpp::Node { public: @@ -93,6 +81,10 @@ class TeleopNode : public rclcpp::Node this->declare_parameter("emergency.button"); this->get_parameter("emergency.button", emergency_button); + this->declare_parameter("arm.button"); + this->get_parameter("arm.button", arm_button); + is_armed_ = false; + on_mode_switched(); dt_ = 1.0f/frequency_; @@ -107,6 +99,7 @@ class TeleopNode : public rclcpp::Node } client_emergency_ = this->create_client("emergency"); + client_arm_ = this->create_client("arm"); client_takeoff_ = this->create_client("takeoff"); client_land_ = this->create_client("land"); client_notify_setpoints_stop_ = this->create_client("notify_setpoints_stop"); @@ -153,6 +146,7 @@ class TeleopNode : public rclcpp::Node int land_button; int emergency_button; + int arm_button; void on_parameter_event(const rcl_interfaces::msg::ParameterEvent &event) { @@ -215,21 +209,26 @@ class TeleopNode : public rclcpp::Node void joyChanged(const sensor_msgs::msg::Joy::SharedPtr msg) { + static std::vector lastButtonState; - static std::vector lastButtonState(Xbox360Buttons::COUNT); - - std::cout << "takeoff_paras_.button: " << takeoff_paras_.button << std::endl; - if (msg->buttons.size() >= Xbox360Buttons::COUNT && lastButtonState.size() >= Xbox360Buttons::COUNT) { - if (msg->buttons[emergency_button] == 1 && lastButtonState[emergency_button] == 0) { - emergency(); - } + auto checkButton = [&](int button) { + return msg->buttons.size() > button && + msg->buttons[button] == 1 && + lastButtonState.size() > button && + lastButtonState[button] == 0; + }; - if (msg->buttons[takeoff_paras_.button] == 1 && lastButtonState[takeoff_paras_.button] == 0) { - takeoff(); - } - if (msg->buttons[land_button] == 1 && lastButtonState[land_button] == 0) { - land(); - } + if (checkButton(emergency_button)) { + emergency(); + } + if (checkButton(arm_button)) { + arm(); + } + if (checkButton(takeoff_paras_.button)) { + takeoff(); + } + if (checkButton(land_button)) { + land(); } lastButtonState = msg->buttons; @@ -243,7 +242,6 @@ class TeleopNode : public rclcpp::Node else { twist_.angular.z = auto_yaw_rate_; } - } sensor_msgs::msg::Joy::_axes_type::value_type getAxis(const sensor_msgs::msg::Joy::SharedPtr &msg, Axis a) @@ -278,6 +276,18 @@ class TeleopNode : public rclcpp::Node client_emergency_->async_send_request(request); } + void arm() + { + if (!client_arm_->service_is_ready()) { + RCLCPP_ERROR(get_logger(), "Arm service not ready!"); + return; + } + auto request = std::make_shared(); + request->arm = !is_armed_; + client_arm_->async_send_request(request); + is_armed_ = !is_armed_; + } + void takeoff() { if (!client_takeoff_->service_is_ready()) { @@ -373,6 +383,7 @@ class TeleopNode : public rclcpp::Node rclcpp::Subscription::SharedPtr subscription_; rclcpp::Client::SharedPtr client_emergency_; + rclcpp::Client::SharedPtr client_arm_; rclcpp::Client::SharedPtr client_takeoff_; rclcpp::Client::SharedPtr client_land_; rclcpp::Client::SharedPtr client_notify_setpoints_stop_; @@ -393,6 +404,7 @@ class TeleopNode : public rclcpp::Node float dt_; bool is_low_level_flight_active_; double auto_yaw_rate_; + bool is_armed_; }; int main(int argc, char *argv[]) From 832ad006508bcd55e95d057133de549181997aaf Mon Sep 17 00:00:00 2001 From: knmcguire Date: Tue, 28 May 2024 12:46:37 +0200 Subject: [PATCH 140/162] readd get_param --- crazyflie_py/crazyflie_py/crazyflie.py | 43 ++++++++++++++++---------- 1 file changed, 27 insertions(+), 16 deletions(-) diff --git a/crazyflie_py/crazyflie_py/crazyflie.py b/crazyflie_py/crazyflie_py/crazyflie.py index 006dcb1bb..aff4379a5 100644 --- a/crazyflie_py/crazyflie_py/crazyflie.py +++ b/crazyflie_py/crazyflie_py/crazyflie.py @@ -484,26 +484,37 @@ def notifySetpointsStop(self, remainValidMillisecs=100, groupMask=0): # '/world', '/cf' + str(self.id), rospy.Time(0)) # return np.array(position) - # def getParam(self, name): - # """Returns the current value of the onboard named parameter. + def getParam(self, name): + """ + Get the current value of the onboard named parameter. - # Parameters are named values of various primitive C types that control - # the firmware's behavior. For more information, see - # https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/userguides/logparam/. + Parameters are named values of various primitive C types that control + the firmware's behavior. For more information, see + https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/userguides/logparam/. - # Parameters are read at system startup over the radio and cached. - # The ROS launch file can also be used to set parameter values at startup. - # Subsequent calls to :meth:`setParam()` will update the cached value. - # However, if the parameter changes for any other reason, the cached value - # might become stale. This situation is not common. + Parameters are read at system startup over the radio and cached. + The ROS launch file can also be used to set parameter values at startup. + Subsequent calls to :meth:`setParam()` will update the cached value. + However, if the parameter changes for any other reason, the cached value + might become stale. This situation is not common. - # Args: - # name (str): The parameter's name. + Args: + name (str): The parameter's name. - # Returns: - # value (Any): The parameter's value. - # """ - # return rospy.get_param(self.prefix + '/' + name) + Returns: + value (Any): The parameter's value. + """ + param_name = self.prefix[1:] + '.params.' + name + req = GetParameters.Request() + req.names = [param_name] + future = self.getParamsService.call_async(req) + rclpy.spin_until_future_complete(self.node, future) + param_type = self.paramTypeDict[name] + if param_type == ParameterType.PARAMETER_INTEGER: + param_value = future.result().values[0].integer_value + elif param_type == ParameterType.PARAMETER_DOUBLE: + param_value = future.result().values[0].double_value + return param_value def setParam(self, name, value): """ From 92906489b2312b5aad0440e4910b161d4fe4aabf Mon Sep 17 00:00:00 2001 From: knmcguire Date: Tue, 28 May 2024 12:59:11 +0200 Subject: [PATCH 141/162] add blank line --- crazyflie_py/crazyflie_py/crazyflie.py | 1 + 1 file changed, 1 insertion(+) diff --git a/crazyflie_py/crazyflie_py/crazyflie.py b/crazyflie_py/crazyflie_py/crazyflie.py index aff4379a5..d0e733bd0 100644 --- a/crazyflie_py/crazyflie_py/crazyflie.py +++ b/crazyflie_py/crazyflie_py/crazyflie.py @@ -503,6 +503,7 @@ def getParam(self, name): Returns: value (Any): The parameter's value. + """ param_name = self.prefix[1:] + '.params.' + name req = GetParameters.Request() From dddf703ca798a3e09c832dd5d47d327df51f3d7e Mon Sep 17 00:00:00 2001 From: knmcguire Date: Tue, 28 May 2024 13:11:10 +0200 Subject: [PATCH 142/162] check param in setparam script --- crazyflie_examples/crazyflie_examples/set_param.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/crazyflie_examples/crazyflie_examples/set_param.py b/crazyflie_examples/crazyflie_examples/set_param.py index 69c49daf0..db5ca347b 100644 --- a/crazyflie_examples/crazyflie_examples/set_param.py +++ b/crazyflie_examples/crazyflie_examples/set_param.py @@ -12,6 +12,8 @@ def main(): for cf in allcfs.crazyflies: cf.setParam('led.bitmask', 128) timeHelper.sleep(1.0) + if cf.getParam('led.bitmask') != 128: + print('LED of cf', cf.id, 'is not disabled!') timeHelper.sleep(2.0) From 7720abb183f89b3a854be645a8853d965663bb3f Mon Sep 17 00:00:00 2001 From: knmcguire Date: Tue, 28 May 2024 16:10:50 +0200 Subject: [PATCH 143/162] fix issue with not finding parameter service --- crazyflie_py/crazyflie_py/crazyflie.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/crazyflie_py/crazyflie_py/crazyflie.py b/crazyflie_py/crazyflie_py/crazyflie.py index d0e733bd0..5402bd21b 100644 --- a/crazyflie_py/crazyflie_py/crazyflie.py +++ b/crazyflie_py/crazyflie_py/crazyflie.py @@ -141,11 +141,11 @@ def __init__(self, node, cfname, paramTypeDict): self.status = {} # Query some settings - getParamsService = node.create_client(GetParameters, '/crazyflie_server/get_parameters') - getParamsService.wait_for_service() + self.getParamsService = node.create_client(GetParameters, '/crazyflie_server/get_parameters') + self.getParamsService.wait_for_service() req = GetParameters.Request() req.names = ['robots.{}.initial_position'.format(cfname), 'robots.{}.uri'.format(cfname)] - future = getParamsService.call_async(req) + future = self.getParamsService.call_async(req) while rclpy.ok(): rclpy.spin_once(node) if future.done(): From c235e25f13f473ed247c3ebef1d4f0d5f63ab87d Mon Sep 17 00:00:00 2001 From: knmcguire Date: Wed, 29 May 2024 09:45:10 +0200 Subject: [PATCH 144/162] add try except for getparam --- crazyflie_py/crazyflie_py/crazyflie.py | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/crazyflie_py/crazyflie_py/crazyflie.py b/crazyflie_py/crazyflie_py/crazyflie.py index 5402bd21b..7471028d2 100644 --- a/crazyflie_py/crazyflie_py/crazyflie.py +++ b/crazyflie_py/crazyflie_py/crazyflie.py @@ -511,10 +511,16 @@ def getParam(self, name): future = self.getParamsService.call_async(req) rclpy.spin_until_future_complete(self.node, future) param_type = self.paramTypeDict[name] - if param_type == ParameterType.PARAMETER_INTEGER: - param_value = future.result().values[0].integer_value - elif param_type == ParameterType.PARAMETER_DOUBLE: - param_value = future.result().values[0].double_value + try: + if param_type == ParameterType.PARAMETER_INTEGER: + param_value = future.result().values[0].integer_value + elif param_type == ParameterType.PARAMETER_DOUBLE: + param_value = future.result().values[0].double_value + except KeyError as e: + self.get_logger().warn(f'(crazyflie.py)getParam : keyError raised {e}') + except Exception as e: + self.get_logger().warn(f'(crazyflie.py)getParam : exception raised {e}') + return param_value def setParam(self, name, value): From 1118919d03b7fd5c302e440665cbabe86e41b203 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Wed, 29 May 2024 09:46:35 +0200 Subject: [PATCH 145/162] fix too long line --- crazyflie_py/crazyflie_py/crazyflie.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/crazyflie_py/crazyflie_py/crazyflie.py b/crazyflie_py/crazyflie_py/crazyflie.py index 7471028d2..2e653dee3 100644 --- a/crazyflie_py/crazyflie_py/crazyflie.py +++ b/crazyflie_py/crazyflie_py/crazyflie.py @@ -141,7 +141,8 @@ def __init__(self, node, cfname, paramTypeDict): self.status = {} # Query some settings - self.getParamsService = node.create_client(GetParameters, '/crazyflie_server/get_parameters') + self.getParamsService = node.create_client( + GetParameters, '/crazyflie_server/get_parameters') self.getParamsService.wait_for_service() req = GetParameters.Request() req.names = ['robots.{}.initial_position'.format(cfname), 'robots.{}.uri'.format(cfname)] From 331a4ece9643407e6dc3cc03c1b2c72de3e633bf Mon Sep 17 00:00:00 2001 From: knmcguire Date: Thu, 30 May 2024 10:58:23 +0200 Subject: [PATCH 146/162] add text about motion capture --- crazyflie/config/motion_capture.yaml | 4 ++-- docs2/usage.rst | 36 +++++++++++++++++++++------- 2 files changed, 30 insertions(+), 10 deletions(-) diff --git a/crazyflie/config/motion_capture.yaml b/crazyflie/config/motion_capture.yaml index c9324ea41..ea20e4b44 100644 --- a/crazyflie/config/motion_capture.yaml +++ b/crazyflie/config/motion_capture.yaml @@ -1,10 +1,10 @@ /motion_capture_tracking: ros__parameters: + # one of "optitrack", "optitrack_closed_source", "vicon", "qualisys", "nokov", "vrpn", "motionanalysis" type: "optitrack" + # Specify the hostname or IP of the computer running the motion capture software hostname: "141.23.110.143" - mode: "libobjecttracker" # one of motionCapture,libRigidBodyTracker - topics: poses: qos: diff --git a/docs2/usage.rst b/docs2/usage.rst index 74caf33d9..e48acd263 100644 --- a/docs2/usage.rst +++ b/docs2/usage.rst @@ -12,8 +12,8 @@ Usage .. warning:: - If you work in a shared network (lab, classroom) or similar, you might want to avoid - controlling other robots. This is in particular true for simulation. In this case, + If you work in a shared network (lab, classroom) or similar, you might want to avoid + controlling other robots. This is in particular true for simulation. In this case, you can use .. code-block:: bash @@ -29,7 +29,7 @@ Usage Configuration ------------- -All configuration files are in crazyflie/config. +All configuration files are in crazyflie/config. * crazyflies.yaml : setting up everything related to the robots. * server.yaml : setting up everything related to the server. @@ -40,7 +40,7 @@ crazyflies.yaml ~~~~~~~~~~~~~~~ Each crazyflie should have an unique URI which can `be changed in Bitcraze's CFclient `_. -They can also be enabled in case you don't want the server to connect with it. +They can also be enabled in case you don't want the server to connect with it. .. code-block:: yaml @@ -109,13 +109,33 @@ The yaml file also contain an 'all' field, in case you have parameters or loggin estimator: 2 # 1: complementary, 2: kalman controller: 2 # 1: PID, 2: mellinger -The above also contains an example of the firmware_logging field, where default topics can be enabled or custom topics based on the `existing log toc of the crazyflie `_. -Moreover, it also contains the firmware_params field, where parameters can be set at startup. -Also see the `parameter list of the crazyflie `_ for that. +The above also contains an example of the firmware_logging field, where default topics can be enabled or custom topics based on the `existing log toc of the crazyflie `_. +Moreover, it also contains the firmware_params field, where parameters can be set at startup. +Also see the `parameter list of the crazyflie `_ for that. Mind that you can also place the firmware_params and firmware_logging fields per crazyflie in 'robots' or the 'robot_types' field. -The server node will upon initialization, first look at the params/logs from the individual crazyflie's settings, then the robot_types, and then anything in 'all' which has lowest priority. +The server node will upon initialization, first look at the params/logs from the individual crazyflie's settings, then the robot_types, and then anything in 'all' which has lowest priority. + +Positioning +----------- + +Motion capture +~~~~~~~~~~~~~~ + +If you have a motion capture system, you can input the specifics in the motion_capture.yaml file. + +.. code-block:: yaml + /motion_capture_tracking: + ros__parameters: + type: "optitrack" + hostname: "optitrackPC" + +'Type' can replaced by "optitrack", "vicon", "qualisys" or any of the other supported motion capture systems of the `motion capture tracking package `_. +'hostname' is the hostname of the computer running the motion capture software which can either be the PC name or the IP. + + + Simulation From 76248e96866eb4212572e22ed3fd2f4381d04e24 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Thu, 30 May 2024 17:10:58 +0200 Subject: [PATCH 147/162] add text about other positoing systems --- docs2/usage.rst | 44 ++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 44 insertions(+) diff --git a/docs2/usage.rst b/docs2/usage.rst index e48acd263..edc065909 100644 --- a/docs2/usage.rst +++ b/docs2/usage.rst @@ -120,6 +120,10 @@ The server node will upon initialization, first look at the params/logs from the Positioning ----------- +The Crazyflie can be positioned in different ways, including motion capture and onboard positioning. +This blogpost provides a good overview of the different positioning systems if you are unsure about which one you are using: `Positioning System Overview + `_. + Motion capture ~~~~~~~~~~~~~~ @@ -134,8 +138,48 @@ If you have a motion capture system, you can input the specifics in the motion_c 'Type' can replaced by "optitrack", "vicon", "qualisys" or any of the other supported motion capture systems of the `motion capture tracking package `_. 'hostname' is the hostname of the computer running the motion capture software which can either be the PC name or the IP. +Also make sure that in crazyflies.yaml, the motion_capture field is enabled for the specific robot type, or that the crazyflie is of a type that supports motion capture. + +.. code-block:: yaml + robot_types: + cf21: + motion_capture: + enabled: true + +For more indepth information about the motion capture tracking package, see the `documentation `_. + +Onboard positioning +~~~~~~~~~~~~~~~~~~~ + +The Crazyflie also supports several alternative positioning systems that provide direct onboard position or pose estimation. +In this case you do not need to receive positioning from an external system like with MoCap. + +Instructions per positioing system.: +* The `Loco positioning system `_ - Follow Bitcraze's tutorial `here `. +* The `Lighthouse positioning system `_ - Follow Bitcraze's tutorial `here `. + * Make sure to review the system management for saving and loading a system config, such that you don't have to redo the basestation geometry estimation for each crazyflie. +* The `Flow deck `_ - Follow Bitcraze's tutorial `here `. + * Note that the flow deck provides an relative positoing estimate and might conflict when you are flying with crazyswarm2 if you are flying with absolute coordinates instead of relative ones. +Also in this case, make sure that motion_capture is disabled in the crazyflies.yaml file: + +.. code-block:: yaml + robot_types: + cf21: + motion_capture: + enabled: false + +Also it is a good idea to turn on pose estimation logging such that you are able to see the poses and transforms of the Crazyflie updated in real life in rviz or the Swarm management gui. + +.. code-block:: yaml + all: + firmware_logging: + enabled: true + default_topics: + # remove to disable default topic + pose: + frequency: 10 # Hz Simulation From feefb6030693402dceb6699d226fc7024a730921 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Thu, 30 May 2024 17:19:22 +0200 Subject: [PATCH 148/162] fix issue --- docs2/usage.rst | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/docs2/usage.rst b/docs2/usage.rst index edc065909..5fdb08ec7 100644 --- a/docs2/usage.rst +++ b/docs2/usage.rst @@ -121,8 +121,7 @@ Positioning ----------- The Crazyflie can be positioned in different ways, including motion capture and onboard positioning. -This blogpost provides a good overview of the different positioning systems if you are unsure about which one you are using: `Positioning System Overview - `_. +This blogpost provides a good overview of the different positioning systems if you are unsure about which one you are using: `Positioning System Overview `_. Motion capture ~~~~~~~~~~~~~~ From 497a3535fa5fb0bd0faff959418b6046a9a7a948 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Thu, 30 May 2024 17:23:46 +0200 Subject: [PATCH 149/162] fix block issue --- docs2/usage.rst | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/docs2/usage.rst b/docs2/usage.rst index 5fdb08ec7..744998229 100644 --- a/docs2/usage.rst +++ b/docs2/usage.rst @@ -129,6 +129,7 @@ Motion capture If you have a motion capture system, you can input the specifics in the motion_capture.yaml file. .. code-block:: yaml + /motion_capture_tracking: ros__parameters: type: "optitrack" @@ -140,6 +141,7 @@ If you have a motion capture system, you can input the specifics in the motion_c Also make sure that in crazyflies.yaml, the motion_capture field is enabled for the specific robot type, or that the crazyflie is of a type that supports motion capture. .. code-block:: yaml + robot_types: cf21: motion_capture: @@ -163,6 +165,7 @@ Instructions per positioing system.: Also in this case, make sure that motion_capture is disabled in the crazyflies.yaml file: .. code-block:: yaml + robot_types: cf21: motion_capture: @@ -171,6 +174,7 @@ Also in this case, make sure that motion_capture is disabled in the crazyflies.y Also it is a good idea to turn on pose estimation logging such that you are able to see the poses and transforms of the Crazyflie updated in real life in rviz or the Swarm management gui. .. code-block:: yaml + all: firmware_logging: From 100976a100b7aeaaea918e52c2fb104e9a1c5ad7 Mon Sep 17 00:00:00 2001 From: knmcguire Date: Thu, 30 May 2024 17:28:39 +0200 Subject: [PATCH 150/162] indentation issue --- docs2/usage.rst | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/docs2/usage.rst b/docs2/usage.rst index 744998229..af242c8a0 100644 --- a/docs2/usage.rst +++ b/docs2/usage.rst @@ -157,10 +157,8 @@ In this case you do not need to receive positioning from an external system like Instructions per positioing system.: * The `Loco positioning system `_ - Follow Bitcraze's tutorial `here `. -* The `Lighthouse positioning system `_ - Follow Bitcraze's tutorial `here `. - * Make sure to review the system management for saving and loading a system config, such that you don't have to redo the basestation geometry estimation for each crazyflie. -* The `Flow deck `_ - Follow Bitcraze's tutorial `here `. - * Note that the flow deck provides an relative positoing estimate and might conflict when you are flying with crazyswarm2 if you are flying with absolute coordinates instead of relative ones. +* The `Lighthouse positioning system `_ - Follow Bitcraze's tutorial `here `. Make sure to review the system management for saving and loading a system config, such that you don't have to redo the basestation geometry estimation for each crazyflie. +* The `Flow deck `_ - Follow Bitcraze's tutorial `here `. Note that the flow deck provides an relative positoing estimate and might conflict when you are flying with crazyswarm2 if you are flying with absolute coordinates instead of relative ones. Also in this case, make sure that motion_capture is disabled in the crazyflies.yaml file: From 21cc171c244aefeca567128f3aafdd4700785ee5 Mon Sep 17 00:00:00 2001 From: Kimberly McGuire Date: Fri, 31 May 2024 08:58:44 +0200 Subject: [PATCH 151/162] Update docs2/usage.rst --- docs2/usage.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs2/usage.rst b/docs2/usage.rst index af242c8a0..6321485f0 100644 --- a/docs2/usage.rst +++ b/docs2/usage.rst @@ -155,7 +155,7 @@ Onboard positioning The Crazyflie also supports several alternative positioning systems that provide direct onboard position or pose estimation. In this case you do not need to receive positioning from an external system like with MoCap. -Instructions per positioing system.: +Instructions per positioning system.: * The `Loco positioning system `_ - Follow Bitcraze's tutorial `here `. * The `Lighthouse positioning system `_ - Follow Bitcraze's tutorial `here `. Make sure to review the system management for saving and loading a system config, such that you don't have to redo the basestation geometry estimation for each crazyflie. * The `Flow deck `_ - Follow Bitcraze's tutorial `here `. Note that the flow deck provides an relative positoing estimate and might conflict when you are flying with crazyswarm2 if you are flying with absolute coordinates instead of relative ones. From 33fae442ad0b6490ef6eb25dcaad23aab44706ec Mon Sep 17 00:00:00 2001 From: knmcguire Date: Fri, 31 May 2024 09:03:46 +0200 Subject: [PATCH 152/162] fix indention --- docs2/usage.rst | 18 +++++++----------- 1 file changed, 7 insertions(+), 11 deletions(-) diff --git a/docs2/usage.rst b/docs2/usage.rst index 6321485f0..fd54ef49a 100644 --- a/docs2/usage.rst +++ b/docs2/usage.rst @@ -143,9 +143,9 @@ Also make sure that in crazyflies.yaml, the motion_capture field is enabled for .. code-block:: yaml robot_types: - cf21: - motion_capture: - enabled: true + cf21: + motion_capture: + enabled: true For more indepth information about the motion capture tracking package, see the `documentation `_. @@ -165,24 +165,20 @@ Also in this case, make sure that motion_capture is disabled in the crazyflies.y .. code-block:: yaml robot_types: - cf21: - motion_capture: - enabled: false + cf21: + motion_capture: + enabled: false Also it is a good idea to turn on pose estimation logging such that you are able to see the poses and transforms of the Crazyflie updated in real life in rviz or the Swarm management gui. .. code-block:: yaml - all: - firmware_logging: enabled: true default_topics: - # remove to disable default topic - pose: + pose: frequency: 10 # Hz - Simulation ---------- From 796c5b55acc45eecdbbb8253dc857a54df49c92b Mon Sep 17 00:00:00 2001 From: knmcguire Date: Fri, 31 May 2024 09:16:54 +0200 Subject: [PATCH 153/162] add mocap launch variable --- crazyflie/launch/launch.py | 5 +++-- docs2/usage.rst | 3 +++ 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/crazyflie/launch/launch.py b/crazyflie/launch/launch.py index be2ed1339..734824b3c 100644 --- a/crazyflie/launch/launch.py +++ b/crazyflie/launch/launch.py @@ -5,7 +5,7 @@ from launch.actions import DeclareLaunchArgument from launch_ros.actions import Node from launch.conditions import LaunchConfigurationEquals -from launch.conditions import LaunchConfigurationNotEquals +from launch.conditions import IfCondition from launch.substitutions import LaunchConfiguration, PythonExpression @@ -83,13 +83,14 @@ def generate_launch_description(): DeclareLaunchArgument('debug', default_value='False'), DeclareLaunchArgument('rviz', default_value='False'), DeclareLaunchArgument('gui', default_value='True'), + DeclareLaunchArgument('mocap', default_value='True'), DeclareLaunchArgument('server_yaml_file', default_value=''), DeclareLaunchArgument('teleop_yaml_file', default_value=''), DeclareLaunchArgument('mocap_yaml_file', default_value=''), Node( package='motion_capture_tracking', executable='motion_capture_tracking_node', - condition=LaunchConfigurationNotEquals('backend','sim'), + condition=IfCondition(PythonExpression(["'", LaunchConfiguration('backend'), "' != 'sim' and '", LaunchConfiguration('mocap'), "' == 'True'"])), name='motion_capture_tracking', output='screen', parameters= [PythonExpression(["'tmp_motion_capture.yaml' if '", LaunchConfiguration('mocap_yaml_file'), "' == '' else '", LaunchConfiguration('mocap_yaml_file'), "'"])], diff --git a/docs2/usage.rst b/docs2/usage.rst index fd54ef49a..9f8270b32 100644 --- a/docs2/usage.rst +++ b/docs2/usage.rst @@ -179,6 +179,9 @@ Also it is a good idea to turn on pose estimation logging such that you are able pose: frequency: 10 # Hz + +Moreover, be aware that the motion capture node is enabled in the launch file by default, which can be turned off by adding 'mocap:=False' to the launch command. + Simulation ---------- From 59ff36d92c8e5a077138e157fd9a5fe01c4b1c29 Mon Sep 17 00:00:00 2001 From: Kimberly McGuire Date: Sun, 2 Jun 2024 16:59:14 +0200 Subject: [PATCH 154/162] Update usage.rst --- docs2/usage.rst | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/docs2/usage.rst b/docs2/usage.rst index 9f8270b32..64a96bcb6 100644 --- a/docs2/usage.rst +++ b/docs2/usage.rst @@ -155,10 +155,11 @@ Onboard positioning The Crazyflie also supports several alternative positioning systems that provide direct onboard position or pose estimation. In this case you do not need to receive positioning from an external system like with MoCap. -Instructions per positioning system.: -* The `Loco positioning system `_ - Follow Bitcraze's tutorial `here `. -* The `Lighthouse positioning system `_ - Follow Bitcraze's tutorial `here `. Make sure to review the system management for saving and loading a system config, such that you don't have to redo the basestation geometry estimation for each crazyflie. -* The `Flow deck `_ - Follow Bitcraze's tutorial `here `. Note that the flow deck provides an relative positoing estimate and might conflict when you are flying with crazyswarm2 if you are flying with absolute coordinates instead of relative ones. +Instructions per positioning system: + +* The `Loco positioning system `_ - Follow Bitcraze's tutorial `here `_. +* The `Lighthouse positioning system `_ - Follow Bitcraze's tutorial `here `_. Make sure to review the system management for saving and loading a system config, such that you don't have to redo the basestation geometry estimation for each crazyflie. +* The `Flow deck `_ - Follow Bitcraze's tutorial `here `_. Note that the flow deck provides an relative positoing estimate and might conflict when you are flying with crazyswarm2 if you are flying with absolute coordinates instead of relative ones. Also in this case, make sure that motion_capture is disabled in the crazyflies.yaml file: @@ -238,4 +239,4 @@ Swarm Management The launch file will also start a swarm management tool that is a ROS node and web-based GUI. In the upper pane is the location of the drone visualized in a 3D window, similar to rviz. In the lower pane, the status as well as log messages are visible (tabbed per drone). -In the future, we are planning to add support for rebooting and other actions. \ No newline at end of file +In the future, we are planning to add support for rebooting and other actions. From ca4fac360c340b9957abceb26240f7cd45f8ab67 Mon Sep 17 00:00:00 2001 From: Kimberly McGuire Date: Tue, 11 Jun 2024 11:21:30 +0200 Subject: [PATCH 155/162] Update usage.rst --- docs2/usage.rst | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/docs2/usage.rst b/docs2/usage.rst index 64a96bcb6..215f9c56b 100644 --- a/docs2/usage.rst +++ b/docs2/usage.rst @@ -157,9 +157,9 @@ In this case you do not need to receive positioning from an external system like Instructions per positioning system: -* The `Loco positioning system `_ - Follow Bitcraze's tutorial `here `_. -* The `Lighthouse positioning system `_ - Follow Bitcraze's tutorial `here `_. Make sure to review the system management for saving and loading a system config, such that you don't have to redo the basestation geometry estimation for each crazyflie. -* The `Flow deck `_ - Follow Bitcraze's tutorial `here `_. Note that the flow deck provides an relative positoing estimate and might conflict when you are flying with crazyswarm2 if you are flying with absolute coordinates instead of relative ones. +* The `Loco positioning system `_ - `Follow Bitcraze's tutorial on LPS here `_. +* The `Lighthouse positioning system `_ - `Follow Bitcraze's tutorial on Lighthouse here `_. Make sure to review the system management for saving and loading a system config, such that you don't have to redo the basestation geometry estimation for each crazyflie. +* The `Flow deck `_ - `Follow Bitcraze's tutorial on the flowdeck here `_. Note that the flow deck provides an relative positoing estimate and might conflict when you are flying with crazyswarm2 if you are flying with absolute coordinates instead of relative ones. Also in this case, make sure that motion_capture is disabled in the crazyflies.yaml file: From 063e62343b306cda53389c83d9841f84b9a97c4f Mon Sep 17 00:00:00 2001 From: Kimberly McGuire Date: Sat, 22 Jun 2024 21:46:07 +0200 Subject: [PATCH 156/162] Explain more clearly that distro needs to be replaced on install (#527) --- docs2/installation.rst | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/docs2/installation.rst b/docs2/installation.rst index aac92d566..eca21418b 100644 --- a/docs2/installation.rst +++ b/docs2/installation.rst @@ -30,18 +30,18 @@ First Installation sudo apt install libboost-program-options-dev libusb-1.0-0-dev pip3 install rowan nicegui - Then install the motion capture ROS 2 package for your ROS distro + Then install the motion capture ROS 2 package (replace DISTRO with your version of ROS, namely humble or iron): .. code-block:: bash - sudo apt-get ros-*DISTRO*-motion-capture-tracking + sudo apt-get ros-DISTRO-motion-capture-tracking If you are planning to use the CFlib backend, do: .. code-block:: bash pip3 install cflib transforms3d - sudo apt-get install ros-*DISTRO*-tf-transformations + sudo apt-get install ros-DISTRO-tf-transformations 3. Set up your ROS 2 workspace From 9397af5579269f885339f1deea23a7df34045994 Mon Sep 17 00:00:00 2001 From: Kimberly McGuire Date: Mon, 24 Jun 2024 14:16:22 +0200 Subject: [PATCH 157/162] Update tutorials.rst --- docs2/tutorials.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs2/tutorials.rst b/docs2/tutorials.rst index 3a3894123..ba082ec36 100644 --- a/docs2/tutorials.rst +++ b/docs2/tutorials.rst @@ -37,7 +37,7 @@ in another terminal run: .. code-block:: bash - ros2 run teleop_twist_keyboard telop_twist_keyboard + ros2 run teleop_twist_keyboard teleop_twist_keyboard Use 't' to take off, and 'b' to land. For the rest, use the instructions of the telop package. From e89395e56f3555ce1781b6bc5e8226856ef7af34 Mon Sep 17 00:00:00 2001 From: Kimberly McGuire Date: Mon, 24 Jun 2024 14:27:35 +0200 Subject: [PATCH 158/162] Update installation.rst --- docs2/installation.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs2/installation.rst b/docs2/installation.rst index eca21418b..8071fb117 100644 --- a/docs2/installation.rst +++ b/docs2/installation.rst @@ -34,7 +34,7 @@ First Installation .. code-block:: bash - sudo apt-get ros-DISTRO-motion-capture-tracking + sudo apt-get install ros-DISTRO-motion-capture-tracking If you are planning to use the CFlib backend, do: From d1537eb40e5e09b17e4b29ac7c273ccdb0db25c7 Mon Sep 17 00:00:00 2001 From: Christian Llanes Date: Tue, 25 Jun 2024 12:31:25 -0400 Subject: [PATCH 159/162] Use OpaqueFunction to load string path of custom user-defined crazyflies yaml file --- crazyflie/launch/launch.py | 34 +++++++++++++++++++--------------- 1 file changed, 19 insertions(+), 15 deletions(-) diff --git a/crazyflie/launch/launch.py b/crazyflie/launch/launch.py index 770c805ab..8c4264c1c 100644 --- a/crazyflie/launch/launch.py +++ b/crazyflie/launch/launch.py @@ -2,23 +2,17 @@ import yaml from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument +from launch.actions import DeclareLaunchArgument, OpaqueFunction from launch_ros.actions import Node from launch.conditions import LaunchConfigurationEquals from launch.conditions import IfCondition from launch.substitutions import LaunchConfiguration, PythonExpression - -def generate_launch_description(): - - # load crazyflies - crazyflies_yaml = os.path.join( - get_package_share_directory('crazyflie'), - 'config', - 'crazyflies.yaml') - - with open(crazyflies_yaml, 'r') as ymlfile: - crazyflies = yaml.safe_load(ymlfile) +def parse_yaml(context): + # Load the crazyflies YAML file + crazyflies_yaml_file = LaunchConfiguration('crazyflies_yaml_file').perform(context) + with open(crazyflies_yaml_file, 'r') as file: + crazyflies = yaml.safe_load(file) # server params server_yaml = os.path.join( @@ -38,9 +32,10 @@ def generate_launch_description(): get_package_share_directory('crazyflie'), 'urdf', 'crazyflie_description.urdf') + with open(urdf, 'r') as f: - robot_desc = f.read() + server_yaml_content["/crazyflie_server"]["ros__parameters"]["robot_description"] = robot_desc # construct motion_capture_configuration @@ -48,7 +43,6 @@ def generate_launch_description(): get_package_share_directory('crazyflie'), 'config', 'motion_capture.yaml') - with open(motion_capture_yaml, 'r') as ymlfile: motion_capture_content = yaml.safe_load(ymlfile) @@ -73,12 +67,22 @@ def generate_launch_description(): with open('tmp_motion_capture.yaml', 'w') as outfile: yaml.dump(motion_capture_content, outfile, default_flow_style=False, sort_keys=False) + +def generate_launch_description(): + default_crazyflies_yaml_path = os.path.join( + get_package_share_directory('crazyflie'), + 'config', + 'crazyflies.yaml') + telop_yaml_path = os.path.join( get_package_share_directory('crazyflie'), 'config', 'teleop.yaml') - + return LaunchDescription([ + DeclareLaunchArgument('crazyflies_yaml_file', + default_value=default_crazyflies_yaml_path), + OpaqueFunction(function=parse_yaml), DeclareLaunchArgument('backend', default_value='cpp'), DeclareLaunchArgument('debug', default_value='False'), DeclareLaunchArgument('rviz', default_value='False'), From 6bbe811aa8ebae8351cc2584da466f26f848f10d Mon Sep 17 00:00:00 2001 From: Kimberly McGuire Date: Wed, 26 Jun 2024 11:24:17 +0200 Subject: [PATCH 160/162] Update multiranger_mapping_launch.py --- crazyflie_examples/launch/multiranger_mapping_launch.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/crazyflie_examples/launch/multiranger_mapping_launch.py b/crazyflie_examples/launch/multiranger_mapping_launch.py index 67e0dde9f..5dedb0d04 100644 --- a/crazyflie_examples/launch/multiranger_mapping_launch.py +++ b/crazyflie_examples/launch/multiranger_mapping_launch.py @@ -42,14 +42,14 @@ def generate_launch_description(): output='screen', parameters=[{'hover_height': 0.3}, {'incoming_twist_topic': '/cmd_vel'}, - {'robot_prefix': '/cf1'}] + {'robot_prefix': '/cf231'}] ), Node( parameters=[ {'odom_frame': 'odom'}, - {'map_frame': 'world'}, - {'base_frame': 'cf1'}, - {'scan_topic': '/cf1/scan'}, + {'map_frame': 'map'}, + {'base_frame': 'cf231'}, + {'scan_topic': '/cf231/scan'}, {'use_scan_matching': False}, {'max_laser_range': 3.5}, {'resolution': 0.1}, From 6f39cbd319ca491a7c8df2a35a1e292f0784e551 Mon Sep 17 00:00:00 2001 From: Kimberly McGuire Date: Wed, 26 Jun 2024 11:27:22 +0200 Subject: [PATCH 161/162] Update tutorials.rst --- docs2/tutorials.rst | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/docs2/tutorials.rst b/docs2/tutorials.rst index ba082ec36..48abc34ec 100644 --- a/docs2/tutorials.rst +++ b/docs2/tutorials.rst @@ -201,14 +201,14 @@ Let's first look at the launch file real quick (multiranger_mapping_launch.py): output='screen', parameters=[{"hover_height": 0.3}, {"incoming_twist_topic": "/cmd_vel"}, - {"robot_prefix": "/cf1"}] + {"robot_prefix": "/cf231"}] ), Node( parameters=[ {'odom_frame': 'odom'}, - {'map_frame': 'world'}, - {'base_frame': 'cf1'}, - {'scan_topic': '/cf1/scan'}, + {'map_frame': 'map'}, + {'base_frame': 'cf231'}, + {'scan_topic': '/cf231/scan'}, {'use_scan_matching': False}, {'max_laser_range': 3.5}, {'resolution': 0.1}, @@ -224,7 +224,7 @@ Let's first look at the launch file real quick (multiranger_mapping_launch.py): Here is an explanation of the nodes: -* The first node enables the crazyflie server, namely the python version (cflib) as that currently has logging enabled. This takes the crazyflies.yaml file you just edited and uses those values to set up the crazyflie. +* The first node enables the crazyflie server, namely the python version (cflib) as that currently has logging enabled. This takes the crazyflies.yaml file you just edited and uses those values to set up the crazyflie. You might need to change some topic strings based on your Crazyflie name (`/cf231` to something else) * The second node is a velocity command handler, which takes an incoming twist message, makes the Crazyflie take off to a fixed height and enables velocity control of external packages (you'll see why soon enough). * The third node is the slam toolbox node. You noted that we gave it some different parameters, where we upped the speed of the map generation, decreased the resolution and turn of ray matching as mentioned in the warning above. @@ -274,7 +274,7 @@ Now, open up a rviv2 window in a seperate terminal with : Add the following displays and panels to RVIZ: -* Changed the 'Fixed frame' to 'world +* Changed the 'Fixed frame' to 'map' * 'Add' button under displays and 'by topic' tab, select the '/map' topic. * 'Add' button under displays and 'by display type' add a transform. * 'Panels' on the top menu, select 'add new panel' and select the SLAMToolBoxPlugin From 7db011da7eb579a4b128ef4198eb838a54be4c5d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Wolfgang=20H=C3=B6nig?= Date: Sun, 7 Jul 2024 21:33:36 +0200 Subject: [PATCH 162/162] enable CI for jazzy (#542) * Support for ROS Jazzy --- .github/workflows/ci-ros2.yml | 12 +++++++++++- crazyflie/deps/crazyflie_tools | 2 +- crazyflie_py/crazyflie_py/crazyflie.py | 4 ++-- docs2/installation.rst | 6 ++++-- docs2/tutorials.rst | 2 +- 5 files changed, 19 insertions(+), 7 deletions(-) diff --git a/.github/workflows/ci-ros2.yml b/.github/workflows/ci-ros2.yml index 315d94ba1..713b75dd9 100644 --- a/.github/workflows/ci-ros2.yml +++ b/.github/workflows/ci-ros2.yml @@ -16,6 +16,7 @@ jobs: ros_distribution: - humble - iron + - jazzy # Define the Docker image(s) associated with each ROS distribution. include: @@ -29,6 +30,11 @@ jobs: ros_distribution: iron ros_version: 2 + # Jazzy Jalisco (May 2024 - May 2029) + - docker_image: ubuntu:noble + ros_distribution: jazzy + ros_version: 2 + container: image: ${{ matrix.docker_image }} steps: @@ -40,12 +46,16 @@ jobs: - name: install dependencies run: | sudo apt update - sudo apt install -y libusb-1.0-0-dev + sudo apt install -y libboost-program-options-dev libusb-1.0-0-dev - name: install pip dependencies # TODO: would be better to follow https://answers.ros.org/question/370666/how-to-declare-an-external-python-dependency-in-ros2/ # but this requires some upstream changes + + # colcon still does not seem to properly support venv, so we use a workaround to install + # a python package globally by disabling the externally managed flag that is default on Ubuntu 24.04 run: | + sudo rm -f /usr/lib/python3.12/EXTERNALLY-MANAGED pip install rowan - uses: actions/checkout@v2 diff --git a/crazyflie/deps/crazyflie_tools b/crazyflie/deps/crazyflie_tools index 5f6b39cc5..a2d74b41f 160000 --- a/crazyflie/deps/crazyflie_tools +++ b/crazyflie/deps/crazyflie_tools @@ -1 +1 @@ -Subproject commit 5f6b39cc50a7e6432435e0a807b7c07dbe5f5da6 +Subproject commit a2d74b41f9a3675851697b9d4999d1cfe033d30b diff --git a/crazyflie_py/crazyflie_py/crazyflie.py b/crazyflie_py/crazyflie_py/crazyflie.py index 30cf4028e..44583123c 100644 --- a/crazyflie_py/crazyflie_py/crazyflie.py +++ b/crazyflie_py/crazyflie_py/crazyflie.py @@ -15,7 +15,7 @@ from crazyflie_interfaces.msg import FullState, Position, Status, TrajectoryPolynomialPiece -from crazyflie_interfaces.srv import Arm, GoTo, Land,\ +from crazyflie_interfaces.srv import Arm, GoTo, Land, \ NotifySetpointsStop, StartTrajectory, Takeoff, UploadTrajectory from geometry_msgs.msg import Point import numpy as np @@ -160,7 +160,7 @@ def __init__(self, node, cfname, paramTypeDict): elif response.values[0].type == ParameterType.PARAMETER_DOUBLE_ARRAY: self.initialPosition = np.array(response.values[0].double_array_value) else: - assert(False) + assert False # extract uri self.uri = response.values[1].string_value diff --git a/docs2/installation.rst b/docs2/installation.rst index 8071fb117..aa18e7020 100644 --- a/docs2/installation.rst +++ b/docs2/installation.rst @@ -9,6 +9,8 @@ Crazyswarm2 runs on **Ubuntu Linux** in one of the following configurations: Ubuntu Python ROS 2 ------ -------- ------------ 22.04 3.10 Humble, Iron +------ -------- ------------ +24.04 3.12 Jazzy ====== ======== ============ .. warning:: @@ -21,7 +23,7 @@ Ubuntu Python ROS 2 First Installation ------------------ -1. If needed, install ROS 2 using the instructions at https://docs.ros.org/en/galactic/Installation.html or https://docs.ros.org/en/humble/Installation.html. +1. If needed, install ROS 2 using the instructions at https://docs.ros.org/en/jazzy/Installation.html. 2. Install dependencies @@ -30,7 +32,7 @@ First Installation sudo apt install libboost-program-options-dev libusb-1.0-0-dev pip3 install rowan nicegui - Then install the motion capture ROS 2 package (replace DISTRO with your version of ROS, namely humble or iron): + Then install the motion capture ROS 2 package (replace DISTRO with your version of ROS, namely humble, iron, or jazzy): .. code-block:: bash diff --git a/docs2/tutorials.rst b/docs2/tutorials.rst index 48abc34ec..b09cf7586 100644 --- a/docs2/tutorials.rst +++ b/docs2/tutorials.rst @@ -19,7 +19,7 @@ We have an example of the telop_twist_keyboard package working together with the First, make sure that the crazyflies.yaml has the right URI and if you are using the `Flow deck `_ or `any other position system available `_ to the crazyflie. set the controller to 1 (PID). -And if you have not already, install the teleop package for the keyboard. (replace DISTRO with humble or iron): +And if you have not already, install the teleop package for the keyboard. (replace DISTRO with humble, iron, or jazzy): .. code-block:: bash