sitl: support MAVLink 1.0 builds

This commit is contained in:
Andrew Tridgell 2012-04-24 22:19:10 +10:00
parent cbecb3eff9
commit 532ac607b2

View File

@ -344,6 +344,16 @@ void sitl_simstate_send(uint8_t chan)
{ {
double p, q, r; double p, q, r;
float yaw; float yaw;
extern void mavlink_simstate_send(uint8_t chan,
float roll,
float pitch,
float yaw,
float xAcc,
float yAcc,
float zAcc,
float p,
float q,
float r);
// we want the gyro values to be directly comparable to the // we want the gyro values to be directly comparable to the
// raw_imu message, which is in body frame // raw_imu message, which is in body frame
@ -357,7 +367,7 @@ void sitl_simstate_send(uint8_t chan)
yaw -= 360; yaw -= 360;
} }
mavlink_msg_simstate_send((mavlink_channel_t)chan, mavlink_simstate_send(chan,
ToRad(sim_state.rollDeg), ToRad(sim_state.rollDeg),
ToRad(sim_state.pitchDeg), ToRad(sim_state.pitchDeg),
ToRad(yaw), ToRad(yaw),