Sub: Add 'SimpleROV' frame configuration for 3/4-dof ROVs

This commit is contained in:
Rustom Jehangir 2016-04-11 22:05:48 -07:00 committed by Andrew Tridgell
parent c711fedc4c
commit d628b0d022
7 changed files with 9 additions and 3 deletions

View File

@ -10,6 +10,7 @@
* BLUEROV_FRAME * BLUEROV_FRAME
* VECTORED_FRAME * VECTORED_FRAME
* VECTORED6DOF_FRAME * VECTORED6DOF_FRAME
* SIMPLEROV_FRAME
*/ */
// uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards) // uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards)

View File

@ -95,7 +95,7 @@ NOINLINE void Sub::send_heartbeat(mavlink_channel_t chan)
MAV_TYPE_ROCKET, MAV_TYPE_ROCKET,
#elif (FRAME_CONFIG == COAX_FRAME) //because mavlink did not define a singlecopter, we use a rocket #elif (FRAME_CONFIG == COAX_FRAME) //because mavlink did not define a singlecopter, we use a rocket
MAV_TYPE_ROCKET, MAV_TYPE_ROCKET,
#elif (FRAME_CONFIG == BLUEROV_FRAME || FRAME_CONFIG == VECTORED_FRAME || FRAME_CONFIG == VECTORED6DOF_FRAME) #elif (FRAME_CONFIG == BLUEROV_FRAME || FRAME_CONFIG == VECTORED_FRAME || FRAME_CONFIG == VECTORED6DOF_FRAME || FRAME_CONFIG == SIMPLEROV_FRAME )
MAV_TYPE_SUBMARINE, MAV_TYPE_SUBMARINE,
#else #else
#error Unrecognised frame type #error Unrecognised frame type

View File

@ -942,7 +942,7 @@ const AP_Param::Info Sub::var_info[] = {
GOBJECT(rally, "RALLY_", AP_Rally), GOBJECT(rally, "RALLY_", AP_Rally),
#endif #endif
//#if (FRAME_CONFIG == VECTORED_FRAME || FRAME_CONFIG == BLUEROV_FRAME || FRAME_CONFIG == VECTORED6DOF_FRAME) //#if (FRAME_CONFIG == VECTORED_FRAME || FRAME_CONFIG == BLUEROV_FRAME || FRAME_CONFIG == VECTORED6DOF_FRAME || FRAME_CONFIG == SIMPLEROV )
// @Group: MOT_ // @Group: MOT_
// @Path: ../libraries/AP_Motors/AP_Motors6DOF.cpp // @Path: ../libraries/AP_Motors/AP_Motors6DOF.cpp
GOBJECT(motors, "MOT_", AP_Motors6DOF), GOBJECT(motors, "MOT_", AP_Motors6DOF),

View File

@ -325,6 +325,8 @@ private:
#define MOTOR_CLASS AP_MotorsVectoredROV #define MOTOR_CLASS AP_MotorsVectoredROV
#elif FRAME_CONFIG == VECTORED6DOF_FRAME #elif FRAME_CONFIG == VECTORED6DOF_FRAME
#define MOTOR_CLASS AP_MotorsVectored6DOF #define MOTOR_CLASS AP_MotorsVectored6DOF
#elif FRAME_CONFIG == SIMPLEROV_FRAME
#define MOTOR_CLASS AP_MotorsSimpleROV
#else #else
#error Unrecognised frame type #error Unrecognised frame type

View File

@ -72,6 +72,8 @@
# define FRAME_CONFIG_STRING "ROV_VECTORED_FRAME" # define FRAME_CONFIG_STRING "ROV_VECTORED_FRAME"
#elif FRAME_CONFIG == VECTORED6DOF_FRAME #elif FRAME_CONFIG == VECTORED6DOF_FRAME
# define FRAME_CONFIG_STRING "ROV_VECTORED6DOF_FRAME" # define FRAME_CONFIG_STRING "ROV_VECTORED6DOF_FRAME"
#elif FRAME_CONFIG == SIMPLEROV_FRAME
# define FRAME_CONFIG_STRING "ROV_SIMPLEROV_FRAME"
#else #else
# define FRAME_CONFIG_STRING "UNKNOWN" # define FRAME_CONFIG_STRING "UNKNOWN"
#endif #endif

View File

@ -88,6 +88,7 @@ enum aux_sw_func {
#define BLUEROV_FRAME 10 #define BLUEROV_FRAME 10
#define VECTORED_FRAME 11 #define VECTORED_FRAME 11
#define VECTORED6DOF_FRAME 12 #define VECTORED6DOF_FRAME 12
#define SIMPLEROV_FRAME 13
// HIL enumerations // HIL enumerations
#define HIL_MODE_DISABLED 0 #define HIL_MODE_DISABLED 0

View File

@ -35,7 +35,7 @@ def build(bld):
) )
frames = ( frames = (
'bluerov','vectored','vectored6DOF', 'bluerov','vectored','vectored6DOF','simplerov'
) )
for frame in frames: for frame in frames: