Browse Source

Only update TECS filter if auto is enabled. This forces the internal TECS logic to reset between auto runs

sbg
Lorenz Meier 10 years ago
parent
commit
e84d97b387
  1. 5
      src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp

5
src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp

@ -1054,8 +1054,9 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi @@ -1054,8 +1054,9 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
math::Vector<3> accel_body(_sensor_combined.accelerometer_m_s2);
math::Vector<3> accel_earth = _R_nb * accel_body;
if (!_mTecs.getEnabled() && !_vehicle_status.condition_landed) {
_tecs.update_50hz(_global_pos.alt /* XXX might switch to alt err here */, _airspeed.indicated_airspeed_m_s, _R_nb, accel_body, accel_earth);
/* update TECS filters, but only if in auto mode. */
if (_control_mode.flag_control_auto_enabled && (_global_pos.timestamp > 0) && !_mTecs.getEnabled() && !_vehicle_status.condition_landed) {
_tecs.update_50hz(_global_pos.alt, _airspeed.indicated_airspeed_m_s, _R_nb, accel_body, accel_earth);
}
/* define altitude error */

Loading…
Cancel
Save