8 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane) 10 # define POSCONTROL_POS_Z_P 1.0f // vertical position controller P gain default 11 # define POSCONTROL_VEL_Z_P 5.0f // vertical velocity controller P gain default 12 # define POSCONTROL_ACC_Z_P 0.3f // vertical acceleration controller P gain default 13 # define POSCONTROL_ACC_Z_I 1.0f // vertical acceleration controller I gain default 14 # define POSCONTROL_ACC_Z_D 0.0f // vertical acceleration controller D gain default 15 # define POSCONTROL_ACC_Z_IMAX 800 // vertical acceleration controller IMAX gain default 16 # define POSCONTROL_ACC_Z_FILT_HZ 10.0f // vertical acceleration controller input filter default 17 # define POSCONTROL_ACC_Z_DT 0.02f // vertical acceleration controller dt default 18 # define POSCONTROL_POS_XY_P 1.0f // horizontal position controller P gain default 19 # define POSCONTROL_VEL_XY_P 1.4f // horizontal velocity controller P gain default 20 # define POSCONTROL_VEL_XY_I 0.7f // horizontal velocity controller I gain default 21 # define POSCONTROL_VEL_XY_D 0.35f // horizontal velocity controller D gain default 22 # define POSCONTROL_VEL_XY_IMAX 1000.0f // horizontal velocity controller IMAX gain default 23 # define POSCONTROL_VEL_XY_FILT_HZ 5.0f // horizontal velocity controller input filter 24 # define POSCONTROL_VEL_XY_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D 25 #elif APM_BUILD_TYPE(APM_BUILD_ArduSub) 27 # define POSCONTROL_POS_Z_P 3.0f // vertical position controller P gain default 28 # define POSCONTROL_VEL_Z_P 8.0f // vertical velocity controller P gain default 29 # define POSCONTROL_ACC_Z_P 0.5f // vertical acceleration controller P gain default 30 # define POSCONTROL_ACC_Z_I 0.1f // vertical acceleration controller I gain default 31 # define POSCONTROL_ACC_Z_D 0.0f // vertical acceleration controller D gain default 32 # define POSCONTROL_ACC_Z_IMAX 100 // vertical acceleration controller IMAX gain default 33 # define POSCONTROL_ACC_Z_FILT_HZ 20.0f // vertical acceleration controller input filter default 34 # define POSCONTROL_ACC_Z_DT 0.0025f // vertical acceleration controller dt default 35 # define POSCONTROL_POS_XY_P 1.0f // horizontal position controller P gain default 36 # define POSCONTROL_VEL_XY_P 1.0f // horizontal velocity controller P gain default 37 # define POSCONTROL_VEL_XY_I 0.5f // horizontal velocity controller I gain default 38 # define POSCONTROL_VEL_XY_D 0.0f // horizontal velocity controller D gain default 39 # define POSCONTROL_VEL_XY_IMAX 1000.0f // horizontal velocity controller IMAX gain default 40 # define POSCONTROL_VEL_XY_FILT_HZ 5.0f // horizontal velocity controller input filter 41 # define POSCONTROL_VEL_XY_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D 44 # define POSCONTROL_POS_Z_P 1.0f // vertical position controller P gain default 45 # define POSCONTROL_VEL_Z_P 5.0f // vertical velocity controller P gain default 46 # define POSCONTROL_ACC_Z_P 0.5f // vertical acceleration controller P gain default 47 # define POSCONTROL_ACC_Z_I 1.0f // vertical acceleration controller I gain default 48 # define POSCONTROL_ACC_Z_D 0.0f // vertical acceleration controller D gain default 49 # define POSCONTROL_ACC_Z_IMAX 800 // vertical acceleration controller IMAX gain default 50 # define POSCONTROL_ACC_Z_FILT_HZ 20.0f // vertical acceleration controller input filter default 51 # define POSCONTROL_ACC_Z_DT 0.0025f // vertical acceleration controller dt default 52 # define POSCONTROL_POS_XY_P 1.0f // horizontal position controller P gain default 53 # define POSCONTROL_VEL_XY_P 2.0f // horizontal velocity controller P gain default 54 # define POSCONTROL_VEL_XY_I 1.0f // horizontal velocity controller I gain default 55 # define POSCONTROL_VEL_XY_D 0.5f // horizontal velocity controller D gain default 56 # define POSCONTROL_VEL_XY_IMAX 1000.0f // horizontal velocity controller IMAX gain default 57 # define POSCONTROL_VEL_XY_FILT_HZ 5.0f // horizontal velocity controller input filter 58 # define POSCONTROL_VEL_XY_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D 193 _attitude_control(attitude_control),
200 _last_update_xy_ms(0),
201 _last_update_z_ms(0),
206 _accel_last_z_cms(0.0
f),
213 _distance_to_target(0.0
f),
259 speed_down = -fabsf(speed_down);
414 float linear_distance;
415 float linear_velocity;
427 stopping_point.
z = curr_pos_z;
434 if (fabsf(curr_vel_z) < linear_velocity) {
436 stopping_point.
z = curr_pos_z + curr_vel_z/
_p_pos_z.
kP();
440 stopping_point.
z = curr_pos_z + (linear_distance + curr_vel_z*curr_vel_z/(2.0f*
_accel_z_cms));
442 stopping_point.
z = curr_pos_z - (linear_distance + curr_vel_z*curr_vel_z/(2.0f*
_accel_z_cms));
709 float linear_distance;
710 float linear_velocity;
721 float vel_total =
norm(curr_vel.
x, curr_vel.
y);
725 stopping_point.
x = curr_pos.
x;
726 stopping_point.
y = curr_pos.
y;
734 if (vel_total < linear_velocity) {
735 stopping_dist = vel_total/kP;
738 stopping_dist = linear_distance + (vel_total*vel_total)/(2.0
f*
_accel_cms);
745 stopping_point.
x = curr_pos.
x + (stopping_dist * curr_vel.
x / vel_total);
746 stopping_point.
y = curr_pos.
y + (stopping_dist * curr_vel.
y / vel_total);
843 float accel_x, accel_y;
846 DataFlash_Class::instance()->
Log_Write(
"PSC",
"TimeUS,TPX,TPY,PX,PY,TVX,TVY,VX,VY,TAX,TAY,AX,AY",
847 "smmmmnnnnoooo",
"FBBBBBBBBBBBB",
"Qffffffffffff",
849 (
double)pos_target.
x,
850 (
double)pos_target.
y,
853 (
double)vel_target.
x,
854 (
double)vel_target.
y,
857 (
double)accel_target.
x,
858 (
double)accel_target.
y,
1035 Vector2f accel_target, vel_xy_p, vel_xy_i, vel_xy_d;
1069 accel_target.
x = (vel_xy_p.
x + vel_xy_i.
x + vel_xy_d.
x) * ekfNavVelGainScaler;
1070 accel_target.
y = (vel_xy_p.
y + vel_xy_i.
y + vel_xy_d.
y) * ekfNavVelGainScaler;
1104 float accel_right, accel_forward;
1111 pitch_target = atanf(-accel_forward/(
GRAVITY_MSS * 100.0
f))*(18000.0f/
M_PI);
1112 float cos_pitch_target = cosf(pitch_target*
M_PI/18000.0f);
1113 roll_target = atanf(accel_right*cos_pitch_target/(
GRAVITY_MSS * 100.0f))*(18000.0f/
M_PI);
1130 if (accel_cms <= 0.0
f) {
1140 if(speed_cms <= accel_cms / kP) {
1142 leash_length = speed_cms / kP;
1145 leash_length = (accel_cms / (2.0f*kP*kP)) + (speed_cms*speed_cms / (2.0f*accel_cms));
1153 return leash_length;
1198 float vector_length =
norm(vector_x, vector_y);
1199 if ((vector_length > max_length) &&
is_positive(max_length)) {
1200 vector_x *= (max_length / vector_length);
1201 vector_y *= (max_length / vector_length);
1215 float linear_dist = second_ord_lim/
sq(p);
1216 float error_length =
norm(error.
x, error.
y);
1217 if (error_length > linear_dist) {
1218 float first_order_scale =
safe_sqrt(2.0
f*second_ord_lim*(error_length-(linear_dist * 0.5
f)))/error_length;
1219 return Vector3f(error.
x*first_order_scale, error.
y*first_order_scale, error.
z);
float norm(const T first, const U second, const Params... parameters)
#define POSCONTROL_ACCEL_FILTER_HZ
#define POSCONTROL_ACC_Z_IMAX
void get_stopping_point_xy(Vector3f &stopping_point) const
Vector2< float > Vector2f
uint32_t _last_update_z_ms
void init_takeoff()
init_takeoff - initialises target altitude if we are taking off
virtual float get_velocity_z() const =0
#define POSCONTROL_LEASH_LENGTH_MIN
void set_integrator(const Vector2f &i)
const AP_Motors & _motors
float get_lean_angle_max_cd() const
get_lean_angle_max_cd - returns the maximum lean angle the autopilot may request
Vector3< float > Vector3f
void init_ekf_xy_reset()
initialise and check for ekf position resets
void shift_pos_xy_target(float x_cm, float y_cm)
shift position target target in x, y axis
virtual const Vector3f & get_position() const =0
#define POSCONTROL_ACC_Z_DT
void set_alt_target_with_slew(float alt_cm, float dt)
float safe_sqrt(const T v)
const Vector3f & get_accel_target() const
#define POSCONTROL_DT_50HZ
float _distance_to_target
const Vector3f & get_vel_target() const
accessors for reporting
#define POSCONTROL_ACCEL_XY
static const struct AP_Param::GroupInfo var_info[]
float get_distance_to_target() const
get_distance_to_target - get horizontal distance to position target in cm (used for reporting) ...
virtual void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend)
float get_althold_lean_angle_max() const
#define POSCONTROL_VEL_ERROR_CUTOFF_FREQ
float get_alt_error() const
get_alt_error - returns altitude error in cm
void get_stopping_point_z(Vector3f &stopping_point) const
get_stopping_point_z - calculates stopping point based on current position, velocity, vehicle acceleration
const AP_AHRS_View & _ahrs
void set_input(const Vector2f &input)
virtual void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff)=0
#define POSCONTROL_ACC_Z_FILT_HZ
void update_z_controller()
update_z_controller - fly to altitude in cm above home
void set_desired_accel_xy(float accel_lat_cms, float accel_lon_cms)
void init_vel_controller_xyz()
xyz velocity controller
#define AP_GROUPINFO(name, idx, clazz, element, def)
struct AP_Motors::AP_Motors_limit limit
#define POSCONTROL_VEL_Z_P
void run_xy_controller(float dt, float ekfNavVelGainScaler)
AC_PosControl(const AP_AHRS_View &ahrs, const AP_InertialNav &inav, const AP_Motors &motors, AC_AttitudeControl &attitude_control)
Constructor.
void update_xy_controller(float ekfNavVelGainScaler)
update_xy_controller - run the horizontal position controller - should be called at 100hz or higher ...
float get_horizontal_error() const
#define POSCONTROL_SPEED_UP
static Vector3f sqrt_controller(const Vector3f &error, float p, float second_ord_lim)
Proportional controller with piecewise sqrt sections to constrain second derivative.
#define POSCONTROL_ACTIVE_TIMEOUT_MS
LowPassFilterVector2f _accel_target_filter
bool is_positive(const T fVal1)
#define POSCONTROL_VEL_XY_I
#define POSCONTROL_STOPPING_DIST_DOWN_MAX
const Vector3f & get_accel_ef_blended(void) const
#define POSCONTROL_ACC_Z_I
void update_vel_controller_xy(float ekfNavVelGainScaler)
#define POSCONTROL_DT_400HZ
uint16_t reset_accel_to_throttle
uint16_t reset_rate_to_accel_z
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
void set_integrator(float i)
void set_cutoff_frequency(float cutoff_freq)
#define POSCONTROL_POS_XY_P
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
void set_xy_target(float x, float y)
set_xy_target in cm from home
AP_MotorsMatrix motors(400)
void add_takeoff_climb_rate(float climb_rate_cms, float dt)
void update_vel_controller_xyz(float ekfNavVelGainScaler)
Object managing one P controller.
bool is_active_xy() const
#define POSCONTROL_VEL_XY_IMAX
void desired_vel_to_pos(float nav_dt)
desired_vel_to_pos - move position target using desired velocities
uint16_t reset_accel_to_lean_xy
#define POSCONTROL_POS_Z_P
float lean_angle_max() const
#define POSCONTROL_SPEED_DOWN
void check_for_ekf_xy_reset()
check for ekf position reset and adjust loiter or brake target position
void relax_alt_hold_controllers(float throttle_setting)
relax_alt_hold_controllers - set all desired and targets to measured
void lean_angles_to_accel(float &accel_x_cmss, float &accel_y_cmss) const
uint32_t getLastPosDownReset(float &posDelta) const
const Vector3f & get_pos_target() const
get_pos_target - get target as position vector (from home in cm)
void Log_Write(const char *name, const char *labels, const char *fmt,...)
struct AC_PosControl::poscontrol_limit_flags _limit
bool is_zero(const T fVal1)
void accel_to_lean_angles(float accel_x_cmss, float accel_y_cmss, float &roll_target, float &pitch_target) const
AC_AttitudeControl & _attitude_control
AP_Float _accel_xy_filt_hz
void init_xy_controller(bool reset_I=true)
void set_speed_z(float speed_down, float speed_up)
#define POSCONTROL_JERK_RATIO
struct AC_PosControl::poscontrol_flags _flags
void calc_leash_length_z()
static DataFlash_Class * instance(void)
void set_desired_velocity(const Vector3f &des_vel)
void set_dt(float delta_sec)
set_dt - sets time delta in seconds for all controllers (i.e. 100hz = 0.01, 400hz = 0...
void calc_leash_length_xy()
void set_accel_z(float accel_cmss)
set_accel_z - set vertical acceleration in cm/s/s
void init_ekf_z_reset()
initialise ekf z axis reset check
static float sqrt_controller(float error, float p, float second_ord_lim, float dt)
virtual float get_throttle_hover() const =0
#define POSCONTROL_ACC_Z_P
virtual void set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend)
void set_pos_target(const Vector3f &position)
set_pos_target in cm from home
const AP_InertialNav & _inav
void set_desired_rate(float desired)
#define POSCONTROL_ACC_Z_D
#define POSCONTROL_ACCEL_XY_MAX
Vector2f _vehicle_horiz_vel
#define POSCONTROL_OVERSPEED_GAIN_Z
uint32_t getLastPosNorthEastReset(Vector2f &pos) const
int32_t get_bearing_to_target() const
get_bearing_to_target - get bearing to target position in centi-degrees
void freeze_ff_z()
freeze_ff_z - used to stop the feed forward being calculated during a known discontinuity ...
#define POSCONTROL_THROTTLE_CUTOFF_FREQ
static bool limit_vector_length(float &vector_x, float &vector_y, float max_length)
limit vector to a given length, returns true if vector was limited
#define POSCONTROL_ACCEL_Z
float constrain_float(const float amt, const float low, const float high)
void shift_alt_target(float z_cm)
shift altitude target (positive means move altitude up)
Copter PID control class.
void set_target_to_stopping_point_xy()
set_target_to_stopping_point_xy - sets horizontal target to reasonable stopping position in cm from h...
void set_alt_target(float alt_cm)
set_alt_target - set altitude target in cm above home
void check_for_ekf_z_reset()
check for ekf position reset and adjust loiter or brake target position
void set_accel_xy(float accel_cmss)
set_accel_xy - set horizontal acceleration in cm/s/s
void set_input_filter_all(float input)
uint32_t _last_update_xy_ms
#define error(fmt, args ...)
uint16_t reset_desired_vel_to_pos
#define POSCONTROL_ACCELERATION_MIN
uint16_t vehicle_horiz_vel_override
void set_target_to_stopping_point_z()
set_target_to_stopping_point_z - sets altitude target to reasonable stopping altitude in cm above hom...
float time_since_last_xy_update() const
float get_p(float error) const
#define POSCONTROL_VEL_XY_P
virtual const Vector3f & get_velocity() const =0
float get_integrator() const
float get_throttle() const
void desired_accel_to_vel(float nav_dt)
move velocity target using desired acceleration
Copter PID control class.
#define POSCONTROL_VEL_XY_FILT_D_HZ
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
virtual float get_altitude() const =0
void set_speed_xy(float speed_cms)
set_speed_xy - set horizontal speed maximum in cm/s
LowPassFilterFloat _vel_error_filter
#define POSCONTROL_VEL_XY_D
#define POSCONTROL_STOPPING_DIST_UP_MAX
T apply(T sample, float dt)
#define POSCONTROL_VEL_XY_FILT_HZ
uint32_t _ekf_xy_reset_ms
float calc_leash_length(float speed_cms, float accel_cms, float kP) const
calc_leash_length - calculates the horizontal leash length given a maximum speed, acceleration and po...
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)