don't use waypoint heading for landing descent

This commit is contained in:
Andreas Antener 2016-02-02 23:44:56 +01:00
parent b05465470a
commit 134e95efda

View File

@ -437,6 +437,7 @@ Mission::set_mission_items()
_mission_item.nav_cmd = NAV_CMD_TAKEOFF;
_mission_item.lat = _navigator->get_global_position()->lat;
_mission_item.lon = _navigator->get_global_position()->lon;
/* ignore yaw for takeoff items */
_mission_item.yaw = NAN;
_mission_item.altitude = takeoff_alt;
_mission_item.altitude_is_relative = false;
@ -479,6 +480,13 @@ Mission::set_mission_items()
new_work_item_type = WORK_ITEM_TYPE_DEFAULT;
}
/* ignore yaw for landing items */
/* XXX: if specified heading for landing is desired we could add another step before the descent
* that aligns the vehicle first */
if (_mission_item.nav_cmd == NAV_CMD_LAND) {
_mission_item.yaw = NAN;
}
/* handle non-position mission items such as commands */
} else {