From bde1aaa2f69155c9a02119712f4f32be49dac3da Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar Do Carmo Lucas" Date: Fri, 24 Nov 2017 18:04:34 +0100 Subject: [PATCH] Copter: Rename variable to correct the meaning (NFC) --- ArduCopter/GCS_Mavlink.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 2059982d67..569b2769c7 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -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;