mirror of https://github.com/ArduPilot/ardupilot
Sub: Fixed ROV motor parameters
This commit is contained in:
parent
771ce2f607
commit
1853935b71
|
@ -1037,7 +1037,7 @@ const AP_Param::Info Sub::var_info[] = {
|
|||
// @Path: ../libraries/AP_Motors/AP_MotorsTri.cpp
|
||||
GOBJECT(motors, "MOT_", AP_MotorsTri),
|
||||
|
||||
#elif FRAME_CONFIG == BLUEROV
|
||||
#elif (FRAME_CONFIG == VECTORED_FRAME || FRAME_CONFIG == BLUEROV_FRAME)
|
||||
// @Group: MOT_
|
||||
// @Path: ../libraries/AP_Motors/AP_Motors6DOF.cpp
|
||||
GOBJECT(motors, "MOT_", AP_Motors6DOF),
|
||||
|
|
Loading…
Reference in New Issue