209 const float desired_rate = desired_accel / speed;
352 const float speed_error = desired_speed - speed;
374 float throttle_base = 0.0f;
376 throttle_base = desired_speed * (cruise_throttle / cruise_speed);
380 float throttle_out = (ff+p+i+d+throttle_base);
389 if ((desired_speed >= 0.0
f) && (throttle_out <= 0.0f)) {
393 if ((desired_speed <= 0.0
f) && (throttle_out >= 0.0f)) {
439 return get_throttle_out_speed(desired_speed_limited, motor_limit_low, motor_limit_high, cruise_speed, cruise_throttle, dt);
509 float speed_change_max;
515 return constrain_float(desired_speed, speed_prev - speed_change_max, speed_prev + speed_change_max);
525 if ((accel_max <= 0.0
f) ||
is_zero(speed)) {
530 return 0.5f *
sq(speed) / accel_max;
float get_steering_out_lat_accel(float desired_accel, bool motor_limit_left, bool motor_limit_right, float dt)
virtual bool get_velocity_NED(Vector3f &vec) const
#define AR_ATTCONTROL_THR_ACCEL_MAX
bool speed_control_active() const
float get_desired_turn_rate() const
AP_Float _throttle_accel_max
#define AR_ATTCONTROL_THR_SPEED_IMAX
#define AR_ATTCONTROL_THR_SPEED_D
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)
#define AP_GROUPINFO(name, idx, clazz, element, def)
#define AR_ATTCONTROL_STEER_RATE_D
AR_AttitudeControl(AP_AHRS &ahrs)
float get_yaw_rate_earth(void) const
bool is_positive(const T fVal1)
auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f))
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)
int32_t ground_course_cd(uint8_t instance) const
#define AR_ATTCONTROL_STEER_RATE_FILT
#define AR_ATTCONTROL_STEER_RATE_MAX
float get_desired_lat_accel() const
Object managing one P controller.
#define AR_ATTCONTROL_STEER_RATE_FF
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 wrap_PI(const T radian)
#define AR_ATTCONTROL_THR_SPEED_I
float ground_speed(uint8_t instance) const
float get_accel_max() const
bool is_zero(const T fVal1)
uint32_t _steer_turn_last_ms
float get_ff(float requested_rate)
float get_desired_speed() const
#define AR_ATTCONTROL_STEER_ANG_P
#define AR_ATTCONTROL_STEER_RATE_IMAX
#define AR_ATTCONTROL_STEER_SPEED_MIN
GPS_Status status(uint8_t instance) const
Query GPS status.
#define AR_ATTCONTROL_STOP_SPEED_DEFAULT
AC_PID _throttle_speed_pid
void set_desired_rate(float desired)
float constrain_float(const float amt, const float low, const float high)
float get_decel_max() const
#define AR_ATTCONTROL_STEER_ACCEL_MAX
bool get_lat_accel(float &lat_accel) const
static constexpr float radians(float deg)
AP_Float _steer_accel_max
#define AR_ATTCONTROL_TIMEOUT_MS
void set_input_filter_all(float input)
#define AR_ATTCONTROL_STEER_RATE_P
float get_steering_out_rate(float desired_rate, bool motor_limit_left, bool motor_limit_right, float dt)
bool is_negative(const T fVal1)
#define AR_ATTCONTROL_THR_SPEED_FILT
float get_p(float error) const
Receiving valid messages and 3D lock.
float get_integrator() const
Copter PID control class.
bool _throttle_limit_high
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
float get_desired_speed_accel_limited(float desired_speed, float dt) const
#define AR_ATTCONTROL_STEER_RATE_I
AP_Float _throttle_decel_max
static const struct AP_Param::GroupInfo var_info[]
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define AR_ATTCONTROL_THR_SPEED_P
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)