|
71 | 71 | 'bottom right': enums.mjtGridPos.mjGRID_BOTTOMRIGHT, |
72 | 72 | } |
73 | 73 |
|
74 | | -_DIVERGENCE_WARNINGS = [ |
75 | | - enums.mjtWarning.mjWARN_INERTIA, |
76 | | - enums.mjtWarning.mjWARN_BADQPOS, |
77 | | - enums.mjtWarning.mjWARN_BADQVEL, |
78 | | - enums.mjtWarning.mjWARN_BADQACC, |
79 | | - enums.mjtWarning.mjWARN_BADCTRL, |
80 | | -] |
81 | | - |
82 | 74 | Contexts = collections.namedtuple('Contexts', ['gl', 'mujoco']) |
83 | 75 | Selected = collections.namedtuple( |
84 | 76 | 'Selected', ['body', 'geom', 'world_position']) |
@@ -146,7 +138,7 @@ def step(self): |
146 | 138 | if self.model.opt.integrator != enums.mjtIntegrator.mjINT_EULER: |
147 | 139 | mjlib.mj_step1(self.model.ptr, self.data.ptr) |
148 | 140 |
|
149 | | - self.check_divergence() |
| 141 | + self.check_invalid_state() |
150 | 142 |
|
151 | 143 | def render(self, height=240, width=320, camera_id=-1, overlays=(), |
152 | 144 | depth=False, scene_option=None): |
@@ -250,16 +242,16 @@ def forward(self): |
250 | 242 | # http://www.mujoco.org/book/programming.html#siForward |
251 | 243 | mjlib.mj_forward(self.model.ptr, self.data.ptr) |
252 | 244 |
|
253 | | - def check_divergence(self): |
254 | | - """Raises a `base.PhysicsError` if the simulation state is divergent.""" |
255 | | - warning_counts = [self.data.warning[i].number for i in _DIVERGENCE_WARNINGS] |
| 245 | + def check_invalid_state(self): |
| 246 | + """Raises a `base.PhysicsError` if the simulation state is invalid.""" |
| 247 | + warning_counts = [self.data.warning[i].number for i in |
| 248 | + xrange(enums.mjtWarning.mjNWARNING)] |
256 | 249 | if any(warning_counts): |
257 | 250 | warning_names = [] |
258 | 251 | for i in np.where(warning_counts)[0]: |
259 | | - field_idx = _DIVERGENCE_WARNINGS[i] |
260 | | - warning_names.append(enums.mjtWarning._fields[field_idx]) |
| 252 | + warning_names.append(enums.mjtWarning._fields[i]) |
261 | 253 | raise _control.PhysicsError( |
262 | | - 'Physics state has diverged. Warning(s) raised: {}'.format( |
| 254 | + 'Physics state is invalid. Warning(s) raised: {}'.format( |
263 | 255 | ', '.join(warning_names))) |
264 | 256 |
|
265 | 257 | def __getstate__(self): |
|
0 commit comments