AP_RangeFinder: add AP_RANGEFINDER_LEDDARVU8_ENABLED

This commit is contained in:
Peter Barker 2022-03-07 09:30:16 +11:00 committed by Andrew Tridgell
parent 54e57ccff0
commit c7d72821da
2 changed files with 12 additions and 0 deletions

View File

@ -15,6 +15,8 @@
#include "AP_RangeFinder_LeddarVu8.h" #include "AP_RangeFinder_LeddarVu8.h"
#if AP_RANGEFINDER_LEDDARVU8_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <ctype.h> #include <ctype.h>
@ -202,3 +204,5 @@ bool AP_RangeFinder_LeddarVu8::parse_byte(uint8_t b, bool &valid_reading, uint16
valid_reading = false; valid_reading = false;
return false; return false;
} }
#endif

View File

@ -3,6 +3,12 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend_Serial.h" #include "AP_RangeFinder_Backend_Serial.h"
#ifndef AP_RANGEFINDER_LEDDARVU8_ENABLED
#define AP_RANGEFINDER_LEDDARVU8_ENABLED 1
#endif
#if AP_RANGEFINDER_LEDDARVU8_ENABLED
#define LEDDARVU8_PAYLOAD_LENGTH (8*2) #define LEDDARVU8_PAYLOAD_LENGTH (8*2)
class AP_RangeFinder_LeddarVu8 : public AP_RangeFinder_Backend_Serial class AP_RangeFinder_LeddarVu8 : public AP_RangeFinder_Backend_Serial
@ -90,3 +96,5 @@ private:
uint32_t last_distance_ms; // system time of last successful distance sensor read uint32_t last_distance_ms; // system time of last successful distance sensor read
uint32_t last_distance_request_ms; // system time of last request to sensor to send distances uint32_t last_distance_request_ms; // system time of last request to sensor to send distances
}; };
#endif