2017-02-07 20:49:55 -04:00
# pragma once
# include "AC_PosControl.h"
2021-04-16 12:53:14 -03:00
# define POSCONTROL_JERK_RATIO 1.0f // Defines the time it takes to reach the requested acceleration
2017-02-07 20:49:55 -04:00
class AC_PosControl_Sub : public AC_PosControl {
public :
2021-10-27 02:32:33 -03:00
using AC_PosControl : : AC_PosControl ;
2017-02-07 20:49:55 -04:00
/// set_alt_max - sets maximum altitude above the ekf origin in cm
2021-04-16 12:53:14 -03:00
/// only enforced when set_pos_target_z_from_climb_rate_cm is used
2017-02-07 20:49:55 -04:00
/// set to zero to disable limit
void set_alt_max ( float alt ) { _alt_max = alt ; }
/// set_alt_min - sets the minimum altitude (maximum depth) in cm
2021-04-16 12:53:14 -03:00
/// only enforced when set_pos_target_z_from_climb_rate_cm is used
2017-02-07 20:49:55 -04:00
/// set to zero to disable limit
void set_alt_min ( float alt ) { _alt_min = alt ; }
2021-08-06 06:40:56 -03:00
/// input_accel_z - calculate a jerk limited path from the current position, velocity and acceleration to an input acceleration.
2021-04-16 12:53:14 -03:00
/// The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt.
2021-08-06 06:40:56 -03:00
/// 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.
void input_vel_accel_z ( float & vel , float accel , bool force_descend , bool limit_output = true ) override ;
2019-03-18 14:11:25 -03:00
2017-02-07 20:49:55 -04:00
private :
float _alt_max ; // max altitude - should be updated from the main code with altitude limit from fence
float _alt_min ; // min altitude - should be updated from the main code with altitude limit from fence
} ;