mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 09:38:29 -04:00
Copter: reset ROI when requested, regardless of current MOUNT_MODE
This commit is contained in:
parent
d84c1cd3e4
commit
343a673762
@ -518,7 +518,7 @@ static void set_auto_yaw_look_at_heading(float angle_deg, float turn_rate_dps, i
|
|||||||
static void set_auto_yaw_roi(const Location &roi_location)
|
static void set_auto_yaw_roi(const Location &roi_location)
|
||||||
{
|
{
|
||||||
// if location is zero lat, lon and altitude turn off ROI
|
// if location is zero lat, lon and altitude turn off ROI
|
||||||
if (auto_yaw_mode == AUTO_YAW_ROI && (roi_location.alt == 0 && roi_location.lat == 0 && roi_location.lng == 0)) {
|
if (roi_location.alt == 0 && roi_location.lat == 0 && roi_location.lng == 0) {
|
||||||
// set auto yaw mode back to default assuming the active command is a waypoint command. A more sophisticated method is required to ensure we return to the proper yaw control for the active command
|
// set auto yaw mode back to default assuming the active command is a waypoint command. A more sophisticated method is required to ensure we return to the proper yaw control for the active command
|
||||||
set_auto_yaw_mode(get_default_auto_yaw_mode(false));
|
set_auto_yaw_mode(get_default_auto_yaw_mode(false));
|
||||||
#if MOUNT == ENABLED
|
#if MOUNT == ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user