diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index db60b9cfc7..d9c8f7afdc 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -9,7 +9,6 @@ //#define AC_OAPATHPLANNER_ENABLED DISABLED // disable path planning around obstacles //#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 PRECISION_LANDING DISABLED // disable precision landing using companion computer or IRLock sensor //#define BEACON_ENABLED DISABLED // disable beacon support //#define STATS_ENABLED DISABLED // disable statistics support //#define MODE_ACRO_ENABLED DISABLED // disable acrobatic mode support diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 293d1d38f5..bb80d616ad 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -180,7 +180,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { SCHED_TASK(three_hz_loop, 3, 75, 57), SCHED_TASK_CLASS(AP_ServoRelayEvents, &copter.ServoRelayEvents, update_events, 50, 75, 60), SCHED_TASK_CLASS(AP_Baro, &copter.barometer, accumulate, 50, 90, 63), -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED SCHED_TASK(update_precland, 400, 50, 69), #endif #if FRAME_CONFIG == HELI_FRAME diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index be136776ed..425e419cfc 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -69,6 +69,7 @@ #include // Crop sprayer library #include // ADS-B RF based collision avoidance module library #include // ArduPilot proximity sensor library +#include #include #include @@ -115,7 +116,7 @@ #if AP_GRIPPER_ENABLED # include #endif -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED # include # include #endif @@ -529,7 +530,7 @@ private: #endif // Precision Landing -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED AC_PrecLand precland; AC_PrecLand_StateMachine precland_statemachine; #endif diff --git a/ArduCopter/GCS_Copter.cpp b/ArduCopter/GCS_Copter.cpp index 7721e5e746..02599b045d 100644 --- a/ArduCopter/GCS_Copter.cpp +++ b/ArduCopter/GCS_Copter.cpp @@ -114,7 +114,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void) } #endif -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED if (copter.precland.enabled()) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_VISION_POSITION; diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 28aebf0511..9250a79284 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -640,7 +640,7 @@ void GCS_MAVLINK_Copter::handle_command_ack(const mavlink_message_t &msg) */ void GCS_MAVLINK_Copter::handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) { -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED copter.precland.handle_msg(packet, timestamp_ms); #endif } diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 4e699f3655..1092475d55 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -664,7 +664,7 @@ const AP_Param::Info Copter::var_info[] = { GOBJECT(optflow, "FLOW", AP_OpticalFlow), #endif -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED // @Group: PLND_ // @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp GOBJECT(precland, "PLND_", AC_PrecLand), diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index afcd65754c..03d398c67a 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -391,7 +391,7 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi break; case AUX_FUNC::PRECISION_LOITER: -#if PRECISION_LANDING == ENABLED && MODE_LOITER_ENABLED == ENABLED +#if AC_PRECLAND_ENABLED && MODE_LOITER_ENABLED == ENABLED switch (ch_flag) { case AuxSwitchPos::HIGH: copter.mode_loiter.set_precision_loiter_enabled(true); diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 5a4704b149..9900d7e39b 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -138,12 +138,6 @@ # define AUTOTUNE_ENABLED ENABLED #endif -////////////////////////////////////////////////////////////////////////////// -// Precision Landing with companion computer or IRLock sensor -#ifndef PRECISION_LANDING - # define PRECISION_LANDING ENABLED -#endif - ////////////////////////////////////////////////////////////////////////////// // Parachute release #ifndef PARACHUTE diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index 61b1cbb756..516de29c84 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -594,7 +594,7 @@ void Mode::land_run_vertical_control(bool pause_descent) // Constrain the demanded vertical velocity so that it is between the configured maximum descent speed and the configured minimum descent speed. cmb_rate = constrain_float(cmb_rate, max_land_descent_velocity, -abs(g.land_speed)); -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED const bool navigating = pos_control->is_active_xy(); bool doing_precision_landing = !copter.ap.land_repo_active && copter.precland.target_acquired() && navigating; @@ -668,7 +668,7 @@ void Mode::land_run_horizontal_control() AP::logger().Write_Event(LogEvent::LAND_REPO_ACTIVE); } copter.ap.land_repo_active = true; -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED } else { // no override right now, check if we should allow precland if (copter.precland.allow_precland_after_reposition()) { @@ -681,7 +681,7 @@ void Mode::land_run_horizontal_control() // this variable will be updated if prec land target is in sight and pilot isn't trying to reposition the vehicle copter.ap.prec_land_active = false; -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED copter.ap.prec_land_active = !copter.ap.land_repo_active && copter.precland.target_acquired(); // run precision landing if (copter.ap.prec_land_active) { @@ -738,7 +738,7 @@ void Mode::land_run_horizontal_control() // pause_descent is true if vehicle should not descend void Mode::land_run_normal_or_precland(bool pause_descent) { -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED if (pause_descent || !copter.precland.enabled()) { // we don't want to start descending immediately or prec land is disabled // in both cases just run simple land controllers @@ -753,7 +753,7 @@ void Mode::land_run_normal_or_precland(bool pause_descent) #endif } -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED // Go towards a position commanded by prec land state machine in order to retry landing // The passed in location is expected to be NED and in m void Mode::precland_retry_position(const Vector3f &retry_pos) diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 812b9eb332..dc417f51c6 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -147,7 +147,7 @@ protected: // pause_descent is true if vehicle should not descend void land_run_normal_or_precland(bool pause_descent = false); -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED // Go towards a position commanded by prec land state machine in order to retry landing // The passed in location is expected to be NED and in meters void precland_retry_position(const Vector3f &retry_pos); @@ -1181,7 +1181,7 @@ public: bool has_user_takeoff(bool must_navigate) const override { return true; } bool allows_autotune() const override { return true; } -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED void set_precision_loiter_enabled(bool value) { _precision_loiter_enabled = value; } #endif @@ -1194,14 +1194,14 @@ protected: int32_t wp_bearing() const override; float crosstrack_error() const override { return pos_control->crosstrack_error();} -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED bool do_precision_loiter(); void precision_loiter_xy(); #endif private: -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED bool _precision_loiter_enabled; bool _precision_loiter_active; // true if user has switched on prec loiter #endif diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index b6be6d5cef..77be356074 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -53,7 +53,7 @@ bool ModeAuto::init(bool ignore_checks) // reset flag indicating if pilot has applied roll or pitch inputs during landing copter.ap.land_repo_active = false; -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED // initialise precland state machine copter.precland_statemachine.init(); #endif diff --git a/ArduCopter/mode_land.cpp b/ArduCopter/mode_land.cpp index 4072e76c8b..377bef5ee9 100644 --- a/ArduCopter/mode_land.cpp +++ b/ArduCopter/mode_land.cpp @@ -46,7 +46,7 @@ bool ModeLand::init(bool ignore_checks) copter.fence.auto_disable_fence_for_landing(); #endif -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED // initialise precland state machine copter.precland_statemachine.init(); #endif diff --git a/ArduCopter/mode_loiter.cpp b/ArduCopter/mode_loiter.cpp index 0198db443e..602aa52859 100644 --- a/ArduCopter/mode_loiter.cpp +++ b/ArduCopter/mode_loiter.cpp @@ -34,14 +34,14 @@ bool ModeLoiter::init(bool ignore_checks) pos_control->set_max_speed_accel_z(-get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z); pos_control->set_correction_speed_accel_z(-get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z); -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED _precision_loiter_active = false; #endif return true; } -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED bool ModeLoiter::do_precision_loiter() { if (!_precision_loiter_enabled) { @@ -165,7 +165,7 @@ void ModeLoiter::run() // set motors to full range motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED bool precision_loiter_old_state = _precision_loiter_active; if (do_precision_loiter()) { precision_loiter_xy(); diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index fc08b39b19..e6ae505e82 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -28,7 +28,7 @@ bool ModeRTL::init(bool ignore_checks) // this will be set true if prec land is later active copter.ap.prec_land_active = false; -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED // initialise precland state machine copter.precland_statemachine.init(); #endif diff --git a/ArduCopter/precision_landing.cpp b/ArduCopter/precision_landing.cpp index 0761776678..ad98c2fa75 100644 --- a/ArduCopter/precision_landing.cpp +++ b/ArduCopter/precision_landing.cpp @@ -4,7 +4,7 @@ #include "Copter.h" -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED void Copter::init_precland() { diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 1a7429558a..499c552a58 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -132,7 +132,7 @@ void Copter::init_ardupilot() camera.init(); #endif -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED // initialise precision landing init_precland(); #endif