Plane: Allow GUIDED mode to take advantage of crosstrack flag.
This commit is contained in:
parent
7b1157e2d8
commit
518abfe1d0
@ -91,6 +91,9 @@ void Plane::set_guided_WP(void)
|
|||||||
setup_glide_slope();
|
setup_glide_slope();
|
||||||
setup_turn_angle();
|
setup_turn_angle();
|
||||||
|
|
||||||
|
// disable crosstrack, head directly to the point
|
||||||
|
auto_state.crosstrack = false;
|
||||||
|
|
||||||
// reset loiter start time.
|
// reset loiter start time.
|
||||||
loiter.start_time_ms = 0;
|
loiter.start_time_ms = 0;
|
||||||
|
|
||||||
|
@ -190,7 +190,7 @@ void Plane::update_loiter(uint16_t radius)
|
|||||||
quadplane.guided_start();
|
quadplane.guided_start();
|
||||||
}
|
}
|
||||||
} else if ((loiter.start_time_ms == 0 &&
|
} else if ((loiter.start_time_ms == 0 &&
|
||||||
control_mode == AUTO &&
|
(control_mode == AUTO || control_mode == GUIDED) &&
|
||||||
auto_state.crosstrack &&
|
auto_state.crosstrack &&
|
||||||
get_distance(current_loc, next_WP_loc) > radius*3) ||
|
get_distance(current_loc, next_WP_loc) > radius*3) ||
|
||||||
(control_mode == RTL && quadplane.available() && quadplane.rtl_mode == 1)) {
|
(control_mode == RTL && quadplane.available() && quadplane.rtl_mode == 1)) {
|
||||||
|
Loading…
Reference in New Issue
Block a user