34 virtual void handle_msg(mavlink_message_t *msg) {
return; }
46 return MAV_DISTANCE_SENSOR_UNKNOWN;
uint16_t voltage_mv() const
RangeFinder::RangeFinder_Type type() const
enum Rotation orientation() const
uint16_t distance_cm() const
int16_t ground_clearance_cm() const
AP_RangeFinder_Backend(RangeFinder::RangeFinder_State &_state)
virtual void handle_msg(mavlink_message_t *msg)
const Vector3f & get_pos_offset() const
enum RangeFinder_Status status
AP_Int8 ground_clearance_cm
virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const =0
virtual ~AP_RangeFinder_Backend(void)
uint8_t range_valid_count() const
void update_pre_arm_check()
Common definitions and utility routines for the ArduPilot libraries.
MAV_DISTANCE_SENSOR get_mav_distance_sensor_type() const
uint8_t range_valid_count
void set_status(RangeFinder::RangeFinder_Status status)
RangeFinder::RangeFinder_Status status() const
int16_t min_distance_cm() const
RangeFinder::RangeFinder_State & state
int16_t max_distance_cm() const