SITL: FDM structure is no longer a network protocol structure
remove unused fields and change comments
This commit is contained in:
parent
a6ef064950
commit
585e6dabb8
@ -258,7 +258,6 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm) const
|
|||||||
fdm.pitchDeg = degrees(p);
|
fdm.pitchDeg = degrees(p);
|
||||||
fdm.yawDeg = degrees(y);
|
fdm.yawDeg = degrees(y);
|
||||||
fdm.airspeed = airspeed;
|
fdm.airspeed = airspeed;
|
||||||
fdm.magic = 0x4c56414f;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
uint64_t Aircraft::get_wall_time_us() const
|
uint64_t Aircraft::get_wall_time_us() const
|
||||||
|
@ -8,10 +8,8 @@ class DataFlash_Class;
|
|||||||
|
|
||||||
namespace SITL {
|
namespace SITL {
|
||||||
|
|
||||||
struct PACKED sitl_fdm {
|
struct sitl_fdm {
|
||||||
// this is the packet sent by the simulator
|
// this is the structure passed between FDM models and the main SITL code
|
||||||
// to the APM executable to update the simulator state
|
|
||||||
// All values are little-endian
|
|
||||||
uint64_t timestamp_us;
|
uint64_t timestamp_us;
|
||||||
double latitude, longitude; // degrees
|
double latitude, longitude; // degrees
|
||||||
double altitude; // MSL
|
double altitude; // MSL
|
||||||
@ -21,7 +19,6 @@ struct PACKED sitl_fdm {
|
|||||||
double rollRate, pitchRate, yawRate; // degrees/s/s in body frame
|
double rollRate, pitchRate, yawRate; // degrees/s/s in body frame
|
||||||
double rollDeg, pitchDeg, yawDeg; // euler angles, degrees
|
double rollDeg, pitchDeg, yawDeg; // euler angles, degrees
|
||||||
double airspeed; // m/s
|
double airspeed; // m/s
|
||||||
uint32_t magic; // 0x4c56414f
|
|
||||||
};
|
};
|
||||||
|
|
||||||
// number of rc output channels
|
// number of rc output channels
|
||||||
|
Loading…
Reference in New Issue
Block a user