AP_RangeFinder: allow separate enable of MSP rangefinder

This commit is contained in:
Andrew Tridgell 2020-09-01 17:54:29 +10:00
parent 87cf7b58ae
commit 34430e9d6c
4 changed files with 8 additions and 6 deletions

View File

@ -143,7 +143,7 @@ public:
#if HAL_MSP_RANGEFINDER_ENABLED
// Handle an incoming DISTANCE_SENSOR message (from a MSP enabled range finder)
void handle_msp(const MSP::msp_rangefinder_sensor_t &pkt);
#endif //HAL_MSP_RANGEFINDER_ENABLED
#endif
// return true if we have a range finder with the specified orientation
bool has_orientation(enum Rotation orientation) const;

View File

@ -32,7 +32,7 @@ public:
virtual void update() = 0;
virtual void handle_msg(const mavlink_message_t &msg) { return; }
#if HAL_MSP_ENABLED
#if HAL_MSP_RANGEFINDER_ENABLED
virtual void handle_msp(const MSP::msp_rangefinder_sensor_t &pkt) { return; }
#endif

View File

@ -16,7 +16,7 @@
#include "AP_RangeFinder_MSP.h"
#include <AP_HAL/AP_HAL.h>
#if HAL_MSP_ENABLED
#if HAL_MSP_RANGEFINDER_ENABLED
extern const AP_HAL::HAL& hal;
@ -68,4 +68,5 @@ void AP_RangeFinder_MSP::update(void)
}
}
#endif //HAL_MSP_ENABLED
#endif //HAL_MSP_RANGEFINDER_ENABLED

View File

@ -3,7 +3,7 @@
#include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend.h"
#if HAL_MSP_ENABLED
#if HAL_MSP_RANGEFINDER_ENABLED
// Data timeout
#define AP_RANGEFINDER_MSP_TIMEOUT_MS 500
@ -38,4 +38,5 @@ private:
static bool get_reading(uint16_t &reading_cm);
};
#endif //HAL_MSP_ENABLED
#endif //HAL_MSP_RANGEFINDER_ENABLED