mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
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:
parent
9a8fd4738e
commit
6e46db39a1
@ -64,7 +64,7 @@ static void stabilize()
|
||||
// Mix Stick input to allow users to override control surfaces
|
||||
// -----------------------------------------------------------
|
||||
if ((control_mode < FLY_BY_WIRE_A) ||
|
||||
(ENABLE_STICK_MIXING == 1 &&
|
||||
(g.stick_mixing &&
|
||||
geofence_stickmixing() &&
|
||||
control_mode > FLY_BY_WIRE_B &&
|
||||
failsafe == FAILSAFE_NONE)) {
|
||||
@ -98,7 +98,7 @@ static void stabilize()
|
||||
// important for steering on the ground during landing
|
||||
// -----------------------------------------------
|
||||
if (control_mode <= FLY_BY_WIRE_B ||
|
||||
(ENABLE_STICK_MIXING == 1 &&
|
||||
(g.stick_mixing &&
|
||||
geofence_stickmixing() &&
|
||||
failsafe == FAILSAFE_NONE)) {
|
||||
ch4_inf = (float)g.channel_rudder.radio_in - (float)g.channel_rudder.radio_trim;
|
||||
|
@ -70,13 +70,11 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
|
||||
base_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED;
|
||||
}
|
||||
|
||||
#if ENABLE_STICK_MIXING==ENABLED
|
||||
if (control_mode != INITIALISING) {
|
||||
if (g.stick_mixing && control_mode != INITIALISING) {
|
||||
// all modes except INITIALISING have some form of manual
|
||||
// override if stick mixing is enabled
|
||||
base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if HIL_MODE != HIL_MODE_DISABLED
|
||||
base_mode |= MAV_MODE_FLAG_HIL_ENABLED;
|
||||
|
@ -69,6 +69,7 @@ public:
|
||||
k_param_manual_level,
|
||||
k_param_land_pitch_cd,
|
||||
k_param_ins,
|
||||
k_param_stick_mixing,
|
||||
|
||||
// 110: Telemetry control
|
||||
//
|
||||
@ -308,6 +309,7 @@ public:
|
||||
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 sonar_enabled;
|
||||
AP_Int8 stick_mixing;
|
||||
|
||||
// Camera
|
||||
#if CAMERA == ENABLED
|
||||
|
@ -65,6 +65,13 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @User: Advanced
|
||||
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
|
||||
// @DisplayName: Landing Pitch
|
||||
// @Description: Used in autoland for planes without airspeed sensors in hundredths of a degree
|
||||
|
@ -386,14 +386,6 @@
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// ENABLE_STICK_MIXING
|
||||
//
|
||||
#ifndef ENABLE_STICK_MIXING
|
||||
# define ENABLE_STICK_MIXING ENABLED
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// THROTTLE_OUT
|
||||
//
|
||||
|
Loading…
Reference in New Issue
Block a user