mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Avoidance: fixed generated param docs
This commit is contained in:
parent
83d3488eb2
commit
ead3689ca9
@ -48,7 +48,6 @@ const AP_Param::GroupInfo AP_Avoidance::var_info[] = {
|
|||||||
// @Param: F_ACTION
|
// @Param: F_ACTION
|
||||||
// @DisplayName: Collision Avoidance Behavior
|
// @DisplayName: Collision Avoidance Behavior
|
||||||
// @Description: Specifies aircraft behaviour when a collision is imminent
|
// @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
|
// @Values: 0:None,1:Report,2:Climb Or Descend,3:Move Horizontally,4:Move Perpendicularly in 3D,5:RTL,6:Hover
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("F_ACTION", 2, AP_Avoidance, _fail_action, AP_AVOIDANCE_FAIL_ACTION_DEFAULT),
|
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
|
// @Param: W_ACTION
|
||||||
// @DisplayName: Collision Avoidance Behavior - Warn
|
// @DisplayName: Collision Avoidance Behavior - Warn
|
||||||
// @Description: Specifies aircraft behaviour when a collision may occur
|
// @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
|
// @Values: 0:None,1:Report
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("W_ACTION", 3, AP_Avoidance, _warn_action, MAV_COLLISION_ACTION_REPORT),
|
AP_GROUPINFO("W_ACTION", 3, AP_Avoidance, _warn_action, MAV_COLLISION_ACTION_REPORT),
|
||||||
|
Loading…
Reference in New Issue
Block a user