mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: Add APM_BUILD_Heli
This commit is contained in:
parent
765f6b69fa
commit
94b97313be
@ -187,7 +187,7 @@ AP_AHRS::AP_AHRS(uint8_t flags) :
|
|||||||
// load default values from var_info table
|
// load default values from var_info table
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
|
|
||||||
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
|
#if APM_BUILD_COPTER_OR_HELI() || APM_BUILD_TYPE(APM_BUILD_ArduSub)
|
||||||
// Copter and Sub force the use of EKF
|
// Copter and Sub force the use of EKF
|
||||||
_ekf_flags |= AP_AHRS::FLAG_ALWAYS_USE_EKF;
|
_ekf_flags |= AP_AHRS::FLAG_ALWAYS_USE_EKF;
|
||||||
#endif
|
#endif
|
||||||
|
@ -611,7 +611,7 @@ Vector3f AP_AHRS_DCM::ra_delayed(uint8_t instance, const Vector3f &ra)
|
|||||||
*/
|
*/
|
||||||
bool AP_AHRS_DCM::should_correct_centrifugal() const
|
bool AP_AHRS_DCM::should_correct_centrifugal() const
|
||||||
{
|
{
|
||||||
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduSub) || APM_BUILD_TYPE(APM_BUILD_Blimp)
|
#if APM_BUILD_COPTER_OR_HELI() || APM_BUILD_TYPE(APM_BUILD_ArduSub) || APM_BUILD_TYPE(APM_BUILD_Blimp)
|
||||||
return hal.util->get_soft_armed();
|
return hal.util->get_soft_armed();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user