Skip to content

Conversation

mrceki
Copy link

@mrceki mrceki commented Feb 17, 2025

Hi!

As discussed in issue #25, this pull request adds pause functionality. You can toggle the pause state via the space bar.
Also, you can trigger pause at startup using the 'pause_simulation': True parameter in the launch file.

Copy link
Member

@sangteak601 sangteak601 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hi @mrceki,
I'm still in the process of reviewing, but I have a quick question to help me understand it better. Please bear with me.

Comment on lines 134 to 147
if (pause_simulation_) {
// when paused, use the wall clock
sim_time_ros = node_->get_clock()->now();
sim_period = control_period_;
}
else {
// Get the simulation time and period
auto sim_time = mj_data_->time;
int sim_time_sec = static_cast<int>(sim_time);
int sim_time_nanosec = static_cast<int>((sim_time - sim_time_sec)*1000000000);

sim_time_ros = rclcpp::Time(sim_time_sec, sim_time_nanosec, RCL_ROS_TIME);
sim_period = sim_time_ros - last_update_sim_time_ros_;
}
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why do we need to separate these two cases?
I think it might cause a problem, particularly when we resume the simulation, as time will jump (and also go backward).

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I separated the cases to keep controller updates running even when simulation time is frozen. But I'm not completely sure if simulation time really stops when paused. I'll need to double-check that.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This version does not lead to time jumping as I observed. But it is also unnecessary to separate it in two cases because it's working unlike what I remember about time freezing.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@sangteak601 I think I found out why I separated in two cases. If you pause the sim without pausing at startup, that's OK. But If we want to pause simulation in startup, controllers cannot be loaded. What is your suggestion on that?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@sangteak601 I think I found out why I separated in two cases. If you pause the sim without pausing at startup, that's OK. But If we want to pause simulation in startup, controllers cannot be loaded. What is your suggestion on that?

I have done testing and was able to reproduce the issue of controllers not being loaded. One potential solution is to move controller_manager_->update() outside the if (sim_period >= control_period_) condition, similar to how controller_manager_->write() is currently positioned.

However, I am uncertain whether this change might introduce performance overhead, and I am also unsure why I initially placed controller_manager_->write() outside the condition.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants