Browse Source

FW landingslope delete unused (#7046)

sbg
Daniel Agar 8 years ago committed by GitHub
parent
commit
a41001354a
  1. 62
      src/modules/fw_pos_control_l1/landingslope.cpp
  2. 62
      src/modules/fw_pos_control_l1/landingslope.h

62
src/modules/fw_pos_control_l1/landingslope.cpp

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012-2016 PX4 Development Team. All rights reserved.
* 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
@ -39,27 +39,10 @@ @@ -39,27 +39,10 @@
#include "landingslope.h"
#include <px4_config.h>
#include <stdlib.h>
#include <errno.h>
#include <math.h>
#include <unistd.h>
#include <mathlib/mathlib.h>
Landingslope::Landingslope() :
_landing_slope_angle_rad(0.0f),
_flare_relative_alt(0.0f),
_motor_lim_relative_alt(0.0f),
_H1_virt(0.0f),
_H0(0.0f),
_d1(0.0f),
_flare_constant(0.0f),
_flare_length(0.0f),
_horizontal_slope_displacement(0.0f)
{
}
void Landingslope::update(float landing_slope_angle_rad_new,
void
Landingslope::update(float landing_slope_angle_rad_new,
float flare_relative_alt_new,
float motor_lim_relative_alt_new,
float H1_virt_new)
@ -73,7 +56,8 @@ void Landingslope::update(float landing_slope_angle_rad_new, @@ -73,7 +56,8 @@ void Landingslope::update(float landing_slope_angle_rad_new,
calculateSlopeValues();
}
void Landingslope::calculateSlopeValues()
void
Landingslope::calculateSlopeValues()
{
_H0 = _flare_relative_alt + _H1_virt;
_d1 = _flare_relative_alt / tanf(_landing_slope_angle_rad);
@ -82,13 +66,15 @@ void Landingslope::calculateSlopeValues() @@ -82,13 +66,15 @@ void Landingslope::calculateSlopeValues()
_horizontal_slope_displacement = (_flare_length - _d1);
}
float Landingslope::getLandingSlopeRelativeAltitude(float wp_landing_distance)
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
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 */
@ -100,25 +86,8 @@ float Landingslope::getLandingSlopeRelativeAltitudeSave(float wp_landing_distanc @@ -100,25 +86,8 @@ float Landingslope::getLandingSlopeRelativeAltitudeSave(float wp_landing_distanc
}
}
float Landingslope::getLandingSlopeAbsoluteAltitude(float wp_landing_distance, float wp_altitude)
{
return Landingslope::getLandingSlopeAbsoluteAltitude(wp_landing_distance, wp_altitude, _horizontal_slope_displacement,
_landing_slope_angle_rad);
}
float Landingslope::getLandingSlopeAbsoluteAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp,
float bearing_airplane_currwp, float wp_altitude)
{
/* If airplane is in front of waypoint return slope altitude, else return waypoint altitude */
if (fabsf(bearing_airplane_currwp - bearing_lastwp_currwp) < math::radians(90.0f)) {
return getLandingSlopeAbsoluteAltitude(wp_landing_distance, wp_altitude);
} else {
return wp_altitude;
}
}
float Landingslope::getFlareCurveRelativeAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp,
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 */
@ -129,12 +98,3 @@ float Landingslope::getFlareCurveRelativeAltitudeSave(float wp_landing_distance, @@ -129,12 +98,3 @@ float Landingslope::getFlareCurveRelativeAltitudeSave(float wp_landing_distance,
return 0.0f;
}
}
float Landingslope::getFlareCurveAbsoluteAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp,
float bearing_airplane_currwp, float wp_landing_altitude)
{
return wp_landing_altitude + getFlareCurveRelativeAltitudeSave(wp_landing_distance, bearing_lastwp_currwp,
bearing_airplane_currwp);
}

62
src/modules/fw_pos_control_l1/landingslope.h

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012-2016 PX4 Development Team. All rights reserved.
* 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
@ -41,28 +41,26 @@ @@ -41,28 +41,26 @@
#define LANDINGSLOPE_H_
#include <math.h>
#include <systemlib/err.h>
class Landingslope
{
private:
/* see Documentation/fw_landing.png for a plot of the landing slope */
float _landing_slope_angle_rad; /**< phi in the plot */
float _flare_relative_alt; /**< h_flare,rel in the plot */
float _motor_lim_relative_alt;
float _H1_virt; /**< H1 in the plot */
float _H0; /**< h_flare,rel + H1 in the plot */
float _d1; /**< d1 in the plot */
float _flare_constant;
float _flare_length; /**< d1 + delta d in the plot */
float _horizontal_slope_displacement; /**< delta d in the plot */
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();
~Landingslope() {}
Landingslope() = default;
~Landingslope() = default;
/**
*
@ -78,21 +76,6 @@ public: @@ -78,21 +76,6 @@ public:
float getLandingSlopeRelativeAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp,
float bearing_airplane_currwp);
/**
*
* @return Absolute altitude of point on landing slope at distance to landing waypoint=wp_landing_distance
*/
float getLandingSlopeAbsoluteAltitude(float wp_landing_distance, float wp_altitude);
/**
*
* @return Absolute 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 getLandingSlopeAbsoluteAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp,
float bearing_airplane_currwp, float wp_landing_altitude);
/**
*
* @return Relative altitude of point on landing slope at distance to landing waypoint=wp_landing_distance
@ -100,8 +83,8 @@ public: @@ -100,8 +83,8 @@ public:
__EXPORT static float getLandingSlopeRelativeAltitude(float wp_landing_distance, float horizontal_slope_displacement,
float landing_slope_angle_rad)
{
return (wp_landing_distance - horizontal_slope_displacement) * tanf(
landing_slope_angle_rad); //flare_relative_alt is negative
// flare_relative_alt is negative
return (wp_landing_distance - horizontal_slope_displacement) * tanf(landing_slope_angle_rad);
}
/**
@ -128,24 +111,17 @@ public: @@ -128,24 +111,17 @@ public:
float getFlareCurveRelativeAltitudeSave(float wp_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp);
float getFlareCurveAbsoluteAltitudeSave(float wp_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp,
float wp_altitude);
void update(float landing_slope_angle_rad_new,
float flare_relative_alt_new,
float motor_lim_relative_alt_new,
float H1_virt_new);
inline float landing_slope_angle_rad() {return _landing_slope_angle_rad;}
inline float flare_relative_alt() {return _flare_relative_alt;}
inline float motor_lim_relative_alt() {return _motor_lim_relative_alt;}
inline float H1_virt() {return _H1_virt;}
inline float H0() {return _H0;}
inline float d1() {return _d1;}
inline float flare_constant() {return _flare_constant;}
inline float flare_length() {return _flare_length;}
inline float horizontal_slope_displacement() {return _horizontal_slope_displacement;}
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; }
};

Loading…
Cancel
Save