mirror of https://github.com/ArduPilot/ardupilot
AP_Math: add and use AP_CUSTOMROTATIONS_ENABLED
also add to build_options.py
This commit is contained in:
parent
077dd82bdc
commit
cf9c85d295
|
@ -381,8 +381,8 @@ void QuaternionT<T>::from_rotation(enum Rotation rotation)
|
||||||
|
|
||||||
case ROTATION_CUSTOM_1:
|
case ROTATION_CUSTOM_1:
|
||||||
case ROTATION_CUSTOM_2:
|
case ROTATION_CUSTOM_2:
|
||||||
#if !APM_BUILD_TYPE(APM_BUILD_AP_Periph)
|
#if AP_CUSTOMROTATIONS_ENABLED
|
||||||
// Do not support custom rotations on Periph
|
// custom rotations not supported on eg. Periph by default
|
||||||
AP::custom_rotations().from_rotation(rotation, *this);
|
AP::custom_rotations().from_rotation(rotation, *this);
|
||||||
return;
|
return;
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -259,8 +259,8 @@ void Vector3<T>::rotate(enum Rotation rotation)
|
||||||
}
|
}
|
||||||
case ROTATION_CUSTOM_1:
|
case ROTATION_CUSTOM_1:
|
||||||
case ROTATION_CUSTOM_2:
|
case ROTATION_CUSTOM_2:
|
||||||
#if !APM_BUILD_TYPE(APM_BUILD_AP_Periph)
|
#if AP_CUSTOMROTATIONS_ENABLED
|
||||||
// Do not support custom rotations on Periph
|
// custom rotations not supported on eg. Periph by default
|
||||||
AP::custom_rotations().rotate(rotation, *this);
|
AP::custom_rotations().rotate(rotation, *this);
|
||||||
return;
|
return;
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue