From e016e906f59164bcb7918c4d93ae98c97a829d45 Mon Sep 17 00:00:00 2001 From: jaxxzer Date: Wed, 18 May 2016 01:56:30 -0400 Subject: [PATCH] Sub: Create new Vectored 90DEG (6DOF) class --- ArduSub/APM_Config.h | 1 + ArduSub/Parameters.cpp | 2 +- ArduSub/Sub.h | 2 ++ ArduSub/config.h | 2 ++ ArduSub/defines.h | 1 + ArduSub/wscript | 2 +- 6 files changed, 8 insertions(+), 2 deletions(-) diff --git a/ArduSub/APM_Config.h b/ArduSub/APM_Config.h index 1e1ec27d3a..f287ccf06d 100644 --- a/ArduSub/APM_Config.h +++ b/ArduSub/APM_Config.h @@ -11,6 +11,7 @@ * VECTORED_FRAME * VECTORED6DOF_FRAME * SIMPLEROV_FRAME + * VECTORED90_FRAME */ // uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards) diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index ae1699c73a..a558c659a4 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -897,7 +897,7 @@ const AP_Param::Info Sub::var_info[] = { GOBJECT(rally, "RALLY_", AP_Rally), #endif -//#if (FRAME_CONFIG == VECTORED_FRAME || FRAME_CONFIG == BLUEROV_FRAME || FRAME_CONFIG == VECTORED6DOF_FRAME || FRAME_CONFIG == SIMPLEROV ) +//#if (FRAME_CONFIG == VECTORED_FRAME || FRAME_CONFIG == BLUEROV_FRAME || FRAME_CONFIG == VECTORED6DOF_FRAME || FRAME_CONFIG == SIMPLEROV || FRAME_CONFIG == VECTORED90_FRAME) // @Group: MOT_ // @Path: ../libraries/AP_Motors/AP_Motors6DOF.cpp GOBJECT(motors, "MOT_", AP_Motors6DOF), diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 61375df45e..6e2d394152 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -318,6 +318,8 @@ private: #define MOTOR_CLASS AP_MotorsVectored6DOF #elif FRAME_CONFIG == SIMPLEROV_FRAME #define MOTOR_CLASS AP_MotorsSimpleROV +#elif FRAME_CONFIG == VECTORED90_FRAME + #define MOTOR_CLASS AP_MotorsVectored90 #else #error Unrecognised frame type diff --git a/ArduSub/config.h b/ArduSub/config.h index c1afa36cd4..6cc7a4be17 100644 --- a/ArduSub/config.h +++ b/ArduSub/config.h @@ -69,6 +69,8 @@ # define FRAME_CONFIG_STRING "ROV_VECTORED6DOF_FRAME" #elif FRAME_CONFIG == SIMPLEROV_FRAME # define FRAME_CONFIG_STRING "ROV_SIMPLEROV_FRAME" +#elif FRAME_CONFIG == VECTORED90_FRAME +# define FRAME_CONFIG_STRING "ROV_VECTORED90_FRAME" #else # define FRAME_CONFIG_STRING "UNKNOWN" #endif diff --git a/ArduSub/defines.h b/ArduSub/defines.h index f472756623..4f998086d7 100644 --- a/ArduSub/defines.h +++ b/ArduSub/defines.h @@ -89,6 +89,7 @@ enum aux_sw_func { #define VECTORED_FRAME 11 #define VECTORED6DOF_FRAME 12 #define SIMPLEROV_FRAME 13 +#define VECTORED90_FRAME 14 // HIL enumerations #define HIL_MODE_DISABLED 0 diff --git a/ArduSub/wscript b/ArduSub/wscript index be933c31cb..c6368f13de 100644 --- a/ArduSub/wscript +++ b/ArduSub/wscript @@ -37,7 +37,7 @@ def build(bld): ) frames = ( - 'bluerov','vectored','vectored6DOF','simplerov' + 'bluerov','vectored','vectored6DOF','simplerov','vectored90' ) for frame in frames: