diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index ee5a3cb220..57d276ffd4 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -84,7 +84,7 @@ static NOINLINE void send_attitude(mavlink_channel_t chan) { mavlink_msg_attitude_send( chan, - micros(), + millis(), ahrs.roll, ahrs.pitch, ahrs.yaw, @@ -418,7 +418,7 @@ static void NOINLINE send_raw_imu2(mavlink_channel_t chan) { mavlink_msg_scaled_pressure_send( chan, - micros(), + millis(), (float)barometer.get_pressure()/100.0, (float)(barometer.get_pressure() - barometer.get_ground_pressure())/100.0, (int)(barometer.get_temperature()*10)); diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index a54641492b..3122876f60 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -104,7 +104,7 @@ static NOINLINE void send_attitude(mavlink_channel_t chan) Vector3f omega = ahrs.get_gyro(); mavlink_msg_attitude_send( chan, - micros(), + millis(), ahrs.roll, ahrs.pitch - radians(g.pitch_trim*0.01), ahrs.yaw, @@ -377,7 +377,7 @@ static void NOINLINE send_raw_imu2(mavlink_channel_t chan) int32_t pressure = barometer.get_pressure(); mavlink_msg_scaled_pressure_send( chan, - micros(), + millis(), pressure/100.0, (pressure - barometer.get_ground_pressure())/100.0, barometer.get_temperature());