From 5c0eaaaee823efa0fee01e667276be5db12a9de3 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Mon, 3 Jun 2024 08:20:42 -0700 Subject: [PATCH 01/21] Fix typo in a comment (#2429) Signed-off-by: Nate Koenig --- src/ModelCommandAPI_TEST.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/ModelCommandAPI_TEST.cc b/src/ModelCommandAPI_TEST.cc index 95f5b8b4a4..673f9c9a8b 100644 --- a/src/ModelCommandAPI_TEST.cc +++ b/src/ModelCommandAPI_TEST.cc @@ -608,7 +608,7 @@ TEST(ModelCommandAPI, GZ_UTILS_TEST_DISABLED_ON_MAC(RgbdCameraSensor)) // Run without blocking. server.Run(false, 0, false); - // Tested command: gz model -m altimeter_mode -l link -s altimeter_sensor + // Tested command: gz model -m rgbd_camera -l rgbd_camera_link -s rgbd_camera { const std::string cmd = kGzModelCommand + "-m rgbd_camera -l rgbd_camera_link -s rgbd_camera"; From 1b577f1b77a2a93a3cc210de9b33ec9e54550329 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Mon, 3 Jun 2024 11:18:18 -0700 Subject: [PATCH 02/21] Use topicFromScopedName in a few systems (#2427) * Use topicFromScopedName in a few systems Signed-off-by: Nate Koenig * Fix topic name generation Signed-off-by: Nate Koenig --------- Signed-off-by: Nate Koenig --- .../LogicalAudioSensorPlugin.cc | 7 +++---- src/systems/pose_publisher/PosePublisher.cc | 3 +-- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc index dd14a2d271..c0836401dd 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.cc @@ -405,12 +405,11 @@ void LogicalAudioSensorPluginPrivate::CreateAudioSource( }; // create services for this source - const auto fullName = scopedName(entity, _ecm); - auto validName = transport::TopicUtils::AsValidTopic(fullName); + const auto validName = topicFromScopedName(entity, _ecm, false); if (validName.empty()) { gzerr << "Failed to create valid topics with entity scoped name [" - << fullName << "]" << std::endl; + << scopedName(entity, _ecm) << "]" << std::endl; return; } if (!this->node.Advertise(validName + "/play", playSrvCb)) @@ -504,7 +503,7 @@ void LogicalAudioSensorPluginPrivate::CreateMicrophone( // create the detection publisher for this microphone auto pub = this->node.Advertise( - scopedName(entity, _ecm) + "/detection"); + topicFromScopedName(entity, _ecm, false) + "/detection"); if (!pub) { gzerr << "Error creating a detection publisher for microphone " diff --git a/src/systems/pose_publisher/PosePublisher.cc b/src/systems/pose_publisher/PosePublisher.cc index e75d5789a3..fd167a882e 100644 --- a/src/systems/pose_publisher/PosePublisher.cc +++ b/src/systems/pose_publisher/PosePublisher.cc @@ -250,8 +250,7 @@ void PosePublisher::Configure(const Entity &_entity, this->dataPtr->usePoseV = _sdf->Get("use_pose_vector_msg", this->dataPtr->usePoseV).first; - std::string poseTopic = scopedName(_entity, _ecm) + "/pose"; - poseTopic = transport::TopicUtils::AsValidTopic(poseTopic); + std::string poseTopic = topicFromScopedName(_entity, _ecm, false) + "/pose"; if (poseTopic.empty()) { poseTopic = "/pose"; From 49ab5c6d0c69abdf0db45b99bcd350f4d90bf7cf Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 5 Jun 2024 07:55:42 -0700 Subject: [PATCH 03/21] Handle sdf::Geometry::EMPTY in conversions (#2430) Signed-off-by: Nate Koenig --- src/Conversions.cc | 4 ++++ src/Conversions_TEST.cc | 10 ++++++++++ 2 files changed, 14 insertions(+) diff --git a/src/Conversions.cc b/src/Conversions.cc index 33548a6843..1ef5df8f82 100644 --- a/src/Conversions.cc +++ b/src/Conversions.cc @@ -259,6 +259,10 @@ msgs::Geometry gz::sim::convert(const sdf::Geometry &_in) } } } + else if (_in.Type() == sdf::GeometryType::EMPTY) + { + out.set_type(msgs::Geometry::EMPTY); + } else { gzerr << "Geometry type [" << static_cast(_in.Type()) diff --git a/src/Conversions_TEST.cc b/src/Conversions_TEST.cc index 3d6e3e5861..2e7deecdd0 100644 --- a/src/Conversions_TEST.cc +++ b/src/Conversions_TEST.cc @@ -1206,3 +1206,13 @@ TEST(Conversions, MsgsPluginToSdf) EXPECT_EQ(innerXml, sdfPlugins[1].Contents()[0]->ToString("")); EXPECT_EQ(innerXml2, sdfPlugins[1].Contents()[1]->ToString("")); } + +///////////////////////////////////////////////// +TEST(Conversions, GeometryEmpty) +{ + sdf::Geometry geometry; + geometry.SetType(sdf::GeometryType::EMPTY); + + auto geometryMsg = convert(geometry); + EXPECT_EQ(msgs::Geometry::EMPTY, geometryMsg.type()); +} From 0cc0464e904bb0bc05026580b1fa945e7c4ce33b Mon Sep 17 00:00:00 2001 From: AddisonFarley <93640684+AddisonFarley@users.noreply.github.com> Date: Thu, 6 Jun 2024 03:24:46 -0700 Subject: [PATCH 04/21] Fix warning message to show precise jump back in time duration (#2435) --------- Signed-off-by: AddisonFarley <93640684+AddisonFarley@users.noreply.github.com> --- src/systems/ackermann_steering/AckermannSteering.cc | 4 ++-- src/systems/advanced_lift_drag/AdvancedLiftDrag.cc | 4 ++-- src/systems/air_pressure/AirPressure.cc | 4 ++-- src/systems/air_speed/AirSpeed.cc | 4 ++-- src/systems/altimeter/Altimeter.cc | 4 ++-- src/systems/apply_joint_force/ApplyJointForce.cc | 4 ++-- src/systems/battery_plugin/LinearBatteryPlugin.cc | 4 ++-- src/systems/contact/Contact.cc | 4 ++-- src/systems/diff_drive/DiffDrive.cc | 4 ++-- src/systems/force_torque/ForceTorque.cc | 4 ++-- src/systems/imu/Imu.cc | 4 ++-- src/systems/joint_controller/JointController.cc | 4 ++-- .../joint_position_controller/JointPositionController.cc | 4 ++-- src/systems/lift_drag/LiftDrag.cc | 4 ++-- src/systems/log/LogRecord.cc | 4 ++-- src/systems/logical_camera/LogicalCamera.cc | 4 ++-- src/systems/magnetometer/Magnetometer.cc | 4 ++-- src/systems/mecanum_drive/MecanumDrive.cc | 4 ++-- src/systems/multicopter_control/MulticopterVelocityControl.cc | 4 ++-- src/systems/multicopter_motor_model/MulticopterMotorModel.cc | 4 ++-- src/systems/navsat/NavSat.cc | 4 ++-- src/systems/odometry_publisher/OdometryPublisher.cc | 4 ++-- src/systems/pose_publisher/PosePublisher.cc | 4 ++-- src/systems/touch_plugin/TouchPlugin.cc | 4 ++-- src/systems/velocity_control/VelocityControl.cc | 4 ++-- src/systems/wind_effects/WindEffects.cc | 4 ++-- 26 files changed, 52 insertions(+), 52 deletions(-) diff --git a/src/systems/ackermann_steering/AckermannSteering.cc b/src/systems/ackermann_steering/AckermannSteering.cc index f01c72dfb9..59d81052f8 100644 --- a/src/systems/ackermann_steering/AckermannSteering.cc +++ b/src/systems/ackermann_steering/AckermannSteering.cc @@ -508,8 +508,8 @@ void AckermannSteering::PreUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } // If the joints haven't been identified yet, look for them diff --git a/src/systems/advanced_lift_drag/AdvancedLiftDrag.cc b/src/systems/advanced_lift_drag/AdvancedLiftDrag.cc index a7c60109fd..80065691d5 100644 --- a/src/systems/advanced_lift_drag/AdvancedLiftDrag.cc +++ b/src/systems/advanced_lift_drag/AdvancedLiftDrag.cc @@ -802,8 +802,8 @@ void AdvancedLiftDrag::PreUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } if (!this->dataPtr->initialized) diff --git a/src/systems/air_pressure/AirPressure.cc b/src/systems/air_pressure/AirPressure.cc index 7dba18337f..3a99824e76 100644 --- a/src/systems/air_pressure/AirPressure.cc +++ b/src/systems/air_pressure/AirPressure.cc @@ -132,8 +132,8 @@ void AirPressure::PostUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } this->dataPtr->CreateSensors(_ecm); diff --git a/src/systems/air_speed/AirSpeed.cc b/src/systems/air_speed/AirSpeed.cc index 73c9e92466..39904b9575 100644 --- a/src/systems/air_speed/AirSpeed.cc +++ b/src/systems/air_speed/AirSpeed.cc @@ -134,8 +134,8 @@ void AirSpeed::PostUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } this->dataPtr->CreateSensors(_ecm); diff --git a/src/systems/altimeter/Altimeter.cc b/src/systems/altimeter/Altimeter.cc index ecd3ee1ea1..7f45d2899f 100644 --- a/src/systems/altimeter/Altimeter.cc +++ b/src/systems/altimeter/Altimeter.cc @@ -132,8 +132,8 @@ void Altimeter::PostUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } this->dataPtr->CreateSensors(_ecm); diff --git a/src/systems/apply_joint_force/ApplyJointForce.cc b/src/systems/apply_joint_force/ApplyJointForce.cc index 19add069df..b7ea5eba18 100644 --- a/src/systems/apply_joint_force/ApplyJointForce.cc +++ b/src/systems/apply_joint_force/ApplyJointForce.cc @@ -134,8 +134,8 @@ void ApplyJointForce::PreUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } // If the joint hasn't been identified yet, look for it diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.cc b/src/systems/battery_plugin/LinearBatteryPlugin.cc index 357b01df97..523950b172 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.cc +++ b/src/systems/battery_plugin/LinearBatteryPlugin.cc @@ -550,8 +550,8 @@ void LinearBatteryPlugin::Update(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } if (_info.paused) diff --git a/src/systems/contact/Contact.cc b/src/systems/contact/Contact.cc index f4b8019f0c..0dcea6a8b4 100644 --- a/src/systems/contact/Contact.cc +++ b/src/systems/contact/Contact.cc @@ -276,8 +276,8 @@ void Contact::PostUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } if (!_info.paused) diff --git a/src/systems/diff_drive/DiffDrive.cc b/src/systems/diff_drive/DiffDrive.cc index 04fc968279..b65af3fce6 100644 --- a/src/systems/diff_drive/DiffDrive.cc +++ b/src/systems/diff_drive/DiffDrive.cc @@ -396,8 +396,8 @@ void DiffDrive::PreUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } // If the joints haven't been identified yet, look for them diff --git a/src/systems/force_torque/ForceTorque.cc b/src/systems/force_torque/ForceTorque.cc index 71a2e2800b..8792f514d5 100644 --- a/src/systems/force_torque/ForceTorque.cc +++ b/src/systems/force_torque/ForceTorque.cc @@ -166,8 +166,8 @@ void ForceTorque::PostUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } this->dataPtr->CreateSensors(_ecm); diff --git a/src/systems/imu/Imu.cc b/src/systems/imu/Imu.cc index eebbe77b6c..6026cda124 100644 --- a/src/systems/imu/Imu.cc +++ b/src/systems/imu/Imu.cc @@ -136,8 +136,8 @@ void Imu::PostUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } this->dataPtr->CreateSensors(_ecm); diff --git a/src/systems/joint_controller/JointController.cc b/src/systems/joint_controller/JointController.cc index 40f5caac33..cf8f54187c 100644 --- a/src/systems/joint_controller/JointController.cc +++ b/src/systems/joint_controller/JointController.cc @@ -265,8 +265,8 @@ void JointController::PreUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } // If the joints haven't been identified yet, look for them diff --git a/src/systems/joint_position_controller/JointPositionController.cc b/src/systems/joint_position_controller/JointPositionController.cc index b2835160ff..4b36a5076c 100644 --- a/src/systems/joint_position_controller/JointPositionController.cc +++ b/src/systems/joint_position_controller/JointPositionController.cc @@ -339,8 +339,8 @@ void JointPositionController::PreUpdate( if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } // If the joints haven't been identified yet, look for them diff --git a/src/systems/lift_drag/LiftDrag.cc b/src/systems/lift_drag/LiftDrag.cc index c83837c5ff..902bfec942 100644 --- a/src/systems/lift_drag/LiftDrag.cc +++ b/src/systems/lift_drag/LiftDrag.cc @@ -550,8 +550,8 @@ void LiftDrag::PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ecm) if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } if (!this->dataPtr->initialized) diff --git a/src/systems/log/LogRecord.cc b/src/systems/log/LogRecord.cc index 8cbeadbfb1..3361c407f4 100644 --- a/src/systems/log/LogRecord.cc +++ b/src/systems/log/LogRecord.cc @@ -669,8 +669,8 @@ void LogRecord::PostUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } // Publish only once diff --git a/src/systems/logical_camera/LogicalCamera.cc b/src/systems/logical_camera/LogicalCamera.cc index 1ddfe2146f..ded8c9c36f 100644 --- a/src/systems/logical_camera/LogicalCamera.cc +++ b/src/systems/logical_camera/LogicalCamera.cc @@ -134,8 +134,8 @@ void LogicalCamera::PostUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } this->dataPtr->CreateSensors(_ecm); diff --git a/src/systems/magnetometer/Magnetometer.cc b/src/systems/magnetometer/Magnetometer.cc index 499664a046..82b4e8d0f4 100644 --- a/src/systems/magnetometer/Magnetometer.cc +++ b/src/systems/magnetometer/Magnetometer.cc @@ -274,8 +274,8 @@ void Magnetometer::PostUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } this->dataPtr->CreateSensors(_ecm); diff --git a/src/systems/mecanum_drive/MecanumDrive.cc b/src/systems/mecanum_drive/MecanumDrive.cc index 2f585307c7..732bc07b1d 100644 --- a/src/systems/mecanum_drive/MecanumDrive.cc +++ b/src/systems/mecanum_drive/MecanumDrive.cc @@ -333,8 +333,8 @@ void MecanumDrive::PreUpdate(const gz::sim::UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } // If the joints haven't been identified yet, look for them diff --git a/src/systems/multicopter_control/MulticopterVelocityControl.cc b/src/systems/multicopter_control/MulticopterVelocityControl.cc index 96f547fa4d..d352a68a7a 100644 --- a/src/systems/multicopter_control/MulticopterVelocityControl.cc +++ b/src/systems/multicopter_control/MulticopterVelocityControl.cc @@ -349,8 +349,8 @@ void MulticopterVelocityControl::PreUpdate( if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } // Nothing left to do if paused. diff --git a/src/systems/multicopter_motor_model/MulticopterMotorModel.cc b/src/systems/multicopter_motor_model/MulticopterMotorModel.cc index 8e6e421ce9..2bfe779776 100644 --- a/src/systems/multicopter_motor_model/MulticopterMotorModel.cc +++ b/src/systems/multicopter_motor_model/MulticopterMotorModel.cc @@ -399,8 +399,8 @@ void MulticopterMotorModel::PreUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } // If the joint or links haven't been identified yet, look for them diff --git a/src/systems/navsat/NavSat.cc b/src/systems/navsat/NavSat.cc index f438a9d240..dd6ac144f7 100644 --- a/src/systems/navsat/NavSat.cc +++ b/src/systems/navsat/NavSat.cc @@ -128,8 +128,8 @@ void NavSat::PostUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } this->dataPtr->CreateSensors(_ecm); diff --git a/src/systems/odometry_publisher/OdometryPublisher.cc b/src/systems/odometry_publisher/OdometryPublisher.cc index 8473328320..c2fff130f8 100644 --- a/src/systems/odometry_publisher/OdometryPublisher.cc +++ b/src/systems/odometry_publisher/OdometryPublisher.cc @@ -297,8 +297,8 @@ void OdometryPublisher::PreUpdate(const gz::sim::UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } // Create the pose component if it does not exist. diff --git a/src/systems/pose_publisher/PosePublisher.cc b/src/systems/pose_publisher/PosePublisher.cc index 58661d4816..3cedb95b35 100644 --- a/src/systems/pose_publisher/PosePublisher.cc +++ b/src/systems/pose_publisher/PosePublisher.cc @@ -297,8 +297,8 @@ void PosePublisher::PostUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } // Nothing left to do if paused. diff --git a/src/systems/touch_plugin/TouchPlugin.cc b/src/systems/touch_plugin/TouchPlugin.cc index 91007cfbcc..d9cab9fd1d 100644 --- a/src/systems/touch_plugin/TouchPlugin.cc +++ b/src/systems/touch_plugin/TouchPlugin.cc @@ -251,8 +251,8 @@ void TouchPluginPrivate::Update(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } { diff --git a/src/systems/velocity_control/VelocityControl.cc b/src/systems/velocity_control/VelocityControl.cc index b5a1ccbde1..7af66e743b 100644 --- a/src/systems/velocity_control/VelocityControl.cc +++ b/src/systems/velocity_control/VelocityControl.cc @@ -188,8 +188,8 @@ void VelocityControl::PreUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } // Nothing left to do if paused. diff --git a/src/systems/wind_effects/WindEffects.cc b/src/systems/wind_effects/WindEffects.cc index 5ef1e51aa4..e237d0b1bc 100644 --- a/src/systems/wind_effects/WindEffects.cc +++ b/src/systems/wind_effects/WindEffects.cc @@ -716,8 +716,8 @@ void WindEffects::PreUpdate(const UpdateInfo &_info, if (_info.dt < std::chrono::steady_clock::duration::zero()) { gzwarn << "Detected jump back in time [" - << std::chrono::duration_cast(_info.dt).count() - << "s]. System may not work properly." << std::endl; + << std::chrono::duration(_info.dt).count() + << "s]. System may not work properly." << std::endl; } // Process commands From 5ff44b105d57370e14300e7bfdc5911b33e63566 Mon Sep 17 00:00:00 2001 From: Ryan Date: Tue, 11 Jun 2024 16:51:16 -0600 Subject: [PATCH 05/21] Add pause run tutorial (#2383) Add a tutorial to start/stop the simulation with either the GUI or CLI. This mirrors the reset simulation tutorial. --------- Signed-off-by: Ryan Friedman Signed-off-by: Ryan Signed-off-by: Addisu Z. Taddese Co-authored-by: Addisu Z. Taddese --- tutorials.md.in | 1 + .../pause_run_simlation/gui_pause_run.png | Bin 0 -> 103939 bytes tutorials/pause_run_simulation.md | 57 ++++++++++++++++++ tutorials/reset_simulation.md | 7 ++- 4 files changed, 64 insertions(+), 1 deletion(-) create mode 100644 tutorials/files/pause_run_simlation/gui_pause_run.png create mode 100644 tutorials/pause_run_simulation.md diff --git a/tutorials.md.in b/tutorials.md.in index 46c3f4be71..b75967e1ad 100644 --- a/tutorials.md.in +++ b/tutorials.md.in @@ -11,6 +11,7 @@ Gazebo @GZ_DESIGNATION_CAP@ library and how to use the library effectively. * \subpage gui_config "GUI configuration": Customizing your layout. * \subpage server_config "Server configuration": Customizing what system plugins are loaded. * \subpage model_command "Model Command": Use the CLI to get information about the models in a simulation. +* \subpage pause_run_simulation "Pause and Run simulation": Use Gazebo transport API to pause and run simulation. * \subpage reset_simulation Reset simulation * \subpage resources "Finding resources": The different ways in which Gazebo looks for files. * \subpage debugging "Debugging": Information about debugging Gazebo. diff --git a/tutorials/files/pause_run_simlation/gui_pause_run.png b/tutorials/files/pause_run_simlation/gui_pause_run.png new file mode 100644 index 0000000000000000000000000000000000000000..49dd5396534722d1161a7305ffdacc422646befa GIT binary patch literal 103939 zcmc$`WmH|u6FmqdxCVDZa0mo<2@b*CU4y$zf(IwK2MBJ#-Q6962Y2^i)4cb7^Pdm% zX}%0=v4DFI=X7^@BKnt$ zgdI!_oIcyyyjA{eZ33ZYV*Hkw^{t?t!&_!X@Czd+Hyax_3&&e|nYS_`%EyxJ<`58X zAtXfvmEF<~mtEbIO;(=IZjw_Z%YViYzYUOoMe2lR*P|;x7vxPJ)l~d6O~2n*7Ft$T zW}@aj8+lbxg5?U0`BV63&^!7#2vX$l(#**|KE46)u>(JY$=h$7bsSBYS$2l`Vh7SL zxNf|CqoAn!J`jJR6X2U;^Rc;TIX=lharSLPBn?0lf+H0XFD!j1t397ub#_I(xxa`1 zL7N6AIqo1~K_g#-U9vz>My?M3@1>1{deP^tE2>F~-VEao?H1T&PP%fxH9uO6^{j4q z&mBBY-Ebe(>%jecwU=l9!}5yi2Nlb#LC1+(jr?^-oj{C^K|RLvhq5dq$YQ=0joSuU z9vd7m3NVzANSNYUC}mHEj1{`o9VG}A@jj1yFJVO)nWzAflvRLw;86lC);g1f#h z9`zo%opnMu*B z$HH7v@;ic+ImI8$P_Lfv#(ba78g??8G>T_nG~Xxm%2Ry(^zUL#Bo-Ehg6FK+>DMj7 zBOoBuuLTk01qKFEFlg7?;m8XQIW|0$DQ1yU*I<@Z^Uu|^|Bw@Sygb>-@U*GzF^qXj z@z1^s;M}4K71Gy#t5s*S%xyZHyhOuf@7ur z`MVSYo>_&u$FT~+zZGxI>h z^ZL-8>izqYOr&Rwe@&EDhAEnrmzT%N$M@)wf(n00M7#^L^dyUR=$WmDj1~tT#7{|? zmpNj3Ft7IC1kHQ591Q9f?YYw<>S#j!REtIPr?Tb_a*5Kdf{ThoL`8e@^7EtUXlZF- z_Bri|-^o`q_x3&y*}p{mIjUQG%y=W_DH;Y!n@-F1wGb`ZMJEHLQ1o zuGIQpvZ)1$EGqt8%51HIqEFV=*1^KBzl@mX)YjH&$;LY6)sQhVGKOsD=bw9?Ex|v% zir+CD-*Z|(snh}4~HxdTgCkq+GHPU0pfETu%6rK;jn`dc6LzpDMRC|zn4>auG; z-m7|9`Uiyr&Sn$ju;;2TGFyt?s&J&dgecs)TjjJr z-cig3q6wubk6L@3Pfs;p_TpF-Sb0M^)D^D|-nTV|Z95gK%`jAcqk&$&xRmr=KO>0&{1L9U<{%mxn5B4us)_=b zFi$#yYxSgf!gpP)0chTSU2E-I`>n6|84?kLyC&8Uyi02~wo`3woaZ@K+%|sJbsf1} zEIE!bxg4rf%A`zhwweqjRG5z7AGh4-vZmx!#vpkOyA=dS~!YG-; zmKbcs&r^Aj$XOOE&FcEDw;ugroD_((tJ?wC! z>kp~6f0`9&ME0!->7SD6RnCyupw#CdIKh&5gCMW;r)B<&#vYeDYzi|QraB5 zriKb`@VLrk?kRjdw-FSlbF7~Bb@=}tQ(Y4}zQIiFxeeR48>v=KaSAHzQ@fnUj4tVfWy3!&K{a!B66?)_#n@ljq~#FYs(p#^w38!>3lYjIUT-V_js1 z(!PT%iiL{m^?UK(SB}V!iji|B4#$7mF8FuEE#D8G+AlHwd5fs)lN!hqN>f^rwPH<9 zOBS_fME1MRkS6t7P1xKw=y@H+$9Z19)0mDXfK#%us%|i+^nx$F=;-uPc_fts6(U`B z4!4L`usHU}+}S36N02*{K$EV80c_6D%5I%cZq54Wzuu3J zHFuu6&R}$(GICf5>n)GlVZ*W|@L{_vQ*Z(X4ZR@idRJG~`}Tcfx3Aqzz5cvB0;z0h ztisL@map5&pM!1dQ&`MotFpePn~Q7V6-u5VnB!->0FG|FP94QzgM5S(5r-fVcjz?k zPcDzc*GB@51!BiLHHdil@XbADo$NxJGLKMx}`om#q*qZ z$t#Ta%5IeLjJ-SGRph@rek;5Dw(M@vvia}1WwYC&1XQ8vk)I0T)rzczVbWEBXy?KAy3ycwO;R2Gaf5#j{^5ZoZn8da$T}Bg&>! zZ|}Nz@J0yEp4O6{pl04^%NF_{UnvS*-S92b@jBZydS5chbo@NB@nm09;`>aYdtV#v zkUGb_;IVH_i=2uOU&K~^);R}jmjq*f^{S4UU8v)1N;dS6wy4qn#>bQ5#GNl9FFVeG zLxgQ58{{4c&A(e)F?YS(>}(9VI`PF{0Qz}z=!v}5ugPq@_5t;EAxlvm~! zS^7Ttf!v(d%US{7{TYikE%gJXRU__V*9TGb0Xa|~ay{bYW6nCSMj#)*&a5b?}|x_98VD}umh z#m`05BI8rgP-{IR|?1wfZK zcX3w+QC4O1?Wo0rc-%B;lO&0i%Z1smb7Nz6%{F!!a_mf)IyC0V#Z$-k z{lCFk!g(EgNL3jU2*FJx?mE%m1lM7vHCB#}GEAxV^UNRFH7%FuG}X=nLtU|1&N7+| zVz%+=9+?NXtrVHw)J+>fqZfdQ4*w8gI@%`CsC!nKRec&x^lb_*$ILa**E6b|M2pXm z4KSsO54^bTI#KGJQSO%#X-2V`zhNo{+5b^5dB6Im90^rVjoi#GRIeAJulL(h#$C=j(fv* zR`=IvLz!){&gFP^(=!|05`PB;TIt>?nMKLP=1mPvk234O;HJt3ZVf#E`h57zXUPoYIR|%$JO$nIp2$z^PkZ4G` zx2e1seSiwRw#gzS%8TY?Rt%2DM4A!*RHy`*Hmyq78QZ`bX>s_8+Q`N?9CkxsbE=2n zw_~?-DSLGPG?L*Zit;6O3NFkRiox@!;b5eyBNEvgnuc(m6WTIfI(Ygo=>5M4o`y-f zcFra`uMSI{^h1YChf6H$kDH~Dd~{QJ82#-rf-77s-%#}J+tES>^yD)dKR|0c&r?I0 zAW{YFc43N=GBTo7%`ed(up~?8Tk~k9`p!&x9|7Nlrfc?9`(h62gA>scXFLsE-KS5U z87lulxR&?Wi0rAQQU{E4 zo{ItfU#05tEt~o^G_(ODZb5muZPkxJ)nW=p#$Qr=Jd=?@`PoPAs`S|9|6)_2OF@qo z;&j>If9jM!PTT~=^|Yar>U(8P{^8X*q6n-f72m)7i_=9&cHohyHo99TBd-NYZ$6}8 zA4mW9Rsh<_-H1#n*8lDbH-Um)@-KKs%MSaw)cD`is^!A)Bt8DmI|~S^la~Kg0ch67 zIW9PktIh6?bEzOkfFK`$mY?MUTf8@wZ^WJ|XR7tzi|cXI$6TuDMgRTTDL|w9Z=n-_ zrbFKGU-d=WDDe_6|1pG9%xk*;uGoDCulnzca1)~ck1_t=wYvz8W`sB(HICA&m{J#V6_=A8kwg+UKW@-1mQI_Q8^Beg2wT%u$hFf}Ovxcyw-{ zF@jh(y4EYct+bFMS7KPs-JUQbaNdO~rP1`6=YEjB-iuhJW%IL5h9iq3j>@(9!9Q!z zUAU!E&Uj@(0;k%T;r2Z`I@(4fYToKN;mYX)*2Qd;`@Y=R`9LF?`tr)nXZTOJ9d~t) zU+>FDaxz=%7Jg4pWF}UQIxCFv8H~W_Ha**9+}nI`UO9=%CS$bVtZTi7eEu-^`b&^Q z?L$4}l*;!zP&vSnb{FP|`_1f0<$A4=G@O^+%omgNmo$;A|GjXKj6#60#JZpRuo+vo z`lpI2)3|+8?oK7BwvJ%wLL2sO^ElP*!4p=vEM-WzF0JRs?#BW;6SaHsjMD;-sip=Z@cR{;WxHDmCm@m zH7Ofq^jIbkl@@}@8EgBd=X=9{pyF!;rJ{{Oz@85y`~@<7lJCfYr&OItGaS;R+PZ8i zV#>6ukPZEZWlN%j^L)jE%B2{YHE(r{<*M(Uxd}zqRK{9OgWC694F=w{f^NZ0Juj*v zkL;KZyjV_-oKi}jsJgD3D|cNf2*~9t(|?D`zZc1KvKh&bR={iAtdc+f`}~aHLH&)y ziVmuSNv!^ z?~jrWV`ReK=~P{PQH={&ts9>qj5%3@+dmzfo5n1hRGCsf&yZRc3mG4`nbqV?=Frd+ zKPIiprTVSMf3-;99iDG6vwwCKC$KF}^8GM%VRqK*v7Gr4eOFr(Wk_2~U$;-TZMJNLhSCJTjUJEL)o?xWd&qctu+nw;=S9OkZJ z5JA0>DoF3)FZ?-7?~h^z)8)DHi{9co$E%6CyY;=Q5Gclx|75K8&=TAA|59V-3ebF-mekq-tD4l zSG2_42-FA12-3Hy3U|Jp6k2+(c}baxiL%w0wN~o0i&>(aNRqSS{mz=k1~HyOeEzB9 z@qNMQT1s#kspxWN{)d)POV?H5P2qX3yJ6ZO?Ps2hf$?7#s~^q>VcRz99$D^g%Sfv+ z-T(2PfL#Xk67J$BMo+0y^UkS(kYn{eJ-esO+nc!sN&~CGhAQ0q{IG`ODvsL|+dO+2 zU+8Qx`@O52l=qg)XV`U54iwv@b!XcrR2WbN!L5JJ%zQ=CFFBum4!C)zV)I5h!?HSX z?5AMI&dyZam)2)2T}tez?mmp}#D{GVG}7mfz7;S)!Qp=(_I+NbU1?&6MvnJ-UJrZE zg!*UphJP#TVPoR(P(%7tbIMSLd%78aTbygT%x5n3>(l|Fxt+@Wz!Ue)2L)cD)Pd89 zJLx3e_^Ld)w>-TPO)y7=6jo)831d$ub4W~3+U;>a@kd*Zy`QcNl6m-V!(qjs*?CKh{bDc8sUQ_9l{;`TSUvE>}kjOQbV-n_P)1hp( zxLWRaj7dwL0tN&5jt!qp*$rx%G_FP#c`w?LhX;pDW>21EVoI;-8twViv_I9V-6-w0 zGa(^C8;zQ1^S?XoCKAL8A4KSJ`5EG0bEHxCPuk*~NsHNu=$_t|;itW#7h;Z!7-R5V#(uhg5mf3081H zwQ!{?TJeY6`p!ruwy)H$%>9h^aNriDJ{2gCPT%KF6Xz8yiG9@MeUqNn^;2$?f@7k; zk}RI^VoH+g-({Bi2}UT~_hrbZhwB>(d+Rx4d0BafZ(qd1p_(XUgzDVoNco4&Dmjix zCzp8tY}AvjQ8kyz=OCQBJ{kWOaYFW5GLv(s%5d1*vE~z+GoDMC+=0*4%67+hLC;z` z%bUHGBm#zO2CtGg#4*YtV!D!<->0ScJ#SoCyOj4ea^9}q+_rX0^xjU8SD({35U%vr zIy^g%r3bVBdisIv-G+&-S@@p%-=XSJ@u}*(@kWViwZnn6@&0D^A+vW~%4WL}@f;76 zMV$vy`ulwPys=Mz z@HCnp^*-RNZEcR_)o-0&wF6U@os+oy)G%Gq2kxgqw#gTRkJ@{@?IgaAq+}bf?C0W@ zs*gSS@9U$paw%p?zj!g?<*ODiv>z52+Dc!BCK5V5#4~n)H%BH}KMwm}CP{*m>^!wdX4eRSw zxaoLd0}4G~BUVor1XhehWjJGxQ%A{tYDFAu@4MsANZ z$eove$lN}Tk{cFNbo$zjl00Dh?95U3@Gd8dya9bI(AOu0KK|xnmaJ`4Aj(2vJeKoO zm$=Cu6?IuHa{D%#$5n^TxhSE??|G{=^{H+TqZl8Z!8g8qTUJz#+Q|2rl%$t`m_+ZE zr!M`O12Y232Fr=`lEj_K%pLhosoLXmFY)YN!P0HN?80qjABOdH-pG1PVy3?8@HZyk zj)t4_YfA*z=VQI$^a~F-ym+Gir9B7h3KdKN1X`S3v5S(+6=ZSB3yeLN zRHU6D*^PFM%9y1nrBH;=Eu#4J+!1mfc8i=Yn`kB~s;nIo-94fhhNmdRv^I%|Dihf= z)b$5+TwVoff4``I$9TtB%UU8=qokrJU8q69$Q=_vtrRR98ovMY*qkO8OJy44qq@_3 z`nVF;DY-(l;FaeQ#H=+1{Y@OeH{M*NAj=i9@l~_~(sP(%ESAa*@ zUBndKn`Hk5h5yF=Fj&5cZYF#upo{Z))HoI zCp?vD;iWHg)?BRjrrK${g|4%4ab)ED=HDT?)HpwK_ra$lFVpqP<>F<%DgTN@fz^Kt zNR!wB5jQtZ0|SGAz(56U?cvdM9-#BJEQ_=$Dk}C550k%p=hxpap{&xg<&afGtD>T! z48%6eIR+GB-rtKdS5gX?zgv{m~^}o#+iNli_ReNW!)L z7_ye-IGZ;_L?i8AUuo3Y5COubE|pBve&rro9Rr4~MWNWNhW(r4s@70eAMB-U*UJo5 zJ;>GFX}R%`U^+WH;ZRX+k>uaJc>{J~xEL9Xf0m@HmZ~atS1_vC)?hp)4$g*4lV^5= zb!b?a(O?|S<-r^(MBQRUQBnP}4W?+vkqgF~H-hTwxR3WYeOByM_8Vf?M~ib!$O5v( zGt72>J_ex>ebUx`IBS4;YLZY_WA^3$jFRNL0i58COW)tdBNTwLMA ze2r&IxIleYvgIg-Z_ynC5L!}7ij12ZUsR!>q{R67>CtMr@hTkA&&GNvwQ=_NMRep| z|7ooNgGwxIY)rnkwiXZ+gpQ65q-y=XUK$J5?w%g|0gA+5zRy0Y<+>v=Wa1vq`Bv-Q z-;fB{k#Z(Nii!$~7I5=;dF$M1H39c8TD) zS}LE}4~dA#(Q8u|izFPF)AQ|F>k9VF9MVbA$KY#RrUMQlei4Vc!a;U#pYu&O` zlm`U`#d&{NwYS>l8~c0`5b%0^V?$C_b~~8F=LgWWakOY&?C&GHKv>LVblyKUX7;E3 zE12q=m#8FZR9ILzoWYl>_ppuw9_8w2xo9?9qOrNPWx$-A5@&Pyn)+nGz7?lbRZ2_@ zhQ)MvH@?<0oQNl3dit{W+9fWVIv_aM@fb7|1k5_8jhJrKF4~Z>uwdj*ed}5?cc@rA z0xERx>c;wd{dS7wXg%3AA1OI`Kyx#%kg#y-a^m;zelr$5h8589`O{r&y?T7@zS zn3a{4NqnB{pFe+28ZpIY(C$YSco@(3u&vRgkEN2c!7kzj6elU^*Q!x&slh}<`xFOG zLU3gy5l_&J#nI6=oV^&=XFk$5T`tltg~ z4=KNPH}wr}Ioy?UuQxejkdTbso^5!R?i4j`;{^r(sFSnS68zhx_DOo+I^h2 zZ_oz&G)UT-b$!kPLv=Vq#*->*=AkKipm5u~}dq%$3_# zhRf!Ig^2}LMZ?DKty}e3+;Mp=O^E^KL&?U5RjN9)(&DMn;6O1mGt;tMZHkV8At@(k zd-dZRm9~kgX{F=NsOsDfo}y<_m`Vv|okJ#CK4S6ACs9$+jaEr(YkCl}d{EusNgG!s zNwkmmN+BO$N-!MVmikCGt{aa#kFI^15iTEs_<4ELz(&lOu}BT1lGEbjIVH~Mb8B5{ zUQA0#`2@VQTzb7uvy^)9+gd2m%qh1{(nyOyc)w{C6X>1jmEZcH?he&3v}MuENr*Da zccZ=HdBS(;;r*f2Zz^nPE4!p59IO@a3OFPrDDxCg<3@;?j;0O#y*jub{(R+0{6YaG@rX}QO3lC0)#$$o7{P;JP?F|hfkOv2CB|8 zsVOU*u!ydpq07_{JiEp>wT2>8wd_UUW2{Y(;>s%0i4tgEDXVGNrFMRUo4$6j{98?Y zN6E(|CmvQ*^!vyqO;#=T#|+x1g@w15qjxU@{x)E2L3qBi_su`AW01$r-9zeO!lGt# zdz%?Fw`90O>VlxEKfYndiNAUgL|ON=!rn~Gp=!zJ?Ck8F&HW=kaonPY9lnKlrH76e zG!5zJPVN0te;*Kd6_LS#DrYO> z5gHoW+hD_;9$8<{3CzQoEKSJe5Fi|kVo;;Wlsa-aUllw&ER90QIX+Y>K>GIW7bc_L z==Agm)#BXx`XtbyU=KQ+R%|qjfw7xVlK`_XC4$kYmnY{`R*v8APR9D=Kz60pFOp(y!<3re=G00U-vq>B~}IEjB6sGt~#VDRM_*= z>9N#oz)!~a+&^Cjz7KfvC8T!S8D z@JeY*%lzUOn%kV@Q2cGT8`n>^x8K2)i*Cg|Y|Di9k#e~+Vk1YkGuEk%_>uVP@U~Ig z=Fnx8=%UsAdoKVB>+9<&!|~_ZUwTPRGtwWfi3d>N;Yr`U%T{xl<}DXiNw3!)?PcdU zjAla)0!<_NRR%uaLBA18JYJT;P94BQExM~e`vxyuPl*wB?+CckWe;6=K-M1{W;%P_ z0y;IAtQS}Ts@pIdzDQ{fX7$+qK7Zr_9INMM)i(+RM2w4AcAKS;sXdXL2}X-)YLM3l zhK9)a`2o_BkdzcuQ7I}e)@X8}kBNyX(WnYa=W$h3QJE>Wo-=2Cfg_+VsW*y5PFfmC zwK)F8ygrYAmEI{k{iGUE>Y28wQ&LnEl9ZI(@CF+V@)iE4=mRHifB`~BOpPwKN0wK% zGvZRFGh-A2kuO}D_>|e?-v`fE+LLfU%2ub2nq79om3vwr>a+x8`Y?2TMyA;AwE2so zsH}`NJ!&ORfQ^|CId(m+&pA=Pf%lh=s*|6O&1;pAl9Vb!B7JOCyG8-JG53y+ z*otGzhcn{+xs_UX*xuGt4=Z*8(Aq;bFfah1jIxULq0D7Q-Oi({9d|mw+u95`Wa5$J zJUpqBlZx9Tslg!3%pe!sJQRR+cG$~JWas&`PxFP@aa($OEECwvx>9LXYjSETnctfm zbpNHxio3gWNhLB^JNK9AmY-m>)Dg$W#~T|PSKr~Ch7;nlm?AZ~p4hOzp1Mc@7)wl2 z5+0-l?|o;N-s4w2%{tmWjfdYLc&oFc3BGp@NXza&QB6^>7`j0R4zbJgue~?q^^N?S z{$5K(@ci^^TR*rv<1q)R? z9Cyu?>?DgCAxAvw7-Oek>fj0_2?S9EAUz%~)P(hf;ne+>0$~xC--}a2L&NK4*;QFt z`O+@zak0h{2c+fCRS3mHTZVg+xgh5-v#<>G_v_zZA5G8Bvh$k)DCJ!i=Vhj>qIR)T z>s|7VD8#3mu{s$4Ni~>->LRfc{an?0bK#J+v&miE?z~?Cu>0Z&kBOrt2E``$!q4fk1!Bg|txmcmVUe`H;4K*l04wdq1`<$kxXXK4SMNXSeH(ux3e4FaKz)> znD2upw4OCegU#Y6dp?}4-%yUWv1JOAw2gFHW2x7yA*I;As?+2DEK=q%27SLT_FRT0CH`4E@#xoxd(s_XZ8M^$rO9zwnevhBlX0!`=;+&<(T zo;$ASJuJnX=tFF*oQ5Or`2E5{$JMCL~#rtT&(IUyW zIlZTKKmqc-PjH<3$r5+^C}ma=AD`;S4fr6@v4f)(+N$~Cm#W!V9W+y3cvfhZ0!y^r z+$F>c?4&t*G;5}3Qx2QqNmN`M0|y6|_4UX=EENaw@UA2P{{VGy zjCNc+=-p%B;SGQt)Cbzuz>XnhVyXz%TCCjPw*bwnnnbm`E=@Gl)IUH%1ObfQdO^g% zfD~+w7kB}p@{cT$r$VpOzCEY&`32;qrnZc$uDt9h8S`sgoi?{w)YRUVdwQ>07vYWO z_GA6wGzp(eNYxUWJcH61E1g#8AQ@wkxD(mHSm9N^F8?uKareQ7C6BR|C6|e}!&16y zV{+a-x?{XPSGdK`H%w0zzrI&r*zUC6+n9LtYwF%RADM&+uf~8=pakSe5ab(Cx;C?8oxqNX5Look_ z#~)ib|7Mr0GTDAD5IHKHIXWbqX%qLl>O5FR*+Zc1;B7H>NfxWsYcdSYuuR%M)wZD~ zt-p?E@pmHB-e!L#Jtd=52za46n(44SKt*J%o?zyt;pth@olHkV0}pE1-vnF9a$9(& z3kzOMtNJJKP#Hh4Ffja=ZETy~EbF&_fegoG^4r}tx3IJ%K$L$C3tMM7ny6ZAP54ZL ziP;S*xq-n!!?`jYtKYw}`nGlEt=JRZYY3^RU~O$}`2@Fs?qUG7-QC?^!@xKk{$>Kj znhXH0VFy>r7>5Js=NY<6nUMAhSIErL+Gyva*oW(-*VXOgq_0BU&U`YQEzEg^)7)Q?_*Q3psXE>mtBd?; zF!+oXWE`Y__o(&Yx%WOOJ&{^mRgU!j<|O~;&!0N?7+=4BH8wMonptECv=q>L+H!d+ z{_OFV*#q2f4IY)_OSp@YnGX{2*O~Dz^SevDOMGFhzx#5fsv&<37ibU zNIh$Li2P2ADVe>nSWNA)urgaf+{7J{)k8tyrrgka6$f_3-&2uMDf8Qe3LN^azIPbH zCwP*|bbVSgMwV`_x}=XEeEn!1tLrW0T5M@Rq(5EBx_UT+7yz5pky#_7eM_(p?g$LTg0in_xNi@{xe2{W!Gc!H?>+=*P3^IOqfkF<%ODz(H^Wk{n z+I2?BguSS;@B8Ks3nmu9ni>4Z90N}e6geA>5i|eB6_`3Lspn>|zrI(mhFmhl|9s7T zAY@GO3<}JepS^sZaco=x(q{b6<`Jj1lT=G0fGV$29#kbfaP#GUXpw%36raSQX?cMCvWcTV4$P>^%xqAq_BZ9 zB&WyS02GhXX`C^eo1485O9Y@CU#zo*#n%Cf{rUe@ydK{=~&SF@f&ELY>gf;i-v7==ru? zNDJY+prD%tOW*Q7%fMZUe!f%}2|m&YNW}|2Epv8C=ziiqBV@R$?3X zgrjA>#HH7)E>IgCsquY&qTI<+REaOus$>2<`BT+%3>266I|1Nu!F6HAo7jPFK#AkB znxlngzi?>@^jcyv5znzkbfH3kWW2k(194kXM`vVzrg*-^(-pO@nM+0G#jinBHs0tB zGB6KDC9x?%ss}}6?^;e#QKiGypy^O%XpuHULh6A8>+S$M9@E{W{tQpLRWWyOR^tNp z>^L;Sk4rMw$&dUV2LuTPF~jxzL}Y(>UdbA<{!pS z+ENMlaeLCo9wTY!k+^s1fDy8O{tS3}ysuMNU2Y<8Xv_Li8lykc>{$wby$&g~q5yJHkb|f3jyE7u#9!Vm9YatD2DuS-@{B!sbyY~97f8(@l#r!+WA%c;E z5xp>C8QkBo1bGeh2{7mjE;CefaWI$7WMd(`*|1srFwbw|Ht4$g7SSQSI#?0ZIA0&XxoO zD6gv-H6%jL=)*%RK(B*ySyl7W_V!F5-hrf5<$RzD;B0y37Y;zH6e{H#R?Xuw>O%l7 z2Jke%EP@&u$*U%S(4?o2_=Z7+PDm*2?d@#@cW{J${sfE}0lKXKpv4!^0#^TR#hxdf zECk5dV%1W^sXUpMrOD$RMFa7ch*#{e)5JNg`TVv9cT4OXZC8CF5o^t7dZ*LbzGtQj zEyH*?!Fh&!Bo7BXD1kfnH@BRaZ>jICOpVL7S1(q`dA2DjDJ%-LpM9HKdWE9Z%+k<# zV&={0^^bAJE*$!w?Uv)5I+67`5-acXdoWW*xAx%`sIE*9?epZFAYWfPM8({-o3gVK z2$oYYdsEX8{bm~%@5ZoJ@1ETfsGxhB{4v6hhWTs1Y1H%^Vw}LW-|VW`hi^IgaQzvQ z`h5&=qi$xSGS~y6GM-aTrsdC1h(w(TY!yB#Bkb|(Ny*}mN@WFf$7am-H5En10?UFz z(Bbyf03?zJnBvg@T60dtLr+E72_|4EP}HHLp^bCKl>r)vj|xCPL-y2rX${Q?F<~I? zu%|}&`9baP@5`%T0qd$yL*a+!x@{`~Tqz+Tu~F&W1B8`pv2k>2s+5BRGa?Sd;S6yG@Y(M%F%z6il|O!baXy%>!Hou) z5D@NEbaaT|Yz;_A>a|uHQHf0_aDXlL_U3#1dzDjNU43>9su9460+P=d5WVgf+x+%_ z){F~Wo7TvKXjO6q=OWQNLVG<=Wf{B5eZMRoj-6f8-Bev-K`X;a^zZzIwK1`}Jrl=g zslVl@Q@kENXntzay2Zgqis91s=pmnNZ6K7{P&jxSqo$OY8r@)PW9F( z(0A>Agh=y9>9}0O<9@YT&T=D8CCm10-toCpbnQ#F=t0dQX0k7`qmNH~)T&P?mMllg z6VCam9s}9Y?TzH`Q@qW-GLx8;K8-GJEn0E^Z1ZvI{L$;(I3!g*jYeGknIaW{a@Y&) zwzX7S$iRV6mzxGs`TTb|6B44L&{4-OThf0)5_{2(e{Au3% zo$7aeV?OA$vhi9YQWmAloeSjLqV68`ik{1_YhEqndg8fi55A(MBbs{V5?4^Z2@C#IH|jOF++dBnzm>tLTh4t)2*f^ zsE8Z+(M;Mvo=%ibGe@c^t*w=(Y0p)Q#C6gy{+gT^>R^wo5YYMWbsFPdYWY;lt-JXZ z`7MWr7yT>@%xy8!|C{MqFw-I&f%l_Qbs%Q`BI8x^VZ(188Cs zdrol)36)-V=ael1-sxgFq_ni5KnbY=5Cs7dk<0D$Ei5WAAV@(s^7sa9Id>Nz24?-R z9-JMqCN!y{gR@KIgb3sHO;3-g4C zV#4fhw9a~LqX+Lt{K<1=t87>K!IS~VWzHT@(o){H<)EOh{=3+*xY07W zu>7?!h(ExUfC4-{H&^HOL}d%a9a7Hvcp~}<8UP5ruIJ5so=NiLGG#%01C+@Nq^Mv{ z-|>;vI&^Ie786PqhlQnFs`%c*3;A=xXg5p_4`1oo-+hsAIVln+T0%8(!>^un zoTjFQqj-mQCC}F6O0vOn~lLbo6!KBvDT`Oj_m?54OTe+;nDq4JJ?EEx0IT^*8!MHaWNAtS1h(vrcmL}JK0FDY*pb6T} z1N;Q`n{*Q6*QBH*cEqleCtj6$wqKrDTG2$Rp5?L9U5gLu^ z9!G{IfCyhu+~?1GG0;o^T ziMgM<+JASx^-YZ*2zEUeaY68(qGT;G+QO+;_Y*PW+*)A)eJXee1~gr`?zF_Ob}9K3 zn>!6Fei;v-gUEsh=y@6%8f6utoV>ggKu!*uvVgV`Kz;&E6R@D(9$hMGYJGmth#}$O zfR&0*O2YN?_lHNYz&+E|(vkvQAz+CP7wgK$jwFhT20^REe5*GPa9(g`CMGU!np1pW z>Hvs`b`9Df56bH-quF_~OxN}rGXrf;quTt`nnvZ`H#n8_czkfv6ghPW0kcUdjfPj>K`%R|CzN1C5lAc4O z(ip4QQVkrrn|FVXR#mN`(3;@~(d+fe@KQ_Dg2Nd7&Ll1x0n!j(`{O{?dky9`wFA($ zuzon6qX7xd(cf;ys=|}rmktgN^5d{Ns{$$ztl*=ePER2qAUU_HeJ-cK2O)SH`cgr9 z-W(qt(S|rqe=o#n=-*hoJJNC=jDxFjvEi6G&k4%|YvS4D@zSn^{>Z!x4*G;R#?Dw! z^lHgqSzFmz;*!%?Q|$t?Je)rydo?vf!BL%&TmJm6%ps1HGq5`g&$MCz-wRqQs`s?D zlt2S;Hc8dIl~vP`p-pAHkwZH8oQI-qPE?dqlOF3;-o2}DXZBRcMG&eFhpD`r)d>YD z8xc3j+A~YWbY_dzI76z)U?dCVWG~HJf8&2A;XZkFj?x^6pWJxv*mQ}TE#7U2MeKe*2OV{3>EthmfF?df5U}}SE#n@NclTXv zx_&sQ{pVdBW7;2}849#d38j(3|L-`{I+Eo7eO$;)0_uM!jyQ$U|JRb&jrYC%e=T{V z(Xan^5XnBsnB?VZ?~Ipb3)+|aQc?Uf1@Hhk`yg&!L%{b=rC*+Ta;crR^ir1-nUI1EuMqk()**0~uTdk{h!ONO7M{uwqD1kT=vJ2$ zs;c|`hd~5E=`KM8q@=sMq(r(Kq&ua%Q3+`fkhnBRcPou_cV4>tzMJR!{{A!0IOAN; zJ@@Q$)?VvV$JL@`_<;NV`;V)s3$aD8Mht|6dW+nqgfi|bg8%*g@N5x(fA;uk*ttL& zy$(0tUK+-Sk!g?`B9TR-1rM%hxYW!1gun71Th|&2q*#uZexcU-qh82Fin8 zzU`M~L$gdU5PTzk>6}B~eRwHg-U&eTP+COV;&+ z63N}a~#}N@RR;WlG-?`=JsLe4+LcWm- zeH^UiBauBZC+$1h<_;>~D)MXl_r<$<2Lm| zJ;Z+b&yDc1KN+5M`cQCFRYHH0Sn?wj<7T%9=jBr{y8Fy(o)IBau&)&|Iq7sGWKv&&U!e^f=lbDl#dPHl6}x!`+d3VA%^V79NT ztM+}9gy`PVUd$}mH}3Z(Km+DW@XDs4L_aY$cNJAKU^GH_t6@PPV}L`;B#)4g%K5-Lg>3jR+6F`*LJgd({8-3p8HW)Mn+^bltiY4>cz8SBFWt zJaXRl$1cweJI_GLTdPcOC(cATp6k=ctds6lOMxoZG=wJiYS;?>qrsl2zV~s=aGSnh zULOKO7t5&Y>$c^%X=u;-2}hG>i~hZ@aATQ?%gx@Cl`V&o<2&;$op7do#p4aZ?8h=3 zQcF zFhZ683yb{Eii{nayuC@z?>iQT!?yUarMW@Yupj<((I0Ej&04cAbNyM2O~l8pW*u)k z3j3++v}s`E)9hOYG?_uG&a15X%6q7z1T;&oUkoS5{2_vkWw}s32*j8zh1l!G(-uf( zm^OT6*Agy>(egKK%p{F;luq-8C+@L0_++^;$Y78}EO_nBLrs`R(LI%5XXKn0acmCP z`Qem`8s6`px^8z$T3<(-SF=-dWOlyTqEHO`=6|$VHFx=e<6aOSM4$ZLTy-&Ge)|4S z)O~uDU6n(Dg6CiEG_NC6gof`UZhQoe0VOehwN&=7sI9wv3cJg*(8&Cn3$qR50U&q4 zFgQIK3R_w)9SFrS!aeO!Dqm%$@fk`m-=u?tN+HMF`-Bvfk%v$1o2f*|?x&rI)FG*N zWEV2zpCdkl_ZA`t3vT&O4LFN(EF|Px0$@!%@nJ%F|W=qCl5Q| zh|nr0vBO%TNCl#K(7)=C^rQ`dFn?k8%_N!k9d;q55CwM2`?OrQ_*sj;RBI8I)!!usqvwxUvf)Y|VldZYKxU-DVPLzH(#4pF3 ztS2X|Z4Z^KOT-y;{_*{8S3ZB+0?L7JTbtapEK%rK{o_;jwnKy^e{(tXUPd)l-UNl( zQUvwG7{1W_cj?6OkO8$YZilUw!X)LWn_DWJFR&Zhkuv%1ofD`2xNT>{0i;XyKXWD& zUeeDEnjVCbevxkc{WYHKH*|G#sCJg(d2wdyzG6be1r58m`5AF>wbY^1(;m%4FW&K*zz=feR zP+nXNojR3-Ic;aS*Y0h6!VS@Dayz-%&Ke+|%9l5PZ>wM*k>2axD*Qt)j$EVzZZNv} zRN9+iTXxCsRHH;4_aiQDS3BEQw|%^EmGPvG{Py@@vi7|<9fT;p=x0YR+RAr+zp$&6 zw$tH(tFz71+qNIXY=QQVM)){u+BU#Cw1Z{Uuhv{)$swoj^$mk-TbY3WN7hn&Z`75y zn9HFnD`D)#P~^>M39a7a3{( z(qiI1)^D4{|8K)LVZA$y!&C7$hUP0d!pE1VB!rM>pY!zZ*voFVM{efPgiWq%VaGws zLLIhYe!a_O89geHz??!uk^M~?vT0NF9xFSt4Lb8zQ@tvK(KjbL-YXAS!d~Z!t&bS5 zRS_j)OmFQU2c}2l@|b;b=tZ7gz^jj^HT)fVF5hx@*pvm83FwIS6YMZ$yGU7~2bK)U zDEyz6!~lKD&B@8BD|XS=E;G8DTWFYhYiqOA909<7eaPhOb|7LDu%bIu-vKppL}V2f z_CIemo0>&*5f@d}>bn+wX1v72JSrOQrnZX0@JR#jDYP0P?t0xam8|DLTYCQ2p9&M% zkSzre2gQ^9Xxt0!5Vhht)Y|RA6oht~EN`(lnC(Yb?gP$^n@KvuJGW0zF@S=YAVYM7 ze2vO&TScyIWuhV&{t!;B0mJMs)&MvY*C-7R4a2b-BQEEB#s{zZ`<->6_OgZH4*WAn z=+v4h0vU~)G@}q>bYUTK38NCG*m(|Ih`ruOde-Z00+MNmK201#J|RCiHTLl>Y${ZN zOXEm}`(PS$DvF!~w~|%IkJ|b%8Yt9ke5r*jXAwtv{^VKckiRZ#{JE=+ctg=ep4}nS z%2KkDi~(P1*Vc1UxZRJxES=E7xDT}5-ruFWUgaAz7fVLTQvEfzeR%kM?Z}({yfZg~ zWwMP+s30TKil&h|kXDCkl_I|v`m8Yy?w!2$_>q+GqkrVzJT7JfcV#v8fG+Faq^~0K zpSR~8&8vxk>ITqj{H}VV3k}W@ad9w|3X)@l)_2@~<2pZLH4$;t;PUeGjVm>upmcy( z=meG;eu`RB{0vqYI1t_l2#|KMJlO-Rr%E~w?3mHamW`t#-?CDCOP%b`Q|6a}!#I7GAFS0ig{>u`B_92nWUWqhZn zXGCdS`Lhr3>*v@#E+Mt~kC&I*)zyb>ut$~H>yWUpYNyQ)K$&@`>yVh53al|IfG;pU z-S`VuIpp;8lxsw<+8hmNirB%*Mw4*Io}atKlJfrR;yg4-nCei74=OC>JHzFWdp_o9 zdo-uh26v}=MMtX*J%dxVe$I+gMOlIABf5BL(QqXmMC9Dd#_~_@qzuFJHbQB1TcAI& z2u;CCvdczDtIME+nA6`#nT8kfV+q%Hq}pnfGOHXln~B49dQF=MR6FGa{o1UdJ2@zO za;07OVun|C>5{Hrg33 zi=KP%{WggStt9mwq+U%z|n=-V;M0ez( zkSUM?DCF!`EFwI-9v~>6{cVXOlvS<)odPoB@Hi#Ig=@#|KALRHIa!i+K;xtf+mp@L z+WpGT&R#xX&8L0I>Ui>e5UWt1CK1oa1tHkCAGi*Hz_`IDbS4o$g#(CkH6Sz{NKOp{pyk9y9c0=a(Hs`c$}=cjkq`Hk_vhy0LqW4 ze&yNI^q=z@Pf~iO>6CIw>#%*Dd$jWf%S~k4@p71-jMefD(GF(rx!;2GL9S^{HPeK^ zBf5}2E8-BTq73Z%<`AcG-xd@3dFn4!W(J0JAf}K9Mv}ZdDnLZa$jNm9pdA>UPS*SW z4h;#eD`%{%U#gd%069D%r}b{KuuNEsBQN(d*iZ3uN!Y3 ze1Rv-VTy+&sH1S_GdLu1R@z@v^R1FukCr80PA9yyufaK~4%2f*jLej5|D?Q6MV|SR zCvN(|%(riQ;Ln1VBw znVYGkjSL*$rDCuq4?#pMmBO|dOh=(wb!#euKytEI2qi;83NEj^f3sVS*%(pBcjj5Wo0s05mTgPVsfZl7-kZuA- z9KdW0@dbd^aBS>Ch3sjWUb`=d%E%x;T{56H^m!+OVs2r(cef1lZQ7OwzN}B50*wfP z{8)~y;w6QI4sN1QRW}Tkc4B*h_vT2=;6@P2+(=cyhMGHs<`4E3KrC3v?~MY3%jZ-n zuoU16qsfIc0U`{3^pjBa_wNLNj-xB^j=Mf2sLVD7O+(Et_9j6BC@>O5SjjMfTvn|% zU%|+nbIrGLv0x7~me+om%LKA=P~{d5jeS6A-BL)SWoCxfX>Gk#V}_VhFbRE&3>_=F zwG2R^g-G$}dr`{2r+uHZsnY}&$m6Ns>74@;FF4qR=oqoh|t~pnwlCxUGb-h%Wv;{JESz5 zzObU=D-b(?&nRh!=Foy7j){ZQ1)d%NZBI;0H~_IHK)>Dl;RaZu$zGKJx)w;ho<9rd z<=9X#K}Skw-X5Eez%CVQ2Sho8#;wixjhK8w?ajCz^w>^8QJOF|hG zkU1yorx_rTm^p7|dylTp{?cTvIPhE#ySI+7x+;^!g}q{Ku5cXs^btJz zhC7imC?(eI$ zvJKYlDtj3na;Ei^anrqy^7n+(Kol>~D>s(8(?8UY?}Cjj&v76y8$2YSs?JSL?t{ho z+8dL42X$#>R|cM)>t!E`af;FM?^{okAHSEAPCnT{BRTT(nOa*C&<7QG2ZkDfn{d3S z$Z8Q!GY04*W#iv*zDn=x>Pq3V)oz+j-}i7xU2pb0dunZ#TYdEOx80zVqfz?M62aW* zf$icEvKgI}xttfjPPG@Oc{F|A5{X4%4;;Pz!A|K*I{i7VkY4DeKO#BSNyLu6`-3Wb zjc+#xJs;AfP0x1iIA;^YRnbpTe~e5`ErrEMtoW`N0=YgPS0X{sS5tdptALUp4wYPp z^vA#?J+Gv;_8gsbWMkCwk^TMS7)K1SQG*U2`9Q=Xung)WG%E)rJ7JlxM$PWfp8~Bc zn#dN12kq+OQ&RqdT~?8=25h)5cj-eJw zMWZ%l_HbWX1eb$KXkWHzIl|@3`)^EXZMosTC_L|RwEd&J(me+Od$REww!;mcF^&q0 z3pva+w!@mFn-hzq=)KTf?ntgMP5Dmr!h&w=?H&VaS3C5=m=FmVrqqhnS%LF$nE&X> z^g3^|aitm{k_o|O#~<@L3xwU5^8a@`nr5nkZ*)bLCeNg<#?;2)7RD2Me=1s zkPPEVv?MItrn9$@DU$6QE}=H^9?eBU;$h-VUDJ>JtqJw^tiE!-afmz-pP&QaoRuzWf4^Gb0-CzsPOR5sIj2FZl7@u;Ciqvwk%aM)Gr>Q zk09?bsK9@T{<-eTTjbbqf`~i#^P7ZZsPT6*b5I`@f66^8jx`?&yv=^{0_b|IhLq+% zua!>$nw}seG~<)C9$@fJ%*naLVRG4C+XI$jFy-+aHJ>5BdIgx)&^Y18`dQu|dTv@K z2$iMlK;dmCqpT0eX`LreeeG>+LD_JKQFrFpBOkC5$Bb8l-m4K}l~GW55iqgWXLRj} zNrsUhf8=aRh@_TyA)1&&do8w3E0-#++e6kHyg86iz*Gy2{~QYIrvuFP`w9NHoZ-Nw zwb^pDWC8>MPr1o0ngg}G8N4vAk(pvHMncdd^X#vbfaslLarM)#0`_j&K3=60Q z3xsw{R*kQs+)ror*iuV+C0@yycCL}s-^|TYT`jpi1t#3qGoh5IsvS(YwB+QxMJE>; z1Y%p_qqDmQAl>u_3Ia|Y4d9aka-^rG9q5yQzU7gNytt`aJrT%Xo)X!IQeEc)WC4c? z3YBdwOEb;E-$5#N%Jpa|vrtqbpn;ZG|v^jNM zN+rFq#<%3hC0bfo_(o7Lg}y+I|Kqj_rtij!YX!O_95^GQUTZfK!3$IMih0hEh{N)7lF&Smt~$=?yxheD~RwPf&y?kw76WEYt>n*Mt7>V%_=+JPVyZ*+ z_}#Jb@uy~1CS5atv{V^vq{*z7z#o4oH6aSdU69MM<%SB-W`*%v)i)mWK-pf3ZSx!O z0O?MzBA4Bo9fRyfpl%(fq@fALG+r zlAC1qtS(2aJopaKidQ-lQ0J9$Hph&n{f27$17Ups&)%Vlmm0A2fdjI>__$ zbA3wz;?NF+X~or};%d68I{kG{`jXhRu%u6mrYu7?l`G^d8N!K*rk__u9}}*LCi~8c z_F}>z0c6N4XWU9}bD(@eZA*K;eqG3=BS#j%rY9jKkqzYoP58C9(9?V&A@RIV?n6ar zaQ4+VsfTo4=j;2kktf&CzdYHPWt>o>r&ba4^j)E7(8UjKfg{_{(JxD&X;e7y;sb3X zU$fB{Kd8tqnGqG${HV7gsVjW@P=Gu6>KI=ZP~BW4DRr>GjZR$>JU^Ggqkm& z>#fpSYS_c=@M9l!dQ#ul!-hjN;ahBQnD0+Kr+(mEc)5-#k|z zaR+-oNaJ{sYQX|DZW~ntObCWRlUPvm)4^RuEs==b0_bU2z#5cN0K)}pm*GQW4RD$Q zWl4mrEGjuydUqZbheFrURkiarI;8kZd8L|;ayO&1aU}y+=H31q{WoGKr|}c?E^<6K zdn}(iH&K0AJOipZOGV6{r&vBWOZCTM8j^=Q#IHZeKz66o&ky_h-UNdb8jKoKpYq|^u6 zf3puh_}#!|4x~)1s6jvlc;&>%KfHbB>T#fIfKdYS|HGs!?(S6EnO6T=xJ#jUb>kvQ zS=L`R4^@+I#5+wM-3(o)7}e#mi>~tFMH5BJucB9-?L?F7|K$|Ln-uSfW!>4K2y` z?SIO8nOE>uR#)$}$nxopCSoV#bD?c4s|HWCx?o{TO@PJ!A|5E1n93%9_W%bQ`fI)k znjrc@zk`7f1K`t|)zeDTuJ7d2C4edkwDK_{11zW@(}dsM<|wh7gt1}KuB5)feis=s zfo#(%zktWoY=q#^U`mRG&^nTQ%vQUVc5SrJg(P)Z?y72AR8rDy!?k{O*RTgE27L|{ zvv8Iib4#!v>~2})fiJriTeAq#|D9Uyseb~112r=Qhb98nq!+pu}@@U0fbKtJL?eW%a;A1rXW%)ybi9XF`Rqp<5YZ|2*ey`6Jeg3S~ zY_$=Mnd7$O86LRcaD!A?ey=sk=7*ppb;=&Q+~L)lqxaONW*g2Y*;v60*;Z(|wVO>^ zZ6iI$#Y`63C6Pvig_ZI3h93k-uJ(Vm3#Ju5R^NlEKq3f0N?`LkKd(@ExaQALckj-2MHciWp(mX6y3xforA6BE6? zVfmIZMaO7e0C5H4r$0kO6vE8qBWAp3 z?B|1&;Uho)h#MmEX4IzXX?pqe2^&2u*YW6AYo}FBmCNoYFkw9jtU`@gd~RL9?R;m` z?sU|0#dTMgLkr&9AlRasHe6g*W)5l%@L-?2sogT>T47{0`w=QkRs>6a6L@s;_1?wa z`X%*~2q0w>#<3*w#+va_xFoU>Kd;^JKW&9ls3bYAOL{gRZ`s#hrie!3 zd8_pm9beOV!rbqVyKpj`LYITEjQds*pX5E^z6EkLPHFP*yoC&YTqW!^E?M1@rzZ!_ zq&=N6kf?)*5Zgfq@a~jZ04`-IHP{d$rKAvnM-iKVAgpgazakq`5HlNeJ=OV0O^c!m zLn+iPJC>Jw^irP?eGB(y)CC30vMZ233;ERKR0T#x_V+$y2JWM&)OzbhMM=`h7*A@SxV4Nnak$?AZx>TPsEJ3o$n0njEvJdVnYAs8P+#nBZ#akeT2)>==;c_ zia3g$>^zVw|F8u=1-r9dGB~j~oU2M$UT{YM@2L@cj#GX|J*^O(twj)IOp$-#JNwif z1%MkYFhEi1A{F%cLSqiJbaY0bNdN=r3%%*tT3ekq%V+?z0k~uk2=2f$W47Gd(xUgv zx$`h%ezwK=OW3d)$+V^x5t|1l7=yjf$NUNlc`9k9!90YF_F6);gY^l|wY@;{GE*(7 ztKQdopJYCc!0+U14~7#^*=xQuSF5lDkz_?7eZUnD?Oid*kX7GJM3uEfj@pZ@qL~-H zUKvBRLXE~PaWv7o@48E2zu-OevSBBQ(;ces=prOMq^fI|Uc>8(usNy(8}~Vb-eVLI zsp#He?~lKxdnzgsPeR|%f2O9Exh7orGHhlW5jAXK`au&}>BIWQU?_Nk6o7SV^~{rG z0K|lN2#^6}8e9n8T%UeE5Y`a{O7_*vHZvx21;9?pJWFbU7SR{f6!+W4)_Px5!<*C1 zjMjY6t7!#hI;SNnNBv-NJaBrvsPn`2f&R)1Rj*h-Xgl+ieMaEzhmZ1-2gBC1&Yo~R zOv2<>Y-cBZvlTLy(Yx@>elr5pwbeM-FpjeD%KR&p2+li4(vhD6#>DJl17AVb^||!o zKfKw+jzsXgF6jJic{4cneIz}#wCpuRT|}g$q>5|U0agk8dzYH8K~-Q-FZn$9b~fX` zVd5v$t2{>0I(2GwV&g#+3`Yg!yaj>uL&2N4ZOq#JlJ}=}1S0}x@O}>$A5cZm$omn6 zZ>YHyW1hRvqx<$2+rREC1)NrnX{4xWPdU4=hFbZACiuwULhJhJOk{sa~B;ORX?YYW-5#IG|k zerOCI^SR#Ue!^Q`0L-J!SdZj2;w!$CK<>s3@|0gSm6AuhFq0FIDs; z(gUNik6PTXFE5d#K|e=`1lrRs7GnF47c?zC>Q~VbUeQQk2YXukSu3`2+<~BlQXUe4RHaHQUX~S_%DD z@aXAc*4oKTKGSi%EHK2}hhOb}#l*Jn?8u}*oyTv{$y0Z>ZyQ(Pyir9+gCJb549@zOtPzjXeOka~o>G`vPZOed-cV~DieN#CH6N69lU zyqmDtPk4OcCq*cl$SXzkZ?9y~J$p7MJa9X)rP<7SpCbj=?2J#m-Z)t5FH8RrP9&Rp zu`zCXp89gXRYEHExZ)v*`A>!;XBUazkk5v1ZD8rG%qN_)N)5iThyurt0}d*Uek3|q z_{s!a{wUSvtX!v(Sp& z0uwQV_Pf$i*9?(2B4E@9+k%B|YZ>(E2B*TerLN<_1A%@yw3_enIZ7vwzqC>Q_x!=r zj!_b36guwgC_|zhsTlmBEIRDzsH90Evt_SIn|yI8<^9_d(wm7pU&NV}t zIHtL`v^~T}4*zMcw4l6K^!3ldW*4$Y0*%wv;hqJdd3C?h)*uY^O;*FznCRsPdY#vb z-XF;|8{&?~C^1gGywIkS2}=$?EP3_xPLSURG?f!7BE#7^33&zI>B|*xaU{)PGGF>N z9ux6lRV#A*i;iRz@LP`e_Fa%S{*GpU)6{&jC1KYL1825GfNh6NvC_@azVbP-49Y_q zt9Yb0nQ2(z_AUh;y0-_mP%xh{6{*;NFQb0CS=-aQ3yrw;UZOje{A8bY^`PWG=t^lb zL?@dF&!kmJUz_(1S(}jwhX%SM|g}K`sMyBJF<_7cSgzCOJU!fR~i^ z5}pa&uD_l0)H>boQ8&MjpvueyT|c{QteC3JwX83&U%0){SD{^Zclzl&q%@$kIP;_y5HGbb9w9HIfQ;39{v?EAyY`Aoz$VAKQLEt-d zTOdbL0%y#{S8mg;b+FKACq#plU$porBQ~?Ua~FjN-Qp{BZ)1Qdc!x_tx+E}Hu5k%( zS1e6fs$wwyAjFl;Le7v{8!h06j__C)%goO7=E4vq zX_X+JcrxW5-tT;p&sOgSt>El4!r)vSHslJ*rWD#ud#s-Q4j9y7OT2vo2fbw ze)FDi)AVXPtBSf${4|)ADqWVwdcr}9x+uZ?@NHXHwc-6lL$e`D&)o4VGEQ5RS2&R~ z2AEyuD)-aXmejA7Y)wIiN`ZEU z*Kz4agT!dZ6J+a(OXiFtY)nNdomn44D3q)TwQM043%A2xFzC18a@R`9P*5EsD+W<; zYhV9&nQ=RIv`ix2&$jo?tG;7Qc6rMi!WCSu$3i?E%RFPNWHdJc|61Q*^4&Nxz5#E> z=>C<*IWx@MU7s#7@mGTS7saZ?MDn`%I4hJ6Z13Z*W4fmgY4y8PX$=CLRGM1vDa>&V z^d5eT+akXzOBdC=yc4)sBS!y`;Cz2ftbYp)BaKP#NqiNW4ez+^6VxMar3oACYOY;n zk=(>nP2k;|wnUuGuh__0*&u`JENq81SXcFn~f>ce@{mEyPV#PzUv*v{qTF@s9x@eN)4IJmano$ zhm?X=NbI3pS&ccVgUP@1VYP;KM4p!K20Qk>XsO;eXWTt7A5WygHUbQqW8rBdBk62t zlelsjUY7%{3vuYLN^4b0&)ZGi*?j>-xzEV?{seI#EzofrmcBfFAJez&5!%$s(*6;d zh~tM2Fy3zUa8A(Kyj{NQ()+9=I0DP8kH?6)wN_I>j-ZSAMryfy``VpE>EsIbkhpx` z2d5^gY%AYDop|=CidlB)tS zP?oabEjFS|wotp37dv-Dihof#pnjYIPzNpb0&EnIwCzkq006l!c1(!jGyHRMYQ{c( zJ_7hljK3lro`RrbrqRyxXY`PK4h$hw=9#$KNDR>LJ^Bp{`ftr1+naR%XSQ=Cv>QJf2T|R|0bWJeA)Mb@E;wXGZ1QW4!xO4O3GDM2r9}Kooo=$ zM*M$Yu5L{%!ig3Pat2W$fm#SkAas5OvRUbz@&5)SggN4tXMBlvEtFRo#s71LZF>r2 zE|mp>>CN|#4cFC-$=?sawfNu2^?!!192DVUVB#^|SlvH>{2pjmagBc1y`ww1bko}d zZ>{Ldy%HXT^6%^EyImw{c=+dxuQ(5p*T8w{%dwesF;Q%{>em|KQrqS?6GZV8oqze+OtEBD@RldtTK zobu*gmVn_*T}4^F^W-}lz4gM*Yn|RPcsukK7&1n4W6WL|{b{tv3~bfF^VFbEhL~uw z$83J~=F-6P5(k6|YBkmGtDKQ~#Ah)!g>1XKDkLA2{xR=soGe-N^8e&MPqYJ9xX@i3 zCp=(vWQcUJAkWmEecY1e+%v>n4a*~cpr5)wBrbbc=i?*!@FKQsZCALhS7@FVdycQ8 zGV`vyAvLVEaD%G+Bf})ruP-N}TGMNs`R2gh?{8^cTkj)NWDsQPKGV9~FCk`_OjBud zt~YmDujfcT5$nF+;m9YpxIoe5q|UG3{;(mQ{9(tj)yc(AjZbdsKX)G-;SBrZUlXNr zs-|~vkY}Or+PFBa&KPZaYzdcVW*2&{Uko;5!=^tKK?)V-B&6E=gLPnoEzWYh2`Qpd z=MwuGF_g`6a|-CSLOvjnxy0%piz-V<0n5$5Bj@o+71i;1+5?Yx*0x<-GoiWF&^Ud4Q6D=HIEUM&-$JNilI(i~+fHTv+_#ZSTLo z59gHs7^`p2LJ*qDh;J#DZpW=ji63!R06Q|MN-bv$<#jQOVWhr=Dh zG#ew`^DY&I$FdC7SmFuhAc)k5_uH@?4R4>%XIVZfztP07ua_v9onnX;>p%S9q>mAS zGg~oR@Y%*jvgRYZV`UTai@Q=6=tY=xKRJdeP@g9Js;6amPu;m(R~eLIJ5eu=A)oR!Q_5MALR`S1)%_&j}_UW!s zXt}AI?n7PT-?@wt*p{>ErOnOoWa|CZlx*U0IB zBD&R!uKI=4)Kz;bwoHb*WwCP$Uf67d4+dh5`uARWi>+%@v7m!jet6OtTPiqg;lIB* zPK+3zeoFH3H&)^h9}mU+6|h?Vi{lFJg>z(~gQ&+E%R9vknGb~ivDJnc^X?WZhiDYO zGn(&|2t`Y39z~zkgqYgRcdVYmDRjoqX#v zOkP|%y=hCZB9K5Q9vR%tjj$dwK25TS|EBC$Kr9%IA`XS=bab5zqHW--<%H3&d-bbI z^=LKzx@z`e`Ug9syFnm0n~|T7XnJsqwYg1aW`E^Ck41$>(wDFsFROswr|Od&vy15Q zY$#V#5_1fV`2Vy3F@`hITB!DiAX!Ov^ri~k8tZ2BfA3;?!OU&u;da=8&xGrAL9FyG`dz+CbDG${WLR9lv5@ z&60}SC+KdUbg??ob~lW!1l^E?E#M}K`E#A)KApmLlp6F8eI1L(mT9xsfO~3KXDRvF zZc zwK$QyntDXRWlpTD{`cRru@(;(ykds1i{gVqe`4P6v(=$L@sG?G=U$W2mvo!GZcmW> zQTj zV$hT{zRA1k3MajHef#Fvee!0Hf#t09eAmA=bJ?JB>ZO14l1=l6Q3__|tUVm=P{pFx zZ49c3lg~D>!9g<4C^XbB8ffZ9`d?^y*&Q>FDW!s!mQg z%88NRm4ZI`7e@C*S5A{oxZL#eB;n59-v(zA@$K}maSP8i;O#vBgPBuEdA7;#>7l?m z^@lb`ti4p>t@)|Mr)Vp;mRsq}TMlx;_o>MaiF1tyx@V(4?`7e)TkAZoPvUq!kjjoB zsgXB#>2$SqlpnQZ{vIb*Eu?tJ=)0l4l@@q}&7qV$9pw~L$yYs^jw0f-0TIKJR}|}V zYuK_rZw?M6oe|YL$?ScnH3yRH*DGBF`X+7Wl(;lzzwFP3`dp*( zzQd!0qmw(_4ETuvhm2dkb);lZ$*0?;XHvk0Ir3isL2h9yQY;7{(BVqc-=PlH&wB;J z>P6uZB~`mGt6Ku`NVuMp(C38H;@i;9V8M&hJqtt*{P&BFkwU~vsdnT}y2=RW``3@$ z4niZIDzhFxy3Lu%0!zni(cfwzGC`-3HL%@wBO=$ z=^o57{O>8>WQ`uaBv(5L5Hxa~tcEMUXFgWbY~guz>L|7RXOMFnXM5glkKUYdByY0i z!BUyjea79p7q)neEByKsa#Uomln@b-*3Nc}*)B82zxP+}OZCWcwheHrL12&oHd=cmGusepXeT$y}m4$Kd|rp@)=!e>G-u?8*uiJyjWej z5bC;Z?iAMM0h;r#X&?4xwhO1Jk`scx#d5@zPyfmIxuNQ1W(@61^I-=E9M8xMrs!z4 zP{uJd&co5j&ci7AOHdg15@IjE|A4ha?k}VFmT`+Mg~pFsf)u6)jW&w~E1u;sZQbaQ zn;$8hX`VQ_2f{rZKg(>oL7X5^KNhF?qy6x*%g#5x?WI^m4AHKhT1$D02U4W+ef!GGiW4>+<)(j< zm|sxkpz3Fr24t^M=G`9SvbWxhiU}_xtdJ%!~{=?TgU+gY>(h*{5M&c>1uiscQ2~rn^&Kt^|EEDYMXy)5IqMO>( zL^Z;9xFaODxv8LimC;`O-@eMQUjizQ#qPbJ{(Z!eRBdl`6wF*;aFqHXxe0>c8dYby zd@pnr4I+962*w&0Vh!O!Z0>iA4sXRIujnV5Jo%zxUzU*WU$00Z2~`tQm*Jt6dXjp< zbg)}tiH;eZ$N5zoyVeapb8Z4yu0>}3t3w2@PP|-+Z)_z+DRv9CZ`yh!r)wG>K5vcu z50*iev04<;_1ksQ*JFvHA-fL}n%3=`B&d1U>%H;!K=wZ6O8Ab%WaLH4y`Nw>r^nx= zQ@rxlN5LbX@$VXs)1gjt!Sva=Q?J{TQMxS6pS!%)3m8-*KU?ZVOj4*Ms>uKGH;ey<&YpWZ{=mUd-PW-%P!Qvav0~z*Ew>e699_O>kN6kNWg*HV=3T$HlaJTA@5jz$nIa&@2l)=alr&j!`FIyAe-_WNMp~=BXTgZ&@1lGfjMRslOx`N#uaUpU!#@zuc#O_)AYmNJ zCb%CcIbmk~GWE7>MWrS*Wq1C#1%Qe|#4zOJ2vT`*jW}4AKrS z4%W8_WB8r2G8}n_wHm#QDf0|BB1f~>W1LAeh?eb|l$gH2A?3atio|IAxZ9N4`GHUzl$p`)~;W z<`qUaj@Lc=%+llRAG%uaNXUq9-;6}>_1_3D$gv}=T;y=ylP{NeCB6!RTZ}4eZ>?(b zzLw7PTqCJ!iZfX~zuP5*tPCv=7r3KtX)U|&jlLDij2}cSzwdQ-?=gaNDM0w)m$14p ze4kZ|<9I@O9?s;&a8bZ2AjF_!>Y1bOL<$@up#S_H{&W_)$rLa3iPJiWF z9QJ3*&I4C&uF6p_vnKCu4t*YG7BAa>c_{EAEC+VvBhWZ~ zxff91B=2*9tK|#K@{xJbSb}ziwN$nJu{o!U3j%CwxQ{5-+~GeLDS4XRsQF(huB_uB zhPZH*E_@JO_eE`c+iLm-rRQ@;iP&T8@(n+AsvUyYr;)r|sG;pr+ACr&p5u|jNNJjJ zc1_s2eCz$`!1rlxId_xtPaRb^+gGIsy?QuP4{c%incqjBycuoXE-kaJA;vfMWG81%K7;pNjK`Ut&cNZKGES zYy47E`MNWu@Ok%rt>awUn&?p9`^1fR8f^9A%FaLCVQ*V?R79HiGuIClS9|ane|4S` z*m$I2jXZuhhbgRQtUCI(UD8w=A7=6J>x;wkB`4MUYCQ*+j8_6*WUcmYO_|j8o4xl7 z_+kJH<5KeLwASd(HZ3>VO0z%iCFv>uYfw$m7u=Kcy~UP@;R+YmwNhm;IgS-O3xb!0 zQ;IH#l==VB^_D?#L|xl%f+o0I&_Hl^CpZLmcXxN0;O_1OcXtiJ-QC@tpaY!F^Sqy& zI(2?gMNLgl@7}#^uXWvW$_xDWX4sd-RM`>L=EC-_U&EIB{lxb~dGA*solRKu_*epc zo8@-Dmm91tGgK)@6lXUiUaBs0U6zf8&3-ts?=i8FcY7U358#fSY!Z0uaW!x=bfq&o zHy{|=&%yjMY~@OY&A}Ag`1}Ryta5xl|1#gq0YoYVcH!m97Gzj z8{dx^bFTt{k+_4g=zhTrqU;hS;sktR#<;p1!31ZhVSJ|{XCd!Kp0)mW_=V2 z$4i@0XR*V?by&Q9*WJje7|?{YcKeb%v&^tO zAthdj--0%WGk)_me9NV+CpAi^7@Qu0COH{G!JKErB_Ky+RRbr-K5P->9)EDV!zb|K zQ}QKb@w;?1B&A&gCxP4u43>8@qRKoYw77inD>2~_=o|Jx5QfTK-Mhht8H;)if1GwP zcE5H1(M*`L*OlVB9thK4$QtNuU&_KH2u+|pl{2N|7g?JU%v4)bK9<;+H1PU#uDQVH z8g4wGI1rsW)BGn$^Z)3`uQjCcOFHD_8buFi13CO|{O--KTEBcOn%w=MWU2_~d@A z3^VZIh>Sk1pWDuCKzF0Xok#^wXDw!7QqFKV-S|z7CQL7-Xm%%=r}o?{s2^11aGTVw z(eO1*43fS$X<2F}yVE%BbSf_nv>GhtJj?kfD`F`t6}hsEJGecg!3TDzelB05_eZ*$ zAq?|D&}oawUH+XVzu&~-+UU{r!&LFFOX`|>mkaN=sEgiI_;5S44QVu_J%iFk|KKEq zmehI>(eZ}zLG;nspO;t7DS{_=&4PHHITaJE(m56@|8hM>Cdq%Rk>b-e3#TK9 z`Bp}_53G7`*I#&o*Zhl0k8H846ca{|S~6`r%EHU2fBKjG9NaEgQ5vG8PKVQNZeM${ z!cY-qVl8?Xc5^T=J}zrC{6tX~uP&q#!y+lFAg@x>)Dj$GcP?R`Ch+ACO&Kb+dE*PS z=bv#_hH9kp;yUk>4DZHb)PPH`xQJb0`CHekzgCxoS>Y=4d6vZ-s1#1)$h1;66IX&Z z*Dm?f{{FQk^f$NBOf2QuBVeYO8_|0c>E{c2&E)Vu&PcRb<2e@-yk4T(k|-vhkOm5P zhDO~WlAKGNE)53qC+ns>(R1W*6caaKQ8sei7B0CwpRQJ)jK@)288RmNQYdcMwz$T; z-Y9(Cb8S?Rgj?yt!;79eQwHiRSeDm4$%xi)Vl@0T*Dp**UWTpPcZ|B!y+i#t=09Hg zCQqyfUi)LWbZo~pHj<|}{q?B6oycp%x9$umw6JNpE%Otx&K^tEd*9LDb)l8A{%xYx z)bHxwbsaNo)8Ld&0qE`PM{6p^)80lbq?o(JOgG6cetAxuaX+oDoecZg~aX4j?qeo zLTp8ZIM%WPcDwgeHrw_?VSKgj-;r|9Gh}_jI}iCS*Ol>f80*cMPZ({vc&%e9SR1bn zrgm)sbOJuV%d0ykg@KGB?*Z%jSRN84A-tG41cC#TXa!G1@jq;>a6pDDsxG&kfRj)4 zWN@)3voT@(>^%17U=y(^bl)_Bb64lZ<$b zKX|NUYd)zyY3z7_klo>fZFFGYDPKE((@1#WB=bR|KKO^ z^)a?JBxD{34ZDuoMr$aP2 zZP?pstPAaLH_c*hz&DJxS)9qE`P71dhX347Q3HiJ)4NfJ}z%-IxHeaT_jek{~Xitwg z>7P0uk;R~Y@nh)HkPrfYfN4gCz_4uOiQ&%X1HTRWb|=ngH_^UlG{hb_Tj*x#a#J@> zT8Yyg();Q(U8V{om-Ixny7ysVRi%!oER2t3w-dn1*Ek@-yDlEY3ueWDIe*Oob5rX0 zJlOTla{aJ89imz%R znSP)*x|S867vTB%Uo72+?1FF7FZxJUuHWLavt(Qc1e+M%{4d`oNXV+_9N2?2v2{gb zQjM{?IimV`kQ1`oQUv&O{w%JtuH0V=cc97}ny=ULZ|FEZ?S*tN=VZ!yT2gaOl!1Q` z{&=Bb$TN7$@n+xGTDXuQCnZfP$g)~aJnCBmGe0*5kF#tVuk2Kk6%-_7XAVsWyz6@{ zNOGh6Kr#454u{rUw=2(Y%a_Xj`aIRwl`Katd)S;MSzub=zmt>+5(Pm(K|N2IAimoIfyEeRn_`;>3QWF`3Jl&`O`(`H_ zzL^2(RBg~4f*0A2AOEDXA<4Qd)-HSJ-6;M&!3JR z&+0-}wPH=O2;CZctv7T7k0ys`B7mscSbWC-iHK982t=D$7hi4mI()GwT~|LVv2@Kq zg%lP0=?l!wGNT zsQQb)JRVn_ddqDbVFf-sPp5}O>K?f_`jj1#=y~T_j|KyZuEnNt2?>&}e(&6P4%m8P z@Qaq@d|W|=s}BGIR~JoDs<{P5v|rze{AzG!ynwp{Wi1rzFWXxNN7j?peZAYF9_^zC zWHKcyd_s81(BZ{|8tn6+&Dd6mf+`o@QZG~PXNpv$eH!xVPiK$PS-FEDLgM1hRtLs zwWaT9pZo}Dm8VJ(GQIlDDvV0ChRm?0 z2hi^VpJt}#IDYU|$;a{2;Mj#V#$#bZ?n#6T9Wb*Sd=DRmlf!xbWb#anz6Kr@+$9&-GQ-Thk&GWe^y$Po*P5Vi+%^i;;eqGQrUKaskZmuQyS9;3lxj(No zPgk|g9xXLTcHxG3u9wr^cimX#9yE{FDI$29GJGAik94BPDL8k)x(PJaaU^5;uUG)gG9_AD<3y*_v&+wG@E zm5$kFf@Xmi0pBhsJhz9m=rYSdXZOU*XI2uY%a6>=`k*ob!=|hA$Cos>r64smd5okf zti|h_+1GHGD|35NqA|y-rJ)p$r{|5x+w*Rc#3tY6sxr$z=AXdkQXdT|;cCEoV%;ep zj~KHm2AFD`vUp}?sOq3)uDi9@Cue0&uOY6?%kQfnU)7A~--gdfWzE-CWWw-fDGf3+Gff>{JF76pUs~uY*)g z8grHju?9n9V8AYoxu1Ka%d1NuI!}$j4G`(7^YW;C;oWsGRytEFOuMU)3GrLG_Llf? zDh&dmztA8o{rimW@LLk?QIAHfxb3em^B93_oS&T1_!--ZW7jf;oSi12lhYC>;HatZgWbI$+CJOt2(;n z|6BYvac4!H$~k=6Q%QpZ2E|hP%FT|vTz?;o^GWT+wXLXi3HwY>AabnBVOt&EBfrr` zh|i_5G_DZ%WYX>l$08v)K2W+G8X8U3cj;By4nHI%TNL{a%y?x za*&XeCh0dQZLdyAqRL{zQQdwcDK}am&tU)$PeHq+Ox`#iK_d_W!RF7n8F_R8!8}uU z4JC?#YDu+H#1he)hNsXd6z=PM#XTe`M_MmW!ud5k6vc^ay|ja~PDyftR-`c)9TQh< zDlP)0dN4qZ3BR?gtjDw-aA~~&?5eDrc`9EV8Q^?~Lwxzbv329s`l>f$2n-|$CCW3c zd@VJJ;2m(pORm8gd3yxSDITDF9p8UAl*d4F`5%8G+8ULKGAM8^3=r7ny%5wX*`1TgEJQ3C4;Veo73 zYDeeN=#$-Del1+C0c*0J{KEwF*oJ=IYGTC5=Q3vX`vIs0v23{)awheghkDBcvZ5+v zqb;+}@R15UM%Ct7xWy1CzueBJ60ig0|McL(1uWEls93e|oY(>{}Lkgb5_r4|| zFk5T?vurLnA1&KRec4G0-HWdpB8C~sS*+|?!8-O!LHw`Qod4I-*&6UmfME@q#_Esb zZqr)Vdqu@`-N7xSq$q@624N*Ky+)DLWg34Hxt*JxGJy^NBPv?%1ld8UsL{jWFJ_< zoCP_0ShukrCjQb-K)`!KMfUoFEI{{|9pgyQ(uqg%m&bm*pp+LR#Wk9;W4M^7w?wd! z@#2|+c>dv#4^$f=xOlK%>>p+8+cfgZsU2%SN#pf~Nd!6@-*M&-_3>?3aO5hf*E zmzXcrdB0T5RzFIKKb(l7-(@4VD~&97*s%o^K>VXS_>P%Am8#8&6yLNZT?V4~6_FRv z{QE!91SazRe~q00vmO5zs@ng5?i{!}`hUAP{(V04fA@f)>_83Mp8{Xdm$pMi%w~Z6 zxr*D_noy-tk4L8!Uv^12ej`>^hLqDnX_wQ9vjv1a98B&U3D2k4*Fn}~_Zp)d5;wKt z&|s|@vNdAXiU}C=`2V(H#SF^&{(>Dxi!Ah~C;+;lF0TyX>I}K3KjiDP{tzMUQ`qy~2L;2qtO+W8vKt#@HbGywE zzj|{X=~O{#ukI~i(EX{|-ZleF9dMG}aG#e@5(_eu+e*UyGIaGb?`Ks29{%K3vF_eN zllbL4>T}%t-!qf#v2SD?9nsgjwt0;*J-f~U$BCCeQH16s{^vrO8Www=YXx-K!+%Eg zcGATPi4rE>514M7d)?RY(pu>um`3a`9+QXltpC{eNNlvUb0FGKSFMpXfjxdMnPS4K zcrJ6?Ak}d!3unf zo7TDB8^-7Dl%%AInkFYG`X%vXbe=BO_{w2fIxBIzoPN)bt>bdCt$P5Er$@aEEf|__ z2n}koS{SbyhJQntLpElaSK^1SN*%_fd zA+tHud|OKw@hhaa*}*@uFPKbT3>qyrtf8p2@L`9`g<33jiBKO?p$Z3fn9=`q$xPKA z9&9h1I4N|ScfB6K`gS&<2b^LUaPfC*ucB zUFmnU>aqA}lEUyZMYnT@U_;Yvu&M&k*o=q-`9FrAlx`o%2mLOBf_=wDgWi27M;RuJ zGidxZo3v%GTp!;eryG$pgUSq}^)|vMsu=FW zK$QvQ$f&;2-eQ|+y7NDK@}Ne?rUA4Ip^>lK{%vFh05|dP1^ckJceuCvIh>+vGU)Ef z1s@*Uy6}?kyf%Kc=xJ1<%#DlGlkMPenI35mV+UH9FA8&Z<8ZOVb?x=Q=+4gC&mZ)3 z-H4sWZ-QsD;h72FOJeo6*t>=-;(()jV0N*QSbe&dNWHJGSb%tZQQCO3=i$<~Hyeh7 zWjoEv!cwK?@-4bn4m27G?PKm{#5-u&5`N?hx!ABVhONif-+AikG+y)T?o=7sYB)AP z7m5Dq=j6hPGXYnc_%qw@$dnG9&D$HN`Vs4Kk$MAkT#${AaR*>FN;1cc{yDA>TVFZa zKhX9-1vTu9ywMG7GR4eO>GHyYj4mvB&Z{n@X19ndOp%|KJz75U{bfkDp(nl=*}k)} zruvaq&z}EY!#_8H@n;ndS^@WI~yUnz>9iKJN!+P&GHEP=rd_m(@ zuDdoXIbRrT6n z7kJd@{xi7K;n{T~`37Dgf8{d|Xi+~E&9B3*G}nJgrJ%_VQepZu;Uu{d{j@j|;x$95 z+CJ6_Vy5I0bEV<)MF@~@j_N5zi)ibbkz~VY?0J>7&;*-vYx9I7Ek+WX+%ibNU(uL$ zg2|5aH}#c^rQ;RPQ+H2Ls2V>2jn5W)$<+T@+1#4nQKm?LazBuqBfv1O4b~{4A(fN zI;N~Kf(!}!z*#bWJejauhh6*3Fi`!reE+yC2_hbPeo?JJzjW`T`_8Mb4BjACF^Xyq zns&s>FFf61_!yGpq9~!EcRPZ2Wvb?XGw&+@86Xw<;7)+C!e>sdB*`6u=JkxT24g z)MY(l@SD!+mUQ$!cU<^N6f9295fxwzKy{OeWADVQeTIGjVu4+otA_8?%y+1q#ggfG z1Ibso%q*eCi|Cy;buiv821+NKB=Z20@F0#vG#?Hx1KDV7mfBA4HI6DD8v|MyfY*lS zMr=!z6j8#k%4jwMw?d6U9Gv%I^xfpn3-@Pqj_>pFoNlLQR;eRk892o&wOiv)0ZIa^ zcYO54^^OW#gHgfSzf`L#uMF-j!t;E&zzj2Q$BcW;p>dqf z)&PpKGFCoAis<6CXJ@Wu$zYm4Fq3GOK5b4$K@kE#qzD$D`8@B4xw$>bYChUS(s!q< zzJH?wY%~ef2e|Me6^kx%Q7VB)MLL7NIV7He6>4%Vvf3siT9Z0dRHbX7aMK>u=}!US zAFV{_Do_V0;qa2DC~5a)cq=GN(#LcGOQ`bA=RdX{cx`r|{*N{Y#s8%ZBKTid|1Vzp z{C~7T{(l3m+kd^rpWKl`cBQcefp-DXm^GOt?3wE8e}48qzvA%!3eZY_0^b}MbMc>) z(~lrUtp^7~NL>O2W?vfn?9p8(2!p$G|4oKPqZUWbevns^HiJEY4l&q%@@J8{thE*3 zuK3kRxLl#FLciq(qg@Oj3|1>z8;0&Qo)Fjkreg%GNpU&T zr*^wqdE6oNhrh&mf1o?b#zB4*-75j&D%Z%rocS^%#JYPzqZg=sj1ST+q`~|N5rkfu zU5&3z%J!)?8SHgj#XL{18HNrQ#tVINODlV>+4u`^w+yu=w8ck^je;hbkg0oo${Sksh7luf!Q!2lPd$!T> zIUmVG{Km2w<|uD4xO3bJfKw4Yae6HIONTd^NuLb~eUEk9f~jKPIf(e5xoI5f0BW=0be4MCz)Y75 zZFb^j+Vjl|I1W|BxdBsr<-z;Oh2p~d0+qhp>cb+xueS$6Ju+Tx&{7Sht7F~mBWneV z8~+1k$~+$$*S>95KTmr@9!B?y8skB~SfEM^GPnFjbte$@$r;~azyE>?K|?Fp8X6|Q zoF&#=XALff=_impbh|CKNf#}sf3E)w#(Kv=kAS2R^=oKkNvl&3 zUF?}TP|fb9Pr|L9pa55KxIfPv<;5QzgZXx4y6p8P%Z;=$3!J_Ma`I5J;y-f3SCqL1U}cs0==`r;>?|Teqvk-f?XEls z!rdhaMvZTfrgw)40+D;WoB?>Q1s8q)7Webc%^(Pefl&$ zS=2AJDj(KuFPnp~*ewv^!r0f#i&p9I_4g*Wz(`P+`S@IC6qqO9MU+QlMA-lS7**YZ316Y006F z|D7@V6O(6F=kp|lmgQkwd|@=&hIlr?I{lp7;|vEaKh64m@w#O_^^04c%N#^gf$?r0 z*0)`)M?@R|!{&M8scP*sV=MvU7AZMui^iLei&zoAIgGBvw|6c~VtA+`o06|#J&~=( zs(<7p@sqams+dO<%6w6Ob;2Xx9|}Lfio0tm81sGMpOcS}<Zhn!*=vo^VO+wnkj7^PD2ZKMPx3O28IQx&O=QGwTLN(pUQ5J-#hIx%P)) z^F5--GPS~B&UQ8jRSh9mt)7wf`{Zgr!>oYWhTh9?Q+tnb|K2^?&V8ay2UUNXL#T5| z!kk^sb`?=H6j$4--(tFOH2Mfp^;+b(Xi2OnRFpBHzZ@cd=|{BjmwIql91~IH46N}l z!zv^otj_yeUf-c<8&iR9V7?R}r8#!Ensh4Jnah>IK|tQ|I?fs=NCP<3&;PZ7WsZcV ziyQb~+cySd31uRld0J;`DF=}}rE4AL;Irj~;xm@~9F|73N~m={W3cq7l3w^jWMW21 zI>h5v_Ta1^?-7&_kD-W2#0J;rnw#G%+9+5O(6@9D)Ng2v_IkSgo(_syF!QunXGvo7ES(iXpjDHeMWs&Jb*JnQLYU*xwt6-tcvWSm)1<9g93eSSsG&^m46;CV`9N=nuWtWBmD-LP(a2#^QkP{(yE_s z(k<6vow+;35+-uO2Fz&TRod)AAT-&X^SRQ}ujgm2bXjh6xG5#>1cY#Y*P3&`p0p-o z+VrRjM!!%3$>a`0v-e-AE*y?<+_GS%A`0XNb4g`NeOuXXzeBb&QMd#A^{-$Bg+5mWb$zE;nxQy3~2Q?hWyRZ56)nKu~iJvhq24&f0&w*|F}L9 z0%WuSY5Ihm9FUmn_fI;=;Lp2#!w&3Or}Y+kvM?Fr!0>ZFAWw>=%G%XjbqXlLG6KL` z7(_g0&5>WHgdMt=DoW9D28aDBu~N2vU;2#!R)!(nakmvV=&| zfq}tj#&=)F{_OUYmzn$KKPG9>uL~QF7FRKP_`{HtGvmVGi<+^glW7TqY zW-Jj(fauo^C~Fhyh|U6PS+oDU@*90x?{#-1=)U05)S#j2e zM%z(V#PDFuvGhX&$_q|DW%sYvD=7&ifMjw2%chcW?*40XlG^`YD{}|)=kn3(7>q64ETtp59%7gh77~agu22m*F z%?{0p$(8Y-aDjTr3~yuWl`v^XccJ836hRt@Qar?ku0AZR16B9^v+jsfQ8$m-&Qj)y z4^rT*&a6LYy~YX$@TxyPU(0mR^2w;)>pC!fDj4!8NLt1=(|*Xo(&yW+>m+;rdT(0VCim8$KtPsEl&z`<>C z=D%0JA{?Tuu17_5^5f?1fI!JjC2-C&?8(*`?X3t|p6-bPtjPNd4V~h=8}q1M0xUi% z5OhB$A(nZ6OakfezqpzB0qj)qM#U$Hiu4W7Z>2wXT80`?mMn!L{2C+(6lMd)((OBe zM1hkF96$v$O|G7c0dzzb7JxJMUrps7{&Ym53IK=$m{%3jIM2So+Fk`+ zl6vcN?3NHz8H!2cIO&Oo3D)zBA#?x(eFz^-z4MX*lHb2}zw+z^CXfL<qc%;KNT4s38Bz39xbuna*G~W85%o}32?n2g;%e$t}mcC z>e!J>oqL)aGX2zHr?a7$BJ^}zxtFh^`psF;5nH;b$ z6#;nn-u^zIv|8Q~{r(%H3*+~VA^@t22J|0J7OMgIX3D>~Y_%KIr9THt$+N9V%F2tz za8(G{sFt|m>K5j9;mxYfF7~p{CgAe=5d&IteI*pYMiGVm{g5NH$KR|j$=QuD&#mOM zR2wR6deT}m=)Snc$EHX1qDUr0uOH)M2ZPXl_2Qe*+dZN~w;r^(R2?U+JtehSgu8FMTrtzs*JRkfv1& zyhmd7>g@#my8d?T<2j(opVLC9qA)dIw00x*6e=zJap2eBDdZGE(hku3LM{KjY zZ=2HU#yDc){G-SM<5tbh1CHs@AwcYun3E$1;A9&Ys8%)i;j3g}bQb?%AOSsKGQ_Ee zG7A?WU<*hMw{ml2h20W<>RD?=Ih!kJ`2D?wJUT@4lG*kIXoVWj7%4%eX*p{%(4H+u ztUbtgd}uKRLj@0}M0Z%~J>e5Qs6}YD@lw&|JVM#gfzxatFN*W4=x~8y&U! zN~0N8wM?dr?&7NZ$@Fch)x4zMD+$Adv&yX#CWegY^m>b|>;p7OAZ5QXGoX_(>CE(_ zbT|RxC4pbHI1OLep@~Ohu>}gPa6V8U!BUp1d<;eQ+??gvfJYV?$KNKkBWMq^rN^$L zJF}CAO9VZ5gEjX4Zv^$HV0p+b_zG5kYeDlW@0+ae-=Y)@qIN>(Kn9~l0q*Inxu*B5 zfYYO{UzQdW?5V}B=o_w@#6t-FAo*E<$xMfO>$>ciqOK@m7xWD6Y?AyN+1a~HOV$FH zM>E&^oevi4rYFY3xuxRExK)V$)n44);)8c1dq`~4xrHI5leCZFcz4akVUjkQ6X8Op z2-=#=v3xuI_CaNIZ1< zH~WfD8^FN{3oEEJ&NV^qFUu3Kk=K-k!8RAg8hP1rs~o;c!&>_h#zK46pbz=&lolp5 zffzo2NvSm+K6LkPFH8+Px95uyaK>%K$i4rz=6Fs$0J=qrdH<(z@Ef z0ntLL(FhiXgvbhB{M64;;Uv5g`Dg1(r(>ivi$TL!KWd(aHeF(}z?r;ooiMbjG^!Dw zE9XYItNdvl&tUv}t<_nfr>;FafC{Gx|B%rn3C$qV0m>iYfDvmzepgmnSCRfW&sxrW;>n2Hed-#!Vv}*MA5ot(AH}|6Cch zSUxJiMgfq*0IQJ|j|nfTaOQ)Rr4Qdf=j5p$gyP2_9}r&uOPkm)6*zg60l%ny1n7VO z|GKPf$FcPjGBQKjR&xheskdJeh=?wKT0Q>$(5kU)__ab-QeQ<0IheCO>wK|L*-);s zo@D9sp0i}DZxG5?`zOtE?*#Z42$GmVrLu1$yVro|6Afa8_p$H(>tb`H-BY^QvwGO9 zSXGYFsWZM_DOgn|7Y0LxF6FKrkaJdutAkW|g!r0EmRokjwPO`^W7E4Rv=856`7F}& z5fD3&Whh+>9mzcUOX9aY4Z*bZxsUl@6v$TQ#PIO9_6GWU7Z&ZNQ!far=O)o6>IS(8 z98i|7NtE>agjQaOf#2cc^W8^s2n}Kw9zS(*APi2Txy;ting)B1rXWUpuTHsi&JFou z+Vp~6>pS~BH(FqWD+xn(2QaC2R%j&DH8d+w%t@>w&f%?f!bauI%wolksi4Y^Z7h4gBq%7+Jl02}QlUX@JW=4730IvL7v45C?Ycvvg48SY@rHtfwtltbO}N(^ zkg8@U#j`(qO+)TlktyGPu=gNUg6`)W+G)-)Q&@*hTWZoxit$7F%J|qU@#IgvsjY+* z5>Qb=>*(l6-3fcz7Tvr3d)q!XBST71@FNgNeM^A+f)Jb^tWbT{RZR&8Bm6svn4+I* zmF6=-_>co<=bk%J&d;*B?4RF}en+b`)$iluSO0#zI5D~N6aDktJ#4P|&KW@cJ8k4m7+R#EGqyR7 zpk%e_i%y2PLD|uryACHGx0oC^4~LD&ydcwJo<=#hx)j~R`&pKky7r<+_2xD|V<;-e zupyZkGulw@5-}BJG9Kx&tYwdbrd}es4Eh5g9FyH7DL30N-WisVaF9LVn#CQpPc|VM zx6b;p&;o^6eCUsa{vh%1A)LNkVp}|YeX+FzFq3BQCx^7ohZS>_Qy;=?-Z(QKuXDBx zgV%$Xh0D{z=k`e_`nFJk_q`CV8d-@}PG-mORso8;{@KV@-(D%iL)@!sliTz5*50(d zYGz-9UYZ4bi?{~=K!U;({w1SC!WjOC!8-|{^_$Q9ypVREy;av zJVqvJR2>y2tG*rYFo+iUh)y3z?)=q;KTd2e7!tp&J(vOCD?A1~PK5-16J7%?+8Fmu zR;?PVL2o|ya4l@SQ+3@`oiEX%w?x0f=R9rzjUsP6?s^+w6Bl3ob-wqZZt%4$7Pb4e z_R-c%A0Aw@S*^OmhQuoiuR}!+-Q_br=-sP1eh9Pe{qU6cnMm&XyaWHu0W{#vRrD>* z`_&BmGQB84|D@G*^~Pu1_xtY3&i#Ix!BG+F4%zuz_n`B6%E}>5fs0Q=lBP z^0Xm+@kg%NxNVb*uFV5aN|L8Q9Q$TcOR%G);UH-PifO)MPN95 zQ#xChKrpFL9VF5;Dq+*aZ{&}Q*mxjUtS6+Q(?Sosjq2kXrpQL@2mL!R8grL}6c7Lt z_&#?|-rznAKAjP99lcj(lwK2dy@K93-cj*cdiRnnW=xPS2JFTkcbX>jgdbFnW&?sqhKYxC^ zE3U7;1=`wj7{`X7Xj9{rC^0xN6p+ltr1Nv$IYxcuTOm%qSN1lR{FM)^Q=F8mWSy>A z@+Pg#Q7fq2oDoS#ZOm|c>-9wAe^v0cKY^-5?g}X}ho8oEyD0`a#YQ>3`D?~Ahe6)? zUZyu(t1k3s|H|+0Pg?hYmnb(k%*#(r%QRj=uBWQ8Ag3@TrcS5SAsSWyB<6Y&u{Xb3 za7Za*U|FBJABMOeBCR%>FeGy>lp+0r>o5DNoe*9as`H!5r4Y5&tRnf#HzbG>7kOF= znq%ZI$N;FajSp(DrAyZ9=Hz~E$RN20`EXlD59qk6|t;&r3l|*r~&a}m2a24bgV?-`f^>k>Z`T#K_Arng*nGsiGqbwrB2YXLpH>^xkLA@AVONNflZgvGTJ6 z%eO{nZG09RYW+n#!#{4Wg014mUN{me{xZV_?F5sIv>6#1rlvE;>*a`kqRD?5%;>lE zS)Nc|r?efoCDUw4o1CXqg{9eUjkr5EgKk?sLc&NKcd&-9PUEfacVoxJj6DDmv4Zv+XF82H{it3?wx>x0oV zQ|ptz`_-PRDZ0jo<75)o)NmMMLbU?;9D;kA$hpNSuF*%+6Ggy~mEeQFqqoL|w8kC# zz8jvSCYFTn%mTcx+?@f!2uM-P+sGcsXF+RjDUc7xx`upEq3|ShRLsmE6uO$ zS}5dk*)rjGPeFC@2h`XC0odHFS0nJsDtuok>mh6U60VD2AE(~Az868OzhLoSDG+UX zoM}XRALl%h_(h4VJ-0tiW!wx)`?qLa7FnzDZNB!XJzhLlU-hh#jG#$Lpu***~4^P)>U8BzopxD*0uhiUouTAR{FZ|Df zhJ-Ijn0oJ&0)HW~;1#AnSFC>R3XvguM}80MZsZ*Rfgd=Y`X<3BCOv3LLen|>bzb#l z(8`owQAs?3R(DBhX=88iwHkvyK+d;@t7gMzew?g~SUxLD@VkD{TVF7^??aHB!0R2l zR+BXoNT}Sow_Wp63)!;rYeBb#l5!=;U3;R;SB&;?*zKB^FPP70Z zoBHQ;Ppg5J^MRim9Zk;9pUq~q0Mvw8A7TO3vR>f4D>l|XswO--x~piw{iX|Tgd~LimwNRLHElTOFW@r+-UXakQmb6cp>i-sEU|{Fr1<{Lx~&R0@thE(UTG4fdG2w+a_{>Km3Sc&la_89%ktL1l4h+}nF!(1(NKqhEpH zJPJRu^=s-{TUzbq%a@qM!~(n5flv0%M!IDv@>TYUXkMG8sukqlna9YTh!anWd6D*- zdI?jblmK{L_d zhnSvrn1^(A|i6z>f@$nYvT^g{d^81&Nveo^2c=R9Wgy%5PQBq55s|U z61UB#x}93OEglXou85>0;-f@oXXhI*>JsIg&}iVt;@;rM$V)f3EA%AAwd~)Ed)D(U zKE)|EgIBJJd=3wu5AS}7<_R#?+GMNKYrO}9tXiELNS-QN3mXi`z;~l?BLyiY;IwZ1;^n&iR1H#ueFPzeCz?=Vszcq%f9}GF+Jm- zI#>7Q6%|{j9cGD-G$3DuL9s23_nvEN5`mLNK0joP3G(#3DU&ceGov$Fr2FIu63sow z7B`C*FK)pQUZ5$8J7I|wR8@1<2`45d$}1~<1&nrQ8p8jVh#s;Coj1$#&#P`0b(12xLgfX5=?RdJG1qBTG zPH__C?v}6qPGQ4=O&k1F`saDFwFXkkz$@6gj~_qs|M`Af5BV-jhfx_r{5&#+QnksC zrzSYc#{G#fpa)%ezVg?ZIz6sz5^wv}<#{W79_$HX3!7$^-`{+PrGJCZVdvMu+5Eho zOwpK#kx}-_Cd@nhIW~rOw5h15$PrWm<3QpQ5?ZmyF)%2gDyO8Rhd1UJ+syd>D~&(0GMnJfJJKe2%N9k3VLHp16&#zS2|sj^`W&uOsHL6vgN1Er0xd z6t>w6E_mbLBetg0%mEfzS?A3l5-{P{D@q*s3* zMY{<;tv^L*0BpFmpBC-m!$tc#j=sFSydW4O_$E%Z`t6pz%eWbuC%ToaY-lzM3@@aD zL77{}FH@HZ_4^Kje}=EWubWmY!}b(E|2;f{1r;Se8D6n zBxIi!dM+b_4xalI(_`nhp#frhpWRj`ub#PG5GP>y_Y;@ zF^(lE$j2{hwLUr;<&U$Kb!o&%Ymsk^&=o0OjhEFoE`GdNo-7UE!0(^cZEteh;@NUP zl(Fwu?V3wzSv_QV^p?VAhU>lmS?g>%?UBRj_b0emGgLF=+SiA71y#yI!UXL3=G`T! zu>%u46U5YB{;rCLxr_b%vM>(@F@?F6WbD_kwyrM!^|!oyd^L`HPyhX`P8}Q=Uq3&m z+4C8^BfGX(m>VwhwzjsGJ%r%Nlhv(>viOeYZ}uBuhI`-Ja)Y6RP^XnRWA@pwQ5LXC z{{3DyY&^V(I63HGkajyuhAHGb#g6dj#Sew}@; zyWpbh9v-+tM(K5JO2&EkVCFbCOg@@ePt$`1uc&cK+~wCKzPqM<>BpbxS&MpdO z0Cp7Ld*3_vWp$Q22KQ$9uh`RmM(ujXFLk?(d|R7n=;-p`JbqMv2TueSEVe!r%3nuQ z1P63}ygSC8otq0uXsy&RzTSs4LxevEj$uDkeS@Gvqv*V>;om7}(2>asnGcSu!))9v ztbI(EQ z?S71$O?f6r*?*mAEO)>vfYZ19Q-XA-L;3@<(V6a?+4X^)tjvnSS(^L8@l1WdQmly> zQ{~@z+I~)(kIxIrp9hJFx3n zx*)AexTA*u=%@-rF8st=F_kw^)zQyJ=L=X(u0OtLv_`Y9tY-WHB*^=h&Uu4~^^jnzzj z9E_T^-<=WI-CUg{5878}jG;3Zj{f}lxs44A{6ak;cbFY5Y*XQ|J5$^y_2R{g*IIos z#2VsANNEQb`vYcJlJJ{Pvc$P{Gc&;-t|mDQO-xAW>ZUMOb&2D#(eczRH*9qzMD`U_ zj`1AnhD_~q)k!?K8tbV)NNGx^vS3q>nbxwG19TWqxDw(!%>JP|Kyo1M>&b)Ch}Gy= z8I~!V=wT)Y*2hWBm0H*J#(5WuP0J&-yc*6_62Cv(cW88?%hem}Kv%rJY)yPT-BKrb zY%&w~=*b0>N&nOC#4=lgn!#Q=2JM3fA$k%MZJ`U(OW6S~f7y7P1N!%ih9`zQ{T+O( zm8kgar$hH^5BkVsCO4h-mQjN{3Z7Xxuvq4HqN@i^> zZyzPzyg~Ac%MKzOJqzPcUyu9c?AD0{TzzAspp02;Y^?v}_UH#93VZoGffuzc6wtuBBA@}Q7Buy>kh(PNiiVklS9tPcS z^mY$z1ISq(t$)I}I1v+&e#uw8xxN1QbZ`H$d#eAe?VZY#M@844R(1a>9=vL5T?$Kn z`^)w&(g9b(j!=8kCMZ{K=r*R*~!=4Li}fLfur6wL@~N)8(SD= zvlqrwcu&6-8VAol{usVn{`~!?lrN2fjmIBwkKGqgFMcG1-{7jaK67y0?!6-csTww0 zfUzUCRe8kh`H8WULFdSfWdt72)uG(J==P10BX%q*rv28OCYhPEu)RHpSzq)&4`JCA$Aexn3s-rBbo@oS1OMoHce1SCK5FJo(5~!>XWjWfLFf z7GMnb4i&kZ3XEEhEfTsW3Z3x?I<<-Xc=crYQc{Tqn~NhGDK9~ppFz~jjE<@P&x>Mt z%j$juJSLr`i_`u3!vd?UiVBV`J3gC*JAfq)4i9~{Z>{b*a=RSS!-dB&lyzGWg|_VL zvdsc`OdFyx7&MATrlx|YEyoPZ1bBHRot=4;l9KeoJST$VqtCJ45wpQxs;b7UY~J`a zHWrbXSbu<81j!l)fseO>x_XVlsOip1O-&6!Smz`AVQr*XF~Cvpc=;#@smvNwVCXB1 zkW8o|`>X$AZmPx>z_6^M;*v}P=N=6H_Dk9ulFST>>x!Sne*5gLw5HYa=xvAhb0;~c z%O#XEN5)kVUDQQNO2ZL$OzwMpvTl1R5!GV#y*K2qZt6I0NQAoB|G6r1i}mWigKxE( zbNyF6`E*5b$^CM-X86GlUdoDQlx1bZs_w~}NDaCA#fjE+YmCqt!@V}v6AhlTld$#i z6OzW0lKWi}<#R5VRIVEtuTHK?Zf~7pX{pA=kMk z$!ad%W&N^O*nab66~^Y1wDpOBziV=h&BvDKwC*;qhDJ8kYc4N!7Zt5~+FGzbGP#Dh zUu+C;|6LGpb-m{AARcB66}Yn4NI%|dwz|4Yp^mKfhmC{d(Rh94Y-?xJzI}SejckI8 zL)Fu|qKk)3j)!jV9sI7(8@a~>gQSXHt>sazUA4zJ9(0OqT@7YjNa&&DnK@*>&KLZE znm0n3yz-1)>Tpoxp$|uge#zk27|bJQYj1D=mn1cWhCV>xo|Ab$j=r*z63plO)f*e8 zFh}!8Z|^Vu!t(OSwzfY_@kD@v+5#Sp_1WaE<`)$`1i7EQ{FiJV$UYKfb5>l;Oij~M zQ=jj1Ki|hs=o3R2l#OhT;{M@_?dghOKI^#~%F4G;ZGL6gs2(M#N;hdPUveFy7X6R`u6i%2uNE zhMKszL^I+0y2eml+iz?ENl!p>H~Re?t7+MRdg6$G7KSZ*U1_R+3z}IPr&hfvA*X0( zs`>ITzak|rS0dX&b0W$(Cp#zXi-{Uvn7q!1jR%tUg^Q|GlQto(XLs=Ink=cl&4oD) zXjk14O)*5j+jMPtlyri2$dtGkwlf~`Sta`GTApnnneD3Ej<~?fp3R1nqa1CALetv1 z=y;Vb_v^Z%z;EB<+uO8~VkzR^q0Xh~nZEbsm~<%RSVz0Oe0%bRA|H3P_7H=sn_Qsj z0wqjn^2bq=V`S4zjHmo<37;33r|+;-B&GWx1a;TguC7eqVW^Z%e=OIN=FVd2=%}Vh z@Z=7CqoRTWJAwX<$3kw27Z}e0nf8Mgi%O5WiyRpYpFEk4@TB-HQp$mnVw_0xU1+e6LicGE zuR_re%64OOa<*ovSu4NTzn#NlyA+HcpTz~8j0fx1w)xNY2dws`U*0bKf}G7@L*6F6pexiME?1xyK1z-y zu-?vh*YSLfB$m|Vm?6{KzC&8;mA&)hrk#eiuPLd;wVX<8{TF0ng#tDUn~B-fYSRs;!&WVB>oVgm?Db6V8MO?uTIHjmRizHG)f+quMdcbkju z;vFn}O)V|Lfi&v>ZVL6!oYzDB3XN9N;&otF+%C91jBGL;64!__?YtNyN6Rg@MB}Dj ztbV{f!$jAp@Ml4abpu6=wz1;9d-pyBJZo4y`26|vcgPV7Z9K9&nwaU9%0nL=t!s4t z6W$!xQ-lX`Z1(r`03T?=Sb#l{6>XCi;#qMpU#d}HK2uKs8TS5w&;TUQEse>=Ru8K% zOX5V|-`2CO{^Z~qxaLU5f=ha8FS*;_a@Zp0xU)o&Xw?+2ytdTIJ0>Sde)4NjMxka9KV|h z2ES>-xa{?ORDU2@AilFki?MI>mS+VNuYdCQBLN18zl(~&kC$_o43QJChtbi}qPWec z`oLuN`S&#~jj#6jEg(MtR3Nju@jRs(YY`|g_|;nD`mgehO-yJYJwUkJLl?3RVt&WZ ziaE0DyaUFRTor@yao-n{p7IJ_nXb@;YVOvAZ9gj-;4 z6!@IN(BGR!;Vo5s^x$Y#uT%T_G0rwB+;jJ#%FfnM1bNr_PoKGZim=!U@0LarS1E7T zbfkaXw&4tZ%H?WYqmj;f9Hm{4(ddS&bogVQd^zjk-!QOs>YDqvM4nl=%yDDTIcieA z+`yZUVyrBf5e6Zx>Squ6&s6K;@=tkF&V_ppk5i!@&Kp@=+pRzQ+0Q6}#PyGGpR6nR zwD`_bSHWbb6#~Q-8NUyGB2<`nVFkMe(`H}39C@*+q^X(r16_Xb_wT^r^LQ=nerH&Q;^#VYbWtC=G>?1>Sjh7xe@{pKeU>n9T>5i69 zj74~2ElNsB0VW@el)x(VZ9!*=Y+qrRx<|%Zs)}l(XjoxXICm)Xh!_u#e!A44(Z}I> zJ>?IT`;n~uU7>7!VAYL&^Ywc_5ua%1+nMfNLzVk`xT@1JGCSaN_T+Dc)fiix%jY4k z36DE}C1;z7SyoS)SDS>}t!mea2s5ont!1S!7V8tPm1Cc8hBdWuxsQG)YPgMdU_X2` zROD1~{ms;0j;x)xJ!?gE{Xn{JIC!)_`S=R6J%IRPY52)?a?Hw7uy#g=KlhfAT+r)DVp_m!&c88`T z`XaII)PwCwwcZ%(pMzCfi^NtE8OKde789;Vx_qw4?lIZ@bj=PC-gGV+8ra`IFm5Z{Bz$CMKpbqsHv74j>2} z_GGm}vkd~Ot%eFC-WNsc>gu_t@jz$9clzik<{@Dm=Z^Gir5YDnRwclwiCBny_Tl<+&TbOHHh~fAE_@oaZ1+dQ?W1gO#sXkpXqY0Y;lq3s3ik%`^rtlVizDHy9~jz96{rjHOT?7i_5d8y%i@#1m`v@n11NY;uD7>NgXI3Ivgj`J&0eDAq?EjAezE22<$BTM-g4XhiaF`}OtJAI zP1l2>SoSK8+wu`#LPcH8^)`>|dd}=z4*}81!V~iv%i%}F#I1wtIj4WuC*1eXn=ALP z|5Om)#lU%G-laM?pMU=+OWPgy`&i>=bGrM<(Qls{6H(qPE`NHNY3c+mbnX4d7oc__>Jyib%Gww;j$L#02w{<;}rK3RJ zy1H+3@<;ChF>j_*BUE6dI5V}8^o9$JGftKw3MxnSTwM@xb!0e z8cs}fbXjHrQOOK=&FjN}4dDZC^T$e2OcmnrdcB^JauB~Xb4WbhY5*6(X){XCck;90pj6Z$# zHW($R!r~gZYfQD)Lwj%-6?elEqxx#RuiX|BnWRxitX7Bg|(1bprs zT+o#q1PhVA_;l@N*TC?!@d?y<*`hbc+*bncAOGPVw&C0|!!m9Ubtjx1MA_oF%$iItNO$1-jVAkf6cWT+@+M*gNW%s zVDdL0B*gIlSCM5V_{)ZKR+cVx6OV3|?b8gKJO;JJqXfzVqTg)B{rFhQkQSp_V&G}! zMNr9YU?~I93`xxz?-Pn(ssn#o8!^d&4h1U$(&xs;#>}=g7(oU5`u9j!dvZki{aS@z zz3L1fOXBnM_Pzt@`i?>iY*Am9cY68m!TNB#)C?9D)_9rmLj-Q_fI>*6)vWCM_pAs$ z@PNesui&7Y4jl&vhvSZ9*q06OoE(Pd*>^IXjZTBRZKj>$A40@Ry&kY;4jMLZRaYMmdfmyL>w z0;^x=UCdPdESzfodLWM8V>m}{lVoyYg5ZPpaEq2_xfVGku}Y*Ve{|5OL`o$G4ZFy;xELgw^lpgF;^LmiWPam!qwD@Y(U5E6dA2fB)v)9nacP z4i<2`sLo~*^=97O+G1xv>WyQAil5doMQb2+ou)@klP=w<4x-Y9$>Yx?+DE>?s$%4x z(1ekuPAgz2EY`7MbM_qP4L`}aA*WTd1tt+y1KG9LJeICS*PTd%P; zW4uL0L19l&c>Y`q2g;BKYd_7d1QG|*z)O^tma_BQYsqJ3W3|6LJKQ&Fd`gFE5F91w z4n?`w`6QOH#kKOcOc@1Jy`3T;tM&1~0+n#T6@$4cO@yN+SRDiS`aXH?F%a96w z&C44;GbqY~a$tg` z0h>Ae+9OD0393=h!PiH`Q?fqQ`kjUL717`u=EZVot4K%)Uko z5;YVQln)l8z_*Oo*yik*r3kqvhlgWnk6D_U>OKsQ|sWsXAS=6 zqpgM7b+8GjSIO_l=;(r0R*XnV?aRZVO0BFMRmf)ZbkneElEe4|m_HP(9`n5SPU3S2 zPfX0;{N2~r7eB@T4W410tpSgy5D(3^>*?-(3cshLLrmM!NAevF;=}aNv|CImkiXXW z|E&XxKzqjp%Fys661NjQ?OBvDAQvMdGV+3D)f6^4f-xvuH7s)PLLqEvY3UuS2vR#h zF%^~UybqYS(hKwRrN?-3c6Kc7w|}=oW4WF7};{)ikF-(b{)Tz z0B|1WAKg408X55c9A2>l192-WIj0AD|NLQ2EixEc|M33rk_2?j+FdqIz3*X26#S?$ zwi`6Oo>^A*sM>yKJ}?UE#1O=xBpko1jc>|-JY`!e8F}}ApOuC#W1O$zY~cocEDjD% zWOVe#@2|*w2R{A!40fSurKRCZO9mq8l5)DBeC+!2>@m0X^O&!!&V`cr1n)4F(>BL} zSApgKknjq>ME(BS#)ig_=`?*X_w7$dWeRC(1uCUwWnNE(>Gb<*>+0-6W~;28FvdvP z=F<0SRKrwh6T#ycnC^t{U&TRiHV78I|lrCGqONeg3`Vq znn;&QfV3*$asP?y>#|~uMGH<%=ANu&=IVh}R6?0G%nz)hQD3C-QqSvy<{-=j5vtHv zB*PZhO19h)^Z6NKeJApzvvVz(p33Xj81(DIfg`3_kh4N1VtUc%kni2>l%Ga5Q&sgR zGjx^}qNedn??ASKLQnnrlcb+)ZZwf(z6fm$_SpMjRJt!&L&IBmMi%2ifq~Jzw7Cy=`(iw;oF-^ zZ@HrO8o*cC*}h;D(+LG&O4|MJKY@;7`mNrP>u5-u|1vLrnf84&!z9wrhmZ^oG3+GD zQnj|WmY0{)pVj(s9*Q|@1?-8nDTCO;(9n>bo!y(k^2ILPc0fprj>f>i{>-HU<3Hol z=de*k$+Ip~LN$~XT_;IBmzIZRKu1TfeHjP9?$3OyuV~bX@2o#HEfbURY~x40u(-Np z$k!tyBiH(I1461v7VioJ*P6!KB2G#{(f+x(8(3TI{`)~(Xb=Du5N4K#BFX4s<^U2C>u|76>C{)5LfF}ajQi#7mA2_pj1ED<-5SSi(3>?y@%Vf*8 z$D+YmE5+k0;vE{5RaHcmy=Lsb@gg@ec5^1TvzwZPp02z(I38Yme20rxZ0!W9?b^Pa zM#Z1^-+<%wdqAwQGJ)`x3r3`%4g-OL2n#sNYpi#7vORu$PRSj7GE8)b2@f0$Smx30 zY!P1_S!44^LKaq*3zV*XOGW)2KH)TAhibO>M{_`xe{hH{O7AoIeR(YqKY^(;eIP#)jg$SVR*>N>qD zQ+><^)pZMtg2F~sqg47CM4&4PSKrI>P%YG&KiOM6I6C?ZJpKCbKR>81AEiqc?Wg#Y zi2yuNMz}_^dVlCyt%0KNhnO9tjN8vBTxDcrn#H=DSxn0waE+R3zxnl^_|`(Nc!nNq zy@UiZ!acn84{yopmt^n-kC&GxRTT#}Z)BC1W5@L1(9``o3l3sabndyOH_9?7ZZZ$) z=#4^KVzgs71w}(ZY7Dt#Wc}V>Sw3;o8MZAK zLtz2-PJ{)#`zt%ULpzoh9E!9BQ<|zKA0#_8Y%vxMjMeN1kGa49h@e^(;Hvl)^X#dZ zrR5GfpUZ#FuJ5@hYF<_^MR2T$hm999QY0y%&6StOSKjwa{(ADtIy!|s9WRU?iLuHY z9v=Fl(Y+ak;f0-We}RF4!5Rq@YDV{4lKuhn8^wC~5dm909;6 z9#Aq^%Sch`T@6BlA%;THU?}8Ir&DrpL;<(<^VhF(gW&eWN9{3Wpjis2-irF?`o745 zh|k)EC}8Vz>pZhkrE&SeLnKS@U?evAT4PZq;Z)U;WC54x;F58|puW->Hf{`V5nIUp zL|ATsH$hX+_ex~_4q_DWbLj1#edK%WkP=H+6}shsmr6@_lq_y81>*Ecp;4V)P0_LTtv+1XX>;CmRM9-RWreFk8tnMtz+ zW<+ z4C^x4{V(zHrq%U>rWN-N%R> zwulrUdAPm3y|l7I7%ydI#iUtf$-$220n#s#MG+R>n4dr8p*$xcDapzo1Eso-j*bsu z$Bz8)R1FP{;tBKGMG(Cqv^XxV)Zmp7zb6pnj6QuvY#-!cpZ=@m*>z$r!l9ffGY(6u zVdvlg_XNB@BJo7rT>>J;RV$i`dgw4&~?<)3K!~Nm6ygYOw=dQrTLuWABa9rc*TD!4GchhMD zz9d;VEnU66>`G#^Z2jPKvf4e((De@T!~EYaX{~`{%d?=Nv*H&=wXv<8$7s>d`pH_tgyXRP|cgLyuzeV*rrE%GJA zLfzQhoTxC1ndfdXnx?ib7>zmS|K(~vT|4qw{&p7#n`{zgSM3{tq^?0`uMiU;`2H4?3sPdG@BK^`?$zWREWgs^%T<64$Fp$iV^D! z9VGv6t$q)QIAd<`^t&@pZf-y%)EIPpme}`|IgT6NNYBf^yIT@riJh1*KAwn+F!1(G zD)x+J6Vd@|{WouJTcP> z)?k{5Z+jftst~*>WbXr-Gud{nWUL}$?Vp+DKg-jqYHKsJH_M5!>3Yg19E#7};eGtz z?CcD!^G8?L_icNk&}XH(c#K*|n}?_Z`zm=+-~(DGD3K!j(H}k}+OWF&+gXdj7ef`S z6t$lwap0DEsONLFbn3^^-8y|Q1L*&)SMStoJqk7{io63kgZkip-q(P4avR#9Fq{=?Zb(f2zu9bpAZ`RPoIR19N@itg_Z0 zO;W#br#nRBre%x%gRGXEmj1<9FW!ClpcIG!=r1N*8?sy!qx#@pWTTfOAhQ|&Fp>EO`{VBk zA_*I0UOZSzs`~VOH!1&bi*csazgM{zt*ut0Rrn^l z`yEZZzunyTn=}&?1n4ddxTyajFhq(cVteZo5pza5rqSJaw3{FWl#-ALh#YDF1l@Y+ zcLxr(lu={LbX(1|CDx-yS-n!Y0RaI+-pX)a7g=xGc#b zEEkjBa$5FrZo}!l?(Jr+xN-Wz0*YX@Z*y(c5w@H!0%!>yxOn_hLxg#KAIn?d z7(r1Np-(U~JuPEvTZS#q!OaaSsc1qev3m#~adc!)vx0Zy^70ZDd0Ti{g%(+#-H5anIL2bvHV9)5wDJw0_Y=6)F z7#u%T1ksFl$p#~Zo1iMmvto@;ccN0#I!@wAQ!BSnvRa`;#Dmu zEa7M_T63dy!UZuy`oiB`^*|TUEmjP&W$JIimep-j5b7w}Kh;-N;XRk6_kab4h>+Pv zNJ2tMLGe;DU;HY1%CZWSM({NdRertyes<tGis7-aK3?0aU2mpxCs3bAW#ZtfXv;VBb1i$>-=LRFn`2Gmtd)X1A2sJRw2+9i&b)~g(DZq!B$&WH*DH6M!|?m>)Zfe`uSXN zH2kZ6!2|J>NyybRBe7q+u?*w?>mO+=|Mu*z)QZW6caQyuiy%IRbv|2mqNAhBC@c(xRI+tB9gxni(NW0+qURvL z0bMKVQ6DOv%?{igfq(Vbf%~yAm0DE8f613W4M83N4S+t5OJ820UGHJ57Xiya(_#n( zNcdZ)mr=$o_PIp$VyJXfR7SLie)Jw@v zBG<-q3ne@}94)2*#o%|L*A!aph^aPfa`fy-gUd0%z|1MLcVTn{4}2k89Qn9n$~akN zg-E#Hk?4`1f2)uiQ9z17BQS3HXWjnnnJ9VCNARX8#*f6g>rYkI(=zgm9PD0{M%ek( zudEA#kdf2KC<%WzkrOMTZT|A?6+-D4spjS71$lv(#!B9QX+F&g25!(x=Yd?Hzu{W3 z%=U-?^X64+?zOeG&sb7st#etR_|=Qk_ul6-uh5|RN8bJ}#{V=yqAEs&6jZZ4U55vY z-QI3(si^-f#WwBZH-r(z8$1?pjsy{~$liZ1jGc*0N2Xz*mg3ieiX$xc6*Nqo7?m0Y zL(Wn^u#{O{lmi?ga~vv_0@w>ovqZq%o5Ls>=$<08t>U;ZO23%YJh-_Bnphf!9d@Q|5dT>_G}tN75~6hW?*3WU}q;0#Kp}m4kB?dlqjr+w+cT&bH&gC z2Pfx-y{S>^lImwOOtq(zO0Qp&7O=lIC<0gXzdVKxSGz^hAnLhn zG)f^y{U8z30nvDKvoO4@w4PqtufM#XslIvFc%$Wr2;13l0FMwJZDC?!LdM6ZsUeXz zwmCA5;g}Yp3l8VkzB1xqZ`+&f^}g^es3B!zQ;a9Occ)Yu(D+cP$_w)~9K!v8Jn+x} z-VCMXOmFL9%4Ju7dVWt6-;(~I@!b!7WES!ac8nz=Lj+avqGakFuF6v>ik{ak;_I_7 z7~R0qg+0lnFk;ER8N^FHe-m2z^0kai2>Yra5z`tx3DT{;OlapC+4{F|_c*nf8 zIF3r`fQ5R23UC@seb~2eg?fQlv$p;B)T(%_To)GOf^9^564G+qSQl>V(cEDzW^=b?&Rd87xSLsFvL_!3KfLrKxB&L zfBpL}j}ra%=h14aL3G>5=qPlEJUz_+8OLVaf@?Z&zGV<|^M!$C0jhySR(S6*wkxF6luF$udlQKn|Ie8LXOJqP2E?hv zBfRv3UBG)F0(_}UWa%VnXh;DuRCra0KuJXfJkwKUC1uFEag@_@i+gQfx4e0wLO^k+ zZ5AAIi?daWz%JRO5wS{WYbtbJb_w9!ElYnMeaPEOsNRL)0WRdsi4G~&p=-nD?pVr~ z@a7kxo>C>_tHlIap780=z|m>_5AIP%-$wm>v#s|u0R1%JCJN$mdn!?tHfpHfL)H!b zIGJs?@kvO4qjG=Qb_dD|>UJyxDME5$VjbZu71fayRaH`4@oLB{K3~I~aHZSpSq9ES zf@uU74LYz>cEQOH&13+Me!n(IMpN?7E^7V%)fd}d2ZPL}=?HHDcA?)7L#qW_B%44SdK7^O zRd~DepQhb@Yn*Jm0n6AM2*%7qb6egdXrqdckI(#=?EhEGCR(ZE(rUJm7^J6g@PWVa z-O=Tjf{o`+l9f&7C%CvqV6xX!z4(?G_1GBRKuIqJ*4jNUN zC;gSOzhd3PXVtz-Hkhwgsn>MAN?+S*C%c~&fParX$G|LKj&x7A|a#D}VY z>AS+Tf#TBFs^C7_OgOTyu6>Hd(-f7#sSVM>^`|=gx_OQQTS54kAjB>G~3VY1OaE) zAN@8vaTTP|^?({-7iWiu`k3&L5;y2B^iJ$8c6u$mG7^)h zJgo88l$R&dR*L(Xhtk{Qf!z6Of*=*r#7)9mJ>&WDdSwq*Gzxk!sMDYx{QmT>Ax+5( zOyl$wk=+ZQ!`j{C1;=(SA}8}H zBmDe=QFC!I$}~O7m++`43hj%>g05<36I7UEYkJ#03*ETN9yA2Z&z+ypH&6L~FBN_H z@nZwct*=c@y0tbw`7Sz)EtuxcqWTCB?A!ba@g!AMDvoU6WWRnzK)ckhpD7BV**c2@ z12>kUuov3`NF1PiW#I--gq_HE8R=CF-aL}qvkq*PnG=-5i5)CO-l*RaiM$y;H~#(_tRM8>@g3f_vyeg$l}Rxtphu|d-@kLt)Q5vD zHmghaDU?LOl)B&5#s?{!rqKIsYR_`G>Gv z{5o{7b)|RNU){FtIcST!Iq}r+Kb|NT-R17nI?4nnGeRTfppGu3QL-0n_j@Z8gy;Y@ z)f#|j{neY>P7Q z{9a=N8P})P8iSNqh<mL_dn@R(*NX4IZyp^ ztQE=Jy#oO+kZ!{MpoQgi_NnMQlewvI5sJcpp+{kmBA=FyPNs)4ZvNta+32c~|2Ozt z#l$nx;!$Y)9a=^6R1jc8qZ1XGgPskEFpKQIS{=)!jsdhDJI`SAao1Z?YDEcT9^Uib z=8yu3!u6H)6BN(Vf9I2^GSd|r)M23P2MnS`&<_m_Q8O@b7z!Yso5oBe(?Y9s($!BH zw|sGbCGZ=7G+?)-Z8jbeP_TK6N=XHod@9JuXpKDdcuv_Hysw zR5L4}a?lQoAQdQ2ni3HSDXG@=5Amfm4!lX#(>r(H5@D(?T!fz_#rSX&8TwYU_Rx#u z-zU|s{;v>CiA#FhKW_j3DP2JiY=V7d7M#L%l@euhVw;=8`bFi3uS=}@$HCGc^M2@x zH2ZhDS1AAg1*a5z2H`&5gkMur<{F$o@};BVDDg3-k$TjM}Uel~7=+uTS)Q;^z2cY~zPC|JBK2wgp<)W1bdh-nQs2`m`?NLXglwrm2`L!j=++ipTg`RkdoZ3|evQ+IMz#9z?762)?2|L+jp|q|#5}cf#^( z)eE#Wf$HC{*nhz-)-zk-IolZ(bni=5ncTO1i4!}Phhj8+x6fbT9|6K?$Yxfe2I`2~ zY_ekM-cohH?_7&58ZKl{(+;czM+>#hG`2u9qT_yPw{8RE4y+7N1`=WDo@mJgN1GVj zRuxLK^bG?6>Y;ATn)<5Xxf+y)=sTZd!c|H@h(>vk)!9As=Dq&WVJ;8YQv%c#G?vaU zPGa@EZw`)+zw17w0&%zxDjuAyYzuG8%syvw6k5;ZWX1XLKCuiIw|TT?Z| zk&uu~vh~opzMrQTA<^hz7SRg0(&~2n7Z3A73~^M_!<3-Cm&W)B zjE&qh4_|G*%n!IJ2ECls!A0vLF|hOo7v8rP`-5FDhJMY>4cRGjf`0N z`OP(4+1T{Kr{rtbMMJiwxUf4}#YDfCaev-YO-HA3$?TB-mC<4Kr->nfvNq+fZ&TIN zwf?QK_}d9@<#$fW1QZ_txMT++jx%^v=|{@?wr|BK(Qc(%j}>Ywj8T3l8y_5m?$46) zaogOyJT?ZRdpGqss(P&{{AroT-V^t3N8Rhy-~r&;>Q*c&jopD> z64j@T>I*1HoEHU!g(?EM|NIH98m`{R(2%~VQ?m6CtCUiJj`G5V2f<#SDKq^-3Z(U> z9aJA8)()Lz%#i5Uc6Yfrh&bVqSs)uT|Ln6}O8^1*?{BlBI9wqCfux=oCN^&Fcipu? zSBgf4vfkXtRE;DyhDNPgY%)~OIW7?Kwtb`JgPyXkt{i|Xntu0U{&dMi7uHSJu(;K4 zq;J%qE^4H40k}-D=YUbG`i-e;(U^-&r71-KZF8l?r1YZ)DtRLZCw%r>NVN~Ub=;vY zYH7)c0G5ls9ZWzbKrWsiF7j-lJNWnwPg??(D&i=qp~q6@drP$c`BQ8Xhfnsc7t5kW zx+Pzl=uR(lFTW}U8l6G3ZvQm?=-60-QOSdq-}$W-Dw}ljN(}eYwFc;cyyw{QDxJOm zMTVob>(;HfIADMfC=_%m{&eyx#-mOp%NVL2tQ82ttz9OFrllK5W}r+}R7OkvY1uIP z*!!@RjZ*SHeV-tY^Tn~{@_w3NU{pjg3g~>jt)Uq|Bb^~fznwB-~57D&}N+l!{sb9gRlGcyx@6qrYO+{`X8dt*Gc|#Jv{%+K5=NkS!b!1TlG;G&w2h zHz=fC3%RV4;EidoT*EXL<~z5%H5u-V)M*lHcf=pPpnP79Ch=zFxbxt< zHySfrBG2qD`M~*MyebiX|1poT@BBH>z`iSql&EsOBz_1-Z!ft|YixjFv^8qg>E^~p zdVYRynXo9LcI102C_4e(QH^{<}cr(>#i z1m`)TV{nds&CQ*M9>C~)Or|f?NS{cNR7$Az47sm`UEBR}(rIVPGD#g9ptL2!5rO2# zLOp@D@_Wn9!J%`cg?PcL%(83(itj)>bXcI%1>{iF3d_pMPW9YeeNW2HW@b2^(HW$6 zRzS*WgR`5j08I8&JNyF&`0fRK#KXwhSy1U(Ihd0B-Jee}OwJFfEAM53sHKq63!}HT zy>1uzlRnqX#5c#^`9wtHdwVv(LoSqdM2UkY4?v}jcB?fhT2(Wrl-Baf3Mk)*$FRx~ z&vUlH86Z&YAoQ&cG+s~RzJ~(e6%dNvbwAu#K;Z?+kMG&Qs0xhF%m`k3-M;;Q$a)K? zD$_4+6c7OwNf8hcB&53p2}zX@>6SxxcMB4VAcCZnq9AeT?gnWA>6DNL>4v+H^Z&lP z?z*#PM#fp5c;DxJp1psyuQ-%8@DHQ0YCY+d&gVmF!!Py!exX0%d)#9d-?f;Qm&cyB zhI$o^2hh`lA=Xx@9fAtHsD5I}V~|ST`}ied!5pv3X{mSRSZTYr1_VMM;Nu())Igc= zaC2#H-_yd{IxJ@e3o~EK!=sX^R&95R&+l&|He?`#Tj?t+D&j-0=fHFoSESr5#UmJu zR&7141G73aC+d>|!JtNYjg4OfVF(p@yC5Z3hE959h8#L3Xt|eaP5mDu`qv;rfm=xE z&PbHXSIi3NuvS^^c$dt*`BC8*LpHzWw>2Gm0E1G5Ka0xc0p*K>jvN7|I6*f}w({fV z<9yh1H`A`qO_X149H;?BRfQcvE+Y@`M1dhYk_-oTo8?Lp8yRrh(1K^=JJGACsH^0}~_7NV_AWLk@EKF_zNHId|s|NZ#I;!ccn*#d0=&R*K-@JpwgJA8?glap6R zxFmH+ApHZ>l!}UdX%QqHLj9%)!vt7Z=uP%n6`|#C-YtD_g2z*wlXwsdljC-dR18UR zcEg=h*DE}1lS>mVT3iHV0fz0?{f|ai^H^Ffr>J49;r8}+MLt}(TN)ECuPc!wJsDM1 zcgiPhI)q?7E4>>qPsRvGZ`yVh;g!;@X^o*qJtP>~5bwvzF-`NWynKYa(C80q)-mk& z2D^WHGK?etOw?%c!8>8}b~`p#_O8j6X!mt?7D;J>Y`A60mC_VBGM`+^EhSMC@+-La zXQ)|y3<*zOm=xYnK&i)-1>CTOb?v~8ZCgG;RA^MO+gfeh3;N6P@jHiB*p2=T z>bj3!fegOod>kE$tf+(p@8@XKRe!Nc04v znjq!p>&2L+sV>~5)+tOW;F94RG2T)aP3==wGIvSoA% zJG3HU&NFVvhxf4OOOw(B*d4Nh*a+2vr#x!R)WlyjfPz2?HlPs~L|XyPbY3vQMYe7XFho?c53LGC?Yt2TYTP-EG+y3}5B#?h_ie3Ep`gz0F_5iK*!2&Y>(^2mMKtODCCm%0wf#<%ZT#=BB)>jgYJiz*Z5|bMS(^KP$vo_6R+(&La!&OA4 z>a8>ZptD22&0D}J2}A&%`A`D_=isrHfib%H4Ofti4Qdy@$#KUg;3sgPhr6R2uK55d zAswS8fsI^o;pUH3H=YG~AP~A4CLeB(CnaqB6rh65%Gk_IrwGMkmZ`73BM}DEqLPg% zX>p2L*;>Kh2E-Mfa8@M2RY=tWN~z*dr!j1{P=Xh@5?FM3{H%nq1R{W})O?T~rtq4i zY*hw7PRqpOM*rkwH*gDV9n^p>fM|%dBTT#i_a`nP>58d}K#ogs=N>274;!cPHSVX~5L0^yGd%_ewokh+xvQKdAE-2<(_2+GLFu)d`i z5I~{3a+v5+w($lTkwGyMy`jD=Ii|YgZ~psox96CVxJqg|I#zEpxlPrEVEgr9i|+{2 zqQ`Z9_B+ab5K{nCl zXS1cqOPZg*?c?W$Nwb!7GBZ(I{=1hPMDVx*7q4rND9{3J5uBSgZ;xIjOy_B?Pa6?x z0FMBXRhm&T69opZO?m@ic?WzBsKCj2p=2V>-`=SO`e&^e5e#74%8?N_0>&QZunvds z-?l2g*VCq4I^;=XGJHF9C_dSQ1jN5{aBpnq6 zJYIJL_4-5c>_|Xs7t=aBMH%9`J`_O8MeJ>UyJ>5!vQEaXVp(_1+LYCsdNtB&-(uJL zIrY2M$MZt+%mC^uOo8*cwsvY@AF348W;3k=XiIEp@(Tx(Auk!!`G#yzH86>u*J5*2 z&wpt%<|*^+0}1~oK}`lI)nj89LA}t$I@|~nJ#+qOko^_zc?KJ*WiV@Z?LUp@IDk&R zt8fG1DbqQ&U$5Ll@(mEWBNXA*X_77J-_2 zZ+5_}petO;VU4Te&7qJXHTa(NSs62EAc{r^0?wbmW4j`ciDbP*xmW7zXZGfMUGVy& zmlFI#S+$UPK84D9dJ2%%lWy3XO|C(3O9OTBl)nPV3q0-X zl;csWQlK5`8MN4Zrlt5Jt4_g}_wrn_xwf_|T0V4w>lR)Jbi^Oh>YDVodHz`3N zCkc;>#fZz7unu4?_N**O;JtxM1e}#}mn*FYlTyg}O?S6^(sQ$JE151ye32F~cbJTM z!jlhYzTC*3yKq=oSOH*cUBdvnh^@gWrDZod0-X4wKLBD@0BWuvs7?o@fW7Kf)BmFd z0CLUfq&93nDKRk-^nOKqyPLm5s7&EBG#C*EM~{gE>fDz=O3@=t6K?=?0PBK{?UJW+ z+jVo&qQjGOP{YJTAAku|uv&)p5C`4klhaeE!%Ba#<%50$Y7yyN^4tQ@MNGPk=*1?P znOg^E1;(^^_52L?0>KEJ)UkDb;OpxHNg3^l2$!7Zl=p5=?0Z^(Kp?#3_qKZ)yVv{u zBp`)RZZ9~zVq>&toccuIzMwvvDUnk|44_Dbh5e37CZ#=<@N-sH$H00#$kgG7U)8OV zZzA9U=)%IFV0FcDVD*v9&K=IB77_8OLUwiX<(BA$%r+oEV-l$pq9tP6hGb$nt;X#- zG#`QM0tJM6PsOL&3^k`_SS^^1@`g}tp<)ITP0~77|KGEziqOv1woKUR7j*xXDk%oV zw)Ai=7hMnz6=wqpIbX+wC-NlcCVd!R@^c0thKihfKv;%%PuTqUllmt!GKqFrmtU+7 z_V?fZ+xdvzX9mSEE14`>v%dbXsAJU|T-)d7B@r}9vcLh%E)!#Et-JxgX1qJH2g{=A{k&0TKl6{&%%2&y6NqF9Gs=1z2UXy;fd$#7x30>v)DjHZ@+ z{g5Fi91F!)avL6w0P5K_{IB9_C5S0dzMtKoEg*_x`UA=Sh!>Xy$=iX(2L-7nRz-YN zjix|5m=7FWItQgy#ed2hnw$S9+7ELAY-0`#9xTWxY zuw!*7hmC?7mq!Fukpz6efd>FN=}qD0zg000?~R!ua8vz8I52{sK(h42GW*gKZQy3h z2MV_xR`Q0~+0R51P9!i0uB&T@+PvB}Jt5FP^nx7*hIK6(*8N`D{tR~nl(3aQ9E6fV zq@t6OPK?@&q^M1+_uUP@w=B5MXTt zs%5Tyj>%lj3HY4uB|NNWPCPUzLmASs<9oY z%~%WXrS=%w3>%@yTVNq7?&_3V$H+p=0`T6z4~_1WhWj_FtAIS()zwvXjFyK}mT+xt zjrM|^XF4ai5G)F1x)uKpw>)!Nr0Pwy-~?ax9Jy^Y*p9|ZEIux-!Jl*7?Ga#E(T8eY z$*@=yLYpA+a&awNDriv%vx`7&&yC#Yab$E>0$cFSF9v|SS-%-i1}+V7Sc?@jgMXi% z+$Jyv>dnu2sW$>Jj9?dZ5L^o4e~v0Q@iBuFxEnODP8sqC($dm`M!w~2*XfH>88Z*h zM~E8h8iD3UV{QN{{6^+(9$Y1}^e=(_T)Q2sYm`Fsvj2*8`_ivL1(xRKi2c=}*xqdJ z7yW%##l=T}>8y+q&V(vvwG-|BvXp!2LyS9_!ZWDD@-+Ez57d89{)5IYs*c|X;qVQk z9Z7)!6$}eD&cAE&o{?0&4arPm;tseSK&vb(cF+KPEh`(|ak+0^nAfy=H(*Xin*6i> zn1tk#HA!Z%ZU}j~Fo~29=ji$fh)!MrNLab?2=kOzkDU|(3d_B1Bz3cX3|~Vn7FWug9!oGP*3n|?IeuUXmIX(+#Ea46Rr9$EV`UR$rm(a$8UL%dpXkqs_`X**D;#ykvMYg+U?%GQ%vd|%(bX=&9 zzqbfqp`jwX8!^HqAfS;DDP7`J+AVzflU(D!Ei&h3SCHB=T;QgRFJJs&1dK@&1UNF~ z*?RBVM8OFfV-kjzp0;UOqAkG4%xq|EEY&g2>{at$WvFWS8C{$f%zB^$1LMnBs2S24ht7VG=UIasCiVyAu89_H zjF0-~;m6HC?q+d*d^KB%fAc0&$6ZiXLJj!f|GZpRU<{mnm6civncPyz*R7z}cVX`4 zMr`kXz5Nb~S)3|Du3Tw7=a#=N02%e+q5{ z?SzVasO2F@X??U%vf~8mb?~yzI}63&c*k`CH!T9vEm>S+aIgU+3wNdEOzZFR*N9Jd z|6Lotzh&jMJw>I^q(E3I5SQu?vL$-BRr?19(tZ^*0l&KNgV2OR7OuGMOr74?$##LZ zBFdo$axaYs*3ha5g3qi7S$dzb_GNyQ6;$>1mAaitg5Wa+!5k`YE;UtbX(_VDl$HRe z#pE2&c<91c*4M*UeEwFA)b{RG{8yD&KNc1DCpmd~&4cbrB8W}*5k^K|vmaiCGbJY) zvNYcopn63^8W{Eoz#7{s8Q@M^SH@pGn>GAl#JxwT*0x%Ay7_L|12&QvQ$i3`B|UVI z&?>_Xs5ODe+oFX#-D)WZ5S+AAcUa4@xz;EBAIc^xhn@-{FzR`_9iRBDZo4G4w(K@s z!T$^K3=PryMvZU@Kn}fGv-{kHYkjI35e2sFr<1%L1wu}vCMW2-haJq0ep!!GdIAt_FhLAwJ#xVXC!K5rl?(QR4|5Q zEM=wi@d6A@Rk7DvnPpnoySc-}ghRcr&;+KOiLvqTsg~8jye9Cvg6znI3zbFt4~>c_ zB7@d%Wo=Ex@&SktY5#kKSnyPWVjLKh(=#!^2&u}S-wE_ovBls6x#3SNuOTTKwi13g zXSAYws>o#sO@)Xaq&Wn!FH>(qvSjA36Uu<5whdPn9kE{+FJlV0tY`oCDA5~aqaLLU zh^ffRgmVDp7Wc@=1Ov7OE<6UEcYjD2y%3Dnj2ACmtRj3ZJK?11jwm2$8vBuyRYKL* z(*qvhLchz4f|>F;Ay72HnFWA0FAC6p3{;|p4{IT!`>oQVFjgZ{&&n!ihe&wnUmX-5 z8To}b7)+Xr`9bVtv1`m+)+1_wdlt?%%(~AzR{nJtmX*!`J>(01{TrsJG7Aq@4(9zx zE@@42zgudy2uM~1&;nE`Oz+SGw5p;1O6SVFhhq%}zYGDp08d!cpb6Kw^Lq6j1CFVc z^N%EGsz(H8q0FLM=^d`7*5>3VC1}2jmsus7XK!0{Wa=R!zY_RJNJvT-bp&3M>qea}mcQ$kV3fg~ zJIZx$x7OEHZ8gzn+2Hi>uJu?^5TMLV;j{pA zfLwji5HzMxz&mT*Rj)$a;a_LYokd+{1FjZ2WEgrwKdyTic3U^=kVF$iu7d+A1dMn~~IOAdtiB}Bm^5n=r_buuC!p&s~hjA1TVi;qmd9%xjat^w!&SGhq zR2A^X-*$kF$BHlnm*6(+8ARdGi2U~auH8+Rcz?)&47f_xX|owEx9TZv;~wbtN*S*R zL$=fHu}8@;^H_-zgP=rDLoXOr2xaSCzi)2*WgMXFbM;~~>#QHYI{z)(`-E?0HU9^@ zr59&ErW(YBJu;hJ8dC(?G-z%*Zdu4eexf6|`wsR3S(=MK1z}<7khkk@daE0Cj{-8M zbSH!hask?@H133;?!1)jFLIWcW;gNFI%b3?Plk{cmUuA^YW*{Mx)f+(7iy1?>vf`w zNBB1qbl*0CBZrh1q(iWhq59ZS7MA>XuQl$0^l!ef{T}L{!L-m;Txe#5jNgR$KA>!o z2d$E$mrFd;lV86-g@uP(^y^>c6c$DbVQ&0vb)*a!;~6Sj``q4uK)K4`RaZGP%;d<= z)tSR}z9nfudHnR&Z4v5G*|0k1AuS%9sx8PJ(@KcHHnj{1{vV(nq<83+iR=E?KWOIm zNsxBAyaHy_Mk)pG%4>tR7m|zeOs`=afw{ree8~ffS4>pRFF9V%t7Ov>!j0mk*K$FN zG~83$n5dkHKT=&vdu{Lz}-FDLn(RAQXfsThn4!97{O8F#1XAg(&{z#roYDw%gcfT!>sC*!d%1Sg}3Q0Y}e_nskHK|{HodUfL+mk%r{zJJ?YWlkx z1;K;$KKH)@?b{rGYfAR>mumA_j5_9GQ4P@C<0fOIGntGvYG(i=@G9pk#2@*%fk%4Q z!{W%{rLQF=s_%*fLYlv*u>$P&E3FOH+<^C20V@|~T!37Ri;L@vP*TBYn||8)m~HR# zV8SM*4!S2<5gau~nEDqjS9tNdV;{Q4=2!dA$xB-6eOuDdpQoxnpm-i1*&_SwfuM0m z!-7^-s?Y7dzv&DJx%m2V*a9@Du0s`Y&>xt&?`~es*=&W z3lUh>=AE>?1@jrCynxMQvFUn1S}|BqTc1jX^M{E_HwiE z@frDps3NB7`Fqn|hYw;I8h`lfc`vqO3oeQEUHY63o^g%IG^93fP#t-_Ox|V1_t|#n zwK=7x@>ILM5phN#=8DfHxcLV=)i;HX;zMzemnFk-D}HJ^Vrj-{OF=8H#r`A<`#7TZ zqqWxzc7@UY8O_g!sRd?yXI^!?`TM%=i#nA)h8z)RCj<-(vhHhfqCKf3C*A7mbGs`t-<4@ETn zRxY`%4n!b|rK?=JH}nNfJW>N11#d~qvqqQdDbQ8wS+HUW_4H%FfD6K$eL=83E&zy~ z-HgUws;6=8b+s`i4Qdz`Qg!>R$e>lCi5FiqAg7_#iZAiiOkd5=2JuVJ69$W;0|RB< z{6Bj6+HLj|9LFmh7s+<4r!=XaJ64l*VZ>XcP{&V2I|FOc=d zgW2ZXRt5#f^E4p zW&|V#j>q0#Mpzi=>1Bhaktr#?(AdI82^EQpJ4eWM5z6j6xLvzed6hE9`&_|f0{r}z z1~kssRN9Xh&$kvw4&?mA26YeZFGI3_aMf|15tUWfH$2(WC1>5KF2tP3Qv5p~E1Bf6 z&wPDk@@eZV&l#p>nJbUZaPZmNyEjC3h}5Gs3Jw|+uVHdCjd`=A4@%HA|1%ecDzu3c9mivjBMiQKvCzJ@8Znv*x_^w zH(IBIUSiPJ{LH-HCrkHMt9J#-)(ep*qO#N8VyWJG*O)lOwocOMME4UsQ`}uy{G6OJ z$i=S**vB|6|NQbM#SMn6JWqPawRA`ggX8 z(|?2I?&W7OR_ty5CSnknsW8lN>P+d$R+FoI=p5|yu^9hO&PidU*C3^}_IS_WsR-s) z{rmp0Bd_O+Q%wiqU53J&*6X)aCp$|mc=Qwg-u*T&&rk8PFbb%Tm-(by2|P(Ad=$fU zgMK9;N*GB#7t~W1M7EP3dMiIHg`31UOzkKMKT+g4^f5x!IqW6fn&emPTr8r8x$Y%f z_lS#GIZe&=UrUCQ$oxGgC+BAc!O!=9xV&xWEc!`*55~-ZJJIx9y#rab^86(*^F-CZ zaJdI1u6|7Z6>a=iaZX@RPi(N2QfKGr?Bc=8inTj=^?#onlqQ+%=adz}436|$v26OT z9aP)9l9FNAy*t%g-ceVc#a)-YT%hY%^U-bT%XE8lgH&;+CGNssB+mHv6?wg5ASS}RZrK?n=QTmfJ<1;l7Jb6l)_a4Opl{r&)&K44HGP^&*X zUzua8nm2F4^HHnfMR4%aOS#^^b{@8dly+yt-?I!&TumGuEt#JkkesbB)HO`V4K|%) z@?#|FM}i&wKt zimt8)drOg)VMMLKG-l$N+$l!(eT-$jAM{Q)Ue{bTKlvAZmi@LcX>)g>EPLLc_d84} zewG|wi4h+bJV|tJTWJ@ft@Pf!^*#B|i-~LOqt>JBUTC8~SZd!3&nRg>3PJQPp=#~^ zw3vbcr52D?0=Jwl6lMX|C8U}w&K|KR4Bav|m7U-Bh6bhzE?u75Ox*7uBh%A)a1Wr1 zv#_%pky+2xDh>ux#pWbe#`EH-j?M(Kok~#jZt|>bht{)~*>UgBbMLN*G`=O~fP6f9 z#Rp!}>{+k-cB^CA-={uo?6@%KrRW;FK3bD|*KfkscQB^yrVh)Gcg2Xp#hEsWEzMTB z>dV*Im*pRM>fXsK=(Pwq2OP{?1U~unn!Z7<)6%{94;`N99-r^g=}VbjMQ%QiltOjB9HreUv(ky^{p&YkYbkPd6_2U8OL8W@^kLc$M z-FhrG;S%q#Ft~WW@edj(DKEDo{s-4fqMwv)n;p)>KSLO3wF|XsKU5`aJQc*p9(KF9I4FvPqK1KtOBEf2YAL+cF17<5o{c@b~In2T{`2_81uIHV{_1uqf zgl_eYurg)R62w39dhwr9ri4%(s(0wBAhofi%Dsd1?8>;l<__3z9---vqoZHm zxxXE7||IqV~Q_`$La9?3)drQx0G#~@R0n6q=T7#=!?A39zP@~E4nZa0{sBKsiA$Hv32kr^&H1< zk`|3UlfC}25Pm5N5wI#4d);18KbdGOcRh~&)A4kAd%~=F^W_e5rq#+7Nz1poTXePW zzBPh>-KlMd`Q{OTXpZI5?uF3_a{*o(50_sim|Dnz`@@+}nyhi&Hv3Z(qjqn~3c zgS9iCzM?rCtjvQ4iP0?rO`r|4LW)lrSBjolxfAFO_!d5plhPNwH6 zg4<##;s^xW_OZA2O=Wgw=7BcXsn1Ac7=X!^d;)p@)wnjYx6r{n0(KBF5N&JM`VJeJ zd9+e^Z1Hs%=Q_`^KGpEUR)KesgjU&2S`!(PwzpeXSg7;}eQ;nv0*w0V6jwkX1}5DS z(D=VtUm4b?S6_<+5Ghx!?fPd3_Gg)J!NFUmgm`LZE0c=b+0F~aJv$5he{8_^X*sW( ziAAABFHo>TGU62e?{eh;4tD$>UT?*KfKIKns|lX&VwW}bAp_mu_lAAfbM{%%`nSwleXIKK<--EB;XF3@cZH2Dmuw zLc`WHQenv21f!}6_*;P}VLfp-b%5D#fDx6h841Dv1K=;2X=GX+1g9VYe5<4D>Sf)b z3S;7~2xdrZac9zv<}Q zm-=XI1jfk_+M z4-g`P=c0reJ&?TldNRyHd`FBAAS7VG4o)-g_H|R;=dQ`!ePHxfaR_awl8lOq0rbE{ z6*MF$xs7B9o`plLgi&u_-$*Yf24ZC(eH{e8C?)Vt>5`X%m6er4^;AZ*Iu(@5{q3kb z6XP?Mnj(5oI90F+8tm~}T7 z^_g=pBnLcqaqPD)<+Cv z_BO_fpSUpoyC@oS?8q=8f+;By%+`1BwRmxQ-wb^5@Z*P8WIV>{dZCJ@CfT8XO(D(; zI4LYFvSP=0DY3C6|9-LoHyuC-S$K=wsOt=m{hki0DAC|`AVFPbpq)1>=HI)s6BC2- z=~YTVetLRPPa-^dw5%ZF0{3P%`~-S%Fp0>G$nPOhNvyWi`Qp;jL9w>>cp<>!rB5{= z;+fP+1`xCZ)>U1La}aAbm|Bba;P&Z+0tV?$`XrBmcL2~`nNmg*wK4DxzWTh})z_y1 z{|#5BWG$w8Tr2FayrSZW`kr7iOm2%<F z008@_34N0I4^ArGAO_ZFTxfGe7Yh~0Y?5!07I$UUvJy{xVjr;1EcpIa+WC^4Uo(uT z$S^P2f!cX@wHo#1S|hCw(8KGp!Fc=0$6N&xNPwYKcOf%a+1Q{5O?{XA9ZauyXEvo< zhTp;J2T3D?Gj66h&w-2wU2f%Ktd9JfAG#8`BQB@OE)VYxZU#Y#`+~C91VCv3#eE_6 zlcvs9E|&H8GdtxZS`?a;N9VfmT&pT&g**q6IBkHw%&?%GI-q_?Pyqp&E@Vz=PWT^( z)Ypoi!L7<$*2TkVM8>=yUPA+aEZTT13#c5xm6K^xriyxe(^^&kA?>Kg&&}>8;Cp4k zBro$dbl$lTB<`~$xNGJmGVwx|<3pd55{q^o;;&B>G=7_rX|*J3{#gf6HKgR^nQ+9z z#h`8puxOH9s$<4!L!l12%WKd(lt~c=jPdH7<~$A`Is6nYE}%Skhv)=(wK z?_c+YFz3P8JKh@s@Div77>w)H%9o_8L^!hXB;h0e#8C-EX<;C`1RgdXJToEKr~u-~ zJ$()9XsKJh)lp#78r(nJdfLV${Wv6gowtaUbko0o=i%f;jBj_>VF^v-NrINGeZIf! zThF2+$Ztxzvw>fP!xI80esb5@?==fg@e9>*XX33K}F%*)$#wo1{ zycH^LtF?{)Zt#9}-nNUYtK}mCvOSI~d&l16y~DD%;Ivj48*P)+T%9&EF%EKOvjDIh zEbf*QH%wbb;DQT9zd8D$=-cyAGV4f%68;tzED4M_TNuf1MzL7Di2f#sU_ddkHgfBr zw1w>O@mNL-P}-R%D-4dAQU<86!H(%dHb`eUEb9j9BD*ZkHwS#YMG{qplkPv&lJcNS z0B5g_+-=E(f^?}pJ`^UjYNQ03P&Oem9%omkz|SfMumO~f@!}kCJdN?F77+o# znea3^Fqop!EZq0{pOoHa1CC9*F9@R+8$+@H_eI=AdgTk7Qr~n=ke%=Lwdp)veTj$T ziH{qcP^nXON1E&$G&MRCzI?A@m@eMbxt4OeoMC&{ZgO}Oc@5OOez}e~^x9g`ssD@E zz`O(db}M1=KduQZ(pLRx#b2}X7I8MK>0x%KX_&fhKW+Xn~V_^{pP znrgZPj_FgZ!S@_wnAHBFlCTb_Wq{z>{-s3#(tUFqP4p9dOe}NY>pv;IlS;zH!?R>U zQaiK^8M2P#3bg~k4F|e$hjyVd;JCTZFfsMbV4KYC$HF|#g^*wQmGVz_s0{ul%y5nt zjqp0eL?_Aju$0@|d7vN0lD^pOoOmkxoPTlj?K4B~HrTB-#eezTghc^?Kj2*Bxwjo3 z(0}Rzb7P@reGW$?L>~7G$>5B~ud#j>r^?x{e2VEnlCxM9vt-(`43L#iEw~lo=!Ol? z#?KCjU(oL9I`#04w=FwXf&{HE&8Xx%8@SCQSbnki-_I=@hPqk*?ZXNndf|R1%u00{qQw#b1q98H$^*wfD zy@)Okt}3VGyNzBjaQ)uutm>uUncPUhLD{1*%};Uz-eOB$Z@<>tEdxor(-c~3@Q?g@wk=S-vM!=%Iz~C^+HUHo z%%P(M?4c!4Co=kKkO@^Y#}x!QSGivG)bZEGt6XwcIsZtzff6CqoNJg9yV+4>ARIXq z&<`h=jHgHH@5NCcydIZuG>$i8ZK*;;E1m-mA?TtL06fNCjes3WKRqr8p_9-u1=bUek@l z8}r}TIH+ko0t$=Gwij!H{H%}A1}#L(@fats-OjJ()nupkILPdqdkGk&^cbjs)z4>xn0|C?B)E-@KWvB6TiSED)&eD z3O*@*m)oV^CQgp0o@5`Nh*HTpIck0KOzGz_^I$Zg&A)8ScVDs*Y(zZK@i?2xUy6jm zo4E-36;dqsg-MSy6+x--MWO9(hT|5Ux_1I1Atqh1oP2X8#@#X(IrW_k^%wU-mnzJN z9-iO0SfkbdE1Ef+5olvnV0uU-$mrt1M66}z7|ogAAe^< z98`T%`b5tTb$53h+VQ>p{f@i*e*X<3K{Co4RvZ?enNMLK9re{Ug$pXxq6+*tLN%t( zT==phH?MGRFs3_&5!}T=ew229=v=Oa4dwC3h0q;3i9gKBs>!I)q$sL>?an(90V6~~ zFF=!48-_UI4v;(g+{tM-?Y&X)L`T)OYwWGtJRY0Y@+SU142pkujh+ZrYQ6OZMPEh7b0 z+g(!Qhp?IZPn?_hX|HI3AbHR8%!?Prj64R`pFZ@HY-p`+^WPiJdVrj zp(Bi$(=ETW(On zBSJfNeI1#%j5h`huwLG&+^gU}?HaMT#Am)8$gLE&k7ZCH4C}1}%s*_&bD%2f~zDj-ZXW~ah zSlEZiNCN}jcTY4NViFQy#Oq8=pAw}P&1l}0aSEx1FtlGDjQIwQd7rNNy(;6Px^%M* zEB+{c1w!J2r|wNQrHY6(UM73L<=-NIkU=AWle**TWNOWHHJ$#OH02P%c{}#AmxcZ$ zT@rQHT_)1c_&=U={G>X?yo$I+Ua3W=N7m{_NVc}PuyW%YX+FJ`5;12pqRYs|;y(YD z((~{@zs}Ya{hhB~0^9FzR@Qh(irV?@e_#0o(+~v(%Y9_D*}DdQH;pp-B9J4^Z|YOe zsm2>7x-|ask6fSrQx#4{b$5OaA!anU!H&~JQ)!3{gM$);`;#ENfg*;~h`L~Nj)M?X zh!1PrA^S7C`OT-t)QC`#(gfB8WTv(%Ia%47&?O%EmDeu(g|9xN{hIpG6rK18T};wO z(V?zBWWl7%XtVgvr%#5LKgguBn5^wt(d$!tzlfi-8LDs|l*q@@DROiDX;v(ur+Y@1 zKDw1cw$F1(Q6mYT?aGK7zDa*jfF(_8En>9ZG60lLMMsSO@Dh~b5vSn!togtmr%&Zx3sIqYxFJn*BKhU#HGEF%r-|V*RW-FH1?g8En8xx+CI`}NoMR&S-(5& zdPCVNKY!j0`*pLKuk%UUkN&h%MPhV*{pQW*KOcT~C-C8JILwuKedU{;*A1&!bc^E! z<1zA${en!);eq{Vy|`BUwacA=G1{#M`V01Ja-;8FiYuwdZ>65ohE$&;eI~?|R2I|h zhwfZ|7u&Z*Ll)ecIv?G0JqGk?|O!McCzC`S8FP_AfC5%VZ1=Wz&H!i(YYh9W?bQL|UQaIan6Z*^H&J<_g zqa!L6)ZFux>IC~Df2uj*o`Bcow#d4uazpM`U80&RwTlQzxqh?e{P`I|gSghmCuv2n zakS}%ZfI^io8S2Z^`x`=m)jbte-1aM+)q!*9`f8ir^{(T^YdQ7zPtX{{vh4Vp~l1J5nsO)LS@{R|bZ@(*OWYMQ=%MT7#(I7hjI+AQWBXQ>v zEqo0jQ2sEnv8mmP^dL+0pyW^g0vyD(>=!6>jRQLnw$*>lXlD|Hcde{zL#n{4y?m<} zS6fi=_cS84^YicSM=NIJ2^9_c>N5@FrO$CNKf9r2oE1Efe;`JG?RoN*>YGuo>jgOK zmVaZPUOqL|WFpCewfuA` zh&EdA-MGN}RKB-8b{+Ao6Un#!jBd-dXA;@q8?~8#d4A9?4cb zVEWYe?iRc7p`CZu0kQlT24o+2W>y{oeIJEh#GNWTe)~!nozp8yl$Uu`tstC<4AaD&T?zI)_SzSAGFr# z4y=JAYvJz@Tsrb6-l8aJISgeup!vyJsJU)tA&hzayEz1sBIcjj?J016qGFNFogy)O&+xyT>d?@yB` z{VX{XQ-rvhrq*H$ch&re#9O`}pJOv0kN3N6r%$CC>Rq2rHSV-)PDzp)ReaMR-G=?# zesfN_=*I4|8(v+!4GYWU!66KYXIOH@#ZTo@2$lV_o}KBAf8<@N^1pG^d*Ec-t>`Gj zt~EwZ_eArOd%GHcr?H&heo*mX_x(*#8E@Bt-Rm8ij>qU2A4R>1XMfmZjvVSE<|egd z+B2TY>bDJa<0^l&X}iYBw}@Yb{hW&VF~X6kUgVg_A7?g|%y{%sck6UT+t2=RRHXx$?ee|}1iQ?RK@wWY1}c&vK5yBGT&!v`K7 z?n4Rf2jTZP9&zY65cSbgeRtTC8IHSM_{;AT>7noI_QSA(O{4tpE%Ep!ig<)K3<}ae zyqq<@uvMYxAU|H{HAu6RldY>Uv&eI?$$IEGG8?}idr#!xQPt_vfxBX-lYud9FkDB`_B9r>b zfg*gzo#uZ*1sE@F=wlm#AQN8})ww}rM$NfwQ!HBD2idGBpHUEDYwAyhPh&K4OZT#$ zYS#OTfQXJqL9=zulWchHAM6S@P)sZ}FE1~U0Lff1wozkwj#U;G{wC;%LawZJr>&&2Am^?ZEVw+Ir>|!>Qko_zI(kMz7gxL)|1_St_~it?{OEfTPh7|dfmiUK*iffz3kbZU zr5j$e1idSd;O<3VE$5FJ+scEY#5*f;JRVOf-?>e?4}!DHw0OH*Cy)NHsoP;#SGdc| zHhIRp-Bj^8LdgWtY+BxT&Y5CV9JECOFym8uB5os-(Hw>*${_&Rf#o2k8BR$_2`u7J z{H8fCF3io^wvWQT^e3d4v2jaZDn@HU{&XqFHNHfOuKcAnlk~Gyw?0ls-%zpqadB;2 zrybk+#Rs+yHnXHX*qUW@31Zc`vELQ~&zx8QI+PNZFh%~)_p-`KllISL2MQ6XuuUK8 z;P?t<Dz*_rCoh^`TEhv zc&Qk1ZBHS)v2BK5lXcQkz{@tNNi&eS6k;Lrgl?huyQgGCvYKFNLIK)+*<{Xc zZV-W;11$=OTA$)HUf0MNs$w^W@E;+eZ1~-$ii%4?q%U8<=SI<(ot>brP^XlYg1AC3 zG80MQpaLWU@aUoo!0IB$_yz3spE$>|VGZD8V!(6sA(E^8@ofX8_?W9j82?~?ize#} zKz6p>g|8_Yn&C9&4E>P!2kX)sT(7^`94bY~3`fZ|9)K##wD8-95T$vcQjS=G3DfDC zW*k};kG6n;7fJ?>4xYO($QOZBp_0PTdJ$SKSydGHsi$eUVtMUjApqppj6fUQ-w%um zVE8Ry8=#BsIT_l-VeI~3F7b2Gkv>d87&DwTtuVCQGP9H!QehrCBNLxgR~;YUm=bnF zCW5_W$N)t>-1$I2o&!t~0AWNKm*30F;~)q$aO{Y}}t-D+Fh^ z@fh@fL^NHuIp7sX_jMUAQ;NdkIt2n~>D{dy9i!Bqy#L#{?Q~``Rtki07M>b>{}+J= zI`r@Z;H7`%M?XDByp^Q^q0xHTntCjHa1`T}*Ehphb<*~V5_&57 z+I6Njyw^|IYMcje7Vut;LZkQ))h#z-H#<*KZtvDkDD$LUH3YR@86~_7h9)QF!IL8~ zDHzgn=bvaCt|T-UchnN+asbCg1}5Nxtv4Jg+%Leqx?53Yb-_Kk>1VFiPx7;wT_N&3TW(TF7+Q_p*Roox5G`@ zg@uveH$Z(BZ&7`To0wQkImAsLpT@3Xp{)5PW2$B(z{L|=K92?&C8TI%7wh{WXs!*s zbd3pZiK7*Ki@iQv^#XMRJrP%Su6@!B6#f5XrPyjAP~PHeOR8~Cw*y+NN#5ReN^8AA zRIHZyX6&E2xczu{iA~Q9lK89?v2l<-m1g{}E9KB{Vl-qK2t9aSsLZ_vuP&=qWPI)a zrl@rMe^XR4b}!dX~-n(q-?_ z{T8ux1_O2+fS`ph&wS5w`Tq2N-oKyI-fFqDbs``Bn?k6WWx+)~M7nMNy=6P*IFhh5UE+nK0QhekeW8gpf9SL&vhVI9+QdPzH;)(lGYg+_J+TpPm%v}6uyI)lJubN_Et+6XhaIKHH z2o%A-$H2i60WlBpEkoIAIhy?wlxHE^WeJ8dx;=j|?C%wcJkioA5h{{C`+C=Fb;aw%`;`H!%>${Mk6FMT0bV`Ajuf9R+vU?Ca#V@oiL(JZKVUgQ!nWQN??JS1>yx~a2uEZc(VCfi!J4)qU8?fY)PLFzMgUf7gJBbJQ-hfYfHGl4#svXK^y4 z9D8MUNq3Oc<5a`x_=L*VM9=iq^pokH;fV8;Eac*X=>sl@16(t)$lgB@V!fB%dk4_)wxyk~bG7T;)%hm%zMyIaM5k}u?FwDTklO~;9Vo=1gr z1MA~Lwrf~Ek%dHp`eumBByYOh^{Slk6Aq5!8wA}ij$d8NkXGAiu()`@!7a$+u|O*P zYj(+H#?5IqYi3|URBB`})ku!ll97P=gTo_z&#I4-eJ=Ljs$;h59muik&ec*LlD9fw zid)K{`Tid*0P4%d6kKO`-1L@tzP`9#EVaSX#%8gN!VUtL!M9Js+}6}e;(1nS7_oP^ z*+*q7|N4ENUL*EDEc&+^P1(V{0t^uF?ns@%Ges(u?GIVR{(0xL;rRLoBs3QsrDbs za}lV+N9wtJlclH<-|5V6O!ehUMFoZJNvA#thQfmrJ){2iX65c%CZ3id-I+vG5Chw! z^PobUu$?Qi_|oq_I;jP+U)b%yg%kPzH1!ogQFd{^OQ&=R2uMknAgoAAhlEIXcQ;5k z(%n*mba!``f^>>VNyF0j@ZRscbD5plVFz}e=bZDL^N(L_n7!5-3&C%4GQp+M;ZJWe zGg2>Suglh_0HP>pjRshUwdmqkS0R8Bx9vFnAE2n%o{xOdZ0XKN$QRa2`J_<+c$Z2S z8gK;#1;^DtG1jjp=gW#9SX5bGk@$}dT4SCls?=H|-)?g?XDBj?#Ra47|Z=1Jx|(U{jMLtp-QhDP#hZa4xk5#Ubt4shuu z+vJ{weG(RL*&r-+d8zzl5Pc!x%SP?M^AmR~n z70@qsh)&Ximc4SteGA=qv+L8DV`3Ivdtl8zI&rQ%w=$8DJnwM#I|T>Tezp1whDBQD zsK$768&9TIM~IUL-H&}BUV7*A=q%tth12x=@zC`ah@-s!TJ1{v&v)R22oD~BN}hap zjfdl_CZAo^Pw|-vO@_I!nYB)xVbYyzis2z3-X>y-@DbMtkMCXomnX+=Dtf-)@9FzJ>R#iXD$&-IG=#*MkL-R z$Y?TaVD`hhP|xSKFPSt}3pK^j&Ffw9E@I7C&V^D>nv&u_LmB6 zPCING+;Zwi;|oC?WHHm*!fNxYO=Gd}bEEC&jCLDODK-9;Ki{BGc@C0SZ%B-+vEZ$% za8P6UND9n+*Cjh#_I;d1sc7}qCM9zuJ+ZEwR$}ZOADwlsj*vkHS$+7|>hGQqhWUkX zG~7_<-P*o|kR^Sn5-g5?%hG9Y?4|d9%)>KmcDPttDUKeWos?tPiU|bbG>Q-Vm;WC2 zd+qVL?PDXvSSq$|VW_+fL33MZ{OyYx7t)G5F^uvL81e;Z2H*%2n~^rRfJx;=jB7Je z=UX51F?p?t4cn_NU(K+weJ$%mFu8wWztCV%aQXI&DlZ#lD~n>{L1Mf`1Z_p$vs0RI z0&y0mP9IGcB7=oYhNWI~{_SRlp4j#rYPm!!>VD#KF-3yM`FZvEYN?ajH6HexL?dsZ z#LJ&IxG}=UAQ9u_e~vfYZO&~7CV19>HYnakYgifeyB|oAd6oWxbnAFs1ej{t=%kJT zD{BMbO$Wp&nDIWL6SnV6ZC}EB@I$N+ro5r=FZR(AZzlTgjiR>&)_SHp*n1DN{U+`F zn)?C*$p3`$4u5IS`3(1pGQ9@|<7TtC7-Hwn@A}%B$(^8hU!C)H2OGkA=6iNvB^a5K z6(c%BzsW8I0ytWk<(>#i=d(PS>w~M?xUG!7fr;L#tj`!N{V>%wVkNF+q_cUAR0*%? zqb5R(=09JXlo1o9v`-9ala+-o$$gf7`~dXA#i|Ept@>*T>X-ck17^QqRy4VD>>b=r zz&i|ZlM||(KeGB1+VF@BnPJb~RL_hh4Q}~Qn}50X9?>k%bat6XNVfT<=ebMw^Vi_N znFd`Tnjk7EiDKJ+F$W@GV&p(L0CesqvupEDPEJ+{MSw7{u*hj@K~oWYZmp;qF*w>G zZG~DB+ShfcU0@U6vi&$R@!r9MB7!C}f0!|-Ub&Ex^hFJ9VJ4nPLxYn=QSRx+lbU{2 zZz2VqX7g|y-`)?oVdqxdBh9z!$ww3`PqDIft==>3E$Rt(crlnec4M?kRZEPph2MM?2K`n{pcisSkZKPaur3JOx=A&CS1iL(M)-J0Gq$_@tv1-rT~-| z+d7}({xW2Z@=AeS03>5E^8rWcVlyc`>VscwbTzXC(JqM>_Z=y#el>g&zu&;;t_jnw z4z#L7eNJJaO>nu|hh^^3gzP2o{*cpwtm1u`8!(#qU|WYtcz-ygd%WTN<935}6-V`^ zD6yn^JAk?uLuqaPp?VPfJ%C4^tX_5Sj@iD$L8UUALpU3uT6gK?*b3?1AJEQ5 zI%_5xBTCfIYr{%Nx=`mx4{+*N=O&e}!nP)2N_Kp^`ZJK27l?D2V^2mpw zpyA$pbJAe2s&^z9y>MohMeutfmT<2rvWx-G?isF2fMIL9I~{ET3J1zBJ}9T1jKjaC z5Z*(%De}i-rP}q|rTe|37!pQ>x@q|;7pf{FohqfW4Wn23aWPX8!4$lCwo*JiEUs{d zQWa}O6v5oNMoAAI;|7hFy%9|M3x@ajIWRG)&ZvZ)l$}_p0=1hZcbPz-8$9w6;+T<{ z(!wphcd&`Q&3ts+;y#B}1!{z_YHC;?A;h3L2d`FBFY$1Go&=OBf>bX&vN0G0ya-Ho zqI>>6do0vAIukxR>*5xKXiegd{UJ1P{!ve|K5nf`qi~}hyFKK zT`6sytf3lmmhV=;zR-ow0cgz!0Iw&|Sg9NR$#m8SbmD)UE|fZ)O_cLFZW8F9LtaZz zsbRB>!3XY~cwH5#EzpBvOq@5K=Aev7V*TR02MJgQ!;u{5;B9{1gRhK0G10+rbXM$s z{p!pH=&$AjkFbKE%Df%ahK`5#^9mG15lpzvAM>kn-hC;re8eFXknEZJvso*3lFU{z zo?&TcCkg6_QoA`Uqs4!Ho<*m0gr>Xsuo8Tt{-Vokxq8h*&i)yjaHTT1ez+5+zS+NX z28akiGa)P~KUKH@e`GCn+B|4*OWJ`u+<=2bzj0}LVIgf#5zi1n$$xSDsr!)bW<2Tj$vN9(t7y)fD*6Y3e*3hhA* zm(ms=l?h*EW-s~?4giCHFK*WF7%U91$YSo%T_k-&yeF@NZeow1F)jH*y#q#_0d*Y2 znZ9&*YA2{-6qUasmzVp9*1lX&1d)`^Mr>?ssD#GhjI=23zFiyKurJsS= zT10=3t65GoDR3|EUE@LXub5%*1(_Voz5JPw?*Xo{NgM*D2u|PZ2kk@*;y2i{|R1Q@XaBuHZ;=ROnF#!&$E#f5OpbY&BA11Kdp zK*WHzv!ej9qQ@UMY5Y&<@hthLV@I+3%{cTG^MYZUpZ1BpvPQSjli^5TNmOn8WS(NB z<83Y0((DTPSlPwLiPtFnMWUu`PFlM^#;`dX%gID+&8{T{p#}rFhz3aCaiqzSkdn&$ z&vlm2{zfnUiW!TsGEuxx(x3MHZj#q@YVg3Sn6;O^(OAS-nV*9%`YK1Gj~ajPaZxK| zGGkVDsEnpa@vp04OVeA^MyQhS{3OI4;E_QQ0#e;sT z4U`NUM~gAbv4g8q1{X?rKZuw8kub`8(nIB(vR6a4aB72N(XH!BB)%Z1d@jFUwr>J( z41iH&YsJbgC?od!(ddj$1HQnFW4C@VzyfRltES?T5=|w3WBn)aZC@`aUYsYyOD#WV zrm8FZkZeLAhbfZLwOnG}9O&+ZvDl9UKIq?;dX*m2XR7w+&ma4L%TN&SQ;qWb^&zleyzAr(^CZ`gKAjb3muAj=w_=)`UreBNRy3`AXbJ>pU0Dvp^n>V_+-T7uTt4oGF8(yvQO}e^0 zZJZdYmx5DggG+&LEmXeLtUuTc!$M3*vh(Ej7i7{s;6=y*yc5{Y{QrdJ&~rsKsavfr&9F!b21} zo`1HTO|&9?{FMz#lJ%Uh)_DOttYw<}v0^UccMzo*UCP~zQN@$f~qKC}xm);GjeI&PM$OxolWWzpL z;EIQ&@M^SnG!#0oBimLD>zT}ifc8}`=slU%LYvn9Mm|K|e{sW7pwJ;wT61Cbzo0(x z+&La^z;I7tXzkZOmk;V^@cc(TzYhSt5X9HE;F&s#d{dS9H3J05o+!Za5K|^ z?p=+dO2tnN$MtjUqv3y|u8q3r@{BNP&qH0hFm9$ex=Kdd_Dh>W=@%5tdTsZ#1YS}z zR`{Jk_XpwKbaN^#6>+T^#F9+_=pYaHx5J<~sQPby;W?2zVaW3BV4(K@IOP=jrcyU! zT>+(aA{x!4Ra(d&-3}Nx#n70vnjl%xsVreYL874afsU_8>h{R?o(83((x)tDYVk5si|G(=iDqrvSI2c+v)iY<>MngD2qjRq>#9W(C4dhBH60+hz+KM;1;7NfsC7mVSe<;FtZOyW3g-mm3 zq8}5Rz`gtYGuSSQt*4&EZ;3bN$gSyEEnxwcpec|iJ?0VE;$tIYX zm`{BOgPrdtW!&+II;up1RkIPlG)InUY0~RbV%j@%5i9EwH!^rU6D2+NI_@@$IVJZa zSw;a!6`Ron(QmisltgoSbMA%eyN^hBcZW*azV3)#dM+DYXP(}l?KpjecyC@`5F`gL ztA)#7lkdZ~gYt@13j;$qv&&rI_Ki#@W&Sj3%4pJD9-@>l4Hg8LbQyPk0DF}&fkTEG z1A?JREQ>TA{rJA5x_mmbs3AhnYZaC}xChWA0VF3hDrc&l8e5`zzqekTy0|8}#`;b! zoVvD*y^WUV#bGBFwO0ngs2KuAxAcbY?j%5XNiDC;Mefb(>^dnu!*O7u%1oG_R*A#s9r;+$v~G6U z5;-TII@}ndOSNlnR479vGqVvgGLJ+E8T+l}Fx|p1M$sGFdjkmv?J{SvcGaRJ{gD|&y%1El6dpWuXSE5|sfhBQ8f=L?L1?&is`WF_ z%QK+A4vewDP4-kMEs`!bk!>YEQ@Tw@1#cwFOKn$0MGzuBK zdS|0jnHaQ^1my@54Vqdw-Ptc6ECXb09zE?bX&hXFRWvGI-SQ71jykT(2ql^j&Jh0Z zSzllHmf&fo)p1+gKMH}@@zgH zRO>L5_Nt4&SAZWwJAruhoOS?VF?dbIy?g zl5$EGwiJw3x1$f5-r;z|X(yKN!In_UvT2E?l`$RyWV%2-zFg+kD%h~S!=QKXZoU>| zf>`8GM?~93{=-guaBG`;bQ{XTCb7#43*n%Lz_NG7(d59JT;mu|VayHQo_-^`P+Q(I z99L!ptf~B}DjY!Y>M2V()h(ShtTM&^z*9#RThQ$)9B*HeixkM?^>x-V@M`CEpfwQ# z9@uN=v6cSF#?xZjc3=tA^U~7!1ZOXjaWq}Ggk432UeKB{0KG`f3WWOf$#)+|{?27w zc;>C8b?ZMtw1I+a_V2K#z0B}1Y^g0^C0odsBAzz4t&JQ^D^0_Tzm-^xjCwXVrEUg& z4exnA5{`BNIbVHHnFRxw7eUAa(xsxthOea$$%K)mezduz4@8-(i}2;DWUlNTEU`y{ z<~d7;Sd3;W`;vAmKF)J%0dy-PeaG=^C|MVcUmIRqZkL4V;*#xr1v2;vk5?LSfU=W~?86NMUyItMyYsexZK zt){hnA!ic!b#e>jorFn~)lTuC*=T=z*eJ;pIb~T7Dqyj+Xm7Kyd^#z?+TgHV@QVr@ zRD>=D!dEg|F8}bLBVjCk?|Z=pliLP={*unGjLKjuTt&I)9N;yGfoLw8kLn*)#%kuZ z9O_MDje)LjZU$||q@N}l4Je`hZ3};s7j^TWBP8*2)NPQu%WqF{7^+@tDdIPIFH_S> z0|9*qdGz0J3|8`Ok>qB0r54Q{b9wdOz99pKlR5CV{c(FbbhgE}-gTzt;>MdU&q{N)q|k&%5u8Oj@bGJmLm?T zAX7tz0%Mi5PlN6rrll?&A9Q`~(RMOG20IQFA}4RM;wA;jta-hrTpF{3Th8My3@#VB&TZHpy1b`E-{Sc9{eS5P{4x)iG#^lRcs3woY0vnJe2lz$Gw=w3 zSxW4F10^3QgT9xQl~q3g#mk$bSpV&MrC$l|FHH$zuJY#vP|wauFwZ^?W##xQ z==o{9hXc!xguP_I{X_zktB{OTxjr4#?&!erz@Lov9LW~Wda`JjesC>@-@fWIY&0EcZEae;YYgQg92zKtZ!r>&0F=+u_?JI z1Lq1aE-K7B?O=s4;Xks>FK0gHBVvJOhk}2 z8~`pj++Y0a)#pI0rMwgNSv2e&e$i<3axje448=Ke*da%2WJF{wgg)~-zhCg^CL(I% zxoXB_Z|l!2!Ox^XEcNAc7FF$P!w5-S`gq#zqbnoMN%*4aApa68s!=X@f8k?oRR#-g zQg9CR{M*qh8```b1iGt%ou@T{K}%y{Nn3oDnaOnPNo0`^+=?V+|E&=(yUz2-&wQ}< zoNkLpzU;f6tm2V)POrUC*yvzRKX&@w@l-uh*TItezlFyx=dGd>Uy2Ug{&dK@a)qth zwL2`I8CYXer!M6|r0=Eo9LOM^cYMK*oXja&SPuWWe_@nh&rorORM#-znWR3eGldo1fi z`p0x%;R$*l0P%vUU1#umnJ2waM80#|(>N|Pss1_)%<{Hlw{7F#6-qqyT#xljd=2bL z;EjiMSb0zIcwSh!K4^w8G#=q2UlaSPE4e25t7X2 zoa@zw6UED$uZ{pAO(oT`x0yz&qku+wd=m)mby(P)ifK-Rb}2{R%#6O6QCHMbgST)+ z78HWGPk9tzr0lH)UU6&d9!<27xoPVKoY}SeJEe%>vUhE1h>9q^tbzPxr5kGH4*o9d z_ii>~$LFm-nc#!2byzDFHF^IK^~z4vlbE6!vBP7PI|%J&>$88>uVL!GH+>sFkbqr%Ihy^~4g(Mug2+){Al$dPo1XeMgtJ`=La< zM>7s{^y1>Q44vI&GkE9WMQ55#U!cOf044_=DiX(zMpS@k>(Qb~#WJ z!LQ!|Ga9B?mCK~=h-%#3QjO<1i4#&J4!4unHsg2lU;v}){o#w1aJ|jIGnRKoEEHIK zlHXMN20CiPAVI|5dFQCSNb__6)KgWg5lKo&Kp^0>?Q(>sDWmtNQ$tYkQDsBC`3_q- z)K?JCesiF|3N^@nhdnw*a-QNnH8}~14{AQpX8HZwfVz_);Sai8noTPAQUz)%s$s-r zM3~IV{1(6t^4YHo4?(S^^BH7mnR1PC0#BLWF$ciP>K>$pDdKZ7m|Y8j@VomYM>`;cGb(&~hR9R$IlB3a8@Uk{Oi8WMJ{f4+$ zm+BimlM2d+k*B&)HC*+P&*DyHi4C)2FPTNfww){;CMG5ful}vPbcjU0_C7d(9%M3Y zw=~Jj{z|gq{nAH;jSWe??glQQkPpwg6m0@0%Kata^%n!N*M9i1Kb-wKo?6H%em%La zoq~aMN!?Y6mLM2G^4xp-`Mc`_{;K5%Dhl6X^u=l;*shR36no4tY%%9w|EYozo^eE>UsO%a1IT1BsB&|<)WNZ6Ojcw;W^eNNiHTcYyeN+nAtRf~(!#=X0&2_WY)T<= z;R!L!ptX>LKRm0*x-~$(cy!_(;A^!z;+gusjTc7#M zIMlQwV|=dJ9jqSSeVOATKz+c_Ra1+|dHhW%2NjG^SaTEDD=k&>I$VJz+-5lJj{6Q; z?H~xd3bJ_M{V8hKFZ#$TCvWt!6%rhR`e-#ps^6e#FoRI>%O~jZ=WY56y3n1 z0fh~AN*~mm+n*Q56c6mq;}r*J&oPmodiW+$|E2Jxz57CGp_1{* z;}nT_@(<^eOi&ckZH)=M>(Av^eua?hk8Qh0QB!M2AVS~2b+UH5p z?Q!3TSC}5KbNtCI428r^cEKwY^C7KK5?T@_w~cnn#rnJHU;e&-(rdW8>I7q zA0x#V<&8Oe3 zCd-w{4kBgHW@TVMxzsGR>a7X&1{fl8VwCcygXYW520a{T@bbOiL`|wzn-bnZ?=HMs z^Z3N72A6H!G}X%oM{mZKX+sQ~Dz|{-#&a@kTLww;@DdMgf=UdyD!Z zYC_+~0oMt?$l-X`x6kU-rD;cijQw%X1r1?vRkU(6R5mg)^#y-4rSGkt!^}*8mtB=E z+d@W{m4ZNoknd?H2NMFa5#8!GL-5W#hWkk(N@NY@;~13u;S(ACScZ~b2|{dSId3~g zatHCrqn<#FtRtjjmG~rq=EuDEkBj2yn}iJPSH34s+D(^RO;)m45SlVV33ud>4WxCa z>|S+O#xiNCw`L>QEKdpSpM)w-wv04`#u2KFtfF31_rz{q{>IRi%7aLiiGj#i^MDxf zcv=AE-+H(`!rqNse8(*4v+ZM@9B~*bT41eE;BzubMa1cNvMK&4ALUZe`%<2Oe~n#f zj#c?jTnseXn#^}>=d3%MUUfe_b{Ls>_vN>q=6{zcx#QPRCLSxYN5eG{?+dH70lMc9 zZjSlO&2IJw+*Lw3@!{iacPzcz3=H))?+*`u+_n^id?_2aJZaXQ41PAcUnfxT`fk2# z^Z4U%cUrBmNlg0ew;!fWH<9;o?(KADr+2c!zU1-LXByZ|t#3$-ATyi~tBl>buK*34_Vhi!ADfA{-`Dfr6J;?BdsVvoD$?`~qzX3p_Q|2@JtROsjGKh=YzctQL4 zfJ&RTV%|SVwe(qX^2xSI8#G{1|6`&@go-0Q-lv1=jST|;)_z}!eJ>=){sm^lLhWC8 zV3rf5$)AVUEVUz+UtazU``xjhC8Z&5*g<_$t9$_)+iYuR72JOZqNSk+kv?xO;aq&MTp|T_4NSzgs@dZ54lA)(NlNH zn92c-`3*DZWqZ2@=EU^%m`Ue_W9UkSUw%(Is=ft$6^9@4yx&)46DB!ldfurs@md?IMQV0i@5r5GM&<7=8mE}tvT^EYynS-CbwTM zxHMBFV+@UHM$bt6kedr#QQyyP=QU9S1`C))YNK#|BSLBI>OjkewiwDP1RPTj0x=WQ z1BfndjUnzQ(0>BG)|d3y2OidXKXK4ll=$-mOT%$G*yGlh)_-})aQnnPYfVp8#t&xR zMH%ht64ulzuME0it4V}$Ijmx21dk%lDYKZ0&c#0+gQ_y3^`v#djW?g_+1ON)w7qN1W+?t~#%#v$Jy)LSAy%kzoYB&^3DbyABpc@8KK1`^n% zgpZaN@5NfQ%3mS)bZC_r>2Gm>b>aSwG17_$6w?158~|-5X>kpX|D=+_W?v}}$aLJ{ zQIBY!EW}C`ntDsWSPOw?UseD4=Oj$*DF*@ySS57L#lF>;mJ7FM_hH-V>S4|u>8#f> zn=w2M#+QL~31xE$;&qt2maCFt?~?a-MfXPF)UZvu*X8!`pH@LZ?9h!l9qU=cBD&0_ zXtj)4a5TeKK{76`h6nSYdaKKHy9X|CvknE?r$K!bQSLPyckMJLyPGx&hj*a8m^ZPfR?TboUvNm*;?!c%o%Dg!{I#rHdyUiWY3TTr+X9yIc3*KTr zJ&Hr_@rFx%OW9|G^Td7}B80mF>?2}%;dURzyuA1U{-CPdU2*hFzo!lLuRh04z${CZ zqri(2QhHe*e+!7JsdC?%{=LT;&I2VOFyVl=@g1}RyS7e@Gf|)P?!qpROF4{_uBv$m zOdu0x>3Js3Fb{Q01m_2BT;ObEZflD*kcR3_#JXUj9$vS$v=j*>=F2p1!>eX)wOLj7 z)BFrCW2KEZmqGamXlwd|F0D%Ff7Ge807c#truXuS{Va9!T*5rKy&1G&U-0ux_~*UE z$l4kk8+$kGX<15s0&w$$xeYCoD4^&}EiY%rR>M8EsWH{WFJ%AP7Y7zEJVgkqr94|T z{0Hw!<$Ay|sIRa8X^~!17>v&*6BT__0q()?H9aK*hvdMM=S=nfZUrJxcHwzURTc&e z_{!u_ZSFV*&vLO?M!*FIX3^H4jAC5nYi@d|9ig;g^#vd%179AY@BB9FJ67=1TAm?X zZK6K-TtE=5m{v~9k3Y_)V>88;?nKB8gbVw>$!Bb~n9}u8m&JFluTuf@nS`0-fWOy+ zhV>t`vy2TF$gAGHvZ$}&|6cI@I~stEf5!^^?_0B)bl^-($y_;^J@G`i?PKcLr@a6j zt;?9pBy;>2n57M9#+zAoa^Y@!0V5Y#2ijq}kE3uJ`z}ulfod~kR$SDfP^2krlU?z` zO5xjcQLZILL*RBGqNB4Cv8Y|iU`j6hXUu`B^y0i1^hSU+5?D@Ia@>C)$+fD+?N2Qz z90z=98YH2}Kk6sMVbP(nd#4=J_bax%o?c!+Q@8%lN!gPU9#GGb22WXN+1wB8gki*- z$&@{g_z(1?P7u@yp29N1r-!0XoZE)r&7e&5X~c--bJF4!@FbR1R${xYdYH`|wNrpV zZM^AJ!Vi2$9Pp#~LZB*zl}%zmsftGCDI{KMsLcq z{>1&0e1{qePtP<2U|_+UH26{><2Rnc-~wXgT#yj~RPwchV0^c}-+#p#vy%5uzQtkA z)Frx`uT@K#D#Xe{=sbWm5IL4)Jhir7+0%dflf#8yh)GLJ4@5|W_Qu5}pMo(&td{A^ zi|gT1&BH)Q(X;3VC?g;-{Mykkd-yZWOoCj!HVW4-*B4)r0-wkR)E@{0Xz@OEU%l-{ zE0JM&fvgbG@A zj@6DPJ5X4VI`*Y$N7;LD`Q+;wQ>#2BA5BdMxb zG(|d03S5=R|3y2^Si3`ZadCORi;N0cyPj~%^Fi57uLh*b_ZAk6K$kUkPf;}(xM(AT zeAW(VWe|dahl2p&QpRXw7x#zj9S2~$X7(Eo1@wWzvTC}R)7t8AWqqv*Sf{$RUQan` z5ai7+Escsc(&V(TKo;RTsm8Cd@o|%bfG)q5@weDXJ2+PI-!vniM#C}MN7$Av(HV5!tv$G3bu~l#(DV6xf=3XYOy5HwX_aiue#ddNY zYWy_qakP2kmGN-G@Ub!5*D9nCP1Dg1SB#0c)GJccoSJRDu&O7T#(yt$M#mtVy6*~b z5FgW=oP{;l>({sFP)Yb$lL&+QVTG5L&Q zFvNXDM`!kVQ3^>Gk5;~Ug(u=&wK%$@UZZN6#)PN(fByx5aU-PE8JFB^J{{b0obPs>fXlwrWUZn`8 zHL2RZ8m^%r9_25Tlxmi5IS$C+icce|(uxpHw*CLtn_%7}vmlXSM~A0wc`LfOE(_;B zb%0Nn7}80yr%@us=4Y(^{|2N+>2;Ojs-zPdL3pY8t%@uhp}Pa!OKojw)Nyr2c;;j| z!f?j_8Ez_73|*CzC8;!KB_dfHJt;=2obT{wX_IfOH)R%H;i*_Ul@w#f{@/control` and fill the request message type +`gz.msgs.WorldControl`. This service returns a `gz.msgs.Boolean` with the status of the request (true means everything was fine, false otherwise). + +The `WorldControl` message contains a `pause` field for starting and stopping the simulation. + +To start the simulation: + +```bash +gz service -s /world/default/control --reqtype gz.msgs.WorldControl --reptype gz.msgs.Boolean --timeout 3000 --req 'pause: false' +``` + +To pause the simulation: + +```bash +gz service -s /world/default/control --reqtype gz.msgs.WorldControl --reptype gz.msgs.Boolean --timeout 3000 --req 'pause: true' +``` + +When paused, time will stop in Gazebo, and the physics will not be running. + +To check the current state of the simulator, check the `paused` field in `/stats` like so: +```bash +gz topic --echo --topic /stats -n 1 +``` +If the simulator is currently paused but was running before, we would see something similar to this: +```text +sim_time { + sec: 8 + nsec: 707000000 +} +real_time { + sec: 8 + nsec: 824323281 +} +iterations: 8707 +real_time_factor: 0.998022916602211 +``` + + +## GUI + +We included a button in the `World Control` plugin allowing to start and stop the simulation from the GUI. + +@image html files/pause_run_simulation/gui_pause_run.png diff --git a/tutorials/reset_simulation.md b/tutorials/reset_simulation.md index 7a62a3fa3d..bf8ae121ab 100644 --- a/tutorials/reset_simulation.md +++ b/tutorials/reset_simulation.md @@ -4,6 +4,11 @@ The Reset Gazebo transport API is exposed to allow resetting simulation to time It's possible to call this API using the command line or through the GUI. In addition to the API, we have also expanded the simulation system API with a Reset interface. +To repeat this demo, run the `rolling_shapes.sdf` file: +```bash +gz sim rolling_shapes.sdf +``` + ## Reset interface System authors may now choose to implement the Reset interface to have a more intelligent @@ -16,7 +21,7 @@ Follow the tutorial \subpage createsystemplugins to see how to support Reset by ## Transport API To invoke reset over transport API, we should call the service `/world//control` and fill the request message type -`gz.msgs.WorldControl`. This service returns a `gz.msgs.Boolean` with the status of the reset (true means everything was fine, false otherwise) +`gz.msgs.WorldControl`. This service returns a `gz.msgs.Boolean` with the status of the reset (true means everything was fine, false otherwise). The `WorldControl` message now contains a `reset` field for resetting the world: From f024ea83dd26d3711976544a835b74d030cccdb0 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Wed, 12 Jun 2024 17:29:16 -0700 Subject: [PATCH 06/21] Prepare for 8.4.0 release (#2442) Signed-off-by: Ian Chen --- CMakeLists.txt | 2 +- Changelog.md | 77 ++++++++++++++++++++++++++++++++++++++++++++++++++ package.xml | 2 +- 3 files changed, 79 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4d8ff41d68..30236494c0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) #============================================================================ # Initialize the project #============================================================================ -project(gz-sim8 VERSION 8.3.0) +project(gz-sim8 VERSION 8.4.0) set (GZ_DISTRIBUTION "Harmonic") #============================================================================ diff --git a/Changelog.md b/Changelog.md index cb821fd2cc..b6d5dc3c2b 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,5 +1,82 @@ ## Gazebo Sim 8.x +### Gazebo Sim 8.4.0 (2024-06-12) + +1. Add pause run tutorial + * [Pull request #2383](https://github.com/gazebosim/gz-sim/pull/2383) + +1. Fix warning message to show precise jump back in time duration + * [Pull request #2435](https://github.com/gazebosim/gz-sim/pull/2435) + +1. Optimize rendering sensor pose updates + * [Pull request #2425](https://github.com/gazebosim/gz-sim/pull/2425) + +1. Remove a few extra zeros from some sdf files + * [Pull request #2426](https://github.com/gazebosim/gz-sim/pull/2426) + +1. Use VERSION_GREATER_EQUAL in cmake logic + * [Pull request #2418](https://github.com/gazebosim/gz-sim/pull/2418) + +1. Support mesh optimization when using AttachMeshShapeFeature + * [Pull request #2417](https://github.com/gazebosim/gz-sim/pull/2417) + +1. Rephrase cmake comment about CMP0077 + * [Pull request #2419](https://github.com/gazebosim/gz-sim/pull/2419) + +1. Fix CMake warnings in Noble + * [Pull request #2397](https://github.com/gazebosim/gz-sim/pull/2397) + +1. Update sensors with pending trigger immediately in Sensors system + * [Pull request #2408](https://github.com/gazebosim/gz-sim/pull/2408) + +1. Add missing algorithm include + * [Pull request #2414](https://github.com/gazebosim/gz-sim/pull/2414) + +1. Add Track and Follow options in gui EntityContextMenu + * [Pull request #2402](https://github.com/gazebosim/gz-sim/pull/2402) + +1. ForceTorque system: improve readability + * [Pull request #2403](https://github.com/gazebosim/gz-sim/pull/2403) + +1. LTA Dynamics System + * [Pull request #2241](https://github.com/gazebosim/gz-sim/pull/2241) + +1. Remove Empty Test File + * [Pull request #2396](https://github.com/gazebosim/gz-sim/pull/2396) + +1. Fix GCC/CMake warnings for Noble + * [Pull request #2375](https://github.com/gazebosim/gz-sim/pull/2375) + +1. Fix warn unused variable in test + * [Pull request #2388](https://github.com/gazebosim/gz-sim/pull/2388) + +1. Fix name of gz-fuel_tools in package.xml + * [Pull request #2386](https://github.com/gazebosim/gz-sim/pull/2386) + +1. Add package.xml + * [Pull request #2337](https://github.com/gazebosim/gz-sim/pull/2337) + +1. Fix namespace and class links in documentation references that use namespace `gz` + * [Pull request #2385](https://github.com/gazebosim/gz-sim/pull/2385) + +1. Fix ModelPhotoShootTest test failures + * [Pull request #2294](https://github.com/gazebosim/gz-sim/pull/2294) + +1. Enable StoreResolvedURIs when loading SDF + * [Pull request #2349](https://github.com/gazebosim/gz-sim/pull/2349) + +1. Drop python3-disttutils from apt packages files + * [Pull request #2374](https://github.com/gazebosim/gz-sim/pull/2374) + +1. Added example world for `DopplerVelocityLogSystem` + * [Pull request #2373](https://github.com/gazebosim/gz-sim/pull/2373) + +1. Fix Gazebo/White and refactored MaterialParser + * [Pull request #2302](https://github.com/gazebosim/gz-sim/pull/2302) + +1. Support for Gazebo materials + * [Pull request #2269](https://github.com/gazebosim/gz-sim/pull/2269) + ### Gazebo Sim 8.3.0 (2024-04-11) 1. Use relative install paths for plugin shared libraries and gz-tools data diff --git a/package.xml b/package.xml index 49abe1f7aa..09ca32a77e 100644 --- a/package.xml +++ b/package.xml @@ -2,7 +2,7 @@ gz-sim8 - 8.3.0 + 8.4.0 Gazebo Sim : A Robotic Simulator Michael Carroll Apache License 2.0 From 45239e9e12077ade60bd01078e7ce92acf353889 Mon Sep 17 00:00:00 2001 From: AzulRadio <50132891+AzulRadio@users.noreply.github.com> Date: Thu, 13 Jun 2024 02:32:15 -0500 Subject: [PATCH 07/21] Add support for no gravity link (#2398) Signed-off-by: youhy Signed-off-by: Ian Chen Co-authored-by: Ian Chen --- src/SdfEntityCreator.cc | 8 ++++++++ src/systems/physics/Physics.cc | 18 ++++++++++++++++++ 2 files changed, 26 insertions(+) diff --git a/src/SdfEntityCreator.cc b/src/SdfEntityCreator.cc index 6947ff329c..a84343fd42 100644 --- a/src/SdfEntityCreator.cc +++ b/src/SdfEntityCreator.cc @@ -588,6 +588,14 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Link *_link) linkEntity, components::WindMode(_link->EnableWind())); } + if (!_link->EnableGravity()) + { + // If disable gravity, create a gravity component to the entity + // This gravity will have value 0,0,0 + this->dataPtr->ecm->CreateComponent( + linkEntity, components::Gravity()); + } + // Visuals for (uint64_t visualIndex = 0; visualIndex < _link->VisualCount(); ++visualIndex) diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index 544f16d54e..c61279205f 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -1160,6 +1160,24 @@ void PhysicsPrivate::CreateLinkEntities(const EntityComponentManager &_ecm) link.SetInertial(inertial->Data()); } + // get link gravity + const components::Gravity *gravity = + _ecm.Component(_entity); + if (nullptr != gravity) + { + // Entity has a gravity component that is all zeros when + // is set to false + // See SdfEntityCreator::CreateEntities() + if (gravity->Data() == math::Vector3d::Zero) + { + link.SetEnableGravity(false); + } + else + { + link.SetEnableGravity(true); + } + } + auto linkPtrPhys = modelPtrPhys->ConstructLink(link); this->entityLinkMap.AddEntity(_entity, linkPtrPhys); this->topLevelModelMap.insert(std::make_pair(_entity, From 2297be704cdc151205c195d6d1e3b84c79192e27 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 14 Jun 2024 15:52:34 -0700 Subject: [PATCH 08/21] Do not update sensors if it a triggered sensor (#2443) Signed-off-by: Ian Chen --- CMakeLists.txt | 2 +- src/systems/sensors/Sensors.cc | 5 +++++ 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 30236494c0..e6c3f77eac 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -136,7 +136,7 @@ set(GZ_PHYSICS_VER ${gz-physics7_VERSION_MAJOR}) #-------------------------------------- # Find gz-sensors -gz_find_package(gz-sensors8 REQUIRED +gz_find_package(gz-sensors8 REQUIRED VERSION 8.2.0 # component order is important COMPONENTS # non-rendering diff --git a/src/systems/sensors/Sensors.cc b/src/systems/sensors/Sensors.cc index 84769ca3f2..601a4b3c9d 100644 --- a/src/systems/sensors/Sensors.cc +++ b/src/systems/sensors/Sensors.cc @@ -1034,6 +1034,11 @@ std::chrono::steady_clock::duration SensorsPrivate::NextUpdateTime( continue; } + if (rs->IsTriggered()) + { + continue; + } + std::chrono::steady_clock::duration time; // if sensor's next update tims is less or equal to current sim time then // it's in the process of being updated by the render loop From 4fde8523ad90add3c59244e0224fe0bb8118c768 Mon Sep 17 00:00:00 2001 From: Mabel Zhang Date: Fri, 14 Jun 2024 18:59:44 -0400 Subject: [PATCH 09/21] Add tutorial for using the Pose component (#2219) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Adds a tutorial on how to use the Pose component, using OdometryPublisher system as an example, because that system depends on only 1 component, good as a standalone example. --------- Signed-off-by: Addisu Z. Taddese Signed-off-by: Mabel Zhang Signed-off-by: Ian Chen Signed-off-by: Mabel Zhang Co-authored-by: Addisu Z. Taddese Co-authored-by: Ian Chen Co-authored-by: Alejandro Hernández Cordero --- .../odometry_publisher/OdometryPublisher.cc | 23 +++--- .../odometry_publisher/OdometryPublisher.hh | 7 ++ tutorials/component_pose.md | 80 +++++++++++++++++++ tutorials/using_components.md | 1 + 4 files changed, 102 insertions(+), 9 deletions(-) create mode 100644 tutorials/component_pose.md diff --git a/src/systems/odometry_publisher/OdometryPublisher.cc b/src/systems/odometry_publisher/OdometryPublisher.cc index c2fff130f8..fe5270ebe2 100644 --- a/src/systems/odometry_publisher/OdometryPublisher.cc +++ b/src/systems/odometry_publisher/OdometryPublisher.cc @@ -59,7 +59,9 @@ class gz::sim::systems::OdometryPublisherPrivate public: transport::Node node; /// \brief Model interface + //! [modelDeclaration] public: Model model{kNullEntity}; + //! [modelDeclaration] /// \brief Name of the world-fixed coordinate frame for the odometry message. public: std::string odomFrame; @@ -133,12 +135,14 @@ OdometryPublisher::OdometryPublisher() } ////////////////////////////////////////////////// +//! [Configure] void OdometryPublisher::Configure(const Entity &_entity, const std::shared_ptr &_sdf, EntityComponentManager &_ecm, EventManager &/*_eventMgr*/) { this->dataPtr->model = Model(_entity); + //! [Configure] if (!this->dataPtr->model.Valid(_ecm)) { @@ -233,8 +237,10 @@ void OdometryPublisher::Configure(const Entity &_entity, } else { + //! [definePub] this->dataPtr->odomPub = this->dataPtr->node.Advertise( odomTopicValid); + //! [definePub] gzmsg << "OdometryPublisher publishing odometry on [" << odomTopicValid << "]" << std::endl; } @@ -300,15 +306,6 @@ void OdometryPublisher::PreUpdate(const gz::sim::UpdateInfo &_info, << std::chrono::duration(_info.dt).count() << "s]. System may not work properly." << std::endl; } - - // Create the pose component if it does not exist. - auto pos = _ecm.Component( - this->dataPtr->model.Entity()); - if (!pos) - { - _ecm.CreateComponent(this->dataPtr->model.Entity(), - components::Pose()); - } } ////////////////////////////////////////////////// @@ -347,7 +344,9 @@ void OdometryPublisherPrivate::UpdateOdometry( } // Construct the odometry message and publish it. + //! [declarePoseMsg] msgs::Odometry msg; + //! [declarePoseMsg] const std::chrono::duration dt = std::chrono::steady_clock::time_point(_info.simTime) - lastUpdateTime; @@ -357,7 +356,10 @@ void OdometryPublisherPrivate::UpdateOdometry( return; // Get and set robotBaseFrame to odom transformation. + //! [worldPose] const math::Pose3d rawPose = worldPose(this->model.Entity(), _ecm); + //! [worldPose] + //! [setPoseMsg] math::Pose3d pose = rawPose * this->offset; msg.mutable_pose()->mutable_position()->set_x(pose.Pos().X()); msg.mutable_pose()->mutable_position()->set_y(pose.Pos().Y()); @@ -366,6 +368,7 @@ void OdometryPublisherPrivate::UpdateOdometry( { msg.mutable_pose()->mutable_position()->set_z(pose.Pos().Z()); } + //! [setPoseMsg] // Get linear and angular displacements from last updated pose. double linearDisplacementX = pose.Pos().X() - this->lastUpdatePose.Pos().X(); @@ -476,7 +479,9 @@ void OdometryPublisherPrivate::UpdateOdometry( this->lastOdomPubTime = _info.simTime; if (this->odomPub.Valid()) { + //! [publishMsg] this->odomPub.Publish(msg); + //! [publishMsg] } // Generate odometry with covariance message and publish it. diff --git a/src/systems/odometry_publisher/OdometryPublisher.hh b/src/systems/odometry_publisher/OdometryPublisher.hh index cab9bd6d14..33c8fd23af 100644 --- a/src/systems/odometry_publisher/OdometryPublisher.hh +++ b/src/systems/odometry_publisher/OdometryPublisher.hh @@ -76,6 +76,13 @@ namespace systems /// - ``: Standard deviation of the Gaussian noise to be added /// to pose and twist messages. This element is optional, and the default /// value is 0. + /// + /// ## Components + /// + /// This system uses the following components: + /// + /// - gz::sim::components::Pose: Pose represented by gz::math::Pose3d. Used + /// to calculate the odometry to publish. class OdometryPublisher : public System, public ISystemConfigure, diff --git a/tutorials/component_pose.md b/tutorials/component_pose.md new file mode 100644 index 0000000000..34d440e12e --- /dev/null +++ b/tutorials/component_pose.md @@ -0,0 +1,80 @@ +\page posecomponent Case Study: Using the Pose Component + +We will show how to use the gz::sim::components::Pose component in a system. + +An example usage of the component can be found in the +gz::sim::systems::OdometryPublisher system +([source code](https://github.com/gazebosim/gz-sim/tree/gz-sim8/src/systems/odometry_publisher)), +which reads the pose component of a model through the Model entity, uses the +pose for some calculations, and then publishes the result as a message. + +More usage can be found in the +[integration test](https://github.com/gazebosim/gz-sim/blob/gz-sim8/test/integration/odometry_publisher.cc) +for the system, with test worlds `odometry*.sdf` +[here](https://github.com/gazebosim/gz-sim/tree/main/test/worlds). + +### Objects of interest + +- gz::sim::components::Pose: A component containing pose information +- gz::math::Pose3d: The actual data underlying a pose component +- gz::sim::systems::OdometryPublisher: A system that reads the pose component + of a model +- gz::sim::Model: The type underlying a model entity (gz::sim::Entity) + +### Find the model entity + +First, we will need access to an entity, the \ref gz::sim::Model entity in this +case. +`OdometryPublisher` happens to be a system meant to be specified under `` +in the SDF, so at the time `Configure()` is called, it has access to a model +entity from which we can extract a \ref gz::sim::Model: + +\snippet src/systems/odometry_publisher/OdometryPublisher.cc modelDeclaration +\snippet src/systems/odometry_publisher/OdometryPublisher.cc Configure + +### Read the pose component + +Once we have the handle to an entity, we can access components associated with +it. +A component may have been created at the time the world is loaded, or you may +create a component at runtime if it does not exist yet. + +In this case, we use the model entity found above to access its pose component, +which is created by default on every model entity. + +In `PostUpdate()`, which happens after physics has updated, we can get the +world pose of a model through gz::sim::worldPose, by passing in the model +entity and the entity component manager. + +\snippet src/systems/odometry_publisher/OdometryPublisher.cc worldPose + +It returns the raw data to us in the gz::math::Pose3d type, which is also the +data type underlying a pose component. +We can perform calculations on the gz::math::Pose3d type, not the +gz::sim::components::Pose type, which is just a wrapper. + +### Use the pose component + +Now we can use the pose data as we like. + +Here, we manipulate the pose and package the result into a gz::msgs::Odometry +message to be published: + +\snippet src/systems/odometry_publisher/OdometryPublisher.cc declarePoseMsg + +\snippet src/systems/odometry_publisher/OdometryPublisher.cc setPoseMsg + +See the source code for setting other fields of the message, such as twist and +the header. + +The message is then published: + +\snippet src/systems/odometry_publisher/OdometryPublisher.cc publishMsg + +where `odomPub` is defined in `Configure()`: + +\snippet src/systems/odometry_publisher/OdometryPublisher.cc definePub + +Outside the scope of this tutorial, the odometry publisher system also +calculates the covariance and publishes a pose vector on a TF topic. +See the source code to learn more. diff --git a/tutorials/using_components.md b/tutorials/using_components.md index 717beea566..1c91d47e46 100644 --- a/tutorials/using_components.md +++ b/tutorials/using_components.md @@ -72,3 +72,4 @@ The rest of the tutorial is case studies that walk through the usage of specific components. - \subpage jointforcecmdcomponent "JointForceCmd" +- \subpage posecomponent "Pose" From ed2b64ca00fee8be4fa4cd7dddc2b56445bd24dc Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 14 Jun 2024 17:26:55 -0700 Subject: [PATCH 10/21] Fix model command api test (#2444) Signed-off-by: Ian Chen --- src/ModelCommandAPI_TEST.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/ModelCommandAPI_TEST.cc b/src/ModelCommandAPI_TEST.cc index 95f5b8b4a4..a277c1e831 100644 --- a/src/ModelCommandAPI_TEST.cc +++ b/src/ModelCommandAPI_TEST.cc @@ -657,7 +657,7 @@ TEST(ModelCommandAPI, GZ_UTILS_TEST_DISABLED_ON_MAC(RgbdCameraSensor)) " - Lens intrinsics Fy: 277\n" " - Lens intrinsics Cx: 160\n" " - Lens intrinsics Cy: 120\n" - " - Lens intrinsics skew: 1\n" + " - Lens intrinsics skew: 0\n" " - Visibility mask: 4294967295\n"; EXPECT_EQ(expectedOutput, output); } From cd9a855ae6066ba1f0cad8d43ef13151a2941c72 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Mon, 17 Jun 2024 13:27:43 -0700 Subject: [PATCH 11/21] Parse voxel resolution SDF param when decomposing meshes (#2445) Signed-off-by: Ian Chen --- src/Util.cc | 18 +++++++++++------- 1 file changed, 11 insertions(+), 7 deletions(-) diff --git a/src/Util.cc b/src/Util.cc index e9cb2406f0..c73ac54dbc 100644 --- a/src/Util.cc +++ b/src/Util.cc @@ -891,20 +891,24 @@ const common::Mesh *optimizeMesh(const sdf::Mesh &_meshSdf, auto &meshManager = *common::MeshManager::Instance(); std::size_t maxConvexHulls = 16u; + std::size_t voxelResolution = 200000u; + if (_meshSdf.ConvexDecomposition()) + { + // limit max number of convex hulls to generate + maxConvexHulls = _meshSdf.ConvexDecomposition()->MaxConvexHulls(); + voxelResolution = _meshSdf.ConvexDecomposition()->VoxelResolution(); + } if (_meshSdf.Optimization() == sdf::MeshOptimization::CONVEX_HULL) { /// create 1 convex hull for the whole submesh maxConvexHulls = 1u; } - else if (_meshSdf.ConvexDecomposition()) - { - // limit max number of convex hulls to generate - maxConvexHulls = _meshSdf.ConvexDecomposition()->MaxConvexHulls(); - } + // Check if MeshManager contains the decomposed mesh already. If not // add it to the MeshManager so we do not need to decompose it again. const std::string convexMeshName = - _mesh.Name() + "_CONVEX_" + std::to_string(maxConvexHulls); + _mesh.Name() + "_" + _meshSdf.Submesh() + "_CONVEX_" + + std::to_string(maxConvexHulls) + "_" + std::to_string(voxelResolution); auto *optimizedMesh = meshManager.MeshByName(convexMeshName); if (!optimizedMesh) { @@ -916,7 +920,7 @@ const common::Mesh *optimizeMesh(const sdf::Mesh &_meshSdf, auto mergedSubmesh = mergedMesh->SubMeshByIndex(0u).lock(); std::vector decomposed = gz::common::MeshManager::ConvexDecomposition( - *mergedSubmesh.get(), maxConvexHulls); + *mergedSubmesh.get(), maxConvexHulls, voxelResolution); gzdbg << "Optimizing mesh (" << _meshSdf.OptimizationStr() << "): " << _mesh.Name() << std::endl; // Create decomposed mesh and add it to MeshManager From ca1b62602e282a905c4373da09128a10720d74e1 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Tue, 25 Jun 2024 19:35:56 -0700 Subject: [PATCH 12/21] Add GravityEnabled boolean component (#2451) This adds a boolean GravityEnabled component to the existing gz/sim/components/Gravity.hh header file, which should be used with Link entities instead of the Vector3 gravity component. --------- Signed-off-by: Steve Peters Signed-off-by: youhy Co-authored-by: youhy --- include/gz/sim/components/Gravity.hh | 5 +++++ src/SdfEntityCreator.cc | 5 ++--- src/systems/physics/Physics.cc | 21 ++++++--------------- 3 files changed, 13 insertions(+), 18 deletions(-) diff --git a/include/gz/sim/components/Gravity.hh b/include/gz/sim/components/Gravity.hh index fe3cf88a9f..713e797acf 100644 --- a/include/gz/sim/components/Gravity.hh +++ b/include/gz/sim/components/Gravity.hh @@ -36,6 +36,11 @@ namespace components /// \brief Store the gravity acceleration. using Gravity = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Gravity", Gravity) + + /// \brief Store the gravity acceleration. + using GravityEnabled = Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.GravityEnabled", GravityEnabled) } } } diff --git a/src/SdfEntityCreator.cc b/src/SdfEntityCreator.cc index a84343fd42..71c295db9b 100644 --- a/src/SdfEntityCreator.cc +++ b/src/SdfEntityCreator.cc @@ -590,10 +590,9 @@ Entity SdfEntityCreator::CreateEntities(const sdf::Link *_link) if (!_link->EnableGravity()) { - // If disable gravity, create a gravity component to the entity - // This gravity will have value 0,0,0 + // If disable gravity, create a GravityEnabled component to the entity this->dataPtr->ecm->CreateComponent( - linkEntity, components::Gravity()); + linkEntity, components::GravityEnabled(false)); } // Visuals diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index c61279205f..687178a369 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -1161,21 +1161,12 @@ void PhysicsPrivate::CreateLinkEntities(const EntityComponentManager &_ecm) } // get link gravity - const components::Gravity *gravity = - _ecm.Component(_entity); - if (nullptr != gravity) - { - // Entity has a gravity component that is all zeros when - // is set to false - // See SdfEntityCreator::CreateEntities() - if (gravity->Data() == math::Vector3d::Zero) - { - link.SetEnableGravity(false); - } - else - { - link.SetEnableGravity(true); - } + const components::GravityEnabled *gravityEnabled = + _ecm.Component(_entity); + if (nullptr != gravityEnabled) + { + // gravityEnabled set in SdfEntityCreator::CreateEntities() + link.SetEnableGravity(gravityEnabled->Data()); } auto linkPtrPhys = modelPtrPhys->ConstructLink(link); From 04a5e0da8d699695ea9637ad9cfea6ca8047026b Mon Sep 17 00:00:00 2001 From: Silvio Traversaro Date: Wed, 26 Jun 2024 06:08:43 +0200 Subject: [PATCH 13/21] Permit to run gz sim -g on Windows (#2382) Signed-off-by: Silvio Traversaro Co-authored-by: mergify[bot] <37929162+mergify[bot]@users.noreply.github.com> --- src/cmd/cmdsim.rb.in | 6 ------ 1 file changed, 6 deletions(-) diff --git a/src/cmd/cmdsim.rb.in b/src/cmd/cmdsim.rb.in index 64ee638c7b..65946d3494 100755 --- a/src/cmd/cmdsim.rb.in +++ b/src/cmd/cmdsim.rb.in @@ -598,12 +598,6 @@ See https://github.com/gazebosim/gz-sim/issues/168 for more info." options['record-period'], options['seed']) # Otherwise run the gui else options['gui'] - if plugin.end_with? ".dll" - puts "`gz sim` currently only works with the -s argument on Windows. -See https://github.com/gazebosim/gz-sim/issues/168 for more info." - exit(-1) - end - ENV['RMT_PORT'] = '1501' Importer.runGui(options['gui_config'], options['file'], options['wait_gui'], options['render_engine_gui'], From 26d425bcd3a7fcc29f5199c5790b47bc3241217f Mon Sep 17 00:00:00 2001 From: Benjamin Perseghetti Date: Wed, 26 Jun 2024 13:26:18 -0400 Subject: [PATCH 14/21] Backport: Adding cone primitives (#2404) Signed-off-by: Benjamin Perseghetti --- examples/worlds/shapes.sdf | 48 +++++++++++++++--- include/gz/sim/Primitives.hh | 5 +- src/Conversions.cc | 18 +++++++ src/Primitives.cc | 48 ++++++++++++++++++ .../ComponentInspectorEditor.qml | 8 +++ .../component_inspector_editor/ModelEditor.cc | 9 ++++ src/gui/plugins/entity_tree/EntityTree.qml | 9 ++++ src/gui/plugins/shapes/Shapes.qml | 17 +++++++ src/gui/plugins/shapes/Shapes.qrc | 1 + src/gui/plugins/shapes/cone.png | Bin 0 -> 5605 bytes .../VisualizationCapabilities.cc | 8 +++ src/rendering/MarkerManager.cc | 2 + src/rendering/SceneManager.cc | 8 +++ src/systems/physics/Physics.cc | 1 + src/systems/physics/Physics.hh | 1 + 15 files changed, 173 insertions(+), 10 deletions(-) create mode 100644 src/gui/plugins/shapes/cone.png diff --git a/examples/worlds/shapes.sdf b/examples/worlds/shapes.sdf index 1d75661b49..5d020a8c32 100644 --- a/examples/worlds/shapes.sdf +++ b/examples/worlds/shapes.sdf @@ -1,12 +1,13 @@ - - + + + 1.0 1.0 1.0 @@ -240,5 +241,36 @@ Try moving a model: + + + 0 4.5 0.5 0 0 0 + + + 1 + + + + + 0.5 + 1.0 + + + + + + + + 0.5 + 1.0 + + + + 1 0.47 0 1 + 1 0.47 0 1 + 1 0.47 0 1 + + + + diff --git a/include/gz/sim/Primitives.hh b/include/gz/sim/Primitives.hh index 84bc8344f5..b90b9e7553 100644 --- a/include/gz/sim/Primitives.hh +++ b/include/gz/sim/Primitives.hh @@ -35,6 +35,7 @@ namespace gz { kBox, kCapsule, + kCone, kCylinder, kEllipsoid, kSphere, @@ -67,8 +68,8 @@ namespace gz /// \brief Return an SDF string of one of the available primitive shape or /// light types. /// \param[in] _typeName Type name of the of shape or light to retrieve. - /// Must be one of: box, sphere, cylinder, capsule, ellipsoid, directional, - /// point, or spot. + /// Must be one of: box, sphere, cylinder, cone, capsule, ellipsoid, + /// directional, point, or spot. /// \return String containing SDF description of primitive shape or light. /// Empty string if the _typeName is invalid. std::string GZ_SIM_VISIBLE diff --git a/src/Conversions.cc b/src/Conversions.cc index fbe7587141..e10e0d1184 100644 --- a/src/Conversions.cc +++ b/src/Conversions.cc @@ -20,6 +20,7 @@ #include #include #include +#include #include #include #include @@ -53,6 +54,7 @@ #include #include #include +#include #include #include #include @@ -176,6 +178,12 @@ msgs::Geometry gz::sim::convert(const sdf::Geometry &_in) out.mutable_capsule()->set_radius(_in.CapsuleShape()->Radius()); out.mutable_capsule()->set_length(_in.CapsuleShape()->Length()); } + else if (_in.Type() == sdf::GeometryType::CONE && _in.ConeShape()) + { + out.set_type(msgs::Geometry::CONE); + out.mutable_cone()->set_radius(_in.ConeShape()->Radius()); + out.mutable_cone()->set_length(_in.ConeShape()->Length()); + } else if (_in.Type() == sdf::GeometryType::CYLINDER && _in.CylinderShape()) { out.set_type(msgs::Geometry::CYLINDER); @@ -293,6 +301,16 @@ sdf::Geometry gz::sim::convert(const msgs::Geometry &_in) out.SetCapsuleShape(capsuleShape); } + else if (_in.type() == msgs::Geometry::CONE && _in.has_cone()) + { + out.SetType(sdf::GeometryType::CONE); + + sdf::Cone coneShape; + coneShape.SetRadius(_in.cone().radius()); + coneShape.SetLength(_in.cone().length()); + + out.SetConeShape(coneShape); + } else if (_in.type() == msgs::Geometry::CYLINDER && _in.has_cylinder()) { out.SetType(sdf::GeometryType::CYLINDER); diff --git a/src/Primitives.cc b/src/Primitives.cc index 4fa93cea54..fcb7f65942 100644 --- a/src/Primitives.cc +++ b/src/Primitives.cc @@ -104,6 +104,49 @@ constexpr const char * kSphereSdf = R"( )"; +///////////////////////////////////////////////// +constexpr const char * kConeSdf = R"( + + + 0 0 0.5 0 0 0 + + + + 0.075 + 0 + 0 + 0.075 + 0 + 0.075 + + 1.0 + + + + + 0.5 + 1.0 + + + + + + + 0.5 + 1.0 + + + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 1 1 1 1 + + + + + +)"; + ///////////////////////////////////////////////// constexpr const char * kCylinderSdf = R"( @@ -301,6 +344,8 @@ std::string gz::sim::getPrimitiveShape(const PrimitiveShape &_type) return kBoxSdf; case PrimitiveShape::kSphere: return kSphereSdf; + case PrimitiveShape::kCone: + return kConeSdf; case PrimitiveShape::kCylinder: return kCylinderSdf; case PrimitiveShape::kCapsule: @@ -339,6 +384,8 @@ std::string gz::sim::getPrimitive(const std::string &_typeName) return getPrimitiveShape(PrimitiveShape::kSphere); else if (type == "cylinder") return getPrimitiveShape(PrimitiveShape::kCylinder); + else if (type == "cone") + return getPrimitiveShape(PrimitiveShape::kCone); else if (type == "capsule") return getPrimitiveShape(PrimitiveShape::kCapsule); else if (type == "ellipsoid") @@ -354,6 +401,7 @@ std::string gz::sim::getPrimitive(const std::string &_typeName) gzwarn << "The valid options are:\n"; gzwarn << " - box\n"; gzwarn << " - sphere\n"; + gzwarn << " - cone\n"; gzwarn << " - cylinder\n"; gzwarn << " - capsule\n"; gzwarn << " - ellipsoid\n"; diff --git a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.qml b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.qml index f1e47ccd81..c21f8787f1 100644 --- a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.qml +++ b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.qml @@ -373,6 +373,14 @@ Rectangle { } } + MenuItem { + id: coneLink + text: "Cone" + onClicked: { + ComponentInspectorEditor.OnAddEntity("cone", "link"); + } + } + MenuItem { id: cylinderLink text: "Cylinder" diff --git a/src/gui/plugins/component_inspector_editor/ModelEditor.cc b/src/gui/plugins/component_inspector_editor/ModelEditor.cc index a838054b80..2f32916f66 100644 --- a/src/gui/plugins/component_inspector_editor/ModelEditor.cc +++ b/src/gui/plugins/component_inspector_editor/ModelEditor.cc @@ -32,6 +32,7 @@ #include #include #include +#include #include #include #include @@ -330,6 +331,14 @@ std::optional ModelEditorPrivate::CreateGeom( geom.SetSphereShape(shape); geom.SetType(sdf::GeometryType::SPHERE); } + else if (_eta.geomOrLightType == "cone") + { + sdf::Cone shape; + shape.SetRadius(size.X() * 0.5); + shape.SetLength(size.Z()); + geom.SetConeShape(shape); + geom.SetType(sdf::GeometryType::CONE); + } else if (_eta.geomOrLightType == "cylinder") { sdf::Cylinder shape; diff --git a/src/gui/plugins/entity_tree/EntityTree.qml b/src/gui/plugins/entity_tree/EntityTree.qml index 8b6db13123..1d65b9e7be 100644 --- a/src/gui/plugins/entity_tree/EntityTree.qml +++ b/src/gui/plugins/entity_tree/EntityTree.qml @@ -202,6 +202,15 @@ Rectangle { } } + MenuItem + { + id: cone + text: "Cone" + onClicked: { + EntityTree.OnInsertEntity("cone") + } + } + MenuItem { id: cylinder diff --git a/src/gui/plugins/shapes/Shapes.qml b/src/gui/plugins/shapes/Shapes.qml index 781eaca28f..fb80c1431f 100644 --- a/src/gui/plugins/shapes/Shapes.qml +++ b/src/gui/plugins/shapes/Shapes.qml @@ -67,6 +67,23 @@ ToolBar { Shapes.OnMode("sphere") } } + ToolButton { + id: cone + ToolTip.text: "Cone" + ToolTip.visible: hovered + ToolTip.delay: Qt.styleHints.mousePressAndHoldInterval + contentItem: Image { + fillMode: Image.Pad + horizontalAlignment: Image.AlignHCenter + verticalAlignment: Image.AlignVCenter + source: "cone.png" + sourceSize.width: 24; + sourceSize.height: 24; + } + onClicked: { + Shapes.OnMode("cone") + } + } ToolButton { id: cylinder ToolTip.text: "Cylinder" diff --git a/src/gui/plugins/shapes/Shapes.qrc b/src/gui/plugins/shapes/Shapes.qrc index 754d997c5d..00fddab57c 100644 --- a/src/gui/plugins/shapes/Shapes.qrc +++ b/src/gui/plugins/shapes/Shapes.qrc @@ -3,6 +3,7 @@ Shapes.qml box.png sphere.png + cone.png cylinder.png capsule.png ellipsoid.png diff --git a/src/gui/plugins/shapes/cone.png b/src/gui/plugins/shapes/cone.png new file mode 100644 index 0000000000000000000000000000000000000000..53f26d831c7b5f129ab2c47739781ebcfcb9dcee GIT binary patch literal 5605 zcmV zaB^>EX>4U6ba`-PAZ2)IW&i+q+O3*vn%g>$g#U9Dvjp)@E{E6WnH|jX=LIO)?sO+P z-nv-&{Ng#Xyng!L@$Px|=gZf8UIy|X7o^v_{pouffBD|Org2|ZRGxtxuaEENW!?4p zQ{I2~o@H~-M$Qf`B;u3qn|f|Vk2tXt7_XNlUYWm<~`5#KYj7e54XJMTlZRv)p@H< zH*8_zX*ttb2D4nDFY_GyUtd2CwD*t@S?>Oc73*>maF!v+$-kThAa*}IiW=bO_3ID7 zGDzSo33K5F+ttqyJ=!<7yiuS%Cq~}Gxj4^z07Asvk;PaK0#~v=+GMZnT(*`t7Vv4T z+<6mR2Lc%NB`d+NEDUV9tRXM_<)8hMmaM>Eq+Kf{bO%{y4wpiMb&)4>^pLQM$O)+0hm$D0w+DF@paD65LV4%m|fM8716QEDBw&hh=E{O*2QgK*u9bahMOVp|1ECr6FDQ${eK{51iBxP z`;OZWs7=xLA$fQqY?6i&)XS58oYY+5&vpI&z16wr=ImMe=zGq^M^pE5BYBHn+BSOc zGx#-g_dCb#Sz`%iHZ$pA;|f)#kwH;sPS*j#*gfRB8Gixqn7wDaR`xUXzV>Ct zE|q0i=XZ}1>OAWnKt~j&&udK%lLa|$sdKrVt*846CTKZuYo!{Eerh8*7+Wq614f7p zQ?sswbHF*ZIaqEfEzRqKl2m%fTHD}efO;(>lX4Sw32?*pw1$%bSjkHKuBSBQ_bCf@ zkTG6YoZmTN{zjV8TF%VL?ZHXm#LmhITVM?suX4E+vk|_?X@gMoHf#5Ok5~sMUpuw7 za#hHss+9#XM)chV=tRg$BSn0Zm>Bt#reA$5s7c)6M1E7^vMUoTN-v0IxoaU|k^JaZ z<69SWY6UmKt;5ce{EZzaw{&Btgmj}TdOc6>rbQXDBruU*!<#8QHn^wBtZRT1j36l{ zF|`9eZ;*t+nM;_X+;sE{uC991F)Om&-GrPQOe6=mlRi@IDAKZ(l?o|CCRj>J*6Vk* z{Ig;sRiPE*dOKY=$PGD`Y6}vztB?{Yx;uiXCQB>a?$US+=7cxPLx|8&mtHtA+1iI` zbCSp`cuRKoX=CVNs|4)d5GjfdDL+2m&F2@bMU*Rl%FKt#P!BjS^sVXKEpoe29X<+S zjL^!m*ogcRFF)pWzlTC)xe$C5I9x3bKKWEWcvJ!f#s-FQ5$lJdZ%@KDpGORbCqa0U z4o?vDWkoDT6wT4K0kQy70>MpnrCLl9hDO*(auR>es&-FSJw1Tz6?8bLA-O@U`&x=p z!_`eMqxmiXn}e{(4hRdrDmn*W6&;3C(U}>It=D@(q2fIuOf-4DW>hlfUWJTnA5~0; zhNZt$F>mK@RV3Dwxmkqn#3*e-MhOc-p=txwP&i4Rq80>N!b-^!;K}`#7k-!V{aqeN zEh!I%G>1K{;|?-vG?&nO&WQC&L{2M;tSV<&G4X&-tw*MbHbnb+XGJmN@ltB3H^jF~ z+CkEqKLkb4i-Ec!cHiA(a8s>_lomc2Z1_G|sgsIg7-QCz6_A@}pq0U4{I?oJgP9FKFPPv zEsWSk5`kzDAWHKsV9J9YMQf);m>>*REaFGS(&$mco7N)IK}PXsnRGtFYi{Pv40p;> z++T>XzY-(3bVxOdH-C3NzZf5gWyQg8pnrnl@@f`m49HKJ|X^>jeYl*gq zp-zGF1~$b?jT=VX>cv0w=+g%M)IUG$!wDZ#-M9E)>Vbd#2)~E|!3zTwtPR&;&uK$@ zcD;#KOXKWnG*5R71A^FulXKEcG4AYu{IvbuVf^mvvo zm+xWd${y1aK21ydVp_7?y89g`F8F4g2*oOxI|498zy|k6HQDfyyY_08lLr4HA~a(I zHK)(gtjvi9XQFkcs^38EcA;?5S28tTGFVjz5rHg9ab!b;tXha5T*}33XG^LRCWEmP zO1udnY&iHU`T#HZgT92O&M?T-P#IXuLsu%)70jd|JtYDT@WoAqrc@A{@MZ$XqEc;K zZ+LE*K-fN%;^3o70Y1`xkSRe|67sT5;i0}cKab@IAC|+k^wo1D@f_~06Abw$jUgR%2anKVgoc zz<)QIF|I3B+pUW$_Mcki*!vgzXYK=vyptn@FLyEhXlg;U09F!+BqLUrm->DY1$-R- zL6XS@5E{#xxQL3yx2+_b6KS4}gV3=1(bCPNoLKWdW$#VCJ`6SETC;F2v{*-?4=TV6z z3@``LqB``GH~at-|BA7DF$akks%9llGe_YMb3PS5&XqryQ?D0uwET=yed?(`yI)4i zkJRv=whp4GHn|z3pC5h2J&qJ~X$41&j?9Z*JG0S|RP-Fc$yLA0=m3Rh1mlihTBu zNFxP|G*ZA;m#m%7bmMF}B?bK>Z@*-%x!VBl{HLrvb3S>iQ~oA%jU13PMJPiSB>l_PnLj1{ z4=Mkd@L%%XsBvS>RDGp3WfZqoIo*Pz_IBX7f0U23-U>oMS~NX*~{zzm{4-^~qD|#={SLmfzm{)t~ZQj8^CQr8- z%Ss<@oPFaM(lv9WIB1=aX9Po9Qa|P4l9}02j^m1~2T7A1Qt1;!YpM9BRXPNi^(_qf1j)0-$Um}AG{@bpwUX9zw|VIc}#k1-S$iv5>k+;YFpavl(s{3$ajhQ zC7V$WhjCg{+J0iLjwcz>IR^B)GfaRkW=WDf;L$)w~CK2rAlGqtFW3}9sdral9tGxHfhX13>gBMqVqVNvB>Tow`_`$ZwV zca~C+CZpz~2z?Bp48E&7j2ojhz%;6fc~sS=*Kn(E}*ZC^S_%JV&_^s&2VXo^b&LauSgQZXp(Qk@QUG;bN#mp73y`N^M-a`FeO# zhDx{;bocj1U9WfZ7}!e{rp87;CNs=t7wEwQI7}NTF_m3T2s?ctJy<$-NjsP|c}>te z-(*GipS0s{|H7QF#4#VtnMuVKxBG^VYjb`9NTHOSD$(mHOBL({Jl0C3rQqgyk;O6q zzqkH10D8O}Yq^>5O7aJ}hF;mr zqv-RD&D84^>|>*@v5*r5DU7!Ec?M35yC@4J~h0X|m~5&ZC`G&kpI? z^%HAx`Zuvy_3VqtuO9AU5g~FYOhI?V45EKtpL^>At0wzY8OhEUPN^bzwy5Bh_SQ@T3U=3Y50CP{C-T4<;I)B%1izH{SshOcjYr@f(nc z4<<+eXD=VlZC}gUjvihhrhVW_U;|H!$U?nSfRbJ9oD6|Qaxe3XC82sXV~B0fnS&~ zDis?~f0;rU)&$l9BBt~M?sC1K19zD4M4%_rmuWl$Y>4lPDLpdz)#BZ8m3Oo>DhnOpT{3 z2G;W+B%xEV8oY0$uRMF50xpRk7Nx$aS2YR|fm`fRY!6B3K&z6K=Jb9Th}%sBc9^M! zFEZi;@R8`jXw&XR6l}~#2M;TNQH@>^SZ@)CdvyeU4GL=YZaoLy2R;!K4a}}yT-OL} zGg4E|dM~5KwaEj$IWG)lCES|;n4q8thU36zl1;s)tc%hs6Cww8uu%;+rD|KwgE76d zEemY4qHsHOKuUlLJ{*9;+ra1IJl!VJFFic4RrdSUE6f0++%Yx4=L9aaqHv=k@Vhd_ z5KX;r0bh0;|ILm(t_av5ufsB|jcXG?#4u-DdLRXXo!Tj;YHtExiGNih_&#G{CnNB0 z%~Yb%k{ncOu1e{_#g>U^+pJ3q{gS}R6zwuK2sVtUB)Y=yDX1u&3TFg1TamCaoFq19 z`USyxe-b%9G30e zm|#tiztwvImeB}bqS_vRIxTQ%Y8npx-Aq>FUB1h+!128POCAJQzPli2H2rNn$grY_ z7C??kZqvlmo`yiz4{%E0^0d97eSTifnhky z1FBuV_e0>axTFkARFq@TZk6CE?0&C17j-JZpwr+(`}O5nlLyZ-1jiux=@PJ+>yLrr zvZeiX8U-#HQlWl7_Ac@v3_xA_HF+@163qtjKMP!tIGU395Z~{*G8$wKEGW82a^0y3 zh`KOKN$4Joi+zC$7NE<)`IjDLslC@D2eRR(#b2WAr$zqP!KWS!DgrMvDdEloYmx$K zHGenCvjCJ!GLuu#<1gxpP=jwG5qe<4HQ@p>atN!yis;2Tg_2#2fFtpu)I4@0rz}s? zP}EI7)8Q)*Y`Q9b1)19bmPMjvN4y;gDfG*L!`cze%w0YH61hS`q&RsP`;i0C3N~cb^bwQx>cI2eMqDEj5*kWu%-G1mn=(7fV)l506ox9Ss?%9oY zfVrcvh3|p&^#dF@I{%G7?V?iYcOEcz?BJCar{xFUnEzIytw_8G?E^o5?BLhgC*K1j zf&Qvp6HyN+`nE9k6=Ln_#1S*7$%GzT@Fevr53H^qU~Kk%$N$jg-#y%Lux6x|K-PYc z$u7VLjBCL&++j03j7?t>P2ipbuTLRR{vS>L=>R^>G*z|V5OSr1S0 ze5ZdO47=I-LfQFm*Z&@SiobvEweCUMVv+v #include +#include #include #include #include @@ -1191,6 +1192,13 @@ rendering::GeometryPtr VisualizationCapabilitiesPrivate::CreateGeometry( capsule->SetLength(_geom.CapsuleShape()->Length()); geom = capsule; } + else if (_geom.Type() == sdf::GeometryType::CONE) + { + geom = this->scene->CreateCone(); + scale.X() = _geom.ConeShape()->Radius() * 2; + scale.Y() = scale.X(); + scale.Z() = _geom.ConeShape()->Length(); + } else if (_geom.Type() == sdf::GeometryType::CYLINDER) { geom = this->scene->CreateCylinder(); diff --git a/src/rendering/MarkerManager.cc b/src/rendering/MarkerManager.cc index 50b761cecb..04b1bef0e1 100644 --- a/src/rendering/MarkerManager.cc +++ b/src/rendering/MarkerManager.cc @@ -387,6 +387,8 @@ rendering::MarkerType MarkerManagerPrivate::MsgToType( return rendering::MarkerType::MT_BOX; case msgs::Marker::CAPSULE: return rendering::MarkerType::MT_CAPSULE; + case msgs::Marker::CONE: + return rendering::MarkerType::MT_CONE; case msgs::Marker::CYLINDER: return rendering::MarkerType::MT_CYLINDER; case msgs::Marker::LINE_STRIP: diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index d94e6aa8b7..c1aefe8918 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -24,6 +24,7 @@ #include #include #include +#include #include #include #include @@ -667,6 +668,13 @@ rendering::GeometryPtr SceneManager::LoadGeometry(const sdf::Geometry &_geom, capsule->SetLength(_geom.CapsuleShape()->Length()); geom = capsule; } + else if (_geom.Type() == sdf::GeometryType::CONE) + { + geom = this->dataPtr->scene->CreateCone(); + scale.X() = _geom.ConeShape()->Radius() * 2; + scale.Y() = scale.X(); + scale.Z() = _geom.ConeShape()->Length(); + } else if (_geom.Type() == sdf::GeometryType::CYLINDER) { geom = this->dataPtr->scene->CreateCylinder(); diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index 1f6defbf44..1d7ca23c15 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -53,6 +53,7 @@ #include #include +#include #include #include #include diff --git a/src/systems/physics/Physics.hh b/src/systems/physics/Physics.hh index cec62d341c..256ee5ac75 100644 --- a/src/systems/physics/Physics.hh +++ b/src/systems/physics/Physics.hh @@ -26,6 +26,7 @@ // Features need to be defined ahead of entityCast #include #include +#include #include #include #include From 055e969bba59bc8b28510a0b67263e7f9ccf8cce Mon Sep 17 00:00:00 2001 From: Benjamin Perseghetti Date: Wed, 26 Jun 2024 15:39:00 -0400 Subject: [PATCH 15/21] Prepare for 8.5.0 (#2455) Signed-off-by: Benjamin Perseghetti --- CMakeLists.txt | 2 +- Changelog.md | 20 ++++++++++++++++++++ package.xml | 2 +- 3 files changed, 22 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e6c3f77eac..a85cfe43ba 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) #============================================================================ # Initialize the project #============================================================================ -project(gz-sim8 VERSION 8.4.0) +project(gz-sim8 VERSION 8.5.0) set (GZ_DISTRIBUTION "Harmonic") #============================================================================ diff --git a/Changelog.md b/Changelog.md index b6d5dc3c2b..7a4ba62198 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,5 +1,25 @@ ## Gazebo Sim 8.x +### Gazebo Sim 8.5.0 (2024-06-26) + +1. Backport: Adding cone primitives + * [Pull request #2404](https://github.com/gazebosim/gz-sim/pull/2404) + +1. Permit to run gz sim -g on Windows + * [Pull request #2382](https://github.com/gazebosim/gz-sim/pull/2382) + +1. Parse voxel resolution SDF param when decomposing meshes + * [Pull request #2445](https://github.com/gazebosim/gz-sim/pull/2445) + +1. Fix model command api test + * [Pull request #2444](https://github.com/gazebosim/gz-sim/pull/2444) + +1. Add tutorial for using the Pose component + * [Pull request #2219](https://github.com/gazebosim/gz-sim/pull/2219) + +1. Do not update sensors if it a triggered sensor + * [Pull request #2443](https://github.com/gazebosim/gz-sim/pull/2443) + ### Gazebo Sim 8.4.0 (2024-06-12) 1. Add pause run tutorial diff --git a/package.xml b/package.xml index 09ca32a77e..a655c2508c 100644 --- a/package.xml +++ b/package.xml @@ -2,7 +2,7 @@ gz-sim8 - 8.4.0 + 8.5.0 Gazebo Sim : A Robotic Simulator Michael Carroll Apache License 2.0 From a02e891679c09a4850284012506abc7c06da1116 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Wed, 26 Jun 2024 23:26:07 +0000 Subject: [PATCH 16/21] Set max contacts for collision pairs (#2270) Signed-off-by: Ian Chen Co-authored-by: Addisu Z. Taddese --- src/systems/physics/Physics.cc | 38 +++++++++++++++++++++++++++++++++- 1 file changed, 37 insertions(+), 1 deletion(-) diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index b3581ae3e8..0a6564231f 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -617,6 +617,14 @@ class gz::sim::systems::PhysicsPrivate public: struct SolverFeatureList : gz::physics::FeatureList< gz::physics::Solver>{}; + ////////////////////////////////////////////////// + // CollisionPairMaxContacts + /// \brief Feature list for setting and getting the max total contacts for + /// collision pairs + public: struct CollisionPairMaxContactsFeatureList : + gz::physics::FeatureList< + gz::physics::CollisionPairMaxContacts>{}; + ////////////////////////////////////////////////// // Nested Models @@ -642,7 +650,8 @@ class gz::sim::systems::PhysicsPrivate NestedModelFeatureList, CollisionDetectorFeatureList, SolverFeatureList, - WorldModelFeatureList + WorldModelFeatureList, + CollisionPairMaxContactsFeatureList >; /// \brief A map between world entity ids in the ECM to World Entities in @@ -1045,6 +1054,33 @@ void PhysicsPrivate::CreateWorldEntities(const EntityComponentManager &_ecm, } } + auto physicsComp = + _ecm.Component(_entity); + if (physicsComp) + { + auto maxContactsFeature = + this->entityWorldMap.EntityCast< + CollisionPairMaxContactsFeatureList>(_entity); + if (!maxContactsFeature) + { + static bool informed{false}; + if (!informed) + { + gzdbg << "Attempting to set physics options, but the " + << "phyiscs engine doesn't support feature " + << "[CollisionPairMaxContacts]. " + << "Options will be ignored." + << std::endl; + informed = true; + } + } + else + { + maxContactsFeature->SetCollisionPairMaxContacts( + physicsComp->Data().MaxContacts()); + } + } + // World Model proxy (used for joints directly under in SDF) auto worldModelFeature = this->entityWorldMap.EntityCast(_entity); From d6067cdc1cccc0d1ff80c90c9614dfbd6a16a77c Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Mon, 1 Jul 2024 17:44:26 +0100 Subject: [PATCH 17/21] Correct name of sensor in warning message (#2457) Signed-off-by: Rhys Mainwaring --- src/systems/magnetometer/Magnetometer.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/systems/magnetometer/Magnetometer.cc b/src/systems/magnetometer/Magnetometer.cc index 82b4e8d0f4..105792b426 100644 --- a/src/systems/magnetometer/Magnetometer.cc +++ b/src/systems/magnetometer/Magnetometer.cc @@ -430,7 +430,7 @@ void MagnetometerPrivate::Update( auto latLonEle = sphericalCoordinates(_entity, _ecm); if (!latLonEle) { - gzwarn << "Failed to update NavSat sensor enity [" << _entity + gzwarn << "Failed to update Magnetometer sensor enity [" << _entity << "]. Spherical coordinates not set." << std::endl; return true; } From b8bbf1d9dee47af68fd1c85fa8382afc47732ff2 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Mon, 1 Jul 2024 14:31:00 -0700 Subject: [PATCH 18/21] Address a couple of todos in Conversion.cc (#2461) Signed-off-by: Ian Chen --- src/Conversions.cc | 49 +++----------------- src/Conversions_TEST.cc | 10 +--- test/integration/scene_broadcaster_system.cc | 4 +- 3 files changed, 9 insertions(+), 54 deletions(-) diff --git a/src/Conversions.cc b/src/Conversions.cc index e6c94f7591..a553ac60e6 100644 --- a/src/Conversions.cc +++ b/src/Conversions.cc @@ -870,7 +870,7 @@ msgs::Atmosphere gz::sim::convert(const sdf::Atmosphere &_in) out.set_type(msgs::Atmosphere::ADIABATIC); } // todo(anyone) add mass density to sdf::Atmosphere? - // out.set_mass_density(_in.MassDensity());k + // out.set_mass_density(_in.MassDensity()); return out; } @@ -1703,15 +1703,7 @@ msgs::ParticleEmitter gz::sim::convert(const sdf::ParticleEmitter &_in) } } - /// \todo(nkoenig) Modify the particle_emitter.proto file to - /// have a topic field. - if (!_in.Topic().empty()) - { - auto header = out.mutable_header()->add_data(); - header->set_key("topic"); - header->add_value(_in.Topic()); - } - + out.mutable_topic()->set_data(_in.Topic()); out.mutable_particle_scatter_ratio()->set_data(_in.ScatterRatio()); return out; } @@ -1766,15 +1758,8 @@ sdf::ParticleEmitter gz::sim::convert(const msgs::ParticleEmitter &_in) out.SetColorRangeImage(_in.color_range_image().data()); if (_in.has_particle_scatter_ratio()) out.SetScatterRatio(_in.particle_scatter_ratio().data()); - - for (int i = 0; i < _in.header().data_size(); ++i) - { - auto data = _in.header().data(i); - if (data.key() == "topic" && data.value_size() > 0) - { - out.SetTopic(data.value(0)); - } - } + if (_in.has_topic()) + out.SetTopic(_in.topic().data()); return out; } @@ -1792,10 +1777,7 @@ msgs::Projector gz::sim::convert(const sdf::Projector &_in) out.set_fov(_in.HorizontalFov().Radian()); out.set_texture(_in.Texture().empty() ? "" : asFullPath(_in.Texture(), _in.FilePath())); - - auto header = out.mutable_header()->add_data(); - header->set_key("visibility_flags"); - header->add_value(std::to_string(_in.VisibilityFlags())); + out.set_visibility_flags(_in.VisibilityFlags()); return out; } @@ -1812,26 +1794,7 @@ sdf::Projector gz::sim::convert(const msgs::Projector &_in) out.SetHorizontalFov(math::Angle(_in.fov())); out.SetTexture(_in.texture()); out.SetRawPose(msgs::Convert(_in.pose())); - - /// \todo(anyone) add "visibility_flags" field to projector.proto - for (int i = 0; i < _in.header().data_size(); ++i) - { - auto data = _in.header().data(i); - if (data.key() == "visibility_flags" && data.value_size() > 0) - { - try - { - out.SetVisibilityFlags(std::stoul(data.value(0))); - } - catch (...) - { - gzerr << "Failed to parse projector : " - << data.value(0) << ". Using default value: 0xFFFFFFFF." - << std::endl; - out.SetVisibilityFlags(0xFFFFFFFF); - } - } - } + out.SetVisibilityFlags(_in.visibility_flags()); return out; } diff --git a/src/Conversions_TEST.cc b/src/Conversions_TEST.cc index 2d67bcfe29..53246e44f4 100644 --- a/src/Conversions_TEST.cc +++ b/src/Conversions_TEST.cc @@ -1041,10 +1041,7 @@ TEST(Conversions, ParticleEmitter) EXPECT_EQ(math::Color(0.4f, 0.5f, 0.6f), msgs::Convert(emitterMsg.color_end())); EXPECT_EQ("range_image", emitterMsg.color_range_image().data()); - - auto header = emitterMsg.header().data(0); - EXPECT_EQ("topic", header.key()); - EXPECT_EQ("my_topic", header.value(0)); + EXPECT_EQ("my_topic", emitterMsg.topic().data()); EXPECT_FLOAT_EQ(0.9f, emitterMsg.particle_scatter_ratio().data()); @@ -1094,10 +1091,7 @@ TEST(Conversions, Projector) EXPECT_NEAR(30, projectorMsg.far_clip(), 1e-3); EXPECT_NEAR(0.4, projectorMsg.fov(), 1e-3); EXPECT_EQ("projector.png", projectorMsg.texture()); - - auto header = projectorMsg.header().data(0); - EXPECT_EQ("visibility_flags", header.key()); - EXPECT_EQ(0xFF, std::stoul(header.value(0))); + EXPECT_EQ(0xFF, projectorMsg.visibility_flags()); // Convert the message back to SDF. sdf::Projector projector2 = convert(projectorMsg); diff --git a/test/integration/scene_broadcaster_system.cc b/test/integration/scene_broadcaster_system.cc index 5c0185d5c9..41508e9466 100644 --- a/test/integration/scene_broadcaster_system.cc +++ b/test/integration/scene_broadcaster_system.cc @@ -1091,9 +1091,7 @@ TEST_P(SceneBroadcasterTest, EXPECT_DOUBLE_EQ(0.5, projector.fov()); EXPECT_NE(std::string::npos, projector.texture().find("path/to/dummy_image.png")); - auto header = projector.header().data(0); - EXPECT_EQ("visibility_flags", header.key()); - EXPECT_EQ(0x01, std::stoul(header.value(0))); + EXPECT_EQ(0x01, projector.visibility_flags()); } } From 771d4fa184fa4055bf4250852fb20eec377cca98 Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Mon, 8 Jul 2024 21:56:40 +0100 Subject: [PATCH 19/21] Magnetometer: correct field calculation (#2460) - The magnetic intensity table has units centi gauss not centi tesla - Add conversion to publish field in telsa. - Field is calculated in NED frame. - Convert to ENU frame for Gazebo world frame convention. Signed-off-by: Rhys Mainwaring --- src/systems/magnetometer/Magnetometer.cc | 62 +++++++++++++++++++++--- src/systems/magnetometer/Magnetometer.hh | 7 +++ 2 files changed, 61 insertions(+), 8 deletions(-) diff --git a/src/systems/magnetometer/Magnetometer.cc b/src/systems/magnetometer/Magnetometer.cc index 105792b426..72474d5cb9 100644 --- a/src/systems/magnetometer/Magnetometer.cc +++ b/src/systems/magnetometer/Magnetometer.cc @@ -98,7 +98,7 @@ static constexpr const int8_t inclination_table[13][37] = \ { 71, 71, 72, 73, 75, 77, 78, 80, 81, 81, 80, 79, 77, 76, 74, 73, 73, 73, 73, 73, 73, 74, 74, 75, 76, 77, 78, 78, 78, 78, 77, 75, 73, 72, 71, 71, 71 }, // NOLINT }; -// strength data in centi-Tesla +// strength data in centi gauss static constexpr const int8_t strength_table[13][37] = \ { { 62, 60, 58, 56, 54, 52, 49, 46, 43, 41, 38, 36, 34, 32, 31, 31, 30, 30, 30, 31, 33, 35, 38, 42, 46, 51, 55, 59, 62, 64, 66, 67, 67, 66, 65, 64, 62 }, // NOLINT @@ -134,6 +134,12 @@ class gz::sim::systems::MagnetometerPrivate /// True if the rendering component is initialized public: bool initialized = false; + /// \brief True if the magnetic field is reported in gauss rather than tesla. + public: bool useUnitsGauss = true; + + /// \brief True if the magnetic field earth frame is NED rather than ENU. + public: bool useEarthFrameNED = true; + /// \brief Create sensor /// \param[in] _ecm Immutable reference to ECM. /// \param[in] _entity Entity of the IMU @@ -226,7 +232,7 @@ class gz::sim::systems::MagnetometerPrivate return get_table_data(lat, lon, inclination_table); } - // return magnetic field strength in centi-Tesla + // return magnetic field strength in centi-Gauss float get_mag_strength(float lat, float lon) { return get_table_data(lat, lon, strength_table); @@ -242,6 +248,29 @@ Magnetometer::Magnetometer() : System(), dataPtr( ////////////////////////////////////////////////// Magnetometer::~Magnetometer() = default; +////////////////////////////////////////////////// +void Magnetometer::Configure(const Entity &/*_entity*/, + const std::shared_ptr &_sdf, + EntityComponentManager &/*_ecm*/, + EventManager &/*_eventMgr*/) +{ + if (_sdf->HasElement("use_units_gauss")) + { + this->dataPtr->useUnitsGauss = _sdf->Get("use_units_gauss"); + } + gzdbg << "Magnetometer: using param [use_units_gauss: " + << this->dataPtr->useUnitsGauss << "]." + << std::endl; + + if (_sdf->HasElement("use_earth_frame_ned")) + { + this->dataPtr->useEarthFrameNED = _sdf->Get("use_earth_frame_ned"); + } + gzdbg << "Magnetometer: using param [use_earth_frame_ned: " + << this->dataPtr->useEarthFrameNED << "]." + << std::endl; +} + ////////////////////////////////////////////////// void Magnetometer::PreUpdate(const UpdateInfo &/*_info*/, EntityComponentManager &_ecm) @@ -446,16 +475,32 @@ void MagnetometerPrivate::Update( get_mag_inclination( lat_rad * 180 / GZ_PI, lon_rad * 180 / GZ_PI) * GZ_PI / 180; - // Magnetic strength (10^5xnanoTesla) + // Magnetic strength in gauss (10^5 nano tesla = 10^-2 centi gauss) float strength_ga = 0.01f * get_mag_strength(lat_rad * 180 / GZ_PI, lon_rad * 180 / GZ_PI); - // Magnetic filed components are calculated by http://geomag.nrcan.gc.ca/mag_fld/comp-en.php - float H = strength_ga * cosf(inclination_rad); - float Z = tanf(inclination_rad) * H; - float X = H * cosf(declination_rad); - float Y = H * sinf(declination_rad); + // Magnetic intensity measured in telsa + float strength_tesla = 1.0E-4 * strength_ga; + + // Magnetic field components are calculated in world NED frame using: + // http://geomag.nrcan.gc.ca/mag_fld/comp-en.php + float H = cosf(inclination_rad); + H *= this->useUnitsGauss ? strength_ga : strength_tesla; + float Z_ned = tanf(inclination_rad) * H; + float X_ned = H * cosf(declination_rad); + float Y_ned = H * sinf(declination_rad); + + float X = X_ned; + float Y = Y_ned; + float Z = Z_ned; + if (!this->useEarthFrameNED) + { + // Use ENU convention for earth frame. + X = Y_ned; + Y = X_ned; + Z = -1.0 * Z_ned; + } math::Vector3d magnetic_field_I(X, Y, Z); it->second->SetWorldMagneticField(magnetic_field_I); @@ -494,6 +539,7 @@ void MagnetometerPrivate::RemoveMagnetometerEntities( } GZ_ADD_PLUGIN(Magnetometer, System, + Magnetometer::ISystemConfigure, Magnetometer::ISystemPreUpdate, Magnetometer::ISystemPostUpdate ) diff --git a/src/systems/magnetometer/Magnetometer.hh b/src/systems/magnetometer/Magnetometer.hh index 854eb44a3b..e2e1c5d166 100644 --- a/src/systems/magnetometer/Magnetometer.hh +++ b/src/systems/magnetometer/Magnetometer.hh @@ -37,6 +37,7 @@ namespace systems /// current location. class Magnetometer: public System, + public ISystemConfigure, public ISystemPreUpdate, public ISystemPostUpdate { @@ -46,6 +47,12 @@ namespace systems /// \brief Destructor public: ~Magnetometer() override; + // Documentation inherited + public: void Configure(const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm, + EventManager &_eventMgr) override; + /// Documentation inherited public: void PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ecm) final; From 924607bf68c1732dcfb9572445fa08d108bafd48 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Mon, 8 Jul 2024 13:56:53 -0700 Subject: [PATCH 20/21] Update description of reset_sensors test (#2467) Signed-off-by: Steve Peters --- test/integration/reset_sensors.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/test/integration/reset_sensors.cc b/test/integration/reset_sensors.cc index 40544b92c4..8636346180 100644 --- a/test/integration/reset_sensors.cc +++ b/test/integration/reset_sensors.cc @@ -140,8 +140,8 @@ common::Image toImage(const msgs::Image &_msg) } ///////////////////////////////////////////////// -/// This test checks that that the sensors system handles cases where entities -/// are removed and then added back +/// This test checks that that air-pressure and camera sensor systems +/// handle Reset events TEST_F(ResetFixture, GZ_UTILS_TEST_DISABLED_ON_MAC(HandleReset)) { gz::sim::ServerConfig serverConfig; From 90a7ba7e79e76d50b2cb97e4a20aad5ebba9b023 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Tue, 9 Jul 2024 10:52:06 -0700 Subject: [PATCH 21/21] Enable tests on macOS (#2468) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit They appear to be passing now. Signed-off-by: Steve Peters Co-authored-by: Alejandro Hernández Cordero --- test/integration/actor_trajectory.cc | 2 +- test/integration/camera_sensor_background_from_scene.cc | 2 +- test/integration/sensors_system.cc | 2 +- test/integration/sensors_system_battery.cc | 2 +- test/integration/sensors_system_update_rate.cc | 2 +- test/integration/thermal_sensor_system.cc | 2 +- test/integration/thermal_system.cc | 4 ++-- test/integration/wide_angle_camera.cc | 2 +- 8 files changed, 9 insertions(+), 9 deletions(-) diff --git a/test/integration/actor_trajectory.cc b/test/integration/actor_trajectory.cc index 7a6819ba28..901789ce2e 100644 --- a/test/integration/actor_trajectory.cc +++ b/test/integration/actor_trajectory.cc @@ -99,7 +99,7 @@ class ActorFixture : public InternalFixture> // Load the actor_trajectory.sdf world that animates a box (actor) to follow // a trajectory. Verify that the box pose changes over time on the rendering // side. -TEST_F(ActorFixture, GZ_UTILS_TEST_DISABLED_ON_MAC(ActorTrajectoryNoMesh)) +TEST_F(ActorFixture, ActorTrajectoryNoMesh) { sim::ServerConfig serverConfig; diff --git a/test/integration/camera_sensor_background_from_scene.cc b/test/integration/camera_sensor_background_from_scene.cc index 88d55cfc67..d53234258f 100644 --- a/test/integration/camera_sensor_background_from_scene.cc +++ b/test/integration/camera_sensor_background_from_scene.cc @@ -77,7 +77,7 @@ void cameraCb(const msgs::Image & _msg) ///////////////////////////////////////////////// // Test sensors use the background color of by default TEST_F(CameraSensorBackgroundFixture, - GZ_UTILS_TEST_DISABLED_ON_MAC(RedBackgroundFromScene)) + RedBackgroundFromScene) { const auto sdfFile = common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds", "camera_sensor_scene_background.sdf"); diff --git a/test/integration/sensors_system.cc b/test/integration/sensors_system.cc index 84e95e94f6..a116d54cf7 100644 --- a/test/integration/sensors_system.cc +++ b/test/integration/sensors_system.cc @@ -183,7 +183,7 @@ void testDefaultTopics(const std::vector &_topics) ///////////////////////////////////////////////// /// This test checks that that the sensors system handles cases where entities /// are removed and then added back -TEST_F(SensorsFixture, GZ_UTILS_TEST_DISABLED_ON_MAC(HandleRemovedEntities)) +TEST_F(SensorsFixture, HandleRemovedEntities) { gz::sim::ServerConfig serverConfig; diff --git a/test/integration/sensors_system_battery.cc b/test/integration/sensors_system_battery.cc index 4eb35ec92f..49bfd0cd0b 100644 --- a/test/integration/sensors_system_battery.cc +++ b/test/integration/sensors_system_battery.cc @@ -83,7 +83,7 @@ class SensorsFixture : public InternalFixture> ///////////////////////////////////////////////// // Battery -TEST_F(SensorsFixture, GZ_UTILS_TEST_DISABLED_ON_MAC(SensorsBatteryState)) +TEST_F(SensorsFixture, SensorsBatteryState) { const auto sdfPath = common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds", "sensors_system_battery.sdf"); diff --git a/test/integration/sensors_system_update_rate.cc b/test/integration/sensors_system_update_rate.cc index 9df4de1d86..55d9130b13 100644 --- a/test/integration/sensors_system_update_rate.cc +++ b/test/integration/sensors_system_update_rate.cc @@ -76,7 +76,7 @@ class SensorsFixture : public InternalFixture> }; ///////////////////////////////////////////////// -TEST_F(SensorsFixture, GZ_UTILS_TEST_DISABLED_ON_MAC(UpdateRate)) +TEST_F(SensorsFixture, UpdateRate) { gz::sim::ServerConfig serverConfig; diff --git a/test/integration/thermal_sensor_system.cc b/test/integration/thermal_sensor_system.cc index 16dfde6f6e..9ad00dcdaf 100644 --- a/test/integration/thermal_sensor_system.cc +++ b/test/integration/thermal_sensor_system.cc @@ -74,7 +74,7 @@ void thermalCb(const msgs::Image &_msg) ///////////////////////////////////////////////// TEST_F(ThermalSensorTest, - GZ_UTILS_TEST_DISABLED_ON_MAC(ThermalSensorSystemInvalidConfig)) + ThermalSensorSystemInvalidConfig) { // Start server ServerConfig serverConfig; diff --git a/test/integration/thermal_system.cc b/test/integration/thermal_system.cc index 1e9155514c..bc5e81692f 100644 --- a/test/integration/thermal_system.cc +++ b/test/integration/thermal_system.cc @@ -49,7 +49,7 @@ class ThermalTest : public InternalFixture<::testing::Test> }; ///////////////////////////////////////////////// -TEST_F(ThermalTest, GZ_UTILS_TEST_DISABLED_ON_MAC(TemperatureComponent)) +TEST_F(ThermalTest, TemperatureComponent) { // Start server ServerConfig serverConfig; @@ -173,7 +173,7 @@ TEST_F(ThermalTest, GZ_UTILS_TEST_DISABLED_ON_MAC(TemperatureComponent)) } ///////////////////////////////////////////////// -TEST_F(ThermalTest, GZ_UTILS_TEST_DISABLED_ON_MAC(ThermalSensorSystem)) +TEST_F(ThermalTest, ThermalSensorSystem) { // Start server ServerConfig serverConfig; diff --git a/test/integration/wide_angle_camera.cc b/test/integration/wide_angle_camera.cc index d2857bdccd..32dd00bd92 100644 --- a/test/integration/wide_angle_camera.cc +++ b/test/integration/wide_angle_camera.cc @@ -61,7 +61,7 @@ void imageCb(const msgs::Image &_msg) ///////////////////////////////////////////////// // The test checks the Wide Angle Camera readings -TEST_F(WideAngleCameraTest, GZ_UTILS_TEST_DISABLED_ON_MAC(WideAngleCameraBox)) +TEST_F(WideAngleCameraTest, WideAngleCameraBox) { // Start server ServerConfig serverConfig;