Copter: remove PHLD_BRAKE_* params when PosHold is disabled

This commit is contained in:
Tatsuya Yamaguchi 2021-01-06 22:00:44 +09:00 committed by Randy Mackay
parent e8d24a1f68
commit b6b39673d4
2 changed files with 5 additions and 1 deletions

View File

@ -371,6 +371,7 @@ const AP_Param::Info Copter::var_info[] = {
// @User: Advanced
ASCALAR(angle_max, "ANGLE_MAX", DEFAULT_ANGLE_MAX),
#if MODE_POSHOLD_ENABLED == ENABLED
// @Param: PHLD_BRAKE_RATE
// @DisplayName: PosHold braking rate
// @Description: PosHold flight mode's rotation rate during braking in deg/sec
@ -386,6 +387,7 @@ const AP_Param::Info Copter::var_info[] = {
// @Range: 2000 4500
// @User: Advanced
GSCALAR(poshold_brake_angle_max, "PHLD_BRAKE_ANGLE", POSHOLD_BRAKE_ANGLE_DEFAULT),
#endif
// @Param: LAND_REPOSITION
// @DisplayName: Land repositioning

View File

@ -408,9 +408,11 @@ public:
AP_Int8 wp_yaw_behavior; // controls how the autopilot controls yaw during missions
#if MODE_POSHOLD_ENABLED == ENABLED
AP_Int16 poshold_brake_rate; // PosHold flight mode's rotation rate during braking in deg/sec
AP_Int16 poshold_brake_angle_max; // PosHold flight mode's max lean angle during braking in centi-degrees
#endif
// Waypoints
//
AP_Int32 rtl_loiter_time;