aboutsummaryrefslogtreecommitdiff
path: root/src/modules/fw_pos_control_l1
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-10-07 10:01:16 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-10-07 10:01:16 +0200
commit5d52978bc780707d63c1422369842629d26fb1e2 (patch)
tree70d1e8b876f8d399764afeec613ca12d968a9393 /src/modules/fw_pos_control_l1
parentc0eefc983a5bbe2faf05eb21daaf3514b767daa6 (diff)
parent852159d9edaa85c3abee3059359264f3329841e8 (diff)
downloadpx4-firmware-5d52978bc780707d63c1422369842629d26fb1e2.tar.gz
px4-firmware-5d52978bc780707d63c1422369842629d26fb1e2.tar.bz2
px4-firmware-5d52978bc780707d63c1422369842629d26fb1e2.zip
Merge pull request #1341 from PX4/fwlandingterrain
FW landing: use terrain estimate
Diffstat (limited to 'src/modules/fw_pos_control_l1')
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp132
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c26
2 files changed, 84 insertions, 74 deletions
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index fdb1b2429..dbaecfbed 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -88,7 +88,6 @@
#include <launchdetection/LaunchDetector.h>
#include <ecl/l1/ecl_l1_pos_controller.h>
#include <external_lgpl/tecs/tecs.h>
-#include <drivers/drv_range_finder.h>
#include "landingslope.h"
#include "mtecs/mTecs.h"
@@ -146,7 +145,6 @@ private:
int _params_sub; /**< notification of parameter updates */
int _manual_control_sub; /**< notification of manual control updates */
int _sensor_combined_sub; /**< for body frame accelerations */
- int _range_finder_sub; /**< range finder subscription */
orb_advert_t _attitude_sp_pub; /**< attitude setpoint */
orb_advert_t _tecs_status_pub; /**< TECS status publication */
@@ -162,17 +160,16 @@ private:
struct vehicle_global_position_s _global_pos; /**< global vehicle position */
struct position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of mission items */
struct sensor_combined_s _sensor_combined; /**< for body frame accelerations */
- struct range_finder_report _range_finder; /**< range finder report */
perf_counter_t _loop_perf; /**< loop performance counter */
/* land states */
- /* not in non-abort mode for landing yet */
bool land_noreturn_horizontal;
bool land_noreturn_vertical;
bool land_stayonground;
bool land_motor_lim;
bool land_onslope;
+ bool land_useterrain;
/* takeoff/launch states */
LaunchDetectionResult launch_detection_state;
@@ -243,7 +240,9 @@ private:
float land_flare_alt_relative;
float land_thrust_lim_alt_relative;
float land_heading_hold_horizontal_distance;
- float range_finder_rel_alt;
+ float land_flare_pitch_min_deg;
+ float land_flare_pitch_max_deg;
+ int land_use_terrain_estimate;
} _parameters; /**< local copies of interesting parameters */
@@ -289,7 +288,9 @@ private:
param_t land_flare_alt_relative;
param_t land_thrust_lim_alt_relative;
param_t land_heading_hold_horizontal_distance;
- param_t range_finder_rel_alt;
+ param_t land_flare_pitch_min_deg;
+ param_t land_flare_pitch_max_deg;
+ param_t land_use_terrain_estimate;
} _parameter_handles; /**< handles for interesting parameters */
@@ -321,12 +322,6 @@ private:
bool vehicle_airspeed_poll();
/**
- * Check for range finder updates.
- */
- bool range_finder_poll();
-
-
- /**
* Check for position updates.
*/
void vehicle_attitude_poll();
@@ -347,9 +342,9 @@ private:
void navigation_capabilities_publish();
/**
- * Get the relative alt either from the difference between estimate and waypoint or from the laser range finder
+ * Return the terrain estimate during landing: uses the wp altitude value or the terrain estimate if available
*/
- float get_relative_landingalt(float land_setpoint_alt, float current_alt, const struct range_finder_report &range_finder, float range_finder_use_relative_alt);
+ float get_terrain_altitude_landing(float land_setpoint_alt, const struct vehicle_global_position_s &global_pos);
/**
* Control position.
@@ -423,7 +418,6 @@ FixedwingPositionControl::FixedwingPositionControl() :
_params_sub(-1),
_manual_control_sub(-1),
_sensor_combined_sub(-1),
- _range_finder_sub(-1),
/* publications */
_attitude_sp_pub(-1),
@@ -441,7 +435,6 @@ FixedwingPositionControl::FixedwingPositionControl() :
_global_pos(),
_pos_sp_triplet(),
_sensor_combined(),
- _range_finder(),
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "fw l1 control")),
@@ -451,6 +444,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
land_stayonground(false),
land_motor_lim(false),
land_onslope(false),
+ land_useterrain(false),
launch_detection_state(LAUNCHDETECTION_RES_NONE),
last_manual(false),
landingslope(),
@@ -489,7 +483,9 @@ FixedwingPositionControl::FixedwingPositionControl() :
_parameter_handles.land_flare_alt_relative = param_find("FW_LND_FLALT");
_parameter_handles.land_thrust_lim_alt_relative = param_find("FW_LND_TLALT");
_parameter_handles.land_heading_hold_horizontal_distance = param_find("FW_LND_HHDIST");
- _parameter_handles.range_finder_rel_alt = param_find("FW_LND_RFRALT");
+ _parameter_handles.land_flare_pitch_min_deg = param_find("FW_FLARE_PMIN");
+ _parameter_handles.land_flare_pitch_max_deg = param_find("FW_FLARE_PMAX");
+ _parameter_handles.land_use_terrain_estimate= param_find("FW_LND_USETER");
_parameter_handles.time_const = param_find("FW_T_TIME_CONST");
_parameter_handles.time_const_throt = param_find("FW_T_THRO_CONST");
@@ -590,8 +586,9 @@ FixedwingPositionControl::parameters_update()
}
param_get(_parameter_handles.land_heading_hold_horizontal_distance, &(_parameters.land_heading_hold_horizontal_distance));
-
- param_get(_parameter_handles.range_finder_rel_alt, &(_parameters.range_finder_rel_alt));
+ param_get(_parameter_handles.land_flare_pitch_min_deg, &(_parameters.land_flare_pitch_min_deg));
+ param_get(_parameter_handles.land_flare_pitch_max_deg, &(_parameters.land_flare_pitch_max_deg));
+ param_get(_parameter_handles.land_use_terrain_estimate, &(_parameters.land_use_terrain_estimate));
_l1_control.set_l1_damping(_parameters.l1_damping);
_l1_control.set_l1_period(_parameters.l1_period);
@@ -695,20 +692,6 @@ FixedwingPositionControl::vehicle_airspeed_poll()
return airspeed_updated;
}
-bool
-FixedwingPositionControl::range_finder_poll()
-{
- /* check if there is a range finder measurement */
- bool range_finder_updated;
- orb_check(_range_finder_sub, &range_finder_updated);
-
- if (range_finder_updated) {
- orb_copy(ORB_ID(sensor_range_finder), _range_finder_sub, &_range_finder);
- }
-
- return range_finder_updated;
-}
-
void
FixedwingPositionControl::vehicle_attitude_poll()
{
@@ -846,21 +829,23 @@ void FixedwingPositionControl::navigation_capabilities_publish()
}
}
-float FixedwingPositionControl::get_relative_landingalt(float land_setpoint_alt, float current_alt, const struct range_finder_report &range_finder, float range_finder_use_relative_alt)
+float FixedwingPositionControl::get_terrain_altitude_landing(float land_setpoint_alt, const struct vehicle_global_position_s &global_pos)
{
- float rel_alt_estimated = current_alt - land_setpoint_alt;
-
- /* only use range finder if:
- * parameter (range_finder_use_relative_alt) > 0
- * the measurement is valid
- * the estimated relative altitude (from global altitude estimate and landing waypoint) <= range_finder_use_relative_alt
- */
- if (range_finder_use_relative_alt < 0 || !range_finder.valid || range_finder.distance > range_finder_use_relative_alt ) {
- return rel_alt_estimated;
+ if (!isfinite(global_pos.terrain_alt)) {
+ return land_setpoint_alt;
}
- return range_finder.distance;
-
+ /* Decide if the terrain estimation can be used, once we switched to using the terrain we stick with it
+ * for the whole landing */
+ if (_parameters.land_use_terrain_estimate && (global_pos.terrain_alt_valid || land_useterrain)) {
+ if(!land_useterrain) {
+ mavlink_log_info(_mavlink_fd, "#audio: Landing, using terrain estimate");
+ land_useterrain = true;
+ }
+ return global_pos.terrain_alt;
+ } else {
+ return land_setpoint_alt;
+ }
}
bool
@@ -965,10 +950,17 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
} else if (pos_sp_triplet.current.type == SETPOINT_TYPE_LAND) {
float bearing_lastwp_currwp = get_bearing_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1));
+ float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1));
/* Horizontal landing control */
/* switch to heading hold for the last meters, continue heading hold after */
float wp_distance = get_distance_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1));
+ /* calculate a waypoint distance value which is 0 when the aircraft is behind the waypoint */
+ float wp_distance_save = wp_distance;
+ if (fabsf(bearing_airplane_currwp - bearing_lastwp_currwp) >= math::radians(90.0f)) {
+ wp_distance_save = 0.0f;
+ }
+
//warnx("wp dist: %d, alt err: %d, noret: %s", (int)wp_distance, (int)altitude_error, (land_noreturn) ? "YES" : "NO");
if (wp_distance < _parameters.land_heading_hold_horizontal_distance || land_noreturn_horizontal) {
@@ -1004,29 +996,30 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* Vertical landing control */
//xxx: using the tecs altitude controller for slope control for now
-
-// /* do not go down too early */
-// if (wp_distance > 50.0f) {
-// altitude_error = (_global_triplet.current.alt + 25.0f) - _global_pos.alt;
-// }
/* apply minimum pitch (flare) and limit roll if close to touch down, altitude error is negative (going down) */
// XXX this could make a great param
- float flare_pitch_angle_rad = -math::radians(5.0f);//math::radians(pos_sp_triplet.current.param1)
float throttle_land = _parameters.throttle_min + (_parameters.throttle_max - _parameters.throttle_min) * 0.1f;
float airspeed_land = 1.3f * _parameters.airspeed_min;
float airspeed_approach = 1.3f * _parameters.airspeed_min;
+ /* Get an estimate of the terrain altitude if available, otherwise terrain_alt will be
+ * equal to _pos_sp_triplet.current.alt */
+ float terrain_alt = get_terrain_altitude_landing(_pos_sp_triplet.current.alt, _global_pos);
+
/* Calculate distance (to landing waypoint) and altitude of last ordinary waypoint L */
- float L_altitude_rel = _pos_sp_triplet.previous.valid ? _pos_sp_triplet.previous.alt - _pos_sp_triplet.current.alt : 0.0f;
+ float L_altitude_rel = _pos_sp_triplet.previous.valid ?
+ _pos_sp_triplet.previous.alt - terrain_alt : 0.0f;
- float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1));
float landing_slope_alt_rel_desired = landingslope.getLandingSlopeRelativeAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp);
- float relative_alt = get_relative_landingalt(_pos_sp_triplet.current.alt, _global_pos.alt, _range_finder, _parameters.range_finder_rel_alt);
-
- if ( (relative_alt < landingslope.flare_relative_alt()) || land_noreturn_vertical) { //checking for land_noreturn to avoid unwanted climb out
-
+ /* Check if we should start flaring with a vertical and a
+ * horizontal limit (with some tolerance)
+ * The horizontal limit is only applied when we are in front of the wp
+ */
+ if (((_global_pos.alt < terrain_alt + landingslope.flare_relative_alt()) &&
+ (wp_distance_save < landingslope.flare_length() + 5.0f)) ||
+ land_noreturn_vertical) { //checking for land_noreturn to avoid unwanted climb out
/* land with minimal speed */
// /* force TECS to only control speed with pitch, altitude is only implicitely controlled now */
@@ -1035,7 +1028,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* kill the throttle if param requests it */
throttle_max = _parameters.throttle_max;
- if (relative_alt < landingslope.motor_lim_relative_alt() || land_motor_lim) {
+ if (_global_pos.alt < terrain_alt + landingslope.motor_lim_relative_alt() || land_motor_lim) {
throttle_max = math::min(throttle_max, _parameters.throttle_land_max);
if (!land_motor_lim) {
land_motor_lim = true;
@@ -1053,12 +1046,13 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
land_stayonground = true;
}
- tecs_update_pitch_throttle(_pos_sp_triplet.current.alt + flare_curve_alt_rel,
+ tecs_update_pitch_throttle(terrain_alt + flare_curve_alt_rel,
calculate_target_airspeed(airspeed_land), eas2tas,
- flare_pitch_angle_rad, math::radians(15.0f),
+ math::radians(_parameters.land_flare_pitch_min_deg),
+ math::radians(_parameters.land_flare_pitch_max_deg),
0.0f, throttle_max, throttle_land,
- false, flare_pitch_angle_rad,
- _pos_sp_triplet.current.alt + relative_alt, ground_speed,
+ false, land_motor_lim ? math::radians(_parameters.land_flare_pitch_min_deg) : math::radians(_parameters.pitch_limit_min),
+ _global_pos.alt, ground_speed,
land_motor_lim ? TECS_MODE_LAND_THROTTLELIM : TECS_MODE_LAND);
if (!land_noreturn_vertical) {
@@ -1079,8 +1073,8 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
* if current position is below the slope continue at previous wp altitude
* until the intersection with slope
* */
- float altitude_desired_rel = relative_alt;
- if (relative_alt > landing_slope_alt_rel_desired || land_onslope) {
+ float altitude_desired_rel;
+ if (_global_pos.alt > terrain_alt + landing_slope_alt_rel_desired || land_onslope) {
/* stay on slope */
altitude_desired_rel = landing_slope_alt_rel_desired;
if (!land_onslope) {
@@ -1089,10 +1083,11 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
}
} else {
/* continue horizontally */
- altitude_desired_rel = _pos_sp_triplet.previous.valid ? L_altitude_rel : relative_alt;
+ altitude_desired_rel = _pos_sp_triplet.previous.valid ? L_altitude_rel :
+ _global_pos.alt - terrain_alt;
}
- tecs_update_pitch_throttle(_pos_sp_triplet.current.alt + altitude_desired_rel,
+ tecs_update_pitch_throttle(terrain_alt + altitude_desired_rel,
calculate_target_airspeed(airspeed_approach), eas2tas,
math::radians(_parameters.pitch_limit_min),
math::radians(_parameters.pitch_limit_max),
@@ -1101,7 +1096,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
_parameters.throttle_cruise,
false,
math::radians(_parameters.pitch_limit_min),
- _pos_sp_triplet.current.alt + relative_alt,
+ _global_pos.alt,
ground_speed);
}
@@ -1278,7 +1273,6 @@ FixedwingPositionControl::task_main()
_airspeed_sub = orb_subscribe(ORB_ID(airspeed));
_params_sub = orb_subscribe(ORB_ID(parameter_update));
_manual_control_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
- _range_finder_sub = orb_subscribe(ORB_ID(sensor_range_finder));
/* rate limit control mode updates to 5Hz */
orb_set_interval(_control_mode_sub, 200);
@@ -1357,7 +1351,6 @@ FixedwingPositionControl::task_main()
vehicle_setpoint_poll();
vehicle_sensor_combined_poll();
vehicle_airspeed_poll();
- range_finder_poll();
// vehicle_baro_poll();
math::Vector<3> ground_speed(_global_pos.vel_n, _global_pos.vel_e, _global_pos.vel_d);
@@ -1421,6 +1414,7 @@ void FixedwingPositionControl::reset_landing_state()
land_stayonground = false;
land_motor_lim = false;
land_onslope = false;
+ land_useterrain = false;
}
void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_sp, float eas2tas,
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
index 847ecbb5c..c00d82232 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
@@ -412,12 +412,28 @@ PARAM_DEFINE_FLOAT(FW_LND_TLALT, -1.0f);
PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f);
/**
- * Relative altitude threshold for range finder measurements for use during landing
+ * Enable or disable usage of terrain estimate during landing
*
- * range finder measurements will only be used if the estimated relative altitude (gobal_pos.alt - landing_waypoint.alt) is < FW_LND_RFRALT
- * set to < 0 to disable
- * the correct value of this parameter depends on your range measuring device as well as on the terrain at the landing location
+ * 0: disabled, 1: enabled
*
* @group L1 Control
*/
-PARAM_DEFINE_FLOAT(FW_LND_RFRALT, -1.0f);
+PARAM_DEFINE_INT32(FW_LND_USETER, 0);
+
+/**
+ * Flare, minimum pitch
+ *
+ * Minimum pitch during flare, a positive sign means nose up
+ * Applied once FW_LND_TLALT is reached
+ *
+ */
+PARAM_DEFINE_FLOAT(FW_FLARE_PMIN, 2.5f);
+
+/**
+ * Flare, maximum pitch
+ *
+ * Maximum pitch during flare, a positive sign means nose up
+ * Applied once FW_LND_TLALT is reached
+ *
+ */
+PARAM_DEFINE_FLOAT(FW_FLARE_PMAX, 15.0f);