Skip to content

Commit

Permalink
Copter: auto yaw point-at-next-wp checks wpnav get-yaw bool
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Aug 21, 2023
1 parent a34ad1f commit e65314c
Showing 1 changed file with 5 additions and 3 deletions.
8 changes: 5 additions & 3 deletions ArduCopter/autoyaw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -266,8 +266,8 @@ float Mode::AutoYaw::yaw_cd()
default:
// point towards next waypoint.
// we don't use wp_bearing because we don't want the copter to turn too much during flight
_yaw_angle_cd = copter.pos_control->get_yaw_cd();
break;
IGNORE_RETURN(copter.pos_control->get_yaw_cd(_yaw_angle_cd));
break;
}

return _yaw_angle_cd;
Expand All @@ -289,7 +289,9 @@ float Mode::AutoYaw::rate_cds()
break;

case Mode::LOOK_AT_NEXT_WP:
_yaw_rate_cds = copter.pos_control->get_yaw_rate_cds();
if (!copter.pos_control->get_yaw_rate_cds(_yaw_rate_cds)) {
_yaw_rate_cds = 0.0f;
}
break;

case Mode::PILOT_RATE:
Expand Down

0 comments on commit e65314c

Please sign in to comment.