mirror of https://github.com/ArduPilot/ardupilot
Copter: Make mode flowhold a build option via MODE_FLOWHOLD_ENABLED
This commit is contained in:
parent
5b5cdfa1f1
commit
58cb4cbfb1
|
@ -983,7 +983,7 @@ private:
|
|||
#if MODE_SMARTRTL_ENABLED == ENABLED
|
||||
ModeSmartRTL mode_smartrtl;
|
||||
#endif
|
||||
#if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED
|
||||
#if MODE_FLOWHOLD_ENABLED == ENABLED
|
||||
ModeFlowHold mode_flowhold;
|
||||
#endif
|
||||
#if MODE_ZIGZAG_ENABLED == ENABLED
|
||||
|
|
|
@ -885,7 +885,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
// @User: Advanced
|
||||
AP_GROUPINFO("LAND_ALT_LOW", 25, ParametersG2, land_alt_low, 1000),
|
||||
|
||||
#if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED
|
||||
#if MODE_FLOWHOLD_ENABLED == ENABLED
|
||||
// @Group: FHLD
|
||||
// @Path: mode_flowhold.cpp
|
||||
AP_SUBGROUPPTR(mode_flowhold_ptr, "FHLD", 26, ParametersG2, ModeFlowHold),
|
||||
|
@ -1160,7 +1160,7 @@ ParametersG2::ParametersG2(void)
|
|||
#if MODE_SMARTRTL_ENABLED == ENABLED
|
||||
,smart_rtl()
|
||||
#endif
|
||||
#if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED
|
||||
#if MODE_FLOWHOLD_ENABLED == ENABLED
|
||||
,mode_flowhold_ptr(&copter.mode_flowhold)
|
||||
#endif
|
||||
#if MODE_FOLLOW_ENABLED == ENABLED
|
||||
|
|
|
@ -319,6 +319,12 @@
|
|||
# define MODE_TURTLE_ENABLED !HAL_MINIMIZE_FEATURES && !defined(DISABLE_DSHOT) && FRAME_CONFIG != HELI_FRAME
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Flowhold - use optical flow to hover in place
|
||||
#ifndef MODE_FLOWHOLD_ENABLED
|
||||
# define MODE_FLOWHOLD_ENABLED !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
|
|
@ -139,7 +139,7 @@ Mode *Copter::mode_from_mode_num(const Mode::Number mode)
|
|||
break;
|
||||
#endif
|
||||
|
||||
#if AP_OPTICALFLOW_ENABLED
|
||||
#if MODE_FLOWHOLD_ENABLED == ENABLED
|
||||
case Mode::Number::FLOWHOLD:
|
||||
ret = (Mode *)g2.mode_flowhold_ptr;
|
||||
break;
|
||||
|
|
|
@ -836,7 +836,7 @@ private:
|
|||
};
|
||||
|
||||
|
||||
#if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED
|
||||
#if MODE_FLOWHOLD_ENABLED == ENABLED
|
||||
/*
|
||||
class to support FLOWHOLD mode, which is a position hold mode using
|
||||
optical flow directly, avoiding the need for a rangefinder
|
||||
|
@ -922,7 +922,7 @@ private:
|
|||
// last time there was significant stick input
|
||||
uint32_t last_stick_input_ms;
|
||||
};
|
||||
#endif // AP_OPTICALFLOW_ENABLED
|
||||
#endif // MODE_FLOWHOLD_ENABLED
|
||||
|
||||
|
||||
class ModeGuided : public Mode {
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
#include "Copter.h"
|
||||
#include <utility>
|
||||
|
||||
#if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED
|
||||
#if MODE_FLOWHOLD_ENABLED == ENABLED
|
||||
|
||||
/*
|
||||
implement FLOWHOLD mode, for position hold using optical flow
|
||||
|
@ -509,4 +509,4 @@ void ModeFlowHold::update_height_estimate(void)
|
|||
last_ins_height = ins_height;
|
||||
}
|
||||
|
||||
#endif // AP_OPTICALFLOW_ENABLED
|
||||
#endif // MODE_FLOWHOLD_ENABLED
|
||||
|
|
Loading…
Reference in New Issue