mirror of https://github.com/ArduPilot/ardupilot
Rover: ekf check allows relative position estimates
This allows arming using only wheel encoders which provide relative positions
This commit is contained in:
parent
63309c6925
commit
93aa600e5d
|
@ -132,12 +132,12 @@ bool Rover::ekf_position_ok()
|
|||
nav_filter_status filt_status;
|
||||
rover.ahrs.get_filter_status(filt_status);
|
||||
|
||||
// if disarmed we accept a predicted horizontal position
|
||||
// if disarmed we accept a predicted horizontal absolute or relative position
|
||||
if (!arming.is_armed()) {
|
||||
return ((filt_status.flags.horiz_pos_abs || filt_status.flags.pred_horiz_pos_abs));
|
||||
return (filt_status.flags.horiz_pos_abs || filt_status.flags.pred_horiz_pos_abs || filt_status.flags.horiz_pos_rel || filt_status.flags.pred_horiz_pos_rel);
|
||||
} else {
|
||||
// once armed we require a good absolute position and EKF must not be in const_pos_mode
|
||||
return (filt_status.flags.horiz_pos_abs && !filt_status.flags.const_pos_mode);
|
||||
// once armed we require a good absolute or relative position and EKF must not be in const_pos_mode
|
||||
return ((filt_status.flags.horiz_pos_abs || filt_status.flags.horiz_pos_rel) && !filt_status.flags.const_pos_mode);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue