Path: blob/master/libraries/AC_AttitudeControl/AC_PosControl.cpp
9390 views
#include <AP_HAL/AP_HAL.h>1#include "AC_PosControl.h"2#include <AP_Math/AP_Math.h>3#include <AP_Logger/AP_Logger.h>4#include <AP_Motors/AP_Motors.h> // motors library5#include <AP_Vehicle/AP_Vehicle_Type.h>6#include <AP_Scheduler/AP_Scheduler.h>78extern const AP_HAL::HAL& hal;910#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)11// default gains for Plane12# define POSCONTROL_D_POS_P 1.0f // vertical position controller P gain default13# define POSCONTROL_D_VEL_P 5.0f // vertical velocity controller P gain default14# define POSCONTROL_D_VEL_IMAX 10.0f // vertical velocity controller IMAX gain default15# define POSCONTROL_D_VEL_FILT_HZ 5.0f // vertical velocity controller input filter16# define POSCONTROL_D_VEL_FILT_D_HZ 5.0f // vertical velocity controller input filter for D17# define POSCONTROL_D_ACC_P 0.03f // vertical acceleration controller P gain default18# define POSCONTROL_D_ACC_I 0.1f // vertical acceleration controller I gain default19# define POSCONTROL_D_ACC_D 0.0f // vertical acceleration controller D gain default20# define POSCONTROL_D_ACC_IMAX 0.8f // vertical acceleration controller IMAX gain default21# define POSCONTROL_D_ACC_FILT_HZ 10.0f // vertical acceleration controller input filter default22# define POSCONTROL_D_ACC_DT 0.02f // vertical acceleration controller dt default23# define POSCONTROL_NE_POS_P 0.5f // horizontal position controller P gain default24# define POSCONTROL_NE_VEL_P 0.7f // horizontal velocity controller P gain default25# define POSCONTROL_NE_VEL_I 0.35f // horizontal velocity controller I gain default26# define POSCONTROL_NE_VEL_D 0.17f // horizontal velocity controller D gain default27# define POSCONTROL_NE_VEL_IMAX 10.0f // horizontal velocity controller IMAX gain default28# define POSCONTROL_NE_VEL_FILT_HZ 5.0f // horizontal velocity controller input filter29# define POSCONTROL_NE_VEL_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D30#elif APM_BUILD_TYPE(APM_BUILD_ArduSub)31// default gains for Sub32# define POSCONTROL_D_POS_P 3.0f // vertical position controller P gain default33# define POSCONTROL_D_VEL_P 8.0f // vertical velocity controller P gain default34# define POSCONTROL_D_VEL_IMAX 10.0f // vertical velocity controller IMAX gain default35# define POSCONTROL_D_VEL_FILT_HZ 5.0f // vertical velocity controller input filter36# define POSCONTROL_D_VEL_FILT_D_HZ 5.0f // vertical velocity controller input filter for D37# define POSCONTROL_D_ACC_P 0.05f // vertical acceleration controller P gain default38# define POSCONTROL_D_ACC_I 0.01f // vertical acceleration controller I gain default39# define POSCONTROL_D_ACC_D 0.0f // vertical acceleration controller D gain default40# define POSCONTROL_D_ACC_IMAX 0.1f // vertical acceleration controller IMAX gain default41# define POSCONTROL_D_ACC_FILT_HZ 20.0f // vertical acceleration controller input filter default42# define POSCONTROL_D_ACC_DT 0.0025f // vertical acceleration controller dt default43# define POSCONTROL_NE_POS_P 1.0f // horizontal position controller P gain default44# define POSCONTROL_NE_VEL_P 1.0f // horizontal velocity controller P gain default45# define POSCONTROL_NE_VEL_I 0.5f // horizontal velocity controller I gain default46# define POSCONTROL_NE_VEL_D 0.0f // horizontal velocity controller D gain default47# define POSCONTROL_NE_VEL_IMAX 10.0f // horizontal velocity controller IMAX gain default48# define POSCONTROL_NE_VEL_FILT_HZ 5.0f // horizontal velocity controller input filter49# define POSCONTROL_NE_VEL_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D50#else51// default gains for Copter / TradHeli52# define POSCONTROL_D_POS_P 1.0f // vertical position controller P gain default53# define POSCONTROL_D_VEL_P 5.0f // vertical velocity controller P gain default54# define POSCONTROL_D_VEL_IMAX 10.0f // vertical velocity controller IMAX gain default55# define POSCONTROL_D_VEL_FILT_HZ 5.0f // vertical velocity controller input filter56# define POSCONTROL_D_VEL_FILT_D_HZ 5.0f // vertical velocity controller input filter for D57# define POSCONTROL_D_ACC_P 0.05f // vertical acceleration controller P gain default58# define POSCONTROL_D_ACC_I 0.1f // vertical acceleration controller I gain default59# define POSCONTROL_D_ACC_D 0.0f // vertical acceleration controller D gain default60# define POSCONTROL_D_ACC_IMAX 0.8f // vertical acceleration controller IMAX gain default61# define POSCONTROL_D_ACC_FILT_HZ 20.0f // vertical acceleration controller input filter default62# define POSCONTROL_D_ACC_DT 0.0025f // vertical acceleration controller dt default63# define POSCONTROL_NE_POS_P 1.0f // horizontal position controller P gain default64# define POSCONTROL_NE_VEL_P 2.0f // horizontal velocity controller P gain default65# define POSCONTROL_NE_VEL_I 1.0f // horizontal velocity controller I gain default66# define POSCONTROL_NE_VEL_D 0.25f // horizontal velocity controller D gain default67# define POSCONTROL_NE_VEL_IMAX 10.0f // horizontal velocity controller IMAX gain default68# define POSCONTROL_NE_VEL_FILT_HZ 5.0f // horizontal velocity controller input filter69# define POSCONTROL_NE_VEL_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D70#endif7172// vibration compensation gains73#define POSCONTROL_VIBE_COMP_P_GAIN 0.250f74#define POSCONTROL_VIBE_COMP_I_GAIN 0.125f7576// velocity offset targets timeout if not updated within 3 seconds77#define POSCONTROL_POSVELACCEL_OFFSET_TARGET_TIMEOUT_MS 30007879AC_PosControl *AC_PosControl::_singleton;8081const AP_Param::GroupInfo AC_PosControl::var_info[] = {82// 0 was used for HOVER8384// POS_ACC_XY_FILT was here.8586// @Param: _D_POS_P87// @DisplayName: Position (vertical) controller P gain88// @Description: Position (vertical) controller P gain. Converts the difference between the desired altitude and actual altitude into a climb or descent rate which is passed to the throttle rate controller. Previously _POSZ_P.89// @Range: 0.50 4.0090// @Increment: 0.0191// @User: Standard92AP_SUBGROUPINFO(_p_pos_d_m, "_D_POS_", 2, AC_PosControl, AC_P_1D),9394// 3 was _VELZ_ which has become _D_VEL_9596// 4 was _ACCZ_ which has become _D_ACC_9798// @Param: _NE_POS_P99// @DisplayName: Position (horizontal) controller P gain100// @Description: Position controller P gain. Converts the distance (in the latitude direction) to the target location into a desired speed which is then passed to the loiter latitude rate controller. Previously _POSXY_P.101// @Range: 0.50 4.00102// @Increment: 0.01103// @User: Standard104AP_SUBGROUPINFO(_p_pos_ne_m, "_NE_POS_", 5, AC_PosControl, AC_P_2D),105106// 6 was _VELXY_ which has become _NE_VEL_107108// @Param: _ANGLE_MAX109// @DisplayName: Position Control Angle Max110// @Description: Maximum lean angle autopilot can request. Set to zero to use ANGLE_MAX parameter value111// @Units: deg112// @Range: 0 45113// @Increment: 1114// @User: Advanced115AP_GROUPINFO("_ANGLE_MAX", 7, AC_PosControl, _lean_angle_max_deg, 0.0f),116117// IDs 8,9 used for _TC_XY and _TC_Z in beta release candidate118119// @Param: _JERK_NE120// @DisplayName: Jerk limit for the horizontal kinematic input shaping121// @Description: Jerk limit of the horizontal kinematic path generation used to determine how quickly the aircraft varies the acceleration target122// @Units: m/s/s/s123// @Range: 1 50124// @Increment: 1125// @User: Advanced126AP_GROUPINFO("_JERK_NE", 10, AC_PosControl, _shaping_jerk_ne_msss, POSCONTROL_JERK_NE_MSSS),127128// @Param: _JERK_D129// @DisplayName: Jerk limit for the vertical kinematic input shaping130// @Description: Jerk limit of the vertical kinematic path generation used to determine how quickly the aircraft varies the acceleration target131// @Units: m/s/s/s132// @Range: 1 50133// @Increment: 1134// @User: Advanced135AP_GROUPINFO("_JERK_D", 11, AC_PosControl, _shaping_jerk_d_msss, POSCONTROL_JERK_D_MSSS),136137// @Param: _D_VEL_P138// @DisplayName: Velocity (vertical) controller P gain139// @Description: Velocity (vertical) controller P gain. Converts the difference between desired vertical speed and actual speed into a desired acceleration that is passed to the throttle acceleration controller. Previously _VELZ_P.140// @Range: 1.0 10.0141// @Increment: 0.1142// @User: Standard143144// @Param: _D_VEL_I145// @DisplayName: Velocity (vertical) controller I gain146// @Description: Velocity (vertical) controller I gain. Corrects long-term difference in desired velocity to a target acceleration. Previously _VELZ_I.147// @Range: 0.00 10.0148// @Increment: 0.1149// @User: Advanced150151// @Param: _D_VEL_IMAX152// @DisplayName: Velocity (vertical) controller I gain maximum153// @Description: Velocity (vertical) controller I gain maximum. Constrains the target acceleration that the I gain will output. If upgrading from 4.6 this is _VELZ_IMAX * 0.01.154// @Range: 1.000 10.000155// @Increment: 0.1156// @User: Standard157158// @Param: _D_VEL_D159// @DisplayName: Velocity (vertical) controller D gain160// @Description: Velocity (vertical) controller D gain. Corrects short-term changes in velocity. Previously _VELZ_D.161// @Range: 0.00 2.00162// @Increment: 0.01163// @User: Advanced164165// @Param: _D_VEL_FF166// @DisplayName: Velocity (vertical) controller Feed Forward gain167// @Description: Velocity (vertical) controller Feed Forward gain. Produces an output that is proportional to the magnitude of the target. Previously _VELZ_FF.168// @Range: 0.00 2.00169// @Increment: 0.01170// @User: Advanced171172// @Param: _D_VEL_FLTE173// @DisplayName: Velocity (vertical) error filter174// @Description: Velocity (vertical) error filter. This filter (in Hz) is applied to the input for P and I terms. Previously _VELZ_FLTE.175// @Range: 0 100176// @Increment: 1.0177// @Units: Hz178// @User: Advanced179180// @Param: _D_VEL_FLTD181// @DisplayName: Velocity (vertical) input filter for D term182// @Description: Velocity (vertical) input filter for D term. This filter (in Hz) is applied to the input for D terms. Previously _VELZ_FLTD.183// @Range: 0 100184// @Increment: 1.0185// @Units: Hz186// @User: Advanced187AP_SUBGROUPINFO(_pid_vel_d_m, "_D_VEL_", 12, AC_PosControl, AC_PID_Basic),188189// @Param: _D_ACC_P190// @DisplayName: Acceleration (vertical) controller P gain191// @Description: Acceleration (vertical) controller P gain. Converts the difference between desired vertical acceleration and actual acceleration into a motor output. If upgrading from 4.6 this is _ACCZ_P * 0.1.192// @Range: 0.010 0.250193// @Increment: 0.001194// @User: Standard195196// @Param: _D_ACC_I197// @DisplayName: Acceleration (vertical) controller I gain198// @Description: Acceleration (vertical) controller I gain. Corrects long-term difference in desired vertical acceleration and actual acceleration. If upgrading from 4.6 this is _ACCZ_I * 0.1.199// @Range: 0.000 0.500200// @Increment: 0.001201// @User: Standard202203// @Param: _D_ACC_IMAX204// @DisplayName: Acceleration (vertical) controller I gain maximum205// @Description: Acceleration (vertical) controller I gain maximum. Constrains the maximum pwm that the I term will generate. If upgrading from 4.6 this is _ACCZ_IMAX * 0.001.206// @Range: 0.0 1.0207// @Increment: 0.01208// @Units: d%209// @User: Standard210211// @Param: _D_ACC_D212// @DisplayName: Acceleration (vertical) controller D gain213// @Description: Acceleration (vertical) controller D gain. Compensates for short-term change in desired vertical acceleration vs actual acceleration. If upgrading from 4.6 this is _ACCZ_D * 0.1.214// @Range: 0.000 0.100215// @Increment: 0.001216// @User: Standard217218// @Param: _D_ACC_FF219// @DisplayName: Acceleration (vertical) controller feed forward220// @Description: Acceleration (vertical) controller feed forward. If upgrading from 4.6 this is _ACCZ_FF * 0.1.221// @Range: 0.000 0.100222// @Increment: 0.001223// @User: Standard224225// @Param: _D_ACC_FLTT226// @DisplayName: Acceleration (vertical) controller target frequency in Hz227// @Description: Acceleration (vertical) controller target frequency in Hz. Previously _ACCZ_FLTT.228// @Range: 1 50229// @Increment: 1230// @Units: Hz231// @User: Standard232233// @Param: _D_ACC_FLTE234// @DisplayName: Acceleration (vertical) controller error frequency in Hz235// @Description: Acceleration (vertical) controller error frequency in Hz. Previously _ACCZ_FLTE.236// @Range: 1 100237// @Increment: 1238// @Units: Hz239// @User: Standard240241// @Param: _D_ACC_FLTD242// @DisplayName: Acceleration (vertical) controller derivative frequency in Hz243// @Description: Acceleration (vertical) controller derivative frequency in Hz. Previously _ACCZ_FLTD.244// @Range: 1 100245// @Increment: 1246// @Units: Hz247// @User: Standard248249// @Param: _D_ACC_SMAX250// @DisplayName: Accel (vertical) slew rate limit251// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.252// @Range: 0 100253// @Increment: 0.1254// @User: Advanced255256// @Param: _D_ACC_PDMX257// @DisplayName: Acceleration (vertical) controller PD sum maximum258// @Description: Acceleration (vertical) controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output. If upgrading from 4.6 this is _ACCZ_P * 0.1.259// @Range: 0.00 1.00260// @Increment: 0.01261// @Units: d%262263// @Param: _D_ACC_D_FF264// @DisplayName: Accel (vertical) Derivative FeedForward Gain265// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target. If upgrading from 4.6 this is _ACCZ_P * 0.1.266// @Range: 0.000 0.050267// @Increment: 0.001268// @User: Advanced269270// @Param: _D_ACC_NTF271// @DisplayName: Accel (vertical) Target notch filter index272// @Description: Accel (vertical) Target notch filter index. If upgrading from 4.6 this is Previously _ACCZ_NTF.273// @Range: 1 8274// @User: Advanced275276// @Param: _D_ACC_NEF277// @DisplayName: Accel (vertical) Error notch filter index278// @Description: Accel (vertical) Error notch filter index. If upgrading from 4.6 this is Previously _ACCZ_NEF.279// @Range: 1 8280// @User: Advanced281AP_SUBGROUPINFO(_pid_accel_d_m, "_D_ACC_", 13, AC_PosControl, AC_PID),282283// @Param: _NE_VEL_P284// @DisplayName: Velocity (horizontal) P gain285// @Description: Velocity (horizontal) P gain. Converts the difference between desired and actual velocity to a target acceleration. Previously _VELXY_P.286// @Range: 0.10 10.00287// @Increment: 0.01288// @User: Advanced289290// @Param: _NE_VEL_I291// @DisplayName: Velocity (horizontal) I gain292// @Description: Velocity (horizontal) I gain. Corrects long-term difference between desired and actual velocity to a target acceleration. Previously _VELXY_I.293// @Range: 0.10 10.00294// @Increment: 0.01295// @User: Advanced296297// @Param: _NE_VEL_D298// @DisplayName: Velocity (horizontal) D gain299// @Description: Velocity (horizontal) D gain. Corrects short-term changes in velocity. Previously _VELXY_D.300// @Range: 0.00 1.00301// @Increment: 0.01302// @User: Advanced303304// @Param: _NE_VEL_IMAX305// @DisplayName: Velocity (horizontal) integrator maximum306// @Description: Velocity (horizontal) integrator maximum. Constrains the target acceleration that the I gain will output. If upgrading from 4.6 this is _VELXY_IMAX * 0.01.307// @Range: 0 10308// @Increment: 1309// @Units: m/s/s310// @User: Advanced311312// @Param: _NE_VEL_FLTE313// @DisplayName: Velocity (horizontal) input filter314// @Description: Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for P and I terms. Previously _VELXY_FLTE.315// @Range: 0 100316// @Increment: 1317// @Units: Hz318// @User: Advanced319320// @Param: _NE_VEL_FLTD321// @DisplayName: Velocity (horizontal) input filter322// @Description: Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for D term. Previously _VELXY_FLTD.323// @Range: 0 100324// @Increment: 1325// @Units: Hz326// @User: Advanced327328// @Param: _NE_VEL_FF329// @DisplayName: Velocity (horizontal) feed forward gain330// @Description: Velocity (horizontal) feed forward gain. Converts the difference between desired velocity to a target acceleration. Previously _VELXY_FF.331// @Range: 0.10 10.00332// @Increment: 0.01333// @User: Advanced334AP_SUBGROUPINFO(_pid_vel_ne_m, "_NE_VEL_", 14, AC_PosControl, AC_PID_2D),335336AP_GROUPEND337};338339// Default constructor.340// Note that the Vector/Matrix constructors already implicitly zero341// their values.342//343AC_PosControl::AC_PosControl(AP_AHRS_View& ahrs, const AP_Motors& motors, AC_AttitudeControl& attitude_control) :344_ahrs(ahrs),345_motors(motors),346_attitude_control(attitude_control),347_p_pos_ne_m(POSCONTROL_NE_POS_P),348_p_pos_d_m(POSCONTROL_D_POS_P),349_pid_vel_ne_m(POSCONTROL_NE_VEL_P, POSCONTROL_NE_VEL_I, POSCONTROL_NE_VEL_D, 0.0f, POSCONTROL_NE_VEL_IMAX, POSCONTROL_NE_VEL_FILT_HZ, POSCONTROL_NE_VEL_FILT_D_HZ),350_pid_vel_d_m(POSCONTROL_D_VEL_P, 0.0f, 0.0f, 0.0f, POSCONTROL_D_VEL_IMAX, POSCONTROL_D_VEL_FILT_HZ, POSCONTROL_D_VEL_FILT_D_HZ),351_pid_accel_d_m(POSCONTROL_D_ACC_P, POSCONTROL_D_ACC_I, POSCONTROL_D_ACC_D, 0.0f, POSCONTROL_D_ACC_IMAX, 0.0f, POSCONTROL_D_ACC_FILT_HZ, 0.0f),352_vel_max_ne_ms(POSCONTROL_SPEED_MS),353_vel_max_up_ms(POSCONTROL_SPEED_UP_MS),354_vel_max_down_ms(POSCONTROL_SPEED_DOWN_MS),355_accel_max_ne_mss(POSCONTROL_ACCEL_NE_MSS),356_accel_max_d_mss(POSCONTROL_ACCEL_D_MSS),357_jerk_max_ne_msss(POSCONTROL_JERK_NE_MSSS),358_jerk_max_d_msss(POSCONTROL_JERK_D_MSSS)359{360AP_Param::setup_object_defaults(this, var_info);361362_singleton = this;363}364365366///367/// 3D position shaper368///369370// Sets a new NED position target in meters and computes a jerk-limited trajectory.371// Updates internal acceleration commands using a smooth kinematic path constrained372// by configured acceleration and jerk limits.373// The path can be offset vertically to follow the terrain by providing the current374// terrain level in the NED frame and the terrain margin. Terrain margin is used to375// constrain horizontal velocity to avoid vertical buffer violation.376void AC_PosControl::input_pos_NED_m(const Vector3p& pos_ned_m, float pos_terrain_target_d_m, float terrain_margin_m)377{378// Terrain following velocity scalar must be calculated before we remove the position offset379const float offset_d_scalar = terrain_scaler_D_m(pos_terrain_target_d_m, terrain_margin_m);380set_pos_terrain_target_D_m(pos_terrain_target_d_m);381382// calculated increased maximum acceleration and jerk if over speed383const float overspeed_gain = calculate_overspeed_gain();384const float accel_max_d_mss = _accel_max_d_mss * overspeed_gain;385const float jerk_max_d_msss = _jerk_max_d_msss * overspeed_gain;386387update_pos_vel_accel_xy(_pos_desired_ned_m.xy(), _vel_desired_ned_ms.xy(), _accel_desired_ned_mss.xy(), _dt_s, _limit_vector_ned.xy(), _p_pos_ne_m.get_error(), _pid_vel_ne_m.get_error());388389// adjust desired altitude if motors have not hit their limits390update_pos_vel_accel(_pos_desired_ned_m.z, _vel_desired_ned_ms.z, _accel_desired_ned_mss.z, _dt_s, _limit_vector_ned.z, _p_pos_d_m.get_error(), _pid_vel_d_m.get_error());391392// calculate the horizontal and vertical velocity limits to travel directly to the destination defined by pos_ne_m393float vel_max_ne_ms = 0.0f;394float vel_max_d_ms = 0.0f;395Vector3f travel_dir_unit = (pos_ned_m - _pos_desired_ned_m).tofloat();396if (is_positive(travel_dir_unit.length_squared()) ) {397travel_dir_unit.normalize();398float travel_dir_unit_ne_length = travel_dir_unit.xy().length();399400float vel_max_ms = kinematic_limit(travel_dir_unit, _vel_max_ne_ms, _vel_max_up_ms, _vel_max_down_ms);401vel_max_ne_ms = vel_max_ms * travel_dir_unit_ne_length;402vel_max_d_ms = fabsf(vel_max_ms * travel_dir_unit.z);403}404405// reduce speed if we are reaching the edge of our vertical buffer406vel_max_ne_ms *= offset_d_scalar;407408Vector2f vel_ne_ms;409Vector2f accel_ne_mss;410shape_pos_vel_accel_xy(pos_ned_m.xy(), vel_ne_ms, accel_ne_mss, _pos_desired_ned_m.xy(), _vel_desired_ned_ms.xy(), _accel_desired_ned_mss.xy(),411vel_max_ne_ms, _accel_max_ne_mss, _jerk_max_ne_msss, _dt_s, false);412413float pos_d_m = pos_ned_m.z;414shape_pos_vel_accel(pos_d_m, 0, 0,415_pos_desired_ned_m.z, _vel_desired_ned_ms.z, _accel_desired_ned_mss.z,416-vel_max_d_ms, vel_max_d_ms,417-accel_max_d_mss, constrain_float(accel_max_d_mss, 0.0, 7.5),418jerk_max_d_msss, _dt_s, false);419}420421// Returns a scaling factor for horizontal velocity in m/s to ensure422// the vertical controller maintains a safe distance above terrain.423float AC_PosControl::terrain_scaler_D_m(float pos_terrain_d_m, float terrain_margin_m) const424{425if (is_zero(terrain_margin_m)) {426return 1.0;427}428float pos_offset_error_d_m = _pos_estimate_ned_m.z - (_pos_target_ned_m.z + (pos_terrain_d_m - _pos_terrain_d_m));429return constrain_float((1.0 - (fabsf(pos_offset_error_d_m) - 0.5 * terrain_margin_m) / (0.5 * terrain_margin_m)), 0.01, 1.0);430}431432///433/// Lateral position controller434///435436// Sets maximum horizontal speed (cm/s) and acceleration (cm/s²) for NE-axis shaping.437// Can be called anytime; transitions are handled smoothly.438// All arguments should be positive.439// See NE_set_max_speed_accel_m() for full details.440void AC_PosControl::NE_set_max_speed_accel_cm(float speed_ne_cms, float accel_ne_cmss)441{442NE_set_max_speed_accel_m(speed_ne_cms * 0.01, accel_ne_cmss * 0.01);443}444445// Sets maximum horizontal speed (m/s) and acceleration (m/s²) for NE-axis shaping.446// These values constrain the kinematic trajectory used by the lateral controller.447// All arguments should be positive.448void AC_PosControl::NE_set_max_speed_accel_m(float speed_ne_ms, float accel_ne_mss)449{450_vel_max_ne_ms = fabsf(speed_ne_ms);451_accel_max_ne_mss = fabsf(accel_ne_mss);452453// ensure the horizontal jerk is less than the vehicle is capable of454const float jerk_max_msss = MIN(_attitude_control.get_ang_vel_roll_max_rads(), _attitude_control.get_ang_vel_pitch_max_rads()) * GRAVITY_MSS;455const float snap_max_mssss = MIN(_attitude_control.get_accel_roll_max_radss(), _attitude_control.get_accel_pitch_max_radss()) * GRAVITY_MSS;456457// get specified jerk limit458_jerk_max_ne_msss = _shaping_jerk_ne_msss;459460// limit maximum jerk based on maximum angular rate461if (is_positive(jerk_max_msss) && _attitude_control.get_bf_feedforward()) {462_jerk_max_ne_msss = MIN(_jerk_max_ne_msss, jerk_max_msss);463}464465// limit maximum jerk to maximum possible average jerk based on angular acceleration466if (is_positive(snap_max_mssss) && _attitude_control.get_bf_feedforward()) {467_jerk_max_ne_msss = MIN(0.5 * safe_sqrt(_accel_max_ne_mss * snap_max_mssss), _jerk_max_ne_msss);468}469}470471// Sets horizontal correction limits for velocity (cm/s) and acceleration (cm/s²).472// Should be called only during initialization to avoid control discontinuities.473// All arguments should be positive.474// See NE_set_correction_speed_accel_m() for full details.475void AC_PosControl::NE_set_correction_speed_accel_cm(float speed_ne_cms, float accel_ne_cmss)476{477NE_set_correction_speed_accel_m(speed_ne_cms * 0.01, accel_ne_cmss * 0.01);478}479480// Sets horizontal correction limits for velocity (m/s) and acceleration (m/s²).481// These values constrain the PID correction path, not the desired trajectory.482// All arguments should be positive.483void AC_PosControl::NE_set_correction_speed_accel_m(float speed_ne_ms, float accel_ne_mss)484{485// limits that are not positive are ignored486_p_pos_ne_m.set_limits(speed_ne_ms, accel_ne_mss, 0.0f);487}488489// Initializes NE controller to a stationary stopping point with zero velocity and acceleration.490// Use when the expected trajectory begins at rest but the starting position is unspecified.491// The starting position can be retrieved with get_pos_target_NED_m().492void AC_PosControl::NE_init_controller_stopping_point()493{494NE_init_controller();495496get_stopping_point_NE_m(_pos_desired_ned_m.xy());497_pos_target_ned_m.xy() = _pos_desired_ned_m.xy() + _pos_offset_ned_m.xy();498_vel_desired_ned_ms.xy().zero();499_accel_desired_ned_mss.xy().zero();500}501502// Smoothly decays NE acceleration over time to zero while maintaining current velocity and position.503// Reduces output acceleration by ~95% over 0.5 seconds to avoid abrupt transitions.504void AC_PosControl::NE_relax_velocity_controller()505{506// decay acceleration and therefore current attitude target to zero507// this will be reset by NE_init_controller() if !NE_is_active()508if (is_positive(_dt_s)) {509float decay = 1.0 - _dt_s / (_dt_s + POSCONTROL_RELAX_TC);510_accel_target_ned_mss.xy() *= decay;511}512513NE_init_controller();514}515516// Softens NE controller for landing by reducing position error and suppressing I-term windup.517// Used to make descent behavior more stable near ground contact.518void AC_PosControl::NE_soften_for_landing()519{520// decay position error to zero521if (is_positive(_dt_s)) {522_pos_target_ned_m.xy() += (_pos_estimate_ned_m.xy() - _pos_target_ned_m.xy()) * (_dt_s / (_dt_s + POSCONTROL_RELAX_TC));523_pos_desired_ned_m.xy() = _pos_target_ned_m.xy() - _pos_offset_ned_m.xy();524}525526// Prevent I term build up in xy velocity controller.527// Note that this flag is reset on each loop in NE_update_controller()528NE_set_externally_limited();529}530531// Fully initializes the NE controller with current position, velocity, acceleration, and attitude.532// Intended for normal startup when the full state is known.533// Private function shared by other NE initializers.534void AC_PosControl::NE_init_controller()535{536// initialise offsets to target offsets and ensure offset targets are zero if they have not been updated.537NE_init_offsets();538539// set roll, pitch lean angle targets to current attitude540const Vector3f &att_target_euler_rad = _attitude_control.get_att_target_euler_rad();541_roll_target_rad = att_target_euler_rad.x;542_pitch_target_rad = att_target_euler_rad.y;543_yaw_target_rad = att_target_euler_rad.z; // todo: this should be thrust vector heading, not yaw.544_yaw_rate_target_rads = 0.0f;545_angle_max_override_rad = 0.0;546547_pos_target_ned_m.xy() = _pos_estimate_ned_m.xy();548_pos_desired_ned_m.xy() = _pos_target_ned_m.xy() - _pos_offset_ned_m.xy();549550_vel_target_ned_ms.xy() = _vel_estimate_ned_ms.xy();551_vel_desired_ned_ms.xy() = _vel_target_ned_ms.xy() - _vel_offset_ned_ms.xy();552553// Set desired acceleration to zero because raw acceleration is prone to noise554_accel_desired_ned_mss.xy().zero();555556if (!NE_is_active()) {557lean_angles_to_accel_NE_mss(_accel_target_ned_mss.x, _accel_target_ned_mss.y);558}559560// limit acceleration using maximum lean angles561const float angle_max_rad = MIN(_attitude_control.get_althold_lean_angle_max_rad(), get_lean_angle_max_rad());562const float accel_max_mss = angle_rad_to_accel_mss(angle_max_rad);563_accel_target_ned_mss.xy().limit_length(accel_max_mss);564565// initialise I terms from lean angles566_pid_vel_ne_m.reset_filter();567// initialise the I term to (_accel_target_ned_mss - _accel_desired_ned_mss)568// _accel_desired_ned_mss is zero and can be removed from the equation569_pid_vel_ne_m.set_integrator((_accel_target_ned_mss.xy() - _vel_target_ned_ms.xy() * _pid_vel_ne_m.ff()));570571// initialise ekf xy reset handler572NE_init_ekf_reset();573574// initialise z_controller time out575_last_update_ne_ticks = AP::scheduler().ticks32();576}577578// Sets the desired NE-plane acceleration in m/s² using jerk-limited shaping.579// Smoothly transitions to the specified acceleration from current kinematic state.580// Constraints: max acceleration and jerk set via NE_set_max_speed_accel_m().581void AC_PosControl::input_accel_NE_m(const Vector2f& accel_ne_mss)582{583update_pos_vel_accel_xy(_pos_desired_ned_m.xy(), _vel_desired_ned_ms.xy(), _accel_desired_ned_mss.xy(), _dt_s, _limit_vector_ned.xy(), _p_pos_ne_m.get_error(), _pid_vel_ne_m.get_error());584shape_accel_xy(accel_ne_mss, _accel_desired_ned_mss.xy(), _jerk_max_ne_msss, _dt_s);585}586587// Sets desired NE-plane velocity and acceleration (cm/s, cm/s²) using jerk-limited shaping.588// See input_vel_accel_NE_m() for full details.589void AC_PosControl::input_vel_accel_NE_cm(Vector2f& vel_ne_cms, const Vector2f& accel_ne_cmss, bool limit_output)590{591Vector2f vel_ne_ms = vel_ne_cms * 0.01;592input_vel_accel_NE_m(vel_ne_ms, accel_ne_cmss * 0.01, limit_output);593vel_ne_cms = vel_ne_ms * 100.0;594}595596// Sets desired NE-plane velocity and acceleration (m/s, m/s²) using jerk-limited shaping.597// Calculates target acceleration using current kinematics constrained by acceleration and jerk limits.598// If `limit_output` is true, applies limits to total command (desired + correction).599void AC_PosControl::input_vel_accel_NE_m(Vector2f& vel_ne_ms, const Vector2f& accel_ne_mss, bool limit_output)600{601update_pos_vel_accel_xy(_pos_desired_ned_m.xy(), _vel_desired_ned_ms.xy(), _accel_desired_ned_mss.xy(), _dt_s, _limit_vector_ned.xy(), _p_pos_ne_m.get_error(), _pid_vel_ne_m.get_error());602603shape_vel_accel_xy(vel_ne_ms, accel_ne_mss, _vel_desired_ned_ms.xy(), _accel_desired_ned_mss.xy(),604_accel_max_ne_mss, _jerk_max_ne_msss, _dt_s, limit_output);605606update_vel_accel_xy(vel_ne_ms, accel_ne_mss, _dt_s, Vector2f(), Vector2f());607}608609// Sets desired NE position, velocity, and acceleration (cm, cm/s, cm/s²) with jerk-limited shaping.610// See input_pos_vel_accel_NE_m() for full details.611void AC_PosControl::input_pos_vel_accel_NE_cm(Vector2p& pos_ne_cm, Vector2f& vel_ne_cms, const Vector2f& accel_ne_cmss, bool limit_output)612{613Vector2p pos_ne_m = pos_ne_cm * 0.01;614Vector2f vel_ne_ms = vel_ne_cms * 0.01;615input_pos_vel_accel_NE_m(pos_ne_m, vel_ne_ms, accel_ne_cmss * 0.01, limit_output);616pos_ne_cm = pos_ne_m * 100.0;617vel_ne_cms = vel_ne_ms * 100.0;618}619620// Sets desired NE position, velocity, and acceleration (m, m/s, m/s²) with jerk-limited shaping.621// Calculates acceleration trajectory based on current kinematics and constraints.622// If `limit_output` is true, limits apply to full command (desired + correction).623void AC_PosControl::input_pos_vel_accel_NE_m(Vector2p& pos_ne_m, Vector2f& vel_ne_ms, const Vector2f& accel_ne_mss, bool limit_output)624{625update_pos_vel_accel_xy(_pos_desired_ned_m.xy(), _vel_desired_ned_ms.xy(), _accel_desired_ned_mss.xy(), _dt_s, _limit_vector_ned.xy(), _p_pos_ne_m.get_error(), _pid_vel_ne_m.get_error());626627shape_pos_vel_accel_xy(pos_ne_m, vel_ne_ms, accel_ne_mss, _pos_desired_ned_m.xy(), _vel_desired_ned_ms.xy(), _accel_desired_ned_mss.xy(),628_vel_max_ne_ms, _accel_max_ne_mss, _jerk_max_ne_msss, _dt_s, limit_output);629630update_pos_vel_accel_xy(pos_ne_m, vel_ne_ms, accel_ne_mss, _dt_s, Vector2f(), Vector2f(), Vector2f());631}632633// Updates NE offsets by gradually moving them toward their targets.634void AC_PosControl::NE_update_offsets()635{636// Check if NE offset targets have timed out637uint32_t now_ms = AP_HAL::millis();638if (now_ms - _posvelaccel_offset_target_ne_ms > POSCONTROL_POSVELACCEL_OFFSET_TARGET_TIMEOUT_MS) {639// Timeout: reset all NE offset targets to zero640_pos_offset_target_ned_m.xy().zero();641_vel_offset_target_ned_ms.xy().zero();642_accel_offset_target_ned_mss.xy().zero();643}644645// Advance offset target kinematic state (position, velocity, accel)646update_pos_vel_accel_xy(_pos_offset_target_ned_m.xy(), _vel_offset_target_ned_ms.xy(), _accel_offset_target_ned_mss.xy(), _dt_s, Vector2f(), Vector2f(), Vector2f());647update_pos_vel_accel_xy(_pos_offset_ned_m.xy(), _vel_offset_ned_ms.xy(), _accel_offset_ned_mss.xy(), _dt_s, _limit_vector_ned.xy(), _p_pos_ne_m.get_error(), _pid_vel_ne_m.get_error());648649// Shape the offset path from current to target using jerk-limited smoothing650shape_pos_vel_accel_xy(_pos_offset_target_ned_m.xy(), _vel_offset_target_ned_ms.xy(), _accel_offset_target_ned_mss.xy(),651_pos_offset_ned_m.xy(), _vel_offset_ned_ms.xy(), _accel_offset_ned_mss.xy(),652_vel_max_ne_ms, _accel_max_ne_mss, _jerk_max_ne_msss, _dt_s, false);653}654655// Disables NE position correction by setting the target position to the current position.656// Useful to freeze positional control without disrupting velocity control.657void AC_PosControl::NE_stop_pos_stabilisation()658{659_pos_target_ned_m.xy() = _pos_estimate_ned_m.xy();660_pos_desired_ned_m.xy() = _pos_target_ned_m.xy() - _pos_offset_ned_m.xy();661}662663// Disables NE position and velocity correction by setting target values to current state.664// Useful to prevent further corrections and freeze motion stabilization in NE axes.665void AC_PosControl::NE_stop_vel_stabilisation()666{667_pos_target_ned_m.xy() = _pos_estimate_ned_m.xy();668_pos_desired_ned_m.xy() = _pos_target_ned_m.xy() - _pos_offset_ned_m.xy();669670_vel_target_ned_ms.xy() = _vel_estimate_ned_ms.xy();671_vel_desired_ned_ms.xy() = _vel_target_ned_ms.xy() - _vel_offset_ned_ms.xy();672673// reset I terms674_pid_vel_ne_m.reset_filter();675_pid_vel_ne_m.reset_I();676}677678// Returns true if the NE position controller has run in the last 5 control loop cycles.679bool AC_PosControl::NE_is_active() const680{681const uint32_t dt_ticks = AP::scheduler().ticks32() - _last_update_ne_ticks;682return dt_ticks <= 1;683}684685// Uses P and PID controllers to generate corrections which are added to feedforward velocity/acceleration.686// Requires all desired targets to be pre-set using the input_* or set_* methods.687void AC_PosControl::NE_update_controller()688{689// check for ekf xy position reset690NE_handle_ekf_reset();691692// Check for position control time out693if (!NE_is_active()) {694NE_init_controller();695if (has_good_timing()) {696// call internal error because initialisation has not been done697INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);698}699}700_last_update_ne_ticks = AP::scheduler().ticks32();701702float ahrsGndSpdLimit, ahrsControlScaleXY;703AP::ahrs().getControlLimits(ahrsGndSpdLimit, ahrsControlScaleXY);704705// Update lateral position, velocity, and acceleration offsets using path shaping706NE_update_offsets();707708// Position Controller709710// Combine position target with active NE offset to get absolute target711_pos_target_ned_m.xy() = _pos_desired_ned_m.xy() + _pos_offset_ned_m.xy();712713// determine the combined position of the actual position and the disturbance from system ID mode714// calculate the target velocity correction715Vector2p comb_pos_ne_m = _pos_estimate_ned_m.xy();716comb_pos_ne_m += _disturb_pos_ne_m.topostype();717718// Run P controller to compute velocity setpoint from position error719Vector2f vel_target_ne_ms = _p_pos_ne_m.update_all(_pos_target_ned_m.xy(), comb_pos_ne_m);720_pos_desired_ned_m.xy() = _pos_target_ned_m.xy() - _pos_offset_ned_m.xy();721722// Velocity Controller723724// Apply AHRS scaling (e.g. for optical flow noise compensation)725vel_target_ne_ms *= ahrsControlScaleXY;726vel_target_ne_ms *= _ne_control_scale_factor;727728_vel_target_ned_ms.xy() = vel_target_ne_ms;729_vel_target_ned_ms.xy() += _vel_desired_ned_ms.xy() + _vel_offset_ned_ms.xy();730731// Velocity Controller732733// determine the combined velocity of the actual velocity and the disturbance from system ID mode734Vector2f comb_vel_ne_ms = _vel_estimate_ned_ms.xy();735comb_vel_ne_ms += _disturb_vel_ne_ms;736737// Run velocity PID controller and scale result for control authority738Vector2f accel_target_ne_mss = _pid_vel_ne_m.update_all(_vel_target_ned_ms.xy(), comb_vel_ne_ms, _dt_s, _limit_vector_ned.xy());739740// Acceleration Controller741742// Apply AHRS scaling again to correct for measurement distortions743accel_target_ne_mss *= ahrsControlScaleXY;744accel_target_ne_mss *= _ne_control_scale_factor;745746_ne_control_scale_factor = 1.0;747748// pass the correction acceleration to the target acceleration output749_accel_target_ned_mss.xy() = accel_target_ne_mss;750_accel_target_ned_mss.xy() += _accel_desired_ned_mss.xy() + _accel_offset_ned_mss.xy();751752// limit acceleration using maximum lean angles753const float angle_max_rad = MIN(_attitude_control.get_althold_lean_angle_max_rad(), get_lean_angle_max_rad());754const float accel_max_mss = angle_rad_to_accel_mss(angle_max_rad);755// Save unbounded target for use in "limited" check (not unit-consistent with z!)756_limit_vector_ned.xy() = _accel_target_ned_mss.xy();757if (!limit_accel_xy(_vel_desired_ned_ms.xy(), _accel_target_ned_mss.xy(), accel_max_mss)) {758// _accel_target_ned_mss was not limited so we can zero the xy limit vector759_limit_vector_ned.xy().zero();760}761762// Convert acceleration to roll/pitch angle targets (used by attitude controller)763accel_NE_mss_to_lean_angles_rad(_accel_target_ned_mss.x, _accel_target_ned_mss.y, _roll_target_rad, _pitch_target_rad);764765// Update yaw and yaw rate targets to match heading of motion766calculate_yaw_and_rate_yaw();767768// reset the disturbance from system ID mode to zero769_disturb_pos_ne_m.zero();770_disturb_vel_ne_ms.zero();771}772773774///775/// Vertical position controller776///777778// Sets maximum climb/descent rate (cm/s) and vertical acceleration (cm/s²) for the U-axis.779// See D_set_max_speed_accel_m() for full details.780// All values must be positive.781void AC_PosControl::D_set_max_speed_accel_cm(float decent_speed_max_cms, float climb_speed_max_cms, float accel_max_u_cmss)782{783D_set_max_speed_accel_m(decent_speed_max_cms * 0.01, climb_speed_max_cms * 0.01, accel_max_u_cmss * 0.01);784}785786// Sets maximum climb/descent rate (m/s) and vertical acceleration (m/s²) for the U-axis.787// These values are used for jerk-limited kinematic shaping of the vertical trajectory.788// All values must be positive.789void AC_PosControl::D_set_max_speed_accel_m(float decent_speed_max_ms, float climb_speed_max_ms, float accel_max_d_mss)790{791// sanity check and update792if (!is_zero(decent_speed_max_ms)) {793_vel_max_down_ms = fabsf(decent_speed_max_ms);794}795if (!is_zero(climb_speed_max_ms)) {796_vel_max_up_ms = fabsf(climb_speed_max_ms);797}798if (!is_zero(accel_max_d_mss)) {799_accel_max_d_mss = fabsf(accel_max_d_mss);800}801802// ensure the vertical Jerk is not limited by the filters in the Z acceleration PID object803_jerk_max_d_msss = _shaping_jerk_d_msss;804if (is_positive(_pid_accel_d_m.filt_T_hz())) {805_jerk_max_d_msss = MIN(_jerk_max_d_msss, MIN(GRAVITY_MSS, _accel_max_d_mss) * (M_2PI * _pid_accel_d_m.filt_T_hz()) / 5.0);806}807if (is_positive(_pid_accel_d_m.filt_E_hz())) {808_jerk_max_d_msss = MIN(_jerk_max_d_msss, MIN(GRAVITY_MSS, _accel_max_d_mss) * (M_2PI * _pid_accel_d_m.filt_E_hz()) / 5.0);809}810}811812// Sets vertical correction velocity and acceleration limits (cm/s, cm/s²).813// Should only be called during initialization to avoid discontinuities.814// See set_correction_speed_accel_U_m() for full details.815// All values must be positive.816void AC_PosControl::D_set_correction_speed_accel_cm(float decent_speed_max_cms, float climb_speed_max_cms, float accel_max_u_cmss)817{818D_set_correction_speed_accel_m(decent_speed_max_cms * 0.01, climb_speed_max_cms * 0.01, accel_max_u_cmss * 0.01);819}820821// Sets vertical correction velocity and acceleration limits (m/s, m/s²).822// These values constrain the correction output of the PID controller.823// All values must be positive.824void AC_PosControl::D_set_correction_speed_accel_m(float decent_speed_max_ms, float climb_speed_max_ms, float accel_max_d_mss)825{826// define maximum position error and maximum first and second differential limits827_p_pos_d_m.set_limits(-fabsf(decent_speed_max_ms), fabsf(climb_speed_max_ms), fabsf(accel_max_d_mss), 0.0f);828}829830// Initializes U-axis controller to current position, velocity, and acceleration, disallowing descent.831// Used for takeoff or hold scenarios where downward motion is prohibited.832void AC_PosControl::D_init_controller_no_descent()833{834// Initialise the position controller to the current throttle, position, velocity and acceleration.835D_init_controller();836837// remove all descent if present838_vel_target_ned_ms.z = MIN(0.0, _vel_target_ned_ms.z);839_vel_desired_ned_ms.z = MIN(0.0, _vel_desired_ned_ms.z);840_vel_terrain_d_ms = MIN(0.0, _vel_terrain_d_ms);841_vel_offset_ned_ms.z = MIN(0.0, _vel_offset_ned_ms.z);842_accel_target_ned_mss.z = MIN(0.0, _accel_target_ned_mss.z);843_accel_desired_ned_mss.z = MIN(0.0, _accel_desired_ned_mss.z);844_accel_terrain_d_mss = MIN(0.0, _accel_terrain_d_mss);845_accel_offset_ned_mss.z = MIN(0.0, _accel_offset_ned_mss.z);846}847848// Initializes U-axis controller to a stationary stopping point with zero velocity and acceleration.849// Used when the trajectory starts at rest but the initial altitude is unspecified.850// The resulting position target can be retrieved with get_pos_target_NED_m().851void AC_PosControl::D_init_controller_stopping_point()852{853// Initialise the position controller to the current throttle, position, velocity and acceleration.854D_init_controller();855856get_stopping_point_D_m(_pos_desired_ned_m.z);857_pos_target_ned_m.z = _pos_desired_ned_m.z + _pos_offset_ned_m.z;858_vel_desired_ned_ms.z = 0.0f;859_accel_desired_ned_mss.z = 0.0f;860}861862// Smoothly decays U-axis acceleration to zero over time while maintaining current vertical velocity.863// Reduces requested acceleration by ~95% every 0.5 seconds to avoid abrupt transitions.864// `throttle_setting` is used to determine whether to preserve positive acceleration in low-thrust cases.865void AC_PosControl::D_relax_controller(float throttle_setting)866{867// Initialise the position controller to the current position, velocity and acceleration.868D_init_controller();869870// D_init_controller has set the acceleration PID I term to generate the current throttle set point871// Use relax_integrator to decay the throttle set point to throttle_setting872_pid_accel_d_m.relax_integrator(-(throttle_setting - _motors.get_throttle_hover()), _dt_s, POSCONTROL_RELAX_TC);873}874875// Fully initializes the U-axis controller with current position, velocity, acceleration, and attitude.876// Used during standard controller activation when full state is known.877// Private function shared by other vertical initializers.878void AC_PosControl::D_init_controller()879{880// initialise terrain targets and offsets to zero881init_terrain();882883// initialise offsets to target offsets and ensure offset targets are zero if they have not been updated.884D_init_offsets();885886_pos_target_ned_m.z = _pos_estimate_ned_m.z;887_pos_desired_ned_m.z = _pos_target_ned_m.z - _pos_offset_ned_m.z;888889_vel_target_ned_ms.z = _vel_estimate_ned_ms.z;890_vel_desired_ned_ms.z = _vel_target_ned_ms.z - _vel_offset_ned_ms.z;891892// Reset I term of velocity PID893_pid_vel_d_m.reset_filter();894_pid_vel_d_m.set_integrator(0.0f);895896_accel_target_ned_mss.z = constrain_float(get_estimated_accel_D_mss(), -_accel_max_d_mss, _accel_max_d_mss);897_accel_desired_ned_mss.z = _accel_target_ned_mss.z - (_accel_offset_ned_mss.z + _accel_terrain_d_mss);898_pid_accel_d_m.reset_filter();899900// Set acceleration PID I term based on the current throttle901// Remove the expected P term due to _accel_desired_ned_mss.z being constrained to _accel_max_d_mss902// Remove the expected FF term due to non-zero _accel_target_ned_mss.z903_pid_accel_d_m.set_integrator(-(_attitude_control.get_throttle_in() - _motors.get_throttle_hover())904- _pid_accel_d_m.kP() * (_accel_target_ned_mss.z - get_estimated_accel_D_mss())905- _pid_accel_d_m.ff() * _accel_target_ned_mss.z);906907// initialise ekf z reset handler908D_init_ekf_reset();909910// initialise z_controller time out911_last_update_d_ticks = AP::scheduler().ticks32();912}913914// Sets the desired vertical acceleration in m/s² using jerk-limited shaping.915// Smoothly transitions to the target acceleration from current kinematic state.916// Constraints: max acceleration and jerk set via D_set_max_speed_accel_m().917void AC_PosControl::input_accel_D_m(float accel_d_mss)918{919// calculated increased maximum jerk if over speed920float jerk_max_d_msss = _jerk_max_d_msss * calculate_overspeed_gain();921922// adjust desired alt if motors have not hit their limits923update_pos_vel_accel(_pos_desired_ned_m.z, _vel_desired_ned_ms.z, _accel_desired_ned_mss.z, _dt_s, _limit_vector_ned.z, _p_pos_d_m.get_error(), _pid_vel_d_m.get_error());924925shape_accel(accel_d_mss, _accel_desired_ned_mss.z, jerk_max_d_msss, _dt_s);926}927928// Sets desired vertical velocity and acceleration (m/s, m/s²) using jerk-limited shaping.929// Calculates required acceleration using current vertical kinematics.930// If `limit_output` is true, limits apply to the combined (desired + correction) command.931void AC_PosControl::input_vel_accel_D_m(float &vel_d_ms, float accel_d_mss, bool limit_output)932{933// calculated increased maximum acceleration and jerk if over speed934const float overspeed_gain = calculate_overspeed_gain();935const float accel_max_d_mss = _accel_max_d_mss * overspeed_gain;936const float jerk_max_d_msss = _jerk_max_d_msss * overspeed_gain;937938// adjust desired alt if motors have not hit their limits939update_pos_vel_accel(_pos_desired_ned_m.z, _vel_desired_ned_ms.z, _accel_desired_ned_mss.z, _dt_s, _limit_vector_ned.z, _p_pos_d_m.get_error(), _pid_vel_d_m.get_error());940941shape_vel_accel(vel_d_ms, accel_d_mss,942_vel_desired_ned_ms.z, _accel_desired_ned_mss.z,943-accel_max_d_mss, constrain_float(accel_max_d_mss, 0.0, 7.5),944jerk_max_d_msss, _dt_s, limit_output);945946update_vel_accel(vel_d_ms, accel_d_mss, _dt_s, 0.0, 0.0);947}948949// Generates a vertical trajectory using the given climb rate in cm/s and jerk-limited shaping.950// Adjusts the internal target altitude based on integrated climb rate.951// See set_pos_target_D_from_climb_rate_m() for full details.952void AC_PosControl::D_set_pos_target_from_climb_rate_cms(float climb_rate_cms)953{954D_set_pos_target_from_climb_rate_ms(climb_rate_cms * 0.01);955}956957// Generates a vertical trajectory using the given climb rate in m/s and jerk-limited shaping.958// Target altitude is updated over time by integrating the climb rate.959void AC_PosControl::D_set_pos_target_from_climb_rate_ms(float climb_rate_ms, bool ignore_descent_limit)960{961if (ignore_descent_limit) {962// turn off limits in the down (positive z) direction963_limit_vector_ned.z = MIN(_limit_vector_ned.z, 0.0f);964}965966float vel_d_ms = -climb_rate_ms;967input_vel_accel_D_m(vel_d_ms, 0.0);968}969970// Sets vertical position, velocity, and acceleration in cm using jerk-limited shaping.971// See input_pos_vel_accel_D_m() for full details.972void AC_PosControl::input_pos_vel_accel_U_cm(float &pos_u_cm, float &vel_u_cms, float accel_u_cmss, bool limit_output)973{974float pos_d_m = -pos_u_cm * 0.01;975float vel_d_ms = -vel_u_cms * 0.01;976const float accel_d_mss = -accel_u_cmss * 0.01;977input_pos_vel_accel_D_m(pos_d_m, vel_d_ms, accel_d_mss, limit_output);978pos_u_cm = -pos_d_m * 100.0;979vel_u_cms = -vel_d_ms * 100.0;980}981982// Sets vertical position, velocity, and acceleration in meters using jerk-limited shaping.983// Calculates required acceleration using current state and constraints.984// If `limit_output` is true, limits are applied to combined (desired + correction) command.985void AC_PosControl::input_pos_vel_accel_D_m(float &pos_d_m, float &vel_d_ms, float accel_d_mss, bool limit_output)986{987// calculated increased maximum acceleration and jerk if over speed988const float overspeed_gain = calculate_overspeed_gain();989const float accel_max_d_mss = _accel_max_d_mss * overspeed_gain;990const float jerk_max_d_msss = _jerk_max_d_msss * overspeed_gain;991992// adjust desired altitude if motors have not hit their limits993update_pos_vel_accel(_pos_desired_ned_m.z, _vel_desired_ned_ms.z, _accel_desired_ned_mss.z, _dt_s, _limit_vector_ned.z, _p_pos_d_m.get_error(), _pid_vel_d_m.get_error());994995shape_pos_vel_accel(pos_d_m, vel_d_ms, accel_d_mss,996_pos_desired_ned_m.z, _vel_desired_ned_ms.z, _accel_desired_ned_mss.z,997-_vel_max_up_ms, _vel_max_down_ms,998-accel_max_d_mss, constrain_float(accel_max_d_mss, 0.0, 7.5),999jerk_max_d_msss, _dt_s, limit_output);10001001postype_t posp = pos_d_m;1002update_pos_vel_accel(posp, vel_d_ms, accel_d_mss, _dt_s, 0.0, 0.0, 0.0);1003pos_d_m = posp;1004}10051006// Sets target altitude in cm using jerk-limited shaping to gradually move to the new position.1007// See D_set_alt_target_with_slew_m() for full details.1008void AC_PosControl::set_alt_target_with_slew_cm(float pos_u_cm)1009{1010D_set_alt_target_with_slew_m(pos_u_cm * 0.01);1011}10121013// Sets target altitude in meters using jerk-limited shaping.1014void AC_PosControl::D_set_alt_target_with_slew_m(float pos_u_m)1015{1016float pos_d_m = -pos_u_m;1017float zero = 0;1018input_pos_vel_accel_D_m(pos_d_m, zero, 0);1019}10201021// Updates vertical (U) offsets by gradually moving them toward their targets.1022void AC_PosControl::D_update_offsets()1023{1024// Check if vertical offset targets have timed out1025uint32_t now_ms = AP_HAL::millis();1026if (now_ms - _posvelaccel_offset_target_d_ms > POSCONTROL_POSVELACCEL_OFFSET_TARGET_TIMEOUT_MS) {1027// Timeout: reset U-axis offset targets to zero1028_pos_offset_target_ned_m.z = 0.0;1029_vel_offset_target_ned_ms.z = 0.0;1030_accel_offset_target_ned_mss.z = 0.0;1031}10321033// Advance current offset state using PID-derived feedback and vertical limits1034postype_t p_offset_d_m = _pos_offset_ned_m.z;1035update_pos_vel_accel(p_offset_d_m, _vel_offset_ned_ms.z, _accel_offset_ned_mss.z, _dt_s, MIN(_limit_vector_ned.z, 0.0f), _p_pos_d_m.get_error(), _pid_vel_d_m.get_error());1036_pos_offset_ned_m.z = p_offset_d_m;10371038// Shape offset trajectory (position/velocity/acceleration) using jerk-limited smoothing1039shape_pos_vel_accel(_pos_offset_target_ned_m.z, _vel_offset_target_ned_ms.z, _accel_offset_target_ned_mss.z,1040_pos_offset_ned_m.z, _vel_offset_ned_ms.z, _accel_offset_ned_mss.z,1041-get_max_speed_up_ms(), get_max_speed_down_ms(),1042-D_get_max_accel_mss(), D_get_max_accel_mss(),1043_jerk_max_d_msss, _dt_s, false);10441045// Update target state forward in time with assumed zero velocity/acceleration targets1046p_offset_d_m = _pos_offset_target_ned_m.z;1047update_pos_vel_accel(p_offset_d_m, _vel_offset_target_ned_ms.z, _accel_offset_target_ned_mss.z, _dt_s, 0.0, 0.0, 0.0);1048_pos_offset_target_ned_m.z = p_offset_d_m;1049}10501051// Returns true if the U-axis controller has run in the last 5 control loop cycles.1052bool AC_PosControl::D_is_active() const1053{1054const uint32_t dt_ticks = AP::scheduler().ticks32() - _last_update_d_ticks;1055return dt_ticks <= 1;1056}10571058// Runs the vertical (U-axis) position controller.1059// Computes output acceleration based on position and velocity errors using PID correction.1060// Feedforward velocity and acceleration are combined with corrections to produce a smooth vertical command.1061// Desired position, velocity, and acceleration must be set before calling.1062void AC_PosControl::D_update_controller()1063{1064// check for ekf z-axis position reset1065D_handle_ekf_reset();10661067// Check for z_controller time out1068if (!D_is_active()) {1069D_init_controller();1070if (has_good_timing()) {1071// call internal error because initialisation has not been done1072INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);1073}1074}1075_last_update_d_ticks = AP::scheduler().ticks32();10761077// Update vertical offset targets and terrain estimate1078D_update_offsets();1079update_terrain();10801081// Position Controller10821083// Combine desired + offset + terrain for final position target1084_pos_target_ned_m.z = _pos_desired_ned_m.z + _pos_offset_ned_m.z + _pos_terrain_d_m;10851086// P controller: convert position error to velocity target1087_vel_target_ned_ms.z = _p_pos_d_m.update_all(_pos_target_ned_m.z, _pos_estimate_ned_m.z);1088_vel_target_ned_ms.z *= AP::ahrs().getControlScaleZ();10891090_pos_desired_ned_m.z = _pos_target_ned_m.z - (_pos_offset_ned_m.z + _pos_terrain_d_m);10911092// add feed forward component1093_vel_target_ned_ms.z += _vel_desired_ned_ms.z + _vel_offset_ned_ms.z + _vel_terrain_d_ms;10941095// Velocity Controller10961097// PID controller: convert velocity error to acceleration1098_accel_target_ned_mss.z = _pid_vel_d_m.update_all(_vel_target_ned_ms.z, _vel_estimate_ned_ms.z, _dt_s, _motors.limit.throttle_lower, _motors.limit.throttle_upper);1099_accel_target_ned_mss.z *= AP::ahrs().getControlScaleZ();11001101// add feed forward component1102_accel_target_ned_mss.z += _accel_desired_ned_mss.z + _accel_offset_ned_mss.z + _accel_terrain_d_mss;11031104// Acceleration Controller11051106// Gravity-compensated vertical acceleration measurement (positive = up)1107const float estimated_accel_d_mss = get_estimated_accel_D_mss();11081109// Ensure integrator can produce enough thrust to overcome hover throttle1110if (_motors.get_throttle_hover() > _pid_accel_d_m.imax()) {1111_pid_accel_d_m.set_imax(_motors.get_throttle_hover());1112}1113float thrust_d_norm;1114if (_vibe_comp_enabled) {1115// Use vibration-resistant throttle estimator (feedforward + scaled integrator)1116thrust_d_norm = get_throttle_with_vibration_override();1117} else {1118// Standard PID update using vertical acceleration error1119thrust_d_norm = _pid_accel_d_m.update_all(_accel_target_ned_mss.z, estimated_accel_d_mss, _dt_s, (_motors.limit.throttle_lower || _motors.limit.throttle_upper));1120// Include FF contribution to reduce delay1121thrust_d_norm += _pid_accel_d_m.get_ff();1122}1123thrust_d_norm -= _motors.get_throttle_hover();11241125// Actuator commands11261127// Send final throttle output to attitude controller (includes angle boost)1128_attitude_control.set_throttle_out(-thrust_d_norm, true, POSCONTROL_THROTTLE_CUTOFF_FREQ_HZ);11291130// Check for vertical controller health11311132// Update health indicator based on error magnitude vs configured speed range1133float error_ratio = _pid_vel_d_m.get_error() / _vel_max_down_ms;1134_vel_d_control_ratio += _dt_s * 0.1f * (0.5 - error_ratio);1135_vel_d_control_ratio = constrain_float(_vel_d_control_ratio, 0.0f, 2.0f);11361137// set vertical component of the limit vector1138if (_motors.limit.throttle_upper) {1139_limit_vector_ned.z = -1.0f;1140} else if (_motors.limit.throttle_lower) {1141_limit_vector_ned.z = 1.0f;1142} else {1143_limit_vector_ned.z = 0.0f;1144}1145}114611471148///1149/// Accessors1150///11511152// Returns the maximum allowed roll/pitch angle in radians.1153float AC_PosControl::get_lean_angle_max_rad() const1154{1155if (is_positive(_angle_max_override_rad)) {1156return _angle_max_override_rad;1157}1158if (!is_positive(_lean_angle_max_deg)) {1159return _attitude_control.lean_angle_max_rad();1160}1161return radians(_lean_angle_max_deg);1162}11631164// Sets externally computed NED position, velocity, and acceleration in meters, m/s, and m/s².1165// Use when path planning or shaping is done outside this controller.1166void AC_PosControl::set_pos_vel_accel_NED_m(const Vector3p& pos_ned_m, const Vector3f& vel_ned_ms, const Vector3f& accel_ned_mss)1167{1168_pos_desired_ned_m = pos_ned_m;1169_vel_desired_ned_ms = vel_ned_ms;1170_accel_desired_ned_mss = accel_ned_mss;1171}11721173// Sets externally computed NE position, velocity, and acceleration in meters, m/s, and m/s².1174// Use when path planning or shaping is done outside this controller.1175void AC_PosControl::set_pos_vel_accel_NE_m(const Vector2p& pos_ne_m, const Vector2f& vel_ne_ms, const Vector2f& accel_ne_mss)1176{1177_pos_desired_ned_m.xy() = pos_ne_m;1178_vel_desired_ned_ms.xy() = vel_ne_ms;1179_accel_desired_ned_mss.xy() = accel_ne_mss;1180}11811182// Converts lean angles (rad) to NED acceleration in m/s².1183Vector3f AC_PosControl::lean_angles_rad_to_accel_NED_mss(const Vector3f& att_target_euler_rad) const1184{1185// rotate our roll, pitch angles into lat/lon frame1186const float sin_roll = sinf(att_target_euler_rad.x);1187const float cos_roll = cosf(att_target_euler_rad.x);1188const float sin_pitch = sinf(att_target_euler_rad.y);1189const float cos_pitch = cosf(att_target_euler_rad.y);1190const float sin_yaw = sinf(att_target_euler_rad.z);1191const float cos_yaw = cosf(att_target_euler_rad.z);11921193return Vector3f{1194GRAVITY_MSS * (-cos_yaw * sin_pitch * cos_roll - sin_yaw * sin_roll) / MAX(cos_roll * cos_pitch, 0.1f),1195GRAVITY_MSS * (-sin_yaw * sin_pitch * cos_roll + cos_yaw * sin_roll) / MAX(cos_roll * cos_pitch, 0.1f),1196-GRAVITY_MSS1197};1198}11991200/// Terrain12011202// Initializes terrain position, velocity, and acceleration to match the terrain target.1203void AC_PosControl::init_terrain()1204{1205// set terrain position and target to zero1206_pos_terrain_target_d_m = 0.0;1207_pos_terrain_d_m = 0.0;12081209// set velocity offset to zero1210_vel_terrain_d_ms = 0.0;12111212// set acceleration offset to zero1213_accel_terrain_d_mss = 0.0;1214}12151216// Initializes both the terrain altitude and terrain target to the same value1217// (altitude above EKF origin in centimeters, Up-positive).1218// See init_pos_terrain_D_m() for full description.1219void AC_PosControl::init_pos_terrain_U_cm(float pos_terrain_u_cm)1220{1221init_pos_terrain_D_m(-pos_terrain_u_cm * 0.01);1222}12231224// Initializes both the terrain altitude and terrain target to the same value1225// (relative to EKF origin in meters, Down-positive).1226void AC_PosControl::init_pos_terrain_D_m(float pos_terrain_d_m)1227{1228_pos_desired_ned_m.z -= (pos_terrain_d_m - _pos_terrain_d_m);1229_pos_terrain_target_d_m = pos_terrain_d_m;1230_pos_terrain_d_m = pos_terrain_d_m;1231}123212331234/// Offsets12351236// Initializes NE position/velocity/acceleration offsets to match their respective targets.1237void AC_PosControl::NE_init_offsets()1238{1239// check for offset target timeout1240uint32_t now_ms = AP_HAL::millis();1241if (now_ms - _posvelaccel_offset_target_ne_ms > POSCONTROL_POSVELACCEL_OFFSET_TARGET_TIMEOUT_MS) {1242_pos_offset_target_ned_m.xy().zero();1243_vel_offset_target_ned_ms.xy().zero();1244_accel_offset_target_ned_mss.xy().zero();1245}12461247// set position offset to target1248_pos_offset_ned_m.xy() = _pos_offset_target_ned_m.xy();12491250// set velocity offset to target1251_vel_offset_ned_ms.xy() = _vel_offset_target_ned_ms.xy();12521253// set acceleration offset to target1254_accel_offset_ned_mss.xy() = _accel_offset_target_ned_mss.xy();1255}12561257// Initializes vertical (U) offsets to match their respective targets.1258void AC_PosControl::D_init_offsets()1259{1260// check for offset target timeout1261uint32_t now_ms = AP_HAL::millis();1262if (now_ms - _posvelaccel_offset_target_d_ms > POSCONTROL_POSVELACCEL_OFFSET_TARGET_TIMEOUT_MS) {1263_pos_offset_target_ned_m.z = 0.0;1264_vel_offset_target_ned_ms.z = 0.0;1265_accel_offset_target_ned_mss.z = 0.0;1266}12671268// set position offset to target1269_pos_offset_ned_m.z = _pos_offset_target_ned_m.z;12701271// set velocity offset to target1272_vel_offset_ned_ms.z = _vel_offset_target_ned_ms.z;12731274// set acceleration offset to target1275_accel_offset_ned_mss.z = _accel_offset_target_ned_mss.z;1276}12771278#if AP_SCRIPTING_ENABLED1279// Sets additional position, velocity, and acceleration offsets in meters (NED frame) for scripting.1280// Offsets are added to the controller’s internal target.1281// Used in LUA1282bool AC_PosControl::set_posvelaccel_offset(const Vector3f &pos_offset_ned_m, const Vector3f &vel_offset_ned_ms, const Vector3f &accel_offset_ned_mss)1283{1284set_posvelaccel_offset_target_NE_m(pos_offset_ned_m.topostype().xy(), vel_offset_ned_ms.xy(), accel_offset_ned_mss.xy());1285set_posvelaccel_offset_target_D_m(pos_offset_ned_m.topostype().z, vel_offset_ned_ms.z, accel_offset_ned_mss.z);1286return true;1287}12881289// Retrieves current scripted offsets in meters (NED frame).1290// Used in LUA1291bool AC_PosControl::get_posvelaccel_offset(Vector3f &pos_offset_ned_m, Vector3f &vel_offset_ned_ms, Vector3f &accel_offset_ned_mss)1292{1293pos_offset_ned_m = _pos_offset_target_ned_m.tofloat();1294vel_offset_ned_ms = _vel_offset_target_ned_ms;1295accel_offset_ned_mss = _accel_offset_target_ned_mss;1296return true;1297}12981299// Retrieves current target velocity (NED frame, m/s) including any scripted offset.1300// Used in LUA1301bool AC_PosControl::get_vel_target(Vector3f &vel_target_ned_ms)1302{1303if (!NE_is_active() || !D_is_active()) {1304return false;1305}13061307vel_target_ned_ms = _vel_target_ned_ms;1308return true;1309}13101311// Retrieves current target acceleration (NED frame, m/s²) including any scripted offset.1312// Used in LUA1313bool AC_PosControl::get_accel_target(Vector3f &accel_target_ned_mss)1314{1315if (!NE_is_active() || !D_is_active()) {1316return false;1317}13181319accel_target_ned_mss = _accel_target_ned_mss;1320return true;1321}1322#endif13231324// Sets NE offset targets in meters, m/s, and m/s².1325void AC_PosControl::set_posvelaccel_offset_target_NE_m(const Vector2p& pos_offset_target_ne_m, const Vector2f& vel_offset_target_ne_ms, const Vector2f& accel_offset_target_ne_mss)1326{1327// set position offset target1328_pos_offset_target_ned_m.xy() = pos_offset_target_ne_m;13291330// set velocity offset target1331_vel_offset_target_ned_ms.xy() = vel_offset_target_ne_ms;13321333// set acceleration offset target1334_accel_offset_target_ned_mss.xy() = accel_offset_target_ne_mss;13351336// record time of update so we can detect timeouts1337_posvelaccel_offset_target_ne_ms = AP_HAL::millis();1338}13391340// Sets vertical offset targets (m, m/s, m/s²) relative to EKF origin in meters, Down-positive.1341void AC_PosControl::set_posvelaccel_offset_target_D_m(float pos_offset_target_d_m, float vel_offset_target_d_ms, const float accel_offset_target_d_mss)1342{1343// set position offset target1344_pos_offset_target_ned_m.z = pos_offset_target_d_m;13451346// set velocity offset target1347_vel_offset_target_ned_ms.z = vel_offset_target_d_ms;13481349// set acceleration offset target1350_accel_offset_target_ned_mss.z = accel_offset_target_d_mss;13511352// record time of update so we can detect timeouts1353_posvelaccel_offset_target_d_ms = AP_HAL::millis();1354}13551356// Returns desired thrust direction as a unit vector in the body frame.1357Vector3f AC_PosControl::get_thrust_vector() const1358{1359Vector3f accel_target_ned_mss = get_accel_target_NED_mss();1360accel_target_ned_mss.z = -GRAVITY_MSS;1361return accel_target_ned_mss;1362}13631364// Computes NE stopping point in meters based on current position, velocity, and acceleration.1365void AC_PosControl::get_stopping_point_NE_m(Vector2p &stopping_point_ne_m) const1366{1367// Start from estimated NE position with offset removed1368// todo: we should use the current target position and velocity if we are currently running the position controller1369stopping_point_ne_m = _pos_estimate_ned_m.xy();1370stopping_point_ne_m -= _pos_offset_ned_m.xy();13711372Vector2f vel_estimate_ne_ms = _vel_estimate_ned_ms.xy();1373vel_estimate_ne_ms -= _vel_offset_ned_ms.xy();13741375// Compute velocity magnitude1376float speed_ne_ms = vel_estimate_ne_ms.length();13771378if (!is_positive(speed_ne_ms)) {1379return;1380}13811382// Use current P gain and max accel to estimate stopping distance1383float kP = _p_pos_ne_m.kP();1384const float stopping_dist_m = stopping_distance(constrain_float(speed_ne_ms, 0.0, _vel_max_ne_ms), kP, _accel_max_ne_mss);1385if (!is_positive(stopping_dist_m)) {1386return;1387}13881389// Project stopping distance along current velocity direction1390// todo: convert velocity to a unit vector instead.1391const float stopping_time_s = stopping_dist_m / speed_ne_ms;1392stopping_point_ne_m += (vel_estimate_ne_ms * stopping_time_s).topostype();1393}13941395// Computes vertical stopping point in meters based on current velocity and acceleration.1396void AC_PosControl::get_stopping_point_D_m(postype_t &stopping_point_d_m) const1397{1398float curr_pos_d_m = _pos_estimate_ned_m.z;1399curr_pos_d_m -= _pos_offset_ned_m.z;14001401float curr_vel_d_ms = _vel_estimate_ned_ms.z;1402curr_vel_d_ms -= _vel_offset_ned_ms.z;14031404// If controller is unconfigured or disabled, return current position1405if (!is_positive(_p_pos_d_m.kP()) || !is_positive(_accel_max_d_mss)) {1406stopping_point_d_m = curr_pos_d_m;1407return;1408}14091410// Estimate stopping point using current velocity, P gain, and max vertical acceleration1411stopping_point_d_m = curr_pos_d_m + constrain_float(stopping_distance(curr_vel_d_ms, _p_pos_d_m.kP(), _accel_max_d_mss), - POSCONTROL_STOPPING_DIST_UP_MAX_M, POSCONTROL_STOPPING_DIST_DOWN_MAX_M);1412}14131414// Returns bearing from current position to position target in radians.1415// 0 = North, positive = clockwise.1416float AC_PosControl::get_bearing_to_target_rad() const1417{1418return (_pos_target_ned_m.xy() - _pos_estimate_ned_m.xy()).angle();1419}142014211422///1423/// System methods1424///14251426// Updates internal NED position and velocity estimates from AHRS.1427// Falls back to vertical-only data if horizontal velocity or position is invalid or vibration forces it.1428// When high_vibes is true, forces use of vertical fallback for velocity.1429void AC_PosControl::update_estimates(bool high_vibes)1430{1431Vector3p pos_estimate_ned_m;1432if (!AP::ahrs().get_relative_position_NED_origin(pos_estimate_ned_m)) {1433float posD;1434if (AP::ahrs().get_relative_position_D_origin_float(posD)) {1435pos_estimate_ned_m.z = posD;1436}1437}1438_pos_estimate_ned_m = pos_estimate_ned_m;14391440Vector3f vel_estimate_ned_ms;1441if (!AP::ahrs().get_velocity_NED(vel_estimate_ned_ms) || high_vibes) {1442float rate_z;1443if (AP::ahrs().get_vert_pos_rate_D(rate_z)) {1444vel_estimate_ned_ms.z = rate_z;1445}1446}1447_vel_estimate_ned_ms = vel_estimate_ned_ms;1448}14491450// Calculates vertical throttle using vibration-resistant feedforward estimation.1451// Returns throttle output using manual feedforward gain for vibration compensation mode.1452// Integrator is adjusted using velocity error when PID is being overridden.1453float AC_PosControl::get_throttle_with_vibration_override()1454{1455const float thr_per_accel_d_mss = _motors.get_throttle_hover();1456// Estimate throttle based on desired acceleration (manual feedforward gain).1457// Used when IMU vibrations corrupt raw acceleration measurements.1458// Allow integrator to compensate for velocity error only if not thrust-limited,1459// or if integrator is actively helping counteract velocity error direction.1460// ToDo: clear pid_info P, I and D terms for logging1461if (!(_motors.limit.throttle_lower || _motors.limit.throttle_upper) || ((is_positive(_pid_accel_d_m.get_i()) && is_negative(_pid_vel_d_m.get_error())) || (is_negative(_pid_accel_d_m.get_i()) && is_positive(_pid_vel_d_m.get_error())))) {1462// Adjust integrator to help reduce velocity error.1463// Note: scale by velocity P-gain and an override-specific I gain.1464_pid_accel_d_m.set_integrator(_pid_accel_d_m.get_i() + _dt_s * thr_per_accel_d_mss * _pid_vel_d_m.get_error() * _pid_vel_d_m.kP() * POSCONTROL_VIBE_COMP_I_GAIN);1465}1466// Final throttle = P term (feedforward) + scaled I term.1467return POSCONTROL_VIBE_COMP_P_GAIN * thr_per_accel_d_mss * _accel_target_ned_mss.z + _pid_accel_d_m.get_i();1468}14691470// Resets NED position controller state to prevent transients when exiting standby.1471// Zeros I-terms and aligns targets to current position.1472void AC_PosControl::NED_standby_reset()1473{1474// Reset vertical acceleration controller integrator to prevent throttle bias on reentry1475_pid_accel_d_m.set_integrator(0.0f);14761477// Reset position controller targets to match current estimate — avoids position jumps1478_pos_target_ned_m = _pos_estimate_ned_m;14791480// Reset horizontal velocity controller integrator and derivative filter1481_pid_vel_ne_m.reset_filter();14821483// Reset EKF XY position reset tracking for NE controller1484NE_init_ekf_reset();1485}14861487#if HAL_LOGGING_ENABLED1488// Writes position controller diagnostic logs (PSCN, PSCE, etc).1489void AC_PosControl::write_log()1490{1491if (NE_is_active()) {1492float accel_n_mss, accel_e_mss;1493lean_angles_to_accel_NE_mss(accel_n_mss, accel_e_mss);14941495// Log North-axis position control (PSCN): desired, target, and actual1496Write_PSCN(_pos_desired_ned_m.x, _pos_target_ned_m.x, _pos_estimate_ned_m.x ,1497_vel_desired_ned_ms.x, _vel_target_ned_ms.x, _vel_estimate_ned_ms.x,1498_accel_desired_ned_mss.x, _accel_target_ned_mss.x, accel_n_mss);14991500// Log East-axis position control (PSCE): desired, target, and actual1501Write_PSCE(_pos_desired_ned_m.y, _pos_target_ned_m.y, _pos_estimate_ned_m.y,1502_vel_desired_ned_ms.y, _vel_target_ned_ms.y, _vel_estimate_ned_ms.y,1503_accel_desired_ned_mss.y, _accel_target_ned_mss.y, accel_e_mss);15041505// log offsets if they are being used1506if (!_pos_offset_ned_m.xy().is_zero()) {1507// Log North offset tracking (PSON)1508Write_PSON(_pos_offset_target_ned_m.x, _pos_offset_ned_m.x, _vel_offset_target_ned_ms.x, _vel_offset_ned_ms.x, _accel_offset_target_ned_mss.x, _accel_offset_ned_mss.x);15091510// Log East offset tracking (PSOE)1511Write_PSOE(_pos_offset_target_ned_m.y, _pos_offset_ned_m.y, _vel_offset_target_ned_ms.y, _vel_offset_ned_ms.y, _accel_offset_target_ned_mss.y, _accel_offset_ned_mss.y);1512}1513}15141515if (D_is_active()) {1516// Log Down-axis position control (PSCD)1517Write_PSCD(_pos_desired_ned_m.z, _pos_target_ned_m.z, _pos_estimate_ned_m.z,1518_vel_desired_ned_ms.z, _vel_target_ned_ms.z, _vel_estimate_ned_ms.z,1519_accel_desired_ned_mss.z, _accel_target_ned_mss.z, get_estimated_accel_D_mss());15201521// log down and terrain offsets if they are being used1522if (!is_zero(_pos_offset_ned_m.z)) {1523// Log Down offset tracking (PSOD)1524Write_PSOD(_pos_offset_target_ned_m.z, _pos_offset_ned_m.z, _vel_offset_target_ned_ms.z, _vel_offset_ned_ms.z, _accel_offset_target_ned_mss.z, _accel_offset_ned_mss.z);1525}1526if (!is_zero(_pos_terrain_d_m)) {1527// Log terrain-following offset (PSOT)1528Write_PSOT(_pos_terrain_target_d_m, _pos_terrain_d_m, 0, _vel_terrain_d_ms, 0, _accel_terrain_d_mss);1529}1530}1531}1532#endif // HAL_LOGGING_ENABLED15331534// Returns lateral distance to closest point on active trajectory in meters.1535// Used to assess horizontal deviation from path.1536float AC_PosControl::crosstrack_error_m() const1537{1538const Vector2f pos_error = (_pos_target_ned_m.xy() - _pos_estimate_ned_m.xy()).tofloat();1539if (is_zero(_vel_desired_ned_ms.xy().length_squared())) {1540// No desired velocity → return direct distance to target1541return pos_error.length();1542} else {1543// Project position error onto desired velocity vector1544const Vector2f vel_unit = _vel_desired_ned_ms.xy().normalized();1545const float dot_error = pos_error * vel_unit;15461547// Use Pythagorean difference to isolate perpendicular (cross-track) component1548// todo: remove MAX of zero when safe_sqrt fixed1549return safe_sqrt(MAX(pos_error.length_squared() - sq(dot_error), 0.0));1550}1551}15521553#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)1554// Returns true if the requested forward pitch is limited by the configured tilt constraint.1555bool AC_PosControl::get_fwd_pitch_is_limited() const1556{1557if (_limit_vector_ned.xy().is_zero()) {1558return false;1559}1560const float angle_max_rad = MIN(_attitude_control.get_althold_lean_angle_max_rad(), get_lean_angle_max_rad());1561const float accel_max_mss = angle_rad_to_accel_mss(angle_max_rad);1562// Check for pitch limiting in the forward direction1563const float accel_fwd_unlimited_mss = _limit_vector_ned.x * _ahrs.cos_yaw() + _limit_vector_ned.y * _ahrs.sin_yaw();1564const float pitch_target_unlimited_deg = accel_mss_to_angle_deg(- MIN(accel_fwd_unlimited_mss, accel_max_mss));1565const float accel_fwd_limited = _accel_target_ned_mss.x * _ahrs.cos_yaw() + _accel_target_ned_mss.y * _ahrs.sin_yaw();1566const float pitch_target_limited_deg = accel_mss_to_angle_deg(- accel_fwd_limited);15671568return is_negative(pitch_target_unlimited_deg) && pitch_target_unlimited_deg < pitch_target_limited_deg;1569}1570#endif // APM_BUILD_TYPE(APM_BUILD_ArduPlane)15711572///1573/// private methods1574///15751576/// Terrain15771578// Updates terrain estimate (_pos_terrain_d_m) toward target using filter time constants.1579void AC_PosControl::update_terrain()1580{1581// update position, velocity, acceleration offsets for this iteration1582postype_t pos_terrain_d_m = _pos_terrain_d_m;1583update_pos_vel_accel(pos_terrain_d_m, _vel_terrain_d_ms, _accel_terrain_d_mss, _dt_s, MIN(_limit_vector_ned.z, 0.0f), _p_pos_d_m.get_error(), _pid_vel_d_m.get_error());1584_pos_terrain_d_m = pos_terrain_d_m;15851586// input shape horizontal position, velocity and acceleration offsets1587shape_pos_vel_accel(_pos_terrain_target_d_m, 0.0, 0.0,1588_pos_terrain_d_m, _vel_terrain_d_ms, _accel_terrain_d_mss,1589-get_max_speed_up_ms(), get_max_speed_down_ms(),1590-D_get_max_accel_mss(), D_get_max_accel_mss(),1591_jerk_max_d_msss, _dt_s, false);15921593// we do not have to update _pos_terrain_target_d_m because we assume the target velocity and acceleration are zero1594// if we know how fast the terrain altitude is changing we would add update_pos_vel_accel for _pos_terrain_target_d_m here1595}15961597// Converts horizontal acceleration (m/s²) to roll/pitch lean angles in radians.1598void AC_PosControl::accel_NE_mss_to_lean_angles_rad(float accel_n_mss, float accel_e_mss, float& roll_target_rad, float& pitch_target_rad) const1599{1600// rotate accelerations into body forward-right frame1601const float accel_forward_mss = accel_n_mss * _ahrs.cos_yaw() + accel_e_mss * _ahrs.sin_yaw();1602const float accel_right_mss = -accel_n_mss * _ahrs.sin_yaw() + accel_e_mss * _ahrs.cos_yaw();16031604// update angle targets that will be passed to stabilize controller1605pitch_target_rad = accel_mss_to_angle_rad(-accel_forward_mss);1606float cos_pitch_target = cosf(pitch_target_rad);1607roll_target_rad = accel_mss_to_angle_rad(accel_right_mss * cos_pitch_target);1608}16091610// Converts current target lean angles to NE acceleration in m/s².1611void AC_PosControl::lean_angles_to_accel_NE_mss(float& accel_n_mss, float& accel_e_mss) const1612{1613// rotate our roll, pitch angles into lat/lon frame1614Vector3f att_target_euler_rad = _attitude_control.get_att_target_euler_rad();1615att_target_euler_rad.z = _ahrs.yaw;1616Vector3f accel_ne_mss = lean_angles_rad_to_accel_NED_mss(att_target_euler_rad);16171618accel_n_mss = accel_ne_mss.x;1619accel_e_mss = accel_ne_mss.y;1620}16211622// Computes desired yaw and yaw rate based on the NE acceleration and velocity vectors.1623// Aligns yaw with the direction of travel if speed exceeds 5% of maximum.1624void AC_PosControl::calculate_yaw_and_rate_yaw()1625{1626// Calculate the turn rate1627float turn_rate_rads = 0.0f;1628const float vel_desired_length_ne_ms = _vel_desired_ned_ms.xy().length();1629if (is_positive(vel_desired_length_ne_ms)) {1630// Project acceleration vector into velocity direction to extract forward acceleration component1631const float accel_forward_mss = (_accel_desired_ned_mss.x * _vel_desired_ned_ms.x + _accel_desired_ned_mss.y * _vel_desired_ned_ms.y) / vel_desired_length_ne_ms;1632// Subtract forward component to isolate turn acceleration perpendicular to velocity vector1633const Vector2f accel_turn_ne_mss = _accel_desired_ned_mss.xy() - _vel_desired_ned_ms.xy() * accel_forward_mss / vel_desired_length_ne_ms;1634// Compute turn rate from lateral acceleration and velocity (centripetal formula)1635const float accel_turn_length_ne_mss = accel_turn_ne_mss.length();1636turn_rate_rads = accel_turn_length_ne_mss / vel_desired_length_ne_ms;1637// Determine turn direction: positive = clockwise (right)1638if ((accel_turn_ne_mss.y * _vel_desired_ned_ms.x - accel_turn_ne_mss.x * _vel_desired_ned_ms.y) < 0.0) {1639turn_rate_rads = -turn_rate_rads;1640}1641}16421643// If vehicle is moving significantly, align yaw to velocity vector and apply computed turn rate1644if (vel_desired_length_ne_ms > _vel_max_ne_ms * 0.05f) {1645_yaw_target_rad = _vel_desired_ned_ms.xy().angle();1646_yaw_rate_target_rads = turn_rate_rads;1647return;1648}16491650// If motion is too slow, retain last yaw target from attitude controller1651_yaw_target_rad = _attitude_control.get_att_target_euler_rad().z;1652_yaw_rate_target_rads = 0;1653}16541655// Computes scaling factor to increase max vertical accel/jerk if vertical speed exceeds configured limits.1656float AC_PosControl::calculate_overspeed_gain()1657{1658// If desired descent speed exceeds configured max, scale acceleration/jerk proportionally1659if (_vel_desired_ned_ms.z > _vel_max_down_ms && !is_zero(_vel_max_down_ms)) {1660return POSCONTROL_OVERSPEED_GAIN_U * _vel_desired_ned_ms.z / _vel_max_down_ms;1661}16621663// If desired climb speed exceeds configured max, scale acceleration/jerk proportionally1664if (_vel_desired_ned_ms.z < -_vel_max_up_ms && !is_zero(_vel_max_up_ms)) {1665return -POSCONTROL_OVERSPEED_GAIN_U * _vel_desired_ned_ms.z / _vel_max_up_ms;1666}16671668// Within normal speed limits — use nominal acceleration and jerk1669return 1.0;1670}16711672// Initializes tracking of NE EKF position resets.1673void AC_PosControl::NE_init_ekf_reset()1674{1675Vector2f pos_shift;1676_ekf_ne_reset_ms = _ahrs.getLastPosNorthEastReset(pos_shift);1677}16781679// Handles NE position reset detection and response (e.g., clearing accumulated errors).1680void AC_PosControl::NE_handle_ekf_reset()1681{1682// Check for EKF-reported NE position shift since last update1683Vector2f pos_shift_ne_m;1684uint32_t reset_ms = _ahrs.getLastPosNorthEastReset(pos_shift_ne_m);1685// todo: the actual difference in position and velocity estimation.1686// This will prevent the need to pause error calculation for one cycle.16871688if (reset_ms != _ekf_ne_reset_ms) {1689// This ensures controller output remains continuous after EKF realigns the origin.16901691// Reconstruct position target relative to the to new EKF estimation to maintain the current position error1692Vector2p delta_pos_estimate_ne_m = _p_pos_ne_m.get_error().topostype() - (_pos_target_ned_m.xy() - _pos_estimate_ned_m.xy());1693_pos_target_ned_m.xy() += delta_pos_estimate_ne_m;16941695// Reconstruct velocity target relative to the to new EKF estimation to maintain the current velocity error1696Vector2f delta_vel_estimate_ne_ms = _pid_vel_ne_m.get_error() - (_vel_target_ned_ms.xy() - _vel_estimate_ned_ms.xy());1697_vel_target_ned_ms.xy() += delta_vel_estimate_ne_ms;16981699switch (_ekf_reset_method) {1700case EKFResetMethod::MoveTarget:1701// Reset NE controller desired position and velocity to preserve actual position control during Loiter, PosHold, etc.1702_pos_desired_ned_m.xy() += delta_pos_estimate_ne_m;1703_vel_desired_ned_ms.xy() += delta_vel_estimate_ne_ms;1704break;1705case EKFResetMethod::MoveVehicle:1706// Move the change in estimate into the offsest to move the aircraft to our new estimate smoothly during Auto, Guided, etc.1707_pos_offset_ned_m.xy() += delta_pos_estimate_ne_m;1708_vel_offset_ned_ms.xy() += delta_vel_estimate_ne_ms;1709break;1710}1711_ekf_ne_reset_ms = reset_ms;1712}1713}17141715// Initializes tracking of vertical (U) EKF resets.1716void AC_PosControl::D_init_ekf_reset()1717{1718float alt_shift_d_m;1719_ekf_d_reset_ms = _ahrs.getLastPosDownReset(alt_shift_d_m);1720}17211722// Handles U EKF reset detection and response.1723void AC_PosControl::D_handle_ekf_reset()1724{1725// Check for EKF-reported Down-axis shift since last update1726float pos_shift_d_m;1727uint32_t reset_ms = _ahrs.getLastPosDownReset(pos_shift_d_m);1728// todo: the actual difference in position and velocity estimation.1729// This will prevent the need to pause error calculation for one cycle.17301731if (reset_ms != 0 && reset_ms != _ekf_d_reset_ms) {1732// This ensures controller output remains continuous after EKF realigns the origin.1733// Reconstruct position target relative to the to new EKF estimation to maintain the current position error1734postype_t delta_pos_estimate_d_m = _p_pos_d_m.get_error() - (_pos_target_ned_m.z - _pos_estimate_ned_m.z);1735_pos_target_ned_m.z += delta_pos_estimate_d_m;17361737// Reconstruct velocity target relative to the to new EKF estimation to maintain the current velocity error1738float delta_vel_estimate_d_ms = _pid_vel_d_m.get_error() - (_vel_target_ned_ms.z - _vel_estimate_ned_ms.z);1739_vel_target_ned_ms.z += delta_vel_estimate_d_ms;17401741switch (_ekf_reset_method) {1742case EKFResetMethod::MoveTarget:1743// Reset U controller desired position and velocity to preserve actual position control during Loiter, PosHold, etc.1744_pos_desired_ned_m.z += delta_pos_estimate_d_m;1745_vel_desired_ned_ms.z += delta_vel_estimate_d_ms;1746break;1747case EKFResetMethod::MoveVehicle:1748// Move the change in estimate into the offsest to move the aircraft to our new estimate smoothly during Auto, Guided, etc.1749_pos_offset_ned_m.z += delta_pos_estimate_d_m;1750_vel_offset_ned_ms.z += delta_vel_estimate_d_ms;1751break;1752}1753_ekf_d_reset_ms = reset_ms;1754}1755}17561757// Performs pre-arm checks for position control parameters and EKF readiness.1758// Returns false if failure_msg is populated.1759bool AC_PosControl::pre_arm_checks(const char *param_prefix,1760char *failure_msg,1761const uint8_t failure_msg_len)1762{1763if (!is_positive(NE_get_pos_p().kP())) {1764hal.util->snprintf(failure_msg, failure_msg_len, "%s_NE_POS_P must be > 0", param_prefix);1765return false;1766}1767if (!is_positive(D_get_pos_p().kP())) {1768hal.util->snprintf(failure_msg, failure_msg_len, "%s_D_POS_P must be > 0", param_prefix);1769return false;1770}1771if (!is_positive(D_get_vel_pid().kP())) {1772hal.util->snprintf(failure_msg, failure_msg_len, "%s_D_VEL_P must be > 0", param_prefix);1773return false;1774}1775if (!is_positive(D_get_accel_pid().kP())) {1776hal.util->snprintf(failure_msg, failure_msg_len, "%s_D_ACC_P must be > 0", param_prefix);1777return false;1778}1779if (!is_positive(D_get_accel_pid().kI())) {1780hal.util->snprintf(failure_msg, failure_msg_len, "%s_D_ACC_I must be > 0", param_prefix);1781return false;1782}17831784return true;1785}17861787// return true if on a real vehicle or SITL with lock-step scheduling1788bool AC_PosControl::has_good_timing(void) const1789{1790#if CONFIG_HAL_BOARD == HAL_BOARD_SITL1791auto *sitl = AP::sitl();1792if (sitl) {1793return sitl->state.is_lock_step_scheduled;1794}1795#endif1796// real boards are assumed to have good timing1797return true;1798}17991800// perform any required parameter conversions1801void AC_PosControl::convert_parameters()1802{1803// find param table key1804uint16_t k_param_psc_key;1805if (!AP_Param::find_key_by_pointer(this, k_param_psc_key)) {1806return;1807}18081809// return immediately if parameter conversion has already been performed1810if (_pid_accel_d_m.kP().configured()) {1811return;1812}18131814// PARAMETER_CONVERSION - Added: Nov-2025 for 4.71815// parameters that are simply moved1816#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)1817static const AP_Param::ConversionInfo conversion_info[] = {1818{ k_param_psc_key, 258257, AP_PARAM_FLOAT, "Q_P_D_VEL_P" }, // Q_P_VELZ_P moved to Q_P_D_VEL_P1819{ k_param_psc_key, 4305, AP_PARAM_FLOAT, "Q_P_D_VEL_I" }, // Q_P_VELZ_I moved to Q_P_D_VEL_I1820{ k_param_psc_key, 16593, AP_PARAM_FLOAT, "Q_P_D_VEL_D" }, // Q_P_VELZ_D moved to Q_P_D_VEL_D1821{ k_param_psc_key, 12497, AP_PARAM_FLOAT, "Q_P_D_VEL_FLTE" }, // Q_P_VELZ_FLTE moved to Q_P_D_VEL_FLTE1822{ k_param_psc_key, 20689, AP_PARAM_FLOAT, "Q_P_D_VEL_FLTD" }, // Q_P_VELZ_FLTD moved to Q_P_D_VEL_FLTD1823{ k_param_psc_key, 24785, AP_PARAM_FLOAT, "Q_P_D_VEL_FF" }, // Q_P_VELZ_FF moved to Q_P_D_VEL_FF1824{ k_param_psc_key, 16657, AP_PARAM_FLOAT, "Q_P_D_ACC_FF" }, // Q_P_ACCZ_FF moved to Q_P_D_ACC_FF1825{ k_param_psc_key, 37137, AP_PARAM_FLOAT, "Q_P_D_ACC_FLTT" }, // Q_P_ACCZ_FLTT moved to Q_P_D_ACC_FLTT1826{ k_param_psc_key, 41233, AP_PARAM_FLOAT, "Q_P_D_ACC_FLTE" }, // Q_P_ACCZ_FLTE moved to Q_P_D_ACC_FLTE1827{ k_param_psc_key, 45329, AP_PARAM_FLOAT, "Q_P_D_ACC_FLTD" }, // Q_P_ACCZ_FLTD moved to Q_P_D_ACC_FLTD1828{ k_param_psc_key, 49425, AP_PARAM_FLOAT, "Q_P_D_ACC_SMAX" }, // Q_P_ACCZ_SMAX moved to Q_P_D_ACC_SMAX1829{ k_param_psc_key, 53521, AP_PARAM_FLOAT, "Q_P_D_ACC_PDMX" }, // Q_P_ACCZ_PDMX moved to Q_P_D_ACC_PDMX1830{ k_param_psc_key, 57617, AP_PARAM_FLOAT, "Q_P_D_ACC_D_FF" }, // Q_P_ACCZ_D_FF moved to Q_P_D_ACC_D_FF1831{ k_param_psc_key, 65809, AP_PARAM_INT8, "Q_P_D_ACC_NEF" }, // Q_P_ACCZ_NEF moved to Q_P_D_ACC_NEF1832{ k_param_psc_key, 61713, AP_PARAM_INT8, "Q_P_D_ACC_NTF" }, // Q_P_ACCZ_NTF moved to Q_P_D_ACC_NTF1833{ k_param_psc_key, 258449, AP_PARAM_FLOAT, "Q_P_NE_VEL_P" }, // Q_P_VELXY_P moved to Q_P_NE_VEL_P1834{ k_param_psc_key, 4497, AP_PARAM_FLOAT, "Q_P_NE_VEL_I" }, // Q_P_VELXY_I moved to Q_P_NE_VEL_I1835{ k_param_psc_key, 16785, AP_PARAM_FLOAT, "Q_P_NE_VEL_D" }, // Q_P_VELXY_D moved to Q_P_NE_VEL_D1836{ k_param_psc_key, 12689, AP_PARAM_FLOAT, "Q_P_NE_VEL_FLTE" },// Q_P_VELXY_FLTE moved to Q_P_NE_VEL_FLTE1837{ k_param_psc_key, 20881, AP_PARAM_FLOAT, "Q_P_NE_VEL_FLTD" },// Q_P_VELXY_FLTD moved to Q_P_NE_VEL_FLTD1838{ k_param_psc_key, 24977, AP_PARAM_FLOAT, "Q_P_NE_VEL_FF" }, // Q_P_VELXY_FF moved to Q_P_NE_VEL_FF1839};1840#else1841static const AP_Param::ConversionInfo conversion_info[] = {1842{ k_param_psc_key, 4035, AP_PARAM_FLOAT, "PSC_D_VEL_P" }, // PSC_VELZ_P moved to PSC_D_VEL_P1843{ k_param_psc_key, 67, AP_PARAM_FLOAT, "PSC_D_VEL_I" }, // PSC_VELZ_I moved to PSC_D_VEL_I1844{ k_param_psc_key, 259, AP_PARAM_FLOAT, "PSC_D_VEL_D" }, // PSC_VELZ_D moved to PSC_D_VEL_D1845{ k_param_psc_key, 195, AP_PARAM_FLOAT, "PSC_D_VEL_FLTE" }, // PSC_VELZ_FLTE moved to PSC_D_VEL_FLTE1846{ k_param_psc_key, 323, AP_PARAM_FLOAT, "PSC_D_VEL_FLTD" }, // PSC_VELZ_FLTD moved to PSC_D_VEL_FLTD1847{ k_param_psc_key, 387, AP_PARAM_FLOAT, "PSC_D_VEL_FF" }, // PSC_VELZ_FF moved to PSC_D_VEL_FF1848{ k_param_psc_key, 260, AP_PARAM_FLOAT, "PSC_D_ACC_FF" }, // PSC_ACCZ_FF moved to PSC_D_ACC_FF1849{ k_param_psc_key, 580, AP_PARAM_FLOAT, "PSC_D_ACC_FLTT" }, // PSC_ACCZ_FLTT moved to PSC_D_ACC_FLTT1850{ k_param_psc_key, 644, AP_PARAM_FLOAT, "PSC_D_ACC_FLTE" }, // PSC_ACCZ_FLTE moved to PSC_D_ACC_FLTE1851{ k_param_psc_key, 708, AP_PARAM_FLOAT, "PSC_D_ACC_FLTD" }, // PSC_ACCZ_FLTD moved to PSC_D_ACC_FLTD1852{ k_param_psc_key, 772, AP_PARAM_FLOAT, "PSC_D_ACC_SMAX" }, // PSC_ACCZ_SMAX moved to PSC_D_ACC_SMAX1853{ k_param_psc_key, 836, AP_PARAM_FLOAT, "PSC_D_ACC_PDMX" }, // PSC_ACCZ_PDMX moved to PSC_D_ACC_PDMX1854{ k_param_psc_key, 900, AP_PARAM_FLOAT, "PSC_D_ACC_D_FF" }, // PSC_ACCZ_D_FF moved to PSC_D_ACC_D_FF1855{ k_param_psc_key, 1028, AP_PARAM_INT8, "PSC_D_ACC_NEF" }, // PSC_ACCZ_NEF moved to PSC_D_ACC_NEF1856{ k_param_psc_key, 964, AP_PARAM_INT8, "PSC_D_ACC_NTF" }, // PSC_ACCZ_NTF moved to PSC_D_ACC_NTF1857{ k_param_psc_key, 4038, AP_PARAM_FLOAT, "PSC_NE_VEL_P" }, // PSC_VELXY_P moved to PSC_NE_VEL_P1858{ k_param_psc_key, 70, AP_PARAM_FLOAT, "PSC_NE_VEL_I" }, // PSC_VELXY_I moved to PSC_NE_VEL_I1859{ k_param_psc_key, 262, AP_PARAM_FLOAT, "PSC_NE_VEL_D" }, // PSC_VELXY_D moved to PSC_NE_VEL_D1860{ k_param_psc_key, 198, AP_PARAM_FLOAT, "PSC_NE_VEL_FLTE" },// PSC_VELXY_FLTE moved to PSC_NE_VEL_FLTE1861{ k_param_psc_key, 326, AP_PARAM_FLOAT, "PSC_NE_VEL_FLTD" },// PSC_VELXY_FLTD moved to PSC_NE_VEL_FLTD1862{ k_param_psc_key, 390, AP_PARAM_FLOAT, "PSC_NE_VEL_FF" }, // PSC_VELXY_FF moved to PSC_NE_VEL_FF1863};1864#endif1865AP_Param::convert_old_parameters(conversion_info, ARRAY_SIZE(conversion_info));18661867// parameters moved and scaled by 0.11868#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)1869static const AP_Param::ConversionInfo conversion_info_01[] = {1870{ k_param_psc_key, 258321, AP_PARAM_FLOAT, "Q_P_D_ACC_P" }, // Q_P_ACCZ_P moved to Q_P_D_ACC_P1871{ k_param_psc_key, 4369, AP_PARAM_FLOAT, "Q_P_D_ACC_I" }, // Q_P_ACCZ_I moved to Q_P_D_ACC_I1872{ k_param_psc_key, 8465, AP_PARAM_FLOAT, "Q_P_D_ACC_D" }, // Q_P_ACCZ_D moved to Q_P_D_ACC_D1873};1874#else1875static const AP_Param::ConversionInfo conversion_info_01[] = {1876{ k_param_psc_key, 4036, AP_PARAM_FLOAT, "PSC_D_ACC_P" }, // PSC_ACCZ_P moved to PSC_D_ACC_P1877{ k_param_psc_key, 68, AP_PARAM_FLOAT, "PSC_D_ACC_I" }, // PSC_ACCZ_I moved to PSC_D_ACC_I1878{ k_param_psc_key, 132, AP_PARAM_FLOAT, "PSC_D_ACC_D" }, // PSC_ACCZ_D moved to PSC_D_ACC_D1879};1880#endif1881AP_Param::convert_old_parameters_scaled(conversion_info_01, ARRAY_SIZE(conversion_info_01), 0.1, 0);18821883// store PSC_D_ACC_P as flag that parameter conversion was completed1884_pid_accel_d_m.kP().save(true);18851886// parameters moved and scaled by 0.011887#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)1888static const AP_Param::ConversionInfo conversion_info_001[] = {1889{ k_param_psc_key, 8401, AP_PARAM_FLOAT, "Q_P_D_VEL_IMAX" }, // Q_P_VELZ_IMAX moved to Q_P_D_VEL_IMAX1890{ k_param_psc_key, 8593, AP_PARAM_FLOAT, "Q_P_NE_VEL_IMAX" }, // Q_P_VELXY_IMAX moved to Q_P_NE_VEL_IMAX1891};1892#else1893static const AP_Param::ConversionInfo conversion_info_001[] = {1894{ k_param_psc_key, 131, AP_PARAM_FLOAT, "PSC_D_VEL_IMAX" }, // PSC_VELZ_IMAX moved to PSC_D_VEL_IMAX1895{ k_param_psc_key, 134, AP_PARAM_FLOAT, "PSC_NE_VEL_IMAX" }, // PSC_VELXY_IMAX moved to PSC_NE_VEL_IMAX1896};1897#endif1898AP_Param::convert_old_parameters_scaled(conversion_info_001, ARRAY_SIZE(conversion_info_001), 0.01, 0);18991900// parameters moved and scaled by 0.0011901// PSC_ACCZ_IMAX replaced by PSC_D_ACC_IMAX1902#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)1903static const AP_Param::ConversionInfo psc_d_acc_imax_info = { k_param_psc_key, 20753, AP_PARAM_FLOAT, "Q_P_D_ACC_IMAX" };1904#else1905static const AP_Param::ConversionInfo psc_d_acc_imax_info = { k_param_psc_key, 324, AP_PARAM_FLOAT, "PSC_D_ACC_IMAX" };1906#endif1907AP_Param::convert_old_parameter(&psc_d_acc_imax_info, 0.001f);1908}190919101911