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

Control TimeReference source #1859

Open
wants to merge 2 commits into
base: ros2
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
28 changes: 20 additions & 8 deletions mavros/src/plugins/sys_time.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -345,15 +345,27 @@ class SystemTimePlugin : public plugin::Plugin
if (fcu_time_valid) {
// continious publish for ntpd
auto time_unix = sensor_msgs::msg::TimeReference();
rclcpp::Time time_ref(
mtime.time_unix_usec / 1000000, // t_sec
(mtime.time_unix_usec % 1000000) * 1000); // t_nsec

time_unix.header.stamp = node->now();
time_unix.time_ref = time_ref;
time_unix.source = time_ref_source;
if (time_ref_source == "epoc")
{
// time_unix_usec: us
rclcpp::Time time_ref(
mtime.time_unix_usec / 1000000, // t_sec
(mtime.time_unix_usec % 1000000) * 1000); // t_nsec
time_unix.time_ref = time_ref;
}
else
{
// time_unix_usec: ms
rclcpp::Time time_ref(
mtime.time_boot_ms / 1000, // t_sec
(mtime.time_boot_ms % 1000) * 1000000); // t_nsec
time_unix.time_ref = time_ref;
}
time_unix.header.stamp = node->now();
time_unix.header.frame_id = "";
time_unix.source = time_ref_source;

time_ref_pub->publish(time_unix);
time_ref_pub->publish(time_unix);
} else {
RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 60000, "TM: Wrong FCU time.");
}
Expand Down