mirror of https://github.com/ArduPilot/ardupilot
Sub: Create new Vectored 90DEG (6DOF) class
This commit is contained in:
parent
0a6fc0cc43
commit
e016e906f5
|
@ -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)
|
||||
|
|
|
@ -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),
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -37,7 +37,7 @@ def build(bld):
|
|||
)
|
||||
|
||||
frames = (
|
||||
'bluerov','vectored','vectored6DOF','simplerov'
|
||||
'bluerov','vectored','vectored6DOF','simplerov','vectored90'
|
||||
)
|
||||
|
||||
for frame in frames:
|
||||
|
|
Loading…
Reference in New Issue