mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF: fallback to no baro on boards that have no baro
This commit is contained in:
parent
1a7a6b6dd9
commit
cf997df79f
|
@ -17,6 +17,7 @@
|
|||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_DAL/AP_DAL.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
@ -231,6 +232,18 @@ AP_NavEKF_Source::SourceYaw AP_NavEKF_Source::getYawSource() const
|
|||
return _source_set[active_source_set].yaw;
|
||||
}
|
||||
|
||||
// get pos Z source
|
||||
AP_NavEKF_Source::SourceZ AP_NavEKF_Source::getPosZSource() const
|
||||
{
|
||||
#ifdef HAL_BARO_ALLOW_INIT_NO_BARO
|
||||
// check for special case of missing baro
|
||||
if ((_source_set[active_source_set].posz == SourceZ::BARO) && (AP::dal().baro().num_instances() == 0)) {
|
||||
return SourceZ::NONE;
|
||||
}
|
||||
#endif
|
||||
return _source_set[active_source_set].posz;
|
||||
}
|
||||
|
||||
// align position of inactive sources to ahrs
|
||||
void AP_NavEKF_Source::align_inactive_sources()
|
||||
{
|
||||
|
|
|
@ -55,7 +55,7 @@ public:
|
|||
|
||||
// get current position source
|
||||
SourceXY getPosXYSource() const { return _source_set[active_source_set].posxy; }
|
||||
SourceZ getPosZSource() const { return _source_set[active_source_set].posz; }
|
||||
SourceZ getPosZSource() const;
|
||||
|
||||
// set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary
|
||||
void setPosVelYawSourceSet(uint8_t source_set_idx);
|
||||
|
|
Loading…
Reference in New Issue