Skip to content

Commit 9ebe571

Browse files
committed
Use warning instead of assertions
removed some acctidentaly commited debug code
1 parent 7ac780b commit 9ebe571

File tree

2 files changed

+10
-31
lines changed

2 files changed

+10
-31
lines changed

python/rcsss/__init__.py

Lines changed: 10 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
import pathlib
44
import site
55
from typing import TypedDict
6+
from warnings import warn
67

78
from gymnasium import register
89
from rcsss import camera, control, envs, sim
@@ -24,12 +25,15 @@ class SceneData(TypedDict):
2425
}
2526
for path in (pathlib.Path(site.getsitepackages()[0]) / "rcsss" / "scenes").glob("*")
2627
}
27-
# available mujoco scenes
28-
for scene in scenes.values():
29-
assert scene["xml"].exists()
30-
assert scene["mjb"].exists()
31-
for urdf in scene["urdfs"].values():
32-
assert urdf.exists()
28+
29+
for _ in scenes.values():
30+
if not _["xml"].exists():
31+
warn(f"Missing XML scene file {str(_['xml'])}")
32+
if not _["mjb"].exists():
33+
warn(f"Missing mjb scene file {str(_['mjb'])}")
34+
for urdf in _["urdfs"].values():
35+
if not urdf.exists():
36+
warn(f"Missing urdf file {str(urdf)}")
3337

3438
# make submodules available
3539
__all__ = ["__doc__", "__version__", "common", "hw", "sim", "camera", "scenes", "control", "envs"]

src/sim/gui_client.cpp

Lines changed: 0 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,4 @@
11
#include <mujoco/mjui.h>
2-
#include <mujoco/mujoco.h>
32

43
#include <functional>
54
#include <iostream>
@@ -73,28 +72,14 @@ void GuiClient::render_loop() {
7372
this->platform_ui->state().userdata = this;
7473
this->platform_ui->state().nrect = 1;
7574
this->platform_ui->SetEventCallback(event_callback);
76-
auto last_cam_distance = this->cam.distance;
7775
while (!this->platform_ui->ShouldCloseWindow()) {
7876
this->platform_ui->PollEvents();
79-
if (this->cam.distance != last_cam_distance) {
80-
std::cout << "cam.distance after PollEvents: " << this->cam.distance
81-
<< std::endl;
82-
}
8377
this->shm.state_lock.lock_sharable();
8478
mj_setState(this->m, this->d, this->shm.state.ptr, MJ_PHYSICS_SPEC);
8579
this->shm.state_lock.unlock_sharable();
8680
mj_step(this->m, this->d);
87-
if (this->cam.distance != last_cam_distance) {
88-
std::cout << "cam.distance after step: " << this->cam.distance
89-
<< std::endl;
90-
}
9181
mjv_updateScene(this->m, this->d, &this->opt, NULL, &this->cam, mjCAT_ALL,
9282
&this->scn);
93-
if (this->cam.distance != last_cam_distance) {
94-
std::cout << "cam.distance after update_scene: " << this->cam.distance
95-
<< std::endl;
96-
}
97-
last_cam_distance = this->cam.distance;
9883
std::tie(viewport.width, viewport.height) =
9984
this->platform_ui->GetFramebufferSize();
10085
mjr_render(viewport, &this->scn, &this->platform_ui->mjr_context());
@@ -114,20 +99,10 @@ void event_callback(mjuiState* state) {
11499
mjrRect viewport = {0, 0, 0, 0};
115100
std::tie(viewport.width, viewport.height) =
116101
client->platform_ui->GetFramebufferSize();
117-
auto reldy = -0.02 * state->sy;
118102
switch (state->type) {
119103
case mjEVENT_SCROLL:
120-
std::cout << "cam.distance: " << client->cam.distance << std::endl;
121-
std::cout << "m->stat.extent: " << client->m->stat.extent << std::endl;
122-
std::cout << "reldy: " << reldy << std::endl;
123-
std::cout << mju_log(1 +
124-
client->cam.distance / client->m->stat.extent / 3) *
125-
reldy * 9 * client->m->stat.extent
126-
<< std::endl;
127104
mjv_moveCamera(client->m, mjMOUSE_ZOOM, 0, -0.02 * state->sy,
128105
&client->scn, &client->cam);
129-
std::cout << "cam.distance after cam move: " << client->cam.distance
130-
<< std::endl;
131106
case mjEVENT_MOVE:
132107
// determine action based on mouse button
133108
mjtMouse action;

0 commit comments

Comments
 (0)