mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RangeFinder: allow separate enable of MSP rangefinder
This commit is contained in:
parent
87cf7b58ae
commit
34430e9d6c
@ -143,7 +143,7 @@ public:
|
|||||||
#if HAL_MSP_RANGEFINDER_ENABLED
|
#if HAL_MSP_RANGEFINDER_ENABLED
|
||||||
// Handle an incoming DISTANCE_SENSOR message (from a MSP enabled range finder)
|
// Handle an incoming DISTANCE_SENSOR message (from a MSP enabled range finder)
|
||||||
void handle_msp(const MSP::msp_rangefinder_sensor_t &pkt);
|
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
|
// return true if we have a range finder with the specified orientation
|
||||||
bool has_orientation(enum Rotation orientation) const;
|
bool has_orientation(enum Rotation orientation) const;
|
||||||
|
|
||||||
|
@ -32,7 +32,7 @@ public:
|
|||||||
virtual void update() = 0;
|
virtual void update() = 0;
|
||||||
|
|
||||||
virtual void handle_msg(const mavlink_message_t &msg) { return; }
|
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; }
|
virtual void handle_msp(const MSP::msp_rangefinder_sensor_t &pkt) { return; }
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -16,7 +16,7 @@
|
|||||||
#include "AP_RangeFinder_MSP.h"
|
#include "AP_RangeFinder_MSP.h"
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if HAL_MSP_ENABLED
|
#if HAL_MSP_RANGEFINDER_ENABLED
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
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
|
||||||
|
|
||||||
|
@ -3,7 +3,7 @@
|
|||||||
#include "AP_RangeFinder.h"
|
#include "AP_RangeFinder.h"
|
||||||
#include "AP_RangeFinder_Backend.h"
|
#include "AP_RangeFinder_Backend.h"
|
||||||
|
|
||||||
#if HAL_MSP_ENABLED
|
#if HAL_MSP_RANGEFINDER_ENABLED
|
||||||
|
|
||||||
// Data timeout
|
// Data timeout
|
||||||
#define AP_RANGEFINDER_MSP_TIMEOUT_MS 500
|
#define AP_RANGEFINDER_MSP_TIMEOUT_MS 500
|
||||||
@ -38,4 +38,5 @@ private:
|
|||||||
static bool get_reading(uint16_t &reading_cm);
|
static bool get_reading(uint16_t &reading_cm);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif //HAL_MSP_ENABLED
|
#endif //HAL_MSP_RANGEFINDER_ENABLED
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user