Browse Source

Tracker: correct missing parameter documentation

c415-sdk
Peter Barker 5 years ago committed by Peter Barker
parent
commit
6dd204d52c
  1. 68
      AntennaTracker/Parameters.cpp

68
AntennaTracker/Parameters.cpp

@ -284,9 +284,11 @@ const AP_Param::Info Tracker::var_info[] = { @@ -284,9 +284,11 @@ const AP_Param::Info Tracker::var_info[] = {
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
GOBJECT(notify, "NTF_", AP_Notify),
// @Path: RC_Channels.cpp
// @Group: RC
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
GOBJECT(rc_channels, "RC", RC_Channels_Tracker),
// @Group: SERVO
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
GOBJECT(servo_channels, "SERVO", SRV_Channels),
@ -321,6 +323,37 @@ const AP_Param::Info Tracker::var_info[] = { @@ -321,6 +323,37 @@ const AP_Param::Info Tracker::var_info[] = {
// @Description: Pitch axis controller D gain. Compensates for short-term change in desired pitch angle vs actual pitch angle
// @Range: 0.001 0.1
// @Increment: 0.001
// @User: Standard
// @Param: PITCH2SRV_FF
// @DisplayName: Pitch axis controller feed forward
// @Description: Pitch axis controller feed forward
// @Range: 0 0.5
// @Increment: 0.001
// @User: Standard
// @Param: PITCH2SRV_FLTT
// @DisplayName: Pitch axis controller target frequency in Hz
// @Description: Pitch axis controller target frequency in Hz
// @Range: 1 50
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: PITCH2SRV_FLTE
// @DisplayName: Pitch axis controller error frequency in Hz
// @Description: Pitch axis controller error frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: PITCH2SRV_FLTD
// @DisplayName: Pitch axis controller derivative frequency in Hz
// @Description: Pitch axis controller derivative frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
GGROUP(pidPitch2Srv, "PITCH2SRV_", AC_PID),
@ -351,6 +384,37 @@ const AP_Param::Info Tracker::var_info[] = { @@ -351,6 +384,37 @@ const AP_Param::Info Tracker::var_info[] = {
// @Description: Yaw axis controller D gain. Compensates for short-term change in desired yaw angle (heading) vs actual yaw angle
// @Range: 0.001 0.1
// @Increment: 0.001
// @User: Standard
// @Param: YAW2SRV_FF
// @DisplayName: Yaw axis controller feed forward
// @Description: Yaw axis controller feed forward
// @Range: 0 0.5
// @Increment: 0.001
// @User: Standard
// @Param: YAW2SRV_FLTT
// @DisplayName: Yaw axis controller target frequency in Hz
// @Description: Yaw axis controller target frequency in Hz
// @Range: 1 50
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: YAW2SRV_FLTE
// @DisplayName: Yaw axis controller error frequency in Hz
// @Description: Yaw axis controller error frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: YAW2SRV_FLTD
// @DisplayName: Yaw axis controller derivative frequency in Hz
// @Description: Yaw axis controller derivative frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
GGROUP(pidYaw2Srv, "YAW2SRV_", AC_PID),
@ -409,7 +473,7 @@ const AP_Param::Info Tracker::var_info[] = { @@ -409,7 +473,7 @@ const AP_Param::Info Tracker::var_info[] = {
// @User: Standard
GSCALAR(disarm_pwm, "SAFE_DISARM_PWM", 0),
// @Group: STAT_
// @Group: STAT
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
GOBJECT(stats, "STAT", AP_Stats),

Loading…
Cancel
Save