Copter: use guided_posvel for set_position_target messages
This commit is contained in:
parent
bc29008233
commit
474456e349
@ -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) {
|
||||
|
Loading…
Reference in New Issue
Block a user