Browse Source
- landing slope/curve library removed - flare curve removed (the position setpoints will not be tracked during a flare, and were being ignored by open-loop maneuvers anyway) - flare curve replaced by simply commanding a constant glide slope to the ground from the approach entrance, and commanding a sink rate once below flaring alt - flare is now time-to-touchdown -based to account for differing descent rates (e.g. due to wind) - flare pitch limits and height rate commands are ramped in from the previous iteration's values at flare onset to avoid jumpy commands - TECS controls all aspects of the auto landing airspeed and altitude/height rate, and is only constrained by pitch and throttle limits (lessening unintuitive open loop manuever overrides) - throttle is killed on flare - flare is the singular point of no return during landing - lateral manual nudging of the touchdown point is configurable via parameter, allowing the operator to nudge (via remote) either the touchdown point itself (adjusting approach vector) or shifting the entire approach path to the left or right. this helps when GCS map or GNSS uncertainties set the aircraft on a slightly offset approach"main
Thomas Stastny
3 years ago
committed by
Daniel Agar
22 changed files with 388 additions and 747 deletions
@ -1,9 +1,3 @@
@@ -1,9 +1,3 @@
|
||||
uint64 timestamp # time since system start (microseconds) |
||||
|
||||
float32 horizontal_slope_displacement |
||||
|
||||
float32 slope_angle_rad |
||||
|
||||
float32 flare_length |
||||
|
||||
bool abort_landing # true if landing should be aborted |
||||
uint64 timestamp # [us] time since system start |
||||
float32 lateral_touchdown_offset # [m] lateral touchdown position offset manually commanded during landing |
||||
bool abort_landing # true if landing should be aborted |
||||
|
@ -1,34 +0,0 @@
@@ -1,34 +0,0 @@
|
||||
############################################################################ |
||||
# |
||||
# Copyright (c) 2018 PX4 Development Team. All rights reserved. |
||||
# |
||||
# Redistribution and use in source and binary forms, with or without |
||||
# modification, are permitted provided that the following conditions |
||||
# are met: |
||||
# |
||||
# 1. Redistributions of source code must retain the above copyright |
||||
# notice, this list of conditions and the following disclaimer. |
||||
# 2. Redistributions in binary form must reproduce the above copyright |
||||
# notice, this list of conditions and the following disclaimer in |
||||
# the documentation and/or other materials provided with the |
||||
# distribution. |
||||
# 3. Neither the name PX4 nor the names of its contributors may be |
||||
# used to endorse or promote products derived from this software |
||||
# without specific prior written permission. |
||||
# |
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
# POSSIBILITY OF SUCH DAMAGE. |
||||
# |
||||
############################################################################ |
||||
|
||||
px4_add_library(landing_slope Landingslope.cpp) |
@ -1,132 +0,0 @@
@@ -1,132 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2012-2017 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/*
|
||||
* @file landingslope.cpp |
||||
* |
||||
* @author Thomas Gubler <thomasgubler@gmail.com> |
||||
*/ |
||||
|
||||
#include "Landingslope.hpp" |
||||
|
||||
#include <mathlib/mathlib.h> |
||||
#include <matrix/math.hpp> |
||||
|
||||
void |
||||
Landingslope::update(float landing_slope_angle_rad_new, |
||||
float flare_relative_alt_new, |
||||
float motor_lim_relative_alt_new, |
||||
float H1_virt_new) |
||||
{ |
||||
_landing_slope_angle_rad = landing_slope_angle_rad_new; |
||||
_flare_relative_alt = flare_relative_alt_new; |
||||
_motor_lim_relative_alt = motor_lim_relative_alt_new; |
||||
_H1_virt = H1_virt_new; |
||||
|
||||
calculateSlopeValues(); |
||||
} |
||||
|
||||
void |
||||
Landingslope::calculateSlopeValues() |
||||
{ |
||||
_H0 = _flare_relative_alt + _H1_virt; |
||||
_d1 = _flare_relative_alt / tanf(_landing_slope_angle_rad); |
||||
_flare_constant = (_H0 * _d1) / _flare_relative_alt; |
||||
_flare_length = -logf(_H1_virt / _H0) * _flare_constant; |
||||
_horizontal_slope_displacement = (_flare_length - _d1); |
||||
} |
||||
|
||||
float |
||||
Landingslope::getLandingSlopeRelativeAltitude(float wp_landing_distance) |
||||
{ |
||||
return Landingslope::getLandingSlopeRelativeAltitude(wp_landing_distance, _horizontal_slope_displacement, |
||||
_landing_slope_angle_rad); |
||||
} |
||||
|
||||
float |
||||
Landingslope::getLandingSlopeRelativeAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, |
||||
float bearing_airplane_currwp) |
||||
{ |
||||
/* If airplane is in front of waypoint return slope altitude, else return waypoint altitude */ |
||||
if (fabsf(matrix::wrap_pi(bearing_airplane_currwp - bearing_lastwp_currwp)) < math::radians(90.0f)) { |
||||
return getLandingSlopeRelativeAltitude(wp_landing_distance); |
||||
|
||||
} |
||||
|
||||
return 0.0f; |
||||
} |
||||
|
||||
float |
||||
Landingslope::getFlareCurveRelativeAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, |
||||
float bearing_airplane_currwp) |
||||
{ |
||||
/* If airplane is in front of waypoint return flare curve altitude, else return waypoint altitude */ |
||||
if (fabsf(matrix::wrap_pi(bearing_airplane_currwp - bearing_lastwp_currwp)) < math::radians(90.0f)) { |
||||
return _H0 * expf(-math::max(0.0f, _flare_length - wp_landing_distance) / _flare_constant) - _H1_virt; |
||||
|
||||
} |
||||
|
||||
return 0.0f; |
||||
} |
||||
|
||||
/**
|
||||
* |
||||
* @return Relative altitude of point on landing slope at distance to landing waypoint=wp_landing_distance |
||||
*/ |
||||
float Landingslope::getLandingSlopeRelativeAltitude(float wp_landing_distance, float horizontal_slope_displacement, |
||||
float landing_slope_angle_rad) |
||||
{ |
||||
// flare_relative_alt is negative
|
||||
return (wp_landing_distance - horizontal_slope_displacement) * tanf(landing_slope_angle_rad); |
||||
} |
||||
|
||||
/**
|
||||
* |
||||
* @return Absolute altitude of point on landing slope at distance to landing waypoint=wp_landing_distance |
||||
*/ |
||||
float Landingslope::getLandingSlopeAbsoluteAltitude(float wp_landing_distance, float wp_landing_altitude, |
||||
float horizontal_slope_displacement, float landing_slope_angle_rad) |
||||
{ |
||||
return getLandingSlopeRelativeAltitude(wp_landing_distance, horizontal_slope_displacement, |
||||
landing_slope_angle_rad) + wp_landing_altitude; |
||||
} |
||||
|
||||
/**
|
||||
* |
||||
* @return distance to landing waypoint of point on landing slope at altitude=slope_altitude |
||||
*/ |
||||
float Landingslope::getLandingSlopeWPDistance(float slope_altitude, float wp_landing_altitude, |
||||
float horizontal_slope_displacement, float landing_slope_angle_rad) |
||||
{ |
||||
return (slope_altitude - wp_landing_altitude) / tanf(landing_slope_angle_rad) + horizontal_slope_displacement; |
||||
} |
@ -1,118 +0,0 @@
@@ -1,118 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2012-2017 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/*
|
||||
* @file landingslope.h |
||||
* |
||||
* @author Thomas Gubler <thomasgubler@gmail.com> |
||||
*/ |
||||
|
||||
#ifndef LANDINGSLOPE_H_ |
||||
#define LANDINGSLOPE_H_ |
||||
|
||||
#include <math.h> |
||||
|
||||
class Landingslope |
||||
{ |
||||
private: |
||||
/* see Documentation/fw_landing.png for a plot of the landing slope */ |
||||
float _landing_slope_angle_rad{0.0f}; /**< phi in the plot */ |
||||
float _flare_relative_alt{0.0f}; /**< h_flare,rel in the plot */ |
||||
float _motor_lim_relative_alt{0.0f}; |
||||
float _H1_virt{0.0f}; /**< H1 in the plot */ |
||||
float _H0{0.0f}; /**< h_flare,rel + H1 in the plot */ |
||||
float _d1{0.0f}; /**< d1 in the plot */ |
||||
float _flare_constant{0.0f}; |
||||
float _flare_length{0.0f}; /**< d1 + delta d in the plot */ |
||||
float _horizontal_slope_displacement{0.0f}; /**< delta d in the plot */ |
||||
|
||||
void calculateSlopeValues(); |
||||
|
||||
public: |
||||
Landingslope() = default; |
||||
~Landingslope() = default; |
||||
|
||||
/**
|
||||
* |
||||
* @return relative altitude of point on landing slope at distance to landing waypoint=wp_landing_distance |
||||
*/ |
||||
float getLandingSlopeRelativeAltitude(float wp_landing_distance); |
||||
|
||||
/**
|
||||
* |
||||
* @return relative altitude of point on landing slope at distance to landing waypoint=wp_landing_distance |
||||
* Performs check if aircraft is in front of waypoint to avoid climbout |
||||
*/ |
||||
float getLandingSlopeRelativeAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, |
||||
float bearing_airplane_currwp); |
||||
|
||||
/**
|
||||
* |
||||
* @return Relative altitude of point on landing slope at distance to landing waypoint=wp_landing_distance |
||||
*/ |
||||
static float getLandingSlopeRelativeAltitude(float wp_landing_distance, float horizontal_slope_displacement, |
||||
float landing_slope_angle_rad); |
||||
|
||||
/**
|
||||
* |
||||
* @return Absolute altitude of point on landing slope at distance to landing waypoint=wp_landing_distance |
||||
*/ |
||||
static float getLandingSlopeAbsoluteAltitude(float wp_landing_distance, float wp_landing_altitude, |
||||
float horizontal_slope_displacement, float landing_slope_angle_rad); |
||||
|
||||
/**
|
||||
* |
||||
* @return distance to landing waypoint of point on landing slope at altitude=slope_altitude |
||||
*/ |
||||
static float getLandingSlopeWPDistance(float slope_altitude, float wp_landing_altitude, |
||||
float horizontal_slope_displacement, float landing_slope_angle_rad); |
||||
|
||||
float getFlareCurveRelativeAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, |
||||
float bearing_airplane_currwp); |
||||
|
||||
void update(float landing_slope_angle_rad_new, |
||||
float flare_relative_alt_new, |
||||
float motor_lim_relative_alt_new, |
||||
float H1_virt_new); |
||||
|
||||
|
||||
float landing_slope_angle_rad() { return _landing_slope_angle_rad; } |
||||
float flare_relative_alt() { return _flare_relative_alt; } |
||||
float motor_lim_relative_alt() { return _motor_lim_relative_alt; } |
||||
float flare_length() { return _flare_length; } |
||||
float horizontal_slope_displacement() { return _horizontal_slope_displacement; } |
||||
|
||||
}; |
||||
|
||||
|
||||
#endif /* LANDINGSLOPE_H_ */ |
Loading…
Reference in new issue