123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374 |
- #include <AP_Common/AP_Common.h>
- #include <AP_Common/Location.h>
- #include <AP_AHRS/AP_AHRS.h>
- #include <AC_Avoidance/AP_OADatabase.h>
- #include <AP_HAL/AP_HAL.h>
- #include "AP_Proximity.h"
- #include "AP_Proximity_Backend.h"
- AP_Proximity_Backend::AP_Proximity_Backend(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state) :
- frontend(_frontend),
- state(_state)
- {
-
- init_boundary();
- }
- bool AP_Proximity_Backend::get_horizontal_distance(float angle_deg, float &distance) const
- {
- uint8_t sector;
- if (convert_angle_to_sector(angle_deg, sector)) {
- if (_distance_valid[sector]) {
- distance = _distance[sector];
- return true;
- }
- }
- return false;
- }
- bool AP_Proximity_Backend::get_closest_object(float& angle_deg, float &distance) const
- {
- bool sector_found = false;
- uint8_t sector = 0;
-
- for (uint8_t i=0; i<_num_sectors; i++) {
- if (_distance_valid[i]) {
- if (!sector_found || (_distance[i] < _distance[sector])) {
- sector = i;
- sector_found = true;
- }
- }
- }
- if (sector_found) {
- angle_deg = _angle[sector];
- distance = _distance[sector];
- }
- return sector_found;
- }
- uint8_t AP_Proximity_Backend::get_object_count() const
- {
- return _num_sectors;
- }
- bool AP_Proximity_Backend::get_object_angle_and_distance(uint8_t object_number, float& angle_deg, float &distance) const
- {
- if (object_number < _num_sectors && _distance_valid[object_number]) {
- angle_deg = _angle[object_number];
- distance = _distance[object_number];
- return true;
- }
- return false;
- }
- bool AP_Proximity_Backend::get_horizontal_distances(AP_Proximity::Proximity_Distance_Array &prx_dist_array) const
- {
-
- bool valid_distances = false;
- for (uint8_t i=0; i<_num_sectors; i++) {
- if (_distance_valid[i]) {
- valid_distances = true;
- break;
- }
- }
- if (!valid_distances) {
- return false;
- }
-
-
-
- bool dist_set[PROXIMITY_MAX_DIRECTION]{};
- for (uint8_t i=0; i<PROXIMITY_MAX_DIRECTION; i++) {
- prx_dist_array.orientation[i] = i;
- prx_dist_array.distance[i] = distance_max();
- }
-
- for (uint8_t i=0; i<_num_sectors; i++) {
- if (_distance_valid[i]) {
-
- int16_t orientation = static_cast<int16_t>(_angle[i] * (PROXIMITY_MAX_DIRECTION / 360.0f));
- if ((orientation >= 0) && (orientation < PROXIMITY_MAX_DIRECTION) && (_distance[i] < prx_dist_array.distance[orientation])) {
- prx_dist_array.distance[orientation] = _distance[i];
- dist_set[orientation] = true;
- }
- }
- }
-
- for (uint8_t i=0; i<PROXIMITY_MAX_DIRECTION; i++) {
- if (!dist_set[i]) {
- uint8_t orient_before = (i==0) ? (PROXIMITY_MAX_DIRECTION - 1) : (i-1);
- uint8_t orient_after = (i==(PROXIMITY_MAX_DIRECTION - 1)) ? 0 : (i+1);
- if (dist_set[orient_before] && dist_set[orient_after]) {
- prx_dist_array.distance[i] = (prx_dist_array.distance[orient_before] + prx_dist_array.distance[orient_after]) / 2.0f;
- }
- }
- }
- return true;
- }
- const Vector2f* AP_Proximity_Backend::get_boundary_points(uint16_t& num_points) const
- {
-
- if (state.status != AP_Proximity::Proximity_Good) {
- num_points = 0;
- return nullptr;
- }
-
- bool some_valid = false;
- for (uint8_t i=0; i<_num_sectors; i++) {
- if (_distance_valid[i]) {
- some_valid = true;
- break;
- }
- }
- if (!some_valid) {
- num_points = 0;
- return nullptr;
- }
-
- num_points = _num_sectors;
- return _boundary_point;
- }
- void AP_Proximity_Backend::init_boundary()
- {
- for (uint8_t sector=0; sector < _num_sectors; sector++) {
- float angle_rad = radians((float)_sector_middle_deg[sector]+(float)_sector_width_deg[sector]/2.0f);
- _sector_edge_vector[sector].x = cosf(angle_rad) * 100.0f;
- _sector_edge_vector[sector].y = sinf(angle_rad) * 100.0f;
- _boundary_point[sector] = _sector_edge_vector[sector] * PROXIMITY_BOUNDARY_DIST_DEFAULT;
- }
- }
- void AP_Proximity_Backend::update_boundary_for_sector(const uint8_t sector, const bool push_to_OA_DB)
- {
-
- if (sector >= _num_sectors) {
- return;
- }
- if (push_to_OA_DB) {
- database_push(_angle[sector], _distance[sector]);
- }
-
- uint8_t next_sector = sector + 1;
- if (next_sector >= _num_sectors) {
- next_sector = 0;
- }
-
- float shortest_distance = PROXIMITY_BOUNDARY_DIST_DEFAULT;
- if (_distance_valid[sector] && _distance_valid[next_sector]) {
- shortest_distance = MIN(_distance[sector], _distance[next_sector]);
- } else if (_distance_valid[sector]) {
- shortest_distance = _distance[sector];
- } else if (_distance_valid[next_sector]) {
- shortest_distance = _distance[next_sector];
- }
- if (shortest_distance < PROXIMITY_BOUNDARY_DIST_MIN) {
- shortest_distance = PROXIMITY_BOUNDARY_DIST_MIN;
- }
- _boundary_point[sector] = _sector_edge_vector[sector] * shortest_distance;
-
- if (!_distance_valid[next_sector]) {
- _boundary_point[next_sector] = _sector_edge_vector[next_sector] * shortest_distance;
- }
-
- uint8_t prev_sector = (sector == 0) ? _num_sectors-1 : sector-1;
- shortest_distance = PROXIMITY_BOUNDARY_DIST_DEFAULT;
- if (_distance_valid[prev_sector] && _distance_valid[sector]) {
- shortest_distance = MIN(_distance[prev_sector], _distance[sector]);
- } else if (_distance_valid[prev_sector]) {
- shortest_distance = _distance[prev_sector];
- } else if (_distance_valid[sector]) {
- shortest_distance = _distance[sector];
- }
- _boundary_point[prev_sector] = _sector_edge_vector[prev_sector] * shortest_distance;
-
- uint8_t prev_sector_ccw = (prev_sector == 0) ? _num_sectors-1 : prev_sector-1;
- if (!_distance_valid[prev_sector_ccw]) {
- _boundary_point[prev_sector_ccw] = _sector_edge_vector[prev_sector_ccw] * shortest_distance;
- }
- }
- void AP_Proximity_Backend::set_status(AP_Proximity::Proximity_Status status)
- {
- state.status = status;
- }
- bool AP_Proximity_Backend::convert_angle_to_sector(float angle_degrees, uint8_t §or) const
- {
-
- if (angle_degrees > 360.0f || angle_degrees < -180.0f) {
- return false;
- }
-
- if (angle_degrees < 0.0f) {
- angle_degrees += 360.0f;
- }
- bool closest_found = false;
- uint8_t closest_sector;
- float closest_angle;
-
- for (uint8_t i = 0; i < _num_sectors; i++) {
- float angle_diff = fabsf(wrap_180(_sector_middle_deg[i] - angle_degrees));
-
- if (!closest_found || angle_diff < closest_angle) {
- closest_found = true;
- closest_sector = i;
- closest_angle = angle_diff;
- }
- if (fabsf(angle_diff) <= _sector_width_deg[i] / 2.0f) {
- sector = i;
- return true;
- }
- }
-
- if (closest_found) {
- sector = closest_sector;
- return true;
- }
- return false;
- }
- uint8_t AP_Proximity_Backend::get_ignore_area_count() const
- {
-
- uint8_t count = 0;
- for (uint8_t i=0; i < PROXIMITY_MAX_IGNORE; i++) {
- if (frontend._ignore_width_deg[i] != 0) {
- count++;
- }
- }
- return count;
- }
- bool AP_Proximity_Backend::get_ignore_area(uint8_t index, uint16_t &angle_deg, uint8_t &width_deg) const
- {
- if (index >= PROXIMITY_MAX_IGNORE) {
- return false;
- }
- angle_deg = frontend._ignore_angle_deg[index];
- width_deg = frontend._ignore_width_deg[index];
- return true;
- }
- bool AP_Proximity_Backend::get_next_ignore_start_or_end(uint8_t start_or_end, int16_t start_angle, int16_t &ignore_start) const
- {
- bool found = false;
- int16_t smallest_angle_diff = 0;
- int16_t smallest_angle_start = 0;
- for (uint8_t i=0; i < PROXIMITY_MAX_IGNORE; i++) {
- if (frontend._ignore_width_deg[i] != 0) {
- int16_t offset = start_or_end == 0 ? -frontend._ignore_width_deg[i] : +frontend._ignore_width_deg[i];
- int16_t ignore_start_angle = wrap_360(frontend._ignore_angle_deg[i] + offset/2.0f);
- int16_t ang_diff = wrap_360(ignore_start_angle - start_angle);
- if (!found || ang_diff < smallest_angle_diff) {
- smallest_angle_diff = ang_diff;
- smallest_angle_start = ignore_start_angle;
- found = true;
- }
- }
- }
- if (found) {
- ignore_start = smallest_angle_start;
- }
- return found;
- }
- bool AP_Proximity_Backend::database_prepare_for_push(Location ¤t_loc, float ¤t_vehicle_bearing)
- {
- AP_OADatabase *oaDb = AP::oadatabase();
- if (oaDb == nullptr || !oaDb->healthy()) {
- return false;
- }
- if (!AP::ahrs().get_position(current_loc)) {
- return false;
- }
- current_vehicle_bearing = AP::ahrs().yaw_sensor * 0.01f;
- return true;
- }
- void AP_Proximity_Backend::database_push(const float angle, const float distance)
- {
- Location current_loc;
- float current_vehicle_bearing;
- if (database_prepare_for_push(current_loc, current_vehicle_bearing) == true) {
- database_push(angle, distance, AP_HAL::millis(), current_loc, current_vehicle_bearing);
- }
- }
- void AP_Proximity_Backend::database_push(const float angle, const float distance, const uint32_t timestamp_ms, const Location ¤t_loc, const float current_vehicle_bearing)
- {
- AP_OADatabase *oaDb = AP::oadatabase();
- if (oaDb == nullptr || !oaDb->healthy()) {
- return;
- }
- Location temp_loc = current_loc;
- temp_loc.offset_bearing(wrap_180(current_vehicle_bearing + angle), distance);
- oaDb->queue_push(temp_loc, timestamp_ms, distance, angle);
- }
|