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);
|
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
|
#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";
|
_frame_class_string = "QUAD";
|
||||||
_mav_type = MAV_TYPE_QUADROTOR;
|
_mav_type = MAV_TYPE_QUADROTOR;
|
||||||
switch (frame_type) {
|
switch (frame_type) {
|
||||||
@ -774,13 +764,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
|||||||
default:
|
default:
|
||||||
// quad frame class does not support this frame type
|
// quad frame class does not support this frame type
|
||||||
_frame_type_string = "UNSUPPORTED";
|
_frame_type_string = "UNSUPPORTED";
|
||||||
success = false;
|
return false;
|
||||||
break;
|
}
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
break; // quad
|
|
||||||
#endif //AP_MOTORS_FRAME_QUAD_ENABLED
|
#endif //AP_MOTORS_FRAME_QUAD_ENABLED
|
||||||
#if AP_MOTORS_FRAME_HEXA_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";
|
_frame_class_string = "HEXA";
|
||||||
_mav_type = MAV_TYPE_HEXAROTOR;
|
_mav_type = MAV_TYPE_HEXAROTOR;
|
||||||
switch (frame_type) {
|
switch (frame_type) {
|
||||||
@ -853,13 +844,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
|||||||
default:
|
default:
|
||||||
// hexa frame class does not support this frame type
|
// hexa frame class does not support this frame type
|
||||||
_frame_type_string = "UNSUPPORTED";
|
_frame_type_string = "UNSUPPORTED";
|
||||||
success = false;
|
return false;
|
||||||
break;
|
} //hexa
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
break;
|
#endif ////AP_MOTORS_FRAME_HEXA_ENABLED
|
||||||
#endif //AP_MOTORS_FRAME_HEXA_ENABLED
|
|
||||||
#if AP_MOTORS_FRAME_OCTA_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";
|
_frame_class_string = "OCTA";
|
||||||
_mav_type = MAV_TYPE_OCTOROTOR;
|
_mav_type = MAV_TYPE_OCTOROTOR;
|
||||||
switch (frame_type) {
|
switch (frame_type) {
|
||||||
@ -972,13 +964,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
|||||||
default:
|
default:
|
||||||
// octa frame class does not support this frame type
|
// octa frame class does not support this frame type
|
||||||
_frame_type_string = "UNSUPPORTED";
|
_frame_type_string = "UNSUPPORTED";
|
||||||
success = false;
|
return false;
|
||||||
break;
|
|
||||||
} // octa frame type
|
} // octa frame type
|
||||||
break;
|
return true;
|
||||||
|
}
|
||||||
#endif //AP_MOTORS_FRAME_OCTA_ENABLED
|
#endif //AP_MOTORS_FRAME_OCTA_ENABLED
|
||||||
#if AP_MOTORS_FRAME_OCTAQUAD_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;
|
_mav_type = MAV_TYPE_OCTOROTOR;
|
||||||
_frame_class_string = "OCTAQUAD";
|
_frame_class_string = "OCTAQUAD";
|
||||||
switch (frame_type) {
|
switch (frame_type) {
|
||||||
@ -1094,13 +1087,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
|||||||
default:
|
default:
|
||||||
// octaquad frame class does not support this frame type
|
// octaquad frame class does not support this frame type
|
||||||
_frame_type_string = "UNSUPPORTED";
|
_frame_type_string = "UNSUPPORTED";
|
||||||
success = false;
|
return false;
|
||||||
break;
|
} //octaquad
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
break;
|
|
||||||
#endif // AP_MOTORS_FRAME_OCTAQUAD_ENABLED
|
#endif // AP_MOTORS_FRAME_OCTAQUAD_ENABLED
|
||||||
#if AP_MOTORS_FRAME_DODECAHEXA_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;
|
_mav_type = MAV_TYPE_DODECAROTOR;
|
||||||
_frame_class_string = "DODECAHEXA";
|
_frame_class_string = "DODECAHEXA";
|
||||||
switch (frame_type) {
|
switch (frame_type) {
|
||||||
@ -1145,13 +1139,14 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
|||||||
default:
|
default:
|
||||||
// dodeca-hexa frame class does not support this frame type
|
// dodeca-hexa frame class does not support this frame type
|
||||||
_frame_type_string = "UNSUPPORTED";
|
_frame_type_string = "UNSUPPORTED";
|
||||||
success = false;
|
return false;
|
||||||
break;
|
} //dodecahexa
|
||||||
}}
|
return true;
|
||||||
break;
|
}
|
||||||
#endif //AP_MOTORS_FRAME_DODECAHEXA_ENABLED
|
#endif //AP_MOTORS_FRAME_DODECAHEXA_ENABLED
|
||||||
#if AP_MOTORS_FRAME_Y6_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;
|
_mav_type = MAV_TYPE_HEXAROTOR;
|
||||||
_frame_class_string = "Y6";
|
_frame_class_string = "Y6";
|
||||||
switch (frame_type) {
|
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));
|
add_motors_raw(motors, ARRAY_SIZE(motors));
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
} //y6
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
break;
|
|
||||||
#endif // AP_MOTORS_FRAME_Y6_ENABLED
|
#endif // AP_MOTORS_FRAME_Y6_ENABLED
|
||||||
#if AP_MOTORS_FRAME_DECA_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;
|
_mav_type = MAV_TYPE_DECAROTOR;
|
||||||
_frame_class_string = "DECA";
|
_frame_class_string = "DECA";
|
||||||
switch (frame_type) {
|
switch (frame_type) {
|
||||||
@ -1241,9 +1238,55 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
|||||||
}
|
}
|
||||||
default:
|
default:
|
||||||
// deca frame class does not support this frame type
|
// deca frame class does not support this frame type
|
||||||
success = false;
|
return false;
|
||||||
break;
|
} //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;
|
break;
|
||||||
#endif //AP_MOTORS_FRAME_DECA_ENABLED
|
#endif //AP_MOTORS_FRAME_DECA_ENABLED
|
||||||
default:
|
default:
|
||||||
@ -1252,8 +1295,6 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
|
|||||||
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
|
||||||
|
@ -150,6 +150,16 @@ protected:
|
|||||||
|
|
||||||
const char* _frame_class_string = ""; // string representation of frame class
|
const char* _frame_class_string = ""; // string representation of frame class
|
||||||
const char* _frame_type_string = ""; // string representation of frame type
|
const char* _frame_type_string = ""; // string representation of frame type
|
||||||
|
|
||||||
private:
|
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;
|
static AP_MotorsMatrix *_singleton;
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user