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

Advanced Time Synchronisation #1042

Merged
merged 2 commits into from
Jun 4, 2018
Merged

Advanced Time Synchronisation #1042

merged 2 commits into from
Jun 4, 2018

Conversation

mhkabir
Copy link
Member

@mhkabir mhkabir commented May 31, 2018

Mavros version of PX4/PX4-Autopilot#9365.

Tested in SITL. Pending test on vehicle, but everything should be working correctly already.

nh.param("time/timesync_alpha_initial", filter_alpha_initial, 0.05f);
nh.param("time/timesync_beta_initial", filter_beta_initial, 0.05f);
nh.param("time/timesync_alpha_final", filter_alpha_final, 0.003f);
nh.param("time/timesync_alpha_final", filter_beta_final, 0.003f);
Copy link
Member

Choose a reason for hiding this comment

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

Bug.

Copy link
Member

Choose a reason for hiding this comment

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

Use cog.

Copy link
Member Author

@mhkabir mhkabir Jun 1, 2018

Choose a reason for hiding this comment

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

Fixed, but IMHO cog seems too overkill.

ROS_WARN_NAMED("time", "TM : RTT too high for timesync: %0.2f ms", rtt_ns / 1000000.0);
// Reset counter to rate-limit warnings
high_rtt_count = 0;
}
Copy link
Member

Choose a reason for hiding this comment

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

ROS already have THROTTLEd logger. setting not needed.

Copy link
Member Author

Choose a reason for hiding this comment

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

Should've made comment clearer. The intention is to not just rate-limit, but rather to inform the user when the RTT is high n times in a row. This would point to an issue with the system which needs to be fixed by the user.

uint64 remote_timestamp # remote system timestamp (nanoseconds)
int64 observed_offset # raw time offset directly observed from this timesync packet (nanoseconds)
int64 estimated_offset # smoothed time offset between companion system and Mavros (nanoseconds)
float32 round_trip_time # round trip time of this timesync packet (milliseconds)
Copy link
Member

Choose a reason for hiding this comment

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

Perhaps good idea to add _ns/_ms suffixes.

Copy link
Member Author

Choose a reason for hiding this comment

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

Done!

Copy link
Member

@vooon vooon left a comment

Choose a reason for hiding this comment

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

LGTM.

@mhkabir
Copy link
Member Author

mhkabir commented Jun 4, 2018

image

Good to go!

@vooon vooon merged commit 1e4db76 into master Jun 4, 2018
@mhkabir mhkabir deleted the pr-advanced-timesync branch June 5, 2018 03:11
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants