Sub: Remove throttle-zero flag

Doesn't help us like in Copter
This commit is contained in:
Jacob Walser 2017-04-05 14:43:43 -04:00
parent d794bf88cb
commit 3b1827ca21
4 changed files with 2 additions and 50 deletions

View File

@ -236,7 +236,6 @@ private:
uint8_t compass_mot : 1; // true if we are currently performing compassmot calibration
uint8_t motor_test : 1; // true if we are currently performing the motors test
uint8_t initialised : 1; // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
uint8_t throttle_zero : 1; // true if the throttle stick is at zero
uint8_t system_time_set : 1; // true if the system time has been set from the GPS
uint8_t gps_base_pos_set : 1; // true when the gps base position has been set (used for RTK gps only)
enum HomeState home_state : 2; // home status (unset, set, locked)
@ -621,7 +620,6 @@ private:
bool ekf_over_threshold();
void failsafe_ekf_event();
void failsafe_ekf_off_event(void);
bool should_disarm_on_failsafe();
void failsafe_battery_check(void);
void failsafe_gcs_check();
void failsafe_manual_control_check(void);
@ -683,7 +681,6 @@ private:
void handle_jsbutton_press(uint8_t button,bool shift=false,bool held=false);
JSButton* get_button(uint8_t index);
void default_js_buttons(void);
void set_throttle_zero_flag(int16_t throttle_control);
void init_barometer(bool save);
void read_barometer(void);
void init_rangefinder(void);

View File

@ -424,24 +424,3 @@ void Sub::failsafe_terrain_act()
init_disarm_motors();
}
}
bool Sub::should_disarm_on_failsafe()
{
switch (control_mode) {
case STABILIZE:
case ACRO:
// if throttle is zero OR vehicle is landed disarm motors
return ap.throttle_zero;
break;
case AUTO:
// if mission has not started AND vehicle is landed, disarm motors
return !ap.auto_armed;
break;
default:
// used for AltHold, Guided, Loiter, RTL, Circle, Drift, Sport, Flip, PosHold
// if landed disarm
// return ap.land_complete;
return false;
break;
}
}

View File

@ -54,9 +54,6 @@ void Sub::init_rc_in()
}
}
#endif
// initialise throttle_zero flag
ap.throttle_zero = true;
}
// init_rc_out -- initialise motors and check if pilot wants to perform ESC calibration
@ -84,27 +81,6 @@ void Sub::enable_motor_output()
motors.output_min();
}
#define THROTTLE_ZERO_DEBOUNCE_TIME_MS 400
// set_throttle_zero_flag - set throttle_zero flag from debounced throttle control
// throttle_zero is used to determine if the pilot intends to shut down the motors
// Basically, this signals when we are not flying. We are either on the ground
// or the pilot has shut down the vehicle in the air and it is free-falling
void Sub::set_throttle_zero_flag(int16_t throttle_control)
{
static uint32_t last_nonzero_throttle_ms = 0;
uint32_t tnow_ms = millis();
// if not using throttle interlock and non-zero throttle and not E-stopped,
// or using motor interlock and it's enabled, then motors are running,
// and we are flying. Immediately set as non-zero
if ((!ap.using_interlock && (throttle_control < 475 || throttle_control > 525) && !ap.motor_emergency_stop) || (ap.using_interlock && motors.get_interlock())) {
last_nonzero_throttle_ms = tnow_ms;
ap.throttle_zero = false;
} else if (tnow_ms - last_nonzero_throttle_ms > THROTTLE_ZERO_DEBOUNCE_TIME_MS) {
ap.throttle_zero = true;
}
}
// save_trim - adds roll and pitch trims from the radio to ahrs
void Sub::save_trim()
{

View File

@ -312,8 +312,8 @@ void Sub::update_auto_armed()
set_auto_armed(false);
return;
}
// if in stabilize or acro flight mode and throttle is zero, auto-armed should become false
if (mode_has_manual_throttle(control_mode) && ap.throttle_zero && !failsafe.manual_control) {
// if in stabilize or acro flight mode auto-armed should become false
if (mode_has_manual_throttle(control_mode) && !failsafe.manual_control) {
set_auto_armed(false);
}
} else {