mirror of https://github.com/ArduPilot/ardupilot
Rover: disable turning at low speeds when simple avoidance is active
This commit is contained in:
parent
b4fd9848df
commit
4f77f7545a
|
@ -433,8 +433,16 @@ void Mode::navigate_to_waypoint()
|
||||||
const float turn_rate = g2.sailboat.tacking() ? g2.wp_nav.get_pivot_rate() : 0.0f;
|
const float turn_rate = g2.sailboat.tacking() ? g2.wp_nav.get_pivot_rate() : 0.0f;
|
||||||
calc_steering_to_heading(desired_heading_cd, turn_rate);
|
calc_steering_to_heading(desired_heading_cd, turn_rate);
|
||||||
} else {
|
} else {
|
||||||
|
// retrieve turn rate from waypoint controller
|
||||||
|
float desired_turn_rate_rads = g2.wp_nav.get_turn_rate_rads();
|
||||||
|
|
||||||
|
// if simple avoidance is active at very low speed do not attempt to turn
|
||||||
|
if (g2.avoid.limits_active() && (fabsf(attitude_control.get_desired_speed()) <= attitude_control.get_stop_speed())) {
|
||||||
|
desired_turn_rate_rads = 0.0f;
|
||||||
|
}
|
||||||
|
|
||||||
// call turn rate steering controller
|
// call turn rate steering controller
|
||||||
calc_steering_from_turn_rate(g2.wp_nav.get_turn_rate_rads());
|
calc_steering_from_turn_rate(desired_turn_rate_rads);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue