mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
APM: added ALT_CTRL_ALG parameter
this allows you to select different altitude control algorithms. The current choices are for the default (automatic based on if airspeed is available), or to force a non-airspeed algorithm The idea is to make it possible to use airspeed for some things (like wind speed, speed scaling) but not for alt control
This commit is contained in:
parent
16dd911547
commit
3f54b83238
@ -1073,7 +1073,7 @@ static void update_current_flight_mode(void)
|
||||
nav_roll_cd = 0;
|
||||
}
|
||||
|
||||
if(airspeed.use()) {
|
||||
if (alt_control_airspeed()) {
|
||||
calc_nav_pitch();
|
||||
if (nav_pitch_cd < takeoff_pitch_cd)
|
||||
nav_pitch_cd = takeoff_pitch_cd;
|
||||
@ -1092,7 +1092,7 @@ static void update_current_flight_mode(void)
|
||||
|
||||
calc_nav_pitch();
|
||||
calc_throttle();
|
||||
if (!airspeed.use() || land_complete) {
|
||||
if (!alt_control_airspeed() || land_complete) {
|
||||
// hold pitch constant in final approach
|
||||
nav_pitch_cd = g.land_pitch_cd;
|
||||
}
|
||||
|
@ -134,7 +134,7 @@ static void crash_checker()
|
||||
|
||||
static void calc_throttle()
|
||||
{
|
||||
if (!airspeed.use()) {
|
||||
if (!alt_control_airspeed()) {
|
||||
int16_t throttle_target = g.throttle_cruise + throttle_nudge;
|
||||
|
||||
// TODO: think up an elegant way to bump throttle when
|
||||
@ -200,7 +200,7 @@ static void calc_nav_pitch()
|
||||
{
|
||||
// Calculate the Pitch of the plane
|
||||
// --------------------------------
|
||||
if (airspeed.use()) {
|
||||
if (alt_control_airspeed()) {
|
||||
nav_pitch_cd = -g.pidNavPitchAirspeed.get_pid(airspeed_error_cm);
|
||||
} else {
|
||||
nav_pitch_cd = g.pidNavPitchAltitude.get_pid(altitude_error_cm);
|
||||
@ -470,3 +470,9 @@ static void demo_servos(byte i) {
|
||||
i--;
|
||||
}
|
||||
}
|
||||
|
||||
// return true if we should use airspeed for altitude/throttle control
|
||||
static bool alt_control_airspeed(void)
|
||||
{
|
||||
return airspeed.use() && g.alt_control_algorithm == ALT_CONTROL_DEFAULT;
|
||||
}
|
||||
|
@ -88,6 +88,7 @@ public:
|
||||
k_param_flybywire_airspeed_max,
|
||||
k_param_FBWB_min_altitude_cm, // 0=disabled, minimum value for altitude in cm (for first time try 30 meters = 3000 cm)
|
||||
k_param_flybywire_elev_reverse,
|
||||
k_param_alt_control_algorithm,
|
||||
|
||||
//
|
||||
// 130: Sensor parameters
|
||||
@ -238,6 +239,7 @@ public:
|
||||
// Estimation
|
||||
//
|
||||
AP_Float altitude_mix;
|
||||
AP_Int8 alt_control_algorithm;
|
||||
|
||||
// Waypoints
|
||||
//
|
||||
|
@ -128,6 +128,13 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @User: Advanced
|
||||
GSCALAR(altitude_mix, "ALT_MIX", ALTITUDE_MIX),
|
||||
|
||||
// @Param: ALT_CTRL_ALG
|
||||
// @DisplayName: Altitude control algorithm
|
||||
// @Description: This sets what algorithm will be used for altitude control. The default is to select the algorithm based on whether airspeed is enabled. If you set it to 1, then the airspeed based algorithm won't be used for altitude control, but airspeed can be used for other flight control functions
|
||||
// @Values: 0:Default Method,1:non-airspeed
|
||||
// @User: Advanced
|
||||
GSCALAR(alt_control_algorithm, "ALT_CTRL_ALG", ALT_CONTROL_DEFAULT),
|
||||
|
||||
GSCALAR(command_total, "CMD_TOTAL", 0),
|
||||
GSCALAR(command_index, "CMD_INDEX", 0),
|
||||
|
||||
|
@ -255,4 +255,11 @@ enum gcs_severity {
|
||||
#define AP_BARO_BMP085 1
|
||||
#define AP_BARO_MS5611 2
|
||||
|
||||
// altitude control algorithms
|
||||
enum {
|
||||
ALT_CONTROL_DEFAULT=0,
|
||||
ALT_CONTROL_NON_AIRSPEED=1
|
||||
};
|
||||
|
||||
|
||||
#endif // _DEFINES_H
|
||||
|
@ -95,7 +95,7 @@ static void read_radio()
|
||||
g.channel_throttle.servo_out = g.channel_throttle.control_in;
|
||||
|
||||
if (g.channel_throttle.servo_out > 50) {
|
||||
if (airspeed.use()) {
|
||||
if (alt_control_airspeed()) {
|
||||
airspeed_nudge_cm = (g.flybywire_airspeed_max * 100 - g.airspeed_cruise_cm) * ((g.channel_throttle.norm_input()-0.5) / 0.5);
|
||||
} else {
|
||||
throttle_nudge = (g.throttle_max - g.throttle_cruise) * ((g.channel_throttle.norm_input()-0.5) / 0.5);
|
||||
|
Loading…
Reference in New Issue
Block a user