class
#include <esp/physics/URDFImporter.h>
URDFImporter Virtual base class for loading URDF into various simulator implementations.
Derived classes
- class BulletURDFImporter
- Derived importer class for loading URDF into Bullet physics.
Constructors, destructors, conversion operators
-
URDFImporter(esp::
assets:: ResourceManager& resourceManager) explicit - ~URDFImporter() defaulted virtual
Public functions
-
auto loadURDF(const std::
string& urdfFilepath, bool forceReload = false) -> bool - Sets the activeModel_ for the importer. If new or forceReload, parse a URDF file and cache the resulting model. Note: when applying uniform scaling to a 3D model consider scale^3 mass scaling to approximate uniform density.
-
auto getModel() const -> std::
shared_ptr<metadata:: URDF:: Model> virtual - void setFixedBase(bool fixedBase)
- auto getFixedBase() -> bool
-
auto getBodyName() const -> std::
string virtual - auto getRootLinkIndex() const -> int virtual
-
void getLinkChildIndices(int linkIndex,
std::
vector<int>& childLinkIndices) const virtual -
auto getLinkContactInfo(int linkIndex,
metadata::
URDF:: LinkContactInfo& contactInfo) const -> bool virtual -
auto getJointInfo(int linkIndex,
Magnum::
Matrix4& parent2joint, Magnum:: Matrix4& linkTransformInWorld, Magnum:: Vector3& jointAxisInJointSpace, int& jointType, float& jointLowerLimit, float& jointUpperLimit, float& jointDamping, float& jointFriction) const -> bool virtual -
auto getJointInfo(int linkIndex,
Magnum::
Matrix4& parent2joint, Magnum:: Matrix4& linkTransformInWorld, Magnum:: Vector3& jointAxisInJointSpace, int& jointType, float& jointLowerLimit, float& jointUpperLimit, float& jointDamping, float& jointFriction, float& jointMaxForce, float& jointMaxVelocity) const -> bool virtual -
void getMassAndInertia(int linkIndex,
float& mass,
Magnum::
Vector3& localInertiaDiagonal, Magnum:: Matrix4& inertialFrame) const virtual -
auto getCachedModelKeys() -> std::
vector<std:: string> - collect and return a list of cached model keys (filepaths)
- void importURDFAssets(const esp::metadata::attributes::ArticulatedObjectAttributes::ptr& artObjAttributes)
- Load/import any required render and collision assets for the acrive metadata::URDF::Model before instantiating it.
Public variables
- int flags
- importer model conversion flags
Protected variables
-
metadata::
URDF:: Parser urdfParser_ -
esp::
assets:: ResourceManager& resourceManager_ -
std::
map<std:: string, std:: shared_ptr<metadata:: URDF:: Model>> modelCache_ - cache parsed URDF models by filename
-
std::
shared_ptr<metadata:: URDF:: Model> activeModel_
Function documentation
bool esp:: physics:: URDFImporter:: loadURDF(const std:: string& urdfFilepath,
bool forceReload = false)
Sets the activeModel_ for the importer. If new or forceReload, parse a URDF file and cache the resulting model. Note: when applying uniform scaling to a 3D model consider scale^3 mass scaling to approximate uniform density.
Parameters | |
---|---|
urdfFilepath | The filepath for the URDF and key for the cached model. |
forceReload | If true, reload the URDF from file, replacing the cached model. |
Variable documentation
std:: shared_ptr<metadata:: URDF:: Model> esp:: physics:: URDFImporter:: activeModel_ protected
which model is being actively manipulated. Changed by calling loadURDF(filename).