mirror of https://github.com/ArduPilot/ardupilot
Copter: add SCRIPTING_MATRIX frame class
This commit is contained in:
parent
004f873dc7
commit
643966fb3e
|
@ -864,7 +864,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, 10:BiCopter, 11:Heli_Dual, 12:DodecaHexa, 13:HeliQuad, 14:Deca
|
||||
// @Values: 0:Undefined, 1:Quad, 2:Hexa, 3:Octa, 4:OctaQuad, 5:Y6, 6:Heli, 7:Tri, 8:SingleCopter, 9:CoaxCopter, 10:BiCopter, 11:Heli_Dual, 12:DodecaHexa, 13:HeliQuad, 14:Deca, 15:Scripting Matrix
|
||||
// @User: Standard
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("FRAME_CLASS", 15, ParametersG2, frame_class, DEFAULT_FRAME_CLASS),
|
||||
|
|
|
@ -500,6 +500,7 @@ void Copter::allocate_motors(void)
|
|||
case AP_Motors::MOTOR_FRAME_OCTAQUAD:
|
||||
case AP_Motors::MOTOR_FRAME_DODECAHEXA:
|
||||
case AP_Motors::MOTOR_FRAME_DECA:
|
||||
case AP_Motors::MOTOR_FRAME_SCRIPTING_MATRIX:
|
||||
default:
|
||||
motors = new AP_MotorsMatrix(copter.scheduler.get_loop_rate_hz());
|
||||
motors_var_info = AP_MotorsMatrix::var_info;
|
||||
|
|
Loading…
Reference in New Issue