Skip to content

Commit

Permalink
Remove all visual-only assets if discardvisual is selected, not onl…
Browse files Browse the repository at this point in the history
…y the geoms.

PiperOrigin-RevId: 598598250
Change-Id: I12e60ce41ad436d037b4877d197decf6bdce0fc8
  • Loading branch information
quagla authored and Copybara-Service committed Jan 15, 2024
1 parent acf698e commit 1e2e0b3
Show file tree
Hide file tree
Showing 11 changed files with 557 additions and 65 deletions.
22 changes: 14 additions & 8 deletions doc/XMLreference.rst
Expand Up @@ -306,14 +306,20 @@ any effect. The settings here are global and apply to the entire model.
.. _compiler-discardvisual:

:at:`discardvisual`: :at-val:`[false, true], "false" for MJCF, "true" for URDF`
This attribute instructs the parser to discard "visual geoms", defined as geoms whose contype and conaffinity
attributes are both set to 0. This functionality is useful for models that contain two sets of geoms, one for
collisions and the other for visualization. Note that URDF models are usually constructed in this way. It rarely
makes sense to have two sets of geoms in the model, especially since MuJoCo uses convex hulls for collisions, so we
recommend using this feature to discard redundant geoms. Keep in mind however that geoms considered visual per the
above definition can still participate in collisions, if they appear in the explicit list of contact
:ref:`pairs <contact-pair>`. The parser does not check this list before discarding geoms; it relies solely on the geom
attributes to make the determination.
This attribute instructs the compiler to discard all model elements which are purely visual and have no effect on the
physics (with one exception, see below). This often enables smaller :ref:`mjModel` structs and faster simulation.

- All materials are discarded.
- All textures are discarded.
- All geoms with :ref:`contype<body-geom-contype>`=:ref:`conaffinity<body-geom-conaffinity>`=0 are discarded, if they
are not referenced in another MJCF element. If a discarded geom was used for inferring body inertia, an explicit
:ref:`inertial<body-inertial>` element is added to the body.
- All meshes which are not referenced by any geom (in particular those discarded above) are discarded.

The resulting compiled model will have exactly the same dynamics as the original model, with the exception of
raycasting, as used for example by :ref:`rangefinder<sensor-rangefinder>`, since raycasting reports distances to
visual geoms. When visualizing models compiled with this flag, it is important to remember that colliding geoms are
often placed in a :ref:`group<body-geom-group>` which is invisible by default.

.. _compiler-convexhull:

Expand Down
16 changes: 11 additions & 5 deletions doc/changelog.rst
Expand Up @@ -5,16 +5,22 @@ Changelog
Upcoming version (not yet released)
-----------------------------------

General
^^^^^^^
1. Improved the :ref:discardvisual<compiler-discardvisual> compiler flag, which now discards all visual-only assets. See
:ref:discardvisual<compiler-discardvisual> for details.

MJX
^^^
1. Added :ref:`dyntype<actuator-general-dyntype>` ``filterexact``.
2. Added :at:`site` transmission.
3. Updated MJX colab tutorial with more stable quadruped environment.
4. Added ``mjx.ray`` which mirrors :ref:`mj_ray` for planes, spheres, capsules, and boxes.
2. Added :ref:`dyntype<actuator-general-dyntype>` ``filterexact``.
3. Added :at:`site` transmission.
4. Updated MJX colab tutorial with more stable quadruped environment.
5. Added ``mjx.ray`` which mirrors :ref:`mj_ray` for planes, spheres, capsules, and boxes.

Bug fixes
^^^^^^^^^
5. Fixed a bug that prevented the use of pins with plugins if flexes are not in the worldbody. Fixes :github:issue:`1270`.
6. Fixed a bug that prevented the use of pins with plugins if flexes are not in the worldbody. Fixes
:github:issue:`1270`.


Version 3.1.1 (December 18, 2023)
Expand Down
17 changes: 17 additions & 0 deletions src/user/user_mesh.cc
Expand Up @@ -166,6 +166,7 @@ mjCMesh::mjCMesh(mjCModel* _model, mjCDef* _def) {
valideigenvalue_ = true;
validinequality_ = true;
processed_ = false;
visual_ = true;

// reset to default if given
if (_def) {
Expand Down Expand Up @@ -708,6 +709,13 @@ void mjCMesh::CopyGraph(int* arr) const {



void mjCMesh::DelTexcoord() {
if (texcoord_) mju_free(texcoord_);
ntexcoord_ = 0;
}



// set geom size to match mesh
void mjCMesh::FitGeom(mjCGeom* geom, double* meshpos) {
// copy mesh pos into meshpos
Expand Down Expand Up @@ -2229,6 +2237,15 @@ mjCFlex::mjCFlex(mjCModel* _model) {
}


bool mjCFlex::HasTexcoord() const {
return !texcoord.empty();
}


void mjCFlex::DelTexcoord() {
texcoord.clear();
}


// compiler
void mjCFlex::Compile(const mjVFS* vfs) {
Expand Down
163 changes: 157 additions & 6 deletions src/user/user_model.cc
Expand Up @@ -649,9 +649,126 @@ void mjCModel::MakeLists(mjCBody* body) {
}


// delete material with given name or all materials if the name is omitted
template <class T>
static void DeleteMaterial(std::vector<T*>& list, std::string_view name = "") {
for (T* plist : list) {
if (name.empty() || plist->material == name) {
plist->material.clear();
}
}
}


// delete texture with given name or all textures if the name is omitted
template <class T>
static void DeleteTexture(std::vector<T*>& list, std::string_view name = "") {
for (T* plist : list) {
if (name.empty() || plist->texture == name) {
plist->texture.clear();
}
}
}


// delete all texture coordinates
template <class T>
static void DeleteTexcoord(std::vector<T*>& list) {
for (T* plist : list) {
if (plist->HasTexcoord()) {
plist->DelTexcoord();
}
}
}


// returns a vector that stores the reference correction for each entry
template <class T>
static void DeleteElements(std::vector<T*>& elements,
const std::vector<bool>& discard) {
if (elements.empty()) {
return;
}

std::vector<int> ndiscard(elements.size(), 0);

int i = 0;
for (int j=0; j<elements.size(); j++) {
if (discard[j]) {
delete elements[j];
} else {
elements[i] = elements[j];
i++;
}
}

// count cumulative discarded elements
for (int i=0; i<elements.size()-1; i++) {
ndiscard[i+1] = ndiscard[i] + discard[i];
}

// erase elements from vector
if (i < elements.size()) {
elements.erase(elements.begin() + i, elements.end());
}

// update elements
for (T* element : elements) {
if (element->id > 0) {
element->id -= ndiscard[element->id];
}
}
}


template <>
void mjCModel::Delete<mjCGeom>(std::vector<mjCGeom*>& elements,
const std::vector<bool>& discard) {
// update bodies
for (mjCBody* body : bodies) {
body->geoms.erase(
std::remove_if(body->geoms.begin(), body->geoms.end(),
[&discard](mjCGeom* geom) { return discard[geom->id]; }),
body->geoms.end());
}

// remove geoms from the main vector
DeleteElements(elements, discard);
}


template <>
void mjCModel::Delete<mjCMesh>(std::vector<mjCMesh*>& elements,
const std::vector<bool>& discard) {
DeleteElements(elements, discard);
}


template <>
void mjCModel::DeleteAll<mjCMaterial>(std::vector<mjCMaterial*>& elements) {
DeleteMaterial(geoms);
DeleteMaterial(skins);
DeleteMaterial(sites);
DeleteMaterial(tendons);
for (mjCMaterial* element : elements) {
delete element;
}
elements.clear();
}


template <>
void mjCModel::DeleteAll<mjCTexture>(std::vector<mjCTexture*>& elements) {
DeleteTexture(materials);
for (mjCTexture* element : elements) {
delete element;
}
elements.clear();
}


// index assets
void mjCModel::IndexAssets(void) {
void mjCModel::IndexAssets(bool discard) {
// assets referenced in geoms
for (int i=0; i<geoms.size(); i++) {
mjCGeom* pgeom = geoms[i];
Expand All @@ -670,7 +787,19 @@ void mjCModel::IndexAssets(void) {
if (!pgeom->meshname.empty()) {
mjCBase* m = FindObject(mjOBJ_MESH, pgeom->meshname);
if (m) {
pgeom->mesh = (mjCMesh*)m;
if (discard && geoms[i]->visual_) {
// do not associate with a mesh
pgeom->mesh = nullptr;
} else {
// associate mesh with geom
pgeom->mesh = (mjCMesh*)m;

// mark mesh as not visual
// this is irreversible so only performed when IndexAssets is called with discard
if (discard) {
pgeom->mesh->SetNotVisual();
}
}
} else {
throw mjCError(pgeom, "mesh '%s' not found in geom %d", pgeom->meshname.c_str(), i);
}
Expand Down Expand Up @@ -746,6 +875,20 @@ void mjCModel::IndexAssets(void) {
}
}
}

// discard visual meshes and geoms
if (discard) {
std::vector<bool> discard_mesh(meshes.size(), false);
std::vector<bool> discard_geom(geoms.size(), false);

std::transform(meshes.begin(), meshes.end(), discard_mesh.begin(),
[](const mjCMesh* mesh) { return mesh->IsVisual(); });
std::transform(geoms.begin(), geoms.end(), discard_geom.begin(),
[](const mjCGeom* geom) { return geom->IsVisual(); });

Delete(meshes, discard_mesh);
Delete(geoms, discard_geom);
}
}


Expand Down Expand Up @@ -2049,8 +2192,8 @@ void mjCModel::CopyObjects(mjModel* m) {
// geom pairs to include
for (int i=0; i<npair; i++) {
m->pair_dim[i] = pairs[i]->condim;
m->pair_geom1[i] = pairs[i]->geom1;
m->pair_geom2[i] = pairs[i]->geom2;
m->pair_geom1[i] = pairs[i]->geom1->id;
m->pair_geom2[i] = pairs[i]->geom2->id;
m->pair_signature[i] = pairs[i]->signature;
copyvec(m->pair_solref+mjNREF*i, pairs[i]->solref, mjNREF);
copyvec(m->pair_solreffriction+mjNREF*i, pairs[i]->solreffriction, mjNREF);
Expand Down Expand Up @@ -2711,8 +2854,16 @@ void mjCModel::TryCompile(mjModel*& m, mjData*& d, const mjVFS* vfs) {
}
}

// delete visual assets
if (discardvisual) {
DeleteAll(materials);
DeleteTexcoord(flexes);
DeleteTexcoord(meshes);
DeleteAll(textures);
}

// convert names into indices
IndexAssets();
IndexAssets(false);

// mark meshes that need convex hull
for (int i=0; i<geoms.size(); i++) {
Expand Down Expand Up @@ -2811,7 +2962,7 @@ void mjCModel::TryCompile(mjModel*& m, mjData*& d, const mjVFS* vfs) {
reassignid(excludes);

// resolve asset references, compute sizes
IndexAssets();
IndexAssets(discardvisual);
SetSizes();
// fuse static if enabled
if (fusestatic) {
Expand Down
28 changes: 18 additions & 10 deletions src/user/user_model.h
Expand Up @@ -96,6 +96,14 @@ class mjCModel {
mjCKey* AddKey(void); // keyframe
mjCPlugin* AddPlugin(void); // plugin instance

//------------------------ API for deleting model elements
template <class T>
void Delete(std::vector<T*>& elements,
const std::vector<bool>& discard); // delete elements marked as discard=true

template <class T>
void DeleteAll(std::vector<T*>& elements); // delete all elements

//------------------------ API for access to model elements (outside tree)
int NumObjects(mjtObj type); // number of objects in specified list
mjCBase* GetObject(mjtObj type, int id); // pointer to specified object
Expand Down Expand Up @@ -185,16 +193,16 @@ class mjCModel {
void SetDefaultNames(std::vector<T*>& assets);

//------------------------ compile phases
void MakeLists(mjCBody* body); // make lists of bodies, geoms, joints, sites
void IndexAssets(void); // convert asset names into indices
void CheckEmptyNames(void); // check empty names
void SetSizes(void); // compute sizes
void AutoSpringDamper(mjModel*);// automatic stiffness and damping computation
void LengthRange(mjModel*, mjData*); // compute actuator lengthrange
void CopyNames(mjModel*); // copy names, compute name addresses
void CopyPaths(mjModel*); // copy paths, compute path addresses
void CopyObjects(mjModel*); // copy objects outside kinematic tree
void CopyTree(mjModel*); // copy objects inside kinematic tree
void MakeLists(mjCBody* body); // make lists of bodies, geoms, joints, sites
void IndexAssets(bool discard); // convert asset names into indices
void CheckEmptyNames(void); // check empty names
void SetSizes(void); // compute sizes
void AutoSpringDamper(mjModel*); // automatic stiffness and damping computation
void LengthRange(mjModel*, mjData*); // compute actuator lengthrange
void CopyNames(mjModel*); // copy names, compute name addresses
void CopyPaths(mjModel*); // copy paths, compute path addresses
void CopyObjects(mjModel*); // copy objects outside kinematic tree
void CopyTree(mjModel*); // copy objects inside kinematic tree

//------------------------ sizes
// sizes set from object list lengths
Expand Down

0 comments on commit 1e2e0b3

Please sign in to comment.