aboutsummaryrefslogtreecommitdiff
path: root/src/modules/fw_att_control/fw_att_control_main.cpp
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/fw_att_control/fw_att_control_main.cpp')
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp414
1 files changed, 312 insertions, 102 deletions
diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp
index 60c902ce5..3cd4ce928 100644
--- a/src/modules/fw_att_control/fw_att_control_main.cpp
+++ b/src/modules/fw_att_control/fw_att_control_main.cpp
@@ -37,6 +37,7 @@
* Implementation of a generic attitude controller based on classic orthogonal PIDs.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*
*/
@@ -62,6 +63,7 @@
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/parameter_update.h>
+#include <uORB/topics/vehicle_global_position.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <systemlib/pid/pid.h>
@@ -111,13 +113,15 @@ private:
int _att_sp_sub; /**< vehicle attitude setpoint */
int _attitude_sub; /**< raw rc channels data subscription */
int _airspeed_sub; /**< airspeed subscription */
- int _vcontrol_mode_sub; /**< vehicle status subscription */
+ int _vcontrol_mode_sub; /**< vehicle status subscription */
int _params_sub; /**< notification of parameter updates */
int _manual_sub; /**< notification of manual control updates */
+ int _global_pos_sub; /**< global position subscription */
orb_advert_t _rate_sp_pub; /**< rate setpoint publication */
orb_advert_t _attitude_sp_pub; /**< attitude setpoint point */
orb_advert_t _actuators_0_pub; /**< actuator control group 0 setpoint */
+ orb_advert_t _actuators_1_pub; /**< actuator control group 1 setpoint (Airframe) */
struct vehicle_attitude_s _att; /**< vehicle attitude */
struct accel_report _accel; /**< body frame accelerations */
@@ -126,17 +130,21 @@ private:
struct airspeed_s _airspeed; /**< airspeed */
struct vehicle_control_mode_s _vcontrol_mode; /**< vehicle control mode */
struct actuator_controls_s _actuators; /**< actuator control inputs */
+ struct actuator_controls_s _actuators_airframe; /**< actuator control inputs */
+ struct vehicle_global_position_s _global_pos; /**< global position */
perf_counter_t _loop_perf; /**< loop performance counter */
+ perf_counter_t _nonfinite_input_perf; /**< performance counter for non finite input */
+ perf_counter_t _nonfinite_output_perf; /**< performance counter for non finite output */
bool _setpoint_valid; /**< flag if the position control setpoint is valid */
- bool _airspeed_valid; /**< flag if the airspeed measurement is valid */
struct {
float tconst;
float p_p;
float p_d;
float p_i;
+ float p_ff;
float p_rmax_pos;
float p_rmax_neg;
float p_integrator_max;
@@ -144,17 +152,32 @@ private:
float r_p;
float r_d;
float r_i;
+ float r_ff;
float r_integrator_max;
float r_rmax;
float y_p;
float y_i;
float y_d;
+ float y_ff;
float y_roll_feedforward;
float y_integrator_max;
+ float y_coordinated_min_speed;
+ float y_rmax;
float airspeed_min;
float airspeed_trim;
float airspeed_max;
+
+ float trim_roll;
+ float trim_pitch;
+ float trim_yaw;
+ float rollsp_offset_deg; /**< Roll Setpoint Offset in deg */
+ float pitchsp_offset_deg; /**< Pitch Setpoint Offset in deg */
+ float rollsp_offset_rad; /**< Roll Setpoint Offset in rad */
+ float pitchsp_offset_rad; /**< Pitch Setpoint Offset in rad */
+ float man_roll_max; /**< Max Roll in rad */
+ float man_pitch_max; /**< Max Pitch in rad */
+
} _parameters; /**< local copies of interesting parameters */
struct {
@@ -163,6 +186,7 @@ private:
param_t p_p;
param_t p_d;
param_t p_i;
+ param_t p_ff;
param_t p_rmax_pos;
param_t p_rmax_neg;
param_t p_integrator_max;
@@ -170,17 +194,29 @@ private:
param_t r_p;
param_t r_d;
param_t r_i;
+ param_t r_ff;
param_t r_integrator_max;
param_t r_rmax;
param_t y_p;
param_t y_i;
param_t y_d;
+ param_t y_ff;
param_t y_roll_feedforward;
param_t y_integrator_max;
+ param_t y_coordinated_min_speed;
+ param_t y_rmax;
param_t airspeed_min;
param_t airspeed_trim;
param_t airspeed_max;
+
+ param_t trim_roll;
+ param_t trim_pitch;
+ param_t trim_yaw;
+ param_t rollsp_offset_deg;
+ param_t pitchsp_offset_deg;
+ param_t man_roll_max;
+ param_t man_pitch_max;
} _parameter_handles; /**< handles for interesting parameters */
@@ -214,7 +250,7 @@ private:
/**
* Check for airspeed updates.
*/
- bool vehicle_airspeed_poll();
+ void vehicle_airspeed_poll();
/**
* Check for accel updates.
@@ -227,6 +263,11 @@ private:
void vehicle_setpoint_poll();
/**
+ * Check for global position updates.
+ */
+ void global_pos_poll();
+
+ /**
* Shim for calling task_main from task_create.
*/
static void task_main_trampoline(int argc, char *argv[]);
@@ -234,7 +275,7 @@ private:
/**
* Main sensor collection task.
*/
- void task_main() __attribute__((noreturn));
+ void task_main();
};
namespace att_control
@@ -261,43 +302,69 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
_vcontrol_mode_sub(-1),
_params_sub(-1),
_manual_sub(-1),
+ _global_pos_sub(-1),
/* publications */
_rate_sp_pub(-1),
- _actuators_0_pub(-1),
_attitude_sp_pub(-1),
+ _actuators_0_pub(-1),
+ _actuators_1_pub(-1),
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "fw att control")),
+ _nonfinite_input_perf(perf_alloc(PC_COUNT, "fw att control nonfinite input")),
+ _nonfinite_output_perf(perf_alloc(PC_COUNT, "fw att control nonfinite output")),
/* states */
- _setpoint_valid(false),
- _airspeed_valid(false)
+ _setpoint_valid(false)
{
+ /* safely initialize structs */
+ _att = {};
+ _accel = {};
+ _att_sp = {};
+ _manual = {};
+ _airspeed = {};
+ _vcontrol_mode = {};
+ _actuators = {};
+ _actuators_airframe = {};
+ _global_pos = {};
+
+
_parameter_handles.tconst = param_find("FW_ATT_TC");
- _parameter_handles.p_p = param_find("FW_P_P");
- _parameter_handles.p_d = param_find("FW_P_D");
- _parameter_handles.p_i = param_find("FW_P_I");
+ _parameter_handles.p_p = param_find("FW_PR_P");
+ _parameter_handles.p_i = param_find("FW_PR_I");
+ _parameter_handles.p_ff = param_find("FW_PR_FF");
_parameter_handles.p_rmax_pos = param_find("FW_P_RMAX_POS");
_parameter_handles.p_rmax_neg = param_find("FW_P_RMAX_NEG");
- _parameter_handles.p_integrator_max = param_find("FW_P_IMAX");
+ _parameter_handles.p_integrator_max = param_find("FW_PR_IMAX");
_parameter_handles.p_roll_feedforward = param_find("FW_P_ROLLFF");
- _parameter_handles.r_p = param_find("FW_R_P");
- _parameter_handles.r_d = param_find("FW_R_D");
- _parameter_handles.r_i = param_find("FW_R_I");
- _parameter_handles.r_integrator_max = param_find("FW_R_IMAX");
+ _parameter_handles.r_p = param_find("FW_RR_P");
+ _parameter_handles.r_i = param_find("FW_RR_I");
+ _parameter_handles.r_ff = param_find("FW_RR_FF");
+ _parameter_handles.r_integrator_max = param_find("FW_RR_IMAX");
_parameter_handles.r_rmax = param_find("FW_R_RMAX");
- _parameter_handles.y_p = param_find("FW_Y_P");
- _parameter_handles.y_i = param_find("FW_Y_I");
- _parameter_handles.y_d = param_find("FW_Y_D");
- _parameter_handles.y_roll_feedforward = param_find("FW_Y_ROLLFF");
- _parameter_handles.y_integrator_max = param_find("FW_Y_IMAX");
+ _parameter_handles.y_p = param_find("FW_YR_P");
+ _parameter_handles.y_i = param_find("FW_YR_I");
+ _parameter_handles.y_ff = param_find("FW_YR_FF");
+ _parameter_handles.y_integrator_max = param_find("FW_YR_IMAX");
+ _parameter_handles.y_rmax = param_find("FW_Y_RMAX");
_parameter_handles.airspeed_min = param_find("FW_AIRSPD_MIN");
_parameter_handles.airspeed_trim = param_find("FW_AIRSPD_TRIM");
_parameter_handles.airspeed_max = param_find("FW_AIRSPD_MAX");
+ _parameter_handles.y_coordinated_min_speed = param_find("FW_YCO_VMIN");
+
+ _parameter_handles.trim_roll = param_find("TRIM_ROLL");
+ _parameter_handles.trim_pitch = param_find("TRIM_PITCH");
+ _parameter_handles.trim_yaw = param_find("TRIM_YAW");
+ _parameter_handles.rollsp_offset_deg = param_find("FW_RSP_OFF");
+ _parameter_handles.pitchsp_offset_deg = param_find("FW_PSP_OFF");
+
+ _parameter_handles.man_roll_max = param_find("FW_MAN_R_MAX");
+ _parameter_handles.man_pitch_max = param_find("FW_MAN_P_MAX");
+
/* fetch initial parameter values */
parameters_update();
}
@@ -324,6 +391,10 @@ FixedwingAttitudeControl::~FixedwingAttitudeControl()
} while (_control_task != -1);
}
+ perf_free(_loop_perf);
+ perf_free(_nonfinite_input_perf);
+ perf_free(_nonfinite_output_perf);
+
att_control::g_control = nullptr;
}
@@ -333,53 +404,69 @@ FixedwingAttitudeControl::parameters_update()
param_get(_parameter_handles.tconst, &(_parameters.tconst));
param_get(_parameter_handles.p_p, &(_parameters.p_p));
- param_get(_parameter_handles.p_d, &(_parameters.p_d));
param_get(_parameter_handles.p_i, &(_parameters.p_i));
+ param_get(_parameter_handles.p_ff, &(_parameters.p_ff));
param_get(_parameter_handles.p_rmax_pos, &(_parameters.p_rmax_pos));
param_get(_parameter_handles.p_rmax_neg, &(_parameters.p_rmax_neg));
param_get(_parameter_handles.p_integrator_max, &(_parameters.p_integrator_max));
param_get(_parameter_handles.p_roll_feedforward, &(_parameters.p_roll_feedforward));
param_get(_parameter_handles.r_p, &(_parameters.r_p));
- param_get(_parameter_handles.r_d, &(_parameters.r_d));
param_get(_parameter_handles.r_i, &(_parameters.r_i));
+ param_get(_parameter_handles.r_ff, &(_parameters.r_ff));
+
param_get(_parameter_handles.r_integrator_max, &(_parameters.r_integrator_max));
param_get(_parameter_handles.r_rmax, &(_parameters.r_rmax));
param_get(_parameter_handles.y_p, &(_parameters.y_p));
param_get(_parameter_handles.y_i, &(_parameters.y_i));
- param_get(_parameter_handles.y_d, &(_parameters.y_d));
- param_get(_parameter_handles.y_roll_feedforward, &(_parameters.y_roll_feedforward));
+ param_get(_parameter_handles.y_ff, &(_parameters.y_ff));
param_get(_parameter_handles.y_integrator_max, &(_parameters.y_integrator_max));
+ param_get(_parameter_handles.y_coordinated_min_speed, &(_parameters.y_coordinated_min_speed));
+ param_get(_parameter_handles.y_rmax, &(_parameters.y_rmax));
param_get(_parameter_handles.airspeed_min, &(_parameters.airspeed_min));
param_get(_parameter_handles.airspeed_trim, &(_parameters.airspeed_trim));
param_get(_parameter_handles.airspeed_max, &(_parameters.airspeed_max));
+ param_get(_parameter_handles.trim_roll, &(_parameters.trim_roll));
+ param_get(_parameter_handles.trim_pitch, &(_parameters.trim_pitch));
+ param_get(_parameter_handles.trim_yaw, &(_parameters.trim_yaw));
+ param_get(_parameter_handles.rollsp_offset_deg, &(_parameters.rollsp_offset_deg));
+ param_get(_parameter_handles.pitchsp_offset_deg, &(_parameters.pitchsp_offset_deg));
+ _parameters.rollsp_offset_rad = math::radians(_parameters.rollsp_offset_deg);
+ _parameters.pitchsp_offset_rad = math::radians(_parameters.pitchsp_offset_deg);
+ param_get(_parameter_handles.man_roll_max, &(_parameters.man_roll_max));
+ param_get(_parameter_handles.man_pitch_max, &(_parameters.man_pitch_max));
+ _parameters.man_roll_max = math::radians(_parameters.man_roll_max);
+ _parameters.man_pitch_max = math::radians(_parameters.man_pitch_max);
+
+
/* pitch control parameters */
_pitch_ctrl.set_time_constant(_parameters.tconst);
- _pitch_ctrl.set_k_p(math::radians(_parameters.p_p));
- _pitch_ctrl.set_k_i(math::radians(_parameters.p_i));
- _pitch_ctrl.set_k_d(math::radians(_parameters.p_d));
- _pitch_ctrl.set_integrator_max(math::radians(_parameters.p_integrator_max));
+ _pitch_ctrl.set_k_p(_parameters.p_p);
+ _pitch_ctrl.set_k_i(_parameters.p_i);
+ _pitch_ctrl.set_k_ff(_parameters.p_ff);
+ _pitch_ctrl.set_integrator_max(_parameters.p_integrator_max);
_pitch_ctrl.set_max_rate_pos(math::radians(_parameters.p_rmax_pos));
_pitch_ctrl.set_max_rate_neg(math::radians(_parameters.p_rmax_neg));
- _pitch_ctrl.set_roll_ff(math::radians(_parameters.p_roll_feedforward));
+ _pitch_ctrl.set_roll_ff(_parameters.p_roll_feedforward);
/* roll control parameters */
_roll_ctrl.set_time_constant(_parameters.tconst);
- _roll_ctrl.set_k_p(math::radians(_parameters.r_p));
- _roll_ctrl.set_k_i(math::radians(_parameters.r_i));
- _roll_ctrl.set_k_d(math::radians(_parameters.r_d));
- _roll_ctrl.set_integrator_max(math::radians(_parameters.r_integrator_max));
+ _roll_ctrl.set_k_p(_parameters.r_p);
+ _roll_ctrl.set_k_i(_parameters.r_i);
+ _roll_ctrl.set_k_ff(_parameters.r_ff);
+ _roll_ctrl.set_integrator_max(_parameters.r_integrator_max);
_roll_ctrl.set_max_rate(math::radians(_parameters.r_rmax));
/* yaw control parameters */
- _yaw_ctrl.set_k_side(math::radians(_parameters.y_p));
- _yaw_ctrl.set_k_i(math::radians(_parameters.y_i));
- _yaw_ctrl.set_k_d(math::radians(_parameters.y_d));
- _yaw_ctrl.set_k_roll_ff(math::radians(_parameters.y_roll_feedforward));
- _yaw_ctrl.set_integrator_max(math::radians(_parameters.y_integrator_max));
+ _yaw_ctrl.set_k_p(_parameters.y_p);
+ _yaw_ctrl.set_k_i(_parameters.y_i);
+ _yaw_ctrl.set_k_ff(_parameters.y_ff);
+ _yaw_ctrl.set_integrator_max(_parameters.y_integrator_max);
+ _yaw_ctrl.set_coordinated_min_speed(_parameters.y_coordinated_min_speed);
+ _yaw_ctrl.set_max_rate(math::radians(_parameters.y_rmax));
return OK;
}
@@ -412,7 +499,7 @@ FixedwingAttitudeControl::vehicle_manual_poll()
}
}
-bool
+void
FixedwingAttitudeControl::vehicle_airspeed_poll()
{
/* check if there is a new position */
@@ -421,10 +508,8 @@ FixedwingAttitudeControl::vehicle_airspeed_poll()
if (airspeed_updated) {
orb_copy(ORB_ID(airspeed), _airspeed_sub, &_airspeed);
- return true;
+// warnx("airspeed poll: ind: %.4f, true: %.4f", _airspeed.indicated_airspeed_m_s, _airspeed.true_airspeed_m_s);
}
-
- return false;
}
void
@@ -453,6 +538,18 @@ FixedwingAttitudeControl::vehicle_setpoint_poll()
}
void
+FixedwingAttitudeControl::global_pos_poll()
+{
+ /* check if there is a new global position */
+ bool global_pos_updated;
+ orb_check(_global_pos_sub, &global_pos_updated);
+
+ if (global_pos_updated) {
+ orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
+ }
+}
+
+void
FixedwingAttitudeControl::task_main_trampoline(int argc, char *argv[])
{
att_control::g_control->task_main();
@@ -476,6 +573,7 @@ FixedwingAttitudeControl::task_main()
_vcontrol_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
_params_sub = orb_subscribe(ORB_ID(parameter_update));
_manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
+ _global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
/* rate limit vehicle status updates to 5Hz */
orb_set_interval(_vcontrol_mode_sub, 200);
@@ -485,7 +583,7 @@ FixedwingAttitudeControl::task_main()
parameters_update();
/* get an initial update for all sensor and status data */
- (void)vehicle_airspeed_poll();
+ vehicle_airspeed_poll();
vehicle_setpoint_poll();
vehicle_accel_poll();
vehicle_control_mode_poll();
@@ -502,6 +600,8 @@ FixedwingAttitudeControl::task_main()
while (!_task_should_exit) {
+ static int loop_counter = 0;
+
/* wait for up to 500ms for data */
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
@@ -542,7 +642,7 @@ FixedwingAttitudeControl::task_main()
/* load local copies */
orb_copy(ORB_ID(vehicle_attitude), _att_sub, &_att);
- _airspeed_valid = vehicle_airspeed_poll();
+ vehicle_airspeed_poll();
vehicle_setpoint_poll();
@@ -552,6 +652,8 @@ FixedwingAttitudeControl::task_main()
vehicle_manual_poll();
+ global_pos_poll();
+
/* lock integrator until control is started */
bool lock_integrator;
@@ -562,55 +664,82 @@ FixedwingAttitudeControl::task_main()
lock_integrator = true;
}
+ /* Simple handling of failsafe: deploy parachute if failsafe is on */
+ if (_vcontrol_mode.flag_control_termination_enabled) {
+ _actuators_airframe.control[1] = 1.0f;
+// warnx("_actuators_airframe.control[1] = 1.0f;");
+ } else {
+ _actuators_airframe.control[1] = 0.0f;
+// warnx("_actuators_airframe.control[1] = -1.0f;");
+ }
+
/* decide if in stabilized or full manual control */
if (_vcontrol_mode.flag_control_attitude_enabled) {
- /* scale from radians to normalized -1 .. 1 range */
- const float actuator_scaling = 1.0f / (M_PI_F / 4.0f);
-
/* scale around tuning airspeed */
float airspeed;
- /* if airspeed is smaller than min, the sensor is not giving good readings */
- if (!_airspeed_valid ||
- (_airspeed.indicated_airspeed_m_s < _parameters.airspeed_min) ||
- !isfinite(_airspeed.indicated_airspeed_m_s)) {
- airspeed = _parameters.airspeed_min + (_parameters.airspeed_max - _parameters.airspeed_min) / 2.0f;
-
+ /* if airspeed is not updating, we assume the normal average speed */
+ if (bool nonfinite = !isfinite(_airspeed.true_airspeed_m_s) ||
+ hrt_elapsed_time(&_airspeed.timestamp) > 1e6) {
+ airspeed = _parameters.airspeed_trim;
+ if (nonfinite) {
+ perf_count(_nonfinite_input_perf);
+ }
} else {
- airspeed = _airspeed.indicated_airspeed_m_s;
+ airspeed = _airspeed.true_airspeed_m_s;
}
- float airspeed_scaling = _parameters.airspeed_trim / airspeed;
- //warnx("aspd scale: %6.2f act scale: %6.2f", airspeed_scaling, actuator_scaling);
+ /*
+ * For scaling our actuators using anything less than the min (close to stall)
+ * speed doesn't make any sense - its the strongest reasonable deflection we
+ * want to do in flight and its the baseline a human pilot would choose.
+ *
+ * Forcing the scaling to this value allows reasonable handheld tests.
+ */
+
+ float airspeed_scaling = _parameters.airspeed_trim / ((airspeed < _parameters.airspeed_min) ? _parameters.airspeed_min : airspeed);
- float roll_sp, pitch_sp;
+ float roll_sp = _parameters.rollsp_offset_rad;
+ float pitch_sp = _parameters.pitchsp_offset_rad;
float throttle_sp = 0.0f;
if (_vcontrol_mode.flag_control_velocity_enabled || _vcontrol_mode.flag_control_position_enabled) {
- roll_sp = _att_sp.roll_body;
- pitch_sp = _att_sp.pitch_body;
+ /* read in attitude setpoint from attitude setpoint uorb topic */
+ roll_sp = _att_sp.roll_body + _parameters.rollsp_offset_rad;
+ pitch_sp = _att_sp.pitch_body + _parameters.pitchsp_offset_rad;
throttle_sp = _att_sp.thrust;
/* reset integrals where needed */
- if (_att_sp.roll_reset_integral)
+ if (_att_sp.roll_reset_integral) {
_roll_ctrl.reset_integrator();
-
+ }
+ if (_att_sp.pitch_reset_integral) {
+ _pitch_ctrl.reset_integrator();
+ }
+ if (_att_sp.yaw_reset_integral) {
+ _yaw_ctrl.reset_integrator();
+ }
} else {
/*
* Scale down roll and pitch as the setpoints are radians
- * and a typical remote can only do 45 degrees, the mapping is
- * -1..+1 to -45..+45 degrees or -0.75..+0.75 radians.
+ * and a typical remote can only do around 45 degrees, the mapping is
+ * -1..+1 to -man_roll_max rad..+man_roll_max rad (equivalent for pitch)
*
* With this mapping the stick angle is a 1:1 representation of
- * the commanded attitude. If more than 45 degrees are desired,
- * a scaling parameter can be applied to the remote.
+ * the commanded attitude.
+ *
+ * The trim gets subtracted here from the manual setpoint to get
+ * the intended attitude setpoint. Later, after the rate control step the
+ * trim is added again to the control signal.
*/
- roll_sp = _manual.roll * 0.75f;
- pitch_sp = _manual.pitch * 0.75f;
- throttle_sp = _manual.throttle;
+ roll_sp = (_manual.y * _parameters.man_roll_max - _parameters.trim_roll)
+ + _parameters.rollsp_offset_rad;
+ pitch_sp = -(_manual.x * _parameters.man_pitch_max - _parameters.trim_pitch)
+ + _parameters.pitchsp_offset_rad;
+ throttle_sp = _manual.z;
_actuators.control[4] = _manual.flaps;
/*
@@ -622,7 +751,7 @@ FixedwingAttitudeControl::task_main()
att_sp.timestamp = hrt_absolute_time();
att_sp.roll_body = roll_sp;
att_sp.pitch_body = pitch_sp;
- att_sp.yaw_body = 0.0f;
+ att_sp.yaw_body = 0.0f - _parameters.trim_yaw;
att_sp.thrust = throttle_sp;
/* lazily publish the setpoint only once available */
@@ -636,54 +765,120 @@ FixedwingAttitudeControl::task_main()
}
}
+ /* Prepare speed_body_u and speed_body_w */
+ float speed_body_u = 0.0f;
+ float speed_body_v = 0.0f;
+ float speed_body_w = 0.0f;
+ if(_att.R_valid) {
+ speed_body_u = _att.R[0][0] * _global_pos.vel_n + _att.R[1][0] * _global_pos.vel_e + _att.R[2][0] * _global_pos.vel_d;
+ speed_body_v = _att.R[0][1] * _global_pos.vel_n + _att.R[1][1] * _global_pos.vel_e + _att.R[2][1] * _global_pos.vel_d;
+ speed_body_w = _att.R[0][2] * _global_pos.vel_n + _att.R[1][2] * _global_pos.vel_e + _att.R[2][2] * _global_pos.vel_d;
+ } else {
+ if (loop_counter % 10 == 0) {
+ warnx("Did not get a valid R\n");
+ }
+ }
+
+ /* Run attitude controllers */
if (isfinite(roll_sp) && isfinite(pitch_sp)) {
+ _roll_ctrl.control_attitude(roll_sp, _att.roll);
+ _pitch_ctrl.control_attitude(pitch_sp, _att.roll, _att.pitch, airspeed);
+ _yaw_ctrl.control_attitude(_att.roll, _att.pitch,
+ speed_body_u, speed_body_v, speed_body_w,
+ _roll_ctrl.get_desired_rate(), _pitch_ctrl.get_desired_rate()); //runs last, because is depending on output of roll and pitch attitude
+
+ /* Run attitude RATE controllers which need the desired attitudes from above, add trim */
+ float roll_u = _roll_ctrl.control_bodyrate(_att.pitch,
+ _att.rollspeed, _att.yawspeed,
+ _yaw_ctrl.get_desired_rate(),
+ _parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
+ _actuators.control[0] = (isfinite(roll_u)) ? roll_u + _parameters.trim_roll : _parameters.trim_roll;
+ if (!isfinite(roll_u)) {
+ _roll_ctrl.reset_integrator();
+ perf_count(_nonfinite_output_perf);
- float roll_rad = _roll_ctrl.control(roll_sp, _att.roll, _att.rollspeed,
- airspeed_scaling, lock_integrator, _parameters.airspeed_min, _parameters.airspeed_max, airspeed);
- _actuators.control[0] = (isfinite(roll_rad)) ? roll_rad * actuator_scaling : 0.0f;
+ if (loop_counter % 10 == 0) {
+ warnx("roll_u %.4f", (double)roll_u);
+ }
+ }
- float pitch_rad = _pitch_ctrl.control(pitch_sp, _att.pitch, _att.pitchspeed, _att.roll, airspeed_scaling,
- lock_integrator, _parameters.airspeed_min, _parameters.airspeed_max, airspeed);
- _actuators.control[1] = (isfinite(pitch_rad)) ? pitch_rad * actuator_scaling : 0.0f;
+ float pitch_u = _pitch_ctrl.control_bodyrate(_att.roll, _att.pitch,
+ _att.pitchspeed, _att.yawspeed,
+ _yaw_ctrl.get_desired_rate(),
+ _parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
+ _actuators.control[1] = (isfinite(pitch_u)) ? pitch_u + _parameters.trim_pitch : _parameters.trim_pitch;
+ if (!isfinite(pitch_u)) {
+ _pitch_ctrl.reset_integrator();
+ perf_count(_nonfinite_output_perf);
+ if (loop_counter % 10 == 0) {
+ warnx("pitch_u %.4f, _yaw_ctrl.get_desired_rate() %.4f,"
+ " airspeed %.4f, airspeed_scaling %.4f,"
+ " roll_sp %.4f, pitch_sp %.4f,"
+ " _roll_ctrl.get_desired_rate() %.4f,"
+ " _pitch_ctrl.get_desired_rate() %.4f"
+ " att_sp.roll_body %.4f",
+ (double)pitch_u, (double)_yaw_ctrl.get_desired_rate(),
+ (double)airspeed, (double)airspeed_scaling,
+ (double)roll_sp, (double)pitch_sp,
+ (double)_roll_ctrl.get_desired_rate(),
+ (double)_pitch_ctrl.get_desired_rate(),
+ (double)_att_sp.roll_body);
+ }
+ }
- float yaw_rad = _yaw_ctrl.control(_att.roll, _att.yawspeed, _accel.y, airspeed_scaling, lock_integrator,
- _parameters.airspeed_min, _parameters.airspeed_max, airspeed);
- _actuators.control[2] = (isfinite(yaw_rad)) ? yaw_rad * actuator_scaling : 0.0f;
+ float yaw_u = _yaw_ctrl.control_bodyrate(_att.roll, _att.pitch,
+ _att.pitchspeed, _att.yawspeed,
+ _pitch_ctrl.get_desired_rate(),
+ _parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
+ _actuators.control[2] = (isfinite(yaw_u)) ? yaw_u + _parameters.trim_yaw : _parameters.trim_yaw;
+ if (!isfinite(yaw_u)) {
+ _yaw_ctrl.reset_integrator();
+ perf_count(_nonfinite_output_perf);
+ if (loop_counter % 10 == 0) {
+ warnx("yaw_u %.4f", (double)yaw_u);
+ }
+ }
/* throttle passed through */
_actuators.control[3] = (isfinite(throttle_sp)) ? throttle_sp : 0.0f;
+ if (!isfinite(throttle_sp)) {
+ if (loop_counter % 10 == 0) {
+ warnx("throttle_sp %.4f", (double)throttle_sp);
+ }
+ }
+ } else {
+ perf_count(_nonfinite_input_perf);
+ if (loop_counter % 10 == 0) {
+ warnx("Non-finite setpoint roll_sp: %.4f, pitch_sp %.4f", (double)roll_sp, (double)pitch_sp);
+ }
+ }
- // warnx("aspd: %s: %6.2f, aspd scaling: %6.2f, controls: %5.2f %5.2f %5.2f %5.2f", (_airspeed_valid) ? "valid" : "unknown",
- // airspeed, airspeed_scaling, _actuators.control[0], _actuators.control[1],
- // _actuators.control[2], _actuators.control[3]);
-
- /*
- * Lazily publish the rate setpoint (for analysis, the actuators are published below)
- * only once available
- */
- vehicle_rates_setpoint_s rates_sp;
- rates_sp.roll = _roll_ctrl.get_desired_rate();
- rates_sp.pitch = _pitch_ctrl.get_desired_rate();
- rates_sp.yaw = 0.0f; // XXX not yet implemented
+ /*
+ * Lazily publish the rate setpoint (for analysis, the actuators are published below)
+ * only once available
+ */
+ vehicle_rates_setpoint_s rates_sp;
+ rates_sp.roll = _roll_ctrl.get_desired_rate();
+ rates_sp.pitch = _pitch_ctrl.get_desired_rate();
+ rates_sp.yaw = _yaw_ctrl.get_desired_rate();
- rates_sp.timestamp = hrt_absolute_time();
+ rates_sp.timestamp = hrt_absolute_time();
- if (_rate_sp_pub > 0) {
- /* publish the attitude setpoint */
- orb_publish(ORB_ID(vehicle_rates_setpoint), _rate_sp_pub, &rates_sp);
+ if (_rate_sp_pub > 0) {
+ /* publish the attitude setpoint */
+ orb_publish(ORB_ID(vehicle_rates_setpoint), _rate_sp_pub, &rates_sp);
- } else {
- /* advertise and publish */
- _rate_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp);
- }
+ } else {
+ /* advertise and publish */
+ _rate_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp);
}
} else {
/* manual/direct control */
- _actuators.control[0] = _manual.roll;
- _actuators.control[1] = _manual.pitch;
- _actuators.control[2] = _manual.yaw;
- _actuators.control[3] = _manual.throttle;
+ _actuators.control[0] = _manual.y;
+ _actuators.control[1] = -_manual.x;
+ _actuators.control[2] = _manual.r;
+ _actuators.control[3] = _manual.z;
_actuators.control[4] = _manual.flaps;
}
@@ -693,6 +888,7 @@ FixedwingAttitudeControl::task_main()
/* lazily publish the setpoint only once available */
_actuators.timestamp = hrt_absolute_time();
+ _actuators_airframe.timestamp = hrt_absolute_time();
if (_actuators_0_pub > 0) {
/* publish the attitude setpoint */
@@ -703,8 +899,22 @@ FixedwingAttitudeControl::task_main()
_actuators_0_pub = orb_advertise(ORB_ID(actuator_controls_0), &_actuators);
}
+ if (_actuators_1_pub > 0) {
+ /* publish the attitude setpoint */
+ orb_publish(ORB_ID(actuator_controls_1), _actuators_1_pub, &_actuators_airframe);
+// warnx("%.2f %.2f %.2f %.2f %.2f %.2f %.2f %.2f",
+// (double)_actuators_airframe.control[0], (double)_actuators_airframe.control[1], (double)_actuators_airframe.control[2],
+// (double)_actuators_airframe.control[3], (double)_actuators_airframe.control[4], (double)_actuators_airframe.control[5],
+// (double)_actuators_airframe.control[6], (double)_actuators_airframe.control[7]);
+
+ } else {
+ /* advertise and publish */
+ _actuators_1_pub = orb_advertise(ORB_ID(actuator_controls_1), &_actuators_airframe);
+ }
+
}
+ loop_counter++;
perf_end(_loop_perf);
}