mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: add build options for each frame class
This commit is contained in:
parent
8f591a853b
commit
9349abfe48
|
@ -585,7 +585,7 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||||
bool success = true;
|
bool success = true;
|
||||||
|
|
||||||
switch (frame_class) {
|
switch (frame_class) {
|
||||||
|
#if FRAME_QUAD
|
||||||
case MOTOR_FRAME_QUAD:
|
case MOTOR_FRAME_QUAD:
|
||||||
_frame_class_string = "QUAD";
|
_frame_class_string = "QUAD";
|
||||||
_mav_type = MAV_TYPE_QUADROTOR;
|
_mav_type = MAV_TYPE_QUADROTOR;
|
||||||
|
@ -635,7 +635,7 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||||
add_motors(motors, ARRAY_SIZE(motors));
|
add_motors(motors, ARRAY_SIZE(motors));
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#endif
|
#endif //APM_BUILD_TYPE(APM_BUILD_ArduPlane)
|
||||||
case MOTOR_FRAME_TYPE_BF_X: {
|
case MOTOR_FRAME_TYPE_BF_X: {
|
||||||
// betaflight quad X order
|
// betaflight quad X order
|
||||||
// see: https://fpvfrenzy.com/betaflight-motor-order/
|
// see: https://fpvfrenzy.com/betaflight-motor-order/
|
||||||
|
@ -772,7 +772,8 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
break; // quad
|
break; // quad
|
||||||
|
#endif //FRAME_QUAD
|
||||||
|
#if FRAME_HEXA
|
||||||
case MOTOR_FRAME_HEXA:
|
case MOTOR_FRAME_HEXA:
|
||||||
_frame_class_string = "HEXA";
|
_frame_class_string = "HEXA";
|
||||||
_mav_type = MAV_TYPE_HEXAROTOR;
|
_mav_type = MAV_TYPE_HEXAROTOR;
|
||||||
|
@ -850,7 +851,8 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
#endif //FRAME_HEXA
|
||||||
|
#if FRAME_OCTA
|
||||||
case MOTOR_FRAME_OCTA:
|
case MOTOR_FRAME_OCTA:
|
||||||
_frame_class_string = "OCTA";
|
_frame_class_string = "OCTA";
|
||||||
_mav_type = MAV_TYPE_OCTOROTOR;
|
_mav_type = MAV_TYPE_OCTOROTOR;
|
||||||
|
@ -968,7 +970,8 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||||
break;
|
break;
|
||||||
} // octa frame type
|
} // octa frame type
|
||||||
break;
|
break;
|
||||||
|
#endif //FRAME_OCTA
|
||||||
|
#if FRAME_OCTAQUAD
|
||||||
case MOTOR_FRAME_OCTAQUAD:
|
case MOTOR_FRAME_OCTAQUAD:
|
||||||
_mav_type = MAV_TYPE_OCTOROTOR;
|
_mav_type = MAV_TYPE_OCTOROTOR;
|
||||||
_frame_class_string = "OCTAQUAD";
|
_frame_class_string = "OCTAQUAD";
|
||||||
|
@ -1055,7 +1058,8 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
#endif //FRAME_OCTAQUAD
|
||||||
|
#if FRAME_DODECAHEXA
|
||||||
case MOTOR_FRAME_DODECAHEXA: {
|
case MOTOR_FRAME_DODECAHEXA: {
|
||||||
_mav_type = MAV_TYPE_DODECAROTOR;
|
_mav_type = MAV_TYPE_DODECAROTOR;
|
||||||
_frame_class_string = "DODECAHEXA";
|
_frame_class_string = "DODECAHEXA";
|
||||||
|
@ -1105,7 +1109,8 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||||
break;
|
break;
|
||||||
}}
|
}}
|
||||||
break;
|
break;
|
||||||
|
#endif //FRAME_DODECAHEXA
|
||||||
|
#if FRAME_Y6
|
||||||
case MOTOR_FRAME_Y6:
|
case MOTOR_FRAME_Y6:
|
||||||
_mav_type = MAV_TYPE_HEXAROTOR;
|
_mav_type = MAV_TYPE_HEXAROTOR;
|
||||||
_frame_class_string = "Y6";
|
_frame_class_string = "Y6";
|
||||||
|
@ -1153,7 +1158,8 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
#endif //FRAME_Y6
|
||||||
|
#if FRAME_DECA
|
||||||
case MOTOR_FRAME_DECA:
|
case MOTOR_FRAME_DECA:
|
||||||
_mav_type = MAV_TYPE_DECAROTOR;
|
_mav_type = MAV_TYPE_DECAROTOR;
|
||||||
_frame_class_string = "DECA";
|
_frame_class_string = "DECA";
|
||||||
|
@ -1198,13 +1204,15 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
#endif //FRAME_DECA
|
||||||
default:
|
default:
|
||||||
// matrix doesn't support the configured class
|
// matrix doesn't support the configured class
|
||||||
_frame_class_string = "UNSUPPORTED";
|
_frame_class_string = "UNSUPPORTED";
|
||||||
success = false;
|
success = false;
|
||||||
_mav_type = MAV_TYPE_GENERIC;
|
_mav_type = MAV_TYPE_GENERIC;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
|
||||||
} // switch frame_class
|
} // switch frame_class
|
||||||
|
|
||||||
// normalise factors to magnitude 0.5
|
// normalise factors to magnitude 0.5
|
||||||
|
|
|
@ -22,6 +22,28 @@
|
||||||
|
|
||||||
#define AP_MOTORS_MAX_NUM_MOTORS 12
|
#define AP_MOTORS_MAX_NUM_MOTORS 12
|
||||||
|
|
||||||
|
#ifndef FRAME_QUAD
|
||||||
|
#define FRAME_QUAD 1
|
||||||
|
#endif
|
||||||
|
#ifndef FRAME_HEXA
|
||||||
|
#define FRAME_HEXA 1
|
||||||
|
#endif
|
||||||
|
#ifndef FRAME_OCTA
|
||||||
|
#define FRAME_OCTA 1
|
||||||
|
#endif
|
||||||
|
#ifndef FRAME_DECA
|
||||||
|
#define FRAME_DECA 1
|
||||||
|
#endif
|
||||||
|
#ifndef FRAME_DODECAHEXA
|
||||||
|
#define FRAME_DODECAHEXA 1
|
||||||
|
#endif
|
||||||
|
#ifndef FRAME_Y6
|
||||||
|
#define FRAME_Y6 1
|
||||||
|
#endif
|
||||||
|
#ifndef FRAME_OCTAQUAD
|
||||||
|
#define FRAME_OCTAQUAD 1
|
||||||
|
#endif
|
||||||
|
|
||||||
// motor update rate
|
// motor update rate
|
||||||
#define AP_MOTORS_SPEED_DEFAULT 490 // default output rate to the motors
|
#define AP_MOTORS_SPEED_DEFAULT 490 // default output rate to the motors
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue