6 #define PROXIMITY_SF40C_TIMEOUT_MS 200 // requests timeout after 0.2 seconds
static AP_SerialManager serial_manager
uint16_t no_results_available
void set_forward_direction()
union AP_Proximity_LightWareSF40C::@166 _sensor_status
uint32_t _last_distance_received_ms
AP_Proximity_LightWareSF40C(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state, AP_SerialManager &serial_manager)
void set_motor_speed(bool on_off)
bool send_request_for_distance()
void set_motor_direction()
float distance_max() const
void send_request_for_health()
uint32_t _last_request_ms
enum RequestType _last_request_type
static bool detect(AP_SerialManager &serial_manager)
uint16_t system_restarting
uint16_t major_system_abnormal
float distance_min() const
AP_HAL::UARTDriver * uart
int16_t _forward_direction
struct AP_Proximity_LightWareSF40C::@166::PACKED _flags