Browse Source

Sub: Set neutral controls when switching to manual/acro mode

mission-4.1.18
dheideman 7 years ago committed by Jacob Walser
parent
commit
47d5de353d
  1. 4
      ArduSub/control_acro.cpp
  2. 4
      ArduSub/control_manual.cpp

4
ArduSub/control_acro.cpp

@ -11,6 +11,10 @@ bool Sub::acro_init() @@ -11,6 +11,10 @@ bool Sub::acro_init()
// set target altitude to zero for reporting
pos_control.set_alt_target(0);
// attitude hold inputs become thrust inputs in acro mode
// set to neutral to prevent chaotic behavior (esp. roll/pitch)
set_neutral_controls();
return true;
}

4
ArduSub/control_manual.cpp

@ -6,6 +6,10 @@ bool Sub::manual_init() @@ -6,6 +6,10 @@ bool Sub::manual_init()
// set target altitude to zero for reporting
pos_control.set_alt_target(0);
// attitude hold inputs become thrust inputs in manual mode
// set to neutral to prevent chaotic behavior (esp. roll/pitch)
set_neutral_controls();
return true;
}

Loading…
Cancel
Save