Copter: fix ModeGuided::set_destination_posvel

This commit is contained in:
Randy Mackay 2021-08-11 20:17:09 +09:00 committed by Andrew Tridgell
parent 9edb44151e
commit 54c4a9f88a
1 changed files with 1 additions and 2 deletions

View File

@ -414,8 +414,7 @@ void ModeGuided::set_velaccel(const Vector3f& velocity, const Vector3f& accelera
// set_destination_posvel - set guided mode position and velocity target
bool ModeGuided::set_destination_posvel(const Vector3f& destination, const Vector3f& velocity, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw)
{
set_destination_posvelaccel(destination, velocity, Vector3f(), use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw);
return true;
return set_destination_posvelaccel(destination, velocity, Vector3f(), use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw);
}
// set_destination_posvelaccel - set guided mode position, velocity and acceleration target