|
|
|
@ -1,4 +1,4 @@
@@ -1,4 +1,4 @@
|
|
|
|
|
#if ENABLE_SCRIPTING |
|
|
|
|
#if AP_SCRIPTING_ENABLED |
|
|
|
|
|
|
|
|
|
#include "AC_AttitudeControl_Multi_6DoF.h" |
|
|
|
|
#include <AP_HAL/AP_HAL.h> |
|
|
|
@ -160,4 +160,4 @@ void AC_AttitudeControl_Multi_6DoF::input_quaternion(Quaternion attitude_desired
@@ -160,4 +160,4 @@ void AC_AttitudeControl_Multi_6DoF::input_quaternion(Quaternion attitude_desired
|
|
|
|
|
|
|
|
|
|
AC_AttitudeControl_Multi_6DoF *AC_AttitudeControl_Multi_6DoF::_singleton = nullptr; |
|
|
|
|
|
|
|
|
|
#endif // ENABLE_SCRIPTING
|
|
|
|
|
#endif // AP_SCRIPTING_ENABLED
|
|
|
|
|