From 474456e3493f974401d9174ed6e769532b4e41a6 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 4 Dec 2014 09:54:30 -0800 Subject: [PATCH] Copter: use guided_posvel for set_position_target messages --- ArduCopter/GCS_Mavlink.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index b510380fa9..e0efe0fa56 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1328,7 +1328,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) */ if (!pos_ignore && !vel_ignore && acc_ignore) { - guided_set_destination_spline(Vector3f(packet.x * 100.0f, packet.y * 100.0f, -packet.z * 100.0f), Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f)); + guided_set_destination_posvel(Vector3f(packet.x * 100.0f, packet.y * 100.0f, -packet.z * 100.0f), Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f)); } else if (pos_ignore && !vel_ignore && acc_ignore) { guided_set_velocity(Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f)); } else if (!pos_ignore && vel_ignore && acc_ignore) { @@ -1391,7 +1391,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) } if (!pos_ignore && !vel_ignore && acc_ignore) { - guided_set_destination_spline(pos_ned, Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f)); + guided_set_destination_posvel(pos_ned, Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f)); } else if (pos_ignore && !vel_ignore && acc_ignore) { guided_set_velocity(Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f)); } else if (!pos_ignore && vel_ignore && acc_ignore) {