PX4 Firmware
PX4 Autopilot Software http://px4.io
Landingslope.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-2017 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /*
35  * @file landingslope.cpp
36  *
37  * @author Thomas Gubler <thomasgubler@gmail.com>
38  */
39 
40 #include "Landingslope.hpp"
41 
42 #include <mathlib/mathlib.h>
43 
44 void
45 Landingslope::update(float landing_slope_angle_rad_new,
46  float flare_relative_alt_new,
47  float motor_lim_relative_alt_new,
48  float H1_virt_new)
49 {
50  _landing_slope_angle_rad = landing_slope_angle_rad_new;
51  _flare_relative_alt = flare_relative_alt_new;
52  _motor_lim_relative_alt = motor_lim_relative_alt_new;
53  _H1_virt = H1_virt_new;
54 
56 }
57 
58 void
60 {
64  _flare_length = -logf(_H1_virt / _H0) * _flare_constant;
66 }
67 
68 float
70 {
73 }
74 
75 float
76 Landingslope::getLandingSlopeRelativeAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp,
77  float bearing_airplane_currwp)
78 {
79  /* If airplane is in front of waypoint return slope altitude, else return waypoint altitude */
80  if (fabsf(bearing_airplane_currwp - bearing_lastwp_currwp) < math::radians(90.0f)) {
81  return getLandingSlopeRelativeAltitude(wp_landing_distance);
82 
83  }
84 
85  return 0.0f;
86 }
87 
88 float
89 Landingslope::getFlareCurveRelativeAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp,
90  float bearing_airplane_currwp)
91 {
92  /* If airplane is in front of waypoint return flare curve altitude, else return waypoint altitude */
93  if (fabsf(bearing_airplane_currwp - bearing_lastwp_currwp) < math::radians(90.0f)) {
94  return _H0 * expf(-math::max(0.0f, _flare_length - wp_landing_distance) / _flare_constant) - _H1_virt;
95 
96  }
97 
98  return 0.0f;
99 }
100 
101 /**
102  *
103  * @return Relative altitude of point on landing slope at distance to landing waypoint=wp_landing_distance
104  */
107 {
108  // flare_relative_alt is negative
109  return (wp_landing_distance - horizontal_slope_displacement) * tanf(landing_slope_angle_rad);
110 }
111 
112 /**
113  *
114  * @return Absolute altitude of point on landing slope at distance to landing waypoint=wp_landing_distance
115  */
116 float Landingslope::getLandingSlopeAbsoluteAltitude(float wp_landing_distance, float wp_landing_altitude,
118 {
119  return getLandingSlopeRelativeAltitude(wp_landing_distance, horizontal_slope_displacement,
120  landing_slope_angle_rad) + wp_landing_altitude;
121 }
122 
123 /**
124  *
125  * @return distance to landing waypoint of point on landing slope at altitude=slope_altitude
126  */
127 float Landingslope::getLandingSlopeWPDistance(float slope_altitude, float wp_landing_altitude,
129 {
130  return (slope_altitude - wp_landing_altitude) / tanf(landing_slope_angle_rad) + horizontal_slope_displacement;
131 }
void update(float landing_slope_angle_rad_new, float flare_relative_alt_new, float motor_lim_relative_alt_new, float H1_virt_new)
static float getLandingSlopeAbsoluteAltitude(float wp_landing_distance, float wp_landing_altitude, float horizontal_slope_displacement, float landing_slope_angle_rad)
float _flare_relative_alt
h_flare,rel in the plot
float _flare_constant
float getLandingSlopeRelativeAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp)
float _H1_virt
H1 in the plot.
float getLandingSlopeRelativeAltitude(float wp_landing_distance)
float _flare_length
d1 + delta d in the plot
float _horizontal_slope_displacement
delta d in the plot
float landing_slope_angle_rad()
constexpr T radians(T degrees)
Definition: Limits.hpp:85
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
void calculateSlopeValues()
float _H0
h_flare,rel + H1 in the plot
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)
float _motor_lim_relative_alt
constexpr _Tp max(_Tp a, _Tp b)
Definition: Limits.hpp:60
float _d1
d1 in the plot
float horizontal_slope_displacement()
float _landing_slope_angle_rad
phi in the plot