Copter: add dodeca-hexa
This commit is contained in:
parent
66fc49889b
commit
1a76c28655
@ -987,7 +987,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
// @Param: FRAME_CLASS
|
||||
// @DisplayName: Frame Class
|
||||
// @Description: Controls major frame class for multicopter component
|
||||
// @Values: 0:Undefined, 1:Quad, 2:Hexa, 3:Octa, 4:OctaQuad, 5:Y6, 6:Heli, 7:Tri, 8:SingleCopter, 9:CoaxCopter
|
||||
// @Values: 0:Undefined, 1:Quad, 2:Hexa, 3:Octa, 4:OctaQuad, 5:Y6, 6:Heli, 7:Tri, 8:SingleCopter, 9:CoaxCopter, 11:Heli_Dual, 12:DodecaHexa
|
||||
// @User: Standard
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("FRAME_CLASS", 15, ParametersG2, frame_class, 0),
|
||||
|
@ -536,6 +536,8 @@ uint8_t Copter::get_frame_mav_type()
|
||||
case AP_Motors::MOTOR_FRAME_COAX:
|
||||
case AP_Motors::MOTOR_FRAME_TAILSITTER:
|
||||
return MAV_TYPE_COAXIAL;
|
||||
case AP_Motors::MOTOR_FRAME_DODECAHEXA:
|
||||
return MAV_TYPE_HEXAROTOR;
|
||||
}
|
||||
// unknown frame so return generic
|
||||
return MAV_TYPE_GENERIC;
|
||||
@ -567,6 +569,8 @@ const char* Copter::get_frame_string()
|
||||
return "COAX";
|
||||
case AP_Motors::MOTOR_FRAME_TAILSITTER:
|
||||
return "TAILSITTER";
|
||||
case AP_Motors::MOTOR_FRAME_DODECAHEXA:
|
||||
return "DODECA_HEXA";
|
||||
case AP_Motors::MOTOR_FRAME_UNDEFINED:
|
||||
default:
|
||||
return "UNKNOWN";
|
||||
@ -585,6 +589,7 @@ void Copter::allocate_motors(void)
|
||||
case AP_Motors::MOTOR_FRAME_Y6:
|
||||
case AP_Motors::MOTOR_FRAME_OCTA:
|
||||
case AP_Motors::MOTOR_FRAME_OCTAQUAD:
|
||||
case AP_Motors::MOTOR_FRAME_DODECAHEXA:
|
||||
default:
|
||||
motors = new AP_MotorsMatrix(MAIN_LOOP_RATE);
|
||||
motors_var_info = AP_MotorsMatrix::var_info;
|
||||
|
Loading…
Reference in New Issue
Block a user