Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixed support for no baro boards #16360

Merged
merged 4 commits into from
Jul 7, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion Tools/autotest/common.py
Original file line number Diff line number Diff line change
Expand Up @@ -7835,7 +7835,7 @@ def test_config_error_loop(self):
ex = None
try:
self.set_parameter("STAT_BOOTCNT", 0)
self.set_parameter("SIM_BARO_COUNT", 0)
self.set_parameter("SIM_BARO_COUNT", -1)

if self.is_tracker():
# starts armed...
Expand Down
8 changes: 4 additions & 4 deletions libraries/AP_AHRS/AP_AHRS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,11 +41,11 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] = {
AP_GROUPINFO("GPS_GAIN", 2, AP_AHRS, gps_gain, 1.0f),

// @Param: GPS_USE
// @DisplayName: AHRS use GPS for navigation
// @Description: This controls whether to use dead-reckoning or GPS based navigation. If set to 0 then the GPS won't be used for navigation, and only dead reckoning will be used. A value of zero should never be used for normal flight. Currently this affects only the DCM-based AHRS: the EKF uses GPS whenever it is available.
// @Values: 0:Disabled,1:Enabled
// @DisplayName: AHRS DCM use GPS for navigation
// @Description: This controls whether to use dead-reckoning or GPS based navigation. If set to 0 then the GPS won't be used for navigation, and only dead reckoning will be used. A value of zero should never be used for normal flight. Currently this affects only the DCM-based AHRS: the EKF uses GPS whenever it is available. A value of 2 means to use GPS for height as well as position in DCM.
// @Values: 0:Disabled,1:Use GPS for DCM position,2:Use GPS for DCM position and height
// @User: Advanced
AP_GROUPINFO("GPS_USE", 3, AP_AHRS, _gps_use, 1),
AP_GROUPINFO("GPS_USE", 3, AP_AHRS, _gps_use, float(GPSUse::Enable)),

// @Param: YAW_P
// @DisplayName: Yaw P
Expand Down
9 changes: 8 additions & 1 deletion libraries/AP_AHRS/AP_AHRS.h
Original file line number Diff line number Diff line change
Expand Up @@ -631,7 +631,14 @@ class AP_AHRS
AP_Float gps_gain;

AP_Float beta;
AP_Int8 _gps_use;

enum class GPSUse : uint8_t {
Disable = 0,
Enable = 1,
EnableWithHeight = 2,
};

AP_Enum<GPSUse> _gps_use;
AP_Int8 _wind_max;
AP_Int8 _board_orientation;
AP_Int8 _gps_minsats;
Expand Down
24 changes: 18 additions & 6 deletions libraries/AP_AHRS/AP_AHRS_DCM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -414,7 +414,7 @@ AP_AHRS_DCM::_yaw_gain(void) const
// return true if we have and should use GPS
bool AP_AHRS_DCM::have_gps(void) const
{
if (AP::gps().status() <= AP_GPS::NO_FIX || !_gps_use) {
if (AP::gps().status() <= AP_GPS::NO_FIX || _gps_use == GPSUse::Disable) {
return false;
}
return true;
Expand Down Expand Up @@ -1031,15 +1031,21 @@ bool AP_AHRS_DCM::get_position(struct Location &loc) const
{
loc.lat = _last_lat;
loc.lng = _last_lng;
loc.alt = AP::baro().get_altitude() * 100 + _home.alt;
const auto &baro = AP::baro();
const auto &gps = AP::gps();
if (_gps_use == GPSUse::EnableWithHeight &&
gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
loc.alt = gps.location().alt;
} else {
loc.alt = baro.get_altitude() * 100 + _home.alt;
}
loc.relative_alt = 0;
loc.terrain_alt = 0;
loc.offset(_position_offset_north, _position_offset_east);
const AP_GPS &_gps = AP::gps();
if (_flags.fly_forward && _have_position) {
float gps_delay_sec = 0;
_gps.get_lag(gps_delay_sec);
loc.offset_bearing(_gps.ground_course(), _gps.ground_speed() * gps_delay_sec);
gps.get_lag(gps_delay_sec);
loc.offset_bearing(gps.ground_course(), gps.ground_speed() * gps_delay_sec);
}
return _have_position;
}
Expand Down Expand Up @@ -1125,7 +1131,13 @@ bool AP_AHRS_DCM::set_home(const Location &loc)
// a relative ground position to home in meters, Down
void AP_AHRS_DCM::get_relative_position_D_home(float &posD) const
{
posD = -AP::baro().get_altitude();
const auto &gps = AP::gps();
if (_gps_use == GPSUse::EnableWithHeight &&
gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
posD = (_home.alt - gps.location().alt) * 0.01;
} else {
posD = -AP::baro().get_altitude();
}
}

/*
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_AHRS/AP_AHRS_NavEKF.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1416,7 +1416,7 @@ void AP_AHRS_NavEKF::get_relative_position_D_home(float &posD) const
float originD;
if (!get_relative_position_D_origin(originD) ||
!get_origin(originLLH)) {
posD = -AP::baro().get_altitude();
AP_AHRS_DCM::get_relative_position_D_home(posD);
return;
}

Expand Down
9 changes: 9 additions & 0 deletions libraries/AP_Arming/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -200,6 +200,15 @@ void AP_Arming::check_failed(bool report, const char *fmt, ...) const

bool AP_Arming::barometer_checks(bool report)
{
#ifdef HAL_BARO_ALLOW_INIT_NO_BARO
return true;
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (AP::sitl()->baro_count == 0) {
// simulate no baro boards
return true;
}
#endif
if ((checks_to_perform & ARMING_CHECK_ALL) ||
(checks_to_perform & ARMING_CHECK_BARO)) {
if (!AP::baro().all_healthy()) {
Expand Down
12 changes: 11 additions & 1 deletion libraries/AP_Baro/AP_Baro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -254,6 +254,12 @@ void AP_Baro::calibrate(bool save)
return;
}

#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (AP::sitl()->baro_count == 0) {
return;
}
#endif

#ifdef HAL_BARO_ALLOW_INIT_NO_BARO
if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == nullptr) {
BARO_SEND_TEXT(MAV_SEVERITY_INFO, "Baro: no sensors found, skipping calibration");
Expand Down Expand Up @@ -670,7 +676,11 @@ void AP_Baro::init(void)
#endif

#if !defined(HAL_BARO_ALLOW_INIT_NO_BARO) // most boards requires external baro

#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (sitl->baro_count == 0) {
return;
}
#endif
if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == nullptr) {
AP_BoardConfig::config_error("Baro: unable to initialise driver");
}
Expand Down