mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter: use the return code of the guided_set_destination_posvel() function calls
This commit is contained in:
parent
c7a2fcdc37
commit
ce3197e0ac
@ -1446,8 +1446,11 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|||||||
|
|
||||||
// send request
|
// send request
|
||||||
if (!pos_ignore && !vel_ignore && acc_ignore) {
|
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);
|
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;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
|
} else {
|
||||||
|
result = MAV_RESULT_FAILED;
|
||||||
|
}
|
||||||
} else if (pos_ignore && !vel_ignore && acc_ignore) {
|
} 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);
|
copter.guided_set_velocity(vel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative);
|
||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
@ -1545,8 +1548,11 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (!pos_ignore && !vel_ignore && acc_ignore) {
|
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);
|
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;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
|
} else {
|
||||||
|
result = MAV_RESULT_FAILED;
|
||||||
|
}
|
||||||
} else if (pos_ignore && !vel_ignore && acc_ignore) {
|
} 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);
|
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;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
|
Loading…
Reference in New Issue
Block a user