From 532ac607b27c3530a2fe78351b72d9cf6a0c5ef8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 24 Apr 2012 22:19:10 +1000 Subject: [PATCH] sitl: support MAVLink 1.0 builds --- libraries/Desktop/support/sitl.cpp | 26 ++++++++++++++++++-------- 1 file changed, 18 insertions(+), 8 deletions(-) diff --git a/libraries/Desktop/support/sitl.cpp b/libraries/Desktop/support/sitl.cpp index 9ee53f4440..ab7ab16f9c 100644 --- a/libraries/Desktop/support/sitl.cpp +++ b/libraries/Desktop/support/sitl.cpp @@ -344,6 +344,16 @@ void sitl_simstate_send(uint8_t chan) { double p, q, r; 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 // raw_imu message, which is in body frame @@ -357,12 +367,12 @@ void sitl_simstate_send(uint8_t chan) yaw -= 360; } - mavlink_msg_simstate_send((mavlink_channel_t)chan, - ToRad(sim_state.rollDeg), - ToRad(sim_state.pitchDeg), - ToRad(yaw), - sim_state.xAccel, - sim_state.yAccel, - sim_state.zAccel, - p, q, r); + mavlink_simstate_send(chan, + ToRad(sim_state.rollDeg), + ToRad(sim_state.pitchDeg), + ToRad(yaw), + sim_state.xAccel, + sim_state.yAccel, + sim_state.zAccel, + p, q, r); }