mirror of https://github.com/ArduPilot/ardupilot
Plane: remove none-functional NAV_CONTROLLER param
This commit is contained in:
parent
d7a5e460cc
commit
e6968395c6
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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();
|
||||
|
|
|
@ -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) {
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue