APM: Added STICK_MIXING option

this replaces the compile time option. Disabling during long distance
flights when the transmitter may be out of range is useful.
This commit is contained in:
Andrew Tridgell 2012-08-09 08:53:29 +10:00
parent 9a8fd4738e
commit 6e46db39a1
5 changed files with 12 additions and 13 deletions

View File

@ -64,7 +64,7 @@ static void stabilize()
// Mix Stick input to allow users to override control surfaces // Mix Stick input to allow users to override control surfaces
// ----------------------------------------------------------- // -----------------------------------------------------------
if ((control_mode < FLY_BY_WIRE_A) || if ((control_mode < FLY_BY_WIRE_A) ||
(ENABLE_STICK_MIXING == 1 && (g.stick_mixing &&
geofence_stickmixing() && geofence_stickmixing() &&
control_mode > FLY_BY_WIRE_B && control_mode > FLY_BY_WIRE_B &&
failsafe == FAILSAFE_NONE)) { failsafe == FAILSAFE_NONE)) {
@ -98,7 +98,7 @@ static void stabilize()
// important for steering on the ground during landing // important for steering on the ground during landing
// ----------------------------------------------- // -----------------------------------------------
if (control_mode <= FLY_BY_WIRE_B || if (control_mode <= FLY_BY_WIRE_B ||
(ENABLE_STICK_MIXING == 1 && (g.stick_mixing &&
geofence_stickmixing() && geofence_stickmixing() &&
failsafe == FAILSAFE_NONE)) { failsafe == FAILSAFE_NONE)) {
ch4_inf = (float)g.channel_rudder.radio_in - (float)g.channel_rudder.radio_trim; ch4_inf = (float)g.channel_rudder.radio_in - (float)g.channel_rudder.radio_trim;

View File

@ -70,13 +70,11 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
base_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED; base_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED;
} }
#if ENABLE_STICK_MIXING==ENABLED if (g.stick_mixing && control_mode != INITIALISING) {
if (control_mode != INITIALISING) {
// all modes except INITIALISING have some form of manual // all modes except INITIALISING have some form of manual
// override if stick mixing is enabled // override if stick mixing is enabled
base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED; base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
} }
#endif
#if HIL_MODE != HIL_MODE_DISABLED #if HIL_MODE != HIL_MODE_DISABLED
base_mode |= MAV_MODE_FLAG_HIL_ENABLED; base_mode |= MAV_MODE_FLAG_HIL_ENABLED;

View File

@ -69,6 +69,7 @@ public:
k_param_manual_level, k_param_manual_level,
k_param_land_pitch_cd, k_param_land_pitch_cd,
k_param_ins, k_param_ins,
k_param_stick_mixing,
// 110: Telemetry control // 110: Telemetry control
// //
@ -308,6 +309,7 @@ public:
AP_Int32 pack_capacity; // Battery pack capacity less reserve AP_Int32 pack_capacity; // Battery pack capacity less reserve
AP_Int8 inverted_flight_ch; // 0=disabled, 1-8 is channel for inverted flight trigger AP_Int8 inverted_flight_ch; // 0=disabled, 1-8 is channel for inverted flight trigger
AP_Int8 sonar_enabled; AP_Int8 sonar_enabled;
AP_Int8 stick_mixing;
// Camera // Camera
#if CAMERA == ENABLED #if CAMERA == ENABLED

View File

@ -65,6 +65,13 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Advanced // @User: Advanced
GSCALAR(manual_level, "MANUAL_LEVEL", MANUAL_LEVEL), GSCALAR(manual_level, "MANUAL_LEVEL", MANUAL_LEVEL),
// @Param: STICK_MIXING
// @DisplayName: Stick Mixing
// @Description: When enabled, this adds user stick input to the control surfaces in auto modes, allowing the user to have some degree of flight control without changing modes
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
GSCALAR(stick_mixing, "STICK_MIXING", 1),
// @Param: land_pitch_cd // @Param: land_pitch_cd
// @DisplayName: Landing Pitch // @DisplayName: Landing Pitch
// @Description: Used in autoland for planes without airspeed sensors in hundredths of a degree // @Description: Used in autoland for planes without airspeed sensors in hundredths of a degree

View File

@ -386,14 +386,6 @@
#endif #endif
//////////////////////////////////////////////////////////////////////////////
// ENABLE_STICK_MIXING
//
#ifndef ENABLE_STICK_MIXING
# define ENABLE_STICK_MIXING ENABLED
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// THROTTLE_OUT // THROTTLE_OUT
// //