123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699 |
- #include <AP_Math/AP_Math.h>
- #include <AP_HAL/AP_HAL.h>
- #include "AR_AttitudeControl.h"
- #include <AP_GPS/AP_GPS.h>
- extern const AP_HAL::HAL& hal;
- const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_SUBGROUPINFO(_steer_rate_pid, "_STR_RAT_", 1, AR_AttitudeControl, AC_PID),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_SUBGROUPINFO(_throttle_speed_pid, "_SPEED_", 2, AR_AttitudeControl, AC_PID),
-
-
-
-
-
-
-
- AP_GROUPINFO("_ACCEL_MAX", 3, AR_AttitudeControl, _throttle_accel_max, AR_ATTCONTROL_THR_ACCEL_MAX),
-
-
-
-
-
- AP_GROUPINFO("_BRAKE", 4, AR_AttitudeControl, _brake_enable, 1),
-
-
-
-
-
-
-
- AP_GROUPINFO("_STOP_SPEED", 5, AR_AttitudeControl, _stop_speed, AR_ATTCONTROL_STOP_SPEED_DEFAULT),
-
-
-
-
-
-
- AP_SUBGROUPINFO(_steer_angle_p, "_STR_ANG_", 6, AR_AttitudeControl, AC_P),
-
-
-
-
-
-
-
- AP_GROUPINFO("_STR_ACC_MAX", 7, AR_AttitudeControl, _steer_accel_max, AR_ATTCONTROL_STEER_ACCEL_MAX),
-
-
-
-
-
-
-
- AP_GROUPINFO("_STR_RAT_MAX", 8, AR_AttitudeControl, _steer_rate_max, AR_ATTCONTROL_STEER_RATE_MAX),
-
-
-
-
-
-
-
- AP_GROUPINFO("_DECEL_MAX", 9, AR_AttitudeControl, _throttle_decel_max, 0.00f),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_SUBGROUPINFO(_pitch_to_throttle_pid, "_BAL_", 10, AR_AttitudeControl, AC_PID),
-
-
-
-
-
-
- AP_GROUPINFO("_BAL_SPD_FF", 11, AR_AttitudeControl, _pitch_to_throttle_speed_ff, AR_ATTCONTROL_BAL_SPEED_FF),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_SUBGROUPINFO(_sailboat_heel_pid, "_SAIL_", 12, AR_AttitudeControl, AC_PID),
- AP_GROUPEND
- };
- AR_AttitudeControl::AR_AttitudeControl(AP_AHRS &ahrs) :
- _ahrs(ahrs),
- _steer_angle_p(AR_ATTCONTROL_STEER_ANG_P),
- _steer_rate_pid(AR_ATTCONTROL_STEER_RATE_P, AR_ATTCONTROL_STEER_RATE_I, AR_ATTCONTROL_STEER_RATE_D, AR_ATTCONTROL_STEER_RATE_FF, AR_ATTCONTROL_STEER_RATE_IMAX, 0.0f, AR_ATTCONTROL_STEER_RATE_FILT, 0.0f, AR_ATTCONTROL_DT),
- _throttle_speed_pid(AR_ATTCONTROL_THR_SPEED_P, AR_ATTCONTROL_THR_SPEED_I, AR_ATTCONTROL_THR_SPEED_D, 0.0f, AR_ATTCONTROL_THR_SPEED_IMAX, 0.0f, AR_ATTCONTROL_THR_SPEED_FILT, 0.0f, AR_ATTCONTROL_DT),
- _pitch_to_throttle_pid(AR_ATTCONTROL_PITCH_THR_P, AR_ATTCONTROL_PITCH_THR_I, AR_ATTCONTROL_PITCH_THR_D, 0.0f, AR_ATTCONTROL_PITCH_THR_IMAX, 0.0f, AR_ATTCONTROL_PITCH_THR_FILT, 0.0f, AR_ATTCONTROL_DT),
- _sailboat_heel_pid(AR_ATTCONTROL_HEEL_SAIL_P, AR_ATTCONTROL_HEEL_SAIL_I, AR_ATTCONTROL_HEEL_SAIL_D, 0.0f, AR_ATTCONTROL_HEEL_SAIL_IMAX, 0.0f, AR_ATTCONTROL_HEEL_SAIL_FILT, 0.0f, AR_ATTCONTROL_DT)
- {
- AP_Param::setup_object_defaults(this, var_info);
- }
- float AR_AttitudeControl::get_steering_out_lat_accel(float desired_accel, bool motor_limit_left, bool motor_limit_right, float dt)
- {
-
- _steer_lat_accel_last_ms = AP_HAL::millis();
- _desired_lat_accel = desired_accel;
-
- float speed;
- if (!get_forward_speed(speed)) {
-
-
- return 0.0f;
- }
- const float desired_rate = get_turn_rate_from_lat_accel(desired_accel, speed);
- return get_steering_out_rate(desired_rate, motor_limit_left, motor_limit_right, dt);
- }
- float AR_AttitudeControl::get_steering_out_heading(float heading_rad, float rate_max_rads, bool motor_limit_left, bool motor_limit_right, float dt)
- {
-
- float desired_rate = get_turn_rate_from_heading(heading_rad, rate_max_rads);
- return get_steering_out_rate(desired_rate, motor_limit_left, motor_limit_right, dt);
- }
- float AR_AttitudeControl::get_turn_rate_from_heading(float heading_rad, float rate_max_rads) const
- {
- const float yaw_error = wrap_PI(heading_rad - _ahrs.yaw);
-
- float desired_rate = _steer_angle_p.get_p(yaw_error);
-
- if (is_positive(rate_max_rads)) {
- desired_rate = constrain_float(desired_rate, -rate_max_rads, rate_max_rads);
- }
- return desired_rate;
- }
- float AR_AttitudeControl::get_steering_out_rate(float desired_rate, bool motor_limit_left, bool motor_limit_right, float dt)
- {
-
- dt = constrain_float(dt, 0.0f, 1.0f);
-
- const uint32_t now = AP_HAL::millis();
- if ((_steer_turn_last_ms == 0) || ((now - _steer_turn_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
- _steer_rate_pid.reset_filter();
- _steer_rate_pid.reset_I();
- _desired_turn_rate = _ahrs.get_yaw_rate_earth();
- }
- _steer_turn_last_ms = now;
-
- if (is_positive(_steer_accel_max)) {
- const float change_max = radians(_steer_accel_max) * dt;
- desired_rate = constrain_float(desired_rate, _desired_turn_rate - change_max, _desired_turn_rate + change_max);
- }
- _desired_turn_rate = desired_rate;
-
- if (is_positive(_steer_rate_max)) {
- const float steer_rate_max_rad = radians(_steer_rate_max);
- _desired_turn_rate = constrain_float(_desired_turn_rate, -steer_rate_max_rad, steer_rate_max_rad);
- }
-
- _steer_rate_pid.set_dt(dt);
- float output = _steer_rate_pid.update_all(_desired_turn_rate, _ahrs.get_yaw_rate_earth(), (motor_limit_left || motor_limit_right));
- output += _steer_rate_pid.get_ff();
-
- return output;
- }
- float AR_AttitudeControl::get_desired_turn_rate() const
- {
-
- if ((_steer_turn_last_ms == 0) || ((AP_HAL::millis() - _steer_turn_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
- return 0.0f;
- }
- return _desired_turn_rate;
- }
- float AR_AttitudeControl::get_desired_lat_accel() const
- {
-
- if ((_steer_lat_accel_last_ms == 0) || ((AP_HAL::millis() - _steer_lat_accel_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
- return 0.0f;
- }
- return _desired_lat_accel;
- }
- bool AR_AttitudeControl::get_lat_accel(float &lat_accel) const
- {
- float speed;
- if (!get_forward_speed(speed)) {
- return false;
- }
- lat_accel = speed * _ahrs.get_yaw_rate_earth();
- return true;
- }
- float AR_AttitudeControl::get_turn_rate_from_lat_accel(float lat_accel, float speed) const
- {
-
- if (fabsf(speed) < AR_ATTCONTROL_STEER_SPEED_MIN) {
- if (is_negative(speed)) {
- speed = -AR_ATTCONTROL_STEER_SPEED_MIN;
- } else {
- speed = AR_ATTCONTROL_STEER_SPEED_MIN;
- }
- }
- return lat_accel / speed;
- }
- float AR_AttitudeControl::get_throttle_out_speed(float desired_speed, bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt)
- {
-
- dt = constrain_float(dt, 0.0f, 1.0f);
-
- float speed;
- if (!get_forward_speed(speed)) {
-
-
- return 0.0f;
- }
-
- if (!speed_control_active()) {
- _throttle_speed_pid.reset_filter();
- _throttle_speed_pid.reset_I();
- _desired_speed = speed;
- }
- _speed_last_ms = AP_HAL::millis();
-
- _desired_speed = get_desired_speed_accel_limited(desired_speed, dt);
-
- _throttle_speed_pid.set_dt(dt);
-
- float throttle_base = 0.0f;
- if (is_positive(cruise_speed) && is_positive(cruise_throttle)) {
- throttle_base = desired_speed * (cruise_throttle / cruise_speed);
- }
-
- float throttle_out = _throttle_speed_pid.update_all(desired_speed, speed, (_throttle_limit_low || _throttle_limit_high));
- throttle_out += _throttle_speed_pid.get_ff();
- throttle_out += throttle_base;
-
- _throttle_limit_low = false;
- _throttle_limit_high = false;
-
- if (!_brake_enable) {
-
- if ((desired_speed >= 0.0f) && (throttle_out <= 0.0f)) {
- throttle_out = 0.0f;
- _throttle_limit_low = true;
- } else if ((desired_speed <= 0.0f) && (throttle_out >= 0.0f)) {
- throttle_out = 0.0f;
- _throttle_limit_high = true;
- }
- }
-
- return throttle_out;
- }
- float AR_AttitudeControl::get_throttle_out_stop(bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt, bool &stopped)
- {
-
- const uint32_t now = AP_HAL::millis();
-
- bool _stopped = (_stop_last_ms != 0) && (now - _stop_last_ms) < 300;
-
- float desired_speed_limited = get_desired_speed_accel_limited(0.0f, dt);
-
- float speed;
- if (!get_forward_speed(speed)) {
-
- _stopped = true;
- } else {
-
- if (is_zero(desired_speed_limited) && fabsf(speed) <= fabsf(_stop_speed)) {
- _stopped = true;
- }
- }
-
- stopped = _stopped;
-
- if (stopped) {
-
- _stop_last_ms = now;
-
- _speed_last_ms = now;
- return 0.0f;
- }
-
- _stop_last_ms = 0;
-
- return get_throttle_out_speed(desired_speed_limited, motor_limit_low, motor_limit_high, cruise_speed, cruise_throttle, dt);
- }
- float AR_AttitudeControl::get_throttle_out_from_pitch(float desired_pitch, float vehicle_speed_pct, bool motor_limit_low, bool motor_limit_high, float dt)
- {
-
- dt = constrain_float(dt, 0.0f, 1.0f);
-
- const uint32_t now = AP_HAL::millis();
- if ((_balance_last_ms == 0) || ((now - _balance_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
- _pitch_to_throttle_pid.reset_filter();
- _pitch_to_throttle_pid.reset_I();
- }
- _balance_last_ms = now;
-
- _pitch_to_throttle_pid.set_dt(dt);
-
- float output = vehicle_speed_pct * 0.01f * _pitch_to_throttle_speed_ff;
- output += _pitch_to_throttle_pid.update_all(desired_pitch, _ahrs.pitch, (motor_limit_low || motor_limit_high));
- output += _pitch_to_throttle_pid.get_ff();
-
- return output;
- }
- float AR_AttitudeControl::get_desired_pitch() const
- {
-
- if ((_balance_last_ms == 0) || ((AP_HAL::millis() - _balance_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
- return 0.0f;
- }
- return _pitch_to_throttle_pid.get_pid_info().target;
- }
- float AR_AttitudeControl::get_sail_out_from_heel(float desired_heel, float dt)
- {
-
- dt = constrain_float(dt, 0.0f, 1.0f);
-
- const uint32_t now = AP_HAL::millis();
- if ((_heel_controller_last_ms == 0) || ((now - _heel_controller_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
- _sailboat_heel_pid.reset_filter();
- _sailboat_heel_pid.reset_I();
- }
- _heel_controller_last_ms = now;
-
- _sailboat_heel_pid.set_dt(dt);
- _sailboat_heel_pid.update_all(desired_heel, fabsf(_ahrs.roll));
-
- const float ff = _sailboat_heel_pid.get_ff();
-
- float p = _sailboat_heel_pid.get_p();
- if (is_positive(p)) {
- p = 0.0f;
- }
-
- float i = _sailboat_heel_pid.get_i();
- if (is_positive(i)) {
- i = 0.0f;
- _sailboat_heel_pid.reset_I();
- }
-
- const float d = _sailboat_heel_pid.get_d();
-
- return (ff + p + i + d) * -1.0f;
- }
- bool AR_AttitudeControl::get_forward_speed(float &speed) const
- {
- Vector3f velocity;
- if (!_ahrs.get_velocity_NED(velocity)) {
-
- if (AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D) {
- if (fabsf(wrap_180_cd(_ahrs.yaw_sensor - AP::gps().ground_course_cd())) <= 9000) {
- speed = AP::gps().ground_speed();
- } else {
- speed = -AP::gps().ground_speed();
- }
- return true;
- } else {
- return false;
- }
- }
-
- speed = velocity.x*_ahrs.cos_yaw() + velocity.y*_ahrs.sin_yaw();
- return true;
- }
- float AR_AttitudeControl::get_decel_max() const
- {
- if (is_positive(_throttle_decel_max)) {
- return _throttle_decel_max;
- } else {
- return _throttle_accel_max;
- }
- }
- bool AR_AttitudeControl::speed_control_active() const
- {
-
- if ((_speed_last_ms == 0) || ((AP_HAL::millis() - _speed_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
- return false;
- }
- return true;
- }
- float AR_AttitudeControl::get_desired_speed() const
- {
-
- if (!speed_control_active()) {
- return 0.0f;
- }
- return _desired_speed;
- }
- float AR_AttitudeControl::get_desired_speed_accel_limited(float desired_speed, float dt) const
- {
-
-
- if (!speed_control_active() || !is_positive(_throttle_accel_max)) {
- return desired_speed;
- }
-
- dt = constrain_float(dt, 0.0f, 1.0f);
-
- float speed_prev = _desired_speed;
-
- if (!speed_control_active()) {
- get_forward_speed(speed_prev);
- }
-
- float speed_change_max;
- if (fabsf(desired_speed) < fabsf(_desired_speed) && is_positive(_throttle_decel_max)) {
- speed_change_max = _throttle_decel_max * dt;
- } else {
- speed_change_max = _throttle_accel_max * dt;
- }
- return constrain_float(desired_speed, speed_prev - speed_change_max, speed_prev + speed_change_max);
- }
- float AR_AttitudeControl::get_stopping_distance(float speed) const
- {
-
- const float accel_max = get_accel_max();
-
- if ((accel_max <= 0.0f) || is_zero(speed)) {
- return 0.0f;
- }
-
- return 0.5f * sq(speed) / accel_max;
- }
- void AR_AttitudeControl::relax_I()
- {
- _steer_rate_pid.reset_I();
- _throttle_speed_pid.reset_I();
- _pitch_to_throttle_pid.reset_I();
- }
|