mirror of https://github.com/ArduPilot/ardupilot
AP_Vehicle: add and use AP_CUSTOMROTATIONS_ENABLED
also add to build_options.py
This commit is contained in:
parent
cf9c85d295
commit
bff8688ac9
|
@ -94,9 +94,11 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = {
|
||||||
AP_SUBGROUPINFO(airspeed, "ARSPD", 10, AP_Vehicle, AP_Airspeed),
|
AP_SUBGROUPINFO(airspeed, "ARSPD", 10, AP_Vehicle, AP_Airspeed),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AP_CUSTOMROTATIONS_ENABLED
|
||||||
// @Group: CUST_ROT
|
// @Group: CUST_ROT
|
||||||
// @Path: ../AP_CustomRotations/AP_CustomRotations.cpp
|
// @Path: ../AP_CustomRotations/AP_CustomRotations.cpp
|
||||||
AP_SUBGROUPINFO(custom_rotations, "CUST_ROT", 11, AP_Vehicle, AP_CustomRotations),
|
AP_SUBGROUPINFO(custom_rotations, "CUST_ROT", 11, AP_Vehicle, AP_CustomRotations),
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAL_WITH_ESC_TELEM
|
#if HAL_WITH_ESC_TELEM
|
||||||
// @Group: ESC_TLM
|
// @Group: ESC_TLM
|
||||||
|
@ -488,7 +490,9 @@ void AP_Vehicle::setup()
|
||||||
fence.init();
|
fence.init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AP_CUSTOMROTATIONS_ENABLED
|
||||||
custom_rotations.init();
|
custom_rotations.init();
|
||||||
|
#endif
|
||||||
|
|
||||||
#if AP_FILTER_ENABLED
|
#if AP_FILTER_ENABLED
|
||||||
filters.init();
|
filters.init();
|
||||||
|
|
|
@ -528,7 +528,10 @@ private:
|
||||||
|
|
||||||
uint32_t _last_internal_errors; // backup of AP_InternalError::internal_errors bitmask
|
uint32_t _last_internal_errors; // backup of AP_InternalError::internal_errors bitmask
|
||||||
|
|
||||||
|
#if AP_CUSTOMROTATIONS_ENABLED
|
||||||
AP_CustomRotations custom_rotations;
|
AP_CustomRotations custom_rotations;
|
||||||
|
#endif
|
||||||
|
|
||||||
#if AP_FILTER_ENABLED
|
#if AP_FILTER_ENABLED
|
||||||
AP_Filters filters;
|
AP_Filters filters;
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue