Skip to content

Comments

Add odometry subscription helper#176

Merged
bkueng merged 1 commit intoAuterion:mainfrom
rocketSzw:main
Jan 15, 2026
Merged

Add odometry subscription helper#176
bkueng merged 1 commit intoAuterion:mainfrom
rocketSzw:main

Conversation

@rocketSzw
Copy link
Contributor

Provide Odometry wrapper exposing NED position/velocity and attitude fields, set required PX4 data, and register the new header/source in the build.

*/

/**
* @brief Provides access to the vehicle's odometry estimate
Copy link
Collaborator

Choose a reason for hiding this comment

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

Copy link
Contributor Author

Choose a reason for hiding this comment

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

The primary motivation is to ensure strict time synchronization of the full state vector.

In the default PX4 dds configuration, local_position and attitude are published at 50Hz, but angular velocity is often omitted. For advanced control scenarios—such as MPC or End-to-End Reinforcement Learning (mapping states directly to motor throttles)—we require position, velocity, attitude, and angular rates to be aligned at the exact same timestamp.

While attitude.hpp handles orientation, it does not inherently bundle the necessary odometry/velocity data synchronously. This wrapper fills that gap by providing a consolidated, consistent state snapshot, which is critical for the stability of my RL controller.

Copy link
Collaborator

Choose a reason for hiding this comment

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

Yes I'm aware of that :)
But someone looking at the code might not be, so can you add these explanations as a comment?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Okay, I have added explanations and resolved the conflict.

…ude fields, set required PX4 data, registered the new header/source in the build, and added usage guidance to odometry.hpp explaining when to prefer this wrapper for synchronized position/velocity/attitude/rates.
Copy link
Collaborator

@bkueng bkueng left a comment

Choose a reason for hiding this comment

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

Nice, thanks

@bkueng bkueng merged commit fded7ea into Auterion:main Jan 15, 2026
5 checks passed
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