diff --git a/libraries/SITL/SIM_Aircraft.cpp b/libraries/SITL/SIM_Aircraft.cpp index 0f6a622ab6..6cf84e1591 100644 --- a/libraries/SITL/SIM_Aircraft.cpp +++ b/libraries/SITL/SIM_Aircraft.cpp @@ -258,7 +258,6 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm) const fdm.pitchDeg = degrees(p); fdm.yawDeg = degrees(y); fdm.airspeed = airspeed; - fdm.magic = 0x4c56414f; } uint64_t Aircraft::get_wall_time_us() const diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index 4cf492740f..dc4aa7113a 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -8,10 +8,8 @@ class DataFlash_Class; namespace SITL { -struct PACKED sitl_fdm { - // this is the packet sent by the simulator - // to the APM executable to update the simulator state - // All values are little-endian +struct sitl_fdm { + // this is the structure passed between FDM models and the main SITL code uint64_t timestamp_us; double latitude, longitude; // degrees double altitude; // MSL @@ -21,7 +19,6 @@ struct PACKED sitl_fdm { double rollRate, pitchRate, yawRate; // degrees/s/s in body frame double rollDeg, pitchDeg, yawDeg; // euler angles, degrees double airspeed; // m/s - uint32_t magic; // 0x4c56414f }; // number of rc output channels