mirror of https://github.com/ArduPilot/ardupilot
SITL: AirSim: Store last timestamp only
Also change the datatype of deltat
This commit is contained in:
parent
86a70e5797
commit
80bbadf9ca
|
@ -262,8 +262,8 @@ void AirSim::recv_fdm()
|
|||
|
||||
dcm.from_euler(state.pose.roll, state.pose.pitch, state.pose.yaw);
|
||||
|
||||
if (last_state.timestamp) {
|
||||
double deltat = state.timestamp - last_state.timestamp;
|
||||
if (last_timestamp) {
|
||||
int deltat = state.timestamp - last_timestamp;
|
||||
time_now_us += deltat;
|
||||
|
||||
if (deltat > 0 && deltat < 100000) {
|
||||
|
@ -312,7 +312,7 @@ void AirSim::recv_fdm()
|
|||
velocity_ef.z);
|
||||
#endif
|
||||
|
||||
last_state = state;
|
||||
last_timestamp = state.timestamp;
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -66,6 +66,7 @@ private:
|
|||
double average_frame_time;
|
||||
uint64_t frame_counter;
|
||||
uint64_t last_frame_count;
|
||||
uint64_t last_timestamp;
|
||||
|
||||
void send_servos(const struct sitl_input &input);
|
||||
void recv_fdm();
|
||||
|
@ -107,7 +108,7 @@ private:
|
|||
struct {
|
||||
struct float_array rc_channels;
|
||||
} rc;
|
||||
} state, last_state;
|
||||
} state;
|
||||
|
||||
// table to aid parsing of JSON sensor data
|
||||
struct keytable {
|
||||
|
|
Loading…
Reference in New Issue