/// The vel is projected forwards in time based on a time step of dt and acceleration accel.
/// The vel is projected forwards in time based on a time step of dt and acceleration accel.
/// 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 function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt.
/// The function alters the vel to be the kinematic path based on accel
/// The function alters the vel to be the kinematic path based on accel
voidAC_PosControl::input_accel_z(constfloataccel)
voidAC_PosControl::input_accel_z(floataccel)
{
{
// calculated increased maximum acceleration if over speed
// calculated increased maximum acceleration if over speed
/// 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 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 jerk set using the function set_max_speed_accel_z.
/// The kinematic path is constrained by the maximum acceleration and jerk set using the function set_max_speed_accel_z.
/// The parameter limit_output specifies if the velocity and acceleration limits are applied to the sum of commanded and correction values or just correction.
/// The parameter limit_output specifies if the velocity and acceleration limits are applied to the sum of commanded and correction values or just correction.
/// input_pos_vel_accel_z - calculate a jerk limited path from the current position, velocity and acceleration to an input position velocity and acceleration.
/// 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 function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt.
/// The function alters the pos and vel to be the kinematic path based on accel
/// The function alters the pos and vel to be the kinematic path based on accel
/// The parameter limit_output specifies if the velocity and acceleration limits are applied to the sum of commanded and correction values or just correction.
/// The parameter limit_output specifies if the velocity and acceleration limits are applied to the sum of commanded and correction values or just correction.
/// input_accel_z - calculate a jerk limited path from the current position, velocity and acceleration to an input acceleration.
/// input_accel_z - calculate a jerk limited path from the current position, velocity and acceleration to an input 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 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 jerk set using the function set_max_speed_accel_z.
/// The kinematic path is constrained by the maximum acceleration and jerk set using the function set_max_speed_accel_z.
virtualvoidinput_accel_z(constfloataccel);
virtualvoidinput_accel_z(floataccel);
/// input_vel_accel_z - calculate a jerk limited path from the current position, velocity and acceleration to an input velocity and acceleration.
/// input_vel_accel_z - calculate a jerk limited path from the current position, velocity and acceleration to an input 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 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 jerk set using the function set_max_speed_accel_z.
/// The kinematic path is constrained by the maximum acceleration and jerk set using the function set_max_speed_accel_z.
/// The function alters the vel to be the kinematic path based on accel
/// The function alters the vel to be the kinematic path based on accel
/// The parameter limit_output specifies if the velocity and acceleration limits are applied to the sum of commanded and correction values or just correction.
/// The parameter limit_output specifies if the velocity and acceleration limits are applied to the sum of commanded and correction values or just correction.
/// input_pos_vel_accel_z - calculate a jerk limited path from the current position, velocity and acceleration to an input position velocity and acceleration.
/// 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 function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt.
@ -214,7 +214,7 @@ public:
/// set_alt_target_with_slew - adjusts target up or down using a commanded altitude in cm
/// set_alt_target_with_slew - adjusts target up or down using a commanded altitude in cm
/// using the default position control kinematic path.
/// using the default position control kinematic path.
voidset_alt_target_with_slew(constfloat&pos);
voidset_alt_target_with_slew(floatpos);
/// update_pos_offset_z - updates the vertical offsets used by terrain following
/// update_pos_offset_z - updates the vertical offsets used by terrain following