Skip to content

Conversation

SteveMacenski
Copy link
Contributor

@SteveMacenski SteveMacenski commented Sep 16, 2025

Description

This PR introduces a new nav_msgs/Trajectory message to compliment Path for trajectories in the style of trajectory_msgs for manipulation. This will be used on merge in Nav2 for publishing optimal trajectories from MPPI, but has broad use for time-series trajectory planners based on MPC and AI. It has been test run in Nav2 in a nav2_msgs version of the same message.

Fixes #275

Is this user-facing behavior change?

N/A, its message

Did you use Generative AI?

Nope.

Additional Information

N/A

@mjcarroll mjcarroll requested a review from tfoote September 16, 2025 19:03
@mjcarroll
Copy link
Member

LGTM, I may add to PMC agenda to next week just for awareness, but looks like you have already iterated with Tully and community.

Copy link
Contributor

@tfoote tfoote left a comment

Choose a reason for hiding this comment

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

A few tweaks for the documentation but otherwise lgtm

SteveMacenski and others added 3 commits October 1, 2025 13:29
Co-authored-by: Tully Foote <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Tully Foote <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Tully Foote <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
@SteveMacenski
Copy link
Contributor Author

@tfoote done!

Copy link
Contributor

@tfoote tfoote left a comment

Choose a reason for hiding this comment

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

Thanks for pushing on this. Lgtm

@SteveMacenski
Copy link
Contributor Author

SteveMacenski commented Oct 1, 2025

Any more approvals needed? I can pretty much use this immediately once Rolling binaries are rereleased to use this in Nav2 + make an rviz display plugin

@fujitatomoya
Copy link
Collaborator

fujitatomoya commented Oct 2, 2025

Pulls: #296
Gist: https://gist.githubusercontent.com/fujitatomoya/c66ae949fe787168864ef36939322d7a/raw/9863f5cf4b93a971cbd595cd3b669473f3818fae/ros2.repos
BUILD args: --packages-above-and-dependencies nav_msgs
TEST args: --packages-above nav_msgs
ROS Distro: rolling
Job: ci_launcher
ci_launcher ran: https://ci.ros2.org/job/ci_launcher/17120

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

@ros-discourse
Copy link

This pull request has been mentioned on Open Robotics Discourse. There might be relevant details there:

https://discourse.openrobotics.org/t/ros-pmc-minutes-for-september-30-2025/50379/1

@SteveMacenski
Copy link
Contributor Author

aarch64 failure looks networking related

@christophebedard
Copy link
Member

Yeah, it was retried many times (~40 times) automatically and eventually passed.

@christophebedard christophebedard merged commit d81f602 into ros2:rolling Oct 2, 2025
3 checks passed
@christophebedard
Copy link
Member

I will create a new Rolling release.

@SteveMacenski
Copy link
Contributor Author

Thanks @christophebedard !

@christophebedard
Copy link
Member

done: ros/rosdistro#47900

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.

Proposal - New nav_msgs/Trajectory message type
6 participants