9 #define AR_ATTCONTROL_STEER_ANG_P 2.50f 10 #define AR_ATTCONTROL_STEER_RATE_FF 0.20f 11 #define AR_ATTCONTROL_STEER_RATE_P 0.20f 12 #define AR_ATTCONTROL_STEER_RATE_I 0.20f 13 #define AR_ATTCONTROL_STEER_RATE_IMAX 1.00f 14 #define AR_ATTCONTROL_STEER_RATE_D 0.00f 15 #define AR_ATTCONTROL_STEER_RATE_FILT 10.00f 16 #define AR_ATTCONTROL_STEER_RATE_MAX 360.0f 17 #define AR_ATTCONTROL_STEER_ACCEL_MAX 180.0f 18 #define AR_ATTCONTROL_THR_SPEED_P 0.20f 19 #define AR_ATTCONTROL_THR_SPEED_I 0.20f 20 #define AR_ATTCONTROL_THR_SPEED_IMAX 1.00f 21 #define AR_ATTCONTROL_THR_SPEED_D 0.00f 22 #define AR_ATTCONTROL_THR_SPEED_FILT 10.00f 23 #define AR_ATTCONTROL_DT 0.02f 24 #define AR_ATTCONTROL_TIMEOUT_MS 200 27 #define AR_ATTCONTROL_THR_ACCEL_MAX 2.00f 30 #define AR_ATTCONTROL_STEER_SPEED_MIN 1.0f 33 #define AR_ATTCONTROL_STOP_SPEED_DEFAULT 0.1f 51 float get_steering_out_heading(
float heading_rad,
float rate_max,
bool motor_limit_left,
bool motor_limit_right,
float dt);
55 float get_steering_out_rate(
float desired_rate,
bool motor_limit_left,
bool motor_limit_right,
float dt);
79 float get_throttle_out_speed(
float desired_speed,
bool motor_limit_low,
bool motor_limit_high,
float cruise_speed,
float cruise_throttle,
float dt);
82 float get_throttle_out_stop(
bool motor_limit_low,
bool motor_limit_high,
float cruise_speed,
float cruise_throttle,
float dt,
bool &stopped);
float get_steering_out_lat_accel(float desired_accel, bool motor_limit_left, bool motor_limit_right, float dt)
Generic PID algorithm, with EEPROM-backed storage of constants.
bool speed_control_active() const
float get_desired_turn_rate() const
AP_Float _throttle_accel_max
uint32_t _steer_lat_accel_last_ms
float get_throttle_out_stop(bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt, bool &stopped)
AR_AttitudeControl(AP_AHRS &ahrs)
float get_stopping_distance(float speed) const
bool get_forward_speed(float &speed) const
float get_steering_out_heading(float heading_rad, float rate_max, bool motor_limit_left, bool motor_limit_right, float dt)
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
AC_PID & get_steering_rate_pid()
float get_desired_lat_accel() const
Object managing one P controller.
float get_throttle_out_speed(float desired_speed, bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt)
float get_accel_max() const
void set_throttle_limits(float throttle_accel_max, float throttle_decel_max)
uint32_t _steer_turn_last_ms
float get_desired_speed() const
AC_PID _throttle_speed_pid
Common definitions and utility routines for the ArduPilot libraries.
float get_decel_max() const
bool get_lat_accel(float &lat_accel) const
AP_Float _steer_accel_max
AC_P & get_steering_angle_p()
float get_steering_out_rate(float desired_rate, bool motor_limit_left, bool motor_limit_right, float dt)
Copter PID control class.
bool _throttle_limit_high
AC_PID & get_throttle_speed_pid()
float get_desired_speed_accel_limited(float desired_speed, float dt) const
AP_Float _throttle_decel_max
static const struct AP_Param::GroupInfo var_info[]