Skip to content

Deprecates update(float, float) methods and provides update(std::chrono::duration, std::chrono::duration) replacements.#1533

Merged
ahcorde merged 14 commits intoros2:rollingfrom
riv-mjohnson:use_chrono_durations_in_update_methods
Aug 18, 2025
Merged

Deprecates update(float, float) methods and provides update(std::chrono::duration, std::chrono::duration) replacements.#1533
ahcorde merged 14 commits intoros2:rollingfrom
riv-mjohnson:use_chrono_durations_in_update_methods

Conversation

@riv-mjohnson
Copy link
Contributor

@riv-mjohnson riv-mjohnson commented Jul 18, 2025

Description

As detailed in #1322, when rviz was updated from ros1 to ros2, the units used in update(wall_dt, ros_dt) calls were changed from seconds to nanoseconds. This change was not documented, and a lot of downstream classes (including in this repository) were not updated.

This PR attempts to begin rectifying the situation, without introducing breaking changes, by following the ideas listed in #1322. This PR deprecates the update(float, float) method, and introduces an update(std::chrono::duration, std::chrono::duration) replacement.

Is this user-facing behavior change?

Not unless users treat deprecation warnings as errors.

Did you use Generative AI?

No

Additional Information

Can this PR be back-ported to Jazzy and Humble when merged?

…no::duration, std::chrono::duration) replacements.

if (time_update_timer_ > 0.1f) {
time_update_timer_ = 0.0f;
if (time_update_timer_ > std::chrono::nanoseconds(0.1f)) {
Copy link
Contributor Author

@riv-mjohnson riv-mjohnson Jul 18, 2025

Choose a reason for hiding this comment

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

Is 0.1 nanoseconds for time_update_timer_ and 1 nanoseconds for frame_update_timer_ really the intended behaviour here?

In ros1, it was 0.1 seconds and 1 seconds respectively.

@riv-mjohnson
Copy link
Contributor Author

It looks like the tests are failing to find headers added by #1529 . Not sure what to do about that.

riv-mjohnson and others added 6 commits July 21, 2025 08:17
Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
Signed-off-by: Mark Johnson <104826595+riv-mjohnson@users.noreply.github.com>
Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
Signed-off-by: Mark Johnson <104826595+riv-mjohnson@users.noreply.github.com>
Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
Signed-off-by: Mark Johnson <104826595+riv-mjohnson@users.noreply.github.com>
Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
Signed-off-by: Mark Johnson <104826595+riv-mjohnson@users.noreply.github.com>
Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
Signed-off-by: Mark Johnson <104826595+riv-mjohnson@users.noreply.github.com>
Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
Signed-off-by: Mark Johnson <104826595+riv-mjohnson@users.noreply.github.com>
@ahcorde
Copy link
Contributor

ahcorde commented Jul 21, 2025

Pulls: #1533
Gist: https://gist.githubusercontent.com/ahcorde/5656493229bfef6cd585eda6ab9a862b/raw/cc9c5cd7e56c488cda6e27c794cef969b783cd1a/ros2.repos
BUILD args: --packages-above-and-dependencies rviz_common
TEST args: --packages-above rviz_common
ROS Distro: rolling
Job: ci_launcher
ci_launcher ran: https://ci.ros2.org/job/ci_launcher/16544

  • Linux Build Status
  • Linux-aarch64 Build Status
  • Linux-rhel Build Status
  • Windows Build Status

Copy link
Contributor

@ahcorde ahcorde left a comment

Choose a reason for hiding this comment

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

@ahcorde
Copy link
Contributor

ahcorde commented Jul 21, 2025

  • Windows Build Status

@riv-mjohnson
Copy link
Contributor Author

It looks like Windows doesn't like the cast std::chrono::nanoseconds(float).

For converting variables, we can just std::round before casting to nanoseconds.

What do we want to do about the if (time_update_timer_ > 0.1f) line? In ros1, the 0.1f and 1.0f were in seconds, so they made sense. 0.1f nanoseconds is not representable by standard std::chrono types, and is not a reasonable time to be comparing to.

@riv-mjohnson
Copy link
Contributor Author

riv-mjohnson commented Jul 22, 2025

It looks like the tests are failing to find headers added by #1529 again. Is there a dependency missing in the package.xml or CMakeLists in rolling?

Copy link
Contributor

@ahcorde ahcorde left a comment

Choose a reason for hiding this comment

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

I made here some suggestions https://github.com/ros2/rviz/compare/ahcorde/suggestions_1533 do you mind to test it?

@riv-mjohnson
Copy link
Contributor Author

I made here some suggestions https://github.com/ros2/rviz/compare/ahcorde/suggestions_1533 do you mind to test it?

Looks sensible. I've replaced the static_cast<int>(std::round( with std::lround( (which I really should have just used originally)

@riv-mjohnson
Copy link
Contributor Author

riv-mjohnson commented Jul 30, 2025

Incidentally, is there some kind of linting going on as part of your pipelines? I'm not very familiar with Jenkins

Don't worry, I found it.

@riv-mjohnson
Copy link
Contributor Author

@ahcorde Thanks for your help on this so far.

It should be ready for you to re-review, when you get a moment.

@riv-mjohnson riv-mjohnson requested a review from ahcorde August 14, 2025 19:45
@ahcorde
Copy link
Contributor

ahcorde commented Aug 18, 2025

  • Linux Build Status
  • Linux-aarch64 Build Status
  • Linux-rhel Build Status
  • Windows Build Status

@ahcorde ahcorde merged commit c7de3df into ros2:rolling Aug 18, 2025
2 checks passed
riv-mjohnson added a commit to riv-mjohnson/rviz that referenced this pull request Aug 19, 2025
…no::duration, std::chrono::duration) replacements. (ros2#1533)

Signed-off-by: Mark Johnson <104826595+riv-mjohnson@users.noreply.github.com>
Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
riv-mjohnson added a commit to riv-mjohnson/rviz that referenced this pull request Aug 19, 2025
…no::duration, std::chrono::duration) replacements. (ros2#1533)

Signed-off-by: Mark Johnson <104826595+riv-mjohnson@users.noreply.github.com>
Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
riv-mjohnson added a commit to riv-mjohnson/rviz that referenced this pull request Aug 19, 2025
…no::duration, std::chrono::duration) replacements. (ros2#1533)

Signed-off-by: Mark Johnson <104826595+riv-mjohnson@users.noreply.github.com>
Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
riv-mjohnson added a commit to riv-mjohnson/rviz that referenced this pull request Aug 19, 2025
…no::duration, std::chrono::duration) replacements. (ros2#1533)

Signed-off-by: Mark Johnson <104826595+riv-mjohnson@users.noreply.github.com>
Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
riv-mjohnson added a commit to riv-mjohnson/rviz that referenced this pull request Aug 19, 2025
…no::duration, std::chrono::duration) replacements. (ros2#1533)

Signed-off-by: Mark Johnson <104826595+riv-mjohnson@users.noreply.github.com>
Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
riv-mjohnson added a commit to riv-mjohnson/rviz that referenced this pull request Aug 19, 2025
…no::duration, std::chrono::duration) replacements. (ros2#1533)

Signed-off-by: Mark Johnson <104826595+riv-mjohnson@users.noreply.github.com>
Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
void DisplayGroup::update(float wall_dt, float ros_dt)
{
this->update(std::chrono::nanoseconds(std::lround(wall_dt)),
std::chrono::nanoseconds(std::lround(ros_dt)));
Copy link
Contributor

Choose a reason for hiding this comment

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

I am quite rusty on the rviz API but wouldn't it be better to do something like std::chrono::duration_cast<std::chrono::nanoseconds>(std::chrono::duration<float>(seconds)) here to preserve times like 0.1f?

Copy link
Contributor Author

@riv-mjohnson riv-mjohnson Sep 9, 2025

Choose a reason for hiding this comment

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

Unfortunately, float wall_dt = 0.1f is 0.1 nanoseconds, not 0.1 seconds. See #1322. As such, rounding and losing fractions of a nanosecond shouldn't be a problem.

I made this PR to try and remove the ambiguity.

I don't know what we want to do about preserving existing behaviour vs changing behaviour to match the ros1 / documented behaviour.

Copy link
Contributor

Choose a reason for hiding this comment

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

Ah, I did not spend enough time reading your issue. I thought the sec -> ns change just happened in rolling.

nbbrooks added a commit to moveit/moveit2 that referenced this pull request Oct 12, 2025
* Fix image_common NodeT deprecation warnings from ros-perception/image_common#352 - migrate to NodeInterfaces

* Fix image_common rmw_qos_profile_t deprecation warnings from ros-perception/image_common#364 - migrate to rclcpp::QoS

* Fix rviz update float deprecation warnings from ros2/rviz#1533 - migrate to std::chrono::duration

* Fix geometry2 tf2_ros .h deprecation warnings from ros2/geometry2#805 - migrate Kilted and Rolling to .hpp

* Fix geometry2 tf2_ros NodeT deprecation warnings from ros2/geometry2#714 - migrate to NodeInterfaces

* Fix rclcpp spin_some deprecation warnings from ros2/rclcpp#2848 - migrate to SingleThreadedExecutor

---------

Co-authored-by: Andrea <realeandrea@yahoo.it>
helen9975 pushed a commit to personalrobotics/moveit2 that referenced this pull request Feb 17, 2026
* Fix image_common NodeT deprecation warnings from ros-perception/image_common#352 - migrate to NodeInterfaces

* Fix image_common rmw_qos_profile_t deprecation warnings from ros-perception/image_common#364 - migrate to rclcpp::QoS

* Fix rviz update float deprecation warnings from ros2/rviz#1533 - migrate to std::chrono::duration

* Fix geometry2 tf2_ros .h deprecation warnings from ros2/geometry2#805 - migrate Kilted and Rolling to .hpp

* Fix geometry2 tf2_ros NodeT deprecation warnings from ros2/geometry2#714 - migrate to NodeInterfaces

* Fix rclcpp spin_some deprecation warnings from ros2/rclcpp#2848 - migrate to SingleThreadedExecutor

---------

Co-authored-by: Andrea <realeandrea@yahoo.it>
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.

Update dt was changed to nanoseconds

3 participants