ArduCopter: create and use AP_OPTICALFLOW_ENABLED

Including a define for each backend.
This commit is contained in:
Peter Barker 2021-12-24 16:47:22 +11:00 committed by Andrew Tridgell
parent d2693e4276
commit 285d752143
13 changed files with 18 additions and 27 deletions

View File

@ -15,7 +15,6 @@
//#define AC_OAPATHPLANNER_ENABLED DISABLED // disable path planning around obstacles //#define AC_OAPATHPLANNER_ENABLED DISABLED // disable path planning around obstacles
//#define PARACHUTE DISABLED // disable parachute release to save 1k of flash //#define PARACHUTE DISABLED // disable parachute release to save 1k of flash
//#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands //#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
//#define OPTFLOW DISABLED // disable optical flow sensor to save 5K of flash space
//#define FRSKY_TELEM_ENABLED DISABLED // disable FRSky telemetry //#define FRSKY_TELEM_ENABLED DISABLED // disable FRSky telemetry
//#define PRECISION_LANDING DISABLED // disable precision landing using companion computer or IRLock sensor //#define PRECISION_LANDING DISABLED // disable precision landing using companion computer or IRLock sensor
//#define BEACON_ENABLED DISABLED // disable beacon support //#define BEACON_ENABLED DISABLED // disable beacon support

View File

@ -113,7 +113,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(rc_loop, 100, 130, 3), SCHED_TASK(rc_loop, 100, 130, 3),
SCHED_TASK(throttle_loop, 50, 75, 6), SCHED_TASK(throttle_loop, 50, 75, 6),
SCHED_TASK_CLASS(AP_GPS, &copter.gps, update, 50, 200, 9), SCHED_TASK_CLASS(AP_GPS, &copter.gps, update, 50, 200, 9),
#if OPTFLOW == ENABLED #if AP_OPTICALFLOW_ENABLED
SCHED_TASK_CLASS(OpticalFlow, &copter.optflow, update, 200, 160, 12), SCHED_TASK_CLASS(OpticalFlow, &copter.optflow, update, 200, 160, 12),
#endif #endif
SCHED_TASK(update_batt_compass, 10, 120, 15), SCHED_TASK(update_batt_compass, 10, 120, 15),

View File

@ -124,9 +124,7 @@
#if AP_TERRAIN_AVAILABLE #if AP_TERRAIN_AVAILABLE
# include <AP_Terrain/AP_Terrain.h> # include <AP_Terrain/AP_Terrain.h>
#endif #endif
#if OPTFLOW == ENABLED
# include <AP_OpticalFlow/AP_OpticalFlow.h> # include <AP_OpticalFlow/AP_OpticalFlow.h>
#endif
#if RANGEFINDER_ENABLED == ENABLED #if RANGEFINDER_ENABLED == ENABLED
# include <AP_RangeFinder/AP_RangeFinder.h> # include <AP_RangeFinder/AP_RangeFinder.h>
#endif #endif
@ -307,7 +305,7 @@ private:
AP_Arming_Copter arming; AP_Arming_Copter arming;
// Optical flow sensor // Optical flow sensor
#if OPTFLOW == ENABLED #if AP_OPTICALFLOW_ENABLED
OpticalFlow optflow; OpticalFlow optflow;
#endif #endif
@ -975,7 +973,7 @@ private:
#if MODE_SMARTRTL_ENABLED == ENABLED #if MODE_SMARTRTL_ENABLED == ENABLED
ModeSmartRTL mode_smartrtl; ModeSmartRTL mode_smartrtl;
#endif #endif
#if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED #if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED
ModeFlowHold mode_flowhold; ModeFlowHold mode_flowhold;
#endif #endif
#if MODE_ZIGZAG_ENABLED == ENABLED #if MODE_ZIGZAG_ENABLED == ENABLED

View File

@ -114,7 +114,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
} }
#endif #endif
#if OPTFLOW == ENABLED #if AP_OPTICALFLOW_ENABLED
const OpticalFlow *optflow = AP::opticalflow(); const OpticalFlow *optflow = AP::opticalflow();
if (optflow && optflow->enabled()) { if (optflow && optflow->enabled()) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW; control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;

View File

@ -695,7 +695,7 @@ const AP_Param::Info Copter::var_info[] = {
GOBJECT(terrain, "TERRAIN_", AP_Terrain), GOBJECT(terrain, "TERRAIN_", AP_Terrain),
#endif #endif
#if OPTFLOW == ENABLED #if AP_OPTICALFLOW_ENABLED
// @Group: FLOW // @Group: FLOW
// @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp // @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp
GOBJECT(optflow, "FLOW", OpticalFlow), GOBJECT(optflow, "FLOW", OpticalFlow),
@ -915,7 +915,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Advanced // @User: Advanced
AP_GROUPINFO("LAND_ALT_LOW", 25, ParametersG2, land_alt_low, 1000), AP_GROUPINFO("LAND_ALT_LOW", 25, ParametersG2, land_alt_low, 1000),
#if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED #if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED
// @Group: FHLD // @Group: FHLD
// @Path: mode_flowhold.cpp // @Path: mode_flowhold.cpp
AP_SUBGROUPPTR(mode_flowhold_ptr, "FHLD", 26, ParametersG2, ModeFlowHold), AP_SUBGROUPPTR(mode_flowhold_ptr, "FHLD", 26, ParametersG2, ModeFlowHold),
@ -1131,7 +1131,7 @@ ParametersG2::ParametersG2(void)
#if MODE_SMARTRTL_ENABLED == ENABLED #if MODE_SMARTRTL_ENABLED == ENABLED
,smart_rtl() ,smart_rtl()
#endif #endif
#if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED #if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED
,mode_flowhold_ptr(&copter.mode_flowhold) ,mode_flowhold_ptr(&copter.mode_flowhold)
#endif #endif
#if MODE_FOLLOW_ENABLED == ENABLED #if MODE_FOLLOW_ENABLED == ENABLED

View File

@ -574,7 +574,7 @@ public:
ToyMode toy_mode; ToyMode toy_mode;
#endif #endif
#if OPTFLOW == ENABLED #if AP_OPTICALFLOW_ENABLED
// we need a pointer to the mode for the G2 table // we need a pointer to the mode for the G2 table
void *mode_flowhold_ptr; void *mode_flowhold_ptr;
#endif #endif

View File

@ -496,7 +496,7 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi
break; break;
case AUX_FUNC::FLOWHOLD: case AUX_FUNC::FLOWHOLD:
#if OPTFLOW == ENABLED #if AP_OPTICALFLOW_ENABLED
do_aux_function_change_mode(Mode::Number::FLOWHOLD, ch_flag); do_aux_function_change_mode(Mode::Number::FLOWHOLD, ch_flag);
#endif #endif
break; break;

View File

@ -168,12 +168,6 @@
# define EKF_ORIGIN_MAX_ALT_KM 50 // EKF origin and home must be within 50km vertically # define EKF_ORIGIN_MAX_ALT_KM 50 // EKF origin and home must be within 50km vertically
#endif #endif
//////////////////////////////////////////////////////////////////////////////
// OPTICAL_FLOW
#ifndef OPTFLOW
# define OPTFLOW ENABLED
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Auto Tuning // Auto Tuning
#ifndef AUTOTUNE_ENABLED #ifndef AUTOTUNE_ENABLED

View File

@ -132,7 +132,7 @@ bool Copter::ekf_over_threshold()
} }
bool optflow_healthy = false; bool optflow_healthy = false;
#if OPTFLOW == ENABLED #if AP_OPTICALFLOW_ENABLED
optflow_healthy = optflow.healthy(); optflow_healthy = optflow.healthy();
#endif #endif
if (!optflow_healthy && (vel_variance >= (2.0f * g.fs_ekf_thresh))) { if (!optflow_healthy && (vel_variance >= (2.0f * g.fs_ekf_thresh))) {

View File

@ -139,7 +139,7 @@ Mode *Copter::mode_from_mode_num(const Mode::Number mode)
break; break;
#endif #endif
#if OPTFLOW == ENABLED #if AP_OPTICALFLOW_ENABLED
case Mode::Number::FLOWHOLD: case Mode::Number::FLOWHOLD:
ret = (Mode *)g2.mode_flowhold_ptr; ret = (Mode *)g2.mode_flowhold_ptr;
break; break;

View File

@ -770,7 +770,7 @@ private:
}; };
#if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED #if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED
/* /*
class to support FLOWHOLD mode, which is a position hold mode using class to support FLOWHOLD mode, which is a position hold mode using
optical flow directly, avoiding the need for a rangefinder optical flow directly, avoiding the need for a rangefinder
@ -856,7 +856,7 @@ private:
// last time there was significant stick input // last time there was significant stick input
uint32_t last_stick_input_ms; uint32_t last_stick_input_ms;
}; };
#endif // OPTFLOW #endif // AP_OPTICALFLOW_ENABLED
class ModeGuided : public Mode { class ModeGuided : public Mode {

View File

@ -1,7 +1,7 @@
#include "Copter.h" #include "Copter.h"
#include <utility> #include <utility>
#if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED #if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED
/* /*
implement FLOWHOLD mode, for position hold using optical flow implement FLOWHOLD mode, for position hold using optical flow
@ -509,4 +509,4 @@ void ModeFlowHold::update_height_estimate(void)
last_ins_height = ins_height; last_ins_height = ins_height;
} }
#endif // OPTFLOW == ENABLED #endif // AP_OPTICALFLOW_ENABLED

View File

@ -117,10 +117,10 @@ void Copter::init_ardupilot()
attitude_control->parameter_sanity_check(); attitude_control->parameter_sanity_check();
#if OPTFLOW == ENABLED #if AP_OPTICALFLOW_ENABLED
// initialise optical flow sensor // initialise optical flow sensor
optflow.init(MASK_LOG_OPTFLOW); optflow.init(MASK_LOG_OPTFLOW);
#endif // OPTFLOW == ENABLED #endif // AP_OPTICALFLOW_ENABLED
#if HAL_MOUNT_ENABLED #if HAL_MOUNT_ENABLED
// initialise camera mount // initialise camera mount
@ -341,7 +341,7 @@ bool Copter::ekf_has_relative_position() const
// return immediately if neither optflow nor visual odometry is enabled // return immediately if neither optflow nor visual odometry is enabled
bool enabled = false; bool enabled = false;
#if OPTFLOW == ENABLED #if AP_OPTICALFLOW_ENABLED
if (optflow.enabled()) { if (optflow.enabled()) {
enabled = true; enabled = true;
} }