mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-07 01:04:19 +08:00
Fix yaw handling for land command
This commit is contained in:
@@ -539,11 +539,13 @@ MissionBlock::set_land_item(struct mission_item_s *item, bool at_current_locatio
|
||||
if (at_current_location) {
|
||||
item->lat = _navigator->get_global_position()->lat;
|
||||
item->lon = _navigator->get_global_position()->lon;
|
||||
item->yaw = _navigator->get_global_position()->yaw;
|
||||
|
||||
/* use home position */
|
||||
} else {
|
||||
item->lat = _navigator->get_home_position()->lat;
|
||||
item->lon = _navigator->get_home_position()->lon;
|
||||
item->yaw = _navigator->get_home_position()->yaw;
|
||||
}
|
||||
|
||||
item->altitude = 0;
|
||||
|
||||
Reference in New Issue
Block a user