25 #if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \ 26 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && \ 174 #if RANGEFINDER_MAX_INSTANCES > 1 298 #if RANGEFINDER_MAX_INSTANCES > 2 423 #if RANGEFINDER_MAX_INSTANCES > 3 555 estimated_terrain_height(0),
565 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 569 #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL 658 if (
state[instance].address) {
659 #ifdef HAL_RANGEFINDER_LIGHTWARE_I2C_BUS 672 if (
state[instance].address) {
687 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 694 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI 716 #if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \ 717 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && defined(HAVE_LIBIIO) 787 if (backend ==
nullptr) {
814 if (backend ==
nullptr) {
828 if (backend ==
nullptr) {
837 if (backend ==
nullptr) {
846 if (backend ==
nullptr) {
855 if (backend ==
nullptr) {
864 if (backend ==
nullptr) {
873 if (backend ==
nullptr) {
882 if (backend ==
nullptr) {
907 if (backend ==
nullptr) {
916 if (backend ==
nullptr) {
917 return MAV_DISTANCE_SENSOR_UNKNOWN;
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 AP_SerialManager serial_manager
static AP_RangeFinder_Backend * detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static RangeFinder * _singleton
uint16_t voltage_mv() const
static void load_object_from_eeprom(const void *object_pointer, const struct GroupInfo *group_info)
RangeFinder_State state[RANGEFINDER_MAX_INSTANCES]
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
enum Rotation orientation() const
static AP_RangeFinder_Backend * detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
uint16_t distance_cm() const
AP_SerialManager & serial_manager
const Vector3f & get_pos_offset_orient(enum Rotation orientation) const
#define RANGEFINDER_MAX_INSTANCES
static AP_RangeFinder_Backend * detect(uint8_t bus, RangeFinder::RangeFinder_State &_state, RangeFinder::RangeFinder_Type rftype)
int16_t ground_clearance_cm() const
#define AP_GROUPINFO(name, idx, clazz, element, def)
bool has_orientation(enum Rotation orientation) const
float estimated_terrain_height
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
AP_RangeFinder_Backend * find_instance(enum Rotation orientation) const
uint8_t range_valid_count_orient(enum Rotation orientation) const
virtual void handle_msg(mavlink_message_t *msg)
static const struct AP_Param::GroupInfo var_info[]
const Vector3f & get_pos_offset() const
static bool detect(RangeFinder::RangeFinder_State &_state)
enum RangeFinder_Status status
void detect_instance(uint8_t instance, uint8_t &serial_instance)
#define AP_SUBGROUPVARPTR(element, name, idx, thisclazz, var_info)
#define AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR
uint8_t range_valid_count() const
AP_Int16 _powersave_range
bool pre_arm_check() const
uint16_t distance_cm_orient(enum Rotation orientation) const
int16_t max_distance_cm_orient(enum Rotation orientation) const
void update_pre_arm_check()
bool _add_backend(AP_RangeFinder_Backend *driver)
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
uint16_t pre_arm_distance_max
AP_RangeFinder_Backend * drivers[RANGEFINDER_MAX_INSTANCES]
AP_HAL::I2CDeviceManager * i2c_mgr
uint16_t voltage_mv_orient(enum Rotation orientation) const
void handle_msg(mavlink_message_t *msg)
MAV_DISTANCE_SENSOR get_mav_distance_sensor_type() const
RangeFinder_Status status_orient(enum Rotation orientation) const
static AP_RangeFinder_Backend * detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
#define RANGEFINDER_GROUND_CLEARANCE_CM_DEFAULT
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]
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
RangeFinder::RangeFinder_Status status() const
int16_t min_distance_cm() const
void panic(const char *errormsg,...) FMT_PRINTF(1
virtual OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)=0
int16_t ground_clearance_cm_orient(enum Rotation orientation) const
int16_t min_distance_cm_orient(enum Rotation orientation) const
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
uint16_t pre_arm_distance_min
int16_t max_distance_cm() const
static AP_RangeFinder_Backend * detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > i2c_dev)
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)