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

Update dt was changed to nanoseconds #1322

Open
StefanFabian opened this issue Jan 3, 2025 · 1 comment
Open

Update dt was changed to nanoseconds #1322

StefanFabian opened this issue Jan 3, 2025 · 1 comment
Labels
help wanted Extra attention is needed

Comments

@StefanFabian
Copy link

const uint64_t wall_dt = std::chrono::duration_cast<std::chrono::nanoseconds>(wall_diff).count();
const auto ros_now = clock_->now();
const uint64_t ros_dt = ros_now.nanoseconds() - last_update_ros_time_.nanoseconds();
last_update_ros_time_ = ros_now;
last_update_wall_time_ = wall_now;
if (ros_dt < 0.0) {
resetTime();
}
executor_->spin_some(std::chrono::milliseconds(10));
Q_EMIT preUpdate();
frame_manager_->update();
root_display_group_->update(wall_dt, ros_dt);
if (nullptr != view_manager_) {
view_manager_->update(wall_dt, ros_dt);

Compared to rviz1, the update dt was suddenly changed from seconds to nanoseconds, which is not documented anywhere I could find even after finding out.

There are multiple issues with this:

  1. It is not documented despite being a substantial semantic change (neither the change nor in the method documentation)
    On the contrary, the method documentation even still explicitly states it would be in seconds:
    /// Called periodically by the visualization manager.
    /**
    * \param wall_dt Wall-clock time, in seconds, since the last time the update list was run through.
    * \param ros_dt ROS time, in seconds, since the last time the update list was run through.
    */
    virtual
    void
    update(float wall_dt, float ros_dt);
  2. The datatype did not change, which would at least have been an indication of change, but more importantly, a float makes no sense for nanoseconds since there are no decimal places and a significant loss of precision compared to keeping the uint64_t.
    In line with all the other changes in ROS 2 using standard library methods where appropriate, this should have been changed to a std::chrono::duration anyway, which would also make the unit explicit.

Proposed solution

Change the update method signature to a chrono duration.
This will require changing existing displays, but the alternative solution to create a second update method with the duration and keeping this method would be unclean and might still cause issues for anyone porting rviz1 displays that use the dt.
This way, this error would move from a semantic hard-to-spot error to a compilation error, which is easy to find and quick to fix.
And neither solution is ABI compatible, so they can only be made for the upcoming distros anyway.

For existing distributions at least the documentation should be changed.

@clalancette
Copy link
Contributor

This will require changing existing displays, but the alternative solution to create a second update method with the duration and keeping this method would be unclean and might still cause issues for anyone porting rviz1 displays that use the dt.

I agree that we should add a method that takes in a std::chrono::duration, but I do think we should add it as a second method, as our usual policy is to not break downstream without a "tick-tock". So we'd definitely be happy to review a PR that added in the method with std::chrono::duration and marked the old method as deprecated.

@clalancette clalancette added the help wanted Extra attention is needed label Jan 3, 2025
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
help wanted Extra attention is needed
Projects
None yet
Development

No branches or pull requests

2 participants