mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Copter: make flowhold mode conditional
reduces build size on px4-v2 by 4k
This commit is contained in:
parent
7be15cab45
commit
7938bd08bb
@ -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
|
||||
|
||||
|
@ -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
|
||||
{
|
||||
|
@ -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
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user