Skip to content

Commit

Permalink
Correct UTC time in GPS message
Browse files Browse the repository at this point in the history
Pick the UTC time from the mission computer clock instad of steady_time
clock used to timestamp the message at mocap server

Signed-off-by: Jukka Laitinen <[email protected]>
  • Loading branch information
jlaitine committed Mar 23, 2022
1 parent 58edf61 commit cc22c05
Showing 1 changed file with 4 additions and 3 deletions.
7 changes: 4 additions & 3 deletions src/mocap_pose.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,8 @@ struct MocapPose::Impl

px4_msgs::msg::SensorGps PrepareGpsMessage(const Eigen::Vector3f& position,
const Eigen::Quaternionf& q,
const rclcpp::Time& timestamp)
const rclcpp::Time& timestamp,
const rclcpp::Time& utc_timestamp)
{
px4_msgs::msg::SensorGps sensor_gps{};

Expand Down Expand Up @@ -108,7 +109,7 @@ struct MocapPose::Impl
sensor_gps.hdop = 0.0f;
sensor_gps.vdop = 0.0f;

sensor_gps.time_utc_usec = timestamp.nanoseconds() / 1000ULL; // system time (UTF) in millis
sensor_gps.time_utc_usec = utc_timestamp.nanoseconds() / 1000ULL; // system time (UTF) in millis
sensor_gps.satellites_used = 16;
sensor_gps.heading = heading_rad;
sensor_gps.heading_offset = 0.0f;
Expand Down Expand Up @@ -353,7 +354,7 @@ void MocapPose::WorkerThread()
#endif
const auto timestamp = rclcpp::Clock().now();
const auto gps_timestamp = QualisysToRosTimestamp(rtPacket->GetTimeStamp());
const auto gps_msg = impl_->PrepareGpsMessage(Pos, Q, gps_timestamp);
const auto gps_msg = impl_->PrepareGpsMessage(Pos, Q, gps_timestamp, timestamp);
const bool time_to_publish = (impl_->last_published_timestamp.seconds() +
impl_->publishing_timestep) <= timestamp.seconds();

Expand Down

0 comments on commit cc22c05

Please sign in to comment.