1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677 |
- #pragma once
- #include <AP_Common/AP_Common.h>
- #include <AP_HAL/AP_HAL.h>
- #include "RangeFinder.h"
- class AP_RangeFinder_Backend
- {
- public:
-
- AP_RangeFinder_Backend(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params);
-
-
- virtual ~AP_RangeFinder_Backend(void) {}
-
- virtual void update() = 0;
- virtual void handle_msg(const mavlink_message_t &msg) { return; }
- enum Rotation orientation() const { return (Rotation)params.orientation.get(); }
- uint16_t distance_cm() const { return state.distance_cm; }
- uint16_t voltage_mv() const { return state.voltage_mv; }
- int16_t max_distance_cm() const { return params.max_distance_cm; }
- int16_t min_distance_cm() const { return params.min_distance_cm; }
- int16_t ground_clearance_cm() const { return params.ground_clearance_cm; }
- MAV_DISTANCE_SENSOR get_mav_distance_sensor_type() const;
- RangeFinder::RangeFinder_Status status() const;
- RangeFinder::RangeFinder_Type type() const { return (RangeFinder::RangeFinder_Type)params.type.get(); }
-
- bool has_data() const;
-
- uint8_t range_valid_count() const { return state.range_valid_count; }
-
-
- const Vector3f &get_pos_offset() const { return params.pos_offset; }
-
- uint32_t last_reading_ms() const { return state.last_reading_ms; }
- protected:
-
- void update_status();
-
- void set_status(RangeFinder::RangeFinder_Status status);
- RangeFinder::RangeFinder_State &state;
- AP_RangeFinder_Params ¶ms;
-
- HAL_Semaphore _sem;
-
- RangeFinder::RangeFinder_Type _backend_type;
- virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const = 0;
- };
|