Sub: Add support for Vectored 6DOF ROV
Sub: Various defines for vectored-6dof configuration Sub: fix compile errors for vector6dof rov More fixes
This commit is contained in:
parent
6cf24c2770
commit
473016b41d
@ -9,6 +9,7 @@
|
||||
/* options:
|
||||
* BLUEROV_FRAME
|
||||
* VECTORED_FRAME
|
||||
* VECTORED6DOF_FRAME
|
||||
*/
|
||||
|
||||
// uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards)
|
||||
|
@ -92,7 +92,7 @@ NOINLINE void Sub::send_heartbeat(mavlink_channel_t chan)
|
||||
MAV_TYPE_ROCKET,
|
||||
#elif (FRAME_CONFIG == COAX_FRAME) //because mavlink did not define a singlecopter, we use a rocket
|
||||
MAV_TYPE_ROCKET,
|
||||
#elif (FRAME_CONFIG == BLUEROV_FRAME || FRAME_CONFIG == VECTORED_FRAME)
|
||||
#elif (FRAME_CONFIG == BLUEROV_FRAME || FRAME_CONFIG == VECTORED_FRAME || FRAME_CONFIG == VECTORED6DOF_FRAME)
|
||||
MAV_TYPE_HEXAROTOR,
|
||||
#else
|
||||
#error Unrecognised frame type
|
||||
|
@ -997,7 +997,7 @@ const AP_Param::Info Sub::var_info[] = {
|
||||
// @Path: ../libraries/AP_Motors/AP_MotorsTri.cpp
|
||||
GOBJECT(motors, "MOT_", AP_MotorsTri),
|
||||
|
||||
#elif (FRAME_CONFIG == VECTORED_FRAME || FRAME_CONFIG == BLUEROV_FRAME)
|
||||
#elif (FRAME_CONFIG == VECTORED_FRAME || FRAME_CONFIG == BLUEROV_FRAME || FRAME_CONFIG == VECTORED6DOF_FRAME)
|
||||
// @Group: MOT_
|
||||
// @Path: ../libraries/AP_Motors/AP_Motors6DOF.cpp
|
||||
GOBJECT(motors, "MOT_", AP_Motors6DOF),
|
||||
|
@ -312,6 +312,9 @@ private:
|
||||
#define MOTOR_CLASS AP_MotorsBlueROV6DOF
|
||||
#elif FRAME_CONFIG == VECTORED_FRAME
|
||||
#define MOTOR_CLASS AP_MotorsVectoredROV
|
||||
#elif FRAME_CONFIG == VECTORED6DOF_FRAME
|
||||
#define MOTOR_CLASS AP_MotorsVectored6DOF
|
||||
|
||||
#else
|
||||
#error Unrecognised frame type
|
||||
#endif
|
||||
|
@ -63,13 +63,15 @@
|
||||
// FRAME_CONFIG
|
||||
//
|
||||
#ifndef FRAME_CONFIG
|
||||
# define FRAME_CONFIG BLUEROV_FRAME
|
||||
# define FRAME_CONFIG VECTORED6DOF_FRAME
|
||||
#endif
|
||||
|
||||
#if FRAME_CONFIG == BLUEROV_FRAME
|
||||
# define FRAME_CONFIG_STRING "ROV_BLUEROV_FRAME"
|
||||
#elif FRAME_CONFIG == VECTORED_FRAME
|
||||
# define FRAME_CONFIG_STRING "ROV_VECTORED_FRAME"
|
||||
#elif FRAME_CONFIG == VECTORED6DOF_FRAME
|
||||
# define FRAME_CONFIG_STRING "ROV_VECTORED6DOF_FRAME"
|
||||
#else
|
||||
# define FRAME_CONFIG_STRING "UNKNOWN"
|
||||
#endif
|
||||
|
@ -81,6 +81,7 @@ enum aux_sw_func {
|
||||
#define COAX_FRAME 9
|
||||
#define BLUEROV_FRAME 10
|
||||
#define VECTORED_FRAME 11
|
||||
#define VECTORED6DOF_FRAME 12
|
||||
|
||||
// HIL enumerations
|
||||
#define HIL_MODE_DISABLED 0
|
||||
|
Loading…
Reference in New Issue
Block a user