diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 60e2c976c9..5992f84be9 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -455,13 +455,13 @@ bool ModeGuided::set_attitude_target_provides_thrust() const return ((copter.g2.guided_options.get() & uint32_t(Options::SetAttitudeTarget_ThrustAsThrust)) != 0); } -// returns true if GUIDED_OPTIONS param suggests SET_ATTITUDE_TARGET's "thrust" field should be interpreted as thrust instead of climb rate +// returns true if GUIDED_OPTIONS param specifies position should be controlled (when velocity and/or acceleration control is active) bool ModeGuided::stabilizing_pos_xy() const { return !((copter.g2.guided_options.get() & uint32_t(Options::DoNotStabilizePositionXY)) != 0); } -// returns true if GUIDED_OPTIONS param suggests SET_ATTITUDE_TARGET's "thrust" field should be interpreted as thrust instead of climb rate +// returns true if GUIDED_OPTIONS param specifies velocity should be controlled (when acceleration control is active) bool ModeGuided::stabilizing_vel_xy() const { return !((copter.g2.guided_options.get() & uint32_t(Options::DoNotStabilizeVelocityXY)) != 0);