Browse Source

Plane: Allow GUIDED mode to take advantage of crosstrack flag.

mission-4.1.18
Tom Pittenger 7 years ago committed by Tom Pittenger
parent
commit
518abfe1d0
  1. 3
      ArduPlane/commands.cpp
  2. 2
      ArduPlane/navigation.cpp

3
ArduPlane/commands.cpp

@ -91,6 +91,9 @@ void Plane::set_guided_WP(void) @@ -91,6 +91,9 @@ void Plane::set_guided_WP(void)
setup_glide_slope();
setup_turn_angle();
// disable crosstrack, head directly to the point
auto_state.crosstrack = false;
// reset loiter start time.
loiter.start_time_ms = 0;

2
ArduPlane/navigation.cpp

@ -190,7 +190,7 @@ void Plane::update_loiter(uint16_t radius) @@ -190,7 +190,7 @@ void Plane::update_loiter(uint16_t radius)
quadplane.guided_start();
}
} else if ((loiter.start_time_ms == 0 &&
control_mode == AUTO &&
(control_mode == AUTO || control_mode == GUIDED) &&
auto_state.crosstrack &&
get_distance(current_loc, next_WP_loc) > radius*3) ||
(control_mode == RTL && quadplane.available() && quadplane.rtl_mode == 1)) {

Loading…
Cancel
Save