AP_DAL: make AP_RANGEFINDER_ENABLED remove more code

This commit is contained in:
Peter Barker 2023-11-08 09:23:39 +11:00 committed by Andrew Tridgell
parent 955245e4b7
commit abc0179a53
4 changed files with 22 additions and 0 deletions

View File

@ -90,9 +90,11 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype)
if (_airspeed) {
_airspeed->start_frame();
}
#if AP_RANGEFINDER_ENABLED
if (_rangefinder) {
_rangefinder->start_frame();
}
#endif
#if AP_BEACON_ENABLED
if (_beacon) {
_beacon->start_frame();
@ -134,10 +136,12 @@ void AP_DAL::init_sensors(void)
at the time we startup the EKF
*/
#if AP_RANGEFINDER_ENABLED
auto *rng = AP::rangefinder();
if (rng && rng->num_sensors() > 0) {
alloc_failed |= (_rangefinder = NEW_NOTHROW AP_DAL_RangeFinder) == nullptr;
}
#endif
#if AP_AIRSPEED_ENABLED
auto *aspeed = AP::airspeed();

View File

@ -131,9 +131,12 @@ public:
AP_DAL_Baro &baro() { return _baro; }
AP_DAL_GPS &gps() { return _gps; }
#if AP_RANGEFINDER_ENABLED
AP_DAL_RangeFinder *rangefinder() {
return _rangefinder;
}
#endif
AP_DAL_Airspeed *airspeed() {
return _airspeed;
}
@ -261,16 +264,20 @@ public:
}
void handle_message(const log_RRNH &msg) {
#if AP_RANGEFINDER_ENABLED
if (_rangefinder == nullptr) {
_rangefinder = NEW_NOTHROW AP_DAL_RangeFinder;
}
_rangefinder->handle_message(msg);
#endif
}
void handle_message(const log_RRNI &msg) {
#if AP_RANGEFINDER_ENABLED
if (_rangefinder == nullptr) {
_rangefinder = NEW_NOTHROW AP_DAL_RangeFinder;
}
_rangefinder->handle_message(msg);
#endif
}
void handle_message(const log_RGPH &msg) {
@ -358,7 +365,9 @@ private:
AP_DAL_InertialSensor _ins;
AP_DAL_Baro _baro;
AP_DAL_GPS _gps;
#if AP_RANGEFINDER_ENABLED
AP_DAL_RangeFinder *_rangefinder;
#endif
AP_DAL_Compass _compass;
AP_DAL_Airspeed *_airspeed;
#if AP_BEACON_ENABLED

View File

@ -3,6 +3,9 @@
#include <AP_Logger/AP_Logger.h>
#include <AP_RangeFinder/AP_RangeFinder_Backend.h>
#if AP_RANGEFINDER_ENABLED
#include "AP_DAL.h"
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
@ -146,3 +149,5 @@ void AP_DAL_RangeFinder::handle_message(const log_RRNI &msg)
}
}
}
#endif // AP_RANGEFINDER_ENABLED

View File

@ -2,6 +2,8 @@
#include <AP_RangeFinder/AP_RangeFinder.h>
#if AP_RANGEFINDER_ENABLED
#include <AP_Logger/LogStructure.h>
class AP_RangeFinder_Backend;
@ -68,3 +70,5 @@ private:
struct log_RRNI &_RRNI;
};
#endif // AP_RANGEFINDER_ENABLED