mirror of https://github.com/ArduPilot/ardupilot
AP_Proximity: Make new Utils file for PRX utility functions
This commit is contained in:
parent
7cd77f266e
commit
5d29dd98c1
|
@ -395,16 +395,6 @@ bool AP_Proximity::get_upward_distance(float &distance) const
|
|||
return get_upward_distance(primary_instance, distance);
|
||||
}
|
||||
|
||||
// set alt as read from dowward facing rangefinder. Tilt is already adjusted for.
|
||||
void AP_Proximity::set_rangefinder_alt(bool use, bool healthy, float alt_cm)
|
||||
{
|
||||
if (!valid_instance(primary_instance)) {
|
||||
return;
|
||||
}
|
||||
// store alt at the backend
|
||||
drivers[primary_instance]->set_rangefinder_alt(use, healthy, alt_cm);
|
||||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
// Write proximity sensor distances
|
||||
void AP_Proximity::log()
|
||||
|
|
|
@ -155,6 +155,9 @@ public:
|
|||
// 3D boundary
|
||||
AP_Proximity_Boundary_3D boundary;
|
||||
|
||||
// Check if Obstacle defined by body-frame yaw and pitch is near ground
|
||||
bool check_obstacle_near_ground(float pitch, float yaw, float distance) const;
|
||||
|
||||
protected:
|
||||
|
||||
// parameters for backends
|
||||
|
@ -174,6 +177,17 @@ private:
|
|||
AP_Int8 _raw_log_enable; // enable logging raw distances
|
||||
AP_Int8 _ign_gnd_enable; // true if land detection should be enabled
|
||||
AP_Float _filt_freq; // cutoff frequency for low pass filter
|
||||
|
||||
// get alt from rangefinder in meters. This reading is corrected for vehicle tilt
|
||||
bool get_rangefinder_alt(float &alt_m) const;
|
||||
|
||||
struct RangeFinderState {
|
||||
bool use; // true if enabled
|
||||
bool healthy; // true if we can trust the altitude from the rangefinder
|
||||
int16_t alt_cm; // tilt compensated altitude (in cm) from rangefinder
|
||||
uint32_t last_downward_update_ms; // last update ms
|
||||
} _rangefinder_state;
|
||||
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
|
|
|
@ -16,13 +16,9 @@
|
|||
#include "AP_Proximity_Backend.h"
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
#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>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
/*
|
||||
base class constructor.
|
||||
|
@ -85,69 +81,7 @@ bool AP_Proximity_Backend::ignore_reading(float pitch, float yaw, float distance
|
|||
}
|
||||
|
||||
// check if obstacle is near land
|
||||
return check_obstacle_near_ground(pitch, yaw, distance_m);
|
||||
}
|
||||
|
||||
// store rangefinder values
|
||||
void AP_Proximity_Backend::set_rangefinder_alt(bool use, bool healthy, float alt_cm)
|
||||
{
|
||||
_last_downward_update_ms = AP_HAL::millis();
|
||||
_rangefinder_use = use;
|
||||
_rangefinder_healthy = healthy;
|
||||
_rangefinder_alt = alt_cm * 0.01f;
|
||||
}
|
||||
|
||||
// get alt from rangefinder in meters
|
||||
bool AP_Proximity_Backend::get_rangefinder_alt(float &alt_m) const
|
||||
{
|
||||
if (!_rangefinder_use || !_rangefinder_healthy) {
|
||||
// range finder is not healthy
|
||||
return false;
|
||||
}
|
||||
|
||||
const uint32_t dt = AP_HAL::millis() - _last_downward_update_ms;
|
||||
if (dt > PROXIMITY_ALT_DETECT_TIMEOUT_MS) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// readings are healthy
|
||||
alt_m = _rangefinder_alt;
|
||||
return true;
|
||||
}
|
||||
|
||||
// Check if Obstacle defined by body-frame yaw and pitch is near ground
|
||||
bool AP_Proximity_Backend::check_obstacle_near_ground(float pitch, float yaw, float distance) const
|
||||
{
|
||||
if (!frontend._ign_gnd_enable) {
|
||||
return false;
|
||||
}
|
||||
if (!hal.util->get_soft_armed()) {
|
||||
// don't run this feature while vehicle is disarmed, otherwise proximity data will not show up on GCS
|
||||
return false;
|
||||
}
|
||||
if ((pitch > 90.0f) || (pitch < -90.0f)) {
|
||||
// sanity check on pitch
|
||||
return false;
|
||||
}
|
||||
// Assume object is yaw and pitch bearing and distance meters away from the vehicle
|
||||
Vector3f object_3D;
|
||||
object_3D.offset_bearing(wrap_180(yaw), (pitch * -1.0f), distance);
|
||||
const Matrix3f body_to_ned = AP::ahrs().get_rotation_body_to_ned();
|
||||
const Vector3f rotated_object_3D = body_to_ned * object_3D;
|
||||
|
||||
float alt = FLT_MAX;
|
||||
if (!get_rangefinder_alt(alt)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (rotated_object_3D.z > -0.5f) {
|
||||
// obstacle is at the most 0.5 meters above vehicle
|
||||
if ((alt - PROXIMITY_GND_DETECT_THRESHOLD) < rotated_object_3D.z) {
|
||||
// obstacle is near or below ground
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
return frontend.check_obstacle_near_ground(pitch, yaw, distance_m);
|
||||
}
|
||||
|
||||
// returns true if database is ready to be pushed to and all cached data is ready
|
||||
|
|
|
@ -19,9 +19,6 @@
|
|||
#if HAL_PROXIMITY_ENABLED
|
||||
#include <AP_Common/AP_Common.h>
|
||||
|
||||
#define PROXIMITY_GND_DETECT_THRESHOLD 1.0f // set ground detection threshold to be 1 meters
|
||||
#define PROXIMITY_ALT_DETECT_TIMEOUT_MS 500 // alt readings should arrive within this much time
|
||||
|
||||
class AP_Proximity_Backend
|
||||
{
|
||||
public:
|
||||
|
@ -45,9 +42,6 @@ public:
|
|||
// handle mavlink messages
|
||||
virtual void handle_msg(const mavlink_message_t &msg) {}
|
||||
|
||||
// store rangefinder values
|
||||
void set_rangefinder_alt(bool use, bool healthy, float alt_cm);
|
||||
|
||||
protected:
|
||||
|
||||
// set status and update valid_count
|
||||
|
@ -64,12 +58,6 @@ protected:
|
|||
bool ignore_reading(float pitch, float yaw, float distance_m, bool check_for_ign_area = true) const;
|
||||
bool ignore_reading(float yaw, float distance_m, bool check_for_ign_area = true) const { return ignore_reading(0.0f, yaw, distance_m, check_for_ign_area); }
|
||||
|
||||
// get alt from rangefinder in meters. This reading is corrected for vehicle tilt
|
||||
bool get_rangefinder_alt(float &alt_m) const;
|
||||
|
||||
// Check if Obstacle defined by body-frame yaw and pitch is near ground
|
||||
bool check_obstacle_near_ground(float pitch, float yaw, float distance) const;
|
||||
|
||||
// database helpers. All angles are in degrees
|
||||
static bool database_prepare_for_push(Vector3f ¤t_pos, Matrix3f &body_to_ned);
|
||||
// Note: "angle" refers to yaw (in body frame) towards the obstacle
|
||||
|
@ -79,12 +67,6 @@ protected:
|
|||
};
|
||||
static void database_push(float angle, float pitch, float distance, uint32_t timestamp_ms, const Vector3f ¤t_pos, const Matrix3f &body_to_ned);
|
||||
|
||||
// used for ground detection
|
||||
uint32_t _last_downward_update_ms;
|
||||
bool _rangefinder_use;
|
||||
bool _rangefinder_healthy;
|
||||
float _rangefinder_alt;
|
||||
|
||||
AP_Proximity &frontend;
|
||||
AP_Proximity::Proximity_State &state; // reference to this instances state
|
||||
AP_Proximity_Params ¶ms; // parameters for this backend
|
||||
|
|
|
@ -0,0 +1,91 @@
|
|||
/*
|
||||
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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "AP_Proximity.h"
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
|
||||
#define PROXIMITY_GND_DETECT_THRESHOLD 1.0f // set ground detection threshold to be 1 meters
|
||||
#define PROXIMITY_ALT_DETECT_TIMEOUT_MS 500 // alt readings should arrive within this much time
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// set alt as read from downward facing rangefinder. Tilt is already adjusted for.
|
||||
void AP_Proximity::set_rangefinder_alt(bool use, bool healthy, float alt_cm)
|
||||
{
|
||||
_rangefinder_state.use = use;
|
||||
_rangefinder_state.healthy = healthy;
|
||||
_rangefinder_state.alt_cm = alt_cm;
|
||||
_rangefinder_state.last_downward_update_ms = AP_HAL::millis();
|
||||
}
|
||||
|
||||
// get alt from rangefinder in meters
|
||||
bool AP_Proximity::get_rangefinder_alt(float &alt_m) const
|
||||
{
|
||||
if (!_rangefinder_state.use || !_rangefinder_state.healthy) {
|
||||
// range finder is not healthy
|
||||
return false;
|
||||
}
|
||||
|
||||
const uint32_t dt = AP_HAL::millis() - _rangefinder_state.last_downward_update_ms;
|
||||
if (dt > PROXIMITY_ALT_DETECT_TIMEOUT_MS) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// readings are healthy
|
||||
alt_m = _rangefinder_state.alt_cm * 0.01f;
|
||||
return true;
|
||||
}
|
||||
|
||||
// Check if Obstacle defined by body-frame yaw and pitch is near ground
|
||||
bool AP_Proximity::check_obstacle_near_ground(float pitch, float yaw, float distance) const
|
||||
{
|
||||
if (!_ign_gnd_enable) {
|
||||
return false;
|
||||
}
|
||||
if (!hal.util->get_soft_armed()) {
|
||||
// don't run this feature while vehicle is disarmed, otherwise proximity data will not show up on GCS
|
||||
return false;
|
||||
}
|
||||
if ((pitch > 90.0f) || (pitch < -90.0f)) {
|
||||
// sanity check on pitch
|
||||
return false;
|
||||
}
|
||||
// Assume object is yaw and pitch bearing and distance meters away from the vehicle
|
||||
Vector3f object_3D;
|
||||
object_3D.offset_bearing(wrap_180(yaw), (pitch * -1.0f), distance);
|
||||
const Matrix3f body_to_ned = AP::ahrs().get_rotation_body_to_ned();
|
||||
const Vector3f rotated_object_3D = body_to_ned * object_3D;
|
||||
|
||||
float alt = FLT_MAX;
|
||||
if (!get_rangefinder_alt(alt)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (rotated_object_3D.z > -0.5f) {
|
||||
// obstacle is at the most 0.5 meters above vehicle
|
||||
if ((alt - PROXIMITY_GND_DETECT_THRESHOLD) < rotated_object_3D.z) {
|
||||
// obstacle is near or below ground
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
Loading…
Reference in New Issue