ardupilot
ardupilot copied to clipboard
ADRC: Active Disturbance Rejection Control
This adds the ADRC controller as an option for Copter attitude control.
Thanks to @xianglunkai for his earlier PR #20079 which this is adapted from.
I suggest fix some little bugs.
float fal(float e, float alpha, float delta) { if(is_zero(delta)){ return e; }
if(fabsf(e) < delta){
return e / (powf(delta, 1.0f-alpha));
}else{
return powf(fabsf(e), alpha) * sign(e);
}
}
and....float sign(float val) { if(val > 0.0f) return 1.0f; else if(val < 0.0f) return -1.0f; else { return 0; } }
I suggest fix some little bugs.
thanks, added
Should add AP_HAL_ADRC_RATE_CONTROLLER_ENABLED in Tools/scripts/build_options.py and use it.
this is just an experiment, it would be structured quite differently if we were to consider it for merging into master
@xianglunkai Thanks for the fixes. Did you get the equations you used from a specific paper by any chance? I've looked at some ADRC papers and they have similar maths but not the exact same - seems to be adapted to each specific application?
I suggest you could take a look at this paper about ADRC Jiachi_Zou_Thesis 2018 ADRC UAV Github.pdf .
@xianglunkai Thanks. I'll have a look.
Good to know that my thesis helps!
FYI, here is a test video I did before with ADRC: https://www.youtube.com/watch?v=77-_nF-qqpA&t=191s And the test code can be found here: https://github.com/JcZou/StarryPilot/blob/master/starry_fmu/Framework/source/Control/adrc_att.c
In yours implementation, fal non-linear control law is used, which is standard method introduced by ADRC. However, based on my experience, a well-tuned PID + ESO would get a better performance, as fal is relatively too sensitive for the error.
@xianglunkai 微信