Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

SPAWNER: Wait for the clock to be available before proceeding #432

Merged

Conversation

guillaumeautran
Copy link
Contributor

This patch is to resolve an issue when the simulated clock is not published right away (coming from a remote gazebo instance for example).
If the clock is not published right away, the rosservice wait_for_service times out prematurely and the controllers fail to be loaded since the system is not yet ready (no Gazebo clock).

With no, gazebo system, the clock will be ready immediately and the spawner will proceed.

Issue: #431

@matthew-reynolds
Copy link
Member

It looks like the same issue was fixed upstream for C++ in roscpp here, would this be better suited as an upstream fix for Python in rospy?

@guillaumeautran
Copy link
Contributor Author

I can make a similar fix in rospy if you think it is "safe" and has no side-effects.

@guillaumeautran
Copy link
Contributor Author

Actually, @matthew-reynolds , the change that you pointed is actually the opposite to what this change is suggesting. In the referenced change, the service wait fails because it uses the ros::Duration as opposed to the ros::WallDuration. The former takes in consideration the /clock topic while the later does not.
rospy wait_for_service does not currently rely on the simulated clock, which is consistent with the roscpp version. So, no, modifying ros_comm is not the right approach.

Copy link
Member

@matthew-reynolds matthew-reynolds left a comment

Choose a reason for hiding this comment

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

I see, I misunderstood the problem. I thought by "wait_for_service times out prematurely" you meant that there was a problem with wait_for_service. The issue is really that, in our use-case, the timeout should not start counting down until the system is "ready", which we're measuring by seeing whether Gazebo's clock is running.

That makes sense to me, seems like a reasonable change. Since rospy.get_rostime() should only return 0 when the /use_sim_time param is true, can we leverage that to provide more precise log messages?

Comment on lines 119 to 125
# Wait for the clock to be published
while rospy.get_rostime() == rospy.Time(0):
rospy.loginfo_throttle(30, "Waiting for the ROS Clock to be available...")
rospy.sleep(0.2)
rospy.loginfo("ROS Clock acquired. Proceeding to load the controller(s).")

Copy link
Member

Choose a reason for hiding this comment

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

Maybe let's wrap this in a check of the /use_sim_time param, and then update "ROS Clock" to "/clock" or "Simulated clock" or something along those lines?

I think that would be clearer, and it would prevent a confusing log message about "acquiring the clock" on wall-time systems.

@matthew-reynolds
Copy link
Member

matthew-reynolds commented Mar 15, 2021

@guillaumeautran @mikepurvis Bump. Is this approach being used at Clearpath? Assuming it's seen some use and has had a positive impact, we should try to get it tidied up and merged.

Edit: And re-targetted to Noetic

@bmagyar
Copy link
Member

bmagyar commented Mar 22, 2021

I think this is a useful feature we could incorporate, happy to cherry-pick to melodic too but indeed let's aim the PR to noetic first.

If @matthew-reynolds is happy I'm happy to merge & release to Noetic

@guillaumeautran guillaumeautran changed the base branch from melodic-devel to noetic-devel December 21, 2021 15:42
@guillaumeautran
Copy link
Contributor Author

guillaumeautran commented Dec 21, 2021

Very sorry for dropping the ball on this one. I know its been a while.....
The patch is now rebased to target Noetic (instead of Melodic).

@matthew-reynolds WRT wrapping the check in the use_sim_time param, any clean suggestions on implementation? The sim time check is not used anywhere in ros-control (from what I can tell). Does not mean it should not be done but just making sure that's what we want before introducing a new dependency here.

Here is what I am thinking:

    # Wait for the clock to be published
    if rospy.get_param('/use_sim_time', False):
        while rospy.get_rostime() == rospy.Time(0):
            rospy.loginfo_throttle(30, "Waiting for /clock to be available...")
            rospy.sleep(0.2)
        rospy.loginfo("/clock is published. Proceeding to load the controller(s).")

@matthew-reynolds
Copy link
Member

The sim time check is not used anywhere in ros-control (from what I can tell). Does not mean it should not be done but just making sure that's what we want before introducing a new dependency here.

I think that's fine. In general I agree, ros-control should be agnostic to time base, but I think it's appropriate here in a spawner script.

if rospy.get_param('/use_sim_time', False):

Shouldn't this be the other way (True)? We only want to do this check if using sim time (e.g. from Gazebo), right?

@guillaumeautran
Copy link
Contributor Author

guillaumeautran commented Feb 7, 2022

The statement:
if rospy.get_param('/use_sim_time', False):
Means that if the parameter is not defined, the returned value (default) should be False hence bypassing the check altogether. I am assuming that the rosparam will only be defined if in simulation...

This patch is to resolve an issue when the simulated clock is not published right away (coming from a remote gazebo instance for example).
If the clock is not published right away, the rosservice wait_for_service times out prematurely and the controllers fail to be loaded since the system is not yet ready (no Gazebo clock).

With no, gazebo system, the clock will be ready immediately and the spawner will proceed.

Issue: ros-controls#431
Copy link
Member

@matthew-reynolds matthew-reynolds left a comment

Choose a reason for hiding this comment

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

if the parameter is not defined, the default should be False

doh. Been too long since I wrote Python ROS.

LGTM, thanks :) We'll let Bence take a look and merge if he's happy.

@guillaumeautran
Copy link
Contributor Author

Perfect. Thanks much!

@guillaumeautran
Copy link
Contributor Author

ping @bmagyar for review.

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.

3 participants