mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: mark tricopter yaw as tricopter only
This commit is contained in:
parent
79b0c856b2
commit
108cbe1dab
|
@ -152,7 +152,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
|||
// @Units: Degrees
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("YAW_SV_ANGLE", 35, AP_MotorsMulticopter, _yaw_servo_angle_max_deg, 30),
|
||||
AP_GROUPINFO_FRAME("YAW_SV_ANGLE", 35, AP_MotorsMulticopter, _yaw_servo_angle_max_deg, 30, AP_PARAM_FRAME_TRICOPTER),
|
||||
|
||||
// @Param: SPOOL_TIME
|
||||
// @DisplayName: Spool up time
|
||||
|
|
Loading…
Reference in New Issue