From f7d3c38fe757a51f215dc8af1d67f88cabe1c674 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Tue, 2 Mar 2021 19:00:34 -0800 Subject: [PATCH 1/7] Heightmap physics (with DART) Signed-off-by: Louise Poubel --- CMakeLists.txt | 1 + examples/worlds/heightmap.sdf | 256 ++++++++++++++++++++++++++++++++- src/systems/physics/Physics.cc | 72 ++++++++++ 3 files changed, 328 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b065384857..72db27ec35 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -89,6 +89,7 @@ ign_find_package (Qt5 # Find ignition-physics ign_find_package(ignition-physics4 COMPONENTS + heightmap mesh sdf REQUIRED diff --git a/examples/worlds/heightmap.sdf b/examples/worlds/heightmap.sdf index 69f354b513..23cb8589e5 100644 --- a/examples/worlds/heightmap.sdf +++ b/examples/worlds/heightmap.sdf @@ -23,7 +23,113 @@ scene 0.4 0.4 0.4 0.8 0.8 0.8 - -16.6 7.3 8.6 0.0 0.4 -0.45 + -80 40 60 0.0 0.4 -0.45 + + + + + + World control + false + false + 72 + 121 + 1 + + floating + + + + + + + true + true + true + + + + + + + World stats + false + false + 110 + 290 + 1 + + floating + + + + + + + true + true + true + true + + + + + + + Transform control + false + 0 + 0 + 250 + 50 + floating + false + #666666 + + + + + + + false + 250 + 0 + 150 + 50 + floating + false + #666666 + + + + + + + false + 400 + 0 + 150 + 50 + floating + false + #666666 + + + + + + + false + docked + + + + + + + false + docked + @@ -42,6 +148,154 @@ -0.5 0.1 -0.9 + + 30 30 10 0 0 0 + + + + 3 + 0 + 0 + 3 + 0 + 3 + + 3.0 + + + + + 0.5 + + + + + + + + 0.5 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + + + 30 -30 10 0 0 0 + + + + 3 + 0 + 0 + 3 + 0 + 3 + + 3.0 + + + + + 0.5 + + + + + + + + 0.5 + + + + 0 1 0 1 + 0 1 0 1 + 0 1 0 1 + + + + + + + -30 30 10 0 0 0 + + + + 3 + 0 + 0 + 3 + 0 + 3 + + 3.0 + + + + + 0.5 + + + + + + + + 0.5 + + + + 0 0 1 1 + 0 0 1 1 + 0 0 1 1 + + + + + + + -30 -30 20 0 0 0 + + + + 3 + 0 + 0 + 3 + 0 + 3 + + 3.0 + + + + + 0.5 + + + + + + + + 0.5 + + + + 1 1 0 1 + 1 1 0 1 + 1 1 0 1 + + + + + https://fuel.ignitionrobotics.org/1.0/chapulina/models/Heightmap Bowl diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index e8f52800d2..dfc05f29af 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -29,6 +29,8 @@ #include #include +#include +#include #include #include #include @@ -38,6 +40,7 @@ #include #include #include +#include #include #include #include @@ -46,6 +49,7 @@ // SDF #include +#include #include #include #include @@ -476,6 +480,27 @@ class ignition::gazebo::systems::PhysicsPrivate public: std::unordered_map entityLinkMeshMap; + ////////////////////////////////////////////////// + // Heightmap + + /// \brief Feature list for heightmaps. + /// Include MinimumFeatureList so created collision can be automatically + /// up-cast. + public: using HeightmapFeatureList = physics::FeatureList< + CollisionFeatureList, + physics::heightmap::AttachHeightmapShapeFeature>; + + /// \brief Link type with heightmapes. + public: using LinkHeightmapPtrType = physics::LinkPtr< + physics::FeaturePolicy3d, HeightmapFeatureList>; + + /// \brief A map between link entity ids in the ECM to Link Entities in + /// ign-physics, with heightmap feature. + /// All links on this map are also in `entityLinkMap`. The difference is + /// that here they've been casted for `HeightmapFeatureList`. + public: std::unordered_map + entityLinkHeightmapMap; + ////////////////////////////////////////////////// // Nested Models @@ -940,6 +965,53 @@ void PhysicsPrivate::CreatePhysicsEntities(const EntityComponentManager &_ecm) math::eigen3::convert(_pose->Data()), math::eigen3::convert(meshSdf->Scale())); } + else if (_geom->Data().Type() == sdf::GeometryType::HEIGHTMAP) + { + auto linkHeightmapFeature = entityCast(_parent->Data(), linkPtrPhys, + this->entityLinkHeightmapMap); + if (!linkHeightmapFeature) + { + static bool informed{false}; + if (!informed) + { + igndbg << "Attempting to process heightmap geometries, but the physics" + << " engine doesn't support feature " + << "[AttachHeightmapShapeFeature]. Heightmapes will be ignored." + << std::endl; + informed = true; + } + return true; + } + + auto heightmapSdf = _geom->Data().HeightmapShape(); + if (nullptr == heightmapSdf) + { + ignwarn << "Heightmap geometry for collision [" << _name->Data() + << "] missing heightmap shape." << std::endl; + return true; + } + + auto fullPath = asFullPath(heightmapSdf->Uri(), heightmapSdf->FilePath()); + if (fullPath.empty()) + { + ignerr << "Heightmap geometry missing URI" << std::endl; + return true; + } + + common::ImageHeightmap data; + if (data.Load(fullPath) < 0) + { + ignerr << "Failed to load heightmap image data from [" << fullPath + << "]" << std::endl; + return true; + } + + collisionPtrPhys = linkHeightmapFeature->AttachHeightmapShape(_name->Data(), + data, + math::eigen3::convert(_pose->Data()), + math::eigen3::convert(heightmapSdf->Size()), + heightmapSdf->Sampling()); + } else { auto linkCollisionFeature = entityCast(_parent->Data(), linkPtrPhys, From a4d918afa9cd2172162a9ab71e9784c2d5613e26 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Wed, 17 Mar 2021 12:27:29 -0700 Subject: [PATCH 2/7] Update API Signed-off-by: Louise Poubel --- examples/worlds/heightmap.sdf | 9 ++++++--- src/systems/physics/Physics.cc | 21 ++++++--------------- 2 files changed, 12 insertions(+), 18 deletions(-) diff --git a/examples/worlds/heightmap.sdf b/examples/worlds/heightmap.sdf index 23cb8589e5..3d668a5728 100644 --- a/examples/worlds/heightmap.sdf +++ b/examples/worlds/heightmap.sdf @@ -3,12 +3,15 @@ Demonstrates a heightmap terrain. - At the moment, only the visuals work, but not the physics collisions, see - https://github.com/ignitionrobotics/ign-physics/issues/156. - --> + + + + bullet + + diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index 0e62163508..301c9424a7 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -365,20 +365,9 @@ class ignition::gazebo::systems::PhysicsPrivate /// \brief Feature list for heightmaps. /// Include MinimumFeatureList so created collision can be automatically /// up-cast. - public: using HeightmapFeatureList = physics::FeatureList< + public: struct HeightmapFeatureList : ignition::physics::FeatureList< CollisionFeatureList, - physics::heightmap::AttachHeightmapShapeFeature>; - - /// \brief Link type with heightmapes. - public: using LinkHeightmapPtrType = physics::LinkPtr< - physics::FeaturePolicy3d, HeightmapFeatureList>; - - /// \brief A map between link entity ids in the ECM to Link Entities in - /// ign-physics, with heightmap feature. - /// All links on this map are also in `entityLinkMap`. The difference is - /// that here they've been casted for `HeightmapFeatureList`. - public: std::unordered_map - entityLinkHeightmapMap; + physics::heightmap::AttachHeightmapShapeFeature>{}; ////////////////////////////////////////////////// // Nested Models @@ -418,6 +407,7 @@ class ignition::gazebo::systems::PhysicsPrivate MinimumFeatureList, DetachableJointFeatureList, CollisionFeatureList, + HeightmapFeatureList, LinkForceFeatureList, MeshFeatureList>; @@ -906,8 +896,9 @@ void PhysicsPrivate::CreatePhysicsEntities(const EntityComponentManager &_ecm) } else if (_geom->Data().Type() == sdf::GeometryType::HEIGHTMAP) { - auto linkHeightmapFeature = entityCast(_parent->Data(), linkPtrPhys, - this->entityLinkHeightmapMap); + auto linkHeightmapFeature = + this->entityLinkMap.EntityCast( + _parent->Data()); if (!linkHeightmapFeature) { static bool informed{false}; From 100a08afd09a2e9315f42c4b8c03a080045917fb Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Fri, 23 Apr 2021 16:58:36 -0700 Subject: [PATCH 3/7] typo Signed-off-by: Louise Poubel --- src/systems/physics/Physics.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index 732ee18236..5e2fb4279f 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -934,7 +934,7 @@ void PhysicsPrivate::CreatePhysicsEntities(const EntityComponentManager &_ecm) { igndbg << "Attempting to process heightmap geometries, but the physics" << " engine doesn't support feature " - << "[AttachHeightmapShapeFeature]. Heightmapes will be ignored." + << "[AttachHeightmapShapeFeature]. Heightmaps will be ignored." << std::endl; informed = true; } From 0142166e4fa973096d4169c12fe0876820e19f43 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Wed, 16 Jun 2021 16:42:06 -0700 Subject: [PATCH 4/7] Prevent crash when selecting heightmap Signed-off-by: Louise Poubel --- src/rendering/RenderUtil.cc | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 2476219904..ddd980334a 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -2088,9 +2088,15 @@ void RenderUtilPrivate::HighlightNode(const rendering::NodePtr &_node) white->SetEmissive(1.0, 1.0, 1.0); } - ignition::rendering::WireBoxPtr wireBox = - this->scene->CreateWireBox(); - ignition::math::AxisAlignedBox aabb = vis->LocalBoundingBox(); + auto aabb = vis->LocalBoundingBox(); + if (aabb == math::AxisAlignedBox()) + { + // Infinite bounding box, skip hihglighting this node. + // This happens for Heightmaps, for example. + return; + } + + auto wireBox = this->scene->CreateWireBox(); wireBox->SetBox(aabb); // Create visual and add wire box From 9b0d908fa7a460ab0f72480d053e5165e7687358 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Thu, 15 Jul 2021 18:30:12 -0700 Subject: [PATCH 5/7] PR feedback, cppcheck Signed-off-by: Louise Poubel --- examples/worlds/heightmap.sdf | 6 --- src/systems/physics/Physics.cc | 92 +++++++++++++++++++++++++++------- 2 files changed, 73 insertions(+), 25 deletions(-) diff --git a/examples/worlds/heightmap.sdf b/examples/worlds/heightmap.sdf index 3d668a5728..6c2de6cb05 100644 --- a/examples/worlds/heightmap.sdf +++ b/examples/worlds/heightmap.sdf @@ -49,7 +49,6 @@ true true true - @@ -73,7 +72,6 @@ true true true - @@ -172,7 +170,6 @@ - @@ -209,7 +206,6 @@ - @@ -246,7 +242,6 @@ - @@ -283,7 +278,6 @@ - diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index 3adf30373a..0a34d1d8d5 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -180,6 +180,30 @@ class ignition::gazebo::systems::PhysicsPrivate /// \param[in] _ecm Constant reference to ECM. public: void CreatePhysicsEntities(const EntityComponentManager &_ecm); + /// \brief Create world entities + /// \param[in] _ecm Constant reference to ECM. + public: void CreateWorldEntities(const EntityComponentManager &_ecm); + + /// \brief Create model entities + /// \param[in] _ecm Constant reference to ECM. + public: void CreateModelEntities(const EntityComponentManager &_ecm); + + /// \brief Create link entities + /// \param[in] _ecm Constant reference to ECM. + public: void CreateLinkEntities(const EntityComponentManager &_ecm); + + /// \brief Create collision entities + /// \param[in] _ecm Constant reference to ECM. + public: void CreateCollisionEntities(const EntityComponentManager &_ecm); + + /// \brief Create joint entities + /// \param[in] _ecm Constant reference to ECM. + public: void CreateJointEntities(const EntityComponentManager &_ecm); + + /// \brief Create Battery entities + /// \param[in] _ecm Constant reference to ECM. + public: void CreateBatteryEntities(const EntityComponentManager &_ecm); + /// \brief Remove physics entities if they are removed from the ECM /// \param[in] _ecm Constant reference to ECM. public: void RemovePhysicsEntities(const EntityComponentManager &_ecm); @@ -702,6 +726,18 @@ void Physics::Update(const UpdateInfo &_info, EntityComponentManager &_ecm) ////////////////////////////////////////////////// void PhysicsPrivate::CreatePhysicsEntities(const EntityComponentManager &_ecm) +{ + this->CreateWorldEntities(_ecm); + this->CreateModelEntities(_ecm); + this->CreateLinkEntities(_ecm); + // We don't need to add visuals to the physics engine. + this->CreateCollisionEntities(_ecm); + this->CreateJointEntities(_ecm); + this->CreateBatteryEntities(_ecm); +} + +////////////////////////////////////////////////// +void PhysicsPrivate::CreateWorldEntities(const EntityComponentManager &_ecm) { // Get all the new worlds _ecm.EachNew( @@ -779,7 +815,11 @@ void PhysicsPrivate::CreatePhysicsEntities(const EntityComponentManager &_ecm) return true; }); +} +////////////////////////////////////////////////// +void PhysicsPrivate::CreateModelEntities(const EntityComponentManager &_ecm) +{ _ecm.EachNew( [&](const Entity &_entity, @@ -907,7 +947,11 @@ void PhysicsPrivate::CreatePhysicsEntities(const EntityComponentManager &_ecm) return true; }); +} +////////////////////////////////////////////////// +void PhysicsPrivate::CreateLinkEntities(const EntityComponentManager &_ecm) +{ _ecm.EachNew( [&](const Entity &_entity, @@ -961,10 +1005,11 @@ void PhysicsPrivate::CreatePhysicsEntities(const EntityComponentManager &_ecm) return true; }); +} - // We don't need to add visuals to the physics engine. - - // collisions +////////////////////////////////////////////////// +void PhysicsPrivate::CreateCollisionEntities(const EntityComponentManager &_ecm) +{ _ecm.EachNew( @@ -1053,10 +1098,10 @@ void PhysicsPrivate::CreatePhysicsEntities(const EntityComponentManager &_ecm) static bool informed{false}; if (!informed) { - igndbg << "Attempting to process heightmap geometries, but the physics" - << " engine doesn't support feature " - << "[AttachHeightmapShapeFeature]. Heightmaps will be ignored." - << std::endl; + igndbg << "Attempting to process heightmap geometries, but the " + << "physics engine doesn't support feature " + << "[AttachHeightmapShapeFeature]. Heightmaps will be " + << "ignored." << std::endl; informed = true; } return true; @@ -1070,7 +1115,8 @@ void PhysicsPrivate::CreatePhysicsEntities(const EntityComponentManager &_ecm) return true; } - auto fullPath = asFullPath(heightmapSdf->Uri(), heightmapSdf->FilePath()); + auto fullPath = asFullPath(heightmapSdf->Uri(), + heightmapSdf->FilePath()); if (fullPath.empty()) { ignerr << "Heightmap geometry missing URI" << std::endl; @@ -1085,7 +1131,8 @@ void PhysicsPrivate::CreatePhysicsEntities(const EntityComponentManager &_ecm) return true; } - collisionPtrPhys = linkHeightmapFeature->AttachHeightmapShape(_name->Data(), + collisionPtrPhys = linkHeightmapFeature->AttachHeightmapShape( + _name->Data(), data, math::eigen3::convert(_pose->Data()), math::eigen3::convert(heightmapSdf->Size()), @@ -1141,8 +1188,11 @@ void PhysicsPrivate::CreatePhysicsEntities(const EntityComponentManager &_ecm) topLevelModel(_entity, _ecm))); return true; }); +} - // joints +////////////////////////////////////////////////// +void PhysicsPrivate::CreateJointEntities(const EntityComponentManager &_ecm) +{ _ecm.EachNew( - [&](const Entity & _entity, const components::BatterySoC *)->bool - { - // Parent entity of battery is model entity - this->entityOffMap.insert(std::make_pair( - _ecm.ParentEntity(_entity), false)); - return true; - }); - // Detachable joints _ecm.EachNew( [&](const Entity &_entity, @@ -1325,6 +1366,19 @@ void PhysicsPrivate::CreatePhysicsEntities(const EntityComponentManager &_ecm) }); } +////////////////////////////////////////////////// +void PhysicsPrivate::CreateBatteryEntities(const EntityComponentManager &_ecm) +{ + _ecm.EachNew( + [&](const Entity & _entity, const components::BatterySoC *)->bool + { + // Parent entity of battery is model entity + this->entityOffMap.insert(std::make_pair( + _ecm.ParentEntity(_entity), false)); + return true; + }); +} + ////////////////////////////////////////////////// void PhysicsPrivate::RemovePhysicsEntities(const EntityComponentManager &_ecm) { From 288dfa6ffbd3fe37b1a5977514880912efdbbd2a Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Thu, 15 Jul 2021 20:56:16 -0700 Subject: [PATCH 6/7] fix spelling Signed-off-by: Steve Peters --- src/rendering/RenderUtil.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 4ea2dfcb97..f4306b5986 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -1896,7 +1896,7 @@ void RenderUtilPrivate::HighlightNode(const rendering::NodePtr &_node) auto aabb = vis->LocalBoundingBox(); if (aabb == math::AxisAlignedBox()) { - // Infinite bounding box, skip hihglighting this node. + // Infinite bounding box, skip highlighting this node. // This happens for Heightmaps, for example. return; } From 2990e8f5d785f5559b537177bdb733ce91d1f32e Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Fri, 16 Jul 2021 13:36:07 -0700 Subject: [PATCH 7/7] add simple test Signed-off-by: Louise Poubel --- test/integration/physics_system.cc | 80 +++++++++++++++++++++++++++++ test/media/heightmap_bowl.png | Bin 0 -> 11313 bytes test/worlds/heightmap.sdf | 68 ++++++++++++++++++++++++ 3 files changed, 148 insertions(+) create mode 100644 test/media/heightmap_bowl.png create mode 100644 test/worlds/heightmap.sdf diff --git a/test/integration/physics_system.cc b/test/integration/physics_system.cc index d1e34607a2..643d4c17e1 100644 --- a/test/integration/physics_system.cc +++ b/test/integration/physics_system.cc @@ -1458,3 +1458,83 @@ TEST_F(PhysicsSystemFixture, PhysicsOptions) EXPECT_TRUE(checked); } + +///////////////////////////////////////////////// +TEST_F(PhysicsSystemFixture, Heightmap) +{ + ignition::gazebo::ServerConfig serverConfig; + + const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + + "/test/worlds/heightmap.sdf"; + serverConfig.SetSdfFile(sdfFile); + + sdf::Root root; + root.Load(sdfFile); + + bool checked{false}; + int maxIt{0}; + + test::Relay testSystem; + testSystem.OnPostUpdate( + [&](const gazebo::UpdateInfo &_info, + const gazebo::EntityComponentManager &_ecm) + { + double aboveHeight; + double farHeight; + bool checkedAbove{false}; + bool checkedFar{false}; + bool checkedHeightmap{false}; + + _ecm.Each( + [&](const ignition::gazebo::Entity &, const components::Model *, + const components::Name *_name, const components::Pose *_pose)->bool + { + if (_name->Data() == "above_heightmap") + { + aboveHeight = _pose->Data().Pos().Z(); + checkedAbove = true; + } + else if (_name->Data() == "far_from_heightmap") + { + farHeight = _pose->Data().Pos().Z(); + checkedFar = true; + } + else + { + EXPECT_EQ("Heightmap Bowl", _name->Data()); + EXPECT_EQ(math::Pose3d(), _pose->Data()); + checkedHeightmap = true; + } + + return true; + }); + + EXPECT_TRUE(checkedAbove); + EXPECT_TRUE(checkedFar); + EXPECT_TRUE(checkedHeightmap); + + // Both models drop from 7m + EXPECT_GE(7.01, aboveHeight) << _info.iterations; + EXPECT_GE(7.01, farHeight) << _info.iterations; + + // Model above heightmap hits it and never drops below 5.5m + EXPECT_LE(5.5, aboveHeight) << _info.iterations; + + // Model far from heightmap keeps falling + if (_info.iterations > 600) + { + EXPECT_GT(5.5, farHeight) << _info.iterations; + } + + checked = true; + maxIt = _info.iterations; + return true; + }); + + gazebo::Server server(serverConfig); + server.AddSystem(testSystem.systemPtr); + server.Run(true, 1000, false); + + EXPECT_TRUE(checked); + EXPECT_EQ(1000, maxIt); +} diff --git a/test/media/heightmap_bowl.png b/test/media/heightmap_bowl.png new file mode 100644 index 0000000000000000000000000000000000000000..52df5fcd073e26f738a40125f7f50a1fc33caa1d GIT binary patch literal 11313 zcmV-1EY8!3P)Px#24YJ`L;(K){{a7>y{D4^000SaNLh0L01FcU01FcV0GgZ_00007bV*G`2iye@ z4Ji<4g7ppn000?uMObu0Z*6U5Zgc=ca%Ew3Wn>_CX>@2HM@dakSAh-}001BWNklYrAjw3<$|Nr0V9xKelAxQ8plCpX+o2ar3rBZUgeip6(h=|CCKgj&}-}(ZX znfXEH2Z;|pNPYK{pZui0i_a(fOZ{GcJ_+RWpMI;C|91X+{rblrBk}osvfjG>Lp{R> z_I~rPpIlFMUL}8hFd#pl%mnbs^IrJm2ewL|PyG;p{OGN4-r%G6#`!Pk6^)1p#`**O zP5L+LUx)|>gNTR#0)YtB_s;jp2r#%_n{j^d=?~)a!x8Lvr+y0v1Q7&DkPITgAPJu5 zB?&^$h?xH~&XZm~?Rm<_2dh`8uK`9d2%MJ*5a-((b`vf2``y4aEV}>!+#fNuti2UW@uUYRv)> z0O6-ypO3!VxIYBvFWUAY=D5xd5OG!`0DyHM&(R?3gu_2WpOZF~nVHyjK{tnpxg{v|4p$qZ z3fX{Tlc1MkZMNL3oGz%Fs7*gRef&0$^#WN}^13U23Gft=k(YbIkXd7|2QfwgWh79( z`fSInf+89DtaS*kM+0#=JboX`nkWj<<%9kk-6(PnWj&oPp>~8GxhsIr4>DoC12pGj z@ej+q%7eqUJiv+%iQt$IKKZ_fE8$kNeF?`u^m#`glL;QmI@hVx{b8+&HpK4fquqP^ z-gq%Ur=ngv6snz7kS8V1S8@z;Zs+=b^OLc!);T=q6lUG>NRX7%1%kmelMXPD$2cU~ zP=a8B5gBA4ZG8cY$oUWzQ4t9lS-X$5z`ZNSF)$J%~tN zVu?Wn{4x zkV($#DhN3{i}qyguaCckZZ4JI;rFokek14!TPP@-gbupF2%YzG1|4veQ6Wft6Q77W z{T#pKhEhR6YGF^5o3)LM%yX;C;vM(V4_Qt#?IPCWqGQANrRe-{a@F(f8F|haNG38Y zEDUyjPqNZV`diiQB=w5J4fs%S0 zr?n02Ts6EnCdFeiKEn@qutOJN;@;k)-W~LT{%Sf6n=eYE)W0cYB z=&y5!b2KLYO=!O+$$-i@k1iR{J5nVf3mU65p+gQ#QBb7Mb6&_3ubdpC-Vt*T#?0mf!^{Xd6n6Ed;<`HAJcSaDg+&Kr zRY6i%1G`U{K>Nr1v`ZAUXFO}-jv^xEpmG+9=CI2oan22XH9_H7Lf?nrgc!8^t)2^Q zK1l+4uINk1`m&efo1e5ppS(r|M4cl(#SOZ8R2XogM}nuG%cM+1oCr##1exg9Z9oSe z`(Q+}a@EQ{l7U2hK@cc=bk0I5YT7v&FJ2Fig=^0wyXKOoHd;$^Lcw5p3L=sWBrNns ztxYJGJhk9DgLMy9RaT$wlu}RNqjaDPkmY_-?-@L{5#u}woKOU)#JLQJN9>lF+}8kJ zXwJF($NVcvJ`ORfbd!ixt)=#`F3BltV&x2Pz97tnGsAzd(_gSHe#MB)v(Oa+C{fOrgYbb+3Q1AOq+1Y9L|_u#x*1MB8D>DUW(*+fQ)wk zRS>}rqjhRMEv8k_arI13N8mWMSZxo?ey~qNf`L@LEYl-jarRxtdU`61?B@SN|y~=J+^YYk(svC49GR*?rQ%rQa!<%LHX%^dy_4{$s zeZNvn+YD7sx>}*$Nj)ve%rb#pZ^48;Cr5);zju8uHD-}-WhElJ`UU3MWW}sXY|A&P ztFc?Uz(Y>#CR%k_n)4)2l-Hj^N1p!s?8=vtDD({gr_X!yM$Z?rdoXn&*oUq|bW3rM zVd>J3{#niwRoU%$^qcvaihb355Oa5#<-h3{&#qIKb?U6vMoepSPV&jAlv}K{H6B{+ zv;MF{iteqKEj~vcS|W0ajS7#I#Ci@9m+tUisz%)yfmsD>l<7XA8x+}DT@`8A!Bv0v zi;sMA8J%N~l+K)3ubs-J3(==ZjaxVF-OK6|6P>K%IU2-6c#7$slmUR11gFu^$(L>~ zmBU6yeq|?LGD6&XXBV5#Nt+a5+Y{7zJy&#N2xyI|a<#QlMBtl9CDwT$Aq4YeXVx;G zk`iN9y+5FmUyDsuw;*xK*N7`{g1=`+-7V;VSMk~@!JT3iRjx;DgEv(eI7osQV8JzA ze+-kX^`H`1uWOgLyLM6G^F*3c&QXd-tSo3p&-h_3iWiu zG6mV?&J)^F{BQ+$X)R+MX&210W7~6BPGrJJ53^(hDL@` zY7w=UsFYS6Bl$&sBCH)-zzIxz#9mJo>?{2QQWr|rS9pS|8R*oh<2jw3-#_>?jUU6; zDui}>K#!=xS!6VvB^r*_L7SfdK0FD{F>v=>G5wrmH0Vw^pF|-Yl$#{mEu))`Q{oDI z^OKXzFwSPm=PvZhMJt=_yy14g)<_pilM#$%ul3sg&5N@IbXfxCH$qS4BrlTA@!0zOeK%U-CBXo z${ny`OoeFQPi8xav$TOY=INZ`h$&7h*}$<|69{$89<>2M;Weh{ma_=2Hvw0qBd!LT zP-t%Jn(k;}C6rwe+OWU&*gqg#3~;xQEtu$dr=aZSU6oZTX{JZSQz8L_U#!Mg2pWmP zvzt%MLH=QiULqY#e4EyFm`K!@9!^65?!ovqlT#2?c;k}?vER^|*FT5uB0ByKJA=xN^aSK=_)CoY?pI(TwT6zH?3L=1?T4=kM zR?7zNED_bNtm28fGD7-hHMtuoews)`vU@UM#5a+uNgOM7K2>!osUEUdYP*1P;4BV6 z6yi&{9@NQFUO%7&hlM{`VQ_O~tO9@ft89Q(b;z@pxH@N9@is24gLW8boAgU759V-#f_>kXx6op$E0$E4?H~)_{Uze3=H~F8l_S63hNm=(_UU3oyBYTK*a3Wl$elqW_BFK+}Rrk{^TEAUXaG1x#X zz&b1_N%d_ULsUGBCJYI|vasw-coxTF|l<}%CT*Z*aqXRNdE5y+gVI4=r)hRx7m7%5^46tlK>;mpsKx+2? zlz_1+x(jjYkWtJU4N! z4}v=|wvzx=y|eX(xEk^VnoppDmr=cpDb^O;0wH=ItaFF~b>NAmh)0^5TE3h@Y7Qg9!fSO8 z_43nj?WCc4`l3$=1Y%g>b_2WGh^h})Vt4X7&nCEAP_;-oZA|=*bE5&R*zhhYy319= zKjjHUqlOWkOucgbG+-9I@Ar%~<<4PfC3H0PQ$K}vU>HAnfVo1bz#0YT$+QRIVDT~= zLZftuy1d}o*9;+Dy86X^gwQ}y8itqg(%0fWFq$;D(*FwD1Zza62h9j6I@akf=HTXG zP*nhbY35-c2Q&t~!G&tka4HK2ceZnKywOUp@4Sv3pvVC(SMz~r@9$Y7uJ!-L4p!`}52fhPs z>6zi!hMY_rotAYfO@l)Ag%`L(W!&Ysy}9>OT^&>OM>r|A^5TTaDx5$G4S&HvXEzV4 ze6m8Ju5{QjUXYgY2G=&<`WshZLcM50h4NFs2=$EK?SRTU!+N5C$U}}@Y)^D=&CP&5 z^+20$lz^X16CV&S6%eU8R83SG3R_f_Q%3D#TahO8;AM+Y82zeOE6697dFMKzo7F{6 zmg~ykNs5FMYXKYD`x7zE-jXrVG^W3R?)-G-0_PBE{jr)@zd<{A;bOvjHZl}t_RwYB zmJLBG1tinjSLC#RznKY`#selR6YV(eOJA%PE23f>b2u*WG5gPU47`XyT=SybG$?UV z+1=Td?hbYes_1ydUMbQ$>EjXt?U0lWT!yvIx_}g3#OgBiP!n}-L=-9hLFQ`jy*S8+ zAQITC-Q9&-%_m+Kc@?jp7o_9xwiOVtXE<9acsLtGrdEo)ZvZcLD0BBD{Dh!M&m z4J3;qgtn-}X&{I#7v1G=m`r4>xag6C_{tUCy~d`Q3!pezrDY7%iR}-9zdXU! zvLF_1{tCw7r5}t3uHWhr^TiizfuVEOb8RgeFmbFdISDWYZTbDW3it7xzcH?jQTGkGu2Zfx{hNC*oTe{*qQBy?PKVgp8re zVNxRk?(i9Q`ap;18-c;_?dIR0Dny$R7i~JomFrYf>)=iQ0ZID5{s;fgPgO~g*E?cZ zLv>BMY%(DGT*rRO#z@|&2k*iS#>i|Ex_Bp6Xn;6kQgKpWE!!6jG@Xl=`49g*mskG# zHqB_!T-^oLdYT}Drbk6V#0&Zt=b%~Tx;xok8T<3&w;a-<7cP;w7H>;|&uDccr+}ad zxj*cIH|GDrqWumY`rC%yV?=e5{ALU@)+=zdf;hopfHjMGmf{b|K@hth3gL}E1cioj;XL$)c_?u$Kjzw~lzc^}*CkYU&*or8)=GlHO;EcT= zp8}Q^X16ee!yi_TYDkJt;VmA?0N@sn)H6No0r}qA;|neef4tAUmcQb+L@A6(%s?I< zvNdtE(6|>_s}Y`~D&;l9?TsHV#SYDTuVaM!gndSbNM#O3FR0=I@PeL#8o=Modt>`4 zg?#S4!vg;Ejw#mo@n=u$NHMiZ(ila z@a%5i?&?qXfIo(QajQx1mu|H5JCkzYltvRz6?11gT;oRnbrHc@rBX8QBAjA$Q5AzgI95e44;TPEoD>`8*5n$ z-_qI{5Gzyxdjiz@41ZW);tj1MySUoOlL;8yE{K zzDWb0H8e9ZVuuI#+5l0-4&OYgOSvP-fn(I=9SNftF#iD?ZJ+68WNG7gkZIeHmmrD1 zMz;6FNh&^(DSey^p01%bl(@&mdAzEHEbjNjn{o^>biZn=s?ns1FSF1_r;wGntQC(f zYV9%L4ee$nmt19$-4yJ)V3d-KUUCqpWAN^_jZ2pyuMc8xvKFQ=Rc#-_xZqn~0!#kl z?@5ZgA;S&QG+a`&tT4rb?8l%YRSJIEHP?=d=sNK?&MpmA_!>%v)Bq&hxy3WrhJakq z@=KiPpsc^-87=7~=3m7{l_nq2h~po!3>yA)%XS?phL|2HbXTbxG+Db%S(!i3^F|ZB zWg#U!M`Lq;OghZ%kLuqKutam&*NmB~={Y3Bi}`YUM+?D?P!aDLUD0&f`8EX0NM3rG zQlsf40l!o#7GQy`O4BMe-5@?P6$j_9$`u`ZBkemSBd78C1;h+L`Nb#_mhi=8ECDZV zz>y!E%%M=+CAshxzg{fMMWSKXMabgyG}9crjbpVUi6Stv>AHf)8vmiJ!4EVX#6y)< zv|GcuhA1hA8wO-kHnJ6%7*ZDtQ?OzH{C+;B!MpM+>-wq4az583Xr+S)O;>iR9wVK` zQPUXAX2o>#B9e!--uoqVtpl>>dNiO|6xj>5oimKa%Q*a;%%d@i1KdLNsELgI~gKX<&J&&QyUG@SUnZW zG)K-sirKGG+8q@LVv44LOW_W!Re#D2xuHe4T!0HV2;>d-)Lg5DAr#1|r;?1S)p>~G z;Y5)FqlCGvTHj+@ENJp&zf_SZy0eXEXx-x>t-E4yKJ^SP?J<*G8TmZ(LlVEjP&-=K zc!WesT_FZx9`i!p?T-gI5n@v2Rt+q(UJT?^e>*u~gOKEMV)WIl&4+J(QVhUkYS|-N zE5woqm&gmOErMxa4r9k9ei@NR5XJ*3T(k_m@V_Ich>b_??s%I}wyq>{opw%`>w=_w z2(s`7I|g~hf{+}HOY6xVR2Ra4@0A(!^Se<6qR%O3okF1o=TCBB%LxMR4vbn5iX&@ z=ry;(bWLcPQH+{(NDyFlHA}eFt3K|3=`Cyicq-0t!*TA9!PFIm-_5#u71o6Y(EWzMhF>`g z0-|TZxgK#!(6BUb%>`ZxF5mooD!dRflWs^Fj)96TLE|_jI#$;qN|8@;w5^6RSdKFS zCtNBKYMUY=t@r}YW;&CuBjKVjc(!tDMVne#EO}_g*1ai-_WT`PGi;;A2(noYG%=_4Llk#i53~6dqB#P<%G&oH+gcCm4sH~P`6s2vBls2pr znZz(covn;9d8$;J{_{ij`vcaLUWgWpud$R3?&#s7!gW!y*4h{mAxmE>%=7{H;`6D4 zsVi;cIU0GT-$oy{f$Sb$A8^~@Zg1>VVP-?1 zQ<153Q-vcA-imlqb>j=l9}8#BA<2x4gH3rsC>Y|pNr@@e_Q)>s`>7PvJTeu>%T{;( z$yPk5^V`ub?fFs-U9~bop(MMJ?4yRFo=09Ptw;&3!sU{tVV2{{#0uy9+sZ3j z3kg;_e}U%jDI}GA!5Dgjx$I^d3iFYz)Qhk>jH^EfzQ_;mRe}=!E!&VYC&cld)~21Y zKIvwm>GPI34A_Yk^&c|vr2Z-XZE5OD;n0bRWY`?Ca3C$LTZ)O6I&xFahzl$ek0AF8 z`@d>+oH4oHZKUcGa9tl$s+%+$qaE{2WXqMxzEB)DO#j|BXq~JaW8n>ptLpyD)IwL* z=5VTKld#&*81WXtX;l~vMN{_xb~qQ;>@lH;paxOEG~@(0cU+`6F599EW!L5XpJ42 zHpZ(R_kpYQq^;9x@z2oh2#M*S4fpY=b3a-eSkcr7R+Vs<=i6uYaL6j(THNmbxsZ)<=Q6~f#su#h< z!+YQ^6%+RVY@j((CTB(sodt*oysK9Ds(w)U!rqYEAj#PRGOVVm;fYo2q zSgg?sPpSPFagLujz_f|#v81h9-=l|Obu4>p*v}mZ0XHXTqm8n`qT=ed2&6g9?!fFIl9*Fff000YsNkl`5k=L2RYZGo^8E2}sqkeX#vt&}ox5aG8H* z5TvadBJGN@I~dy4Py7oZN3SXotgfXN?D!gM2EL8V+&{Ol;%yU zgsKR#3%v9o3)xzzJkyq4Xj1tBhD94QVXDtBO96Q4we@MBOaXvbi5dILW|*`2D{Vz&x-Xfdfos#W+eYk4 z`-s+JoiP878@DSv^LuBIRH*Hsp^sPo751vskk}fFBckF-mWPHlgE5!9e~$#1a^d%r zK2I1UQ#o+`cJ!;xf*v2o*;`LCfGtQmwrL8yaHz^gIj1*!Y$OTH`v&bgwN$-kic75C z3^@iFgt#i%wKAo#tMD+9XR1h?*|o6HMq*W_EN~kY&EevFk(r~@8*8eVB9Xwr9eWhi zh&YYzo#ju#i(uf%2y7&A12gl^IC6>qr8Z$-r({In;qUZ++#~Zwufa_Z1=FW(sux_# z(P)G|`YzXfDa3b;0vR{#Lc_6Vs7pI1_fuQIUV%q<&bmfwV#yWZsvU)e*1@%0 z&zEG?&ro(gkgX1hP31PvZEK3VES-cyY5Jez>F@}*wwaFt+1n`7!*-gXGhFz^8QyHz z(NizF6QZ#sBBKL((t@E2oA%1HQ%E|UmT~BBP6+59cOOr7A(GyPgJ;A<$()3Wjo|6It`=a ze6v1Fit2e{l%IzkXS&nk-jwSVnn@aZ1-j@g`M|kZYJFUkSgD9hm?(=G-IG^1;~_b~ z@4RbC<>>rcBsH`5a69I92~>^QXB#)|*ekq;%Ssa-$1iO*?t62u?ssJmk20&#K0kW6 zAuqqrI|cd02&UTNty0t?UfDHAVusmjNa04I6|3JZTJzD)PNk0}$VXkq{e;+6#lFoy zu}wQ=@K%@w`ge>QmWBau)YxTb_~723ZrJ@AUku>wc4G;P0M6k)lN)npJ(J9uBY0#5 zyCI^C9*_D(w~vBLxE^no=c4AAd>4+5*z$lYagZ1zHp{A~hHr=zz$c$1*O%cn!EFlon#Z&Xt*W%zhJxLq~5 zIgK#kbKdVK9z$JT7WtI}$QARw{@`f#Koip?mq6sr?jxLiKV)78aMLfsPe zA7}CY!;kgKpB<>q@N_fx1Y-z-jm+UXfqK+zxe z$ekIKsF~`^>VET+zet|{H+^RQ|9hi;dvwj6C}`#k=Ls&_qk?^#N|b-IMQ@Mvmql$b z`lIgAk2*$w-?0b9q*wVXzUp1QeDgQONuNP_s8!Qrq+NtXQbF@W8IhZh_Ro&(&!6`C zGVg;yFB};9SeNVGUFGdwR3rDq6C>UHqfhv&gex!Z-s)yG(OqD{=4@j`HEUqeRk!7G zgc-kSuo_6-CkiYb&YvLuH?%F+JV@{-9NfF~-sW=tc*ULs;&A_T&wGATU!+UK6tCCo z6rgLGoOE@3@~@Zg{Rf7#Y(c_bj0las@&GI$w=U?e@tqmOFG+n*BlZ&;Egz zs<=q}g?xk$sl@=%gfB8p1Ft6iWXa#}Chq#EewH6})m}E>?F4g653MVJc)h1Tn$ee= z^02FK+Mv9$)P@MCu!%x}of+#5;BTLNJLI>;=Y3?ru)E!s4<{jRGMr|fmInAm&M5C! z;t>Hi1lor+U3BTo8s(#li6N5R*5PH>XeGHN1J^{rY>fwTh->+KlACL5I?R}9?b8eB z+ab@`pErLxe9ss8`olJDmotou&U?5B*6}GZ#`Rj=c7n}mw#!wZTI7A+@5Ski>EaNq z?K_$}G>o6&0-`zPqj&B1+qS@K9M?~Fm7a|y4;YJkXbN_56Y6|dYJS!fT-`%g0KEwx z+Bv3mmT}eFv6I)I!sIvJB01bG(j}tQJ+>_0`O{zoOl_qojPJfuolm%Q^ioeK>(;WSfQWIC(m!q2+&J;FTk!j}n{6E|!pSMOQ z*YzGhW^82L(i{Zu&Gc*WE0VL5nb!-_rCu9s>S_aOJdNr4qU6`&?uj-2k8VliE+{+l01Z|Ibb(kOAktb=YzLX zNEahI9E{t- zG$jw=2r*M37DYs~V0h@9aXlK#8cT%8Q~>gayUr=ynXX4{xzeK5%o9pcir^P1lM;nM+^Fb-ztI%jKdhy%?+Ava%~93lSKI zYYs447I}MmJk$V6CuwVMbu{DBBrR(=1i=!%9myA~WX!|S0rJ-%aD39txoFeVoV$zo z@!TSW{Z%k?zFGIBQb5FRnF&f!NjYk zXS*pbxzA0r@95VfT8<`02pYNSe7FQzxEy#ouuk#~9g2m?X5=+|4)_2G)hdvL&l?}; zYp)903-lYpEN8#7APn`RnIm^$*tPB0{IlR2S&R=Z(8E;+KVqk~q~2Bhv$Vw!KG-P!dbjD~Jnc-51b135@x3*y;)smGXp z{8BC*eJ@j+z`Vnav^geM3kzw|#9b_$uC$km;~TTHGAUCK=!kfDDNfLBiRMJ>eqlt! zmK>RdAtB8IQ-?8GPr<=}AiluhgmbNMY%v{N$~|mASD1d`0yM>dlGy>$961qNTM-ZK zC}}K2lM6A)iL~YRA@VEJzjhn0CDJmbWzSmUrRUd;qF7H$X2$h4`uZ=0n@C<~Ia?Ts zR+{~f|MMT=DtlN7hKZo + + + + + true + + + + + ../media/heightmap_bowl.png + 129 129 10 + 0 0 0 + + + + + + + + 0 0 7 0 0 0 + + + + 0.4 + 0 + 0 + 0.4 + 0 + 0.4 + + 1.0 + + + + + 1 + + + + + + + + 1000 1000 7 0 0 0 + + + + 0.4 + 0 + 0 + 0.4 + 0 + 0.4 + + 1.0 + + + + + 1 + + + + + + +