mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: make and use AP_LANDINGGEAR_ENABLED
This commit is contained in:
parent
1eb5911bf5
commit
c32a11f37a
|
@ -31,7 +31,6 @@
|
|||
//#define MODE_THROW_ENABLED DISABLED // disable throw mode support
|
||||
//#define MODE_ZIGZAG_ENABLED DISABLED // disable zigzag mode 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
|
||||
//#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes
|
||||
|
|
|
@ -193,7 +193,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
|||
SCHED_TASK(check_vibration, 10, 50, 87),
|
||||
SCHED_TASK(gpsglitch_check, 10, 50, 90),
|
||||
SCHED_TASK(takeoff_check, 50, 50, 91),
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
#if AP_LANDINGGEAR_ENABLED
|
||||
SCHED_TASK(landinggear_update, 10, 75, 93),
|
||||
#endif
|
||||
SCHED_TASK(standby_update, 100, 75, 96),
|
||||
|
|
|
@ -516,7 +516,7 @@ private:
|
|||
#endif
|
||||
|
||||
// Landing Gear Controller
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
#if AP_LANDINGGEAR_ENABLED
|
||||
AP_LandingGear landinggear;
|
||||
#endif
|
||||
|
||||
|
@ -804,7 +804,7 @@ private:
|
|||
void set_land_complete_maybe(bool b);
|
||||
void update_throttle_mix();
|
||||
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
#if AP_LANDINGGEAR_ENABLED
|
||||
// landing_gear.cpp
|
||||
void landinggear_update();
|
||||
#endif
|
||||
|
|
|
@ -920,7 +920,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
|||
return MAV_RESULT_FAILED;
|
||||
#endif
|
||||
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
#if AP_LANDINGGEAR_ENABLED
|
||||
case MAV_CMD_AIRFRAME_CONFIGURATION: {
|
||||
// Param 1: Select which gear, not used in ArduPilot
|
||||
// Param 2: 0 = Deploy, 1 = Retract
|
||||
|
|
|
@ -472,7 +472,7 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
GOBJECT(parachute, "CHUTE_", AP_Parachute),
|
||||
#endif
|
||||
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
#if AP_LANDINGGEAR_ENABLED
|
||||
// @Group: LGR_
|
||||
// @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp
|
||||
GOBJECT(landinggear, "LGR_", AP_LandingGear),
|
||||
|
@ -1292,7 +1292,7 @@ void Copter::load_parameters(void)
|
|||
AP_Param::load_all();
|
||||
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
|
||||
// PARAMETER_CONVERSION - Added: Nov-2018
|
||||
convert_lgr_parameters();
|
||||
|
@ -1559,7 +1559,7 @@ void Copter::convert_prx_parameters()
|
|||
}
|
||||
#endif
|
||||
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
#if AP_LANDINGGEAR_ENABLED
|
||||
/*
|
||||
convert landing gear parameters
|
||||
*/
|
||||
|
|
|
@ -298,12 +298,6 @@
|
|||
# define BEACON_ENABLED !HAL_MINIMIZE_FEATURES
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Landing Gear support
|
||||
#ifndef LANDING_GEAR_ENABLED
|
||||
#define LANDING_GEAR_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// RADIO CONFIGURATION
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
|
|
@ -337,7 +337,7 @@ void Copter::parachute_release()
|
|||
// release parachute
|
||||
parachute.release();
|
||||
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
#if AP_LANDINGGEAR_ENABLED
|
||||
// deploy landing gear
|
||||
landinggear.set_position(AP_LandingGear::LandingGear_Deploy);
|
||||
#endif
|
||||
|
|
|
@ -88,7 +88,7 @@ void Copter::update_land_detector()
|
|||
#endif
|
||||
|
||||
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) {
|
||||
// we have a WoW sensor so lets loosen the strictness of the landing detector
|
||||
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);
|
||||
|
||||
// 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);
|
||||
#else
|
||||
const bool WoW_check = true;
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#include "Copter.h"
|
||||
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
#if AP_LANDINGGEAR_ENABLED
|
||||
|
||||
// Run landing gear controller at 10Hz
|
||||
void Copter::landinggear_update()
|
||||
|
@ -35,4 +35,4 @@ void Copter::landinggear_update()
|
|||
landinggear.update(height_cm * 0.01f); // convert cm->m for update call
|
||||
}
|
||||
|
||||
#endif // LANDING_GEAR_ENABLED
|
||||
#endif // AP_LANDINGGEAR_ENABLED
|
||||
|
|
|
@ -405,7 +405,7 @@ void ModeAuto::land_start()
|
|||
// initialise yaw
|
||||
auto_yaw.set_mode(AutoYaw::Mode::HOLD);
|
||||
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
#if AP_LANDINGGEAR_ENABLED
|
||||
// optionally deploy landing gear
|
||||
copter.landinggear.deploy_for_landing();
|
||||
#endif
|
||||
|
@ -1785,7 +1785,7 @@ void ModeAuto::do_RTL(void)
|
|||
// verify_takeoff - check if we have completed the takeoff
|
||||
bool ModeAuto::verify_takeoff()
|
||||
{
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
#if AP_LANDINGGEAR_ENABLED
|
||||
// if we have reached our destination
|
||||
if (auto_takeoff_complete) {
|
||||
// retract the landing gear
|
||||
|
|
|
@ -652,7 +652,7 @@ void ModeGuided::takeoff_run()
|
|||
auto_takeoff_run();
|
||||
if (auto_takeoff_complete && !takeoff_complete) {
|
||||
takeoff_complete = true;
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
#if AP_LANDINGGEAR_ENABLED
|
||||
// optionally retract landing gear
|
||||
copter.landinggear.retract_after_takeoff();
|
||||
#endif
|
||||
|
|
|
@ -36,7 +36,7 @@ bool ModeLand::init(bool ignore_checks)
|
|||
// initialise yaw
|
||||
auto_yaw.set_mode(AutoYaw::Mode::HOLD);
|
||||
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
#if AP_LANDINGGEAR_ENABLED
|
||||
// optionally deploy landing gear
|
||||
copter.landinggear.deploy_for_landing();
|
||||
#endif
|
||||
|
|
|
@ -247,7 +247,7 @@ void ModeRTL::descent_start()
|
|||
// initialise yaw
|
||||
auto_yaw.set_mode(AutoYaw::Mode::HOLD);
|
||||
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
#if AP_LANDINGGEAR_ENABLED
|
||||
// optionally deploy landing gear
|
||||
copter.landinggear.deploy_for_landing();
|
||||
#endif
|
||||
|
@ -339,7 +339,7 @@ void ModeRTL::land_start()
|
|||
// initialise yaw
|
||||
auto_yaw.set_mode(AutoYaw::Mode::HOLD);
|
||||
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
#if AP_LANDINGGEAR_ENABLED
|
||||
// optionally deploy landing gear
|
||||
copter.landinggear.deploy_for_landing();
|
||||
#endif
|
||||
|
|
|
@ -132,7 +132,7 @@ void Copter::init_ardupilot()
|
|||
init_precland();
|
||||
#endif
|
||||
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
#if AP_LANDINGGEAR_ENABLED
|
||||
// initialise landing gear position
|
||||
landinggear.init();
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue