AP_Motors: change build option name to new standard

This commit is contained in:
Hwurzburg 2021-10-30 21:56:36 -05:00 committed by Randy Mackay
parent ad29135384
commit 47028f136e
2 changed files with 28 additions and 28 deletions

View File

@ -585,7 +585,7 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
bool success = true;
switch (frame_class) {
#if FRAME_QUAD
#if AP_MOTORS_FRAME_QUAD_ENABLED
case MOTOR_FRAME_QUAD:
_frame_class_string = "QUAD";
_mav_type = MAV_TYPE_QUADROTOR;
@ -783,8 +783,8 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
break;
}
break; // quad
#endif //FRAME_QUAD
#if FRAME_HEXA
#endif //AP_MOTORS_FRAME_QUAD_ENABLED
#if AP_MOTORS_FRAME_HEXA_ENABLED
case MOTOR_FRAME_HEXA:
_frame_class_string = "HEXA";
_mav_type = MAV_TYPE_HEXAROTOR;
@ -862,8 +862,8 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
break;
}
break;
#endif //FRAME_HEXA
#if FRAME_OCTA
#endif //AP_MOTORS_FRAME_HEXA_ENABLED
#if AP_MOTORS_FRAME_OCTA_ENABLED
case MOTOR_FRAME_OCTA:
_frame_class_string = "OCTA";
_mav_type = MAV_TYPE_OCTOROTOR;
@ -981,8 +981,8 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
break;
} // octa frame type
break;
#endif //FRAME_OCTA
#if FRAME_OCTAQUAD
#endif //AP_MOTORS_FRAME_OCTA_ENABLED
#if AP_MOTORS_FRAME_OCTAQUAD_ENABLED
case MOTOR_FRAME_OCTAQUAD:
_mav_type = MAV_TYPE_OCTOROTOR;
_frame_class_string = "OCTAQUAD";
@ -1069,8 +1069,8 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
break;
}
break;
#endif //FRAME_OCTAQUAD
#if FRAME_DODECAHEXA
#endif //AP_MOTORS_FRAME_OCTAQUAD_ENABLED
#if AP_MOTORS_FRAME_DODECAHEXA_ENABLED
case MOTOR_FRAME_DODECAHEXA: {
_mav_type = MAV_TYPE_DODECAROTOR;
_frame_class_string = "DODECAHEXA";
@ -1120,8 +1120,8 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
break;
}}
break;
#endif //FRAME_DODECAHEXA
#if FRAME_Y6
#endif //AP_MOTORS_FRAME_DODECAHEXA_ENABLED
#if AP_MOTORS_FRAME_Y6_ENABLED
case MOTOR_FRAME_Y6:
_mav_type = MAV_TYPE_HEXAROTOR;
_frame_class_string = "Y6";
@ -1169,8 +1169,8 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
}
}
break;
#endif //FRAME_Y6
#if FRAME_DECA
#endif //AP_MOTORS_FRAME_Y6_ENABLED
#if AP_MOTORS_FRAME_DECA_ENABLED
case MOTOR_FRAME_DECA:
_mav_type = MAV_TYPE_DECAROTOR;
_frame_class_string = "DECA";
@ -1215,7 +1215,7 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty
break;
}
break;
#endif //FRAME_DECA
#endif //AP_MOTORS_FRAME_DECA_ENABLED
default:
// matrix doesn't support the configured class
_frame_class_string = "UNSUPPORTED";

View File

@ -22,26 +22,26 @@
#define AP_MOTORS_MAX_NUM_MOTORS 12
#ifndef FRAME_QUAD
#define FRAME_QUAD 1
#ifndef AP_MOTORS_FRAME_QUAD_ENABLED
#define AP_MOTORS_FRAME_QUAD_ENABLED 1
#endif
#ifndef FRAME_HEXA
#define FRAME_HEXA 1
#ifndef AP_MOTORS_FRAME_HEXA_ENABLED
#define AP_MOTORS_FRAME_HEXA_ENABLED 1
#endif
#ifndef FRAME_OCTA
#define FRAME_OCTA 1
#ifndef AP_MOTORS_FRAME_OCTA_ENABLED
#define AP_MOTORS_FRAME_OCTA_ENABLED 1
#endif
#ifndef FRAME_DECA
#define FRAME_DECA 1
#ifndef AP_MOTORS_FRAME_DECA_ENABLED
#define AP_MOTORS_FRAME_DECA_ENABLED 1
#endif
#ifndef FRAME_DODECAHEXA
#define FRAME_DODECAHEXA 1
#ifndef AP_MOTORS_FRAME_DODECAHEXA_ENABLED
#define AP_MOTORS_FRAME_DODECAHEXA_ENABLED 1
#endif
#ifndef FRAME_Y6
#define FRAME_Y6 1
#ifndef AP_MOTORS_FRAME_Y6_ENABLED
#define AP_MOTORS_FRAME_Y6_ENABLED 1
#endif
#ifndef FRAME_OCTAQUAD
#define FRAME_OCTAQUAD 1
#ifndef AP_MOTORS_FRAME_OCTAQUAD_ENABLED
#define AP_MOTORS_FRAME_OCTAQUAD_ENABLED 1
#endif
// motor update rate