GCS_MAVLink: do not send_vibration on APM2

This commit is contained in:
Randy Mackay 2015-06-12 18:27:58 +09:00
parent 0d239d2746
commit 76fdfdfcf2
1 changed files with 3 additions and 1 deletions

View File

@ -1322,15 +1322,17 @@ void GCS_MAVLINK::send_local_position(const AP_AHRS &ahrs) const
*/
void GCS_MAVLINK::send_vibration(const AP_InertialSensor &ins) const
{
#if INS_VIBRATION_CHECK
Vector3f vibration = ins.get_vibration_levels();
mavlink_msg_vibration_send(
chan,
hal.scheduler->millis(),
hal.scheduler->micros64(),
vibration.x,
vibration.y,
vibration.z,
ins.get_accel_clip_count(0),
ins.get_accel_clip_count(1),
ins.get_accel_clip_count(2));
#endif
}