Skip to content

Commit

Permalink
fix: load time warning no longer causes pausing
Browse files Browse the repository at this point in the history
  • Loading branch information
DavidPL1 committed Oct 24, 2024
1 parent 9da4ff1 commit 950f897
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 10 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ Loading and reset times are reported in the server debug log. All plugin stats c
* Added missing call to render callbacks in viewer. While the callbacks were still being run for offscreen rendering, the viewer did not render additional geoms added by plugins.
* *mujoco_ros_control*: fixed sometimes using wrong joint id in default hardware interface (would only be correct, if the joints appear first and in the same order in the compiled MuJoCo model).
* *mujoco_ros_sensors*: now skipping user sensors, as they should be handled in separate, dedicated plugins.
* When loading takes more than 0.25 seconds the simulation is no longer automatically paused.

### Changed
* Moved `mujoco_ros::Viewer::Clock` definition to `mujoco_ros::Clock` (into common_types.h).
Expand Down
22 changes: 12 additions & 10 deletions mujoco_ros/src/mujoco_env.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -650,18 +650,11 @@ bool MujocoEnv::initModelFromQueue()
auto load_interval = Clock::now() - load_start;
double load_seconds = Seconds(load_interval).count();

if (!load_error_[0]) {
ROS_INFO_STREAM("Model loaded in " << load_seconds << " seconds");
if (load_seconds > 0.25) {
mju::sprintf_arr(load_error_, "Model loaded in %.2g seconds", load_seconds);
if (!mnew) {
for (const auto viewer : connected_viewers_) {
mju::strcpy_arr(viewer->load_error, load_error_);
}
}

for (const auto viewer : connected_viewers_) {
mju::strcpy_arr(viewer->load_error, load_error_);
}

if (!mnew) {
ROS_ERROR_STREAM("Loading new model failed: " << load_error_);
ROS_DEBUG("\tRolling back old model");

Expand All @@ -676,6 +669,7 @@ bool MujocoEnv::initModelFromQueue()
return false;
}

ROS_INFO_STREAM("Model loaded in " << load_seconds << " seconds");
ROS_DEBUG("Model compiled successfully");
dnew = mj_makeData(mnew);

Expand All @@ -697,6 +691,14 @@ bool MujocoEnv::initModelFromQueue()
ROS_WARN_STREAM("Model compiled, but got simulation warning: " << load_error_);
if (!settings_.headless)
settings_.run = 0;
} else {
if (load_seconds > 0.25) {
mju::sprintf_arr(load_error_, "Model loaded in %.2g seconds", load_seconds);
}
}

for (const auto viewer : connected_viewers_) {
mju::strcpy_arr(viewer->load_error, load_error_);
}

// Update real-time settings
Expand Down

0 comments on commit 950f897

Please sign in to comment.