21 #define PROXIMITY_SECTORS_MAX 12 // maximum number of sectors 22 #define PROXIMITY_BOUNDARY_DIST_MIN 0.6f // minimum distance for a boundary point. This ensures the object avoidance code doesn't think we are outside the boundary. 23 #define PROXIMITY_BOUNDARY_DIST_DEFAULT 100 // if we have no data for a sector, boundary is placed 100m out 86 bool get_ignore_area(uint8_t index, uint16_t &angle_deg, uint8_t &width_deg)
const;
94 uint16_t
_sector_middle_deg[
PROXIMITY_SECTORS_MAX] = {0, 45, 90, 135, 180, 225, 270, 315, 0, 0, 0, 0};
95 uint8_t
_sector_width_deg[
PROXIMITY_SECTORS_MAX] = {45, 45, 45, 45, 45, 45, 45, 45, 0, 0, 0, 0};
bool _distance_valid[PROXIMITY_SECTORS_MAX]
float _angle[PROXIMITY_SECTORS_MAX]
#define PROXIMITY_MAX_DIRECTION
uint16_t _sector_middle_deg[PROXIMITY_SECTORS_MAX]
void set_status(AP_Proximity::Proximity_Status status)
Vector2f _boundary_point[PROXIMITY_SECTORS_MAX]
bool convert_angle_to_sector(float angle_degrees, uint8_t §or) const
uint8_t get_ignore_area_count() const
float _distance[PROXIMITY_SECTORS_MAX]
virtual bool get_upward_distance(float &distance) const
bool get_closest_object(float &angle_deg, float &distance) const
Vector2f _sector_edge_vector[PROXIMITY_SECTORS_MAX]
bool get_object_angle_and_distance(uint8_t object_number, float &angle_deg, float &distance) const
bool get_horizontal_distances(AP_Proximity::Proximity_Distance_Array &prx_dist_array) const
virtual float distance_max() const =0
virtual ~AP_Proximity_Backend(void)
virtual float distance_min() const =0
Common definitions and utility routines for the ArduPilot libraries.
AP_Proximity::Proximity_State & state
virtual void handle_msg(mavlink_message_t *msg)
bool get_next_ignore_start_or_end(uint8_t start_or_end, int16_t start_angle, int16_t &ignore_start) const
uint8_t _sector_width_deg[PROXIMITY_SECTORS_MAX]
bool get_ignore_area(uint8_t index, uint16_t &angle_deg, uint8_t &width_deg) const
void update_boundary_for_sector(uint8_t sector)
#define PROXIMITY_SECTORS_MAX
bool get_horizontal_distance(float angle_deg, float &distance) const
AP_Proximity_Backend(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state)
const Vector2f * get_boundary_points(uint16_t &num_points) const
uint8_t get_object_count() const