Skip to content

Commit

Permalink
squash
Browse files Browse the repository at this point in the history
  • Loading branch information
lthall committed Aug 1, 2023
1 parent d74d107 commit fc8f4be
Show file tree
Hide file tree
Showing 11 changed files with 155 additions and 0 deletions.
16 changes: 16 additions & 0 deletions AntennaTracker/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -379,6 +379,14 @@ const AP_Param::Info Tracker::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: PITCH2SRV_PDMX
// @DisplayName: Pitch axis PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 4000
// @Increment: 10
// @Units: d%
// @User: Standard

GGROUP(pidPitch2Srv, "PITCH2SRV_", AC_PID),

// @Param: YAW2SRV_P
Expand Down Expand Up @@ -448,6 +456,14 @@ const AP_Param::Info Tracker::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: YAW2SRV_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 4000
// @Increment: 10
// @Units: d%
// @User: Standard

GGROUP(pidYaw2Srv, "YAW2SRV_", AC_PID),

#if AP_SCRIPTING_ENABLED
Expand Down
8 changes: 8 additions & 0 deletions Blimp/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -722,6 +722,14 @@ const AP_Param::Info Blimp::var_info[] = {
// @Range: 0 200
// @Increment: 0.5
// @User: Advanced

// @Param: POSYAW_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 4000
// @Increment: 10
// @Units: d%
// @User: Standard
GOBJECT(pid_pos_yaw, "POSYAW_", AC_PID),

// @Group:
Expand Down
21 changes: 21 additions & 0 deletions libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: RAT_RLL_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1
// @Increment: 0.01
// @User: Standard

AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 1, AC_AttitudeControl_Multi, AC_PID),

// @Param: RAT_PIT_P
Expand Down Expand Up @@ -141,6 +148,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: RAT_PIT_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1
// @Increment: 0.01
// @User: Standard

AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 2, AC_AttitudeControl_Multi, AC_PID),

// @Param: RAT_YAW_P
Expand Down Expand Up @@ -209,6 +223,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: RAT_YAW_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1
// @Increment: 0.01
// @User: Standard

AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 3, AC_AttitudeControl_Multi, AC_PID),

// @Param: THR_MIX_MIN
Expand Down
21 changes: 21 additions & 0 deletions libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: RAT_RLL_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1
// @Increment: 0.01
// @User: Standard

AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 1, AC_AttitudeControl_Sub, AC_PID),

// @Param: RAT_PIT_P
Expand Down Expand Up @@ -141,6 +148,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: RAT_PIT_IMAX
// @DisplayName: Pitch axis rate controller I gain maximum
// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum that the I term will output
// @Range: 0 1
// @Increment: 0.01
// @User: Standard

AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 2, AC_AttitudeControl_Sub, AC_PID),

// @Param: RAT_YAW_P
Expand Down Expand Up @@ -209,6 +223,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: RAT_YAW_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1
// @Increment: 0.01
// @User: Standard

AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 3, AC_AttitudeControl_Sub, AC_PID),

// @Param: THR_MIX_MIN
Expand Down
7 changes: 7 additions & 0 deletions libraries/AC_AttitudeControl/AC_PosControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -204,6 +204,13 @@ const AP_Param::GroupInfo AC_PosControl::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: _ACCZ_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1000
// @Units: d%
// @User: Standard

AP_SUBGROUPINFO(_pid_accel_z, "_ACCZ_", 4, AC_PosControl, AC_PID),

// @Param: _POSXY_P
Expand Down
21 changes: 21 additions & 0 deletions libraries/AC_CustomControl/AC_CustomControl_PID.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,13 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
// @Range: 0 200
// @Increment: 0.5
// @User: Advanced

// @Param: RAT_RLL_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1
// @Increment: 0.01
// @User: Standard
AP_SUBGROUPINFO(_pid_atti_rate_roll, "RAT_RLL_", 4, AC_CustomControl_PID, AC_PID),

// @Param: RAT_PIT_P
Expand Down Expand Up @@ -161,6 +168,13 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
// @Range: 0 200
// @Increment: 0.5
// @User: Advanced

// @Param: RAT_PIT_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1
// @Increment: 0.01
// @User: Standard
AP_SUBGROUPINFO(_pid_atti_rate_pitch, "RAT_PIT_", 5, AC_CustomControl_PID, AC_PID),


Expand Down Expand Up @@ -229,6 +243,13 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
// @Range: 0 200
// @Increment: 0.5
// @User: Advanced

// @Param: RAT_YAW_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1
// @Increment: 0.01
// @User: Standard
AP_SUBGROUPINFO(_pid_atti_rate_yaw, "RAT_YAW_", 6, AC_CustomControl_PID, AC_PID),

AP_GROUPEND
Expand Down
7 changes: 7 additions & 0 deletions libraries/APM_Control/AP_PitchController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -131,6 +131,13 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: _RATE_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1
// @Increment: 0.01
// @User: Standard

AP_SUBGROUPINFO(rate_pid, "_RATE_", 11, AP_PitchController, AC_PID),

AP_GROUPEND
Expand Down
7 changes: 7 additions & 0 deletions libraries/APM_Control/AP_RollController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,13 @@ const AP_Param::GroupInfo AP_RollController::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: _RATE_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1
// @Increment: 0.01
// @User: Standard

AP_SUBGROUPINFO(rate_pid, "_RATE_", 9, AP_RollController, AC_PID),

AP_GROUPEND
Expand Down
7 changes: 7 additions & 0 deletions libraries/APM_Control/AP_YawController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -145,6 +145,13 @@ const AP_Param::GroupInfo AP_YawController::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: _RATE_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 1
// @Increment: 0.01
// @User: Standard

AP_SUBGROUPINFO(rate_pid, "_RATE_", 9, AP_YawController, AC_PID),

AP_GROUPEND
Expand Down
28 changes: 28 additions & 0 deletions libraries/APM_Control/AR_AttitudeControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,13 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: _STR_RAT_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0.000 1.000
// @Increment: 0.01
// @User: Standard

AP_SUBGROUPINFO(_steer_rate_pid, "_STR_RAT_", 1, AR_AttitudeControl, AC_PID),

// @Param: _SPEED_P
Expand Down Expand Up @@ -219,6 +226,13 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: _SPEED_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0.000 1.000
// @Increment: 0.01
// @User: Standard

AP_SUBGROUPINFO(_throttle_speed_pid, "_SPEED_", 2, AR_AttitudeControl, AC_PID),

// @Param: _ACCEL_MAX
Expand Down Expand Up @@ -355,6 +369,13 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: _BAL_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0.000 1.000
// @Increment: 0.01
// @User: Standard

AP_SUBGROUPINFO(_pitch_to_throttle_pid, "_BAL_", 10, AR_AttitudeControl, AC_PID),

// @Param: _BAL_PIT_FF
Expand Down Expand Up @@ -439,6 +460,13 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: _SAIL_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0.000 1.000
// @Increment: 0.01
// @User: Standard

AP_SUBGROUPINFO(_sailboat_heel_pid, "_SAIL_", 12, AR_AttitudeControl, AC_PID),

// @Param: _TURN_MAX_G
Expand Down
12 changes: 12 additions & 0 deletions libraries/AP_WheelEncoder/AP_WheelRateControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,12 @@ const AP_Param::GroupInfo AP_WheelRateControl::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: _RATE_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0.000 1.000
// @User: Standard

AP_SUBGROUPINFO(_rate_pid0, "_RATE_", 3, AP_WheelRateControl, AC_PID),

// @Param: 2_RATE_FF
Expand Down Expand Up @@ -156,6 +162,12 @@ const AP_Param::GroupInfo AP_WheelRateControl::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: 2_RATE_PDMX
// @DisplayName: PD sum maximum
// @Description: The maximum/minimum value that the sum of the P and D term can output
// @Range: 0.000 1.000
// @User: Standard

AP_SUBGROUPINFO(_rate_pid1, "2_RATE_", 4, AP_WheelRateControl, AC_PID),

AP_GROUPEND
Expand Down

0 comments on commit fc8f4be

Please sign in to comment.