Navigator: RTL_direct: onyl start precision land if param is set to enable

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
Silvan Fuhrer 2024-11-07 15:40:03 +01:00
parent 1abc27dd1f
commit 0ecc8278b6
2 changed files with 4 additions and 2 deletions

View File

@ -978,7 +978,7 @@ void MissionBlock::startPrecLand(uint16_t land_precision)
_navigator->get_precland()->set_mode(PrecLandMode::Opportunistic);
_navigator->get_precland()->on_activation();
} else { //_mission_item.land_precision == 2
} else if (_mission_item.land_precision == 2) {
_navigator->get_precland()->set_mode(PrecLandMode::Required);
_navigator->get_precland()->on_activation();
}

View File

@ -369,7 +369,9 @@ void RtlDirect::set_rtl_item()
_mission_item.land_precision = _param_rtl_pld_md.get();
startPrecLand(_mission_item.land_precision);
if (_mission_item.land_precision > 0) {
startPrecLand(_mission_item.land_precision);
}
mavlink_log_info(_navigator->get_mavlink_log_pub(), "RTL: land at destination\t");
events::send(events::ID("rtl_land_at_destination"), events::Log::Info, "RTL: land at destination");