From 016d514d8063dc22d55981f32b963f6b139db736 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sun, 5 Jun 2016 14:27:57 +0200 Subject: [PATCH] commander/navigator: remove param NAV_RCL_ACT The param NAV_RCL_ACT was not implemented as described. Also, it has the completely the wrong name. It should be a COM param and not NAV. Therefore, remove the param and delete the partly implemented and probably never used functionality. --- src/modules/commander/commander.cpp | 4 ---- src/modules/commander/state_machine_helper.cpp | 4 ++-- src/modules/commander/state_machine_helper.h | 2 +- src/modules/navigator/navigator_params.c | 18 ------------------ 4 files changed, 3 insertions(+), 25 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 4d545fbfec..972ee38ea5 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1171,7 +1171,6 @@ int commander_thread_main(int argc, char *argv[]) param_t _param_system_id = param_find("MAV_SYS_ID"); param_t _param_component_id = param_find("MAV_COMP_ID"); param_t _param_enable_datalink_loss = param_find("NAV_DLL_ACT"); - param_t _param_enable_rc_loss = param_find("NAV_RCL_ACT"); param_t _param_offboard_loss_act = param_find("COM_OBL_ACT"); param_t _param_offboard_loss_rc_act = param_find("COM_OBL_RC_ACT"); param_t _param_datalink_loss_timeout = param_find("COM_DL_LOSS_T"); @@ -1526,7 +1525,6 @@ int commander_thread_main(int argc, char *argv[]) transition_result_t arming_ret; int32_t datalink_loss_enabled = 0; - int32_t rc_loss_enabled = 0; int32_t datalink_loss_timeout = 10; float rc_loss_timeout = 0.5; int32_t datalink_regain_timeout = 0; @@ -1613,7 +1611,6 @@ int commander_thread_main(int argc, char *argv[]) /* Safety parameters */ param_get(_param_enable_datalink_loss, &datalink_loss_enabled); - param_get(_param_enable_rc_loss, &rc_loss_enabled); param_get(_param_datalink_loss_timeout, &datalink_loss_timeout); param_get(_param_rc_loss_timeout, &rc_loss_timeout); param_get(_param_rc_in_off, &rc_in_off); @@ -2708,7 +2705,6 @@ int commander_thread_main(int argc, char *argv[]) mission_result.stay_in_failsafe, &status_flags, land_detector.landed, - (rc_loss_enabled > 0), offboard_loss_act, offboard_loss_rc_act); diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 11e0c68b53..8e18c3f2aa 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -588,7 +588,7 @@ transition_result_t hil_state_transition(hil_state_t new_state, orb_advert_t sta */ bool set_nav_state(struct vehicle_status_s *status, struct commander_state_s *internal_state, const bool data_link_loss_enabled, const bool mission_finished, - const bool stay_in_failsafe, status_flags_s *status_flags, bool landed, const bool rc_loss_enabled, + const bool stay_in_failsafe, status_flags_s *status_flags, bool landed, const int offb_loss_act, const int offb_loss_rc_act) { navigation_state_t nav_state_old = status->nav_state; @@ -605,7 +605,7 @@ bool set_nav_state(struct vehicle_status_s *status, struct commander_state_s *in case commander_state_s::MAIN_STATE_ALTCTL: case commander_state_s::MAIN_STATE_POSCTL: /* require RC for all manual modes */ - if (rc_loss_enabled && (status->rc_signal_lost || status_flags->rc_signal_lost_cmd) && armed && !landed) { + if ((status->rc_signal_lost || status_flags->rc_signal_lost_cmd) && armed && !landed) { status->failsafe = true; if (status_flags->condition_global_position_valid && status_flags->condition_home_position_valid) { diff --git a/src/modules/commander/state_machine_helper.h b/src/modules/commander/state_machine_helper.h index 4012c0e89f..07d616b5b9 100644 --- a/src/modules/commander/state_machine_helper.h +++ b/src/modules/commander/state_machine_helper.h @@ -114,7 +114,7 @@ transition_result_t hil_state_transition(hil_state_t new_state, orb_advert_t sta bool set_nav_state(struct vehicle_status_s *status, struct commander_state_s *internal_state, const bool data_link_loss_enabled, const bool mission_finished, const bool stay_in_failsafe, status_flags_s *status_flags, bool landed, - const bool rc_loss_enabled, const int offb_loss_act, const int offb_loss_rc_act); + const int offb_loss_act, const int offb_loss_rc_act); int preflight_check(struct vehicle_status_s *status, orb_advert_t *mavlink_log_pub, bool prearm, bool force_report, status_flags_s *status_flags, battery_status_s *battery); diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c index 523f03b42e..415a51678a 100644 --- a/src/modules/navigator/navigator_params.c +++ b/src/modules/navigator/navigator_params.c @@ -86,24 +86,6 @@ PARAM_DEFINE_FLOAT(NAV_ACC_RAD, 10.0f); */ PARAM_DEFINE_INT32(NAV_DLL_ACT, 0); -/** - * Set RC loss failsafe mode - * - * The RC loss failsafe will only be entered after a timeout, - * set by COM_RC_LOSS_T in seconds. If RC input checks have been disabled - * by setting the COM_RC_IN_MODE param it will not be triggered. - * Setting this parameter to 4 will enable CASA Outback Challenge rules, - * which are only recommended to participants of that competition. - * - * @value 0 Disabled - * @value 1 Loiter - * @value 2 Return to Land - * @value 3 Land at current position - * - * @group Mission - */ -PARAM_DEFINE_INT32(NAV_RCL_ACT, 0); - /** * Airfield home Lat *