ArduCopter: configuration of Precision Landing for custom build server

This commit is contained in:
tzarjakob 2023-03-22 09:45:41 +01:00 committed by Peter Barker
parent bd50e3eacf
commit 97b7e8d1d0
16 changed files with 25 additions and 31 deletions

View File

@ -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

View File

@ -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

View File

@ -69,6 +69,7 @@
#include <AC_Sprayer/AC_Sprayer.h> // Crop sprayer library
#include <AP_ADSB/AP_ADSB.h> // ADS-B RF based collision avoidance module library
#include <AP_Proximity/AP_Proximity.h> // ArduPilot proximity sensor library
#include <AC_PrecLand/AC_PrecLand_config.h>
#include <AP_OpticalFlow/AP_OpticalFlow.h>
#include <AP_Winch/AP_Winch_config.h>
@ -115,7 +116,7 @@
#if AP_GRIPPER_ENABLED
# include <AP_Gripper/AP_Gripper.h>
#endif
#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
# include <AC_PrecLand/AC_PrecLand.h>
# include <AC_PrecLand/AC_PrecLand_StateMachine.h>
#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

View File

@ -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;

View File

@ -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
}

View File

@ -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),

View File

@ -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);

View File

@ -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

View File

@ -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)

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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();

View File

@ -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

View File

@ -4,7 +4,7 @@
#include "Copter.h"
#if PRECISION_LANDING == ENABLED
#if AC_PRECLAND_ENABLED
void Copter::init_precland()
{

View File

@ -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