Browse Source

EKF: Remove use of vehicle arm status

Use single externally set in-air status for all decisions
master
Paul Riseborough 9 years ago
parent
commit
481c624975
  1. 33
      EKF/control.cpp
  2. 2
      EKF/ekf.cpp
  3. 3
      EKF/ekf.h
  4. 2
      EKF/estimator_interface.cpp
  5. 7
      EKF/estimator_interface.h
  6. 6
      EKF/gps_checks.cpp
  7. 2
      EKF/terrain_estimator.cpp

33
EKF/control.cpp

@ -45,8 +45,6 @@ void Ekf::controlFusionModes()
{ {
// Store the status to enable change detection // Store the status to enable change detection
_control_status_prev.value = _control_status.value; _control_status_prev.value = _control_status.value;
// Determine the vehicle status
calculateVehicleStatus();
// Get the magnetic declination // Get the magnetic declination
calcMagDeclination(); calcMagDeclination();
@ -109,7 +107,7 @@ void Ekf::controlFusionModes()
// reset the horizontal velocity variance using the optical flow noise variance // reset the horizontal velocity variance using the optical flow noise variance
P[5][5] = P[4][4] = sq(range) * calcOptFlowMeasVar(); P[5][5] = P[4][4] = sq(range) * calcOptFlowMeasVar();
if (!_in_air) { if (!_control_status.flags.in_air) {
// we are likely starting OF for the first time so reset the horizontal position and vertical velocity states // we are likely starting OF for the first time so reset the horizontal position and vertical velocity states
_state.pos(0) = 0.0f; _state.pos(0) = 0.0f;
_state.pos(1) = 0.0f; _state.pos(1) = 0.0f;
@ -370,12 +368,7 @@ void Ekf::controlFusionModes()
// Determine if we should use simple magnetic heading fusion which works better when there are large external disturbances // Determine if we should use simple magnetic heading fusion which works better when there are large external disturbances
// or the more accurate 3-axis fusion // or the more accurate 3-axis fusion
if (_params.mag_fusion_type == MAG_FUSE_TYPE_AUTO) { if (_params.mag_fusion_type == MAG_FUSE_TYPE_AUTO) {
if (!_control_status.flags.armed) {
// use heading fusion for initial startup
_control_status.flags.mag_hdg = true;
_control_status.flags.mag_3D = false;
} else {
if (_control_status.flags.in_air) { if (_control_status.flags.in_air) {
// if transitioning into 3-axis fusion mode, we need to initialise the yaw angle and field states // if transitioning into 3-axis fusion mode, we need to initialise the yaw angle and field states
if (!_control_status.flags.mag_3D) { if (!_control_status.flags.mag_3D) {
@ -391,7 +384,6 @@ void Ekf::controlFusionModes()
_control_status.flags.mag_hdg = true; _control_status.flags.mag_hdg = true;
_control_status.flags.mag_3D = false; _control_status.flags.mag_3D = false;
} }
}
} else if (_params.mag_fusion_type == MAG_FUSE_TYPE_HEADING) { } else if (_params.mag_fusion_type == MAG_FUSE_TYPE_HEADING) {
// always use heading fusion // always use heading fusion
@ -448,26 +440,3 @@ void Ekf::controlFusionModes()
} }
} }
void Ekf::calculateVehicleStatus()
{
// determine if the vehicle is armed
_control_status.flags.armed = _vehicle_armed;
// record vertical position whilst disarmed to use as a height change reference
if (!_control_status.flags.armed) {
_last_disarmed_posD = _state.pos(2);
}
// Transition to in-air occurs when armed and when altitude has increased sufficiently from the altitude at arming
bool in_air = _control_status.flags.armed && (_state.pos(2) - _last_disarmed_posD) < -1.0f;
if (!_control_status.flags.in_air && in_air) {
_control_status.flags.in_air = true;
}
// Transition to on-ground occurs when disarmed or if the land detector indicated landed state
if (_control_status.flags.in_air && (!_control_status.flags.armed || !_in_air)) {
_control_status.flags.in_air = false;
}
}

2
EKF/ekf.cpp

@ -253,7 +253,7 @@ bool Ekf::update()
} else if ((_time_last_imu - _time_last_hgt_fuse) > 2 * RNG_MAX_INTERVAL && _control_status.flags.rng_hgt) { } else if ((_time_last_imu - _time_last_hgt_fuse) > 2 * RNG_MAX_INTERVAL && _control_status.flags.rng_hgt) {
// If we are supposed to be using range finder data as the primary height sensor, have missed or rejected measurements // If we are supposed to be using range finder data as the primary height sensor, have missed or rejected measurements
// and are on the ground, then synthesise a measurement at the expected on ground value // and are on the ground, then synthesise a measurement at the expected on ground value
if (!_in_air) { if (!_control_status.flags.in_air) {
_range_sample_delayed.rng = _params.rng_gnd_clearance; _range_sample_delayed.rng = _params.rng_gnd_clearance;
_range_sample_delayed.time_us = _imu_sample_delayed.time_us; _range_sample_delayed.time_us = _imu_sample_delayed.time_us;

3
EKF/ekf.h

@ -332,9 +332,6 @@ private:
// Control the filter fusion modes // Control the filter fusion modes
void controlFusionModes(); void controlFusionModes();
// Determine if we are airborne or motors are armed
void calculateVehicleStatus();
// return the square of two floating point numbers - used in auto coded sections // return the square of two floating point numbers - used in auto coded sections
inline float sq(float var) inline float sq(float var)
{ {

2
EKF/estimator_interface.cpp

@ -52,8 +52,6 @@ EstimatorInterface::EstimatorInterface():
_imu_ticks(0), _imu_ticks(0),
_imu_updated(false), _imu_updated(false),
_initialised(false), _initialised(false),
_vehicle_armed(false),
_in_air(false),
_NED_origin_initialised(false), _NED_origin_initialised(false),
_gps_speed_valid(false), _gps_speed_valid(false),
_gps_origin_eph(0.0f), _gps_origin_eph(0.0f),

7
EKF/estimator_interface.h

@ -149,11 +149,8 @@ public:
// in order to give access to the application // in order to give access to the application
parameters *getParamHandle() {return &_params;} parameters *getParamHandle() {return &_params;}
// set vehicle arm status data
void set_arm_status(bool data) { _vehicle_armed = data; }
// set vehicle landed status data // set vehicle landed status data
void set_in_air_status(bool in_air) {_in_air = in_air;} void set_in_air_status(bool in_air) {_control_status.flags.in_air = in_air;}
// return true if the global position estimate is valid // return true if the global position estimate is valid
virtual bool global_position_is_valid() = 0; virtual bool global_position_is_valid() = 0;
@ -258,8 +255,6 @@ protected:
bool _imu_updated; // true if the ekf should update (completed downsampling process) bool _imu_updated; // true if the ekf should update (completed downsampling process)
bool _initialised; // true if the ekf interface instance (data buffering) is initialized bool _initialised; // true if the ekf interface instance (data buffering) is initialized
bool _vehicle_armed; // vehicle arm status used to turn off functionality used on the ground
bool _in_air; // we assume vehicle is in the air, set by the given landing detector
bool _NED_origin_initialised = false; bool _NED_origin_initialised = false;
bool _gps_speed_valid = false; bool _gps_speed_valid = false;

6
EKF/gps_checks.cpp

@ -162,7 +162,7 @@ bool Ekf::gps_is_good(struct gps_message *gps)
// Calculate the horizontal drift speed and fail if too high // Calculate the horizontal drift speed and fail if too high
// This check can only be used if the vehicle is stationary during alignment // This check can only be used if the vehicle is stationary during alignment
if (!_control_status.flags.armed) { if (!_control_status.flags.in_air) {
float drift_speed = sqrtf(_gpsDriftVelN * _gpsDriftVelN + _gpsDriftVelE * _gpsDriftVelE); float drift_speed = sqrtf(_gpsDriftVelN * _gpsDriftVelN + _gpsDriftVelE * _gpsDriftVelE);
_gps_check_fail_status.flags.hdrift = (drift_speed > _params.req_hdrift); _gps_check_fail_status.flags.hdrift = (drift_speed > _params.req_hdrift);
@ -186,7 +186,7 @@ bool Ekf::gps_is_good(struct gps_message *gps)
// Fail if the vertical drift speed is too high // Fail if the vertical drift speed is too high
// This check can only be used if the vehicle is stationary during alignment // This check can only be used if the vehicle is stationary during alignment
if (!_control_status.flags.armed) { if (!_control_status.flags.in_air) {
_gps_check_fail_status.flags.vdrift = (fabsf(_gps_drift_velD) > _params.req_vdrift); _gps_check_fail_status.flags.vdrift = (fabsf(_gps_drift_velD) > _params.req_vdrift);
} else { } else {
@ -195,7 +195,7 @@ bool Ekf::gps_is_good(struct gps_message *gps)
// Check the magnitude of the filtered horizontal GPS velocity // Check the magnitude of the filtered horizontal GPS velocity
// This check can only be used if the vehicle is stationary during alignment // This check can only be used if the vehicle is stationary during alignment
if (!_control_status.flags.armed) { if (!_control_status.flags.in_air) {
vel_limit = 10.0f * _params.req_hdrift; vel_limit = 10.0f * _params.req_hdrift;
float gps_velN = fminf(fmaxf(gps->vel_ned[0], -vel_limit), vel_limit); float gps_velN = fminf(fmaxf(gps->vel_ned[0], -vel_limit), vel_limit);
float gps_velE = fminf(fmaxf(gps->vel_ned[1], -vel_limit), vel_limit); float gps_velE = fminf(fmaxf(gps->vel_ned[1], -vel_limit), vel_limit);

2
EKF/terrain_estimator.cpp

@ -55,7 +55,7 @@ bool Ekf::initHagl()
// success // success
return true; return true;
} else if (!_in_air) { } else if (!_control_status.flags.in_air) {
// if on ground we assume a ground clearance // if on ground we assume a ground clearance
_terrain_vpos = _state.pos(2) + _params.rng_gnd_clearance; _terrain_vpos = _state.pos(2) + _params.rng_gnd_clearance;
// Use the ground clearance value as our uncertainty // Use the ground clearance value as our uncertainty

Loading…
Cancel
Save