6 #define LOITER_SPEED_DEFAULT 1250.0f // default loiter speed in cm/s 7 #define LOITER_SPEED_MIN 20.0f // minimum loiter speed in cm/s 8 #define LOITER_ACCEL_MAX_DEFAULT 500.0f // default acceleration in loiter mode 9 #define LOITER_BRAKE_ACCEL_DEFAULT 250.0f // minimum acceleration in loiter mode 10 #define LOITER_BRAKE_JERK_DEFAULT 500.0f // maximum jerk in cm/s/s/s in loiter mode 11 #define LOITER_BRAKE_START_DELAY_DEFAULT 1.0f // delay (in seconds) before loiter braking begins after sticks are released 12 #define LOITER_VEL_CORRECTION_MAX 200.0f // max speed used to correct position errors in loiter 13 #define LOITER_POS_CORRECTION_MAX 200.0f // max position error in loiter 14 #define LOITER_ACTIVE_TIMEOUT_MS 200 // loiter controller is considered active if it has been called within the past 200ms (0.2 seconds) 82 _pos_control(pos_control),
83 _attitude_control(attitude_control)
160 const float euler_roll_angle =
radians(euler_roll_angle_cd*0.01
f);
161 const float euler_pitch_angle =
radians(euler_pitch_angle_cd*0.01f);
173 const float pilot_cos_pitch_target = cosf(euler_pitch_angle);
174 const float pilot_accel_rgt_cms =
GRAVITY_MSS*100.0f * tanf(euler_roll_angle)/pilot_cos_pitch_target;
175 const float pilot_accel_fwd_cms = -
GRAVITY_MSS*100.0f * tanf(euler_pitch_angle);
234 float gnd_speed_limit_cms =
MIN(
_speed_cms, ekfGndSpdLimit*100.0
f);
250 Vector2f desired_vel(desired_vel_3d.
x,desired_vel_3d.
y);
257 float desired_speed = desired_vel.
length();
259 Vector2f desired_vel_norm = desired_vel/desired_speed;
267 float drag_decel = pilot_acceleration_max*desired_speed/gnd_speed_limit_cms;
270 float loiter_brake_accel = 0.0f;
277 loiter_brake_accel = 0.0f;
284 desired_speed =
MAX(desired_speed-(drag_decel+_brake_accel)*nav_dt,0.0f);
285 desired_vel = desired_vel_norm*desired_speed;
292 float horizSpdDem = desired_vel.
length();
293 if (horizSpdDem > gnd_speed_limit_cms) {
294 desired_vel.
x = desired_vel.
x * gnd_speed_limit_cms / horizSpdDem;
295 desired_vel.
y = desired_vel.
y * gnd_speed_limit_cms / horizSpdDem;
void get_stopping_point_xy(Vector3f &stopping_point) const
void set_desired_velocity_xy(float vel_lat_cms, float vel_lon_cms)
float get_lean_angle_max_cd() const
get_lean_angle_max_cd - returns the maximum lean angle the autopilot may request
void input_shaping_rate_predictor(Vector2f error_angle, Vector2f &target_ang_vel, float dt) const
virtual const Vector3f & get_position() const =0
#define LOITER_VEL_CORRECTION_MAX
void set_desired_accel_xy(float accel_lat_cms, float accel_lon_cms)
#define AP_GROUPINFO(name, idx, clazz, element, def)
#define LOITER_BRAKE_START_DELAY_DEFAULT
void update_xy_controller(float ekfNavVelGainScaler)
update_xy_controller - run the horizontal position controller - should be called at 100hz or higher ...
void set_leash_length_xy(float leash)
set the horizontal leash length
const AC_AttitudeControl & _attitude_control
void soften_for_landing()
reduce response for landing
void calc_desired_velocity(float nav_dt, float ekfGndSpdLimit)
Vector2f _predicted_accel
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
void sanity_check_params()
#define LOITER_SPEED_DEFAULT
float lean_angle_max() const
AC_Loiter(const AP_InertialNav &inav, const AP_AHRS_View &ahrs, AC_PosControl &pos_control, const AC_AttitudeControl &attitude_control)
Constructor.
void update(float ekfGndSpdLimit, float ekfNavVelGainScaler)
run the loiter controller
void get_stopping_point_xy(Vector3f &stopping_point) const
get vector to stopping point based on a horizontal position and velocity
float wrap_PI(const T radian)
static const struct AP_Param::GroupInfo var_info[]
const AP_InertialNav & _inav
#define LOITER_BRAKE_JERK_DEFAULT
const AP_AHRS_View & _ahrs
bool is_zero(const T fVal1)
Vector2f _predicted_euler_rate
void init_xy_controller(bool reset_I=true)
AC_PID_2D & get_vel_xy_pid()
static float sqrt_controller(float error, float p, float second_ord_lim, float dt)
#define LOITER_POS_CORRECTION_MAX
#define LOITER_BRAKE_ACCEL_DEFAULT
Vector2f _predicted_euler_angle
AP_Float _brake_jerk_max_cmsss
const Vector3f & get_desired_velocity()
get_desired_velocity - returns xy desired velocity (i.e. feed forward) in cm/s in lat and lon directi...
void init_target()
initialize's position and feed-forward velocity from current pos and velocity
float constrain_float(const float amt, const float low, const float high)
#define LOITER_ACCEL_MAX_DEFAULT
static constexpr float radians(float deg)
void set_accel_xy(float accel_cmss)
set_accel_xy - set horizontal acceleration in cm/s/s
AP_Float _brake_accel_cmss
Vector3f get_att_target_euler_cd() const
AC_PosControl & _pos_control
void set_pilot_desired_acceleration(float euler_roll_angle_cd, float euler_pitch_angle_cd, float dt)
set pilot desired acceleration in centi-degrees
float time_since_last_xy_update() const
virtual const Vector3f & get_velocity() const =0
void adjust_velocity(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt)
void set_speed_xy(float speed_cms)
set_speed_xy - set horizontal speed maximum in cm/s
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
float get_angle_max_cd() const
get maximum lean angle when using loiter