mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-25 00:31:36 +08:00
simulator: use usual type of timestamp
This commit is contained in:
@@ -270,7 +270,7 @@ GPSSIM::receive(int timeout)
|
||||
simulator::RawGPSData gps;
|
||||
sim->getGPSSample((uint8_t *)&gps, sizeof(gps));
|
||||
|
||||
static int64_t timestamp_last = 0;
|
||||
static uint64_t timestamp_last = 0;
|
||||
|
||||
if (gps.timestamp != timestamp_last) {
|
||||
_report_gps_pos.timestamp = hrt_absolute_time();
|
||||
|
||||
@@ -115,7 +115,7 @@ struct RawAirspeedData {
|
||||
|
||||
#pragma pack(push, 1)
|
||||
struct RawGPSData {
|
||||
int64_t timestamp;
|
||||
uint64_t timestamp;
|
||||
int32_t lat;
|
||||
int32_t lon;
|
||||
int32_t alt;
|
||||
|
||||
Reference in New Issue
Block a user