36 if (
uart !=
nullptr) {
46 return uart !=
nullptr;
52 if (
uart ==
nullptr) {
80 if (
uart ==
nullptr) {
84 uint16_t message_count = 0;
87 while (nbytes-- > 0) {
123 return (message_count > 0);
128 return (buf1 << 8) + buf2;
136 _angle[sector] = angle_deg;
137 _distance[sector] = ((float) distance_cm) / 1000;
float distance_max() const
static AP_SerialManager serial_manager
bool _distance_valid[PROXIMITY_SECTORS_MAX]
#define PROXIMITY_TRTOWER_TIMEOUT_MS
float _angle[PROXIMITY_SECTORS_MAX]
virtual void begin(uint32_t baud)=0
void update_sector_data(int16_t angle_deg, uint16_t distance_cm)
uint32_t _last_distance_received_ms
float distance_min() const
AP_HAL::UARTDriver * uart
uint8_t crc_crc8(const uint8_t *p, uint8_t len)
void set_status(AP_Proximity::Proximity_Status status)
uint16_t process_distance(uint8_t buf1, uint8_t buf2)
uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
bool convert_angle_to_sector(float angle_degrees, uint8_t §or) const
float _distance[PROXIMITY_SECTORS_MAX]
AP_Proximity_TeraRangerTower(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state, AP_SerialManager &serial_manager)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
virtual uint32_t available()=0
void update_boundary_for_sector(uint8_t sector)
static bool detect(AP_SerialManager &serial_manager)
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const