123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166 |
- #pragma once
- #include <AP_Common/AP_Common.h>
- #include <AP_HAL/AP_HAL.h>
- #include <AP_Param/AP_Param.h>
- #include <AP_Math/AP_Math.h>
- #include <AP_SerialManager/AP_SerialManager.h>
- #include <AP_RangeFinder/AP_RangeFinder.h>
- #define PROXIMITY_MAX_INSTANCES 1
- #define PROXIMITY_MAX_IGNORE 6
- #define PROXIMITY_MAX_DIRECTION 8
- #define PROXIMITY_SENSOR_ID_START 10
- class AP_Proximity_Backend;
- class AP_Proximity
- {
- public:
- friend class AP_Proximity_Backend;
- AP_Proximity(AP_SerialManager &_serial_manager);
- AP_Proximity(const AP_Proximity &other) = delete;
- AP_Proximity &operator=(const AP_Proximity) = delete;
-
- enum Proximity_Type {
- Proximity_Type_None = 0,
- Proximity_Type_SF40C = 1,
- Proximity_Type_MAV = 2,
- Proximity_Type_TRTOWER = 3,
- Proximity_Type_RangeFinder = 4,
- Proximity_Type_RPLidarA2 = 5,
- Proximity_Type_TRTOWEREVO = 6,
- Proximity_Type_SITL = 10,
- Proximity_Type_MorseSITL = 11,
- Proximity_Type_AirSimSITL = 12,
- };
- enum Proximity_Status {
- Proximity_NotConnected = 0,
- Proximity_NoData,
- Proximity_Good
- };
-
- struct Proximity_Distance_Array {
- uint8_t orientation[PROXIMITY_MAX_DIRECTION];
- float distance[PROXIMITY_MAX_DIRECTION];
- };
-
- void init(void);
-
- void update(void);
-
- void set_rangefinder(const RangeFinder *rangefinder) { _rangefinder = rangefinder; }
- const RangeFinder *get_rangefinder() const { return _rangefinder; }
-
- uint8_t get_orientation(uint8_t instance) const;
- int16_t get_yaw_correction(uint8_t instance) const;
-
- Proximity_Status get_status(uint8_t instance) const;
- Proximity_Status get_status() const;
-
- uint8_t num_sensors(void) const {
- return num_instances;
- }
-
-
- bool get_horizontal_distance(uint8_t instance, float angle_deg, float &distance) const;
- bool get_horizontal_distance(float angle_deg, float &distance) const;
-
- bool get_horizontal_distances(Proximity_Distance_Array &prx_dist_array) const;
-
-
- const Vector2f* get_boundary_points(uint8_t instance, uint16_t& num_points) const;
- const Vector2f* get_boundary_points(uint16_t& num_points) const;
-
-
- bool get_closest_object(float& angle_deg, float &distance) const;
-
- uint8_t get_object_count() const;
- bool get_object_angle_and_distance(uint8_t object_number, float& angle_deg, float &distance) const;
-
- float distance_max() const;
- float distance_min() const;
-
- void handle_msg(const mavlink_message_t &msg);
-
- struct Proximity_State {
- uint8_t instance;
- enum Proximity_Status status;
- };
-
-
-
-
- bool get_upward_distance(uint8_t instance, float &distance) const;
- bool get_upward_distance(float &distance) const;
- Proximity_Type get_type(uint8_t instance) const;
-
- static const struct AP_Param::GroupInfo var_info[];
- static AP_Proximity *get_singleton(void) { return _singleton; };
-
-
- bool sensor_present() const;
- bool sensor_enabled() const;
- bool sensor_failed() const;
- private:
- static AP_Proximity *_singleton;
- Proximity_State state[PROXIMITY_MAX_INSTANCES];
- AP_Proximity_Backend *drivers[PROXIMITY_MAX_INSTANCES];
- const RangeFinder *_rangefinder;
- uint8_t primary_instance;
- uint8_t num_instances;
- AP_SerialManager &serial_manager;
-
- AP_Int8 _type[PROXIMITY_MAX_INSTANCES];
- AP_Int8 _orientation[PROXIMITY_MAX_INSTANCES];
- AP_Int16 _yaw_correction[PROXIMITY_MAX_INSTANCES];
- AP_Int16 _ignore_angle_deg[PROXIMITY_MAX_IGNORE];
- AP_Int8 _ignore_width_deg[PROXIMITY_MAX_IGNORE];
- void detect_instance(uint8_t instance);
- };
- namespace AP {
- AP_Proximity *proximity();
- };
|