AP_Avoidance: fixed generated param docs

This commit is contained in:
Andrew Tridgell 2020-01-15 15:38:29 +11:00
parent 83d3488eb2
commit ead3689ca9
1 changed files with 0 additions and 2 deletions

View File

@ -48,7 +48,6 @@ const AP_Param::GroupInfo AP_Avoidance::var_info[] = {
// @Param: F_ACTION
// @DisplayName: Collision Avoidance Behavior
// @Description: Specifies aircraft behaviour when a collision is imminent
// The following values should come from the mavlink COLLISION_ACTION enum
// @Values: 0:None,1:Report,2:Climb Or Descend,3:Move Horizontally,4:Move Perpendicularly in 3D,5:RTL,6:Hover
// @User: Advanced
AP_GROUPINFO("F_ACTION", 2, AP_Avoidance, _fail_action, AP_AVOIDANCE_FAIL_ACTION_DEFAULT),
@ -56,7 +55,6 @@ const AP_Param::GroupInfo AP_Avoidance::var_info[] = {
// @Param: W_ACTION
// @DisplayName: Collision Avoidance Behavior - Warn
// @Description: Specifies aircraft behaviour when a collision may occur
// The following values should come from the mavlink COLLISION_ACTION enum
// @Values: 0:None,1:Report
// @User: Advanced
AP_GROUPINFO("W_ACTION", 3, AP_Avoidance, _warn_action, MAV_COLLISION_ACTION_REPORT),