mirror of https://github.com/ArduPilot/ardupilot
AP_CustomRotations: add and use AP_CUSTOMROTATIONS_ENABLED
also add to build_options.py
This commit is contained in:
parent
093deed610
commit
2f30fa2f56
|
@ -1,3 +1,7 @@
|
||||||
|
#include "AP_CustomRotations_config.h"
|
||||||
|
|
||||||
|
#if AP_CUSTOMROTATIONS_ENABLED
|
||||||
|
|
||||||
#include "AP_CustomRotations.h"
|
#include "AP_CustomRotations.h"
|
||||||
|
|
||||||
#include <AP_InternalError/AP_InternalError.h>
|
#include <AP_InternalError/AP_InternalError.h>
|
||||||
|
@ -5,8 +9,6 @@
|
||||||
#include <AP_HAL/AP_HAL_Boards.h>
|
#include <AP_HAL/AP_HAL_Boards.h>
|
||||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
|
|
||||||
#if !APM_BUILD_TYPE(APM_BUILD_AP_Periph)
|
|
||||||
|
|
||||||
const AP_Param::GroupInfo AP_CustomRotations::var_info[] = {
|
const AP_Param::GroupInfo AP_CustomRotations::var_info[] = {
|
||||||
|
|
||||||
// @Param: _ENABLE
|
// @Param: _ENABLE
|
||||||
|
@ -156,4 +158,4 @@ AP_CustomRotations &custom_rotations()
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // !APM_BUILD_TYPE(APM_BUILD_AP_Periph)
|
#endif // AP_CUSTOMROTATIONS_ENABLED
|
||||||
|
|
|
@ -14,6 +14,10 @@
|
||||||
*/
|
*/
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "AP_CustomRotations_config.h"
|
||||||
|
|
||||||
|
#if AP_CUSTOMROTATIONS_ENABLED
|
||||||
|
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
|
|
||||||
|
@ -80,3 +84,5 @@ namespace AP {
|
||||||
AP_CustomRotations &custom_rotations();
|
AP_CustomRotations &custom_rotations();
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
#endif // AP_CUSTOMROTATIONS_ENABLED
|
||||||
|
|
|
@ -0,0 +1,7 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <AP_HAL/AP_HAL_Boards.h>
|
||||||
|
|
||||||
|
#ifndef AP_CUSTOMROTATIONS_ENABLED
|
||||||
|
#define AP_CUSTOMROTATIONS_ENABLED 1
|
||||||
|
#endif
|
|
@ -1,7 +1,8 @@
|
||||||
#include "AP_CustomRotations.h"
|
#include "AP_CustomRotations_config.h"
|
||||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
|
||||||
|
|
||||||
#if !APM_BUILD_TYPE(APM_BUILD_AP_Periph)
|
#if AP_CUSTOMROTATIONS_ENABLED
|
||||||
|
|
||||||
|
#include "AP_CustomRotations.h"
|
||||||
|
|
||||||
const AP_Param::GroupInfo AP_CustomRotation_params::var_info[] = {
|
const AP_Param::GroupInfo AP_CustomRotation_params::var_info[] = {
|
||||||
|
|
||||||
|
@ -33,4 +34,4 @@ AP_CustomRotation_params::AP_CustomRotation_params() {
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // !APM_BUILD_TYPE(APM_BUILD_AP_Periph)
|
#endif // AP_CUSTOMROTATIONS_ENABLED
|
||||||
|
|
Loading…
Reference in New Issue