diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 1d84008eee..9d4b2a0bf9 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1446,8 +1446,11 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg) // send request if (!pos_ignore && !vel_ignore && acc_ignore) { - copter.guided_set_destination_posvel(pos_vector, vel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative); - result = MAV_RESULT_ACCEPTED; + if (copter.guided_set_destination_posvel(pos_vector, vel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative)) { + result = MAV_RESULT_ACCEPTED; + } else { + result = MAV_RESULT_FAILED; + } } else if (pos_ignore && !vel_ignore && acc_ignore) { copter.guided_set_velocity(vel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative); result = MAV_RESULT_ACCEPTED; @@ -1545,8 +1548,11 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg) } if (!pos_ignore && !vel_ignore && acc_ignore) { - copter.guided_set_destination_posvel(pos_neu_cm, Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f), !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative); - result = MAV_RESULT_ACCEPTED; + if (copter.guided_set_destination_posvel(pos_neu_cm, Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f), !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative)) { + result = MAV_RESULT_ACCEPTED; + } else { + result = MAV_RESULT_FAILED; + } } else if (pos_ignore && !vel_ignore && acc_ignore) { copter.guided_set_velocity(Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f), !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative); result = MAV_RESULT_ACCEPTED;