Copter: Rename variable to correct the meaning (NFC)

This commit is contained in:
Dr.-Ing. Amilcar Do Carmo Lucas 2017-11-24 18:04:34 +01:00 committed by Randy Mackay
parent 8678d13e7b
commit bde1aaa2f6

View File

@ -1496,7 +1496,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
* bool force = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE;
*/
Vector3f pos_ned;
Vector3f pos_neu_cm; // position (North, East, Up coordinates) in centimeters
if(!pos_ignore) {
// sanity check location
@ -1529,7 +1529,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
loc.flags.terrain_alt = false;
break;
}
pos_ned = copter.pv_location_to_vector(loc);
pos_neu_cm = copter.pv_location_to_vector(loc);
}
// prepare yaw
@ -1545,13 +1545,13 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
}
if (!pos_ignore && !vel_ignore && acc_ignore) {
copter.guided_set_destination_posvel(pos_ned, 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_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 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;
} else if (!pos_ignore && vel_ignore && acc_ignore) {
if (copter.guided_set_destination(pos_ned, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative)) {
if (copter.guided_set_destination(pos_neu_cm, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative)) {
result = MAV_RESULT_ACCEPTED;
} else {
result = MAV_RESULT_FAILED;