/* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with this program. If not, see . */ #pragma once #include #include #include #define PROXIMITY_NUM_SECTORS 8 // number of sectors #define PROXIMITY_NUM_LAYERS 5 // num of layers in a sector #define PROXIMITY_MIDDLE_LAYER 2 // middle layer #define PROXIMITY_PITCH_WIDTH_DEG 30 // width between each layer in degrees #define PROXIMITY_SECTOR_WIDTH_DEG (360.0f/PROXIMITY_NUM_SECTORS) // width of sectors in degrees #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. #define PROXIMITY_BOUNDARY_DIST_DEFAULT 100 // if we have no data for a sector, boundary is placed 100m out #define PROXIMITY_FILT_RESET_TIME 1000 // reset filter if last distance was pushed more than this many ms away #define PROXIMITY_FACE_RESET_MS 1000 // face will be reset if not updated within this many ms // structure holding distances in PROXIMITY_MAX_DIRECTION directions. used for sending distances to ground station #define PROXIMITY_MAX_DIRECTION 8 struct Proximity_Distance_Array { uint8_t orientation[PROXIMITY_MAX_DIRECTION]; // orientation (i.e. rough direction) of the distance (see MAV_SENSOR_ORIENTATION) float distance[PROXIMITY_MAX_DIRECTION]; // distance in meters bool valid(uint8_t offset) const { // returns true if the distance stored at offset is valid return (offset < 8 && (offset_valid & (1U<= PROXIMITY_NUM_SECTORS-1) ? 0 : sector+1); } // get the prev sector which is CCW to the passed sector uint8_t get_prev_sector(uint8_t sector) const {return ((sector <= 0) ? PROXIMITY_NUM_SECTORS-1 : sector-1); } // Converts obstacle_num passed from avoidance library into appropriate face of the boundary // Returns false if the face is invalid // "update_boundary" method manipulates two sectors ccw and one sector cw from any valid face. // Any boundary that does not fall into these manipulated faces are useless, and will be marked as false // The resultant is packed into a Boundary Location object and returned by reference as "face" bool convert_obstacle_num_to_face(uint8_t obstacle_num, Face& face) const WARN_IF_UNUSED; // Apply a new cutoff_freq to low-pass filter void apply_filter_freq(float cutoff_freq); // Apply low pass filter on the raw distance void set_filtered_distance(const Face &face, float distance); // Return filtered distance for the passed in face bool get_filtered_distance(const Face &face, float &distance) const; Vector3f _sector_edge_vector[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; Vector3f _boundary_points[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; float _angle[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // yaw angle in degrees to closest object within each sector and layer float _pitch[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // pitch angle in degrees to the closest object within each sector and layer float _distance[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // distance to closest object within each sector and layer bool _distance_valid[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // true if a valid distance received for each sector and layer uint32_t _last_update_ms[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // time when distance was last updated uint8_t _prx_instance[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // proximity sensor backend instance that provided the distance LowPassFilterFloat _filtered_distance[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // low pass filter float _filter_freq; // cutoff freq of low pass filter uint32_t _last_check_face_timeout_ms; // system time to throttle check_face_timeout method }; // This class gives an easy way of making a temporary boundary, used for "sorting" distances. // When unknown number of distances at various orientations are sent we store the least distance in the temporary boundary. // After all the messages are received, we copy the contents of the temporary boundary and put it in the main 3-D boundary. class AP_Proximity_Temp_Boundary { public: // constructor. This incorporates initialisation as well. AP_Proximity_Temp_Boundary() { reset(); } // reset the temporary boundary. This fills in distances with FLT_MAX void reset(); // add a distance to the temp boundary if it is shorter than any other provided distance since the last time the boundary was reset // pitch and yaw are in degrees, distance is in meters void add_distance(const AP_Proximity_Boundary_3D::Face &face, float pitch, float yaw, float distance); void add_distance(const AP_Proximity_Boundary_3D::Face &face, float yaw, float distance) { add_distance(face, 0.0f, yaw, distance); } // fill the original 3D boundary with the contents of this temporary boundary // prx_instance should be set to the proximity sensor's backend instance number void update_3D_boundary(uint8_t prx_instance, AP_Proximity_Boundary_3D &boundary); private: float _distances[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // distance to closest object within each sector and layer. Will start with FLT_MAX, and then be changed to a valid distance if needed float _angle[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // yaw angle in degrees to closest object within each sector and layer float _pitch[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // pitch angle in degrees to the closest object within each sector and layer };