mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
Copter: rename "estop" to "emergency stop".
No functional change
This commit is contained in:
parent
9d9f20a6cb
commit
4e51ce6d75
@ -146,9 +146,9 @@ void set_using_interlock(bool b)
|
||||
}
|
||||
}
|
||||
|
||||
void set_motor_estop(bool b)
|
||||
void set_motor_emergency_stop(bool b)
|
||||
{
|
||||
if(ap.motor_estop != b) {
|
||||
ap.motor_estop = b;
|
||||
if(ap.motor_emergency_stop != b) {
|
||||
ap.motor_emergency_stop = b;
|
||||
}
|
||||
}
|
@ -352,7 +352,7 @@ static union {
|
||||
uint8_t gps_base_pos_set : 1; // 17 // true when the gps base position has been set (used for RTK gps only)
|
||||
enum HomeState home_state : 2; // 18,19 // home status (unset, set, locked)
|
||||
uint8_t using_interlock : 1; // 20 // aux switch motor interlock function is in use
|
||||
uint8_t motor_estop : 1; // 21 // motor estop switch, shuts off motors when enabled
|
||||
uint8_t motor_emergency_stop: 1; // 21 // motor estop switch, shuts off motors when enabled
|
||||
};
|
||||
uint32_t value;
|
||||
} ap;
|
||||
|
@ -379,42 +379,42 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @Param: CH7_OPT
|
||||
// @DisplayName: Channel 7 option
|
||||
// @Description: Select which function if performed when CH7 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:E-Stop, 32:Motor Interlock
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock
|
||||
// @User: Standard
|
||||
GSCALAR(ch7_option, "CH7_OPT", AUXSW_DO_NOTHING),
|
||||
|
||||
// @Param: CH8_OPT
|
||||
// @DisplayName: Channel 8 option
|
||||
// @Description: Select which function if performed when CH8 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:E-Stop, 32:Motor Interlock
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock
|
||||
// @User: Standard
|
||||
GSCALAR(ch8_option, "CH8_OPT", AUXSW_DO_NOTHING),
|
||||
|
||||
// @Param: CH9_OPT
|
||||
// @DisplayName: Channel 9 option
|
||||
// @Description: Select which function if performed when CH9 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:E-Stop, 32:Motor Interlock
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock
|
||||
// @User: Standard
|
||||
GSCALAR(ch9_option, "CH9_OPT", AUXSW_DO_NOTHING),
|
||||
|
||||
// @Param: CH10_OPT
|
||||
// @DisplayName: Channel 10 option
|
||||
// @Description: Select which function if performed when CH10 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:E-Stop, 32:Motor Interlock
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock
|
||||
// @User: Standard
|
||||
GSCALAR(ch10_option, "CH10_OPT", AUXSW_DO_NOTHING),
|
||||
|
||||
// @Param: CH11_OPT
|
||||
// @DisplayName: Channel 11 option
|
||||
// @Description: Select which function if performed when CH11 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:E-Stop, 32:Motor Interlock
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock
|
||||
// @User: Standard
|
||||
GSCALAR(ch11_option, "CH11_OPT", AUXSW_DO_NOTHING),
|
||||
|
||||
// @Param: CH12_OPT
|
||||
// @DisplayName: Channel 12 option
|
||||
// @Description: Select which function if performed when CH12 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:E-Stop, 32:Motor Interlock
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock
|
||||
// @User: Standard
|
||||
GSCALAR(ch12_option, "CH12_OPT", AUXSW_DO_NOTHING),
|
||||
|
||||
|
@ -83,13 +83,13 @@ static void auto_disarm_check()
|
||||
}
|
||||
|
||||
// allow auto disarm in manual flight modes or Loiter/AltHold if we're landed
|
||||
// always allow auto disarm if using interlock switch or motors are E-stopped
|
||||
if (mode_has_manual_throttle(control_mode) || ap.land_complete || (ap.using_interlock && !motors.get_interlock()) || ap.motor_estop) {
|
||||
// always allow auto disarm if using interlock switch or motors are Emergency Stopped
|
||||
if (mode_has_manual_throttle(control_mode) || ap.land_complete || (ap.using_interlock && !motors.get_interlock()) || ap.motor_emergency_stop) {
|
||||
auto_disarming_counter++;
|
||||
|
||||
// use a shorter delay if using throttle interlock switch or E-stop, because it is less
|
||||
// use a shorter delay if using throttle interlock switch or Emergency Stop, because it is less
|
||||
// obvious the copter is armed as the motors will not be spinning
|
||||
if (ap.using_interlock || ap.motor_estop){
|
||||
if (ap.using_interlock || ap.motor_emergency_stop){
|
||||
delay = AUTO_DISARMING_DELAY_SHORT;
|
||||
} else {
|
||||
delay = AUTO_DISARMING_DELAY_LONG;
|
||||
@ -180,12 +180,12 @@ static bool init_arm_motors(bool arming_from_gcs)
|
||||
return false;
|
||||
}
|
||||
|
||||
// if we are not E-Stop switch option, force Estop false to ensure motors
|
||||
// if we are not using Emergency Stop switch option, force Estop false to ensure motors
|
||||
// can run normally
|
||||
if (!check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP)){
|
||||
set_motor_estop(false);
|
||||
set_motor_emergency_stop(false);
|
||||
// if we are using motor Estop switch, it must not be in Estop position
|
||||
} else if (check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP) && ap.motor_estop){
|
||||
} else if (check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP) && ap.motor_emergency_stop){
|
||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Motor Emergency Stopped"));
|
||||
AP_Notify::flags.armed = false;
|
||||
return false;
|
||||
@ -240,7 +240,7 @@ static bool pre_arm_checks(bool display_failure)
|
||||
return true;
|
||||
}
|
||||
|
||||
// check if motor interlock and E-stop aux switches are used
|
||||
// check if motor interlock and Emergency Stop aux switches are used
|
||||
// at the same time. This cannot be allowed.
|
||||
if (check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK) && check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP)){
|
||||
if (display_failure) {
|
||||
@ -261,9 +261,9 @@ static bool pre_arm_checks(bool display_failure)
|
||||
return false;
|
||||
}
|
||||
|
||||
// if we are using Motor E-Stop aux switch, check it is not enabled
|
||||
// if we are using Motor Emergency Stop aux switch, check it is not enabled
|
||||
// and warn if it is
|
||||
if (check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP) && ap.motor_estop){
|
||||
if (check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP) && ap.motor_emergency_stop){
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Motor Emergency Stopped"));
|
||||
}
|
||||
@ -792,11 +792,11 @@ static void motors_output()
|
||||
motor_test_output();
|
||||
} else {
|
||||
if (!ap.using_interlock){
|
||||
// if not using interlock switch, set according to E-Stop status
|
||||
// where E-Stop is forced false during arming if E-Stop switch
|
||||
// if not using interlock switch, set according to Emergency Stop status
|
||||
// where Emergency Stop is forced false during arming if Emergency Stop switch
|
||||
// is not used. Interlock enabled means motors run, so we must
|
||||
// invert motor_estop status for motors to run.
|
||||
motors.set_interlock(!ap.motor_estop);
|
||||
// invert motor_emergency_stop status for motors to run.
|
||||
motors.set_interlock(!ap.motor_emergency_stop);
|
||||
}
|
||||
motors.output();
|
||||
}
|
||||
|
@ -184,7 +184,7 @@ static void set_throttle_zero_flag(int16_t throttle_control)
|
||||
// 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 > 0) && !ap.motor_estop) || (ap.using_interlock && motors.get_interlock())) {
|
||||
if ((!ap.using_interlock && (throttle_control > 0) && !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) {
|
||||
|
@ -556,8 +556,8 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
||||
break;
|
||||
|
||||
case AUXSW_MOTOR_ESTOP:
|
||||
// Turn on E-Stop logic when channel is high
|
||||
set_motor_estop(ch_flag == AUX_SWITCH_HIGH);
|
||||
// Turn on Emergency Stop logic when channel is high
|
||||
set_motor_emergency_stop(ch_flag == AUX_SWITCH_HIGH);
|
||||
break;
|
||||
|
||||
case AUXSW_MOTOR_INTERLOCK:
|
||||
|
Loading…
Reference in New Issue
Block a user