24 #define RANGEFINDER_MAX_INSTANCES 2 25 #define RANGEFINDER_GROUND_CLEARANCE_CM_DEFAULT 10 26 #define RANGEFINDER_PREARM_ALT_MAX_CM 200 27 #define RANGEFINDER_PREARM_REQUIRED_CHANGE_CM 50
AP_RangeFinder_Backend * get_backend(uint8_t id) const
bool has_data_orient(enum Rotation orientation) const
MAV_DISTANCE_SENSOR get_mav_distance_sensor_type_orient(enum Rotation orientation) const
static RangeFinder * _singleton
RangeFinder_State state[RANGEFINDER_MAX_INSTANCES]
AP_SerialManager & serial_manager
const Vector3f & get_pos_offset_orient(enum Rotation orientation) const
#define RANGEFINDER_MAX_INSTANCES
RangeFinder & operator=(const RangeFinder &)=delete
static RangeFinder * get_singleton(void)
bool has_orientation(enum Rotation orientation) const
float estimated_terrain_height
AP_RangeFinder_Backend * find_instance(enum Rotation orientation) const
uint8_t range_valid_count_orient(enum Rotation orientation) const
void set_estimated_terrain_height(float height)
void update_instance(uint8_t instance)
uint8_t num_sensors(void) const
enum RangeFinder_Status status
A system for managing and storing variables that are of general interest to the system.
void detect_instance(uint8_t instance, uint8_t &serial_instance)
AP_Int8 ground_clearance_cm
AP_Int16 _powersave_range
uint16_t distance_cm_orient(enum Rotation orientation) const
int16_t max_distance_cm_orient(enum Rotation orientation) const
bool _add_backend(AP_RangeFinder_Backend *driver)
uint16_t pre_arm_distance_max
AP_RangeFinder_Backend * drivers[RANGEFINDER_MAX_INSTANCES]
uint16_t voltage_mv_orient(enum Rotation orientation) const
Common definitions and utility routines for the ArduPilot libraries.
void handle_msg(mavlink_message_t *msg)
RangeFinder_Status status_orient(enum Rotation orientation) const
uint8_t range_valid_count
RangeFinder(AP_SerialManager &_serial_manager, enum Rotation orientation_default)
const struct AP_Param::GroupInfo * var_info
static const struct AP_Param::GroupInfo * backend_var_info[RANGEFINDER_MAX_INSTANCES]
int16_t ground_clearance_cm_orient(enum Rotation orientation) const
int16_t min_distance_cm_orient(enum Rotation orientation) const
uint16_t pre_arm_distance_min