55 if (_state.
pin != -1) {
97 dist_m = (v - offset) * scaling;
101 dist_m = (offset -
v) * scaling;
108 dist_m = scaling / (v - offset);
110 if (isinf(dist_m) || dist_m > _max_distance_cm * 0.01f) {
111 dist_m = _max_distance_cm * 0.01f;
virtual float voltage_average()=0
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
virtual void set_settle_time(uint16_t settle_time_ms)=0
virtual void set_stop_pin(uint8_t p)=0
static bool detect(RangeFinder::RangeFinder_State &_state)
void update_voltage(void)
Common definitions and utility routines for the ArduPilot libraries.
AP_RangeFinder_analog(RangeFinder::RangeFinder_State &_state)
void set_status(RangeFinder::RangeFinder_Status status)
RangeFinder::RangeFinder_State & state
virtual void set_pin(uint8_t p)=0
virtual float voltage_average_ratiometric()=0
AP_HAL::AnalogSource * source
AP_HAL::AnalogIn * analogin
virtual AP_HAL::AnalogSource * channel(int16_t n)=0