mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-03 06:28:32 -04:00
AP_Motors: refactor to allow frame type symbols to be created for ELF
This commit is contained in:
parent
44ce44b2fa
commit
8b02f11c23
@ -569,19 +569,9 @@ void AP_MotorsMatrix::add_motors_raw(const struct MotorDefRaw *motors, uint8_t n
|
||||
add_motor_raw(i, m.roll_fac, m.pitch_fac, m.yaw_fac, m.testing_order);
|
||||
}
|
||||
}
|
||||
|
||||
void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_type frame_type)
|
||||
{
|
||||
// remove existing motors
|
||||
for (int8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||
remove_motor(i);
|
||||
}
|
||||
set_initialised_ok(false);
|
||||
bool success = true;
|
||||
|
||||
switch (frame_class) {
|
||||
#if AP_MOTORS_FRAME_QUAD_ENABLED
|
||||
case MOTOR_FRAME_QUAD:
|
||||
bool AP_MotorsMatrix::setup_quad_matrix(motor_frame_type frame_type)
|
||||
{
|
||||
_frame_class_string = "QUAD";
|
||||
_mav_type = MAV_TYPE_QUADROTOR;
|
||||
switch (frame_type) {
|
||||
@ -748,7 +738,7 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
add_motor(AP_MOTORS_MOT_3, -60, -60, 0, 4);
|
||||
add_motor(AP_MOTORS_MOT_4, 0, 160, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2);
|
||||
break;
|
||||
case MOTOR_FRAME_TYPE_PLUSREV:{
|
||||
case MOTOR_FRAME_TYPE_PLUSREV: {
|
||||
// plus with reversed motor directions
|
||||
_frame_type_string = "PLUSREV";
|
||||
static const AP_MotorsMatrix::MotorDef motors[] {
|
||||
@ -774,13 +764,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
default:
|
||||
// quad frame class does not support this frame type
|
||||
_frame_type_string = "UNSUPPORTED";
|
||||
success = false;
|
||||
break;
|
||||
return false;
|
||||
}
|
||||
break; // quad
|
||||
return true;
|
||||
}
|
||||
#endif //AP_MOTORS_FRAME_QUAD_ENABLED
|
||||
#if AP_MOTORS_FRAME_HEXA_ENABLED
|
||||
case MOTOR_FRAME_HEXA:
|
||||
bool AP_MotorsMatrix::setup_hexa_matrix(motor_frame_type frame_type)
|
||||
{
|
||||
_frame_class_string = "HEXA";
|
||||
_mav_type = MAV_TYPE_HEXAROTOR;
|
||||
switch (frame_type) {
|
||||
@ -853,13 +844,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
default:
|
||||
// hexa frame class does not support this frame type
|
||||
_frame_type_string = "UNSUPPORTED";
|
||||
success = false;
|
||||
break;
|
||||
}
|
||||
break;
|
||||
#endif //AP_MOTORS_FRAME_HEXA_ENABLED
|
||||
return false;
|
||||
} //hexa
|
||||
return true;
|
||||
}
|
||||
#endif ////AP_MOTORS_FRAME_HEXA_ENABLED
|
||||
#if AP_MOTORS_FRAME_OCTA_ENABLED
|
||||
case MOTOR_FRAME_OCTA:
|
||||
bool AP_MotorsMatrix::setup_octa_matrix(motor_frame_type frame_type)
|
||||
{
|
||||
_frame_class_string = "OCTA";
|
||||
_mav_type = MAV_TYPE_OCTOROTOR;
|
||||
switch (frame_type) {
|
||||
@ -972,13 +964,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
default:
|
||||
// octa frame class does not support this frame type
|
||||
_frame_type_string = "UNSUPPORTED";
|
||||
success = false;
|
||||
break;
|
||||
return false;
|
||||
} // octa frame type
|
||||
break;
|
||||
return true;
|
||||
}
|
||||
#endif //AP_MOTORS_FRAME_OCTA_ENABLED
|
||||
#if AP_MOTORS_FRAME_OCTAQUAD_ENABLED
|
||||
case MOTOR_FRAME_OCTAQUAD:
|
||||
bool AP_MotorsMatrix::setup_octaquad_matrix(motor_frame_type frame_type)
|
||||
{
|
||||
_mav_type = MAV_TYPE_OCTOROTOR;
|
||||
_frame_class_string = "OCTAQUAD";
|
||||
switch (frame_type) {
|
||||
@ -1094,13 +1087,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
default:
|
||||
// octaquad frame class does not support this frame type
|
||||
_frame_type_string = "UNSUPPORTED";
|
||||
success = false;
|
||||
break;
|
||||
}
|
||||
break;
|
||||
#endif //AP_MOTORS_FRAME_OCTAQUAD_ENABLED
|
||||
return false;
|
||||
} //octaquad
|
||||
return true;
|
||||
}
|
||||
#endif // AP_MOTORS_FRAME_OCTAQUAD_ENABLED
|
||||
#if AP_MOTORS_FRAME_DODECAHEXA_ENABLED
|
||||
case MOTOR_FRAME_DODECAHEXA: {
|
||||
bool AP_MotorsMatrix::setup_dodecahexa_matrix(motor_frame_type frame_type)
|
||||
{
|
||||
_mav_type = MAV_TYPE_DODECAROTOR;
|
||||
_frame_class_string = "DODECAHEXA";
|
||||
switch (frame_type) {
|
||||
@ -1145,13 +1139,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
default:
|
||||
// dodeca-hexa frame class does not support this frame type
|
||||
_frame_type_string = "UNSUPPORTED";
|
||||
success = false;
|
||||
break;
|
||||
}}
|
||||
break;
|
||||
return false;
|
||||
} //dodecahexa
|
||||
return true;
|
||||
}
|
||||
#endif //AP_MOTORS_FRAME_DODECAHEXA_ENABLED
|
||||
#if AP_MOTORS_FRAME_Y6_ENABLED
|
||||
case MOTOR_FRAME_Y6:
|
||||
bool AP_MotorsMatrix::setup_y6_matrix(motor_frame_type frame_type)
|
||||
{
|
||||
_mav_type = MAV_TYPE_HEXAROTOR;
|
||||
_frame_class_string = "Y6";
|
||||
switch (frame_type) {
|
||||
@ -1196,11 +1191,13 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
add_motors_raw(motors, ARRAY_SIZE(motors));
|
||||
break;
|
||||
}
|
||||
}
|
||||
break;
|
||||
#endif //AP_MOTORS_FRAME_Y6_ENABLED
|
||||
} //y6
|
||||
return true;
|
||||
}
|
||||
#endif // AP_MOTORS_FRAME_Y6_ENABLED
|
||||
#if AP_MOTORS_FRAME_DECA_ENABLED
|
||||
case MOTOR_FRAME_DECA:
|
||||
bool AP_MotorsMatrix::setup_deca_matrix(motor_frame_type frame_type)
|
||||
{
|
||||
_mav_type = MAV_TYPE_DECAROTOR;
|
||||
_frame_class_string = "DECA";
|
||||
switch (frame_type) {
|
||||
@ -1241,9 +1238,55 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
}
|
||||
default:
|
||||
// deca frame class does not support this frame type
|
||||
success = false;
|
||||
break;
|
||||
return false;
|
||||
} //deca
|
||||
return true;
|
||||
}
|
||||
#endif // AP_MOTORS_FRAME_DECA_ENABLED
|
||||
|
||||
void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_type frame_type)
|
||||
{
|
||||
// remove existing motors
|
||||
for (int8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||
remove_motor(i);
|
||||
}
|
||||
set_initialised_ok(false);
|
||||
bool success = true;
|
||||
|
||||
switch (frame_class) {
|
||||
#if AP_MOTORS_FRAME_QUAD_ENABLED
|
||||
case MOTOR_FRAME_QUAD:
|
||||
success = setup_quad_matrix(frame_type);
|
||||
break; // quad
|
||||
#endif //AP_MOTORS_FRAME_QUAD_ENABLED
|
||||
#if AP_MOTORS_FRAME_HEXA_ENABLED
|
||||
case MOTOR_FRAME_HEXA:
|
||||
success = setup_hexa_matrix(frame_type);
|
||||
break;
|
||||
#endif //AP_MOTORS_FRAME_HEXA_ENABLED
|
||||
#if AP_MOTORS_FRAME_OCTA_ENABLED
|
||||
case MOTOR_FRAME_OCTA:
|
||||
success = setup_octa_matrix(frame_type);
|
||||
break;
|
||||
#endif //AP_MOTORS_FRAME_OCTA_ENABLED
|
||||
#if AP_MOTORS_FRAME_OCTAQUAD_ENABLED
|
||||
case MOTOR_FRAME_OCTAQUAD:
|
||||
success = setup_octaquad_matrix(frame_type);
|
||||
break;
|
||||
#endif //AP_MOTORS_FRAME_OCTAQUAD_ENABLED
|
||||
#if AP_MOTORS_FRAME_DODECAHEXA_ENABLED
|
||||
case MOTOR_FRAME_DODECAHEXA:
|
||||
success = setup_dodecahexa_matrix(frame_type);
|
||||
break;
|
||||
#endif //AP_MOTORS_FRAME_DODECAHEXA_ENABLED
|
||||
#if AP_MOTORS_FRAME_Y6_ENABLED
|
||||
case MOTOR_FRAME_Y6:
|
||||
success = setup_y6_matrix(frame_type);
|
||||
break;
|
||||
#endif //AP_MOTORS_FRAME_Y6_ENABLED
|
||||
#if AP_MOTORS_FRAME_DECA_ENABLED
|
||||
case MOTOR_FRAME_DECA:
|
||||
success = setup_deca_matrix(frame_type);
|
||||
break;
|
||||
#endif //AP_MOTORS_FRAME_DECA_ENABLED
|
||||
default:
|
||||
@ -1252,8 +1295,6 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
||||
success = false;
|
||||
_mav_type = MAV_TYPE_GENERIC;
|
||||
break;
|
||||
|
||||
|
||||
} // switch frame_class
|
||||
|
||||
// normalise factors to magnitude 0.5
|
||||
|
@ -150,6 +150,16 @@ protected:
|
||||
|
||||
const char* _frame_class_string = ""; // string representation of frame class
|
||||
const char* _frame_type_string = ""; // string representation of frame type
|
||||
|
||||
private:
|
||||
// setup motors matrix
|
||||
bool setup_quad_matrix(motor_frame_type frame_type);
|
||||
bool setup_hexa_matrix(motor_frame_type frame_type);
|
||||
bool setup_octa_matrix(motor_frame_type frame_type);
|
||||
bool setup_deca_matrix(motor_frame_type frame_type);
|
||||
bool setup_dodecahexa_matrix(motor_frame_type frame_type);
|
||||
bool setup_y6_matrix(motor_frame_type frame_type);
|
||||
bool setup_octaquad_matrix(motor_frame_type frame_type);
|
||||
|
||||
static AP_MotorsMatrix *_singleton;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user