Sub: Fixed ROV motor parameters

This commit is contained in:
Rustom Jehangir 2016-02-04 14:24:48 -08:00 committed by Andrew Tridgell
parent 771ce2f607
commit 1853935b71
1 changed files with 1 additions and 1 deletions

View File

@ -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),