From e6968395c63c3001a886d69db15a5daee755460c Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 4 Sep 2021 16:49:58 +0100 Subject: [PATCH] Plane: remove none-functional NAV_CONTROLLER param --- ArduPlane/Parameters.cpp | 7 ------- ArduPlane/Parameters.h | 5 +---- ArduPlane/Plane.h | 1 - ArduPlane/navigation.cpp | 18 ------------------ ArduPlane/system.cpp | 3 --- 5 files changed, 1 insertion(+), 33 deletions(-) diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 4cf73437d2..d4c8b5701d 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -215,13 +215,6 @@ const AP_Param::Info Plane::var_info[] = { // @User: Advanced GSCALAR(use_reverse_thrust, "USE_REV_THRUST", USE_REVERSE_THRUST_AUTO_LAND_APPROACH), - // @Param: NAV_CONTROLLER - // @DisplayName: Navigation controller selection - // @Description: Which navigation controller to enable. Currently the only navigation controller available is L1. From time to time other experimental controllers will be added which are selected using this parameter. - // @Values: 0:Default,1:L1Controller - // @User: Standard - GSCALAR(nav_controller, "NAV_CONTROLLER", AP_Navigation::CONTROLLER_L1), - // @Param: ALT_OFFSET // @DisplayName: Altitude offset // @Description: This is added to the target altitude in automatic flight. It can be used to add a global altitude offset to a mission diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index e74f168149..63b4be8463 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -81,7 +81,7 @@ public: k_param_level_roll_limit, k_param_hil_servos_unused, // unused k_param_vtail_output, // unused - k_param_nav_controller, + k_param_nav_controller, // unused k_param_elevon_output, // unused k_param_att_controller, // unused k_param_mixing_gain, @@ -377,9 +377,6 @@ public: // speed used for speed scaling AP_Float scaling_speed; - // navigation controller type. See AP_Navigation::ControllerType - AP_Int8 nav_controller; - AP_Int8 auto_fbw_steer; // Waypoints diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index b54fb67627..5fbc82b0fa 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -982,7 +982,6 @@ private: void set_flight_stage(AP_Vehicle::FixedWing::FlightStage fs); // navigation.cpp - void set_nav_controller(void); void loiter_angle_reset(void); void loiter_angle_update(void); void navigate(); diff --git a/ArduPlane/navigation.cpp b/ArduPlane/navigation.cpp index 32c1f82069..e6d073aec7 100644 --- a/ArduPlane/navigation.cpp +++ b/ArduPlane/navigation.cpp @@ -1,20 +1,5 @@ #include "Plane.h" -// set the nav_controller pointer to the right controller -void Plane::set_nav_controller(void) -{ - switch ((AP_Navigation::ControllerType)g.nav_controller.get()) { - - default: - case AP_Navigation::CONTROLLER_DEFAULT: - // no break, fall through to L1 as default controller - - case AP_Navigation::CONTROLLER_L1: - nav_controller = &L1_controller; - break; - } -} - /* reset the total loiter angle */ @@ -100,9 +85,6 @@ void Plane::loiter_angle_update(void) //**************************************************************** void Plane::navigate() { - // allow change of nav controller mid-flight - set_nav_controller(); - // do not navigate with corrupt data // --------------------------------- if (!have_position) { diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 4e45b7a83d..35ce1ff2d5 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -125,9 +125,6 @@ void Plane::init_ardupilot() hal.rcout->set_output_mode(g2.oneshot_mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT); } - // choose the nav controller - set_nav_controller(); - set_mode_by_number((enum Mode::Number)g.initial_mode.get(), ModeReason::INITIALISED); // set the correct flight mode