mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-12 19:03:58 -04:00
Copter: optflow parameters moved to optflow class
This commit is contained in:
parent
4b0548973a
commit
765ce2f6ca
@ -121,6 +121,7 @@ public:
|
|||||||
k_param_terrain,
|
k_param_terrain,
|
||||||
k_param_acro_expo,
|
k_param_acro_expo,
|
||||||
k_param_throttle_deadzone, // 57
|
k_param_throttle_deadzone, // 57
|
||||||
|
k_param_optflow, // 54 - optflow object
|
||||||
|
|
||||||
// 65: AP_Limits Library
|
// 65: AP_Limits Library
|
||||||
k_param_limits = 65, // deprecated - remove
|
k_param_limits = 65, // deprecated - remove
|
||||||
@ -191,7 +192,7 @@ public:
|
|||||||
k_param_compass,
|
k_param_compass,
|
||||||
k_param_sonar_enabled_old, // deprecated
|
k_param_sonar_enabled_old, // deprecated
|
||||||
k_param_frame_orientation,
|
k_param_frame_orientation,
|
||||||
k_param_optflow_enabled,
|
k_param_optflow_enabled, // deprecated
|
||||||
k_param_fs_batt_voltage,
|
k_param_fs_batt_voltage,
|
||||||
k_param_ch7_option,
|
k_param_ch7_option,
|
||||||
k_param_auto_slew_rate, // deprecated - can be deleted
|
k_param_auto_slew_rate, // deprecated - can be deleted
|
||||||
@ -339,7 +340,6 @@ public:
|
|||||||
AP_Int16 gps_hdop_good; // GPS Hdop value at or below this value represent a good position
|
AP_Int16 gps_hdop_good; // GPS Hdop value at or below this value represent a good position
|
||||||
|
|
||||||
AP_Int8 compass_enabled;
|
AP_Int8 compass_enabled;
|
||||||
AP_Int8 optflow_enabled;
|
|
||||||
AP_Int8 super_simple;
|
AP_Int8 super_simple;
|
||||||
AP_Int16 rtl_alt_final;
|
AP_Int16 rtl_alt_final;
|
||||||
|
|
||||||
|
@ -164,13 +164,6 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(compass_enabled, "MAG_ENABLE", MAGNETOMETER),
|
GSCALAR(compass_enabled, "MAG_ENABLE", MAGNETOMETER),
|
||||||
|
|
||||||
// @Param: FLOW_ENABLE
|
|
||||||
// @DisplayName: Optical Flow enable/disable
|
|
||||||
// @Description: Setting this to Enabled(1) will enable optical flow. Setting this to Disabled(0) will disable optical flow
|
|
||||||
// @Values: 0:Disabled,1:Enabled
|
|
||||||
// @User: Standard
|
|
||||||
GSCALAR(optflow_enabled, "FLOW_ENABLE", DISABLED),
|
|
||||||
|
|
||||||
// @Param: SUPER_SIMPLE
|
// @Param: SUPER_SIMPLE
|
||||||
// @DisplayName: Super Simple Mode
|
// @DisplayName: Super Simple Mode
|
||||||
// @Description: Bitmask to enable Super Simple mode for some flight modes. Setting this to Disabled(0) will disable Super Simple Mode
|
// @Description: Bitmask to enable Super Simple mode for some flight modes. Setting this to Disabled(0) will disable Super Simple Mode
|
||||||
@ -1115,6 +1108,12 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
GOBJECT(terrain, "TERRAIN_", AP_Terrain),
|
GOBJECT(terrain, "TERRAIN_", AP_Terrain),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if OPTFLOW == ENABLED
|
||||||
|
// @Group: FLOW
|
||||||
|
// @Path: ../libraries/AP_OpticalFlow/OptFlow.cpp
|
||||||
|
GOBJECT(optflow, "FLOW", OpticalFlow),
|
||||||
|
#endif
|
||||||
|
|
||||||
AP_VAREND
|
AP_VAREND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user