Skip to content

Commit

Permalink
Add bvhactive flag to visual/global. Fixes #1279.
Browse files Browse the repository at this point in the history
PiperOrigin-RevId: 599778272
Change-Id: If5530629035cc68b198447503388f59a04041b13
  • Loading branch information
yuvaltassa authored and Copybara-Service committed Jan 19, 2024
1 parent 2feefbc commit fea7c10
Show file tree
Hide file tree
Showing 18 changed files with 147 additions and 44 deletions.
15 changes: 15 additions & 0 deletions doc/XMLreference.rst
Expand Up @@ -715,6 +715,12 @@ is effectively a miscellaneous subsection.
This attribute specifies how the equivalent inertia is visualized. "false":
use box, "true": use ellipsoid.

.. _visual-global-bvactive:

:at:`bvactive`: :at-val:`[false, true], "true"`
This attribute specifies whether collision and raycasting code should mark elements of Bounding Volume Hierarchies
as intersecting, for the purpose of visualization. Setting this attribute to "false" can speed up simulation for
models with high-resolution meshes.

.. _visual-quality:

Expand Down Expand Up @@ -1122,6 +1128,15 @@ disables the rendering of the corresponding object.
:at:`frustum`: :at-val:`real(4), "1 1 0 0.2"`
Color used to render the camera frustum.

.. _visual-rgba-bv:

:at:`bv`: :at-val:`real(4), "0 1 0 0.5"`
Color used to render bounding volumes.

.. _visual-rgba-bvactive:

:at:`bvactive`: :at-val:`real(4), "1 0 0 0.5"`
Color used to render active bounding volumes, if the :ref:`bvactive<visual-global-bvactive>` flag is "true".

.. _asset:

Expand Down
6 changes: 4 additions & 2 deletions doc/XMLschema.rst
Expand Up @@ -65,7 +65,7 @@
| | | +-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+ |
| | | | :ref:`linewidth<visual-global-linewidth>` | :ref:`glow<visual-global-glow>` | :ref:`offwidth<visual-global-offwidth>` | :ref:`offheight<visual-global-offheight>` | |
| | | +-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+ |
| | | | :ref:`realtime<visual-global-realtime>` | :ref:`ellipsoidinertia<visual-global-ellipsoidinertia>` | | | |
| | | | :ref:`realtime<visual-global-realtime>` | :ref:`ellipsoidinertia<visual-global-ellipsoidinertia>` | :ref:`bvactive<visual-global-bvactive>` | | |
| | | +-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+ |
+------------------------------------+----+------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------+
| |_| visual |br| |_| |L| | | .. table:: |
Expand Down Expand Up @@ -126,7 +126,9 @@
| | | +-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+ |
| | | | :ref:`contacttorque<visual-rgba-contacttorque>` | :ref:`contactgap<visual-rgba-contactgap>` | :ref:`rangefinder<visual-rgba-rangefinder>` | :ref:`constraint<visual-rgba-constraint>` | |
| | | +-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+ |
| | | | :ref:`slidercrank<visual-rgba-slidercrank>` | :ref:`crankbroken<visual-rgba-crankbroken>` | :ref:`frustum<visual-rgba-frustum>` | | |
| | | | :ref:`slidercrank<visual-rgba-slidercrank>` | :ref:`crankbroken<visual-rgba-crankbroken>` | :ref:`frustum<visual-rgba-frustum>` | :ref:`bv<visual-rgba-bv>` | |
| | | +-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+ |
| | | | :ref:`bvactive<visual-rgba-bvactive>` | | | | |
| | | +-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+-----------------------------------------------------------------+ |
+------------------------------------+----+------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------+
| mujoco |br| |L| | | *no attributes* |
Expand Down
21 changes: 15 additions & 6 deletions doc/changelog.rst
Expand Up @@ -12,19 +12,26 @@ General
2. Removed the :ref:`timer<mjtTimer>` for midphase colllision detection, it is now folded in with the narrowphase
timer. This is because timing the two phases seperately required fine-grained timers inside the collision
functions; these functions are so small and fast that the timer itself was incurring a measurable cost.
3. Added the flag :ref:`bvactive<visual-global-bvactive>` to ``visual/global``, allowing users to turn off
visualisation of active bounding volumes (the red/green boxes in this :ref:`this changelog item<midphase>`). For
models with very high-resolution meshes, the computation required for this visualization can slow down simulation
speed. Fixes :github:issue:`1279`.

- Added color of :ref:`bounding volumes<visual-rgba-bv>` and :ref:`active bounding volumes<visual-rgba-bvactive>`
to :ref:`visual/rgba<visual-rgba>`.

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

Bug fixes
^^^^^^^^^
7. Fixed a bug that prevented the use of pins with plugins if flexes are not in the worldbody. Fixes
8. Fixed a bug that prevented the use of pins with plugins if flexes are not in the worldbody. Fixes
:github:issue:`1270`.
7. Fixed a bug in the :ref:`muscle model<CMuscle>` that led to non-zero values outside the lower
9. Fixed a bug in the :ref:`muscle model<CMuscle>` that led to non-zero values outside the lower
bound of the length range. Fixes :github:issue:`1342`.


Expand Down Expand Up @@ -624,6 +631,8 @@ General
:align: right
:width: 350px

.. _midphase:

2. Added a collision mid-phase for pruning geoms in body pairs, see :ref:`documentation<coSelection>` for more details.
This is based on static AABB bounding volume hierarchy (a BVH binary tree) in the body inertial frame. The GIF on
the right is cut from `this longer video <https://youtu.be/e0babIM8hBo>`__.
Expand Down
3 changes: 3 additions & 0 deletions doc/includes/references.h
Expand Up @@ -753,6 +753,7 @@ struct mjVisual_ { // visualization options
int offwidth; // width of offscreen buffer
int offheight; // height of offscreen buffer
int ellipsoidinertia; // geom for inertia visualization (0: box, 1: ellipsoid)
int bvactive; // visualize active bounding volumes (0: no, 1: yes)
} global;

struct { // rendering quality
Expand Down Expand Up @@ -830,6 +831,8 @@ struct mjVisual_ { // visualization options
float slidercrank[4]; // slidercrank
float crankbroken[4]; // used when crank must be stretched/broken
float frustum[4]; // camera frustum
float bv[4]; // bounding volume
float bvactive[4]; // active bounding volume
} rgba;
};
typedef struct mjVisual_ mjVisual;
Expand Down
3 changes: 3 additions & 0 deletions include/mujoco/mjmodel.h
Expand Up @@ -459,6 +459,7 @@ struct mjVisual_ { // visualization options
int offwidth; // width of offscreen buffer
int offheight; // height of offscreen buffer
int ellipsoidinertia; // geom for inertia visualization (0: box, 1: ellipsoid)
int bvactive; // visualize active bounding volumes (0: no, 1: yes)
} global;

struct { // rendering quality
Expand Down Expand Up @@ -536,6 +537,8 @@ struct mjVisual_ { // visualization options
float slidercrank[4]; // slidercrank
float crankbroken[4]; // used when crank must be stretched/broken
float frustum[4]; // camera frustum
float bv[4]; // bounding volume
float bvactive[4]; // active bounding volume
} rgba;
};
typedef struct mjVisual_ mjVisual;
Expand Down
21 changes: 21 additions & 0 deletions introspect/structs.py
Expand Up @@ -352,6 +352,11 @@
type=ValueType(name='int'),
doc='geom for inertia visualization (0: box, 1: ellipsoid)', # pylint: disable=line-too-long
),
StructFieldDecl(
name='bvactive',
type=ValueType(name='int'),
doc='visualize active bounding volumes (0: no, 1: yes)', # pylint: disable=line-too-long
),
),
),
doc='',
Expand Down Expand Up @@ -780,6 +785,22 @@
),
doc='camera frustum',
),
StructFieldDecl(
name='bv',
type=ArrayType(
inner_type=ValueType(name='float'),
extents=(4,),
),
doc='bounding volume',
),
StructFieldDecl(
name='bvactive',
type=ArrayType(
inner_type=ValueType(name='float'),
extents=(4,),
),
doc='active bounding volume',
),
),
),
doc='',
Expand Down
3 changes: 3 additions & 0 deletions python/mujoco/structs.cc
Expand Up @@ -1400,6 +1400,7 @@ PYBIND11_MODULE(_structs, m) {
X(offwidth);
X(offheight);
X(ellipsoidinertia);
X(bvactive);
#undef X

py::class_<raw::MjVisualQuality> mjVisualQuality(mjVisual, "Quality");
Expand Down Expand Up @@ -1529,6 +1530,8 @@ PYBIND11_MODULE(_structs, m) {
X(slidercrank);
X(crankbroken);
X(frustum);
X(bv);
X(bvactive);
#undef X

#define X(var) \
Expand Down
2 changes: 2 additions & 0 deletions python/mujoco/structs.h
Expand Up @@ -233,6 +233,8 @@ class MjWrapper<raw::MjVisualRgba> : public WrapperBase<raw::MjVisualRgba> {
X(slidercrank);
X(crankbroken);
X(frustum);
X(bv);
X(bvactive);
#undef X
};

Expand Down
1 change: 1 addition & 0 deletions simulate/simulate.cc
Expand Up @@ -896,6 +896,7 @@ void MakeVisualizationSection(mj::Simulate* sim, const mjModel* m, int oldstate)
{mjITEM_EDITNUM, "Extent", 2, &(stat->extent), "1"},
{mjITEM_EDITFLOAT, "Field of view", 2, &(vis->global.fovy), "1"},
{mjITEM_RADIO, "Inertia", 5, &(vis->global.ellipsoidinertia), "Box\nEllipsoid"},
{mjITEM_RADIO, "BVH active", 5, &(vis->global.bvactive), "False\nTrue"},
{mjITEM_SEPARATOR, "Map", 1},
{mjITEM_EDITFLOAT, "Stiffness", 2, &(vis->map.stiffness), "1"},
{mjITEM_EDITFLOAT, "Rot stiffness", 2, &(vis->map.stiffnessrot), "1"},
Expand Down
29 changes: 20 additions & 9 deletions src/engine/engine_collision_driver.c
Expand Up @@ -273,7 +273,9 @@ void mj_collision(const mjModel* m, mjData* d) {
mj_clearEfc(d);

// reset the visualization flags
memset(d->bvh_active, 0, m->nbvh);
if (m->vis.global.bvactive) {
memset(d->bvh_active, 0, m->nbvh);
}

// return if disabled
if (mjDISABLED(mjDSBL_CONSTRAINT) || mjDISABLED(mjDSBL_CONTACT)
Expand Down Expand Up @@ -634,6 +636,7 @@ void mj_collideTree(const mjModel* m, mjData* d, int bf1, int bf2,
mjtByte isbody2 = (bf2 < nbody);
int f1 = isbody1 ? -1 : bf1 - nbody;
int f2 = isbody2 ? -1 : bf2 - nbody;
int mark_active = m->vis.global.bvactive;
const int bvhadr1 = isbody1 ? m->body_bvhadr[bf1] : m->flex_bvhadr[f1];
const int bvhadr2 = isbody2 ? m->body_bvhadr[bf2] : m->flex_bvhadr[f2];
const int* child1 = m->bvh_child + 2*bvhadr1;
Expand Down Expand Up @@ -705,8 +708,10 @@ void mj_collideTree(const mjModel* m, mjData* d, int bf1, int bf2,
d->geom_xpos + 3*nodeid2, d->geom_xmat + 9*nodeid2,
margin, NULL, NULL, &initialize)) {
mj_collideGeomPair(m, d, nodeid1, nodeid2, merged, startadr, pairadr);
d->bvh_active[node1 + bvhadr1] = 1;
d->bvh_active[node2 + bvhadr2] = 1;
if (mark_active) {
d->bvh_active[node1 + bvhadr1] = 1;
d->bvh_active[node2 + bvhadr2] = 1;
}
}
}
continue;
Expand Down Expand Up @@ -742,8 +747,10 @@ void mj_collideTree(const mjModel* m, mjData* d, int bf1, int bf2,
if (m->geom_type[nodeid1] != mjGEOM_PLANE) {
mj_collideGeomElem(m, d, nodeid1, f2, nodeid2);
}
d->bvh_active[node1 + bvhadr1] = 1;
d->bvh_active[node2 + bvhadr2] = 1;
if (mark_active) {
d->bvh_active[node1 + bvhadr1] = 1;
d->bvh_active[node2 + bvhadr2] = 1;
}
}
}
continue;
Expand Down Expand Up @@ -771,8 +778,10 @@ void mj_collideTree(const mjModel* m, mjData* d, int bf1, int bf2,
// box filter applied in mj_collideElems, bitmask filter applied earlier
if (isleaf1 && isleaf2) {
mj_collideElems(m, d, f1, nodeid1, f2, nodeid2);
d->bvh_active[node1 + bvhadr1] = 1;
d->bvh_active[node2 + bvhadr2] = 1;
if (mark_active) {
d->bvh_active[node1 + bvhadr1] = 1;
d->bvh_active[node2 + bvhadr2] = 1;
}
continue;
}

Expand All @@ -784,8 +793,10 @@ void mj_collideTree(const mjModel* m, mjData* d, int bf1, int bf2,
}
}

d->bvh_active[node1 + bvhadr1] = 1;
d->bvh_active[node2 + bvhadr2] = 1;
if (mark_active) {
d->bvh_active[node1 + bvhadr1] = 1;
d->bvh_active[node2 + bvhadr2] = 1;
}

// keep traversing the tree
if (!isleaf1 && isleaf2) {
Expand Down
9 changes: 3 additions & 6 deletions src/engine/engine_collision_sdf.c
Expand Up @@ -496,7 +496,7 @@ static void collideBVH(const mjModel* m, mjData* d, int g,
const int* faceid = m->bvh_nodeid + bvhadr;
const mjtNum* bvh = m->bvh_aabb + 6*bvhadr;
const int* child = m->bvh_child + 2*bvhadr;
mjtByte* visited = d->bvh_active + bvhadr;
mjtByte* bvh_active = m->vis.global.bvactive ? d->bvh_active + bvhadr : NULL;

mj_markStack(d);
// TODO(quaglino): Store bvh max depths to make this bound tighter.
Expand All @@ -521,17 +521,14 @@ static void collideBVH(const mjModel* m, mjData* d, int g,

// node1 is a leaf
if (faceid[node] != -1) {
if (visited[node]) {
continue;
}
if (boxIntersect(bvh+6*node, offset, rotation, m, sdf, d)) {
faces[*npoints] = faceid[node];
if (++(*npoints) == MAXSDFFACE) {
mju_warning("mjc_MeshSDF: too many bounding volumes, some contacts may be missed");
mj_freeStack(d);
return;
}
visited[node] = 1;
if (bvh_active) bvh_active[node] = 1;
}
continue;
}
Expand All @@ -541,7 +538,7 @@ static void collideBVH(const mjModel* m, mjData* d, int g,
continue;
}

visited[node] = 1;
if (bvh_active) bvh_active[node] = 1;

// recursive call
for (int i=0; i < 2; i++) {
Expand Down
3 changes: 3 additions & 0 deletions src/engine/engine_io.c
Expand Up @@ -194,6 +194,7 @@ void mj_defaultVisual(mjVisual* vis) {
vis->global.offheight = 480;
vis->global.realtime = 1.0;
vis->global.ellipsoidinertia = 0;
vis->global.bvactive = 1;

// rendering quality
vis->quality.shadowsize = 4096;
Expand Down Expand Up @@ -272,6 +273,8 @@ void mj_defaultVisual(mjVisual* vis) {
setf4(vis->rgba.slidercrank, .5, .3, .8, 1.);
setf4(vis->rgba.crankbroken, .9, .0, .0, 1.);
setf4(vis->rgba.frustum, 1., 1., .0, .2);
setf4(vis->rgba.bv, 0., 1., .0, .5);
setf4(vis->rgba.bvactive, 1., 0., .0, .5);
}


Expand Down
8 changes: 7 additions & 1 deletion src/engine/engine_ray.c
Expand Up @@ -627,6 +627,7 @@ int mju_raySlab(const mjtNum aabb[6], const mjtNum xpos[3],
// ray vs tree intersection
mjtNum mju_rayTree(const mjModel* m, const mjData* d, int id, const mjtNum* pnt,
const mjtNum* vec) {
int mark_active = m->vis.global.bvactive;
const int meshid = m->geom_dataid[id];
const int bvhadr = m->mesh_bvhadr[meshid];
const int* faceid = m->bvh_nodeid + bvhadr;
Expand Down Expand Up @@ -701,12 +702,17 @@ mjtNum mju_rayTree(const mjModel* m, const mjData* d, int id, const mjtNum* pnt,
// update
if (sol >= 0 && (x < 0 || sol < x)) {
x = sol;
if (mark_active) {
d->bvh_active[node + bvhadr] = 1;
}
}
continue;
}

// used for rendering
d->bvh_active[node + bvhadr] = 1;
if (mark_active) {
d->bvh_active[node + bvhadr] = 1;
}

// add children to the stack
for (int i=0; i < 2; i++) {
Expand Down

0 comments on commit fea7c10

Please sign in to comment.