forked from Archive/PX4-Autopilot
EKF: Enable origin to be maintained when starting aiding using EV only
When starting aiding using EV only and commencing GPS aiding later, this change means that the GPS origin is set to the local position 0,0 point rather than the current vehicle position. This avoids large changes in local position when GPs aiding starts.
This commit is contained in:
parent
e08da1c599
commit
3ee6898710
|
@ -68,7 +68,7 @@ bool Ekf::collect_gps(uint64_t time_usec, struct gps_message *gps)
|
|||
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 (_control_status.flags.opt_flow || _control_status.flags.gps) {
|
||||
if (_control_status.flags.opt_flow || _control_status.flags.gps || _control_status.flags.ev_pos) {
|
||||
double 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);
|
||||
|
|
Loading…
Reference in New Issue