mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AC_AttControlHeli: use params from parent class
This commit is contained in:
parent
7951346d72
commit
bef5633ed5
@ -5,56 +5,8 @@
|
|||||||
|
|
||||||
// table of user settable parameters
|
// table of user settable parameters
|
||||||
const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] PROGMEM = {
|
const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] PROGMEM = {
|
||||||
|
// parameters from parent vehicle
|
||||||
// 0, 1 were RATE_RP_MAX, RATE_Y_MAX
|
AP_NESTEDGROUPINFO(AC_AttitudeControl, 0),
|
||||||
|
|
||||||
// @Param: SLEW_YAW
|
|
||||||
// @DisplayName: Yaw target slew rate
|
|
||||||
// @Description: Maximum rate the yaw target can be updated in Loiter, RTL, Auto flight modes
|
|
||||||
// @Units: Centi-Degrees/Sec
|
|
||||||
// @Range: 500 18000
|
|
||||||
// @Increment: 100
|
|
||||||
// @User: Advanced
|
|
||||||
AP_GROUPINFO("SLEW_YAW", 2, AC_AttitudeControl_Heli, _slew_yaw, AC_ATTITUDE_CONTROL_SLEW_YAW_DEFAULT),
|
|
||||||
|
|
||||||
// 3 was for ACCEL_RP_MAX
|
|
||||||
|
|
||||||
// @Param: ACCEL_Y_MAX
|
|
||||||
// @DisplayName: Acceleration Max for Yaw
|
|
||||||
// @Description: Maximum acceleration in yaw axis
|
|
||||||
// @Units: Centi-Degrees/Sec/Sec
|
|
||||||
// @Range: 0 72000
|
|
||||||
// @Values: 0:Disabled, 18000:Slow, 36000:Medium, 54000:Fast
|
|
||||||
// @Increment: 1000
|
|
||||||
// @User: Advanced
|
|
||||||
AP_GROUPINFO("ACCEL_Y_MAX", 4, AC_AttitudeControl_Heli, _accel_yaw_max, AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT),
|
|
||||||
|
|
||||||
// @Param: RATE_FF_ENAB
|
|
||||||
// @DisplayName: Rate Feedforward Enable
|
|
||||||
// @Description: Controls whether body-frame rate feedfoward is enabled or disabled
|
|
||||||
// @Values: 0:Disabled, 1:Enabled
|
|
||||||
// @User: Advanced
|
|
||||||
AP_GROUPINFO("RATE_FF_ENAB", 5, AC_AttitudeControl_Heli, _rate_bf_ff_enabled, AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT),
|
|
||||||
|
|
||||||
// @Param: ACCEL_R_MAX
|
|
||||||
// @DisplayName: Acceleration Max for Roll
|
|
||||||
// @Description: Maximum acceleration in roll axis
|
|
||||||
// @Units: Centi-Degrees/Sec/Sec
|
|
||||||
// @Range: 0 180000
|
|
||||||
// @Increment: 1000
|
|
||||||
// @Values: 0:Disabled, 72000:Slow, 108000:Medium, 162000:Fast
|
|
||||||
// @User: Advanced
|
|
||||||
AP_GROUPINFO("ACCEL_R_MAX", 6, AC_AttitudeControl_Heli, _accel_roll_max, AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT),
|
|
||||||
|
|
||||||
// @Param: ACCEL_P_MAX
|
|
||||||
// @DisplayName: Acceleration Max for Pitch
|
|
||||||
// @Description: Maximum acceleration in pitch axis
|
|
||||||
// @Units: Centi-Degrees/Sec/Sec
|
|
||||||
// @Range: 0 180000
|
|
||||||
// @Increment: 1000
|
|
||||||
// @Values: 0:Disabled, 72000:Slow, 108000:Medium, 162000:Fast
|
|
||||||
// @User: Advanced
|
|
||||||
AP_GROUPINFO("ACCEL_P_MAX", 7, AC_AttitudeControl_Heli, _accel_pitch_max, AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT),
|
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user