Skip to content

Commit 14713cb

Browse files
committed
changed timestamp to header.timestamp
1 parent 3d6a3c9 commit 14713cb

File tree

2 files changed

+4
-3
lines changed

2 files changed

+4
-3
lines changed

src/estimator.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -130,7 +130,7 @@ void Estimator::run()
130130
// Timing Setup
131131
//
132132

133-
const uint64_t now_us = RF_.sensors_.get_imu()->timestamp;
133+
const uint64_t now_us = RF_.sensors_.get_imu()->header.timestamp;
134134

135135
if (last_time_ == 0) {
136136
last_time_ = now_us;
@@ -223,7 +223,7 @@ void Estimator::run()
223223
// Save off adjust gyro measurements with estimated biases for control
224224
state_.angular_velocity = gyro_LPF_ - bias_;
225225

226-
attitude_.timestamp = state_.timestamp_us;
226+
attitude_.header.timestamp = state_.timestamp_us;
227227

228228
attitude_.q[0] = state_.attitude.w;
229229
attitude_.q[1] = state_.attitude.x;

src/rc.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -291,7 +291,8 @@ uint16_t RC::fake_rx(uint16_t *chan, uint16_t len, bool lost, bool failsafe) {
291291
rc_.failsafeActivated = failsafe;
292292
rc_.frameLost = lost;
293293
rc_.nChan = RC_STRUCT_CHANNELS;
294-
rc_.timestamp = RF_.board_.clock_micros();
294+
rc_.header.timestamp = RF_.board_.clock_micros();
295+
rc_.header.status = failsafe | lost;
295296
run();
296297
return len;
297298
};

0 commit comments

Comments
 (0)