Skip to content

Commit f640ba0

Browse files
committed
perf: reduces CPU load by sleeping in paused state
1 parent b494e23 commit f640ba0

File tree

2 files changed

+10
-5
lines changed

2 files changed

+10
-5
lines changed

CHANGELOG.md

+4-2
Original file line numberDiff line numberDiff line change
@@ -17,13 +17,15 @@ Loading and reset times are reported in the server debug log. All plugin stats c
1717
* When loading takes more than 0.25 seconds the simulation is no longer automatically paused.
1818
* Fixed fetching of body quaternion in `get_body_state` service.
1919
* *tests*: PendulumEnvFixture now makes sure `mj_forward` has been run at least once. This ensures the data object is populated with correct initial positions and velocities.
20-
* re-added services for getting and setting gravity, that somehow vanished.
21-
* fixed flaky tests that did not consider control callbacks being called in paused mode, too (#40).
20+
* Re-added services for getting and setting gravity, that somehow vanished.
21+
* Fixed flaky tests that did not consider control callbacks being called in paused mode, too (#40).
22+
* Fixed bug that would not allow breaking out of *as fast as possible* stepping in headless mode without shutting down the simulation.
2223

2324
### Changed
2425
* Moved `mujoco_ros::Viewer::Clock` definition to `mujoco_ros::Clock` (into common_types.h).
2526
* Increased test coverage of `mujoco_ros_sensors` plugin.
2627
* Split monolithic ros interface tests into more individual tests.
28+
* Added sleeping at least until the next lowerbound GUI refresh when paused to reduce cpu load.
2729

2830
Contributors: @DavidPL1
2931

mujoco_ros/src/physics.cpp

+6-3
Original file line numberDiff line numberDiff line change
@@ -93,9 +93,9 @@ void MujocoEnv::physicsLoop()
9393

9494
void MujocoEnv::simPausedPhysics(mjtNum &syncSim)
9595
{
96+
const auto startCPU = Clock::now();
9697
if (settings_.env_steps_request.load() > 0) { // Action call or arrow keys used for stepping
97-
syncSim = data_->time;
98-
const auto startCPU = Clock::now();
98+
syncSim = data_->time;
9999

100100
while (settings_.env_steps_request.load() > 0 &&
101101
(connected_viewers_.empty() ||
@@ -131,6 +131,9 @@ void MujocoEnv::simPausedPhysics(mjtNum &syncSim)
131131
// Run mj_forward, to update rendering and joint sliders
132132
mj_forward(model_.get(), data_.get());
133133
publishSimTime(data_->time);
134+
// Sleep for the difference between the lower bound render rate (30Hz) and the time it took to run the forward
135+
// step to reduce cpu load
136+
std::this_thread::sleep_for(Seconds(mujoco_ros::Viewer::render_ui_rate_lower_bound_) - (Clock::now() - startCPU));
134137
}
135138
}
136139

@@ -194,7 +197,7 @@ void MujocoEnv::simUnpausedPhysics(mjtNum &syncSim, std::chrono::time_point<Cloc
194197
(Clock::now() - startCPU < Seconds(mujoco_ros::Viewer::render_ui_rate_lower_bound_) ||
195198
connected_viewers_.empty()) && // only break if rendering UI is actually necessary
196199
!settings_.exit_request.load() &&
197-
num_steps_until_exit_ != 0) {
200+
num_steps_until_exit_ != 0 && settings_.run.load()) {
198201
// measure slowdown before first step
199202
if (!measured && elapsedSim) {
200203
if (settings_.real_time_index != 0) {

0 commit comments

Comments
 (0)