Browse Source

EKF: code style updates

master
Paul Riseborough 9 years ago
parent
commit
d2407c3463
  1. 1
      EKF/control.cpp
  2. 2
      EKF/gps_checks.cpp
  3. 3
      EKF/terrain_estimator.cpp

1
EKF/control.cpp

@ -125,6 +125,7 @@ void Ekf::controlFusionModes()
if (_control_status.flags.yaw_align) { if (_control_status.flags.yaw_align) {
_control_status.flags.gps = true; _control_status.flags.gps = true;
_time_last_gps = _time_last_imu; _time_last_gps = _time_last_imu;
// if we are not already aiding with optical flow, then we need to reset the position and velocity // if we are not already aiding with optical flow, then we need to reset the position and velocity
if (!_control_status.flags.opt_flow) { if (!_control_status.flags.opt_flow) {
_control_status.flags.gps = resetPosition(); _control_status.flags.gps = resetPosition();

2
EKF/gps_checks.cpp

@ -64,12 +64,14 @@ bool Ekf::collect_gps(uint64_t time_usec, struct gps_message *gps)
double lat = gps->lat / 1.0e7; double lat = gps->lat / 1.0e7;
double lon = gps->lon / 1.0e7; double lon = gps->lon / 1.0e7;
map_projection_init_timestamped(&_pos_ref, lat, lon, _time_last_imu); map_projection_init_timestamped(&_pos_ref, lat, lon, _time_last_imu);
// if we are already doing aiding, corect for the change in posiiton since the EKF started navigating // if we are already doing aiding, corect for the change in posiiton since the EKF started navigating
if (_control_status.flags.opt_flow || _control_status.flags.gps) { if (_control_status.flags.opt_flow || _control_status.flags.gps) {
double est_lat, est_lon; double est_lat, est_lon;
map_projection_reproject(&_pos_ref, -_state.pos(0), -_state.pos(1), &est_lat, &est_lon); map_projection_reproject(&_pos_ref, -_state.pos(0), -_state.pos(1), &est_lat, &est_lon);
map_projection_init_timestamped(&_pos_ref, est_lat, est_lon, _time_last_imu); map_projection_init_timestamped(&_pos_ref, est_lat, est_lon, _time_last_imu);
} }
// Take the current GPS height and subtract the filter height above origin to estimate the GPS height of the origin // Take the current GPS height and subtract the filter height above origin to estimate the GPS height of the origin
_gps_alt_ref = 1e-3f * (float)gps->alt + _state.pos(2); _gps_alt_ref = 1e-3f * (float)gps->alt + _state.pos(2);
_NED_origin_initialised = true; _NED_origin_initialised = true;

3
EKF/terrain_estimator.cpp

@ -78,7 +78,8 @@ void Ekf::predictHagl()
_terrain_var += sq(_imu_sample_delayed.delta_vel_dt * _params.terrain_p_noise); _terrain_var += sq(_imu_sample_delayed.delta_vel_dt * _params.terrain_p_noise);
// process noise due to terrain gradient // process noise due to terrain gradient
_terrain_var += sq(_imu_sample_delayed.delta_vel_dt * _params.terrain_gradient) * (sq(_state.vel(0)) + sq(_state.vel(1))); _terrain_var += sq(_imu_sample_delayed.delta_vel_dt * _params.terrain_gradient) * (sq(_state.vel(0)) + sq(_state.vel(
1)));
// limit the variance to prevent it becoming badly conditioned // limit the variance to prevent it becoming badly conditioned
_terrain_var = math::constrain(_terrain_var, 0.0f, 1e4f); _terrain_var = math::constrain(_terrain_var, 0.0f, 1e4f);

Loading…
Cancel
Save