/* 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 . */ #include #include #include #include #include #include "AP_Proximity.h" #include "AP_Proximity_Backend.h" /* base class constructor. This incorporates initialisation as well. */ AP_Proximity_Backend::AP_Proximity_Backend(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state) : frontend(_frontend), state(_state) { } static_assert(PROXIMITY_MAX_DIRECTION <= 8, "get_horizontal_distances assumes 8-bits is enough for validity bitmask"); // get distances in PROXIMITY_MAX_DIRECTION directions horizontally. used for sending distances to ground station bool AP_Proximity_Backend::get_horizontal_distances(AP_Proximity::Proximity_Distance_Array &prx_dist_array) const { // cycle through all sectors filling in distances and orientations // see MAV_SENSOR_ORIENTATION for orientations (0 = forward, 1 = 45 degree clockwise from north, etc) bool valid_distances = false; prx_dist_array.offset_valid = 0; for (uint8_t i=0; ihealthy()) { return false; } if (!AP::ahrs().get_relative_position_NED_origin(current_pos)) { return false; } body_to_ned = AP::ahrs().get_rotation_body_to_ned(); return true; } // update Object Avoidance database with Earth-frame point void AP_Proximity_Backend::database_push(float angle, float distance) { Vector3f current_pos; Matrix3f body_to_ned; if (database_prepare_for_push(current_pos, body_to_ned)) { database_push(angle, distance, AP_HAL::millis(), current_pos, body_to_ned); } } // update Object Avoidance database with Earth-frame point // pitch can be optionally provided if needed void AP_Proximity_Backend::database_push(float angle, float pitch, float distance, uint32_t timestamp_ms, const Vector3f ¤t_pos, const Matrix3f &body_to_ned) { AP_OADatabase *oaDb = AP::oadatabase(); if (oaDb == nullptr || !oaDb->healthy()) { return; } //Assume object is angle and pitch bearing and distance meters away from the vehicle Vector3f object_3D; object_3D.offset_bearing(wrap_180(angle), wrap_180(pitch * -1.0f), distance); const Vector3f rotated_object_3D = body_to_ned * object_3D; //Calculate the position vector from origin Vector3f temp_pos = current_pos + rotated_object_3D; //Convert the vector to a NEU frame from NED temp_pos.z = temp_pos.z * -1.0f; oaDb->queue_push(temp_pos, timestamp_ms, distance); }