/// input_pos_vel_accel_xyz - calculate a jerk limited path from the current position, velocity and acceleration to an input position velocity and acceleration.
/// The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt.
/// The kinematic path is constrained by the maximum acceleration and time constant set using the function set_max_speed_accel_xy and time constant.
/// The time constant defines the acceleration error decay in the kinematic path as the system approaches constant acceleration.
/// The time constant also defines the time taken to achieve the maximum acceleration.
/// The function alters the input velocity to be the velocity that the system could reach zero acceleration in the minimum time.
/// init_xy_controller_stopping_point - initialise the position controller to the stopping point with zero velocity and acceleration.
/// This function should be used when the expected kinimatic path assumes a stationary initial condition but does not specify a specific starting position.
/// The starting position can be retrieved by getting the position target using get_pos_target_cm() after calling this function.
/// The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt.
/// The kinematic path is constrained by the maximum acceleration and time constant set using the function set_max_speed_accel_xy and time constant.
/// The time constant defines the acceleration error decay in the kinematic path as the system approaches constant acceleration.
/// The time constant also defines the time taken to achieve the maximum acceleration.
/// The function alters the input velocity to be the velocity that the system could reach zero acceleration in the minimum time.
/// input_pos_vel_accel_xy - calculate a jerk limited path from the current position, velocity and acceleration to an input position velocity and acceleration.
/// The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt.
/// The kinematic path is constrained by the maximum acceleration and time constant set using the function set_max_speed_accel_xy and time constant.
/// The time constant defines the acceleration error decay in the kinematic path as the system approaches constant acceleration.
/// The time constant also defines the time taken to achieve the maximum acceleration.
/// The function alters the input velocity to be the velocity that the system could reach zero acceleration in the minimum time.
/// stop_vel_xy_stabilisation - sets the target to the current position and velocity to the current velocity to remove any position and velocity corrections from the system
/// This function is the default initialisation for any position control that provides position, velocity and acceleration.
/// This function does not allow any negative velocity or acceleration
voidinit_z_controller_no_descent();
/// init_z_controller_stopping_point - initialise the position controller to the stopping point with zero velocity and acceleration.
/// This function should be used when the expected kinimatic path assumes a stationary initial condition but does not specify a specific starting position.
/// The starting position can be retrieved by getting the position target using get_pos_target_cm() after calling this function.
voidinit_z_controller_stopping_point();
// relax_z_controller - initialise the position controller to the current position and velocity with decaying acceleration.
/// This function decays the output acceleration by 95% every half second to achieve a smooth transition to zero requested acceleration.
/// The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt.
/// The kinematic path is constrained by the maximum acceleration and time constant set using the function set_max_speed_accel_z and time constant.
/// The time constant defines the acceleration error decay in the kinematic path as the system approaches constant acceleration.
/// The time constant also defines the time taken to achieve the maximum acceleration.
/// The function alters the input velocitiy to be the velocity that the system could reach zero acceleration in the minimum time.
/// input_pos_vel_accel_z - calculate a jerk limited path from the current position, velocity and acceleration to an input position velocity and acceleration.
/// The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt.
/// The kinematic path is constrained by the maximum acceleration and time constant set using the function set_max_speed_accel_z and time constant.
/// The time constant defines the acceleration error decay in the kinematic path as the system approaches constant acceleration.
/// The time constant also defines the time taken to achieve the maximum acceleration.
/// The function alters the input velocity to be the velocity that the system could reach zero acceleration in the minimum time.
AP_Float_lean_angle_max;// Maximum autopilot commanded angle (in degrees). Set to zero for Angle Max
AP_Float_shaping_tc_xy_s;// time constant of the xy kinimatic path generation in seconds used to determine how quickly the aircraft varies the acceleration target
AP_Float_shaping_tc_z_s;// time constant of the z kinimatic path generation in seconds used to determine how quickly the aircraft varies the acceleration target
AC_P_2D_p_pos_xy;// XY axis position controller to convert distance error to desired velocity
AC_P_1D_p_pos_z;// Z axis position controller to convert altitude error to desired climb rate
AC_PID_2D_pid_vel_xy;// XY axis velocity controller to convert velocity error to desired acceleration
AC_PID_Basic_pid_vel_z;// Z axis velocity controller to convert climb rate error to desired acceleration
AC_PID_pid_accel_z;// Z axis acceleration controller to convert desired acceleration to throttle output
uint64_t_last_update_z_us;// system time (in microseconds) since last update_z_controller call
float_tc_xy_s;// time constant of the xy kinimatic path generation in seconds used to determine how quickly the aircraft varies the acceleration target
float_tc_z_s;// time constant of the z kinimatic path generation in seconds used to determine how quickly the aircraft varies the acceleration target
float_vel_max_xy_cms;// max horizontal speed in cm/s
float_vel_max_up_cms;// max climb rate in cm/s
float_vel_max_down_cms;// max descent rate in cm/s
float_accel_max_xy_cmss;// max horizontal acceleration in cm/s/s
float_accel_limit_xy_cmss;// max horizontal acceleration in cm/s/s
float_accel_max_z_cmss;// max vertical acceleration in cm/s/s
float_vel_z_control_ratio=2.0f;// confidence that we have control in the vertical axis