aboutsummaryrefslogtreecommitdiff
path: root/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp')
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp548
1 files changed, 304 insertions, 244 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 7f13df785..189a19d48 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
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier
+ * Copyright (c) 2013, 2014 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
@@ -89,7 +88,11 @@
#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"
+
+static int _control_task = -1; /**< task handle for sensor task */
/**
@@ -115,25 +118,32 @@ public:
/**
* Start the sensors task.
*
- * @return OK on success.
+ * @return OK on success.
+ */
+ static int start();
+
+ /**
+ * Task status
+ *
+ * @return true if the mainloop is running
*/
- int start();
+ bool task_running() { return _task_running; }
private:
int _mavlink_fd;
bool _task_should_exit; /**< if true, sensor task should exit */
- int _control_task; /**< task handle for sensor task */
+ bool _task_running; /**< if true, task is running in its mainloop */
int _global_pos_sub;
int _pos_sp_triplet_sub;
int _att_sub; /**< vehicle attitude subscription */
- int _attitude_sub; /**< raw rc channels data subscription */
int _airspeed_sub; /**< airspeed subscription */
int _control_mode_sub; /**< vehicle status subscription */
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 _nav_capabilities_pub; /**< navigation capabilities publication */
@@ -147,23 +157,10 @@ 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 */
- bool _setpoint_valid; /**< flag if the position control setpoint is valid */
-
- /** manual control states */
- float _seatbelt_hold_heading; /**< heading the system should hold in seatbelt mode */
- double _loiter_hold_lat;
- double _loiter_hold_lon;
- float _loiter_hold_alt;
- bool _loiter_hold;
-
- double _launch_lat;
- double _launch_lon;
- float _launch_alt;
- bool _launch_valid;
-
/* land states */
/* not in non-abort mode for landing yet */
bool land_noreturn_horizontal;
@@ -180,8 +177,8 @@ private:
/* Landingslope object */
Landingslope landingslope;
+ float flare_curve_alt_rel_last;
- float flare_curve_alt_last;
/* heading hold */
float target_bearing;
@@ -198,15 +195,21 @@ private:
ECL_L1_Pos_Controller _l1_control;
TECS _tecs;
+ fwPosctrl::mTecs _mTecs;
+ bool _was_pos_control_mode;
struct {
float l1_period;
float l1_damping;
float time_const;
+ float time_const_throt;
float min_sink_rate;
float max_sink_rate;
float max_climb_rate;
+ float climbout_diff;
+ float heightrate_p;
+ float speedrate_p;
float throttle_damp;
float integrator_gain;
float vertical_accel_limit;
@@ -226,19 +229,16 @@ private:
float throttle_min;
float throttle_max;
float throttle_cruise;
+ float throttle_slew_max;
float throttle_land_max;
- float loiter_hold_radius;
-
- float heightrate_p;
- float speedrate_p;
-
float land_slope_angle;
float land_H1_virt;
float land_flare_alt_relative;
float land_thrust_lim_alt_relative;
float land_heading_hold_horizontal_distance;
+ float range_finder_rel_alt;
} _parameters; /**< local copies of interesting parameters */
@@ -248,9 +248,13 @@ private:
param_t l1_damping;
param_t time_const;
+ param_t time_const_throt;
param_t min_sink_rate;
param_t max_sink_rate;
param_t max_climb_rate;
+ param_t climbout_diff;
+ param_t heightrate_p;
+ param_t speedrate_p;
param_t throttle_damp;
param_t integrator_gain;
param_t vertical_accel_limit;
@@ -270,19 +274,16 @@ private:
param_t throttle_min;
param_t throttle_max;
param_t throttle_cruise;
+ param_t throttle_slew_max;
param_t throttle_land_max;
- param_t loiter_hold_radius;
-
- param_t heightrate_p;
- param_t speedrate_p;
-
param_t land_slope_angle;
param_t land_H1_virt;
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;
} _parameter_handles; /**< handles for interesting parameters */
@@ -309,6 +310,12 @@ private:
bool vehicle_airspeed_poll();
/**
+ * Check for range finder updates.
+ */
+ bool range_finder_poll();
+
+
+ /**
* Check for position updates.
*/
void vehicle_attitude_poll();
@@ -329,13 +336,18 @@ private:
void navigation_capabilities_publish();
/**
+ * Get the relative alt either from the difference between estimate and waypoint or from the laser range finder
+ */
+ float get_relative_landingalt(float land_setpoint_alt, float current_alt, const struct range_finder_report &range_finder, float range_finder_use_relative_alt);
+
+ /**
* Control position.
*/
- bool control_position(const math::Vector<2> &global_pos, const math::Vector<2> &ground_speed,
+ bool control_position(const math::Vector<2> &global_pos, const math::Vector<3> &ground_speed,
const struct position_setpoint_triplet_s &_pos_sp_triplet);
float calculate_target_airspeed(float airspeed_demand);
- void calculate_gndspeed_undershoot(const math::Vector<2> &current_position, const math::Vector<2> &ground_speed, const struct position_setpoint_triplet_s &pos_sp_triplet);
+ void calculate_gndspeed_undershoot(const math::Vector<2> &current_position, const math::Vector<2> &ground_speed_2d, const struct position_setpoint_triplet_s &pos_sp_triplet);
/**
* Shim for calling task_main from task_create.
@@ -345,7 +357,7 @@ private:
/**
* Main sensor collection task.
*/
- void task_main() __attribute__((noreturn));
+ void task_main();
/*
* Reset takeoff state
@@ -356,6 +368,19 @@ private:
* Reset landing state
*/
void reset_landing_state();
+
+ /*
+ * Call TECS : a wrapper function to call one of the TECS implementations (mTECS is called only if enabled via parameter)
+ * XXX need to clean up/remove this function once mtecs fully replaces TECS
+ */
+ void tecs_update_pitch_throttle(float alt_sp, float v_sp, float eas2tas,
+ float pitch_min_rad, float pitch_max_rad,
+ float throttle_min, float throttle_max, float throttle_cruise,
+ bool climbout_mode, float climbout_pitch_min_rad,
+ float altitude,
+ const math::Vector<3> &ground_speed,
+ tecs_mode mode = TECS_MODE_NORMAL);
+
};
namespace l1_control
@@ -367,14 +392,14 @@ namespace l1_control
#endif
static const int ERROR = -1;
-FixedwingPositionControl *g_control;
+FixedwingPositionControl *g_control = nullptr;
}
FixedwingPositionControl::FixedwingPositionControl() :
_mavlink_fd(-1),
_task_should_exit(false),
- _control_task(-1),
+ _task_running(false),
/* subscriptions */
_global_pos_sub(-1),
@@ -384,46 +409,53 @@ FixedwingPositionControl::FixedwingPositionControl() :
_control_mode_sub(-1),
_params_sub(-1),
_manual_control_sub(-1),
+ _sensor_combined_sub(-1),
+ _range_finder_sub(-1),
/* publications */
_attitude_sp_pub(-1),
_nav_capabilities_pub(-1),
+/* states */
+ _att(),
+ _att_sp(),
+ _nav_capabilities(),
+ _manual(),
+ _airspeed(),
+ _control_mode(),
+ _global_pos(),
+ _pos_sp_triplet(),
+ _sensor_combined(),
+ _range_finder(),
+
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "fw l1 control")),
-/* states */
- _setpoint_valid(false),
- _loiter_hold(false),
land_noreturn_horizontal(false),
land_noreturn_vertical(false),
land_stayonground(false),
land_motor_lim(false),
land_onslope(false),
launch_detected(false),
- last_manual(false),
usePreTakeoffThrust(false),
- flare_curve_alt_last(0.0f),
+ last_manual(false),
+ landingslope(),
+ flare_curve_alt_rel_last(0.0f),
+ target_bearing(0.0f),
launchDetector(),
_airspeed_error(0.0f),
_airspeed_valid(false),
+ _airspeed_last_valid(0),
_groundspeed_undershoot(0.0f),
_global_pos_valid(false),
- _att(),
- _att_sp(),
- _nav_capabilities(),
- _manual(),
- _airspeed(),
- _control_mode(),
- _global_pos(),
- _pos_sp_triplet(),
- _sensor_combined()
+ _l1_control(),
+ _mTecs(),
+ _was_pos_control_mode(false)
{
_nav_capabilities.turn_distance = 0.0f;
_parameter_handles.l1_period = param_find("FW_L1_PERIOD");
_parameter_handles.l1_damping = param_find("FW_L1_DAMPING");
- _parameter_handles.loiter_hold_radius = param_find("FW_LOITER_R");
_parameter_handles.airspeed_min = param_find("FW_AIRSPD_MIN");
_parameter_handles.airspeed_trim = param_find("FW_AIRSPD_TRIM");
@@ -434,6 +466,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
_parameter_handles.roll_limit = param_find("FW_R_LIM");
_parameter_handles.throttle_min = param_find("FW_THR_MIN");
_parameter_handles.throttle_max = param_find("FW_THR_MAX");
+ _parameter_handles.throttle_slew_max = param_find("FW_THR_SLEW_MAX");
_parameter_handles.throttle_cruise = param_find("FW_THR_CRUISE");
_parameter_handles.throttle_land_max = param_find("FW_THR_LND_MAX");
@@ -442,11 +475,14 @@ 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.time_const = param_find("FW_T_TIME_CONST");
+ _parameter_handles.time_const_throt = param_find("FW_T_THRO_CONST");
_parameter_handles.min_sink_rate = param_find("FW_T_SINK_MIN");
_parameter_handles.max_sink_rate = param_find("FW_T_SINK_MAX");
_parameter_handles.max_climb_rate = param_find("FW_T_CLMB_MAX");
+ _parameter_handles.climbout_diff = param_find("FW_CLMBOUT_DIFF");
_parameter_handles.throttle_damp = param_find("FW_T_THR_DAMP");
_parameter_handles.integrator_gain = param_find("FW_T_INTEG_GAIN");
_parameter_handles.vertical_accel_limit = param_find("FW_T_VERT_ACC");
@@ -494,7 +530,6 @@ FixedwingPositionControl::parameters_update()
/* L1 control parameters */
param_get(_parameter_handles.l1_damping, &(_parameters.l1_damping));
param_get(_parameter_handles.l1_period, &(_parameters.l1_period));
- param_get(_parameter_handles.loiter_hold_radius, &(_parameters.loiter_hold_radius));
param_get(_parameter_handles.airspeed_min, &(_parameters.airspeed_min));
param_get(_parameter_handles.airspeed_trim, &(_parameters.airspeed_trim));
@@ -506,10 +541,12 @@ FixedwingPositionControl::parameters_update()
param_get(_parameter_handles.throttle_min, &(_parameters.throttle_min));
param_get(_parameter_handles.throttle_max, &(_parameters.throttle_max));
param_get(_parameter_handles.throttle_cruise, &(_parameters.throttle_cruise));
+ param_get(_parameter_handles.throttle_slew_max, &(_parameters.throttle_slew_max));
param_get(_parameter_handles.throttle_land_max, &(_parameters.throttle_land_max));
param_get(_parameter_handles.time_const, &(_parameters.time_const));
+ param_get(_parameter_handles.time_const_throt, &(_parameters.time_const_throt));
param_get(_parameter_handles.min_sink_rate, &(_parameters.min_sink_rate));
param_get(_parameter_handles.max_sink_rate, &(_parameters.max_sink_rate));
param_get(_parameter_handles.throttle_damp, &(_parameters.throttle_damp));
@@ -521,6 +558,7 @@ FixedwingPositionControl::parameters_update()
param_get(_parameter_handles.speed_weight, &(_parameters.speed_weight));
param_get(_parameter_handles.pitch_damping, &(_parameters.pitch_damping));
param_get(_parameter_handles.max_climb_rate, &(_parameters.max_climb_rate));
+ param_get(_parameter_handles.climbout_diff, &(_parameters.climbout_diff));
param_get(_parameter_handles.heightrate_p, &(_parameters.heightrate_p));
param_get(_parameter_handles.speedrate_p, &(_parameters.speedrate_p));
@@ -531,14 +569,18 @@ FixedwingPositionControl::parameters_update()
param_get(_parameter_handles.land_thrust_lim_alt_relative, &(_parameters.land_thrust_lim_alt_relative));
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));
+
_l1_control.set_l1_damping(_parameters.l1_damping);
_l1_control.set_l1_period(_parameters.l1_period);
_l1_control.set_l1_roll_limit(math::radians(_parameters.roll_limit));
_tecs.set_time_const(_parameters.time_const);
+ _tecs.set_time_const_throt(_parameters.time_const_throt);
_tecs.set_min_sink_rate(_parameters.min_sink_rate);
_tecs.set_max_sink_rate(_parameters.max_sink_rate);
_tecs.set_throttle_damp(_parameters.throttle_damp);
+ _tecs.set_throttle_slewrate(_parameters.throttle_slew_max);
_tecs.set_integrator_gain(_parameters.integrator_gain);
_tecs.set_vertical_accel_limit(_parameters.vertical_accel_limit);
_tecs.set_height_comp_filter_omega(_parameters.height_comp_filter_omega);
@@ -574,6 +616,9 @@ FixedwingPositionControl::parameters_update()
/* Update Launch Detector Parameters */
launchDetector.updateParams();
+ /* Update the mTecs */
+ _mTecs.updateParams();
+
return OK;
}
@@ -586,17 +631,7 @@ FixedwingPositionControl::vehicle_control_mode_poll()
orb_check(_control_mode_sub, &vstatus_updated);
if (vstatus_updated) {
-
- bool was_armed = _control_mode.flag_armed;
-
orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode);
-
- if (!was_armed && _control_mode.flag_armed) {
- _launch_lat = _global_pos.lat;
- _launch_lon = _global_pos.lon;
- _launch_alt = _global_pos.alt;
- _launch_valid = true;
- }
}
}
@@ -626,6 +661,20 @@ 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()
{
@@ -663,14 +712,23 @@ FixedwingPositionControl::vehicle_setpoint_poll()
if (pos_sp_triplet_updated) {
orb_copy(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_sub, &_pos_sp_triplet);
- _setpoint_valid = true;
}
}
void
FixedwingPositionControl::task_main_trampoline(int argc, char *argv[])
{
+ l1_control::g_control = new FixedwingPositionControl();
+
+ if (l1_control::g_control == nullptr) {
+ warnx("OUT OF MEM");
+ return;
+ }
+
+ /* only returns on exit */
l1_control::g_control->task_main();
+ delete l1_control::g_control;
+ l1_control::g_control = nullptr;
}
float
@@ -705,15 +763,15 @@ FixedwingPositionControl::calculate_target_airspeed(float airspeed_demand)
}
void
-FixedwingPositionControl::calculate_gndspeed_undershoot(const math::Vector<2> &current_position, const math::Vector<2> &ground_speed, const struct position_setpoint_triplet_s &pos_sp_triplet)
+FixedwingPositionControl::calculate_gndspeed_undershoot(const math::Vector<2> &current_position, const math::Vector<2> &ground_speed_2d, const struct position_setpoint_triplet_s &pos_sp_triplet)
{
- if (_global_pos_valid && !(pos_sp_triplet.current.type == SETPOINT_TYPE_LOITER)) {
+ if (pos_sp_triplet.current.valid && !(pos_sp_triplet.current.type == SETPOINT_TYPE_LOITER)) {
/* rotate ground speed vector with current attitude */
math::Vector<2> yaw_vector(_R_nb(0, 0), _R_nb(1, 0));
yaw_vector.normalize();
- float ground_speed_body = yaw_vector * ground_speed;
+ float ground_speed_body = yaw_vector * ground_speed_2d;
/* The minimum desired ground speed is the minimum airspeed projected on to the ground using the altitude and horizontal difference between the waypoints if available*/
float distance = 0.0f;
@@ -754,24 +812,43 @@ 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 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 || rel_alt_estimated > range_finder_use_relative_alt ) {
+ return rel_alt_estimated;
+ }
+
+ return range_finder.distance;
+
+}
+
bool
-FixedwingPositionControl::control_position(const math::Vector<2> &current_position, const math::Vector<2> &ground_speed,
+FixedwingPositionControl::control_position(const math::Vector<2> &current_position, const math::Vector<3> &ground_speed,
const struct position_setpoint_triplet_s &pos_sp_triplet)
{
bool setpoint = true;
- calculate_gndspeed_undershoot(current_position, ground_speed, pos_sp_triplet);
+ math::Vector<2> ground_speed_2d = {ground_speed(0), ground_speed(1)};
+ calculate_gndspeed_undershoot(current_position, ground_speed_2d, pos_sp_triplet);
float eas2tas = 1.0f; // XXX calculate actual number based on current measurements
- // XXX re-visit
- float baro_altitude = _global_pos.alt;
-
/* filter speed and altitude for controller */
math::Vector<3> accel_body(_sensor_combined.accelerometer_m_s2);
math::Vector<3> accel_earth = _R_nb * accel_body;
- _tecs.update_50hz(baro_altitude, _airspeed.indicated_airspeed_m_s, _R_nb, accel_body, accel_earth);
+ if (!_mTecs.getEnabled()) {
+ _tecs.update_50hz(_global_pos.alt /* XXX might switch to alt err here */, _airspeed.indicated_airspeed_m_s, _R_nb, accel_body, accel_earth);
+ }
+
+ /* define altitude error */
float altitude_error = _pos_sp_triplet.current.alt - _global_pos.alt;
/* no throttle limit as default */
@@ -781,7 +858,17 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
// XXX this should only execute if auto AND safety off (actuators active),
// else integrators should be constantly reset.
- if (_control_mode.flag_control_position_enabled) {
+ if (pos_sp_triplet.current.valid) {
+
+ if (!_was_pos_control_mode) {
+ /* reset integrators */
+ if (_mTecs.getEnabled()) {
+ _mTecs.resetIntegrators();
+ _mTecs.resetDerivatives(_airspeed.true_airspeed_m_s);
+ }
+ }
+
+ _was_pos_control_mode = true;
/* get circle mode */
bool was_circle_mode = _l1_control.circle_mode();
@@ -795,6 +882,10 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* current waypoint (the one currently heading for) */
math::Vector<2> curr_wp((float)pos_sp_triplet.current.lat, (float)pos_sp_triplet.current.lon);
+ /* Initialize attitude controller integrator reset flags to 0 */
+ _att_sp.roll_reset_integral = false;
+ _att_sp.pitch_reset_integral = false;
+ _att_sp.yaw_reset_integral = false;
/* previous waypoint */
math::Vector<2> prev_wp;
@@ -813,31 +904,29 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
}
- if (pos_sp_triplet.current.type == SETPOINT_TYPE_NORMAL) {
+ if (pos_sp_triplet.current.type == SETPOINT_TYPE_POSITION) {
/* waypoint is a plain navigation waypoint */
- _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed);
+ _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed_2d);
_att_sp.roll_body = _l1_control.nav_roll();
_att_sp.yaw_body = _l1_control.nav_bearing();
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _pos_sp_triplet.current.alt, calculate_target_airspeed(_parameters.airspeed_trim),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, math::radians(_parameters.pitch_limit_min),
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ tecs_update_pitch_throttle(_pos_sp_triplet.current.alt, calculate_target_airspeed(_parameters.airspeed_trim), eas2tas,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ false, math::radians(_parameters.pitch_limit_min), _global_pos.alt, ground_speed);
} else if (pos_sp_triplet.current.type == SETPOINT_TYPE_LOITER) {
/* waypoint is a loiter waypoint */
_l1_control.navigate_loiter(curr_wp, current_position, pos_sp_triplet.current.loiter_radius,
- pos_sp_triplet.current.loiter_direction, ground_speed);
+ pos_sp_triplet.current.loiter_direction, ground_speed_2d);
_att_sp.roll_body = _l1_control.nav_roll();
_att_sp.yaw_body = _l1_control.nav_bearing();
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _pos_sp_triplet.current.alt, calculate_target_airspeed(_parameters.airspeed_trim),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, math::radians(_parameters.pitch_limit_min),
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ tecs_update_pitch_throttle(_pos_sp_triplet.current.alt, calculate_target_airspeed(_parameters.airspeed_trim), eas2tas,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ false, math::radians(_parameters.pitch_limit_min), _global_pos.alt, ground_speed);
} else if (pos_sp_triplet.current.type == SETPOINT_TYPE_LAND) {
@@ -862,7 +951,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
// warnx("NORET: %d, target_bearing: %d, yaw: %d", (int)land_noreturn_horizontal, (int)math::degrees(target_bearing), (int)math::degrees(_att.yaw));
- _l1_control.navigate_heading(target_bearing, _att.yaw, ground_speed);
+ _l1_control.navigate_heading(target_bearing, _att.yaw, ground_speed_2d);
/* limit roll motion to prevent wings from touching the ground first */
_att_sp.roll_body = math::constrain(_att_sp.roll_body, math::radians(-10.0f), math::radians(10.0f));
@@ -872,7 +961,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
} else {
/* normal navigation */
- _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed);
+ _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed_2d);
}
_att_sp.roll_body = _l1_control.nav_roll();
@@ -895,13 +984,14 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
float airspeed_approach = 1.3f * _parameters.airspeed_min;
/* Calculate distance (to landing waypoint) and altitude of last ordinary waypoint L */
- float L_wp_distance = get_distance_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1));
- float L_altitude = landingslope.getLandingSlopeAbsoluteAltitude(L_wp_distance, _pos_sp_triplet.current.alt);
+ float L_altitude_rel = _pos_sp_triplet.previous.valid ? _pos_sp_triplet.previous.alt - _pos_sp_triplet.current.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_desired = landingslope.getLandingSlopeAbsoluteAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp, _pos_sp_triplet.current.alt);
+ float landing_slope_alt_rel_desired = landingslope.getLandingSlopeRelativeAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp);
- if ( (_global_pos.alt < _pos_sp_triplet.current.alt + landingslope.flare_relative_alt()) || land_noreturn_vertical) { //checking for land_noreturn to avoid unwanted climb out
+ 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
/* land with minimal speed */
@@ -911,7 +1001,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* kill the throttle if param requests it */
throttle_max = _parameters.throttle_max;
- if (_global_pos.alt < _pos_sp_triplet.current.alt + landingslope.motor_lim_relative_alt() || land_motor_lim) {
+ if (relative_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;
@@ -920,20 +1010,22 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
}
- float flare_curve_alt = landingslope.getFlareCurveAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp, _pos_sp_triplet.current.alt);
+ float flare_curve_alt_rel = landingslope.getFlareCurveRelativeAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp);
/* avoid climbout */
- if ((flare_curve_alt_last < flare_curve_alt && land_noreturn_vertical) || land_stayonground)
+ if ((flare_curve_alt_rel_last < flare_curve_alt_rel && land_noreturn_vertical) || land_stayonground)
{
- flare_curve_alt = pos_sp_triplet.current.alt;
+ flare_curve_alt_rel = 0.0f; // stay on ground
land_stayonground = true;
}
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, flare_curve_alt, calculate_target_airspeed(airspeed_land),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, flare_pitch_angle_rad,
- 0.0f, throttle_max, throttle_land,
- flare_pitch_angle_rad, math::radians(15.0f));
+ tecs_update_pitch_throttle(_pos_sp_triplet.current.alt + flare_curve_alt_rel,
+ calculate_target_airspeed(airspeed_land), eas2tas,
+ flare_pitch_angle_rad, math::radians(15.0f),
+ 0.0f, throttle_max, throttle_land,
+ false, flare_pitch_angle_rad,
+ _pos_sp_triplet.current.alt + relative_alt, ground_speed,
+ land_motor_lim ? TECS_MODE_LAND_THROTTLELIM : TECS_MODE_LAND);
if (!land_noreturn_vertical) {
mavlink_log_info(_mavlink_fd, "#audio: Landing, flaring");
@@ -941,46 +1033,62 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
}
//warnx("Landing: flare, _global_pos.alt %.1f, flare_curve_alt %.1f, flare_curve_alt_last %.1f, flare_length %.1f, wp_distance %.1f", _global_pos.alt, flare_curve_alt, flare_curve_alt_last, flare_length, wp_distance);
- flare_curve_alt_last = flare_curve_alt;
+ flare_curve_alt_rel_last = flare_curve_alt_rel;
} else {
/* intersect glide slope:
* minimize speed to approach speed
- * if current position is higher or within 10m of slope follow the glide slope
- * if current position is below slope -10m continue on maximum of previous wp altitude or L_altitude until the intersection with the slope
+ * if current position is higher than the slope follow the glide slope (sink to the
+ * glide slope)
+ * also if the system captures the slope it should stay
+ * on the slope (bool land_onslope)
+ * if current position is below the slope continue at previous wp altitude
+ * until the intersection with slope
* */
- float altitude_desired = _global_pos.alt;
- if (_global_pos.alt > landing_slope_alt_desired - 10.0f) {
+ float altitude_desired_rel = relative_alt;
+ if (relative_alt > landing_slope_alt_rel_desired || land_onslope) {
/* stay on slope */
- altitude_desired = landing_slope_alt_desired;
+ altitude_desired_rel = landing_slope_alt_rel_desired;
if (!land_onslope) {
mavlink_log_info(_mavlink_fd, "#audio: Landing, on slope");
land_onslope = true;
}
} else {
/* continue horizontally */
- altitude_desired = math::max(_global_pos.alt, L_altitude);
+ altitude_desired_rel = _pos_sp_triplet.previous.valid ? L_altitude_rel : relative_alt;
}
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, altitude_desired, calculate_target_airspeed(airspeed_approach),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, math::radians(_parameters.pitch_limit_min),
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ tecs_update_pitch_throttle(_pos_sp_triplet.current.alt + altitude_desired_rel,
+ calculate_target_airspeed(airspeed_approach), eas2tas,
+ math::radians(_parameters.pitch_limit_min),
+ math::radians(_parameters.pitch_limit_max),
+ _parameters.throttle_min,
+ _parameters.throttle_max,
+ _parameters.throttle_cruise,
+ false,
+ math::radians(_parameters.pitch_limit_min),
+ _pos_sp_triplet.current.alt + relative_alt,
+ ground_speed);
}
} else if (pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF) {
/* Perform launch detection */
-// warnx("Launch detection running");
if(!launch_detected) { //do not do further checks once a launch was detected
if (launchDetector.launchDetectionEnabled()) {
static hrt_abstime last_sent = 0;
if(hrt_absolute_time() - last_sent > 4e6) {
-// warnx("Launch detection running");
mavlink_log_info(_mavlink_fd, "#audio: Launchdetection running");
last_sent = hrt_absolute_time();
}
+
+ /* Tell the attitude controller to stop integrating while we are waiting
+ * for the launch */
+ _att_sp.roll_reset_integral = true;
+ _att_sp.pitch_reset_integral = true;
+ _att_sp.yaw_reset_integral = true;
+
+ /* Detect launch */
launchDetector.update(_sensor_combined.accelerometer_m_s2[0]);
if (launchDetector.getLaunchDetected()) {
launch_detected = true;
@@ -993,7 +1101,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
}
}
- _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed);
+ _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed_2d);
_att_sp.roll_body = _l1_control.nav_roll();
_att_sp.yaw_body = _l1_control.nav_bearing();
@@ -1001,25 +1109,39 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
usePreTakeoffThrust = false;
/* apply minimum pitch and limit roll if target altitude is not within 10 meters */
- if (altitude_error > 15.0f) {
+ if (_parameters.climbout_diff > 0.001f && altitude_error > _parameters.climbout_diff) {
/* enforce a minimum of 10 degrees pitch up on takeoff, or take parameter */
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _pos_sp_triplet.current.alt, calculate_target_airspeed(1.3f * _parameters.airspeed_min),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- true, math::max(math::radians(pos_sp_triplet.current.pitch_min), math::radians(10.0f)),
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ tecs_update_pitch_throttle(_pos_sp_triplet.current.alt,
+ calculate_target_airspeed(1.3f * _parameters.airspeed_min),
+ eas2tas,
+ math::radians(_parameters.pitch_limit_min),
+ math::radians(_parameters.pitch_limit_max),
+ _parameters.throttle_min, _parameters.throttle_max,
+ _parameters.throttle_cruise,
+ true,
+ math::max(math::radians(pos_sp_triplet.current.pitch_min),
+ math::radians(10.0f)),
+ _global_pos.alt,
+ ground_speed,
+ TECS_MODE_TAKEOFF);
/* limit roll motion to ensure enough lift */
_att_sp.roll_body = math::constrain(_att_sp.roll_body, math::radians(-15.0f), math::radians(15.0f));
} else {
-
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _pos_sp_triplet.current.alt, calculate_target_airspeed(_parameters.airspeed_trim),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, math::radians(_parameters.pitch_limit_min),
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ tecs_update_pitch_throttle(_pos_sp_triplet.current.alt,
+ calculate_target_airspeed(_parameters.airspeed_trim),
+ eas2tas,
+ math::radians(_parameters.pitch_limit_min),
+ math::radians(_parameters.pitch_limit_max),
+ _parameters.throttle_min,
+ _parameters.throttle_max,
+ _parameters.throttle_cruise,
+ false,
+ math::radians(_parameters.pitch_limit_min),
+ _global_pos.alt,
+ ground_speed);
}
} else {
@@ -1027,15 +1149,6 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
}
}
- // warnx("nav bearing: %8.4f bearing err: %8.4f target bearing: %8.4f", (double)_l1_control.nav_bearing(),
- // (double)_l1_control.bearing_error(), (double)_l1_control.target_bearing());
- // warnx("prev wp: %8.4f/%8.4f, next wp: %8.4f/%8.4f prev:%s", (double)prev_wp(0), (double)prev_wp(1),
- // (double)next_wp(0), (double)next_wp(1), (pos_sp_triplet.previous_valid) ? "valid" : "invalid");
-
- // XXX at this point we always want no loiter hold if a
- // mission is active
- _loiter_hold = false;
-
/* reset landing state */
if (pos_sp_triplet.current.type != SETPOINT_TYPE_LAND) {
reset_landing_state();
@@ -1051,91 +1164,10 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
_att_sp.roll_reset_integral = true;
}
- } else if (0/* easy mode enabled */) {
-
- /** EASY FLIGHT **/
-
- if (0/* switched from another mode to easy */) {
- _seatbelt_hold_heading = _att.yaw;
- }
-
- if (0/* easy on and manual control yaw non-zero */) {
- _seatbelt_hold_heading = _att.yaw + _manual.yaw;
- }
-
- //XXX not used
-
- /* climb out control */
-// bool climb_out = false;
-//
-// /* user wants to climb out */
-// if (_manual.pitch > 0.3f && _manual.throttle > 0.8f) {
-// climb_out = true;
-// }
-
- /* if in seatbelt mode, set airspeed based on manual control */
-
- // XXX check if ground speed undershoot should be applied here
- float seatbelt_airspeed = _parameters.airspeed_min +
- (_parameters.airspeed_max - _parameters.airspeed_min) *
- _manual.throttle;
-
- _l1_control.navigate_heading(_seatbelt_hold_heading, _att.yaw, ground_speed);
- _att_sp.roll_body = _l1_control.nav_roll();
- _att_sp.yaw_body = _l1_control.nav_bearing();
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.pitch * 2.0f,
- seatbelt_airspeed,
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, _parameters.pitch_limit_min,
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- _parameters.pitch_limit_min, _parameters.pitch_limit_max);
-
- } else if (0/* seatbelt mode enabled */) {
-
- /** SEATBELT FLIGHT **/
-
- if (0/* switched from another mode to seatbelt */) {
- _seatbelt_hold_heading = _att.yaw;
- }
-
- if (0/* seatbelt on and manual control yaw non-zero */) {
- _seatbelt_hold_heading = _att.yaw + _manual.yaw;
- }
-
- /* if in seatbelt mode, set airspeed based on manual control */
-
- // XXX check if ground speed undershoot should be applied here
- float seatbelt_airspeed = _parameters.airspeed_min +
- (_parameters.airspeed_max - _parameters.airspeed_min) *
- _manual.throttle;
-
- /* user switched off throttle */
- if (_manual.throttle < 0.1f) {
- throttle_max = 0.0f;
- /* switch to pure pitch based altitude control, give up speed */
- _tecs.set_speed_weight(0.0f);
- }
-
- /* climb out control */
- bool climb_out = false;
-
- /* user wants to climb out */
- if (_manual.pitch > 0.3f && _manual.throttle > 0.8f) {
- climb_out = true;
- }
-
- _l1_control.navigate_heading(_seatbelt_hold_heading, _att.yaw, ground_speed);
- _att_sp.roll_body = _manual.roll;
- _att_sp.yaw_body = _manual.yaw;
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.pitch * 2.0f,
- seatbelt_airspeed,
- _airspeed.indicated_airspeed_m_s, eas2tas,
- climb_out, _parameters.pitch_limit_min,
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- _parameters.pitch_limit_min, _parameters.pitch_limit_max);
-
} else {
+ _was_pos_control_mode = false;
+
/** MANUAL FLIGHT **/
/* no flight mode applies, do not publish an attitude setpoint */
@@ -1152,9 +1184,9 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
_att_sp.thrust = launchDetector.getThrottlePreTakeoff();
}
else {
- _att_sp.thrust = math::min(_tecs.get_throttle_demand(), throttle_max);
+ _att_sp.thrust = math::min(_mTecs.getEnabled() ? _mTecs.getThrottleSetpoint() : _tecs.get_throttle_demand(), throttle_max);
}
- _att_sp.pitch_body = _tecs.get_pitch_demand();
+ _att_sp.pitch_body = _mTecs.getEnabled() ? _mTecs.getPitchSetpoint() : _tecs.get_pitch_demand();
if (_control_mode.flag_control_position_enabled) {
last_manual = false;
@@ -1170,10 +1202,6 @@ void
FixedwingPositionControl::task_main()
{
- /* inform about start */
- warnx("Initializing..");
- fflush(stdout);
-
/*
* do subscriptions
*/
@@ -1185,6 +1213,7 @@ 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 vehicle status updates to 5Hz */
orb_set_interval(_control_mode_sub, 200);
@@ -1207,6 +1236,8 @@ FixedwingPositionControl::task_main()
fds[1].fd = _global_pos_sub;
fds[1].events = POLLIN;
+ _task_running = true;
+
while (!_task_should_exit) {
/* wait for up to 500ms for data */
@@ -1246,14 +1277,6 @@ FixedwingPositionControl::task_main()
_mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
}
- static uint64_t last_run = 0;
- float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
- last_run = hrt_absolute_time();
-
- /* guard against too large deltaT's */
- if (deltaT > 1.0f)
- deltaT = 0.01f;
-
/* load local copies */
orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
@@ -1264,9 +1287,10 @@ FixedwingPositionControl::task_main()
vehicle_setpoint_poll();
vehicle_sensor_combined_poll();
vehicle_airspeed_poll();
+ range_finder_poll();
// vehicle_baro_poll();
- math::Vector<2> ground_speed(_global_pos.vel_n, _global_pos.vel_e);
+ math::Vector<3> ground_speed(_global_pos.vel_n, _global_pos.vel_e, _global_pos.vel_d);
math::Vector<2> current_position((float)_global_pos.lat, (float)_global_pos.lon);
/*
@@ -1306,6 +1330,8 @@ FixedwingPositionControl::task_main()
perf_end(_loop_perf);
}
+ _task_running = false;
+
warnx("exiting.\n");
_control_task = -1;
@@ -1328,6 +1354,39 @@ void FixedwingPositionControl::reset_landing_state()
land_onslope = false;
}
+void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_sp, float eas2tas,
+ float pitch_min_rad, float pitch_max_rad,
+ float throttle_min, float throttle_max, float throttle_cruise,
+ bool climbout_mode, float climbout_pitch_min_rad,
+ float altitude,
+ const math::Vector<3> &ground_speed,
+ tecs_mode mode)
+{
+ if (_mTecs.getEnabled()) {
+ /* Using mtecs library: prepare arguments for mtecs call */
+ float flightPathAngle = 0.0f;
+ float ground_speed_length = ground_speed.length();
+ if (ground_speed_length > FLT_EPSILON) {
+ flightPathAngle = -asinf(ground_speed(2)/ground_speed_length);
+ }
+ fwPosctrl::LimitOverride limitOverride;
+ if (climbout_mode) {
+ limitOverride.enablePitchMinOverride(M_RAD_TO_DEG_F * climbout_pitch_min_rad);
+ } else {
+ limitOverride.disablePitchMinOverride();
+ }
+ _mTecs.updateAltitudeSpeed(flightPathAngle, altitude, alt_sp, _airspeed.true_airspeed_m_s, v_sp, mode,
+ limitOverride);
+ } else {
+ /* Using tecs library */
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, altitude, alt_sp, v_sp,
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ climbout_mode, climbout_pitch_min_rad,
+ throttle_min, throttle_max, throttle_cruise,
+ pitch_min_rad, pitch_max_rad);
+ }
+}
+
int
FixedwingPositionControl::start()
{
@@ -1337,7 +1396,7 @@ FixedwingPositionControl::start()
_control_task = task_spawn_cmd("fw_pos_control_l1",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 4048,
+ 2000,
(main_t)&FixedwingPositionControl::task_main_trampoline,
nullptr);
@@ -1359,17 +1418,18 @@ int fw_pos_control_l1_main(int argc, char *argv[])
if (l1_control::g_control != nullptr)
errx(1, "already running");
- l1_control::g_control = new FixedwingPositionControl;
-
- if (l1_control::g_control == nullptr)
- errx(1, "alloc failed");
-
- if (OK != l1_control::g_control->start()) {
- delete l1_control::g_control;
- l1_control::g_control = nullptr;
+ if (OK != FixedwingPositionControl::start()) {
err(1, "start failed");
}
+ /* avoid memory fragmentation by not exiting start handler until the task has fully started */
+ while (l1_control::g_control == nullptr || !l1_control::g_control->task_running()) {
+ usleep(50000);
+ printf(".");
+ fflush(stdout);
+ }
+ printf("\n");
+
exit(0);
}