1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 12:55:19 +03:00

Previously, at minimum throttle, the quad would do absolutely no self-leveling

and simply run the motors at constant minthrottle.  This allowed the chance
for the quad to lose control during flight if the throttle was set to minimum,
say, to drop from a high altitude to a lower one.

With this edit, the quad will still self-level at minimum throttle when armed,
allowing for safe decents from altitude.  To prevent motors spinning when
arming/disarming, the yaw input is ignored if the throttle is at minimum and
we're using the sticks to arm/disarm.

Conflicts:
	src/main/flight/mixer.c
This commit is contained in:
Dominic Clifton 2015-03-09 23:44:03 +01:00
parent 1b1163da10
commit acabbf41db
4 changed files with 30 additions and 8 deletions

View file

@ -118,6 +118,7 @@ Re-apply any new defaults as desired.
| disarm_kill_switch | Enabled by default. Disarms the motors independently of throttle value. Setting to 0 reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel. | 0 | 1 | 1 | Master | UINT8 |
| auto_disarm_delay | | 0 | 60 | 5 | Master | UINT8 |
| small_angle | If the copter tilt angle exceed this value the copter will refuse to arm. default is 25°. | 0 | 180 | 25 | Master | UINT8 |
| disable_pid_at_min_throttle | If enabled, the copter will not process the pid algorithm at minimum throttle. | 0 | 1 | 0 | Master | UINT8 |
| flaps_speed | | 0 | 100 | 0 | Master | UINT8 |
| fixedwing_althold_dir | | -1 | 1 | 1 | Master | INT8 |
| reboot_character | | 48 | 126 | 82 | Master | UINT8 |

View file

@ -25,31 +25,48 @@
#include "common/axis.h"
#include "common/maths.h"
#include "common/color.h"
#include "drivers/system.h"
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/pwm_output.h"
#include "drivers/pwm_mapping.h"
#include "drivers/pwm_rx.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/serial.h"
#include "drivers/system.h"
#include "rx/rx.h"
#include "io/gimbal.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "io/gps.h"
#include "io/serial.h"
#include "io/ledstrip.h"
#include "sensors/sensors.h"
#include "sensors/acceleration.h"
#include "sensors/boardalignment.h"
#include "sensors/gyro.h"
#include "sensors/battery.h"
#include "sensors/barometer.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/lowpass.h"
#include "flight/failsafe.h"
#include "flight/navigation.h"
#include "telemetry/telemetry.h"
#include "config/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
#define GIMBAL_SERVO_PITCH 0
#define GIMBAL_SERVO_ROLL 1
@ -695,8 +712,10 @@ void mixTable(void)
motor[i] = constrain(motor[i], escAndServoConfig->mincommand, flight3DConfig->deadband3d_low);
}
} else {
// Don't spin the motors if FEATURE_MOTOR_STOP is enabled and we're
// at minimum throttle.
// If we're at minimum throttle and FEATURE_MOTOR_STOP enabled,
// do not spin the motors.
// If we're at minimum throttle and disable_pid_at_min_throttle
// is enabled, spin motors at minimum throttle.
motor[i] = constrain(motor[i], escAndServoConfig->minthrottle, escAndServoConfig->maxthrottle);
if ((rcData[THROTTLE]) < rxConfig->mincheck) {
if (feature(FEATURE_MOTOR_STOP)) {

View file

@ -58,17 +58,20 @@
static escAndServoConfig_t *escAndServoConfig;
static pidProfile_t *pidProfile;
// true if arming is done via the sticks (as opposed to a switch)
static bool isUsingSticksToArm = true;
int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW
uint32_t rcModeActivationMask; // one bit per mode defined in boxId_e
bool areUsingSticksToArm(void)
bool isUsingSticksForArming(void)
{
return isUsingSticksToArm;
}
bool areSticksInApModePosition(uint16_t ap_mode)
{
return ABS(rcCommand[ROLL]) < ap_mode && ABS(rcCommand[PITCH]) < ap_mode;

View file

@ -525,12 +525,10 @@ void processRx(void)
}
// When armed and motors aren't spinning, disarm board after delay so users without buzzer won't lose fingers.
// mixTable constrains motor commands, so checking throttleStatus is enough
if (
ARMING_FLAG(ARMED)
if (ARMING_FLAG(ARMED)
&& feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING)
&& masterConfig.auto_disarm_delay != 0
&& areUsingSticksToArm()
) {
&& isUsingSticksForArming()) {
if (throttleStatus == THROTTLE_LOW) {
if ((int32_t)(disarmAt - millis()) < 0) // delay is over
mwDisarm();
@ -705,11 +703,12 @@ void loop(void)
// If we're armed, at minimum throttle, and we do arming via the
// sticks, do not process yaw input from the rx. We do this so the
// motors do not spin up while we are trying to arm or disarm.
if (areUsingSticksToArm() &&
if (isUsingSticksForArming() &&
rcData[THROTTLE] <= masterConfig.rxConfig.mincheck) {
rcCommand[YAW] = 0;
}
if (currentProfile->throttle_correction_value && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE))) {
rcCommand[THROTTLE] += calculateThrottleAngleCorrection(currentProfile->throttle_correction_value);
}