Skip to content

Commit

Permalink
add simulated gnss utc timestamp
Browse files Browse the repository at this point in the history
  • Loading branch information
PonomarevDA committed Nov 13, 2024
1 parent 14147fb commit f1f7d96
Showing 1 changed file with 13 additions and 0 deletions.
13 changes: 13 additions & 0 deletions src/uavcan_communicator/converters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

#include "converters.hpp"
#include <algorithm>
#include <chrono>

float clamp_float(float value, float min, float max) {
if (value < min) {
Expand Down Expand Up @@ -126,8 +127,20 @@ void DiffPressureRosToUavcan::ros_callback(IN_ROS_MSG_PTR in_ros_msg) {
broadcast();
}

// Simulate GNSS timestamp by wrapping the time to align with a typical GNSS time reference (e.g., GPS epoch).
// GPS epoch started on January 6, 1980, so we calculate the time since then.
uint64_t simulate_gnss_utc_timestamp_usec() {
auto now = std::chrono::system_clock::now();
auto duration_since_epoch = std::chrono::duration_cast<std::chrono::microseconds>(now.time_since_epoch());
constexpr uint64_t gps_epoch_offset_usec = 315964800000000ULL;
uint64_t gnss_utc_timestamp_usec = duration_since_epoch.count() - gps_epoch_offset_usec;
return gnss_utc_timestamp_usec;
}

void GpsRosToUavcan::ros_callback(IN_ROS_MSG_PTR in_ros_msg) {
out_uavcan_msg_.gnss_timestamp.usec = simulate_gnss_utc_timestamp_usec();
out_uavcan_msg_.gnss_time_standard = 2; // 2 stands for UTC

out_uavcan_msg_.latitude_deg_1e8 = in_ros_msg->latitude * 1e8;
out_uavcan_msg_.longitude_deg_1e8 = in_ros_msg->longitude * 1e8;
out_uavcan_msg_.height_msl_mm = in_ros_msg->altitude * 1e3;
Expand Down

0 comments on commit f1f7d96

Please sign in to comment.