ArduCopter: rename throttle failsafe parameters.

Switch to LAND flight mode if throttle failsafe triggers and we do not have a GPS.
THR_FAILSAFE renamed to FS_THR_ENABLE.
THR_FS_VALUE renamed to FS_THR_VALUE.
THR_FS_ACTION removed (action is now controlled by setting FS_THR parameter).
This commit is contained in:
rmackay9 2012-12-10 23:38:43 +09:00
parent 0b815d9afb
commit 44773d1f2a
7 changed files with 30 additions and 42 deletions

View File

@ -172,9 +172,9 @@ public:
k_param_rc_11, k_param_rc_11,
k_param_throttle_min, k_param_throttle_min,
k_param_throttle_max, k_param_throttle_max,
k_param_throttle_fs_enabled, k_param_failsafe_throttle,
k_param_throttle_fs_action, k_param_throttle_fs_action, // remove
k_param_throttle_fs_value, k_param_failsafe_throttle_value,
k_param_throttle_cruise, k_param_throttle_cruise,
k_param_esc_calibrate, k_param_esc_calibrate,
k_param_radio_tuning, k_param_radio_tuning,
@ -290,9 +290,8 @@ public:
// //
AP_Int16 throttle_min; AP_Int16 throttle_min;
AP_Int16 throttle_max; AP_Int16 throttle_max;
AP_Int8 throttle_fs_enabled; AP_Int8 failsafe_throttle;
AP_Int8 throttle_fs_action; AP_Int16 failsafe_throttle_value;
AP_Int16 throttle_fs_value;
AP_Int16 throttle_cruise; AP_Int16 throttle_cruise;
// Flight modes // Flight modes

View File

@ -281,20 +281,18 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Standard // @User: Standard
GSCALAR(throttle_max, "THR_MAX", MAXIMUM_THROTTLE), GSCALAR(throttle_max, "THR_MAX", MAXIMUM_THROTTLE),
// @Param: THR_FAILSAFE // @Param: FS_THR_ENABLE
// @DisplayName: Throttle Failsafe Enable // @DisplayName: Throttle Failsafe Enable
// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel // @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
// @Values: 0:Disabled,1:Enabled // @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode
// @User: Standard // @User: Standard
GSCALAR(throttle_fs_enabled, "THR_FAILSAFE", THROTTLE_FAILSAFE), GSCALAR(failsafe_throttle, "FS_THR_ENABLE", FS_THR_DISABLED),
GSCALAR(throttle_fs_action, "THR_FS_ACTION", THROTTLE_FAILSAFE_ACTION), // @Param: FS_THR_VALUE
// @Param: THR_FS_VALUE
// @DisplayName: Throttle Failsafe Value // @DisplayName: Throttle Failsafe Value
// @Description: The PWM level on channel 3 below which throttle sailsafe triggers // @Description: The PWM level on channel 3 below which throttle sailsafe triggers
// @User: Standard // @User: Standard
GSCALAR(throttle_fs_value, "THR_FS_VALUE", THROTTLE_FS_VALUE), GSCALAR(failsafe_throttle_value, "FS_THR_VALUE", FS_THR_VALUE_DEFAULT),
// @Param: TRIM_THROTTLE // @Param: TRIM_THROTTLE
// @DisplayName: Throttle Trim // @DisplayName: Throttle Trim

View File

@ -294,11 +294,11 @@ static void do_nav_wp()
// do_land - initiate landing procedure // do_land - initiate landing procedure
static void do_land() static void do_land()
{ {
wp_control = LOITER_MODE;
set_throttle_mode(THROTTLE_LAND);
// hold at our current location // hold at our current location
set_next_WP(&current_loc); set_next_WP(&current_loc);
wp_control = LOITER_MODE;
set_throttle_mode(THROTTLE_LAND);
} }
static void do_loiter_unlimited() static void do_loiter_unlimited()

View File

@ -414,22 +414,17 @@
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// THROTTLE_FAILSAFE // Throttle Failsafe
// THROTTLE_FS_VALUE
// THROTTLE_FAILSAFE_ACTION
// //
#ifndef THROTTLE_FAILSAFE // possible values for FS_THR parameter
# define THROTTLE_FAILSAFE DISABLED #define FS_THR_DISABLED 0
#endif #define FS_THR_ENABLED_ALWAYS_RTL 1
#ifndef THROTTE_FS_VALUE #define FS_THR_ENABLED_CONTINUE_MISSION 2
# define THROTTLE_FS_VALUE 975
#ifndef FS_THR_VALUE_DEFAULT
# define FS_THR_VALUE_DEFAULT 975
#endif #endif
#define THROTTLE_FAILSAFE_ACTION_ALWAYS_RTL 1
#define THROTTLE_FAILSAFE_ACTION_CONTINUE_MISSION 2
#ifndef THROTTLE_FAILSAFE_ACTION
# define THROTTLE_FAILSAFE_ACTION THROTTLE_FAILSAFE_ACTION_CONTINUE_MISSION
#endif
#ifndef MINIMUM_THROTTLE #ifndef MINIMUM_THROTTLE
# define MINIMUM_THROTTLE 130 # define MINIMUM_THROTTLE 130

View File

@ -21,21 +21,17 @@ static void failsafe_on_event()
}else if(ap.home_is_set == true) { }else if(ap.home_is_set == true) {
set_mode(RTL); set_mode(RTL);
}else{ }else{
// We have no GPS so we will crash land in alt hold mode // We have no GPS so we will land
// the low throttle will bring us down at the maximum set_mode(LAND);
// the low throttle will bring us down at the maximum descent speed
// To-Do: make LAND a throttle mode so it can operate without GPS
set_mode(ALT_HOLD);
set_new_altitude(0);
} }
break; break;
case AUTO: case AUTO:
// throttle_fs_action is 1 do RTL, everything else means continue with the mission // failsafe_throttle is 1 do RTL, 2 means continue with the mission
if (g.throttle_fs_action == THROTTLE_FAILSAFE_ACTION_ALWAYS_RTL) { if (g.failsafe_throttle == FS_THR_ENABLED_ALWAYS_RTL) {
// To-Do: check distance from home before initiating RTL // To-Do: check distance from home before initiating RTL
set_mode(RTL); set_mode(RTL);
} }
// if throttle_fs_action is 2 (i.e. THROTTLE_FAILSAFE_ACTION_CONTINUE_MISSION) no need to do anything // if failsafe_throttle is 2 (i.e. FS_THR_ENABLED_CONTINUE_MISSION) no need to do anything
break; break;
default: default:
if(ap.home_is_set == true) { if(ap.home_is_set == true) {

View File

@ -147,7 +147,7 @@ static void read_radio()
#endif #endif
}else{ }else{
// turn on throttle failsafe if no update from ppm encoder for 2 seconds // turn on throttle failsafe if no update from ppm encoder for 2 seconds
if ((millis() - APM_RC.get_last_update() >= RADIO_FS_TIMEOUT_MS) && g.throttle_fs_enabled && motors.armed() && !ap.failsafe) { if ((millis() - APM_RC.get_last_update() >= RADIO_FS_TIMEOUT_MS) && g.failsafe_throttle && motors.armed() && !ap.failsafe) {
set_failsafe(true); set_failsafe(true);
} }
} }
@ -159,13 +159,13 @@ static void set_throttle_and_failsafe(uint16_t throttle_pwm)
static int8_t failsafe_counter = 0; static int8_t failsafe_counter = 0;
// if failsafe not enabled pass through throttle and exit // if failsafe not enabled pass through throttle and exit
if(g.throttle_fs_enabled == 0) { if(g.failsafe_throttle == FS_THR_DISABLED) {
g.rc_3.set_pwm(throttle_pwm); g.rc_3.set_pwm(throttle_pwm);
return; return;
} }
//check for low throttle value //check for low throttle value
if (throttle_pwm < (uint16_t)g.throttle_fs_value) { if (throttle_pwm < (uint16_t)g.failsafe_throttle_value) {
// if we are already in failsafe or motors not armed pass through throttle and exit // if we are already in failsafe or motors not armed pass through throttle and exit
if (ap.failsafe || !motors.armed()) { if (ap.failsafe || !motors.armed()) {

View File

@ -309,7 +309,7 @@ test_radio(uint8_t argc, const Menu::arg *argv)
* fail_test++; * fail_test++;
* } * }
* *
* if(g.throttle_fs_enabled && g.rc_3.get_failsafe()){ * if(g.failsafe_throttle && g.rc_3.get_failsafe()){
* cliSerial->printf_P(PSTR("THROTTLE FAILSAFE ACTIVATED: %d, "), g.rc_3.radio_in); * cliSerial->printf_P(PSTR("THROTTLE FAILSAFE ACTIVATED: %d, "), g.rc_3.radio_in);
* cliSerial->println(flight_mode_strings[readSwitch()]); * cliSerial->println(flight_mode_strings[readSwitch()]);
* fail_test++; * fail_test++;