diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index a190ce8a04..81b8c7688f 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -802,6 +802,13 @@ const AP_Param::Info Copter::var_info[] PROGMEM = { // @Description: Throttle acceleration controller D gain. Compensates for short-term change in desired vertical acceleration vs actual acceleration // @Range: 0.000 0.400 // @User: Standard + + // @Param: ACCEL_Z_FILT_HZ + // @DisplayName: Throttle acceleration filter + // @Description: Filter applied to acceleration to reduce noise. Lower values reduce noise but add delay. + // @Range: 1.000 100.000 + // @Units: Hz + // @User: Standard GGROUP(pid_accel_z, "ACCEL_Z_", AC_PID), // P controllers @@ -886,8 +893,6 @@ const AP_Param::Info Copter::var_info[] PROGMEM = { GOBJECT(circle_nav, "CIRCLE_", AC_Circle), #if FRAME_CONFIG == HELI_FRAME - // @Group: ATC_ - // @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp GOBJECT(attitude_control, "ATC_", AC_AttitudeControl_Heli), #else // @Group: ATC_ @@ -929,7 +934,7 @@ const AP_Param::Info Copter::var_info[] PROGMEM = { GOBJECT(camera_mount, "MNT", AP_Mount), #endif - // @Group: BATT_ + // @Group: BATT // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp GOBJECT(battery, "BATT", AP_BattMonitor), @@ -1012,7 +1017,7 @@ const AP_Param::Info Copter::var_info[] PROGMEM = { #else // @Group: MOT_ - // @Path: ../libraries/AP_Motors/AP_Motors_Class.cpp + // @Path: ../libraries/AP_Motors/AP_MotorsMulticopter.cpp GOBJECT(motors, "MOT_", AP_MotorsMulticopter), #endif