mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: mode: use oa_wp_bearing_cd
This commit is contained in:
parent
db87285153
commit
d88e12b206
@ -394,7 +394,7 @@ void Mode::navigate_to_waypoint()
|
|||||||
desired_speed = calc_speed_nudge(desired_speed, g2.wp_nav.get_reversed());
|
desired_speed = calc_speed_nudge(desired_speed, g2.wp_nav.get_reversed());
|
||||||
calc_throttle(desired_speed, true);
|
calc_throttle(desired_speed, true);
|
||||||
|
|
||||||
float desired_heading_cd = g2.wp_nav.wp_bearing_cd();
|
float desired_heading_cd = g2.wp_nav.oa_wp_bearing_cd();
|
||||||
if (g2.sailboat.use_indirect_route(desired_heading_cd)) {
|
if (g2.sailboat.use_indirect_route(desired_heading_cd)) {
|
||||||
// sailboats use heading controller when tacking upwind
|
// sailboats use heading controller when tacking upwind
|
||||||
desired_heading_cd = g2.sailboat.calc_heading(desired_heading_cd);
|
desired_heading_cd = g2.sailboat.calc_heading(desired_heading_cd);
|
||||||
|
Loading…
Reference in New Issue
Block a user