mirror of https://github.com/ArduPilot/ardupilot
Blimp: add documentation for PID notches and D feed-foward
update PID notch centers at 1Hz with average loop rate
This commit is contained in:
parent
25b66ef6ca
commit
c4dc6f6471
|
@ -209,6 +209,8 @@ void Blimp::one_hz_loop()
|
|||
SRV_Channels::enable_aux_servos();
|
||||
|
||||
AP_Notify::flags.flying = !ap.land_complete;
|
||||
|
||||
blimp.pid_pos_yaw.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
|
||||
}
|
||||
|
||||
void Blimp::read_AHRS(void)
|
||||
|
|
|
@ -729,6 +729,48 @@ const AP_Param::Info Blimp::var_info[] = {
|
|||
// @Increment: 10
|
||||
// @Units: d%
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: POSYAW_ADV
|
||||
// @DisplayName: Advanced Yaw parameters enable
|
||||
// @Description: Advanced Yaw parameters enable
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: POSYAW_D_FF
|
||||
// @DisplayName: Position (yaw) Derivative FeedForward Gain
|
||||
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
|
||||
// @Range: 0.001 0.1
|
||||
// @Increment: 0.001
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: POSYAW_NTF
|
||||
// @DisplayName: Position (yaw) Target notch Filter center frequency
|
||||
// @Description: Position (yaw) Target notch Filter center frequency in Hz.
|
||||
// @Range: 10 495
|
||||
// @Units: Hz
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: POSYAW_NEF
|
||||
// @DisplayName: Position (yaw) Error notch Filter center frequency
|
||||
// @Description: Position (yaw) Error notch Filter center frequency in Hz.
|
||||
// @Range: 10 495
|
||||
// @Units: Hz
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: POSYAW_NBW
|
||||
// @DisplayName: Position (yaw) notch Filter bandwidth
|
||||
// @Description: Position (yaw) notch Filter bandwidth in Hz.
|
||||
// @Range: 5 250
|
||||
// @Units: Hz
|
||||
// @User: Advanced
|
||||
|
||||
// @Param: POSYAW_NATT
|
||||
// @DisplayName: Position (yaw) notch Filter attenuation
|
||||
// @Description: Position (yaw) notch Filter attenuation in dB.
|
||||
// @Range: 5 50
|
||||
// @Units: dB
|
||||
// @User: Advanced
|
||||
|
||||
GOBJECT(pid_pos_yaw, "POSYAW_", AC_PID),
|
||||
|
||||
// @Group:
|
||||
|
|
Loading…
Reference in New Issue