mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: only use pivot steering in AUTO modes
This commit is contained in:
parent
5db9a87d31
commit
203073e3ba
@ -69,7 +69,7 @@ static bool auto_check_trigger(void)
|
|||||||
*/
|
*/
|
||||||
static bool use_pivot_steering(void)
|
static bool use_pivot_steering(void)
|
||||||
{
|
{
|
||||||
if (g.skid_steer_out && g.pivot_turn_angle != 0) {
|
if (control_mode >= AUTO && g.skid_steer_out && g.pivot_turn_angle != 0) {
|
||||||
int16_t bearing_error = wrap_180_cd(nav_controller->target_bearing_cd() - ahrs.yaw_sensor) / 100;
|
int16_t bearing_error = wrap_180_cd(nav_controller->target_bearing_cd() - ahrs.yaw_sensor) / 100;
|
||||||
if (abs(bearing_error) > g.pivot_turn_angle) {
|
if (abs(bearing_error) > g.pivot_turn_angle) {
|
||||||
return true;
|
return true;
|
||||||
|
Loading…
Reference in New Issue
Block a user