Rover: fix sailboat NO_GO_ANGLE param description

This commit is contained in:
Randy Mackay 2019-08-21 15:00:57 +09:00
parent 79feb4edb8
commit bf7432cf2e
1 changed files with 1 additions and 1 deletions

View File

@ -66,7 +66,7 @@ const AP_Param::GroupInfo Sailboat::var_info[] = {
// @User: Standard // @User: Standard
AP_GROUPINFO("HEEL_MAX", 5, Sailboat, sail_heel_angle_max, 15), AP_GROUPINFO("HEEL_MAX", 5, Sailboat, sail_heel_angle_max, 15),
// @Param: SAIL_NO_GO_ANGLE // @Param: NO_GO_ANGLE
// @DisplayName: Sailing no go zone angle // @DisplayName: Sailing no go zone angle
// @Description: The typical closest angle to the wind the vehicle will sail at. the vehicle will sail at this angle when going upwind // @Description: The typical closest angle to the wind the vehicle will sail at. the vehicle will sail at this angle when going upwind
// @Units: deg // @Units: deg