ArduCopter: make and use AP_LANDINGGEAR_ENABLED

This commit is contained in:
Peter Barker 2022-10-01 20:21:38 +10:00 committed by Andrew Tridgell
parent 1eb5911bf5
commit c32a11f37a
14 changed files with 19 additions and 26 deletions

View File

@ -31,7 +31,6 @@
//#define MODE_THROW_ENABLED DISABLED // disable throw mode support //#define MODE_THROW_ENABLED DISABLED // disable throw mode support
//#define MODE_ZIGZAG_ENABLED DISABLED // disable zigzag mode support //#define MODE_ZIGZAG_ENABLED DISABLED // disable zigzag mode support
//#define OSD_ENABLED DISABLED // disable on-screen-display support //#define OSD_ENABLED DISABLED // disable on-screen-display support
//#define LANDING_GEAR_ENABLED DISABLED // disable landing gear support
// features below are disabled by default on all boards // features below are disabled by default on all boards
//#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes //#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes

View File

@ -193,7 +193,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(check_vibration, 10, 50, 87), SCHED_TASK(check_vibration, 10, 50, 87),
SCHED_TASK(gpsglitch_check, 10, 50, 90), SCHED_TASK(gpsglitch_check, 10, 50, 90),
SCHED_TASK(takeoff_check, 50, 50, 91), SCHED_TASK(takeoff_check, 50, 50, 91),
#if LANDING_GEAR_ENABLED == ENABLED #if AP_LANDINGGEAR_ENABLED
SCHED_TASK(landinggear_update, 10, 75, 93), SCHED_TASK(landinggear_update, 10, 75, 93),
#endif #endif
SCHED_TASK(standby_update, 100, 75, 96), SCHED_TASK(standby_update, 100, 75, 96),

View File

@ -516,7 +516,7 @@ private:
#endif #endif
// Landing Gear Controller // Landing Gear Controller
#if LANDING_GEAR_ENABLED == ENABLED #if AP_LANDINGGEAR_ENABLED
AP_LandingGear landinggear; AP_LandingGear landinggear;
#endif #endif
@ -804,7 +804,7 @@ private:
void set_land_complete_maybe(bool b); void set_land_complete_maybe(bool b);
void update_throttle_mix(); void update_throttle_mix();
#if LANDING_GEAR_ENABLED == ENABLED #if AP_LANDINGGEAR_ENABLED
// landing_gear.cpp // landing_gear.cpp
void landinggear_update(); void landinggear_update();
#endif #endif

View File

@ -920,7 +920,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
return MAV_RESULT_FAILED; return MAV_RESULT_FAILED;
#endif #endif
#if LANDING_GEAR_ENABLED == ENABLED #if AP_LANDINGGEAR_ENABLED
case MAV_CMD_AIRFRAME_CONFIGURATION: { case MAV_CMD_AIRFRAME_CONFIGURATION: {
// Param 1: Select which gear, not used in ArduPilot // Param 1: Select which gear, not used in ArduPilot
// Param 2: 0 = Deploy, 1 = Retract // Param 2: 0 = Deploy, 1 = Retract

View File

@ -472,7 +472,7 @@ const AP_Param::Info Copter::var_info[] = {
GOBJECT(parachute, "CHUTE_", AP_Parachute), GOBJECT(parachute, "CHUTE_", AP_Parachute),
#endif #endif
#if LANDING_GEAR_ENABLED == ENABLED #if AP_LANDINGGEAR_ENABLED
// @Group: LGR_ // @Group: LGR_
// @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp // @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp
GOBJECT(landinggear, "LGR_", AP_LandingGear), GOBJECT(landinggear, "LGR_", AP_LandingGear),
@ -1292,7 +1292,7 @@ void Copter::load_parameters(void)
AP_Param::load_all(); AP_Param::load_all();
AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table)); AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));
#if LANDING_GEAR_ENABLED == ENABLED #if AP_LANDINGGEAR_ENABLED
// convert landing gear parameters // convert landing gear parameters
// PARAMETER_CONVERSION - Added: Nov-2018 // PARAMETER_CONVERSION - Added: Nov-2018
convert_lgr_parameters(); convert_lgr_parameters();
@ -1559,7 +1559,7 @@ void Copter::convert_prx_parameters()
} }
#endif #endif
#if LANDING_GEAR_ENABLED == ENABLED #if AP_LANDINGGEAR_ENABLED
/* /*
convert landing gear parameters convert landing gear parameters
*/ */

View File

@ -298,12 +298,6 @@
# define BEACON_ENABLED !HAL_MINIMIZE_FEATURES # define BEACON_ENABLED !HAL_MINIMIZE_FEATURES
#endif #endif
//////////////////////////////////////////////////////////////////////////////
// Landing Gear support
#ifndef LANDING_GEAR_ENABLED
#define LANDING_GEAR_ENABLED ENABLED
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// RADIO CONFIGURATION // RADIO CONFIGURATION
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////

View File

@ -337,7 +337,7 @@ void Copter::parachute_release()
// release parachute // release parachute
parachute.release(); parachute.release();
#if LANDING_GEAR_ENABLED == ENABLED #if AP_LANDINGGEAR_ENABLED
// deploy landing gear // deploy landing gear
landinggear.set_position(AP_LandingGear::LandingGear_Deploy); landinggear.set_position(AP_LandingGear::LandingGear_Deploy);
#endif #endif

View File

@ -88,7 +88,7 @@ void Copter::update_land_detector()
#endif #endif
uint8_t land_detector_scalar = 1; uint8_t land_detector_scalar = 1;
#if LANDING_GEAR_ENABLED == ENABLED #if AP_LANDINGGEAR_ENABLED
if (landinggear.get_wow_state() != AP_LandingGear::LG_WOW_UNKNOWN) { if (landinggear.get_wow_state() != AP_LandingGear::LG_WOW_UNKNOWN) {
// we have a WoW sensor so lets loosen the strictness of the landing detector // we have a WoW sensor so lets loosen the strictness of the landing detector
land_detector_scalar = 2; land_detector_scalar = 2;
@ -105,7 +105,7 @@ void Copter::update_land_detector()
bool rangefinder_check = (!rangefinder_alt_ok() || rangefinder_state.alt_cm_filt.get() < LAND_RANGEFINDER_MIN_ALT_CM); bool rangefinder_check = (!rangefinder_alt_ok() || rangefinder_state.alt_cm_filt.get() < LAND_RANGEFINDER_MIN_ALT_CM);
// if we have weight on wheels (WoW) or ambiguous unknown. never no WoW // if we have weight on wheels (WoW) or ambiguous unknown. never no WoW
#if LANDING_GEAR_ENABLED == ENABLED #if AP_LANDINGGEAR_ENABLED
const bool WoW_check = (landinggear.get_wow_state() == AP_LandingGear::LG_WOW || landinggear.get_wow_state() == AP_LandingGear::LG_WOW_UNKNOWN); const bool WoW_check = (landinggear.get_wow_state() == AP_LandingGear::LG_WOW || landinggear.get_wow_state() == AP_LandingGear::LG_WOW_UNKNOWN);
#else #else
const bool WoW_check = true; const bool WoW_check = true;

View File

@ -1,6 +1,6 @@
#include "Copter.h" #include "Copter.h"
#if LANDING_GEAR_ENABLED == ENABLED #if AP_LANDINGGEAR_ENABLED
// Run landing gear controller at 10Hz // Run landing gear controller at 10Hz
void Copter::landinggear_update() void Copter::landinggear_update()
@ -35,4 +35,4 @@ void Copter::landinggear_update()
landinggear.update(height_cm * 0.01f); // convert cm->m for update call landinggear.update(height_cm * 0.01f); // convert cm->m for update call
} }
#endif // LANDING_GEAR_ENABLED #endif // AP_LANDINGGEAR_ENABLED

View File

@ -405,7 +405,7 @@ void ModeAuto::land_start()
// initialise yaw // initialise yaw
auto_yaw.set_mode(AutoYaw::Mode::HOLD); auto_yaw.set_mode(AutoYaw::Mode::HOLD);
#if LANDING_GEAR_ENABLED == ENABLED #if AP_LANDINGGEAR_ENABLED
// optionally deploy landing gear // optionally deploy landing gear
copter.landinggear.deploy_for_landing(); copter.landinggear.deploy_for_landing();
#endif #endif
@ -1785,7 +1785,7 @@ void ModeAuto::do_RTL(void)
// verify_takeoff - check if we have completed the takeoff // verify_takeoff - check if we have completed the takeoff
bool ModeAuto::verify_takeoff() bool ModeAuto::verify_takeoff()
{ {
#if LANDING_GEAR_ENABLED == ENABLED #if AP_LANDINGGEAR_ENABLED
// if we have reached our destination // if we have reached our destination
if (auto_takeoff_complete) { if (auto_takeoff_complete) {
// retract the landing gear // retract the landing gear

View File

@ -652,7 +652,7 @@ void ModeGuided::takeoff_run()
auto_takeoff_run(); auto_takeoff_run();
if (auto_takeoff_complete && !takeoff_complete) { if (auto_takeoff_complete && !takeoff_complete) {
takeoff_complete = true; takeoff_complete = true;
#if LANDING_GEAR_ENABLED == ENABLED #if AP_LANDINGGEAR_ENABLED
// optionally retract landing gear // optionally retract landing gear
copter.landinggear.retract_after_takeoff(); copter.landinggear.retract_after_takeoff();
#endif #endif

View File

@ -36,7 +36,7 @@ bool ModeLand::init(bool ignore_checks)
// initialise yaw // initialise yaw
auto_yaw.set_mode(AutoYaw::Mode::HOLD); auto_yaw.set_mode(AutoYaw::Mode::HOLD);
#if LANDING_GEAR_ENABLED == ENABLED #if AP_LANDINGGEAR_ENABLED
// optionally deploy landing gear // optionally deploy landing gear
copter.landinggear.deploy_for_landing(); copter.landinggear.deploy_for_landing();
#endif #endif

View File

@ -247,7 +247,7 @@ void ModeRTL::descent_start()
// initialise yaw // initialise yaw
auto_yaw.set_mode(AutoYaw::Mode::HOLD); auto_yaw.set_mode(AutoYaw::Mode::HOLD);
#if LANDING_GEAR_ENABLED == ENABLED #if AP_LANDINGGEAR_ENABLED
// optionally deploy landing gear // optionally deploy landing gear
copter.landinggear.deploy_for_landing(); copter.landinggear.deploy_for_landing();
#endif #endif
@ -339,7 +339,7 @@ void ModeRTL::land_start()
// initialise yaw // initialise yaw
auto_yaw.set_mode(AutoYaw::Mode::HOLD); auto_yaw.set_mode(AutoYaw::Mode::HOLD);
#if LANDING_GEAR_ENABLED == ENABLED #if AP_LANDINGGEAR_ENABLED
// optionally deploy landing gear // optionally deploy landing gear
copter.landinggear.deploy_for_landing(); copter.landinggear.deploy_for_landing();
#endif #endif

View File

@ -132,7 +132,7 @@ void Copter::init_ardupilot()
init_precland(); init_precland();
#endif #endif
#if LANDING_GEAR_ENABLED == ENABLED #if AP_LANDINGGEAR_ENABLED
// initialise landing gear position // initialise landing gear position
landinggear.init(); landinggear.init();
#endif #endif