Skip to content

Commit

Permalink
AP_DAL: cope with AP_BARO_ENABLED being 0
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Sep 1, 2024
1 parent 4d06516 commit 828c897
Show file tree
Hide file tree
Showing 4 changed files with 24 additions and 0 deletions.
4 changes: 4 additions & 0 deletions libraries/AP_DAL/AP_DAL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,9 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype)
_RFRN.lat = _home.lat;
_RFRN.lng = _home.lng;
_RFRN.alt = _home.alt;
#if AP_BARO_ENABLED
_RFRN.EAS2TAS = ahrs.get_EAS2TAS();
#endif
_RFRN.vehicle_class = (uint8_t)ahrs.get_vehicle_class();
_RFRN.fly_forward = ahrs.get_fly_forward();
_RFRN.takeoff_expected = ahrs.get_takeoff_expected();
Expand All @@ -84,7 +86,9 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype)
_rotation_vehicle_body_to_autopilot_body = ahrs.get_rotation_vehicle_body_to_autopilot_body();

_ins.start_frame();
#if AP_BARO_ENABLED
_baro.start_frame();
#endif
_gps.start_frame();
_compass.start_frame();
if (_airspeed) {
Expand Down
8 changes: 8 additions & 0 deletions libraries/AP_DAL/AP_DAL.h
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,9 @@ class AP_DAL {
void *malloc_type(size_t size, enum Memory_Type mem_type) const;

AP_DAL_InertialSensor &ins() { return _ins; }
#if AP_BARO_ENABLED
AP_DAL_Baro &baro() { return _baro; }
#endif
AP_DAL_GPS &gps() { return _gps; }

#if AP_RANGEFINDER_ENABLED
Expand Down Expand Up @@ -257,10 +259,14 @@ class AP_DAL {
}

void handle_message(const log_RBRH &msg) {
#if AP_BARO_ENABLED
_baro.handle_message(msg);
#endif
}
void handle_message(const log_RBRI &msg) {
#if AP_BARO_ENABLED
_baro.handle_message(msg);
#endif
}

void handle_message(const log_RRNH &msg) {
Expand Down Expand Up @@ -363,7 +369,9 @@ class AP_DAL {
uint32_t _last_imu_time_us;

AP_DAL_InertialSensor _ins;
#if AP_BARO_ENABLED
AP_DAL_Baro _baro;
#endif
AP_DAL_GPS _gps;
#if AP_RANGEFINDER_ENABLED
AP_DAL_RangeFinder *_rangefinder;
Expand Down
6 changes: 6 additions & 0 deletions libraries/AP_DAL/AP_DAL_Baro.cpp
Original file line number Diff line number Diff line change
@@ -1,3 +1,7 @@
#include <AP_Baro/AP_Baro_config.h>

#if AP_BARO_ENABLED

#include "AP_DAL_Baro.h"

#include <AP_Logger/AP_Logger.h>
Expand Down Expand Up @@ -33,3 +37,5 @@ void AP_DAL_Baro::update_calibration()
{
AP::baro().update_calibration();
}

#endif // AP_BARO_ENABLED
6 changes: 6 additions & 0 deletions libraries/AP_DAL/AP_DAL_Baro.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,9 @@
#pragma once

#include <AP_Baro/AP_Baro_config.h>

#if AP_BARO_ENABLED

#include <AP_Baro/AP_Baro.h>

#include <AP_Logger/LogStructure.h>
Expand Down Expand Up @@ -51,3 +55,5 @@ class AP_DAL_Baro {
struct log_RBRI _RBRI[BARO_MAX_INSTANCES];
};


#endif // AP_BARO_ENABLED

0 comments on commit 828c897

Please sign in to comment.