Copter: make flowhold mode conditional

reduces build size on px4-v2 by 4k
This commit is contained in:
Andrew Tridgell 2018-02-12 14:26:09 +11:00 committed by Randy Mackay
parent 7be15cab45
commit 7938bd08bb
4 changed files with 5 additions and 5 deletions

View File

@ -968,7 +968,7 @@ private:
ModeThrow mode_throw;
ModeGuidedNoGPS mode_guided_nogps;
ModeSmartRTL mode_smartrtl;
#if OPTFLOW == ENABLED
#if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED
ModeFlowHold mode_flowhold;
#endif

View File

@ -972,7 +972,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Advanced
AP_GROUPINFO("LAND_ALT_LOW", 25, ParametersG2, land_alt_low, 1000),
#if OPTFLOW == ENABLED
#if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED
// @Group: FHLD
// @Path: mode_flowhold.cpp
AP_SUBGROUPPTR(mode_flowhold_ptr, "FHLD", 26, ParametersG2, Copter::ModeFlowHold),
@ -995,7 +995,7 @@ ParametersG2::ParametersG2(void)
#endif
,smart_rtl(copter.ahrs)
,temp_calibration(copter.barometer, copter.ins)
#if OPTFLOW == ENABLED
#if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED
,mode_flowhold_ptr(&copter.mode_flowhold)
#endif
{

View File

@ -583,7 +583,7 @@ private:
};
#if OPTFLOW == ENABLED
#if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED
/*
class to support FLOWHOLD mode, which is a position hold mode using
optical flow directly, avoiding the need for a rangefinder

View File

@ -1,7 +1,7 @@
#include "Copter.h"
#include <utility>
#if OPTFLOW == ENABLED
#if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED
/*
implement FLOWHOLD mode, for position hold using opttical flow