12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541 |
- #include <AP_HAL/AP_HAL.h>
- #include "AC_PosControl.h"
- #include <AP_Math/AP_Math.h>
- #include <AP_Logger/AP_Logger.h>
- #include "../../ArduSub/Sub.h"
- extern const AP_HAL::HAL& hal;
- #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
-
- # define POSCONTROL_POS_Z_P 1.0f
- # define POSCONTROL_VEL_Z_P 5.0f
- # define POSCONTROL_ACC_Z_P 0.3f
- # define POSCONTROL_ACC_Z_I 1.0f
- # define POSCONTROL_ACC_Z_D 0.0f
- # define POSCONTROL_ACC_Z_IMAX 800
- # define POSCONTROL_ACC_Z_FILT_HZ 10.0f
- # define POSCONTROL_ACC_Z_DT 0.02f
- # define POSCONTROL_POS_XY_P 1.0f
- # define POSCONTROL_VEL_XY_P 1.4f
- # define POSCONTROL_VEL_XY_I 0.7f
- # define POSCONTROL_VEL_XY_D 0.35f
- # define POSCONTROL_VEL_XY_IMAX 1000.0f
- # define POSCONTROL_VEL_XY_FILT_HZ 5.0f
- # define POSCONTROL_VEL_XY_FILT_D_HZ 5.0f
- #elif APM_BUILD_TYPE(APM_BUILD_ArduSub)
-
- # define POSCONTROL_POS_Z_P 3.0f
- # define POSCONTROL_VEL_Z_P 8.0f
- # define POSCONTROL_ACC_Z_P 0.5f
- # define POSCONTROL_ACC_Z_I 0.1f
- # define POSCONTROL_ACC_Z_D 0.0f
- # define POSCONTROL_ACC_Z_IMAX 100
- # define POSCONTROL_ACC_Z_FILT_HZ 20.0f
- # define POSCONTROL_ACC_Z_DT 0.0025f
- # define POSCONTROL_POS_XY_P 1.0f
- # define POSCONTROL_VEL_XY_P 1.0f
- # define POSCONTROL_VEL_XY_I 0.5f
- # define POSCONTROL_VEL_XY_D 0.0f
- # define POSCONTROL_VEL_XY_IMAX 1000.0f
- # define POSCONTROL_VEL_XY_FILT_HZ 5.0f
- # define POSCONTROL_VEL_XY_FILT_D_HZ 5.0f
- #else
-
- # define POSCONTROL_POS_Z_P 1.0f
- # define POSCONTROL_VEL_Z_P 5.0f
- # define POSCONTROL_ACC_Z_P 0.5f
- # define POSCONTROL_ACC_Z_I 1.0f
- # define POSCONTROL_ACC_Z_D 0.0f
- # define POSCONTROL_ACC_Z_IMAX 800
- # define POSCONTROL_ACC_Z_FILT_HZ 20.0f
- # define POSCONTROL_ACC_Z_DT 0.0025f
- # define POSCONTROL_POS_XY_P 1.0f
- # define POSCONTROL_VEL_XY_P 2.0f
- # define POSCONTROL_VEL_XY_I 1.0f
- # define POSCONTROL_VEL_XY_D 0.5f
- # define POSCONTROL_VEL_XY_IMAX 1000.0f
- # define POSCONTROL_VEL_XY_FILT_HZ 5.0f
- # define POSCONTROL_VEL_XY_FILT_D_HZ 5.0f
- #endif
- const AP_Param::GroupInfo AC_PosControl::var_info[] = {
-
-
-
-
-
-
-
-
- AP_GROUPINFO("_ACC_XY_FILT", 1, AC_PosControl, _accel_xy_filt_hz, POSCONTROL_ACCEL_FILTER_HZ),
-
-
-
-
-
- AP_SUBGROUPINFO(_p_pos_z, "_POSZ_", 2, AC_PosControl, AC_P),
-
-
-
-
-
- AP_SUBGROUPINFO(_p_vel_z, "_VELZ_", 3, AC_PosControl, AC_P),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_SUBGROUPINFO(_pid_accel_z, "_ACCZ_", 4, AC_PosControl, AC_PID),
-
-
-
-
-
- AP_SUBGROUPINFO(_p_pos_xy, "_POSXY_", 5, AC_PosControl, AC_P),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_SUBGROUPINFO(_pid_vel_xy, "_VELXY_", 6, AC_PosControl, AC_PID_2D),
-
-
-
-
-
-
-
- AP_GROUPINFO("_ANGLE_MAX", 7, AC_PosControl, _lean_angle_max, 0.0f),
- AP_GROUPEND
- };
- AC_PosControl::AC_PosControl(const AP_AHRS_View& ahrs, const AP_InertialNav& inav,
- const AP_Motors& motors, AC_AttitudeControl& attitude_control) :
- _ahrs(ahrs),
- _inav(inav),
- _motors(motors),
- _attitude_control(attitude_control),
- _p_pos_z(POSCONTROL_POS_Z_P),
- _p_vel_z(POSCONTROL_VEL_Z_P),
- _pid_accel_z(POSCONTROL_ACC_Z_P, POSCONTROL_ACC_Z_I, POSCONTROL_ACC_Z_D, 0.0f, POSCONTROL_ACC_Z_IMAX, 0.0f, POSCONTROL_ACC_Z_FILT_HZ, 0.0f, POSCONTROL_ACC_Z_DT),
- _p_pos_xy(POSCONTROL_POS_XY_P),
- _pid_vel_xy(POSCONTROL_VEL_XY_P, POSCONTROL_VEL_XY_I, POSCONTROL_VEL_XY_D, POSCONTROL_VEL_XY_IMAX, POSCONTROL_VEL_XY_FILT_HZ, POSCONTROL_VEL_XY_FILT_D_HZ, POSCONTROL_DT_50HZ),
- _dt(POSCONTROL_DT_400HZ),
- _speed_down_cms(POSCONTROL_SPEED_DOWN),
- _speed_up_cms(POSCONTROL_SPEED_UP),
- _speed_cms(POSCONTROL_SPEED),
- _accel_z_cms(POSCONTROL_ACCEL_Z),
- _accel_cms(POSCONTROL_ACCEL_XY),
- _leash(POSCONTROL_LEASH_LENGTH_MIN),
- _leash_down_z(POSCONTROL_LEASH_LENGTH_MIN),
- _leash_up_z(POSCONTROL_LEASH_LENGTH_MIN),
- _accel_target_filter(POSCONTROL_ACCEL_FILTER_HZ),
- alt_rate(10.0)
- {
- AP_Param::setup_object_defaults(this, var_info);
-
- _flags.recalc_leash_z = true;
- _flags.recalc_leash_xy = true;
- _flags.reset_desired_vel_to_pos = true;
- _flags.reset_accel_to_lean_xy = true;
- _flags.reset_rate_to_accel_z = true;
- _flags.freeze_ff_z = true;
- _flags.use_desvel_ff_z = true;
- _limit.pos_up = true;
- _limit.pos_down = true;
- _limit.vel_up = true;
- _limit.vel_down = true;
- _limit.accel_xy = true;
-
- }
- void AC_PosControl::set_dt(float delta_sec)
- {
- _dt = delta_sec;
-
- _pid_accel_z.set_dt(_dt);
- _pid_vel_xy.set_dt(_dt);
-
- _vel_error_filter.set_cutoff_frequency(POSCONTROL_VEL_ERROR_CUTOFF_FREQ);
- }
- void AC_PosControl::set_max_speed_z(float speed_down, float speed_up)
- {
-
- speed_down = -fabsf(speed_down);
- if ((fabsf(_speed_down_cms - speed_down) > 1.0f) || (fabsf(_speed_up_cms - speed_up) > 1.0f)) {
- _speed_down_cms = speed_down;
- _speed_up_cms = speed_up;
- _flags.recalc_leash_z = true;
- calc_leash_length_z();
- }
- }
- void AC_PosControl::set_max_accel_z(float accel_cmss)
- {
- if (fabsf(_accel_z_cms - accel_cmss) > 1.0f) {
- _accel_z_cms = accel_cmss;
- _flags.recalc_leash_z = true;
- calc_leash_length_z();
- }
- }
- void AC_PosControl::set_alt_target_with_slew(float alt_cm, float dt)
- {
- float alt_change = alt_cm - _pos_target.z;
-
- _flags.use_desvel_ff_z = false;
-
- if ((alt_change < 0 && !_motors.limit.throttle_lower) || (alt_change > 0 && !_motors.limit.throttle_upper)) {
- if (!is_zero(dt)) {
- float climb_rate_cms = constrain_float(alt_change / dt, _speed_down_cms, _speed_up_cms);
- _pos_target.z += climb_rate_cms * dt;
- _vel_desired.z = climb_rate_cms;
- }
- } else {
-
- _vel_desired.z = 0.0f;
- }
-
- float curr_alt = _inav.get_altitude();
- _pos_target.z = constrain_float(_pos_target.z, curr_alt - _leash_down_z, curr_alt + _leash_up_z);
- }
- void AC_PosControl::set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend)
- {
-
-
- if ((climb_rate_cms < 0 && (!_motors.limit.throttle_lower || force_descend)) || (climb_rate_cms > 0 && !_motors.limit.throttle_upper && !_limit.pos_up)) {
- _pos_target.z += climb_rate_cms * dt;
- }
-
-
- _flags.use_desvel_ff_z = false;
- _vel_desired.z = climb_rate_cms;
- }
- void AC_PosControl::set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend)
- {
-
- float accel_z_cms = _accel_z_cms;
- if (_vel_desired.z < _speed_down_cms && !is_zero(_speed_down_cms)) {
- accel_z_cms *= POSCONTROL_OVERSPEED_GAIN_Z * _vel_desired.z / _speed_down_cms;
- }
- if (_vel_desired.z > _speed_up_cms && !is_zero(_speed_up_cms)) {
- accel_z_cms *= POSCONTROL_OVERSPEED_GAIN_Z * _vel_desired.z / _speed_up_cms;
- }
- accel_z_cms = constrain_float(accel_z_cms, 0.0f, 750.0f);
-
- float jerk_z = accel_z_cms * POSCONTROL_JERK_RATIO;
- float accel_z_max = MIN(accel_z_cms, safe_sqrt(2.0f * fabsf(_vel_desired.z - climb_rate_cms) * jerk_z));
- _accel_last_z_cms += jerk_z * dt;
- _accel_last_z_cms = MIN(accel_z_max, _accel_last_z_cms);
- float vel_change_limit = _accel_last_z_cms * dt;
- _vel_desired.z = constrain_float(climb_rate_cms, _vel_desired.z - vel_change_limit, _vel_desired.z + vel_change_limit);
- _flags.use_desvel_ff_z = true;
-
-
- if ((_vel_desired.z < 0 && (!_motors.limit.throttle_lower || force_descend)) || (_vel_desired.z > 0 && !_motors.limit.throttle_upper && !_limit.pos_up)) {
- _pos_target.z += _vel_desired.z * dt;
- }
- }
- void AC_PosControl::add_takeoff_climb_rate(float climb_rate_cms, float dt)
- {
- _pos_target.z += climb_rate_cms * dt;
- }
- void AC_PosControl::shift_alt_target(float z_cm)
- {
- _pos_target.z += z_cm;
-
- if (!is_zero(z_cm)) {
- freeze_ff_z();
- }
- }
- void AC_PosControl::relax_alt_hold_controllers(float throttle_setting)
- {
- _pos_target.z = _inav.get_altitude();
- _vel_desired.z = 0.0f;
- _flags.use_desvel_ff_z = false;
- _vel_target.z = _inav.get_velocity_z();
- _vel_last.z = _inav.get_velocity_z();
- _accel_desired.z = 0.0f;
- _accel_last_z_cms = 0.0f;
- _flags.reset_rate_to_accel_z = true;
- _pid_accel_z.set_integrator((throttle_setting - _motors.get_throttle_hover()) * 1000.0f);
- _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
- _pid_accel_z.reset_filter();
- }
- float AC_PosControl::get_alt_error() const
- {
- return (_pos_target.z - _inav.get_altitude());
- }
- void AC_PosControl::set_target_to_stopping_point_z()
- {
-
- calc_leash_length_z();
- get_stopping_point_z(_pos_target);
- }
- void AC_PosControl::get_stopping_point_z(Vector3f& stopping_point) const
- {
- const float curr_pos_z = _inav.get_altitude();
- float curr_vel_z = _inav.get_velocity_z();
- float linear_distance;
- float linear_velocity;
-
- if (is_active_z()) {
- curr_vel_z += _vel_error.z;
- if (_flags.use_desvel_ff_z) {
- curr_vel_z -= _vel_desired.z;
- }
- }
-
- if (_p_pos_z.kP() <= 0.0f || _accel_z_cms <= 0.0f) {
- stopping_point.z = curr_pos_z;
- return;
- }
-
- linear_velocity = _accel_z_cms / _p_pos_z.kP();
- if (fabsf(curr_vel_z) < linear_velocity) {
-
- stopping_point.z = curr_pos_z + curr_vel_z / _p_pos_z.kP();
- } else {
- linear_distance = _accel_z_cms / (2.0f * _p_pos_z.kP() * _p_pos_z.kP());
- if (curr_vel_z > 0) {
- stopping_point.z = curr_pos_z + (linear_distance + curr_vel_z * curr_vel_z / (2.0f * _accel_z_cms));
- } else {
- stopping_point.z = curr_pos_z - (linear_distance + curr_vel_z * curr_vel_z / (2.0f * _accel_z_cms));
- }
- }
- stopping_point.z = constrain_float(stopping_point.z, curr_pos_z - POSCONTROL_STOPPING_DIST_DOWN_MAX, curr_pos_z + POSCONTROL_STOPPING_DIST_UP_MAX);
- }
- void AC_PosControl::init_takeoff()
- {
- const Vector3f& curr_pos = _inav.get_position();
- _pos_target.z = curr_pos.z;
-
- freeze_ff_z();
-
- _pid_accel_z.set_integrator((_attitude_control.get_throttle_in() - _motors.get_throttle_hover()) * 1000.0f);
-
- init_ekf_z_reset();
- }
- bool AC_PosControl::is_active_z() const
- {
- return ((AP_HAL::micros64() - _last_update_z_us) <= POSCONTROL_ACTIVE_TIMEOUT_US);
- }
- void AC_PosControl::update_z_controller()
- {
-
- const uint64_t now_us = AP_HAL::micros64();
- if (now_us - _last_update_z_us > POSCONTROL_ACTIVE_TIMEOUT_US) {
- _flags.reset_rate_to_accel_z = true;
- _pid_accel_z.set_integrator((_attitude_control.get_throttle_in() - _motors.get_throttle_hover()) * 1000.0f);
- _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
- _pid_accel_z.reset_filter();
- }
- _last_update_z_us = now_us;
-
-
-
- calc_leash_length_z();
-
- run_z_controller();
- }
- float AC_PosControl::update_z_controller_f()
- {
-
- const uint64_t now_us = AP_HAL::micros64();
- if (now_us - _last_update_z_us > POSCONTROL_ACTIVE_TIMEOUT_US) {
- _flags.reset_rate_to_accel_z = true;
- _pid_accel_z.set_integrator((_attitude_control.get_throttle_in() - _motors.get_throttle_hover()) * 1000.0f);
- _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
- _pid_accel_z.reset_filter();
- }
- _last_update_z_us = now_us;
-
-
-
- calc_leash_length_z();
-
- return run_z_controller_f();
- }
- void AC_PosControl::calc_leash_length_z()
- {
- if (_flags.recalc_leash_z) {
- _leash_up_z = calc_leash_length(_speed_up_cms, _accel_z_cms, _p_pos_z.kP());
- _leash_down_z = calc_leash_length(-_speed_down_cms, _accel_z_cms, _p_pos_z.kP());
- _flags.recalc_leash_z = false;
- }
- }
- void AC_PosControl::run_z_controller()
- {
-
- float curr_alt = sub.barometer.get_altitude()*100;
-
-
-
- _limit.pos_up = false;
- _limit.pos_down = false;
-
- _pos_error.z = _pos_target.z - curr_alt;
-
- if (_pos_error.z > _leash_up_z) {
- _pos_target.z = curr_alt + _leash_up_z;
- _pos_error.z = _leash_up_z;
- _limit.pos_up = true;
- }
- if (_pos_error.z < -_leash_down_z) {
- _pos_target.z = curr_alt - _leash_down_z;
- _pos_error.z = -_leash_down_z;
- _limit.pos_down = true;
- }
-
- _vel_target.z = AC_AttitudeControl::sqrt_controller(_pos_error.z, _p_pos_z.kP(), _accel_z_cms, _dt);
-
-
- _limit.vel_up = false;
- _limit.vel_down = false;
- if (_vel_target.z < _speed_down_cms) {
- _vel_target.z = _speed_down_cms;
- _limit.vel_down = true;
- }
- if (_vel_target.z > _speed_up_cms) {
- _vel_target.z = _speed_up_cms;
- _limit.vel_up = true;
- }
-
- if (_flags.use_desvel_ff_z) {
- _vel_target.z += _vel_desired.z;
- }
-
-
-
-
- Vector3f curr_vel;
-
- curr_vel.z=alt_rate.get();
-
-
- if (_flags.reset_rate_to_accel_z) {
- _vel_last.z = _vel_target.z;
- }
-
- if (_dt > 0.0f) {
- if (!_flags.freeze_ff_z) {
- _accel_desired.z = (_vel_target.z - _vel_last.z) / _dt;
- } else {
-
- _flags.freeze_ff_z = false;
- }
- } else {
- _accel_desired.z = 0.0f;
- }
-
- _vel_last.z = _vel_target.z;
-
- if (_flags.reset_rate_to_accel_z) {
-
- _vel_error.z = 0;
- _vel_error_filter.reset(0);
- _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
- _flags.reset_rate_to_accel_z = false;
- } else {
-
- _vel_error.z = _vel_error_filter.apply(_vel_target.z - curr_vel.z, _dt);
- _accel_target.z = _p_vel_z.get_p(_vel_error.z);
- }
-
- _accel_target.z += _accel_desired.z;
-
- float z_accel_meas;
-
- z_accel_meas = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
-
- if (_motors.get_throttle_hover() * 1000.0f > _pid_accel_z.imax()) {
- _pid_accel_z.imax(_motors.get_throttle_hover() * 1000.0f);
- }
-
- float thr_out = _pid_accel_z.update_all(_accel_target.z, z_accel_meas, (_motors.limit.throttle_lower || _motors.limit.throttle_upper)) * 0.001f +0.5;
-
- _attitude_control.set_throttle_out(thr_out, true, POSCONTROL_THROTTLE_CUTOFF_FREQ);
- static uint8_t cnt = 0;
- cnt++;
- if (cnt>250)
- {
- cnt = 0;
-
-
-
- gcs().send_text(MAV_SEVERITY_INFO, " pid %f %f %f %f\n",_accel_target.z,z_accel_meas,_accel_desired.z,thr_out);
- }
- }
- float AC_PosControl::run_z_controller_wangdan(float _vel)
- {
- const uint64_t now_us = AP_HAL::micros64();
- if (now_us - _last_update_z_us > POSCONTROL_ACTIVE_TIMEOUT_US) {
- _flags.reset_rate_to_accel_z = true;
- _pid_accel_z.set_integrator((_attitude_control.get_throttle_in() - _motors.get_throttle_hover()) * 1000.0f);
- _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
- _pid_accel_z.reset_filter();
- }
- _last_update_z_us = now_us;
-
- _vel_target.z = _vel;
-
- if (_flags.use_desvel_ff_z) {
- _vel_target.z += _vel_desired.z;
- }
-
-
-
-
- Vector3f curr_vel;
-
- curr_vel.z=alt_rate.get();
-
-
- if (_flags.reset_rate_to_accel_z) {
- _vel_last.z = _vel_target.z;
- }
-
- if (_dt > 0.0f) {
- if (!_flags.freeze_ff_z) {
- _accel_desired.z = (_vel_target.z - _vel_last.z) / _dt;
- } else {
-
- _flags.freeze_ff_z = false;
- }
- } else {
- _accel_desired.z = 0.0f;
- }
-
- _vel_last.z = _vel_target.z;
-
- if (_flags.reset_rate_to_accel_z) {
-
- _vel_error.z = 0;
- _vel_error_filter.reset(0);
- _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
- _flags.reset_rate_to_accel_z = false;
- } else {
-
- _vel_error.z = _vel_error_filter.apply(_vel_target.z - curr_vel.z, _dt);
- _accel_target.z = _p_vel_z.get_p(_vel_error.z);
- }
-
- _accel_target.z += _accel_desired.z;
-
- float z_accel_meas;
-
- z_accel_meas = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
-
- if (_motors.get_throttle_hover() * 1000.0f > _pid_accel_z.imax()) {
- _pid_accel_z.imax(_motors.get_throttle_hover() * 1000.0f);
- }
-
- float thr_out = _pid_accel_z.update_all(_accel_target.z, z_accel_meas, (_motors.limit.throttle_lower || _motors.limit.throttle_upper)) * 0.001f;
-
-
- static uint8_t cnt = 0;
- cnt++;
- if (cnt>250)
- {
- cnt = 0;
-
-
-
- gcs().send_text(MAV_SEVERITY_INFO, " pid %f %f %f %f\n",_vel_target.z,curr_vel.z,_accel_target.z,thr_out);
- }
- return thr_out;
- }
- void AC_PosControl::calculate_rate(float dt){
- LowPassFilterFloat curr_alt(10.0);
- curr_alt.apply(sub.barometer.get_altitude()*100,dt);
- alt_rate.apply((curr_alt.get()-last_alt)/dt,dt);
- last_alt = curr_alt.get();
-
- }
- float AC_PosControl::run_z_controller_f()
- {
-
-
- float curr_alt = sub.barometer.get_altitude()*100;
-
- _limit.pos_up = false;
- _limit.pos_down = false;
-
- _pos_error.z = _pos_target.z - curr_alt;
-
- if (_pos_error.z > _leash_up_z) {
- _pos_target.z = curr_alt + _leash_up_z;
- _pos_error.z = _leash_up_z;
- _limit.pos_up = true;
- }
- if (_pos_error.z < -_leash_down_z) {
- _pos_target.z = curr_alt - _leash_down_z;
- _pos_error.z = -_leash_down_z;
- _limit.pos_down = true;
- }
-
- _vel_target.z = AC_AttitudeControl::sqrt_controller(_pos_error.z, _p_pos_z.kP(), _accel_z_cms, _dt);
-
-
- _limit.vel_up = false;
- _limit.vel_down = false;
- if (_vel_target.z < _speed_down_cms) {
- _vel_target.z = _speed_down_cms;
- _limit.vel_down = true;
- }
- if (_vel_target.z > _speed_up_cms) {
- _vel_target.z = _speed_up_cms;
- _limit.vel_up = true;
- }
-
- float ff =(float)SRV_Channels::srv_channel(15)->get_output_max()/10000;
-
- static float ff_ratio = ff;
-
-
- if (_flags.use_desvel_ff_z) {
-
-
- if (fabsf(_vel_desired.z)>0)
- {
-
- ff_ratio = constrain_float(ff_ratio*0.997,0.0,2.5);
- _vel_target.z += _vel_desired.z*(1+ff_ratio);
-
-
-
- }else{
-
-
- ff_ratio = ff;
- }
- }else{
-
- ff_ratio = ff;
- }
-
-
-
-
-
- Vector3f curr_vel;
-
- curr_vel.z=alt_rate.get();
-
-
- if (_flags.reset_rate_to_accel_z) {
- _vel_last.z = _vel_target.z;
- }
-
- if (_dt > 0.0f) {
- if (!_flags.freeze_ff_z) {
- _accel_desired.z = (_vel_target.z - _vel_last.z) / _dt;
- } else {
-
- _flags.freeze_ff_z = false;
- }
- } else {
- _accel_desired.z = 0.0f;
- }
-
- _vel_last.z = _vel_target.z;
-
-
- if (_flags.reset_rate_to_accel_z) {
-
- _vel_error.z = 0;
- _vel_error_filter.reset(0);
- _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
-
- _flags.reset_rate_to_accel_z = false;
- } else {
-
- _vel_error.z = _vel_error_filter.apply(_vel_target.z - curr_vel.z, _dt);
- _accel_target.z = _p_vel_z.get_p(_vel_error.z);
-
- }
-
- _accel_target.z += _accel_desired.z;
-
- float z_accel_meas;
-
- z_accel_meas = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
-
- if (_motors.get_throttle_hover() * 1000.0f > _pid_accel_z.imax()) {
- _pid_accel_z.imax(_motors.get_throttle_hover() * 1000.0f);
- }
-
- float thr_out = _pid_accel_z.update_all(_accel_target.z, z_accel_meas, (_motors.limit.throttle_lower || _motors.limit.throttle_upper)) * 0.001f;
-
-
-
- static uint16_t count = 0;
- count++;
- if (count>200)
- {
- count = 0;
- gcs().send_text(MAV_SEVERITY_INFO, "ff %f %f %f \n",_vel_target.z,_accel_target.z,z_accel_meas);
-
- }
- return thr_out;
- }
- void AC_PosControl::set_max_accel_xy(float accel_cmss)
- {
- if (fabsf(_accel_cms - accel_cmss) > 1.0f) {
- _accel_cms = accel_cmss;
- _flags.recalc_leash_xy = true;
- calc_leash_length_xy();
- }
- }
- void AC_PosControl::set_max_speed_xy(float speed_cms)
- {
- if (fabsf(_speed_cms - speed_cms) > 1.0f) {
- _speed_cms = speed_cms;
- _flags.recalc_leash_xy = true;
- calc_leash_length_xy();
- }
- }
- void AC_PosControl::set_pos_target(const Vector3f& position)
- {
- _pos_target = position;
- _flags.use_desvel_ff_z = false;
- _vel_desired.z = 0.0f;
-
-
-
-
- }
- void AC_PosControl::set_xy_target(float x, float y)
- {
- _pos_target.x = x;
- _pos_target.y = y;
- }
- void AC_PosControl::shift_pos_xy_target(float x_cm, float y_cm)
- {
-
- _pos_target.x += x_cm;
- _pos_target.y += y_cm;
- }
- void AC_PosControl::set_target_to_stopping_point_xy()
- {
-
- calc_leash_length_xy();
- get_stopping_point_xy(_pos_target);
- }
- void AC_PosControl::get_stopping_point_xy(Vector3f &stopping_point) const
- {
- const Vector3f curr_pos = _inav.get_position();
- Vector3f curr_vel = _inav.get_velocity();
- float linear_distance;
- float linear_velocity;
- float stopping_dist;
- float kP = _p_pos_xy.kP();
-
- if (is_active_xy()) {
- curr_vel.x += _vel_error.x;
- curr_vel.y += _vel_error.y;
- }
-
- float vel_total = norm(curr_vel.x, curr_vel.y);
-
- if (kP <= 0.0f || _accel_cms <= 0.0f || is_zero(vel_total)) {
- stopping_point.x = curr_pos.x;
- stopping_point.y = curr_pos.y;
- return;
- }
-
- linear_velocity = _accel_cms / kP;
-
- if (vel_total < linear_velocity) {
- stopping_dist = vel_total / kP;
- } else {
- linear_distance = _accel_cms / (2.0f * kP * kP);
- stopping_dist = linear_distance + (vel_total * vel_total) / (2.0f * _accel_cms);
- }
-
- stopping_dist = constrain_float(stopping_dist, 0, _leash);
-
- stopping_point.x = curr_pos.x + (stopping_dist * curr_vel.x / vel_total);
- stopping_point.y = curr_pos.y + (stopping_dist * curr_vel.y / vel_total);
- }
- float AC_PosControl::get_distance_to_target() const
- {
- return norm(_pos_error.x, _pos_error.y);
- }
- int32_t AC_PosControl::get_bearing_to_target() const
- {
- return get_bearing_cd(_inav.get_position(), _pos_target);
- }
- bool AC_PosControl::is_active_xy() const
- {
- return ((AP_HAL::micros64() - _last_update_xy_us) <= POSCONTROL_ACTIVE_TIMEOUT_US);
- }
- float AC_PosControl::get_lean_angle_max_cd() const
- {
- if (is_zero(_lean_angle_max)) {
- return _attitude_control.lean_angle_max();
- }
- return _lean_angle_max * 100.0f;
- }
- void AC_PosControl::init_xy_controller()
- {
-
-
- _roll_target = _ahrs.roll_sensor;
- _pitch_target = _ahrs.pitch_sensor;
-
- _pid_vel_xy.reset_filter();
- lean_angles_to_accel(_accel_target.x, _accel_target.y);
- _pid_vel_xy.set_integrator(_accel_target - _accel_desired);
-
- _flags.reset_desired_vel_to_pos = true;
- _flags.reset_accel_to_lean_xy = true;
-
- init_ekf_xy_reset();
- }
- void AC_PosControl::update_xy_controller()
- {
-
- const uint64_t now_us = AP_HAL::micros64();
- float dt = (now_us - _last_update_xy_us) * 1.0e-6f;
-
- if (dt >= POSCONTROL_ACTIVE_TIMEOUT_US * 1.0e-6f) {
- dt = 0.0f;
- }
-
- check_for_ekf_xy_reset();
-
- calc_leash_length_xy();
-
- desired_vel_to_pos(dt);
-
- run_xy_controller(dt);
-
- _last_update_xy_us = now_us;
- }
- float AC_PosControl::time_since_last_xy_update() const
- {
- const uint64_t now_us = AP_HAL::micros64();
- return (now_us - _last_update_xy_us) * 1.0e-6f;
- }
- void AC_PosControl::write_log()
- {
- const Vector3f &pos_target = get_pos_target();
- const Vector3f &vel_target = get_vel_target();
- const Vector3f &accel_target = get_accel_target();
- const Vector3f &position = _inav.get_position();
- const Vector3f &velocity = _inav.get_velocity();
- float accel_x, accel_y;
- lean_angles_to_accel(accel_x, accel_y);
- AP::logger().Write("PSC",
- "TimeUS,TPX,TPY,PX,PY,TVX,TVY,VX,VY,TAX,TAY,AX,AY",
- "smmmmnnnnoooo",
- "F000000000000",
- "Qffffffffffff",
- AP_HAL::micros64(),
- double(pos_target.x * 0.01f),
- double(pos_target.y * 0.01f),
- double(position.x * 0.01f),
- double(position.y * 0.01f),
- double(vel_target.x * 0.01f),
- double(vel_target.y * 0.01f),
- double(velocity.x * 0.01f),
- double(velocity.y * 0.01f),
- double(accel_target.x * 0.01f),
- double(accel_target.y * 0.01f),
- double(accel_x * 0.01f),
- double(accel_y * 0.01f));
- }
- void AC_PosControl::init_vel_controller_xyz()
- {
-
- _roll_target = _ahrs.roll_sensor;
- _pitch_target = _ahrs.pitch_sensor;
- _pid_vel_xy.reset_filter();
- lean_angles_to_accel(_accel_target.x, _accel_target.y);
- _pid_vel_xy.set_integrator(_accel_target);
-
- _flags.reset_desired_vel_to_pos = true;
- _flags.reset_accel_to_lean_xy = true;
-
- const Vector3f& curr_pos = _inav.get_position();
- set_xy_target(curr_pos.x, curr_pos.y);
- set_alt_target(curr_pos.z);
-
- const Vector3f& curr_vel = _inav.get_velocity();
- set_desired_velocity(curr_vel);
-
- set_desired_accel_xy(0.0f, 0.0f);
-
- init_ekf_xy_reset();
- init_ekf_z_reset();
- }
- void AC_PosControl::update_vel_controller_xy()
- {
-
- const uint64_t now_us = AP_HAL::micros64();
- float dt = (now_us - _last_update_xy_us) * 1.0e-6f;
-
- if (dt >= 0.2f) {
- dt = 0.0f;
- }
-
- check_for_ekf_xy_reset();
-
- calc_leash_length_xy();
-
-
- desired_vel_to_pos(dt);
-
- run_xy_controller(dt);
-
- _last_update_xy_us = now_us;
- }
- void AC_PosControl::update_vel_controller_xyz()
- {
- update_vel_controller_xy();
-
- set_alt_target_from_climb_rate_ff(_vel_desired.z, _dt, false);
-
- update_z_controller();
- }
- float AC_PosControl::get_horizontal_error() const
- {
- return norm(_pos_error.x, _pos_error.y);
- }
- void AC_PosControl::calc_leash_length_xy()
- {
-
- if (_flags.recalc_leash_xy) {
- _leash = calc_leash_length(_speed_cms, _accel_cms, _p_pos_xy.kP());
- _flags.recalc_leash_xy = false;
- }
- }
- void AC_PosControl::desired_accel_to_vel(float nav_dt)
- {
-
- if (nav_dt < 0) {
- return;
- }
-
- if (_flags.reset_desired_vel_to_pos) {
- _flags.reset_desired_vel_to_pos = false;
- } else {
- _vel_desired.x += _accel_desired.x * nav_dt;
- _vel_desired.y += _accel_desired.y * nav_dt;
- }
- }
- void AC_PosControl::desired_vel_to_pos(float nav_dt)
- {
-
- if (nav_dt < 0) {
- return;
- }
-
- if (_flags.reset_desired_vel_to_pos) {
- _flags.reset_desired_vel_to_pos = false;
- } else {
- _pos_target.x += _vel_desired.x * nav_dt;
- _pos_target.y += _vel_desired.y * nav_dt;
- }
- }
- void AC_PosControl::run_xy_controller(float dt)
- {
- float ekfGndSpdLimit, ekfNavVelGainScaler;
- AP::ahrs_navekf().getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
- Vector3f curr_pos = _inav.get_position();
- float kP = ekfNavVelGainScaler * _p_pos_xy.kP();
-
- if (kP <= 0.0f) {
- _vel_target.x = 0.0f;
- _vel_target.y = 0.0f;
- } else {
-
- _pos_error.x = _pos_target.x - curr_pos.x;
- _pos_error.y = _pos_target.y - curr_pos.y;
-
-
-
- if (limit_vector_length(_pos_error.x, _pos_error.y, _leash)) {
- _pos_target.x = curr_pos.x + _pos_error.x;
- _pos_target.y = curr_pos.y + _pos_error.y;
- }
- _vel_target = sqrt_controller(_pos_error, kP, _accel_cms);
- }
-
- _vel_target.x += _vel_desired.x;
- _vel_target.y += _vel_desired.y;
-
- Vector2f accel_target, vel_xy_p, vel_xy_i, vel_xy_d;
-
- if (_flags.vehicle_horiz_vel_override) {
- _flags.vehicle_horiz_vel_override = false;
- } else {
- _vehicle_horiz_vel.x = _inav.get_velocity().x;
- _vehicle_horiz_vel.y = _inav.get_velocity().y;
- }
-
- _vel_error.x = _vel_target.x - _vehicle_horiz_vel.x;
- _vel_error.y = _vel_target.y - _vehicle_horiz_vel.y;
-
-
- _pid_vel_xy.set_input(_vel_error);
-
- vel_xy_p = _pid_vel_xy.get_p();
-
-
- if (!_limit.accel_xy && !_motors.limit.throttle_upper) {
- vel_xy_i = _pid_vel_xy.get_i();
- } else {
- vel_xy_i = _pid_vel_xy.get_i_shrink();
- }
-
- vel_xy_d = _pid_vel_xy.get_d();
-
- accel_target.x = (vel_xy_p.x + vel_xy_i.x + vel_xy_d.x) * ekfNavVelGainScaler;
- accel_target.y = (vel_xy_p.y + vel_xy_i.y + vel_xy_d.y) * ekfNavVelGainScaler;
-
- if (_flags.reset_accel_to_lean_xy) {
- _accel_target_filter.reset(Vector2f(accel_target.x, accel_target.y));
- _flags.reset_accel_to_lean_xy = false;
- }
-
- _accel_target_filter.set_cutoff_frequency(MIN(_accel_xy_filt_hz, 5.0f * ekfNavVelGainScaler));
- _accel_target_filter.apply(accel_target, dt);
-
- _accel_target.x = _accel_target_filter.get().x;
- _accel_target.y = _accel_target_filter.get().y;
-
- _accel_target.x += _accel_desired.x;
- _accel_target.y += _accel_desired.y;
-
-
- float angle_max = MIN(_attitude_control.get_althold_lean_angle_max(), get_lean_angle_max_cd());
- float accel_max = MIN(GRAVITY_MSS * 100.0f * tanf(ToRad(angle_max * 0.01f)), POSCONTROL_ACCEL_XY_MAX);
- _limit.accel_xy = limit_vector_length(_accel_target.x, _accel_target.y, accel_max);
-
- accel_to_lean_angles(_accel_target.x, _accel_target.y, _roll_target, _pitch_target);
- }
- void AC_PosControl::accel_to_lean_angles(float accel_x_cmss, float accel_y_cmss, float& roll_target, float& pitch_target) const
- {
- float accel_right, accel_forward;
-
-
- accel_forward = accel_x_cmss * _ahrs.cos_yaw() + accel_y_cmss * _ahrs.sin_yaw();
- accel_right = -accel_x_cmss * _ahrs.sin_yaw() + accel_y_cmss * _ahrs.cos_yaw();
-
- pitch_target = atanf(-accel_forward / (GRAVITY_MSS * 100.0f)) * (18000.0f / M_PI);
- float cos_pitch_target = cosf(pitch_target * M_PI / 18000.0f);
- roll_target = atanf(accel_right * cos_pitch_target / (GRAVITY_MSS * 100.0f)) * (18000.0f / M_PI);
- }
- void AC_PosControl::lean_angles_to_accel(float& accel_x_cmss, float& accel_y_cmss) const
- {
-
-
- accel_x_cmss = (GRAVITY_MSS * 100) * (-_ahrs.cos_yaw() * _ahrs.sin_pitch() * _ahrs.cos_roll() - _ahrs.sin_yaw() * _ahrs.sin_roll()) / MAX(_ahrs.cos_roll() * _ahrs.cos_pitch(), 0.5f);
- accel_y_cmss = (GRAVITY_MSS * 100) * (-_ahrs.sin_yaw() * _ahrs.sin_pitch() * _ahrs.cos_roll() + _ahrs.cos_yaw() * _ahrs.sin_roll()) / MAX(_ahrs.cos_roll() * _ahrs.cos_pitch(), 0.5f);
- }
- float AC_PosControl::calc_leash_length(float speed_cms, float accel_cms, float kP) const
- {
- float leash_length;
-
- if (accel_cms <= 0.0f) {
- accel_cms = POSCONTROL_ACCELERATION_MIN;
- }
-
- if (kP <= 0.0f) {
- return POSCONTROL_LEASH_LENGTH_MIN;
- }
-
- if (speed_cms <= accel_cms / kP) {
-
- leash_length = speed_cms / kP;
- } else {
-
- leash_length = (accel_cms / (2.0f * kP * kP)) + (speed_cms * speed_cms / (2.0f * accel_cms));
- }
-
- if (leash_length < POSCONTROL_LEASH_LENGTH_MIN) {
- leash_length = POSCONTROL_LEASH_LENGTH_MIN;
- }
- return leash_length;
- }
- void AC_PosControl::init_ekf_xy_reset()
- {
- Vector2f pos_shift;
- _ekf_xy_reset_ms = _ahrs.getLastPosNorthEastReset(pos_shift);
- }
- void AC_PosControl::check_for_ekf_xy_reset()
- {
-
- Vector2f pos_shift;
- uint32_t reset_ms = _ahrs.getLastPosNorthEastReset(pos_shift);
- if (reset_ms != _ekf_xy_reset_ms) {
- shift_pos_xy_target(pos_shift.x * 100.0f, pos_shift.y * 100.0f);
- _ekf_xy_reset_ms = reset_ms;
- }
- }
- void AC_PosControl::init_ekf_z_reset()
- {
- float alt_shift;
- _ekf_z_reset_ms = _ahrs.getLastPosDownReset(alt_shift);
- }
- void AC_PosControl::check_for_ekf_z_reset()
- {
-
- float alt_shift;
- uint32_t reset_ms = _ahrs.getLastPosDownReset(alt_shift);
- if (reset_ms != 0 && reset_ms != _ekf_z_reset_ms) {
- shift_alt_target(-alt_shift * 100.0f);
- _ekf_z_reset_ms = reset_ms;
- }
- }
- bool AC_PosControl::limit_vector_length(float& vector_x, float& vector_y, float max_length)
- {
- float vector_length = norm(vector_x, vector_y);
- if ((vector_length > max_length) && is_positive(vector_length)) {
- vector_x *= (max_length / vector_length);
- vector_y *= (max_length / vector_length);
- return true;
- }
- return false;
- }
- Vector3f AC_PosControl::sqrt_controller(const Vector3f& error, float p, float second_ord_lim)
- {
- if (second_ord_lim < 0.0f || is_zero(second_ord_lim) || is_zero(p)) {
- return Vector3f(error.x * p, error.y * p, error.z);
- }
- float linear_dist = second_ord_lim / sq(p);
- float error_length = norm(error.x, error.y);
- if (error_length > linear_dist) {
- float first_order_scale = safe_sqrt(2.0f * second_ord_lim * (error_length - (linear_dist * 0.5f))) / error_length;
- return Vector3f(error.x * first_order_scale, error.y * first_order_scale, error.z);
- } else {
- return Vector3f(error.x * p, error.y * p, error.z);
- }
- }
- bool AC_PosControl::pre_arm_checks(const char *param_prefix,
- char *failure_msg,
- const uint8_t failure_msg_len)
- {
-
- const struct {
- const char *pid_name;
- AC_P &p;
- } ps[] = {
- { "POSXY", get_pos_xy_p() },
- { "POSZ", get_pos_z_p() },
- { "VELZ", get_vel_z_p() },
- };
- for (uint8_t i=0; i<ARRAY_SIZE(ps); i++) {
-
- if (!is_positive(ps[i].p.kP())) {
- hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be > 0", param_prefix, ps[i].pid_name);
- return false;
- }
- }
-
- if (!is_positive(get_accel_z_pid().kP())) {
- hal.util->snprintf(failure_msg, failure_msg_len, "%s_ACCZ_P must be > 0", param_prefix);
- return false;
- }
- if (!is_positive(get_accel_z_pid().kI())) {
- hal.util->snprintf(failure_msg, failure_msg_len, "%s_ACCZ_I must be > 0", param_prefix);
- return false;
- }
- return true;
- }
|