mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
AC_AttitudeControl: fixed PIRO_COMP index
this is a new conflict due to stricter checking in AP_Param
This commit is contained in:
parent
59a1f260d1
commit
1a25087dd5
@ -6,13 +6,6 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
|
|||||||
// parameters from parent vehicle
|
// parameters from parent vehicle
|
||||||
AP_NESTEDGROUPINFO(AC_AttitudeControl, 0),
|
AP_NESTEDGROUPINFO(AC_AttitudeControl, 0),
|
||||||
|
|
||||||
// @Param: PIRO_COMP
|
|
||||||
// @DisplayName: Piro Comp Enable
|
|
||||||
// @Description: Pirouette compensation enabled
|
|
||||||
// @Values: 0:Disabled,1:Enabled
|
|
||||||
// @User: Advanced
|
|
||||||
AP_GROUPINFO("PIRO_COMP", 0, AC_AttitudeControl_Heli, _piro_comp_enabled, 0),
|
|
||||||
|
|
||||||
// @Param: HOVR_ROL_TRM
|
// @Param: HOVR_ROL_TRM
|
||||||
// @DisplayName: Hover Roll Trim
|
// @DisplayName: Hover Roll Trim
|
||||||
// @Description: Trim the hover roll angle to counter tail rotor thrust in a hover
|
// @Description: Trim the hover roll angle to counter tail rotor thrust in a hover
|
||||||
@ -150,6 +143,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
|
|||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 4, AC_AttitudeControl_Heli, AC_HELI_PID),
|
AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 4, AC_AttitudeControl_Heli, AC_HELI_PID),
|
||||||
|
|
||||||
|
// @Param: PIRO_COMP
|
||||||
|
// @DisplayName: Piro Comp Enable
|
||||||
|
// @Description: Pirouette compensation enabled
|
||||||
|
// @Values: 0:Disabled,1:Enabled
|
||||||
|
// @User: Advanced
|
||||||
|
AP_GROUPINFO("PIRO_COMP", 5, AC_AttitudeControl_Heli, _piro_comp_enabled, 0),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user