AGX Dynamics 2.38.0.0
Loading...
Searching...
No Matches
agxTerrain::Terrain Class Reference

A terrain model based a 3D grid model with overlapping height field that can be deformed by interacting shovels objects performing digging motions, converting solid mass to dynamic mass which can be moved. More...

#include <Terrain.h>

+ Inheritance diagram for agxTerrain::Terrain:

Classes

struct  offsetIndexInfo
 

Public Types

enum class  MassType { SOLID , PARTICLE , FLUID }
 
enum class  MaterialType { TERRAIN , PARTICLE , AGGREGATE }
 
- Public Types inherited from agx::Component
typedef Event2< Component *, Object * > ObjectEvent
 Event when adding removing child objects.
 
typedef Callback1< Object * > TraverseCallback
 
- Public Types inherited from agx::Object
typedef agx::observer_ptr< const EventEventConstObserver
 
typedef agx::ref_ptr< const EventEventConstRef
 
typedef agx::observer_ptr< EventEventObserver
 
typedef agx::Vector< EventObserverEventObserverVector
 
typedef agx::VectorPOD< Event * > EventPtrVector
 
typedef agx::ref_ptr< EventEventRef
 
typedef agx::Vector< EventRefEventRefVector
 

Public Member Functions

 Terrain (size_t resolutionX, size_t resolutionY, agx::Real elementSize, agx::Real maximumDepth)
 Constructor.
 
 Terrain (size_t resolutionX, size_t resolutionY, agx::Real elementSize, const agx::RealVector &heights, bool flipY, agx::Real maximumDepth)
 Constructor.
 
bool add (Shovel *shovel)
 Adds a shovel object in the terrain.
 
bool addNoMergeZoneToGeometry (agxCollide::Geometry *geometry, agx::Real extensionDistance)
 Add disable merge and avalanche inside geometry bound with added extension distance.
 
bool addTerrainMaterial (TerrainMaterial *terrainMaterial)
 Add a non default TerrainMaterial to the terrain instance, without designating its domain.
 
int addTerrainMaterial (TerrainMaterial *terrainMaterial, agxCollide::Geometry *geometry)
 Add a non default TerrainMaterial to the designated region bounded by the overlap between the terrain and the given geometry.
 
agx::Real calculateTotalDynamicMass () const
 
agx::Real calculateTotalFluidMass () const
 
agx::Real calculateTotalMass () const
 
agx::Real calculateTotalSolidMass () const
 
agx::Real calculateVolume ()
 
void clearTerrainMaterials (bool clearAddedMaterials=true)
 
bool contains (const Shovel *shovel) const
 Check is a shovel object is registered in the terrain.
 
void convertToDynamicMassInShape (agxCollide::Shape *shape)
 Converts the terrain occupancy that overlaps the specified shape into dynamic mass.
 
bool exchangeTerrainMaterial (TerrainMaterial *oldTerrainMaterial, TerrainMaterial *newTerrainMaterial)
 Exchange an already added TerrainMaterial with another TerrainMaterial without changing its associated agx::Material or assigned domain.
 
agx::Real getAggregateTerrainContactArea (const Shovel *shovel, Shovel::ExcavationMode excavationMode) const
 Get the aggregate <-> terrain contact area given an excavation mode and a shovel.
 
agx::Vec3 getAggregateTerrainContactForce (const Shovel *shovel, Shovel::ExcavationMode excavationMode) const
 Get the aggregate contact force with the terrain given an excavation mode and a shovel.
 
agxCollide::GeometryContactPtrVector getAggregateTerrainContacts (const Shovel *shovel, Shovel::ExcavationMode excavationMode) const
 Get the aggregate <-> terrain geometry contacts given an excavation mode and a shovel.
 
agx::Vec3 getAggregateTerrainNormalForce (const Shovel *shovel, Shovel::ExcavationMode excavationMode) const
 Get the aggregate normal force with the terrain given an excavation mode and a shovel.
 
agx::Vec3 getAggregateTerrainTangentialForce (const Shovel *shovel, Shovel::ExcavationMode excavationMode) const
 Get the aggregate tangential force with the terrain given an excavation mode and a shovel.
 
agx::MaterialgetAssociatedMaterial (TerrainMaterial *terrainMaterial) const
 
agx::Vec2i getClosestGridPoint (const agx::Vec3 &worldPosition, bool clampToBound=false) const
 Finds the closes terrain grid point given any point in world.
 
agx::Vec3 getContactForce (const Shovel *shovel) const
 Given geometry contacts exists and the solver has solved them - calculates total shovel contact force between this terrain and the given shovel.
 
agx::ContactMaterialgetContactMaterial (Terrain::MaterialType type1, Terrain::MaterialType type2)
 Returns one of the internal contact materials in agxTerrain.
 
TerrainMaterialgetDefaultTerrainMaterial () const
 Returns the default terrain material which is used to derive material and contact material parameters.
 
bool getDeformable () const
 Gets whether or not deformations are enabled for this terrain.
 
agx::Vec3 getDeformationContactForce (const Shovel *shovel) const
 Given geometry contacts exists and the solver has solved them - calculates total contact force between the terrain deformation soil aggregate and the given shovel.
 
agx::Real getDynamicMass (const Shovel *shovel) const
 
agx::Real getElementSize () const
 Returns the element size of a cell in agxTerrain, which is incidentally the distance between the center of each grid point in the surface height field.
 
bool getEnable () const
 
agx::Vec3 getExcavationModeContactForce (const Shovel *shovel, Shovel::ExcavationMode excavationMode) const
 calculates total contact force between the soil aggregate associated with the specified excavation mode and the given shovel.
 
virtual agxCollide::GeometrygetGeometry () const override
 
agx::Real getHeight (const agx::Vec2i &terrainIndex, bool includeSurfaceParticles=false) const
 Gets the terrain height at a specific terrain grid node.
 
const agxCollide::HeightFieldgetHeightField () const
 
agx::Real getInnerVolume (const Shovel *shovel) const
 
bool getIntersectingActiveGridElements (agxCollide::Geometry *geometry, agx::Vec3iVector &gridPoints, MassType massType) const
 Get intersecting 3D grid element with specified geometry that is active/occupied with a specified mass type.
 
bool getIntersectingGridElements (agxCollide::Geometry *geometry, agx::Vec3iVector &gridPoints) const
 Get intersecting 3D grid element with specified geometry.
 
agx::AffineMatrix4x4 getInverseTransform () const
 
agx::Real getLastDeadLoadFraction (const Shovel *shovel) const
 Get the last computed dead load fraction of the shovel, i.e how much of it's inner volume that is filled with dynamic soil.
 
agx::Real getLastExcavatedVolume () const
 
agx::MaterialgetMaterial (Terrain::MaterialType type=Terrain::MaterialType::TERRAIN) const
 Returns one of the internal materials in agxTerrain: MaterialType::TERRAIN - The internal material used on the terrain surface height field structure.
 
agx::RealVector getMaterialWeightsInGridPoints (const agx::Vec3iVector &gridPoints) const
 Get the material weights in the terrain of the specified grid points.
 
agx::RealVector getMaterialWeightsInLine (const agx::Line &line) const
 Get the material weights in the terrain of the voxels that intersect the specified line.
 
size_t getMemoryUsage ()
 Returns the memory usage in bytes in agxTerrain.
 
agx::Real getMinimumAllowedHeight () const
 
const ModifiedVerticesVectorgetModifiedParticleVertices () const
 Returns the modified terrain height field (including particles) vertices during the last time step.
 
const ModifiedVerticesVectorgetModifiedVertices () const
 Returns the modified terrain height field vertices during the last time step.
 
bool getNoMerge ()
 Return whether this terrain is prevented from merging dynamic mass to it.
 
size_t getNumCreatedParticles () const
 Return the number of soil particles created during excavation this time step.
 
size_t getNumSoilParticles () const
 Return the number of soil particles active in the simulation.
 
float getParticleNominalRadius () const
 Get the soil particle nominal radius from the simulation.
 
const ModifiedVerticesVectorgetParticleVertices () const
 Returns the terrain vertices that contains soil particles during the last time step.
 
bool getPenetrationForce (const Shovel *shovel, agx::Vec3 &force, agx::Vec3 &torque) const
 The result includes the active force and torque from the penetration resistance from the terrain on the shovel if the shovel is digging in the terrain.
 
agx::Vec3 getPosition () const
 
TerrainPropertiesgetProperties () const
 
agx::RealVector getResizedHeightField (size_t factorX, size_t factorY) const
 Calculate a reduced version of the height field structure.
 
size_t getResolutionX () const
 
size_t getResolutionY () const
 
agx::Quat getRotation () const
 
agx::Vec3 getSeparationContactForce (const Shovel *shovel) const
 Given geometry contacts exists and the solver has solved them - calculates total contact force between the terrain soil particle aggregate and the given shovel.
 
agx::Vec3 getSeparationFrictionForce (const Shovel *shovel) const
 Given geometry contacts exists and the solver has solved them - calculates total contact friction force between the terrain soil particle aggregate and the given shovel.
 
agx::Vec3 getSeparationNormalForce (const Shovel *shovel) const
 Given geometry contacts exists and the solver has solved them - calculates total contact normal force between the terrain soil particle aggregate and the given shovel.
 
agx::ContactMaterialgetShovelAggregateContactMaterial (const Shovel *shovel, Shovel::ExcavationMode mode=Shovel::ExcavationMode::PRIMARY) const
 Get the explicitly set contact material in a shovel-aggregate contact corresponding to a specified excavation mode for a specific shovel-terrain pair.
 
agxCollide::GeometryContactPtrVector getShovelAggregateContacts (const Shovel *shovel, Shovel::ExcavationMode excavationMode) const
 Get the shovel <-> aggregate contacts with the terrain given an excavation mode and a shovel.
 
ShovelRefVector getShovels () const
 Return the shovels currently added in the terrain.
 
agx::Vec2 getSize () const
 Returns the total surface size of he terrain in X Y coordinate system.
 
agx::Real getSoilAggregateMass (const Shovel *shovel, Shovel::ExcavationMode excavationMode) const
 Returns the total soil aggregate mass in a terrain given a shovel and a specific excavation mode.
 
const agxCollide::HeightFieldgetSoilParticleBoundedHeightField () const
 Get the soil particle height field consisting of the highest point of either the terrain surface or the highest particle position in each terrain index.
 
SoilParticleStatistics getSoilParticleStatistics () const
 Get basic statistics of the soil particles active in the simulation.
 
SoilSimulationInterfacegetSoilSimulationInterface () const
 Get the soil particle system interface used to represent the dynamic mass in the terrain.
 
agx::Vec3 getSurfacePosition (const agx::Vec2i &terrainIndex, bool includeSurfaceParticles=false) const
 Finds the terrain surface position, given in local coordinate frame, for a specified terrain index.
 
agx::Vec3 getSurfacePositionWorld (const agx::Vec2i &terrainIndex, bool includeSurfaceParticles=false) const
 Finds the terrain surface world position for a specified terrain index.
 
const TerrainContactRefVectorgetTerrainContacts () const
 
TerrainGridControlgetTerrainGridControl () const
 Get control interface of the terrain grid data.
 
TerrainMaterialgetTerrainMaterial () const
 Returns the default terrain material which is used to derive material and contact material parameters.
 
TerrainMaterialgetTerrainMaterial (agx::Vec3 position) const
 Returns the terrain material at the specific position which is used to derive material and contact material parameters.
 
TerrainToolCollectiongetToolCollection (const Shovel *shovel) const
 
const TerrainToolCollectionRefVectorgetToolCollections () const
 
agx::Real getTotalSoilParticleMass () const
 Get the total mass (kg) of the active soil particles in the simulation.
 
agx::AffineMatrix4x4 getTransform () const
 
agx::Vec3 getUpDirection () const
 Returns the world up direction of the terrain.
 
agx::Real getVoxelArea () const
 
agx::Real getVoxelVolume () const
 
bool hasOverlap (const agxCollide::Geometry *geometry) const
 Return true if the specified geometry bounding volume overlaps the terrain geometry bounding volume.
 
bool isBorderIndex (const agx::Vec2i &terrainIndex) const
 Checks if the specified index is at the border of the terrain.
 
bool isDigging (const Shovel *shovel) const
 Check if the specified shovel is currently in digging mode with the terrain, i.e if the cutting edge is submerged.
 
bool isGeometryShovel (const agxCollide::Geometry *geometry) const
 Checks if the specified geometry's rigid body is contained in any of the terrain object's registered shovels.
 
bool isIndexWithinBounds (const agx::Vec2i &terrainIndex) const
 Checks if the specified index is within bound of the terrain [(0,0) -> (resolutionX, resolutionY)].
 
bool isLocalPositionWithinBounds (const agx::Vec3 &position) const
 Checks whether the position is within terrain (x,y) position bounds in local space.
 
bool isOfHomogeneousTerrainMaterial () const
 
bool isRigidBodyShovel (const agx::RigidBody *body) const
 Checks if a specified rigid body is contained in any of the terrain object's registered shovels.
 
bool isWorldPositionWithinBounds (const agx::Vec3 &position) const
 Checks whether the position is within terrain (x,y) position bounds in world space.
 
bool loadLibraryMaterial (const agx::String &materialName)
 Loads a TerrainMaterial preset in the TerrainMaterialLibrary that contains calibrated bulk and contact properties for a predefined material archetype.
 
bool loadMaterialFile (const agx::String &filename)
 Load a TerrainMaterial from a specification file in JSON data format.
 
agx::Bool projectPointToSurface (const agx::Vec3 &worldPosition, agx::Vec3 &result) const
 Project a world point to the grid surface.
 
bool remove (Shovel *shovel)
 Removes a shovel object in the terrain, if it exists.
 
float removeFluidMassInGeometry (agxCollide::Geometry *geometry, float fluidMass)
 Remove fluid mass (in kg, NOT occupancy) in the intersecting 3D grid element with specified geometry.
 
void removeModifiedParticleVertice (agx::Vec2i terrainIndex)
 Removes a vertex from the vector with vertices that were modified during the last time step.
 
bool removeNoMergeZoneToGeometry (agxCollide::Geometry *geometry)
 remove disable merge and avalanche inside geometry bound with added extension distance
 
bool removeTerrainMaterial (TerrainMaterial *terrainMaterialToRemove)
 
bool setAssociatedMaterial (TerrainMaterial *terrainMaterial, agx::Material *material)
 Set the associated material with the given TerrainMaterial.
 
void setCompaction (agx::Real compaction, bool replaceCompactedSoil=true) const
 Set a compaction for all current active solid grid elements in the Terrain object.
 
void setDeformable (bool deformable)
 Sets if deformation should be enabled on this terrain.
 
void setEnable (bool enable)
 Set if terrain computations should be enabled.
 
void setHeight (const agx::Vec2i &terrainIndex, agx::Real height)
 Sets Terrain height at a specific terrain grid node.
 
bool setHeights (const agx::RealVector &heights, bool flipY=false, bool resetCompaction=true)
 Set height values of all sampled points.
 
void setMaterial (agx::Material *material, Terrain::MaterialType type=Terrain::MaterialType::TERRAIN)
 Assign new material to this terrain.
 
void setNoMerge (bool noMerge)
 Prevent merge of dynamic mass to this terrain.
 
void setNoMergeEdgeMargin (size_t noMergeEdgeMargin)
 Add disable merge and avalanche a number of indices from the terrain edge.
 
void setPosition (const agx::Vec3 &position)
 Set the position of this terrain.
 
void setRotation (const agx::Quat &rotation)
 Set the rotation of this terrain.
 
bool setShovelAggregateContactMaterial (const Shovel *shovel, agx::ContactMaterial *contactMaterial, Shovel::ExcavationMode mode=Shovel::ExcavationMode::PRIMARY)
 Explicitly set contact material properties in a shovel-aggregate contact for a specific excavation mode for a specific shovel-terrain pair.
 
void setTerrainMaterial (TerrainMaterial *terrainMaterial, agx::Material *material=nullptr)
 Set the default terrain material for the bulk of the terrain which is used to derive material and contact material parameters.
 
void setTransform (const agx::AffineMatrix4x4 &transform)
 Set the transform of this terrain.
 
agx::Vec3 transformPointToTerrain (const agx::Vec3 point) const
 Transform point given in world coordinate frame to local coordinate frame of this terrain.
 
agx::Vec3 transformPointToVoxelSpace (const agx::Vec3 point) const
 Transform point given in world coordinate frame to local coordinate frame of this terrain.
 
agx::Vec3 transformPointToWorld (const agx::Vec3 point) const
 Transform point given in local coordinate frame of this terrain, to world coordinate frame.
 
agx::Vec3 transformVectorToTerrain (const agx::Vec3 vector) const
 Transform vector given in world coordinate frame to local coordinate frame of this terrain.
 
agx::Vec3 transformVectorToWorld (const agx::Vec3 vector) const
 Transform vector given in local coordinate frame of this terrain, to world coordinate frame.
 
void triggerForceAvalancheAll ()
 Triggers initial avalanching on all indices in the terrain.
 
- Public Member Functions inherited from agxSDK::TerrainInstance
void addEventListener (agxSDK::StepEventListener *listener)
 
virtual agxCollide::GeometrygetGeometry () const
 
agxSDK::SimulationgetSimulation () const
 
bool removeEventListener (agxSDK::StepEventListener *listener)
 
- Public Member Functions inherited from agx::Component
 Component (const agx::Name &name=agx::Name(), agx::Model *model=agx::Component::ClassModel(), agx::Device *device=nullptr)
 
virtual void addObject (agx::Object *object, bool assignContext=true)
 Add an object to the component.
 
virtual String autoComplete (const String &partialName, StringVector &matchingNames) const
 
virtual void buildNavigationTree (agxJson::Value &eNode) const override
 
void configure (Model *model)
 
virtual void configure (TiXmlElement *eComponent) override
 
agx::DevicegetDevice ()
 
template<typename T >
T * getDevice ()
 
const agx::DevicegetDevice () const
 
template<typename T >
const T * getDevice () const
 
size_t getNumObjects (const agx::Name &name) const
 
agx::ObjectgetObject (const agx::Name &name, agx::Model *model, size_t index=0)
 
const agx::ObjectgetObject (const agx::Name &name, agx::Model *model, size_t index=0) const
 
agx::ObjectgetObject (const agx::Name &name, size_t index=0)
 
template<typename T >
T * getObject (const agx::Name &name, size_t index=0)
 
const agx::ObjectgetObject (const agx::Name &name, size_t index=0) const
 
template<typename T >
const T * getObject (const agx::Name &name, size_t index=0) const
 
const agx::ObjectRefVectorgetObjects () const
 
template<typename T >
void getObjects (agx::ObjectPtrVector &result, bool recursive=false) const
 
void getObjects (agx::ObjectPtrVector &result, const agx::Model *model, bool recursive=false) const
 
virtual ObjectgetResourceImpl (const Path &path, agx::Model *model) override
 
virtual void printSubtree () const override
 
void printSubtree (std::ostream &stream, int depth=0) const
 
virtual void rebind () override
 
void removeAllObjects ()
 Remove all components.
 
virtual void removeObject (agx::Object *object)
 Remove an object from the component.
 
void removeObject (const agx::Name &name, size_t index=0)
 Remove an object with a specified name (and optional index) from the component.
 
virtual void snapshot (TiXmlNode *eParent, const String &directory) const override
 
void traverse (ComponentVisitor *)
 
void traverse (const TraverseCallback &callback)
 
- Public Member Functions inherited from agx::Object
 Object (const Name &name=Name(), Model *model=Object::ClassModel())
 
void addListener (EventListener *listener)
 
virtual void buildNavigationTree (agxJson::Value &eNode) const
 
virtual void configure (TiXmlElement *)
 
agx::String fullName () const
 
agx::String fullPath () const
 
agx::String fullPath (const agx::Object *root) const
 
template<typename T >
T * getAutoScopedResource (const agx::Path &path)
 
template<typename T >
const T * getAutoScopedResource (const agx::Path &path) const
 
agx::ObjectgetAutoScopedResource (const agx::Path &path, agx::Model *model=nullptr)
 
const agx::ObjectgetAutoScopedResource (const agx::Path &path, agx::Model *model=nullptr) const
 
agx::ObjectgetContext ()
 
template<typename T >
T * getContext ()
 
const agx::ObjectgetContext () const
 
template<typename T >
const T * getContext () const
 
agx::UInt32 getId () const
 
const agx::NamegetImplementationName () const
 
agx::ModelgetModel ()
 
const agx::ModelgetModel () const
 
const agx::NamegetName () const
 
agx::ObjectgetNextSibling ()
 
const agx::ObjectgetNextSibling () const
 
agx::Path getPath () const
 
agx::Path getPath (const agx::Object *root) const
 
template<typename T >
T * getResource (const agx::Path &path)
 
template<typename T >
const T * getResource (const agx::Path &path) const
 
agx::ObjectgetResource (const agx::Path &path, agx::Model *model=nullptr)
 
const agx::ObjectgetResource (const agx::Path &path, agx::Model *model=nullptr) const
 
virtual agx::ObjectgetResourceImpl (const agx::Path &path, agx::Model *model)
 
agx::ObjectgetRootContext ()
 
const agx::ObjectgetRootContext () const
 
bool hasListener (EventListener *listener)
 
bool hasParent (const agx::Object *node) const
 
bool isUnique () const
 
virtual void printSubtree () const
 
virtual void rebind ()
 
void removeListener (EventListener *listener)
 
virtual void save (TiXmlElement *) const
 
virtual void setContext (agx::Object *context)
 
void setId (UInt32 id)
 
void setModel (agx::Model *model)
 Set the object model (handled automatically).
 
void setName (const agx::Name &name)
 Set the name of the object.
 
virtual void snapshot (TiXmlNode *, const String &) const
 
- Public Member Functions inherited from agx::Referenced
 Referenced ()
 Default constructor.
 
 Referenced (const Referenced &)
 
template<typename T >
T * as ()
 Subclass casting.
 
template<typename T >
const T * as () const
 
template<typename T >
T * asSafe ()
 Safe subclass casting, return nullptr if template type does not match.
 
template<typename T >
const T * asSafe () const
 
int getReferenceCount () const
 
template<typename T >
bool is () const
 Subclass test.
 
Referencedoperator= (const Referenced &)
 Assignment operator. Will increment the number of references to the referenced object.
 
void reference (void *ptr=nullptr) const
 Explicitly increment the reference count by one, indicating that this object has another pointer which is referencing it.
 
void unreference (void *ptr=nullptr) const
 Decrement the reference count by one, indicating that a pointer to this object is referencing it.
 
void unreference_nodelete () const
 Decrement the reference count by one, indicating that a pointer to this object is referencing it.
 
- Public Member Functions inherited from agxStream::Serializable
virtual ~Serializable ()
 Destructor for normal C++ use but hidden from SWIG bindings.
 
virtual const char * getClassName () const
 
bool getEnableSerialization () const
 
bool getEnableUuidGeneration ()
 
agx::UInt32 getIndex () const
 This index is given at creation of this object.
 
virtual StorageAgent * getStorageAgent () const =0
 
agx::Uuid getUuid () const
 
bool isFinished () const
 
void setEnableSerialization (bool flag)
 Set to false to disable serialization of this object.
 
void setFinished ()
 Tells this class that it is restored correctly and should not be deleted during destruction of an Archive.
 
void setUuid (const agx::Uuid &uuid)
 Explicitly set a Uuid on a serializable object.
 

Static Public Member Functions

static TerraincreateFromHeightField (const agxCollide::HeightField *heightField, agx::Real maximumDepth)
 Creates a terrain object by using an existing height field as a basis.
 
static Terrainfind (const agxSDK::Simulation *simulation, const agx::Name &name)
 Find first terrain with given name.
 
static Terrainfind (const agxSDK::Simulation *simulation, const agx::Uuid &uuid)
 Find terrain with given UUID.
 
static TerrainPtrVector findAll (const agxSDK::Simulation *simulation)
 Finds all terrains in the given simulation.
 
static TerrainPtrVector findAll (const agxSDK::Simulation *simulation, const agx::Name &name)
 Find all terrains with given name.
 
static agx::StringVector getAvailableLibraryMaterials ()
 Get the available TerrainMaterial presets from the TerrainMaterialLibrary that contains calibrated bulk and contact properties for a predefined material archetype.
 
static agx::Bool getEnableKinematicForParticles (const agx::RigidBody *rb)
 
static TerrainMaterialgetLibraryMaterial (const agx::String &materialName)
 Loads a TerrainMaterial preset in the TerrainMaterialLibrary that contains calibrated bulk and contact properties for a predefined material archetype.
 
static TerrainMaterialgetMaterialFromFile (const agx::String &filename)
 Load a TerrainMaterial from a specification file in JSON data format.
 
static agx::Real getTerrainParticlePackingRatio ()
 
static void setEnableKinematicForParticles (agx::RigidBody *rb, agx::Bool enable)
 Enable/disable particles to see this rigid body as kinematic regardless of current motion control.
 
- Static Public Member Functions inherited from agx::Component
static Component_load (TiXmlElement *eComponent, Device *device)
 
static agx::ModelClassModel ()
 
static Componentload (const Path &path, const Name &implementation, Device *device, const Path &_namespace=Path())
 
static Componentload (const String &path, const Path &_namespace=Path())
 
static Componentload (const String &path, Device *device, const Path &_namespace=Path())
 
static Componentload (TiXmlElement *eComponent, Device *device)
 
- Static Public Member Functions inherited from agx::Object
static agx::ModelClassModel ()
 
static agx::String generateName (const agx::String &bindPath)
 
static const HashSet< Object * > & getActiveObjects ()
 
static bool getEnableRebind ()
 Should rebinding be allowed? Right now a global setting.
 
static Objectload (const String &path, Device *device, const String &type, const String &attribute, const String &value)
 
template<typename T >
static T * load (const String &path, Device *device, const String &type, const String &attribute, const String &value)
 
static Objectload (const String &path, Device *device, const String &type="", size_t instance=0)
 
template<typename T >
static T * load (const String &path, Device *device, const String &type="", size_t instance=0)
 
static void load (const String &path, Device *device, ObjectPtrVector &loadedObjects)
 
static Objectload (TiXmlElement *eObject, Device *device)
 
template<typename T >
static T * load (TiXmlElement *eObject, Device *device)
 
static TiXmlDocument openDocument (const String &path)
 
static void setEnableRebind (bool flag)
 Sets if rebinding of objects should be allowed (Right now a global setting).
 
- Static Public Member Functions inherited from agx::Referenced
template<typename T >
static bool ValidateCast (const Referenced *object)
 
- Static Public Member Functions inherited from agxStream::Serializable
static void setEnableUuidGeneration (bool flag)
 Specify if there should be UUID:s generated for each new Serializable object. By default it is enabled.
 

Protected Types

using GoToStopCondition = std::function< bool(const agx::Vec3i &index)>
 
typedef struct agxTerrain::Terrain::offsetIndexInfo offsetIndexInfo
 
using ParticleIslandVector = agx::Vector< agx::Vector< std::pair< agx::Vec3i, offsetIndexInfo > > >
 

Protected Member Functions

 Terrain ()
 Default constructor used in serialization.
 
 Terrain (agxCollide::HeightField *heightField, agx::Real maximumDepth)
 
virtual ~Terrain ()
 
bool _getIntersectingGridElements (BasicGrid *grid, agxCollide::Geometry *geometry, agx::Vec3iVector &gridPoints, bool isOccupied=true) const
 
const agx::AffineMatrix4x4_getInverseTransform () const
 
const agx::AffineMatrix4x4_getInvVoxelSpaceTransform () const
 
const agx::AffineMatrix4x4_getTransform () const
 
const agx::AffineMatrix4x4_getVoxelSpaceTransform () const
 
void addDirtyVoxelsToAvalanche ()
 
void addModifiedParticleTerrainIndex (const agx::Vec2i &terrainIndex)
 
void addNeighbours (agxData::LocalVector< agx::Vec3i > &indexQueue, agx::Vec3i index)
 
virtual void addNotification () override
 Add notification executed when terrain is added to a simulation.
 
void applyFluidMassChanges (agx::HashTable< agx::Vec3i, float > &fluidMassTable)
 
void avalanche ()
 
void calculateFluidMassTransport (agx::HashTable< agx::Vec3i, float > &fluidMassTable)
 
SoilParticlePtrVector calculateParticlesInContactWithSurfaceGraph (agxCollide::GeometryPtrVector &contactGeometries)
 
void calculateShovelVoxelIntersection ()
 
agx::Real calculateSurfaceHeightFromVoxelIndex (const agx::Vec3i &voxelIndex)
 
void computeForbiddenBounds ()
 
void computeParticleGrowthTables (const agx::UInt64Vector &particleIndices, ParticleDeltaVector &particles)
 
agx::Real convertFluidMassToOccupancy (agx::Real mass) const
 
agx::Real convertFluidOccupancyToMass (agx::Real occupancy) const
 
float convertOccupancyToParticleRadius (float occupancy) const
 
float convertParticleRadiusToOccupancy (float radius) const
 
float convertParticlesToSolidMass (agx::Vec3i voxel, ParticleWeightPairVector particles, float occupancyToRemove, agx::Vec3iVector &changedIndices)
 
void convertRemovedOccupancyToDynamicMass ()
 
void convertVoxelsInActiveZonesToDynamicMass ()
 
void createFluidMassInVoxel (const agx::Vec3i &voxelIndex, agx::Real32 amount)
 
void createFluidMassOnTerrainSurface (const agx::Vec2i &terrainIndex, int surfaceVoxelOffset, agx::Real32 amount)
 
void createParticleIslands (ParticleIslandVector &particleIslands)
 
void createSoilParticles ()
 
agx::TaskGroupRef createTask_preCollide ()
 
void debugRenderContactGeometryVoxels ()
 
void debugRenderForbiddenBounds ()
 
void debugRenderShovelForbiddenBounds ()
 
void enforceIncompressibilityColumnwise ()
 
void filterParticlesAboveContactGeometryVoxels (agx::HashTable< agx::Vec2i, agx::Vec4 > &contactPositionTable, agxTerrain::SoilParticlePtrVector &particles)
 
agx::Real findNewHeightFromVoxelIndex (const agx::Vec3i &index)
 
bool findPathToSurfaceVoxel (const agx::Vec3i &startVoxel, std::deque< agx::Vec3i > &result)
 
bool findSurfaceVoxel (const agx::Vec3i &index, agx::Vec3i &result) const
 
TerrainIndexSet findTerrainIndices (agxTerrain::SoilParticlePtrVector &particles)
 
agx::Real generateRandomNumber ()
 
agx::Vec3 generateRandomSoilParticlePositionPerturbation (agx::Real maxDelta)
 
agx::Quat generateRandomSoilParticleRotation ()
 
AvalancheControllergetAvalancheController () const
 
float getDynamicMassCompaction (const agx::Vec3i &voxelIndex) const
 
agx::Real getMergeSpeedSquared () const
 
agx::HashVector< agx::Vec2i, agx::IntgetShovelHeightPerColumn ()
 
bool getSurfaceVoxel (const agx::Vec3i &voxelIndex, agx::Vec3i &result) const
 
agx::Vec3 getValidParticlePosition (const agx::Real radius, const agx::Vec3i &index, const agx::Vec3 &pos)
 
agx::Vec3f getVoxelVelocity (const agx::Vec3i &voxelIndex, agx::HashTable< agx::Vec3i, size_t > &shovelVoxels)
 
agx::Vec3i goToBoundaryVoxel (const agx::Vec3i &start) const
 
agx::Vec3i goToSurfaceVoxel (const agx::Vec3i &start) const
 
agx::Vec3i goToVoxelKernel (const agx::Vec3i &start, const GoToStopCondition &stopCondition) const
 
void growLargeParticlesFromParticleMass (ParticleDeltaVector &particles, float particleRadiusUpperLimit)
 
void growParticlesFromFluidMass (agx::Vec3i binIndex, int binVoxels, float availableFluidMass, ParticleDeltaVector &particles)
 
void growSmallParticlesFromParticleMass (ParticleDeltaVector &particles, float particleRadiusUpperLimit)
 
bool hasVoxelCompaction (const agx::Vec3i &index) const
 
void initBuildIslandTask ()
 
void initializeFromHeightField ()
 
void initializeSurfaceHeightFieldFromVoxelGrid ()
 
void initVoxelStructureFromHeightField (bool adjustForCompaction=false)
 
bool isDirty ()
 
bool isFilledSolidVoxel (const agx::Vec3i &index) const
 
agx::Bool isIndexWithinBoundsIssueWarning (const agx::Vec2i &terrainIndex) const
 
bool isSolidBoundaryVoxel (const agx::Vec3i &index) const
 
bool isSubmergedVoxel (const agx::Vec3i &index) const
 
bool isSurfaceVoxel (const agx::Vec3i &index) const
 Surface voxel functions.
 
bool isVoxelWithinTerrainIndexBounds (const agx::Vec3i &index) const
 
virtual void last () override
 Callback to be executed at the end of the time step.
 
void markVoxelToAvalanche (const agx::Vec3i &changedVoxel)
 
agx::Vec3iVector mergeCuttingEdgeColumn (agx::Vec3i cuttingEdgeVoxel, size_t numVoxelsToSurfaceThreshold, agx::Plane cuttingPlane)
 
bool mergeFluidMass ()
 
void mergeParticleIslands (const ParticleIslandVector &particleIslands, agxData::LocalVector< agx::Vec3i > &mergedParticleIndices)
 
void mergeSoilParticlesAndFluidMass ()
 
void mergeSoilToCuttingEdge ()
 
void moveEntityDataToCurrentThread ()
 
void moveParticlesToSurface (agx::Vec3iVector changedVoxelIndices)
 
bool particleIslandShouldMerge (const agx::Vector< std::pair< agx::Vec3i, offsetIndexInfo > > &island)
 
virtual void post () override
 Executes post-step events for agxTerrain in the simulation.
 
void postSolveShovels ()
 
void postSortSynchronizeParticleHeightField ()
 
void postUpdateCompaction ()
 
virtual void pre () override
 Executes pre-step events for agxTerrain in the simulation.
 
virtual void preCollide () override
 Executes pre-collide events for agxTerrain in the simulation.
 
void preSortSynchronizeParticleHeightField ()
 
void preUpdateTerrainContacts ()
 
void raytraceColumns (agxCollide::GeometryPtrVector geometries, agx::HashTable< agx::Vec2i, agx::Vec4 > &contactPositionTable, const TerrainIndexSet &columnTerrainIndices, bool parallelExecute)
 
void removeEmptyTerrainMaterialVoxels ()
 Removes terrain material info from the empty voxels that was modified during this pre step.
 
virtual void removeNotification () override
 Remove notification executed when terrain is removed to a simulation.
 
void removeSoilParticlesOutsideTerrainBounds ()
 
void renderVoxelAABB (agx::Vec3i index, agx::Vec4f color)
 
void resizeOrRemoveParticles (const agx::HashTable< SoilParticlePtr, std::array< agx::Real, 2 > > &particlesToUpdate)
 
void resizeSoilParticles ()
 
void sampleParticleMassVelocity ()
 
void sanitizeMaxDepthData (agx::Real maximumDepth)
 
void sanityCheckHeightFieldAgainstMaxDepth ()
 
bool shouldDeformerActiveZoneRemoveMass (TerrainToolCollection *toolCollection, DeformerCollection *deformerCollection)
 
bool shouldPrimaryActiveZoneRemoveMass (TerrainToolCollection *toolCollection)
 
agx::HashTable< agx::Vec3i, agx::UInt64VectorsortParticlesIntoBins (int binVoxels)
 
void sortParticlesIntoColumns ()
 
void sortParticlesIntoVoxels ()
 
void stepFluidMass ()
 
void storeModifiedTerrainIndex (const agx::Vec2i &terrainVertex)
 
void toolCollectionsPreCollide ()
 
agx::Real traceGridSurfaceHeightFromVoxelIndex (const agx::Vec3i &index)
 
void traceGridSurfaceVoxel (const agx::Vec2i &terrainIndex, agx::Vec3i &surfaceVoxel) const
 
void updateIndicesForAvalanche (TerrainIndexSet &forbiddenVertices)
 
void updateInternalTransforms ()
 
void updateOccupancyFromHeightChange (const agx::Vec2i &heightFieldIndex)
 
void updateSurfaceHeightFieldFromDirtyVoxels ()
 
void updateSurfaceHeightFieldFromHeightsTable (agx::HashTable< agx::Vec2i, std::pair< agx::Vec3i, agx::Real > > &table)
 
void updateSurfaceHeightFieldFromVoxelIndex (const agx::Vec3i &voxelIndex)
 
void updateSurfaceHeightFieldFromVoxelIndices (const agx::Vec3iVector &updateIndices)
 
void updateSurfaceHeightFieldFromVoxelIndices (const agxData::LocalVector< agx::Vec3i > &updateIndices)
 
void updateTransformationFromParentBody ()
 
bool voxelColumnHasParticles (const agx::Vec2i &vertex) const
 
- Protected Member Functions inherited from agxSDK::TerrainInstance
 TerrainInstance ()
 Default constructor.
 
virtual ~TerrainInstance ()
 Reference counted object - protected destructor.
 
virtual void addNotification ()
 
virtual void last ()
 
virtual void post ()
 
virtual void pre ()
 
virtual void preCollide ()
 
virtual void removeNotification ()
 
virtual void runBuildIslandsTask ()
 
- Protected Member Functions inherited from agx::Component
virtual ~Component ()
 
String expandAutoCompletionMatch (const String &query, const StringVector &matchingNames) const
 
void setDevice (Device *device)
 
- Protected Member Functions inherited from agx::Object
virtual ~Object ()
 
- Protected Member Functions inherited from agx::Referenced
virtual ~Referenced ()
 Destructor.
 
void allocateObserverVector () const
 
void deleteUsingDeleteHandler () const
 
- Protected Member Functions inherited from agxStream::Serializable
 Serializable ()
 Default constructor.
 
 Serializable (const Serializable &other)
 Copy constructor.
 
void generateUuid ()
 

Additional Inherited Members

- Public Attributes inherited from agx::Component
ObjectEvent addObjectEvent
 
ObjectEvent removeObjectEvent
 
- Static Protected Member Functions inherited from agx::Referenced
static DeleteHandlergetDeleteHandler ()
 
static void setDeleteHandler (DeleteHandler *handler)
 Internal: Set a DeleteHandler to which deletion of all referenced counted objects will be delegated to.
 
- Protected Attributes inherited from agx::Referenced
Mutex m_mutex
 
ObserverContainer m_observers
 
AtomicValue m_refCount
 

Detailed Description

A terrain model based a 3D grid model with overlapping height field that can be deformed by interacting shovels objects performing digging motions, converting solid mass to dynamic mass which can be moved.

The underlying terrain data model consists of a hierarchical sparse 3D grid of cells, containing terrain data such as mass. The terrain surface is represented as a 2D height field that is updated when the underlying grid structure is changed. Mass is moved in the terrain via interacting shovels that converts solid cells to dynamic mass. Each shovel has an "Active Zone" which is defined by specifying two edges on the shovel's constructor, a top edge and a cutting edge. These edges should be perpendicular to the shovel's digging direction and parallel to the shovel's cross section. When the active zone intersects the terrain, dynamic mass is created in the overlapping area.

Definition at line 84 of file Terrain.h.

Member Typedef Documentation

◆ GoToStopCondition

using agxTerrain::Terrain::GoToStopCondition = std::function<bool(const agx::Vec3i& index)>
protected

Definition at line 1390 of file Terrain.h.

◆ offsetIndexInfo

◆ ParticleIslandVector

Definition at line 1391 of file Terrain.h.

Member Enumeration Documentation

◆ MassType

enum class agxTerrain::Terrain::MassType
strong
Enumerator
SOLID 
PARTICLE 
FLUID 

Definition at line 94 of file Terrain.h.

◆ MaterialType

Enumerator
TERRAIN 
PARTICLE 
AGGREGATE 

Definition at line 87 of file Terrain.h.

Constructor & Destructor Documentation

◆ Terrain() [1/4]

agxTerrain::Terrain::Terrain ( size_t  resolutionX,
size_t  resolutionY,
agx::Real  elementSize,
agx::Real  maximumDepth 
)

Constructor.

Creates a terrain object with a specific resolution of 2D grid points with elementSize as the length between them. The terrain length in each direction thus becomes (resolution - 1) * elementSize.

Parameters
resolutionX- Represents the total count of discrete data points or height points present in the 'X' dimension, rather than indicating the number of sample points per unit length in that dimension.
resolutionY- Represents the total count of discrete data points or height points present in the 'Y' dimension, rather than indicating the number of sample points per unit length in that dimension.
elementSize- The distance between the height points in the terrain.
maximumDepth- The maximum depth that the terrain can have.

◆ Terrain() [2/4]

agxTerrain::Terrain::Terrain ( size_t  resolutionX,
size_t  resolutionY,
agx::Real  elementSize,
const agx::RealVector heights,
bool  flipY,
agx::Real  maximumDepth 
)

Constructor.

Creates a terrain object with a specific resolution of 2D grid points with elementSize as the length between them. The terrain length in each direction thus becomes (resolution - 1) * elementSize.

Parameters
resolutionX- Represents the total count of discrete data points or height points present in the 'X' dimension, rather than indicating the number of sample points per unit length in that dimension.
resolutionY- Represents the total count of discrete data points or height points present in the 'Y' dimension, rather than indicating the number of sample points per unit length in that dimension.
elementSize- The distance between the height points in the terrain.
heights- A row major matrix, containing the specified heights, with dimensions (resolutionX, resolutionY).
flipY- set to true if y decreases with increasing indices in heights.
maximumDepth- The maximum depth that the terrain can have.

◆ Terrain() [3/4]

agxTerrain::Terrain::Terrain ( )
protected

Default constructor used in serialization.

◆ ~Terrain()

virtual agxTerrain::Terrain::~Terrain ( )
protectedvirtual

◆ Terrain() [4/4]

agxTerrain::Terrain::Terrain ( agxCollide::HeightField heightField,
agx::Real  maximumDepth 
)
protected

Member Function Documentation

◆ _getIntersectingGridElements()

bool agxTerrain::Terrain::_getIntersectingGridElements ( BasicGrid grid,
agxCollide::Geometry geometry,
agx::Vec3iVector gridPoints,
bool  isOccupied = true 
) const
protected

◆ _getInverseTransform()

const agx::AffineMatrix4x4 & agxTerrain::Terrain::_getInverseTransform ( ) const
inlineprotected

Definition at line 1743 of file Terrain.h.

◆ _getInvVoxelSpaceTransform()

const agx::AffineMatrix4x4 & agxTerrain::Terrain::_getInvVoxelSpaceTransform ( ) const
inlineprotected

Definition at line 1729 of file Terrain.h.

◆ _getTransform()

const agx::AffineMatrix4x4 & agxTerrain::Terrain::_getTransform ( ) const
inlineprotected

Definition at line 1736 of file Terrain.h.

◆ _getVoxelSpaceTransform()

const agx::AffineMatrix4x4 & agxTerrain::Terrain::_getVoxelSpaceTransform ( ) const
inlineprotected

Definition at line 1722 of file Terrain.h.

◆ add()

bool agxTerrain::Terrain::add ( Shovel shovel)

Adds a shovel object in the terrain.

The shovel objects interacts with the terrain by converting solid soil to dynamic soil in it's active zone.

Parameters
shovel- The specified shovel object.
Returns
true if the shovel object was successfully registered in the terrain object, false otherwise.

◆ addDirtyVoxelsToAvalanche()

void agxTerrain::Terrain::addDirtyVoxelsToAvalanche ( )
protected

◆ addModifiedParticleTerrainIndex()

void agxTerrain::Terrain::addModifiedParticleTerrainIndex ( const agx::Vec2i terrainIndex)
protected

◆ addNeighbours()

void agxTerrain::Terrain::addNeighbours ( agxData::LocalVector< agx::Vec3i > &  indexQueue,
agx::Vec3i  index 
)
protected

◆ addNoMergeZoneToGeometry()

bool agxTerrain::Terrain::addNoMergeZoneToGeometry ( agxCollide::Geometry geometry,
agx::Real  extensionDistance 
)

Add disable merge and avalanche inside geometry bound with added extension distance.

◆ addNotification()

virtual void agxTerrain::Terrain::addNotification ( )
overrideprotectedvirtual

Add notification executed when terrain is added to a simulation.

Reimplemented from agxSDK::TerrainInstance.

◆ addTerrainMaterial() [1/2]

bool agxTerrain::Terrain::addTerrainMaterial ( TerrainMaterial terrainMaterial)

Add a non default TerrainMaterial to the terrain instance, without designating its domain.

Parameters
terrainMaterial- The TerrainMaterial to add.
Returns
true if the material was added, false otherwise. If false, perhaps the terrainMaterial was already added?

◆ addTerrainMaterial() [2/2]

int agxTerrain::Terrain::addTerrainMaterial ( TerrainMaterial terrainMaterial,
agxCollide::Geometry geometry 
)

Add a non default TerrainMaterial to the designated region bounded by the overlap between the terrain and the given geometry.

Parameters
terrainMaterial- The TerrainMaterial to add.
geometry- The geometry where the TerrainMaterial should be added.
Returns
num voxel elements that was successfully assigned the material.

◆ applyFluidMassChanges()

void agxTerrain::Terrain::applyFluidMassChanges ( agx::HashTable< agx::Vec3i, float > &  fluidMassTable)
protected

◆ avalanche()

void agxTerrain::Terrain::avalanche ( )
protected

◆ calculateFluidMassTransport()

void agxTerrain::Terrain::calculateFluidMassTransport ( agx::HashTable< agx::Vec3i, float > &  fluidMassTable)
protected

◆ calculateParticlesInContactWithSurfaceGraph()

SoilParticlePtrVector agxTerrain::Terrain::calculateParticlesInContactWithSurfaceGraph ( agxCollide::GeometryPtrVector contactGeometries)
protected

◆ calculateShovelVoxelIntersection()

void agxTerrain::Terrain::calculateShovelVoxelIntersection ( )
protected

◆ calculateSurfaceHeightFromVoxelIndex()

agx::Real agxTerrain::Terrain::calculateSurfaceHeightFromVoxelIndex ( const agx::Vec3i voxelIndex)
protected

◆ calculateTotalDynamicMass()

agx::Real agxTerrain::Terrain::calculateTotalDynamicMass ( ) const
Returns
the calculated current total dynamic mass in the terrain in kg. This includes created soil particles and fluid mass.

◆ calculateTotalFluidMass()

agx::Real agxTerrain::Terrain::calculateTotalFluidMass ( ) const
Returns
the calculated current total fluid mass in the terrain in kg.

◆ calculateTotalMass()

agx::Real agxTerrain::Terrain::calculateTotalMass ( ) const
Returns
the calculated the total mass in the terrain, consisting of both dynamic and solid mass.

◆ calculateTotalSolidMass()

agx::Real agxTerrain::Terrain::calculateTotalSolidMass ( ) const
Returns
the calculated total solid mass in the terrain in kg.

◆ calculateVolume()

agx::Real agxTerrain::Terrain::calculateVolume ( )
Returns
the calculated total terrain volume.

◆ clearTerrainMaterials()

void agxTerrain::Terrain::clearTerrainMaterials ( bool  clearAddedMaterials = true)

◆ computeForbiddenBounds()

void agxTerrain::Terrain::computeForbiddenBounds ( )
protected

◆ computeParticleGrowthTables()

void agxTerrain::Terrain::computeParticleGrowthTables ( const agx::UInt64Vector particleIndices,
ParticleDeltaVector particles 
)
protected

◆ contains()

bool agxTerrain::Terrain::contains ( const Shovel shovel) const

Check is a shovel object is registered in the terrain.

Parameters
shovel- the shovel object that is checked against the terrain.
Returns
true if the shovel object is registered in the terrain, false otherwise.

◆ convertFluidMassToOccupancy()

agx::Real agxTerrain::Terrain::convertFluidMassToOccupancy ( agx::Real  mass) const
protected

◆ convertFluidOccupancyToMass()

agx::Real agxTerrain::Terrain::convertFluidOccupancyToMass ( agx::Real  occupancy) const
protected

◆ convertOccupancyToParticleRadius()

float agxTerrain::Terrain::convertOccupancyToParticleRadius ( float  occupancy) const
protected

◆ convertParticleRadiusToOccupancy()

float agxTerrain::Terrain::convertParticleRadiusToOccupancy ( float  radius) const
protected

◆ convertParticlesToSolidMass()

float agxTerrain::Terrain::convertParticlesToSolidMass ( agx::Vec3i  voxel,
ParticleWeightPairVector  particles,
float  occupancyToRemove,
agx::Vec3iVector changedIndices 
)
protected

◆ convertRemovedOccupancyToDynamicMass()

void agxTerrain::Terrain::convertRemovedOccupancyToDynamicMass ( )
protected

◆ convertToDynamicMassInShape()

void agxTerrain::Terrain::convertToDynamicMassInShape ( agxCollide::Shape shape)

Converts the terrain occupancy that overlaps the specified shape into dynamic mass.

Parameters
shape- The shape within which to convert occupancy into dynamic mass

◆ convertVoxelsInActiveZonesToDynamicMass()

void agxTerrain::Terrain::convertVoxelsInActiveZonesToDynamicMass ( )
protected

◆ createFluidMassInVoxel()

void agxTerrain::Terrain::createFluidMassInVoxel ( const agx::Vec3i voxelIndex,
agx::Real32  amount 
)
protected

◆ createFluidMassOnTerrainSurface()

void agxTerrain::Terrain::createFluidMassOnTerrainSurface ( const agx::Vec2i terrainIndex,
int  surfaceVoxelOffset,
agx::Real32  amount 
)
protected

◆ createFromHeightField()

static Terrain * agxTerrain::Terrain::createFromHeightField ( const agxCollide::HeightField heightField,
agx::Real  maximumDepth 
)
static

Creates a terrain object by using an existing height field as a basis.

The height field data is copied into the internal terrain structure. The existing height field MUST have uniform scale in X and Y axis, otherwise the function returns nullptr.

Note
The specified height field is copied and never used inside Terrain object.
Parameters
heightField- The height field object that will be used as a basis for creating
maximumDepth- The maximum depth of the terrain.
Note
- If the heightfield contains heights which are lower than the specified maximumDepth parameter, then the heightfield heights will be clamped upwards to the maximumDepth.
Returns
A terrain object create from the specified height field or nullptr if an invalid height field is given.

◆ createParticleIslands()

void agxTerrain::Terrain::createParticleIslands ( ParticleIslandVector particleIslands)
protected

◆ createSoilParticles()

void agxTerrain::Terrain::createSoilParticles ( )
protected

◆ createTask_preCollide()

agx::TaskGroupRef agxTerrain::Terrain::createTask_preCollide ( )
protected

◆ debugRenderContactGeometryVoxels()

void agxTerrain::Terrain::debugRenderContactGeometryVoxels ( )
protected

◆ debugRenderForbiddenBounds()

void agxTerrain::Terrain::debugRenderForbiddenBounds ( )
protected

◆ debugRenderShovelForbiddenBounds()

void agxTerrain::Terrain::debugRenderShovelForbiddenBounds ( )
protected

◆ enforceIncompressibilityColumnwise()

void agxTerrain::Terrain::enforceIncompressibilityColumnwise ( )
protected

◆ exchangeTerrainMaterial()

bool agxTerrain::Terrain::exchangeTerrainMaterial ( TerrainMaterial oldTerrainMaterial,
TerrainMaterial newTerrainMaterial 
)

Exchange an already added TerrainMaterial with another TerrainMaterial without changing its associated agx::Material or assigned domain.

Parameters
oldTerrainMaterial- the TerrainMaterial to be replaced
newTerrainMaterial- the new TerrainMaterial to put in its place
Returns
True if exchange was successful, false otherwise

◆ filterParticlesAboveContactGeometryVoxels()

void agxTerrain::Terrain::filterParticlesAboveContactGeometryVoxels ( agx::HashTable< agx::Vec2i, agx::Vec4 > &  contactPositionTable,
agxTerrain::SoilParticlePtrVector particles 
)
protected

◆ find() [1/2]

static Terrain * agxTerrain::Terrain::find ( const agxSDK::Simulation simulation,
const agx::Name name 
)
static

Find first terrain with given name.

Parameters
simulation- simulation the terrain is part of
name- name of the terrain
Returns
terrain instance if found - otherwise nullptr

◆ find() [2/2]

static Terrain * agxTerrain::Terrain::find ( const agxSDK::Simulation simulation,
const agx::Uuid uuid 
)
static

Find terrain with given UUID.

Parameters
simulation- simulation the terrain is part of
uuid- UUID of the terrain
Returns
terrain instance if found - otherwise nullptr

◆ findAll() [1/2]

static TerrainPtrVector agxTerrain::Terrain::findAll ( const agxSDK::Simulation simulation)
static

Finds all terrains in the given simulation.

Parameters
simulation- simulation with terrains.
Returns
vector of terrains

◆ findAll() [2/2]

static TerrainPtrVector agxTerrain::Terrain::findAll ( const agxSDK::Simulation simulation,
const agx::Name name 
)
static

Find all terrains with given name.

Parameters
simulation- simulation the terrain is part of
name- name of the terrain
Returns
vector of terrains

◆ findNewHeightFromVoxelIndex()

agx::Real agxTerrain::Terrain::findNewHeightFromVoxelIndex ( const agx::Vec3i index)
protected

◆ findPathToSurfaceVoxel()

bool agxTerrain::Terrain::findPathToSurfaceVoxel ( const agx::Vec3i startVoxel,
std::deque< agx::Vec3i > &  result 
)
protected

◆ findSurfaceVoxel()

bool agxTerrain::Terrain::findSurfaceVoxel ( const agx::Vec3i index,
agx::Vec3i result 
) const
protected

◆ findTerrainIndices()

TerrainIndexSet agxTerrain::Terrain::findTerrainIndices ( agxTerrain::SoilParticlePtrVector particles)
protected

◆ generateRandomNumber()

agx::Real agxTerrain::Terrain::generateRandomNumber ( )
protected

◆ generateRandomSoilParticlePositionPerturbation()

agx::Vec3 agxTerrain::Terrain::generateRandomSoilParticlePositionPerturbation ( agx::Real  maxDelta)
protected

◆ generateRandomSoilParticleRotation()

agx::Quat agxTerrain::Terrain::generateRandomSoilParticleRotation ( )
protected

◆ getAggregateTerrainContactArea()

agx::Real agxTerrain::Terrain::getAggregateTerrainContactArea ( const Shovel shovel,
Shovel::ExcavationMode  excavationMode 
) const

Get the aggregate <-> terrain contact area given an excavation mode and a shovel.

Parameters
shovel- the specified shovel
excavationMode- the excavation mode that the aggregate belongs too ( PRIMARY, DEFORM_BACK, DEFORM_RIGHT, DEFORM_LEFT )
Returns
the aggregate <-> terrain contact area given an excavation mode and a shovel.

◆ getAggregateTerrainContactForce()

agx::Vec3 agxTerrain::Terrain::getAggregateTerrainContactForce ( const Shovel shovel,
Shovel::ExcavationMode  excavationMode 
) const

Get the aggregate contact force with the terrain given an excavation mode and a shovel.

Parameters
shovel- the specified shovel
excavationMode- the excavation mode that the aggregate belongs too ( PRIMARY, DEFORM_BACK, DEFORM_RIGHT, DEFORM_LEFT )
Returns
the total force (N) acting on the aggregate in the terrain-aggregate contact

◆ getAggregateTerrainContacts()

agxCollide::GeometryContactPtrVector agxTerrain::Terrain::getAggregateTerrainContacts ( const Shovel shovel,
Shovel::ExcavationMode  excavationMode 
) const

Get the aggregate <-> terrain geometry contacts given an excavation mode and a shovel.

Parameters
shovel- the specified shovel
excavationMode- the excavation mode that the aggregate belongs too ( PRIMARY, DEFORM_BACK, DEFORM_RIGHT, DEFORM_LEFT )
Returns
vector containing the geometry contacts between the specified aggregate and the terrain

◆ getAggregateTerrainNormalForce()

agx::Vec3 agxTerrain::Terrain::getAggregateTerrainNormalForce ( const Shovel shovel,
Shovel::ExcavationMode  excavationMode 
) const

Get the aggregate normal force with the terrain given an excavation mode and a shovel.

Parameters
shovel- the specified shovel
excavationMode- the excavation mode that the aggregate belongs too ( PRIMARY, DEFORM_BACK, DEFORM_RIGHT, DEFORM_LEFT )
Returns
the total force (N) acting on the aggregate in the terrain-aggregate contact

◆ getAggregateTerrainTangentialForce()

agx::Vec3 agxTerrain::Terrain::getAggregateTerrainTangentialForce ( const Shovel shovel,
Shovel::ExcavationMode  excavationMode 
) const

Get the aggregate tangential force with the terrain given an excavation mode and a shovel.

Parameters
shovel- the specified shovel
excavationMode- the excavation mode that the aggregate belongs too ( PRIMARY, DEFORM_BACK, DEFORM_RIGHT, DEFORM_LEFT )
Returns
the total force (N) acting on the aggregate in the terrain-aggregate contact

◆ getAssociatedMaterial()

agx::Material * agxTerrain::Terrain::getAssociatedMaterial ( TerrainMaterial terrainMaterial) const

◆ getAvailableLibraryMaterials()

static agx::StringVector agxTerrain::Terrain::getAvailableLibraryMaterials ( )
static

Get the available TerrainMaterial presets from the TerrainMaterialLibrary that contains calibrated bulk and contact properties for a predefined material archetype.

Returns
a vector containing the available TerrainMaterial presets in the TerrainMaterialLibrary.

◆ getAvalancheController()

AvalancheController * agxTerrain::Terrain::getAvalancheController ( ) const
protected

◆ getClosestGridPoint()

agx::Vec2i agxTerrain::Terrain::getClosestGridPoint ( const agx::Vec3 worldPosition,
bool  clampToBound = false 
) const

Finds the closes terrain grid point given any point in world.

Parameters
worldPosition- position in world
clampToBound- true if the grid point should be clamped to border if position is outside bounds
Returns
the closest terrain grid index, going from (0,0) -> (resolutionX-1, resolutionY-1)

◆ getContactForce()

agx::Vec3 agxTerrain::Terrain::getContactForce ( const Shovel shovel) const

Given geometry contacts exists and the solver has solved them - calculates total shovel contact force between this terrain and the given shovel.

This is the contact force that prevents the shovel from falling through the terrain when not in excavation mode, where contact feedback is generated from the soil aggregates.

Note
- This method returns regular contact forces ONLY when no soil aggregates are present to generate excavation feedback!
Parameters
shovel- interacting shovel
Returns
the total non-excavation contact force between this terrain and the given shovel.

◆ getContactMaterial()

agx::ContactMaterial * agxTerrain::Terrain::getContactMaterial ( Terrain::MaterialType  type1,
Terrain::MaterialType  type2 
)

Returns one of the internal contact materials in agxTerrain.

TODO fix this.

Contact materials exist between MaterialType::TERRAIN - MaterialType::PARTICLE MaterialType::PARTICLE - MaterialType::PARTICLE MaterialType::TERRAIN - MaterialType::AGGREGATE

Returns
The specified internal contact material in agxTerrain.

◆ getDefaultTerrainMaterial()

TerrainMaterial * agxTerrain::Terrain::getDefaultTerrainMaterial ( ) const
inline

Returns the default terrain material which is used to derive material and contact material parameters.

Returns
The set default terrain material.

Definition at line 1684 of file Terrain.h.

◆ getDeformable()

bool agxTerrain::Terrain::getDeformable ( ) const
inline

Gets whether or not deformations are enabled for this terrain.

If false, then no dynamic mass particles or fluid mass is created. Additionally, no avalanching or compaction occurs on the terrain.

Returns
true if deformations are enabled for the terrain, false otherwise

Definition at line 1762 of file Terrain.h.

◆ getDeformationContactForce()

agx::Vec3 agxTerrain::Terrain::getDeformationContactForce ( const Shovel shovel) const

Given geometry contacts exists and the solver has solved them - calculates total contact force between the terrain deformation soil aggregate and the given shovel.

This represents the deformation force that is required to move soil via shovel deformation instead of excavation, i.e not excavation or digging. Examples of this would be side movement and backwards grading of the soil.

Parameters
shovel- interacting shovel
Returns
the total contact force between given shovel and the deformer soil aggregates in the terrain.

◆ getDynamicMass()

agx::Real agxTerrain::Terrain::getDynamicMass ( const Shovel shovel) const
Parameters
shovel- interacting shovel
Returns
dynamic mass in given shovel, including both particles and fluid mass

◆ getDynamicMassCompaction()

float agxTerrain::Terrain::getDynamicMassCompaction ( const agx::Vec3i voxelIndex) const
protected

◆ getElementSize()

agx::Real agxTerrain::Terrain::getElementSize ( ) const
inline

Returns the element size of a cell in agxTerrain, which is incidentally the distance between the center of each grid point in the surface height field.

Returns
the element size of a single cell in Terrain.

Definition at line 1715 of file Terrain.h.

◆ getEnable()

bool agxTerrain::Terrain::getEnable ( ) const
Returns
true if terrain computations should be enabled, false otherwise.
Note
- updates for ToolCollections will still be executed if false.

◆ getEnableKinematicForParticles()

static agx::Bool agxTerrain::Terrain::getEnableKinematicForParticles ( const agx::RigidBody rb)
static
Returns
true if particles sees given rigid body as kinematic (regardless of motion control)

◆ getExcavationModeContactForce()

agx::Vec3 agxTerrain::Terrain::getExcavationModeContactForce ( const Shovel shovel,
Shovel::ExcavationMode  excavationMode 
) const

calculates total contact force between the soil aggregate associated with the specified excavation mode and the given shovel.

This represents the deformation force that is required to move soil via shovel deformation instead of excavation, i.e not excavation or digging. Examples of this would be side movement and backwards grading of the soil.

Parameters
shovel- interacting shovel
excavationMode- the excavation mode that the specified soil aggregate belongs to
Returns
the total contact force between given shovel and the soil aggregate specified by the excavation mode

◆ getGeometry()

virtual agxCollide::Geometry * agxTerrain::Terrain::getGeometry ( ) const
overridevirtual
Note
It's undefined to modify this geometry instance.
Returns
the geometry of this terrain

Reimplemented from agxSDK::TerrainInstance.

◆ getHeight()

agx::Real agxTerrain::Terrain::getHeight ( const agx::Vec2i terrainIndex,
bool  includeSurfaceParticles = false 
) const

Gets the terrain height at a specific terrain grid node.

Parameters
terrainIndexAn (x,y) index specifying the grid point.
includeSurfaceParticles- Also consider particles when returning height. Default false.
Returns
the height at the specific grid node.

◆ getHeightField()

const agxCollide::HeightField * agxTerrain::Terrain::getHeightField ( ) const
Note
It's undefined to modify the terrain height field instance.
Returns
the height field shape of this terrain

◆ getInnerVolume()

agx::Real agxTerrain::Terrain::getInnerVolume ( const Shovel shovel) const
Returns
the shovel inner volume that is used in the dead load calculations

◆ getIntersectingActiveGridElements()

bool agxTerrain::Terrain::getIntersectingActiveGridElements ( agxCollide::Geometry geometry,
agx::Vec3iVector gridPoints,
MassType  massType 
) const

Get intersecting 3D grid element with specified geometry that is active/occupied with a specified mass type.

The x,y coordinate of the returned 3D points is the terrain index while the z coordinate is a depth index. See the 'TerrainGridControl' class for further explanation.

Parameters
geometry- The geometry to test intersection with the terrain grid.
gridPoints- Reference to the container where the intersecting terrain grid elements will be put.
massType- The specific mass type (SOLID, FLUID or PARTICLE) that is active/occupied in grid points that will be extracted.
Note
- This function updates the bound of the specified geometry in order to properly do intersection tests.
Returns
true if there are intersecting voxels with specified mass type within terrain bound, false if not.

◆ getIntersectingGridElements()

bool agxTerrain::Terrain::getIntersectingGridElements ( agxCollide::Geometry geometry,
agx::Vec3iVector gridPoints 
) const

Get intersecting 3D grid element with specified geometry.

The x,y coordinate of the returned 3D points is the terrain index while the z coordinate is a depth index. See the 'TerrainGridControl' class for further explanation.

Parameters
geometry- The geometry to test intersection with the terrain grid.
gridPoints- Reference to the container where the intersecting terrain grid elements will be put.
Note
- This function updates the bound of the specified geometry in order to properly do intersection tests.
Returns
true if there are intersecting voxels within terrain bound, false if not.

◆ getInverseTransform()

agx::AffineMatrix4x4 agxTerrain::Terrain::getInverseTransform ( ) const
Returns
inverse transform of this terrain

◆ getLastDeadLoadFraction()

agx::Real agxTerrain::Terrain::getLastDeadLoadFraction ( const Shovel shovel) const

Get the last computed dead load fraction of the shovel, i.e how much of it's inner volume that is filled with dynamic soil.

The dead load fraction ranges from 0.0 (empty), to 1.0 (full).

Parameters
shovel- interacting shovel
Returns
the last computed dead load fraction

◆ getLastExcavatedVolume()

agx::Real agxTerrain::Terrain::getLastExcavatedVolume ( ) const
Returns
the last excavated volume (m3) of the terrain.

◆ getLibraryMaterial()

static TerrainMaterial * agxTerrain::Terrain::getLibraryMaterial ( const agx::String materialName)
static

Loads a TerrainMaterial preset in the TerrainMaterialLibrary that contains calibrated bulk and contact properties for a predefined material archetype.

Note - This method uses the convenience enum MaterialPreset that points to existing preset files.

Parameters
materialName- The name of the material preset that should be loaded.
Returns
The library material if it exists, null otherwise.

◆ getMaterial()

agx::Material * agxTerrain::Terrain::getMaterial ( Terrain::MaterialType  type = Terrain::MaterialType::TERRAIN) const

Returns one of the internal materials in agxTerrain: MaterialType::TERRAIN - The internal material used on the terrain surface height field structure.

MaterialType::PARTICLE - The internal material used on the terrain particles. MaterialType::AGGREGATE - The internal material used on aggregate used to represent the particle mass.

These materials can be used to configure contact materials for interactions between the terrain and other objects.

Returns
The specified internal material in agxTerrain.

◆ getMaterialFromFile()

static TerrainMaterial * agxTerrain::Terrain::getMaterialFromFile ( const agx::String filename)
static

Load a TerrainMaterial from a specification file in JSON data format.

Parameters
filename- the name of the JSON file containing the specified material data.
Returns
The library material if it exists, null otherwise.

◆ getMaterialWeightsInGridPoints()

agx::RealVector agxTerrain::Terrain::getMaterialWeightsInGridPoints ( const agx::Vec3iVector gridPoints) const

Get the material weights in the terrain of the specified grid points.

Returns
a vector containing the material weights of the specified grid points.

◆ getMaterialWeightsInLine()

agx::RealVector agxTerrain::Terrain::getMaterialWeightsInLine ( const agx::Line line) const

Get the material weights in the terrain of the voxels that intersect the specified line.

Returns
a vector containing the material weights of the terrain grid elements intersecting the line.

◆ getMemoryUsage()

size_t agxTerrain::Terrain::getMemoryUsage ( )

Returns the memory usage in bytes in agxTerrain.

◆ getMergeSpeedSquared()

agx::Real agxTerrain::Terrain::getMergeSpeedSquared ( ) const
protected

◆ getMinimumAllowedHeight()

agx::Real agxTerrain::Terrain::getMinimumAllowedHeight ( ) const
Returns
the minimum allowed height of this terrain

◆ getModifiedParticleVertices()

const ModifiedVerticesVector & agxTerrain::Terrain::getModifiedParticleVertices ( ) const

Returns the modified terrain height field (including particles) vertices during the last time step.

Returns
a HashVector containing the modified particle height field indices for the last time step.

◆ getModifiedVertices()

const ModifiedVerticesVector & agxTerrain::Terrain::getModifiedVertices ( ) const

Returns the modified terrain height field vertices during the last time step.

Returns
a HashVector containing the modified terrain indices for the height field during the last time step.

◆ getNoMerge()

bool agxTerrain::Terrain::getNoMerge ( )

Return whether this terrain is prevented from merging dynamic mass to it.

◆ getNumCreatedParticles()

size_t agxTerrain::Terrain::getNumCreatedParticles ( ) const

Return the number of soil particles created during excavation this time step.

Note
- particles may disappear during dynamic mass distribution stage

◆ getNumSoilParticles()

size_t agxTerrain::Terrain::getNumSoilParticles ( ) const

Return the number of soil particles active in the simulation.

◆ getParticleNominalRadius()

float agxTerrain::Terrain::getParticleNominalRadius ( ) const

Get the soil particle nominal radius from the simulation.

The nominal radius is the particle radius that the terrain algorithm will aim for during the dynamic resizing of particles that occur during terrain interaction. This is calculated from the resulting element size upon construction of the terrain object.

◆ getParticleVertices()

const ModifiedVerticesVector & agxTerrain::Terrain::getParticleVertices ( ) const

Returns the terrain vertices that contains soil particles during the last time step.

Returns
a HashVector containing the terrain indices containing particles during the last time step.

◆ getPenetrationForce()

bool agxTerrain::Terrain::getPenetrationForce ( const Shovel shovel,
agx::Vec3 force,
agx::Vec3 torque 
) const

The result includes the active force and torque from the penetration resistance from the terrain on the shovel if the shovel is digging in the terrain.

Parameters
shovel- interacting shovel
force- the penetration force
torque- the penetration torque
Returns
true if resulting force and torque was written to force and torque - otherwise false

◆ getPosition()

agx::Vec3 agxTerrain::Terrain::getPosition ( ) const
Returns
rotation of this terrain, in world coordinate frame

◆ getProperties()

TerrainProperties * agxTerrain::Terrain::getProperties ( ) const
Returns
the properties object for the terrain.

◆ getResizedHeightField()

agx::RealVector agxTerrain::Terrain::getResizedHeightField ( size_t  factorX,
size_t  factorY 
) const

Calculate a reduced version of the height field structure.

Heights in terrain index segments with dimensions [factorX, factorY] are averaged and put into a reduced structure with dimensions [resolutionX/factorX, resolutionY/factorY].

Parameters
factorX- The factor to resize the height field in the X dimension.
factorY- The factor to resize the height field in the Y dimension.
Returns
a row major matrix of heights which corresponds to the reduced height field structure.

◆ getResolutionX()

size_t agxTerrain::Terrain::getResolutionX ( ) const
inline
Returns
the total count of discrete data points or height points present in the 'X' dimension, rather than indicating the number of sample points per unit length in that dimension.

Definition at line 1703 of file Terrain.h.

◆ getResolutionY()

size_t agxTerrain::Terrain::getResolutionY ( ) const
inline
Returns
the total count of discrete data points or height points present in the 'Y' dimension, rather than indicating the number of sample points per unit length in that dimension.

Definition at line 1709 of file Terrain.h.

◆ getRotation()

agx::Quat agxTerrain::Terrain::getRotation ( ) const
Returns
rotation of this terrain, in world coordinate frame

◆ getSeparationContactForce()

agx::Vec3 agxTerrain::Terrain::getSeparationContactForce ( const Shovel shovel) const

Given geometry contacts exists and the solver has solved them - calculates total contact force between the terrain soil particle aggregate and the given shovel.

This represents the separation force that is required to move the excavated soil in the shovel active zone.

Parameters
shovel- interacting shovel
Returns
the total contact force between given shovel and the soil particle aggregate in the terrain.

◆ getSeparationFrictionForce()

agx::Vec3 agxTerrain::Terrain::getSeparationFrictionForce ( const Shovel shovel) const

Given geometry contacts exists and the solver has solved them - calculates total contact friction force between the terrain soil particle aggregate and the given shovel.

Parameters
shovel- interacting shovel
Returns
the total contact friction force between given shovel and the soil particle aggregate in the terrain.

◆ getSeparationNormalForce()

agx::Vec3 agxTerrain::Terrain::getSeparationNormalForce ( const Shovel shovel) const

Given geometry contacts exists and the solver has solved them - calculates total contact normal force between the terrain soil particle aggregate and the given shovel.

Parameters
shovel- interacting shovel
Returns
the total contact normal force between given shovel and the soil particle aggregate in the terrain.

◆ getShovelAggregateContactMaterial()

agx::ContactMaterial * agxTerrain::Terrain::getShovelAggregateContactMaterial ( const Shovel shovel,
Shovel::ExcavationMode  mode = Shovel::ExcavationMode::PRIMARY 
) const

Get the explicitly set contact material in a shovel-aggregate contact corresponding to a specified excavation mode for a specific shovel-terrain pair.

This overrides the shovel-terrain contact material properties that are used in the default case.

Parameters
shovel- The specified shovel.
mode- The specified excavation mode that corresponds to the aggregate.
Note
- this returns nullptr if the shovel is not set to the terrain.
Returns
a contact material if one has been explicitly set, nullptr otherwise.

◆ getShovelAggregateContacts()

agxCollide::GeometryContactPtrVector agxTerrain::Terrain::getShovelAggregateContacts ( const Shovel shovel,
Shovel::ExcavationMode  excavationMode 
) const

Get the shovel <-> aggregate contacts with the terrain given an excavation mode and a shovel.

Parameters
shovel- the specified shovel
excavationMode- the excavation mode that the soil aggregate belongs too ( PRIMARY, DEFORM_BACK, DEFORM_RIGHT, DEFORM_LEFT )
Returns
vector containing the geometry contacts between the specified shovel and the aggregate.

◆ getShovelHeightPerColumn()

agx::HashVector< agx::Vec2i, agx::Int > agxTerrain::Terrain::getShovelHeightPerColumn ( )
protected

◆ getShovels()

ShovelRefVector agxTerrain::Terrain::getShovels ( ) const

Return the shovels currently added in the terrain.

◆ getSize()

agx::Vec2 agxTerrain::Terrain::getSize ( ) const

Returns the total surface size of he terrain in X Y coordinate system.

◆ getSoilAggregateMass()

agx::Real agxTerrain::Terrain::getSoilAggregateMass ( const Shovel shovel,
Shovel::ExcavationMode  excavationMode 
) const

Returns the total soil aggregate mass in a terrain given a shovel and a specific excavation mode.

This function can be used to extract the active mass that the shovel is trying to displace in the failure zones during digging and deformation.

Parameters
shovel- interacting shovel
excavationMode- The excavation mode of the aggregate that will be used to extract the mass.
Returns
the total aggregate mass, including inner shape if excavation mode is PRIMARY_EXCAVATION.

◆ getSoilParticleBoundedHeightField()

const agxCollide::HeightField * agxTerrain::Terrain::getSoilParticleBoundedHeightField ( ) const

Get the soil particle height field consisting of the highest point of either the terrain surface or the highest particle position in each terrain index.

Note
It's undefined to modify the terrain height field instance.
Returns
the soil particle height field shape of this terrain

◆ getSoilParticleStatistics()

SoilParticleStatistics agxTerrain::Terrain::getSoilParticleStatistics ( ) const

Get basic statistics of the soil particles active in the simulation.

◆ getSoilSimulationInterface()

SoilSimulationInterface * agxTerrain::Terrain::getSoilSimulationInterface ( ) const

Get the soil particle system interface used to represent the dynamic mass in the terrain.

This can be used to access and modify soil particle data.

Returns
the interface to the soil particle system used to represent the dynamic mass in the terrain.

◆ getSurfacePosition()

agx::Vec3 agxTerrain::Terrain::getSurfacePosition ( const agx::Vec2i terrainIndex,
bool  includeSurfaceParticles = false 
) const

Finds the terrain surface position, given in local coordinate frame, for a specified terrain index.

Parameters
-terrainIndex - the terrain index, going from (0,0) -> (resolutionX-1, resolutionY-1)
includeSurfaceParticles- Also consider surface particles when calculating the height, default false.
Returns
the position of the terrain surface in the grid point, given in local coordinate frame

◆ getSurfacePositionWorld()

agx::Vec3 agxTerrain::Terrain::getSurfacePositionWorld ( const agx::Vec2i terrainIndex,
bool  includeSurfaceParticles = false 
) const

Finds the terrain surface world position for a specified terrain index.

Parameters
-terrainIndex - the terrain index, going from (0,0) -> (resolutionX-1, resolutionY-1)
includeSurfaceParticles- Also consider surface particles when calculating the height, default false.
Returns
the world position of the terrain surface in the grid point

◆ getSurfaceVoxel()

bool agxTerrain::Terrain::getSurfaceVoxel ( const agx::Vec3i voxelIndex,
agx::Vec3i result 
) const
protected

◆ getTerrainContacts()

const TerrainContactRefVector & agxTerrain::Terrain::getTerrainContacts ( ) const
Returns
the current active terrain contacts with external geometries on this terrain instance.

◆ getTerrainGridControl()

TerrainGridControl * agxTerrain::Terrain::getTerrainGridControl ( ) const

Get control interface of the terrain grid data.

This interface can modify and extract data from the terrain in grid cell level, properties such as mass and compaction.

Returns
the control interface of the terrain grid data.

◆ getTerrainMaterial() [1/2]

TerrainMaterial * agxTerrain::Terrain::getTerrainMaterial ( ) const
inline

Returns the default terrain material which is used to derive material and contact material parameters.

Returns
The set terrain material.

Definition at line 1690 of file Terrain.h.

◆ getTerrainMaterial() [2/2]

TerrainMaterial * agxTerrain::Terrain::getTerrainMaterial ( agx::Vec3  position) const
inline

Returns the terrain material at the specific position which is used to derive material and contact material parameters.

Parameters
position- The world position you want to get the terrain material at.
Returns
The terrain material in the specified position of the terrain. If the position is outside of the terrain, it returns the default terrain material.

Definition at line 1696 of file Terrain.h.

◆ getTerrainParticlePackingRatio()

static agx::Real agxTerrain::Terrain::getTerrainParticlePackingRatio ( )
static
Returns
the packing ratio of soil particles generated from the terrain.

◆ getToolCollection()

TerrainToolCollection * agxTerrain::Terrain::getToolCollection ( const Shovel shovel) const
Parameters
shovel- shovel instance
Returns
tool collection given shovel - nullptr when shovel hasn't been added to this terrain

◆ getToolCollections()

const TerrainToolCollectionRefVector & agxTerrain::Terrain::getToolCollections ( ) const
Returns
registered tool collections for this terrain instance

◆ getTotalSoilParticleMass()

agx::Real agxTerrain::Terrain::getTotalSoilParticleMass ( ) const

Get the total mass (kg) of the active soil particles in the simulation.

◆ getTransform()

agx::AffineMatrix4x4 agxTerrain::Terrain::getTransform ( ) const
Returns
transform of this terrain

◆ getUpDirection()

agx::Vec3 agxTerrain::Terrain::getUpDirection ( ) const

Returns the world up direction of the terrain.

◆ getValidParticlePosition()

agx::Vec3 agxTerrain::Terrain::getValidParticlePosition ( const agx::Real  radius,
const agx::Vec3i index,
const agx::Vec3 pos 
)
protected

◆ getVoxelArea()

agx::Real agxTerrain::Terrain::getVoxelArea ( ) const
Returns
the area of a voxel

◆ getVoxelVelocity()

agx::Vec3f agxTerrain::Terrain::getVoxelVelocity ( const agx::Vec3i voxelIndex,
agx::HashTable< agx::Vec3i, size_t > &  shovelVoxels 
)
protected

◆ getVoxelVolume()

agx::Real agxTerrain::Terrain::getVoxelVolume ( ) const
Returns
the volume of a voxel

◆ goToBoundaryVoxel()

agx::Vec3i agxTerrain::Terrain::goToBoundaryVoxel ( const agx::Vec3i start) const
protected

◆ goToSurfaceVoxel()

agx::Vec3i agxTerrain::Terrain::goToSurfaceVoxel ( const agx::Vec3i start) const
protected

◆ goToVoxelKernel()

agx::Vec3i agxTerrain::Terrain::goToVoxelKernel ( const agx::Vec3i start,
const GoToStopCondition stopCondition 
) const
protected

◆ growLargeParticlesFromParticleMass()

void agxTerrain::Terrain::growLargeParticlesFromParticleMass ( ParticleDeltaVector particles,
float  particleRadiusUpperLimit 
)
protected

◆ growParticlesFromFluidMass()

void agxTerrain::Terrain::growParticlesFromFluidMass ( agx::Vec3i  binIndex,
int  binVoxels,
float  availableFluidMass,
ParticleDeltaVector particles 
)
protected

◆ growSmallParticlesFromParticleMass()

void agxTerrain::Terrain::growSmallParticlesFromParticleMass ( ParticleDeltaVector particles,
float  particleRadiusUpperLimit 
)
protected

◆ hasOverlap()

bool agxTerrain::Terrain::hasOverlap ( const agxCollide::Geometry geometry) const

Return true if the specified geometry bounding volume overlaps the terrain geometry bounding volume.

◆ hasVoxelCompaction()

bool agxTerrain::Terrain::hasVoxelCompaction ( const agx::Vec3i index) const
protected

◆ initBuildIslandTask()

void agxTerrain::Terrain::initBuildIslandTask ( )
protected

◆ initializeFromHeightField()

void agxTerrain::Terrain::initializeFromHeightField ( )
protected

◆ initializeSurfaceHeightFieldFromVoxelGrid()

void agxTerrain::Terrain::initializeSurfaceHeightFieldFromVoxelGrid ( )
protected

◆ initVoxelStructureFromHeightField()

void agxTerrain::Terrain::initVoxelStructureFromHeightField ( bool  adjustForCompaction = false)
protected

◆ isBorderIndex()

bool agxTerrain::Terrain::isBorderIndex ( const agx::Vec2i terrainIndex) const

Checks if the specified index is at the border of the terrain.

Parameters
terrainIndex- the terrain index to check
Returns
true if the given index is at the border, else false

◆ isDigging()

bool agxTerrain::Terrain::isDigging ( const Shovel shovel) const

Check if the specified shovel is currently in digging mode with the terrain, i.e if the cutting edge is submerged.

Parameters
shovel- interacting shovel
Returns
the current penetration force between given shovel and this terrain

◆ isDirty()

bool agxTerrain::Terrain::isDirty ( )
protected

◆ isFilledSolidVoxel()

bool agxTerrain::Terrain::isFilledSolidVoxel ( const agx::Vec3i index) const
protected

◆ isGeometryShovel()

bool agxTerrain::Terrain::isGeometryShovel ( const agxCollide::Geometry geometry) const

Checks if the specified geometry's rigid body is contained in any of the terrain object's registered shovels.

Parameters
geometry- the specified geometry for which its body should be checked against the registered shovels.
Returns
true if the specified geometry's body is contained in any of the registered shovels.

◆ isIndexWithinBounds()

bool agxTerrain::Terrain::isIndexWithinBounds ( const agx::Vec2i terrainIndex) const

Checks if the specified index is within bound of the terrain [(0,0) -> (resolutionX, resolutionY)].

Parameters
terrainIndex- the terrain index to check
Returns
true if the given index is within bounds, else false

◆ isIndexWithinBoundsIssueWarning()

agx::Bool agxTerrain::Terrain::isIndexWithinBoundsIssueWarning ( const agx::Vec2i terrainIndex) const
protected

◆ isLocalPositionWithinBounds()

bool agxTerrain::Terrain::isLocalPositionWithinBounds ( const agx::Vec3 position) const

Checks whether the position is within terrain (x,y) position bounds in local space.

Parameters
position- the position to be checked against the terrain bound.
Returns
true if the position is within bounds of terrain, false otherwise.

◆ isOfHomogeneousTerrainMaterial()

bool agxTerrain::Terrain::isOfHomogeneousTerrainMaterial ( ) const

◆ isRigidBodyShovel()

bool agxTerrain::Terrain::isRigidBodyShovel ( const agx::RigidBody body) const

Checks if a specified rigid body is contained in any of the terrain object's registered shovels.

Parameters
body- the specified body to check against the registered shovels.
Returns
true if the specified body is contained in any of the registered shovels.

◆ isSolidBoundaryVoxel()

bool agxTerrain::Terrain::isSolidBoundaryVoxel ( const agx::Vec3i index) const
protected

◆ isSubmergedVoxel()

bool agxTerrain::Terrain::isSubmergedVoxel ( const agx::Vec3i index) const
protected

◆ isSurfaceVoxel()

bool agxTerrain::Terrain::isSurfaceVoxel ( const agx::Vec3i index) const
protected

Surface voxel functions.

◆ isVoxelWithinTerrainIndexBounds()

bool agxTerrain::Terrain::isVoxelWithinTerrainIndexBounds ( const agx::Vec3i index) const
protected

◆ isWorldPositionWithinBounds()

bool agxTerrain::Terrain::isWorldPositionWithinBounds ( const agx::Vec3 position) const

Checks whether the position is within terrain (x,y) position bounds in world space.

Parameters
position- the position to be checked against the terrain bound.
Returns
true if the position is within bounds of terrain, false otherwise.

◆ last()

virtual void agxTerrain::Terrain::last ( )
overrideprotectedvirtual

Callback to be executed at the end of the time step.

Reimplemented from agxSDK::TerrainInstance.

◆ loadLibraryMaterial()

bool agxTerrain::Terrain::loadLibraryMaterial ( const agx::String materialName)

Loads a TerrainMaterial preset in the TerrainMaterialLibrary that contains calibrated bulk and contact properties for a predefined material archetype.

Note - This method uses the convenience enum MaterialPreset that points to existing preset files.

Parameters
materialName- The name of the material preset that should be loaded.
Returns
true if the material was successfully loaded, false otherwise.

◆ loadMaterialFile()

bool agxTerrain::Terrain::loadMaterialFile ( const agx::String filename)

Load a TerrainMaterial from a specification file in JSON data format.

Parameters
filename- the name of the JSON file containing the specified material data.
Returns
true if the specification was successfully loaded, false otherwise.

◆ markVoxelToAvalanche()

void agxTerrain::Terrain::markVoxelToAvalanche ( const agx::Vec3i changedVoxel)
protected

◆ mergeCuttingEdgeColumn()

agx::Vec3iVector agxTerrain::Terrain::mergeCuttingEdgeColumn ( agx::Vec3i  cuttingEdgeVoxel,
size_t  numVoxelsToSurfaceThreshold,
agx::Plane  cuttingPlane 
)
protected

◆ mergeFluidMass()

bool agxTerrain::Terrain::mergeFluidMass ( )
protected

◆ mergeParticleIslands()

void agxTerrain::Terrain::mergeParticleIslands ( const ParticleIslandVector particleIslands,
agxData::LocalVector< agx::Vec3i > &  mergedParticleIndices 
)
protected

◆ mergeSoilParticlesAndFluidMass()

void agxTerrain::Terrain::mergeSoilParticlesAndFluidMass ( )
protected

◆ mergeSoilToCuttingEdge()

void agxTerrain::Terrain::mergeSoilToCuttingEdge ( )
protected

◆ moveEntityDataToCurrentThread()

void agxTerrain::Terrain::moveEntityDataToCurrentThread ( )
protected

◆ moveParticlesToSurface()

void agxTerrain::Terrain::moveParticlesToSurface ( agx::Vec3iVector  changedVoxelIndices)
protected

◆ particleIslandShouldMerge()

bool agxTerrain::Terrain::particleIslandShouldMerge ( const agx::Vector< std::pair< agx::Vec3i, offsetIndexInfo > > &  island)
protected

◆ post()

virtual void agxTerrain::Terrain::post ( )
overrideprotectedvirtual

Executes post-step events for agxTerrain in the simulation.

Reimplemented from agxSDK::TerrainInstance.

◆ postSolveShovels()

void agxTerrain::Terrain::postSolveShovels ( )
protected

◆ postSortSynchronizeParticleHeightField()

void agxTerrain::Terrain::postSortSynchronizeParticleHeightField ( )
protected

◆ postUpdateCompaction()

void agxTerrain::Terrain::postUpdateCompaction ( )
protected

◆ pre()

virtual void agxTerrain::Terrain::pre ( )
overrideprotectedvirtual

Executes pre-step events for agxTerrain in the simulation.

Reimplemented from agxSDK::TerrainInstance.

◆ preCollide()

virtual void agxTerrain::Terrain::preCollide ( )
overrideprotectedvirtual

Executes pre-collide events for agxTerrain in the simulation.

Reimplemented from agxSDK::TerrainInstance.

◆ preSortSynchronizeParticleHeightField()

void agxTerrain::Terrain::preSortSynchronizeParticleHeightField ( )
protected

◆ preUpdateTerrainContacts()

void agxTerrain::Terrain::preUpdateTerrainContacts ( )
protected

◆ projectPointToSurface()

agx::Bool agxTerrain::Terrain::projectPointToSurface ( const agx::Vec3 worldPosition,
agx::Vec3 result 
) const

Project a world point to the grid surface.

Parameters
worldPosition- position in world
result- position on this terrain, given in world coordinates
Returns
true if worldPosition successfully projected onto this terrain, false if worldPosition is outside

◆ raytraceColumns()

void agxTerrain::Terrain::raytraceColumns ( agxCollide::GeometryPtrVector  geometries,
agx::HashTable< agx::Vec2i, agx::Vec4 > &  contactPositionTable,
const TerrainIndexSet columnTerrainIndices,
bool  parallelExecute 
)
protected

◆ remove()

bool agxTerrain::Terrain::remove ( Shovel shovel)

Removes a shovel object in the terrain, if it exists.

Parameters
shovel- The specified shovel object.
Returns
true if the shovel object was successfully removed in the terrain object, false otherwise.

◆ removeEmptyTerrainMaterialVoxels()

void agxTerrain::Terrain::removeEmptyTerrainMaterialVoxels ( )
protected

Removes terrain material info from the empty voxels that was modified during this pre step.

◆ removeFluidMassInGeometry()

float agxTerrain::Terrain::removeFluidMassInGeometry ( agxCollide::Geometry geometry,
float  fluidMass 
)

Remove fluid mass (in kg, NOT occupancy) in the intersecting 3D grid element with specified geometry.

The x,y coordinate of the returned 3D points is the terrain index while the z coordinate is a depth index. See the 'TerrainGridControl' class for further explanation.

Parameters
geometry- The geometry to test intersection with the terrain grid.
fluidMass- Amount of mass to be removed
Note
- This function updates the bound of the specified geometry in order to properly do intersection tests.
Returns
The amount of fluid mass (in kg) that was removed in the grid points of the intersection.

◆ removeModifiedParticleVertice()

void agxTerrain::Terrain::removeModifiedParticleVertice ( agx::Vec2i  terrainIndex)

Removes a vertex from the vector with vertices that were modified during the last time step.

◆ removeNoMergeZoneToGeometry()

bool agxTerrain::Terrain::removeNoMergeZoneToGeometry ( agxCollide::Geometry geometry)

remove disable merge and avalanche inside geometry bound with added extension distance

◆ removeNotification()

virtual void agxTerrain::Terrain::removeNotification ( )
overrideprotectedvirtual

Remove notification executed when terrain is removed to a simulation.

Reimplemented from agxSDK::TerrainInstance.

◆ removeSoilParticlesOutsideTerrainBounds()

void agxTerrain::Terrain::removeSoilParticlesOutsideTerrainBounds ( )
protected

◆ removeTerrainMaterial()

bool agxTerrain::Terrain::removeTerrainMaterial ( TerrainMaterial terrainMaterialToRemove)

◆ renderVoxelAABB()

void agxTerrain::Terrain::renderVoxelAABB ( agx::Vec3i  index,
agx::Vec4f  color 
)
protected

◆ resizeOrRemoveParticles()

void agxTerrain::Terrain::resizeOrRemoveParticles ( const agx::HashTable< SoilParticlePtr, std::array< agx::Real, 2 > > &  particlesToUpdate)
protected

◆ resizeSoilParticles()

void agxTerrain::Terrain::resizeSoilParticles ( )
protected

◆ sampleParticleMassVelocity()

void agxTerrain::Terrain::sampleParticleMassVelocity ( )
protected

◆ sanitizeMaxDepthData()

void agxTerrain::Terrain::sanitizeMaxDepthData ( agx::Real  maximumDepth)
protected

◆ sanityCheckHeightFieldAgainstMaxDepth()

void agxTerrain::Terrain::sanityCheckHeightFieldAgainstMaxDepth ( )
protected

◆ setAssociatedMaterial()

bool agxTerrain::Terrain::setAssociatedMaterial ( TerrainMaterial terrainMaterial,
agx::Material material 
)

Set the associated material with the given TerrainMaterial.

This material is used to configure contact materials between the given terrainMaterial and other materials, for example the shovelMaterial.

Parameters
terrainMaterial- the added terrainMaterial with which you want to associate a new material.
material- the associated material to the given terrainMaterial.
Returns
true if the material could successfully be associated with the given TerrainMaterial. If it fails, it returns false. This can occur if the TerrainMaterial was not added to the terrain with the addTerrainMaterial method.

◆ setCompaction()

void agxTerrain::Terrain::setCompaction ( agx::Real  compaction,
bool  replaceCompactedSoil = true 
) const

Set a compaction for all current active solid grid elements in the Terrain object.

Note
- the terrain grid elements all start with a the nominal compaction value of 1.0, of which all user specified bulk parameters correspond to.
Parameters
compaction- The compaction value to set to every voxel in the terrain (Default: 1.0)
replaceCompactedSoil- True if all voxels which already have a compaction value (compaction != 1.0) should get overwritten.

◆ setDeformable()

void agxTerrain::Terrain::setDeformable ( bool  deformable)

Sets if deformation should be enabled on this terrain.

If this is set to false no dynamic mass particles or fluid mass is created. Additionally, no avalanching or compaction occurs on the terrain.

Parameters
deformable- Whether or not to deformations should occur on this terrain

◆ setEnable()

void agxTerrain::Terrain::setEnable ( bool  enable)

Set if terrain computations should be enabled.

Note
- updates for ToolCollections will still be executed if false.
Parameters
enable- true if terrain computations should be enabled, false otherwise.

◆ setEnableKinematicForParticles()

static void agxTerrain::Terrain::setEnableKinematicForParticles ( agx::RigidBody rb,
agx::Bool  enable 
)
static

Enable/disable particles to see this rigid body as kinematic regardless of current motion control.

Parameters
rb- rigid body
enable- true to enable this feature, false to disable

◆ setHeight()

void agxTerrain::Terrain::setHeight ( const agx::Vec2i terrainIndex,
agx::Real  height 
)

Sets Terrain height at a specific terrain grid node.

Parameters
terrainIndexAn (x,y) index specifying the grid point to set the height to
heightthe new height in the height field.

◆ setHeights()

bool agxTerrain::Terrain::setHeights ( const agx::RealVector heights,
bool  flipY = false,
bool  resetCompaction = true 
)

Set height values of all sampled points.

Parameters
heights- must be a row major matrix with dimensions (resolutionX, resolutionY).
flipY- set to true if y decreases with increasing indices in heights. ( Default: false )
resetCompaction- Set to true if the compaction data should be erased to default compaction, false if compaction data should be preserved. ( Default: true )
Returns
true if heights were set successfully

◆ setMaterial()

void agxTerrain::Terrain::setMaterial ( agx::Material material,
Terrain::MaterialType  type = Terrain::MaterialType::TERRAIN 
)

Assign new material to this terrain.

The material instance will be assigned to the specified part of the terrain: MaterialType::Terrain - The geometry holding the height field (getHeightFieldGeometry()) will be assigned the material. MaterialType::Particle - The granular body system simulating dynamic soil particles will be assigned the material. MaterialType::Aggregate - NOT SUPPORTED Internal contact materials terrain <-> particles, terrain <-> soil particle aggregate and particles <-> particles will be updated.

Note that the properties in the material will be overwritten by the terrain based on the assigned TerrainMaterial.

Parameters
material- new material for this terrain
type- specifies which material to set.

◆ setNoMerge()

void agxTerrain::Terrain::setNoMerge ( bool  noMerge)

Prevent merge of dynamic mass to this terrain.

◆ setNoMergeEdgeMargin()

void agxTerrain::Terrain::setNoMergeEdgeMargin ( size_t  noMergeEdgeMargin)

Add disable merge and avalanche a number of indices from the terrain edge.

◆ setPosition()

void agxTerrain::Terrain::setPosition ( const agx::Vec3 position)

Set the position of this terrain.

Parameters
position- new position of this terrain, given in world coordinate frame

◆ setRotation()

void agxTerrain::Terrain::setRotation ( const agx::Quat rotation)

Set the rotation of this terrain.

Parameters
rotation- new rotation of this terrain, given in world coordinate frame

◆ setShovelAggregateContactMaterial()

bool agxTerrain::Terrain::setShovelAggregateContactMaterial ( const Shovel shovel,
agx::ContactMaterial contactMaterial,
Shovel::ExcavationMode  mode = Shovel::ExcavationMode::PRIMARY 
)

Explicitly set contact material properties in a shovel-aggregate contact for a specific excavation mode for a specific shovel-terrain pair.

This overrides the shovel-terrain contact material properties that are used in the default case.

Parameters
shovel- The specified shovel.
contactMaterial- The contact material to be set in the aggregate contact.
mode- The specified excavation mode that corresponds to the aggregate.
Note
- this returns false if the shovel is not set to the terrain.
Returns
true if the contact material was successfully set, false otherwise.

◆ setTerrainMaterial()

void agxTerrain::Terrain::setTerrainMaterial ( TerrainMaterial terrainMaterial,
agx::Material material = nullptr 
)

Set the default terrain material for the bulk of the terrain which is used to derive material and contact material parameters.

Parameters
terrainMaterial- The TerrainMaterial to set as default.
material- The corresponding agx::Material. Used to setup contact material between this part of the terrain <-> shovel.

◆ setTransform()

void agxTerrain::Terrain::setTransform ( const agx::AffineMatrix4x4 transform)

Set the transform of this terrain.

Parameters
transform- new transform of this terrain, given in world coordinate frame

◆ shouldDeformerActiveZoneRemoveMass()

bool agxTerrain::Terrain::shouldDeformerActiveZoneRemoveMass ( TerrainToolCollection toolCollection,
DeformerCollection deformerCollection 
)
protected

◆ shouldPrimaryActiveZoneRemoveMass()

bool agxTerrain::Terrain::shouldPrimaryActiveZoneRemoveMass ( TerrainToolCollection toolCollection)
protected

◆ sortParticlesIntoBins()

agx::HashTable< agx::Vec3i, agx::UInt64Vector > agxTerrain::Terrain::sortParticlesIntoBins ( int  binVoxels)
protected

◆ sortParticlesIntoColumns()

void agxTerrain::Terrain::sortParticlesIntoColumns ( )
protected

◆ sortParticlesIntoVoxels()

void agxTerrain::Terrain::sortParticlesIntoVoxels ( )
protected

◆ stepFluidMass()

void agxTerrain::Terrain::stepFluidMass ( )
protected

◆ storeModifiedTerrainIndex()

void agxTerrain::Terrain::storeModifiedTerrainIndex ( const agx::Vec2i terrainVertex)
protected

◆ toolCollectionsPreCollide()

void agxTerrain::Terrain::toolCollectionsPreCollide ( )
protected

◆ traceGridSurfaceHeightFromVoxelIndex()

agx::Real agxTerrain::Terrain::traceGridSurfaceHeightFromVoxelIndex ( const agx::Vec3i index)
protected

◆ traceGridSurfaceVoxel()

void agxTerrain::Terrain::traceGridSurfaceVoxel ( const agx::Vec2i terrainIndex,
agx::Vec3i surfaceVoxel 
) const
protected

◆ transformPointToTerrain()

agx::Vec3 agxTerrain::Terrain::transformPointToTerrain ( const agx::Vec3  point) const

Transform point given in world coordinate frame to local coordinate frame of this terrain.

Parameters
point- point in world coordinate frame
Returns
point in local coordinate frame of this terrain

◆ transformPointToVoxelSpace()

agx::Vec3 agxTerrain::Terrain::transformPointToVoxelSpace ( const agx::Vec3  point) const

Transform point given in world coordinate frame to local coordinate frame of this terrain.

Parameters
point- point in world coordinate frame
Returns
point in local coordinate frame of this terrain

◆ transformPointToWorld()

agx::Vec3 agxTerrain::Terrain::transformPointToWorld ( const agx::Vec3  point) const

Transform point given in local coordinate frame of this terrain, to world coordinate frame.

Parameters
point- point in local coordinate frame of this terrain
Returns
point in world coordinate frame

◆ transformVectorToTerrain()

agx::Vec3 agxTerrain::Terrain::transformVectorToTerrain ( const agx::Vec3  vector) const

Transform vector given in world coordinate frame to local coordinate frame of this terrain.

Parameters
vector- vector in world coordinate frame
Returns
vector in local coordinate frame of this terrain

◆ transformVectorToWorld()

agx::Vec3 agxTerrain::Terrain::transformVectorToWorld ( const agx::Vec3  vector) const

Transform vector given in local coordinate frame of this terrain, to world coordinate frame.

Parameters
vector- vector in local coordinate frame of this terrain
Returns
vector in world coordinate frame

◆ triggerForceAvalancheAll()

void agxTerrain::Terrain::triggerForceAvalancheAll ( )

Triggers initial avalanching on all indices in the terrain.

If any height differences in the terrain violates the angle of repose requirement, avalanching will begin on those indices.

◆ updateIndicesForAvalanche()

void agxTerrain::Terrain::updateIndicesForAvalanche ( TerrainIndexSet forbiddenVertices)
protected

◆ updateInternalTransforms()

void agxTerrain::Terrain::updateInternalTransforms ( )
protected

◆ updateOccupancyFromHeightChange()

void agxTerrain::Terrain::updateOccupancyFromHeightChange ( const agx::Vec2i heightFieldIndex)
protected

◆ updateSurfaceHeightFieldFromDirtyVoxels()

void agxTerrain::Terrain::updateSurfaceHeightFieldFromDirtyVoxels ( )
protected

◆ updateSurfaceHeightFieldFromHeightsTable()

void agxTerrain::Terrain::updateSurfaceHeightFieldFromHeightsTable ( agx::HashTable< agx::Vec2i, std::pair< agx::Vec3i, agx::Real > > &  table)
protected

◆ updateSurfaceHeightFieldFromVoxelIndex()

void agxTerrain::Terrain::updateSurfaceHeightFieldFromVoxelIndex ( const agx::Vec3i voxelIndex)
protected

◆ updateSurfaceHeightFieldFromVoxelIndices() [1/2]

void agxTerrain::Terrain::updateSurfaceHeightFieldFromVoxelIndices ( const agx::Vec3iVector updateIndices)
protected

◆ updateSurfaceHeightFieldFromVoxelIndices() [2/2]

void agxTerrain::Terrain::updateSurfaceHeightFieldFromVoxelIndices ( const agxData::LocalVector< agx::Vec3i > &  updateIndices)
protected

◆ updateTransformationFromParentBody()

void agxTerrain::Terrain::updateTransformationFromParentBody ( )
protected

◆ voxelColumnHasParticles()

bool agxTerrain::Terrain::voxelColumnHasParticles ( const agx::Vec2i vertex) const
protected

The documentation for this class was generated from the following file: