2019-05-28 02:47:34 -03:00
|
|
|
/*
|
|
|
|
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.
|
2016-06-19 22:12:17 -03:00
|
|
|
|
2019-05-28 02:47:34 -03:00
|
|
|
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 "AC_Avoid.h"
|
2019-05-22 03:03:57 -03:00
|
|
|
#include <AP_AHRS/AP_AHRS.h> // AHRS library
|
|
|
|
#include <AC_Fence/AC_Fence.h> // Failsafe fence library
|
|
|
|
#include <AP_Proximity/AP_Proximity.h>
|
|
|
|
#include <AP_Beacon/AP_Beacon.h>
|
|
|
|
|
2018-01-22 02:45:18 -04:00
|
|
|
#if APM_BUILD_TYPE(APM_BUILD_APMrover2)
|
|
|
|
# define AP_AVOID_BEHAVE_DEFAULT AC_Avoid::BehaviourType::BEHAVIOR_STOP
|
|
|
|
#else
|
|
|
|
# define AP_AVOID_BEHAVE_DEFAULT AC_Avoid::BehaviourType::BEHAVIOR_SLIDE
|
|
|
|
#endif
|
|
|
|
|
2016-06-19 22:12:17 -03:00
|
|
|
const AP_Param::GroupInfo AC_Avoid::var_info[] = {
|
|
|
|
|
|
|
|
// @Param: ENABLE
|
|
|
|
// @DisplayName: Avoidance control enable/disable
|
2019-06-06 20:59:31 -03:00
|
|
|
// @Description: Enabled/disable avoidance input sources
|
|
|
|
// @Values: 0:None,1:UseFence,2:UseProximitySensor,3:UseFence and UseProximitySensor,4:UseBeaconFence,7:All
|
|
|
|
// @Bitmask: 0:UseFence,1:UseProximitySensor,2:UseBeaconFence
|
2016-06-19 22:12:17 -03:00
|
|
|
// @User: Standard
|
2017-05-02 06:10:37 -03:00
|
|
|
AP_GROUPINFO("ENABLE", 1, AC_Avoid, _enabled, AC_AVOID_DEFAULT),
|
2016-06-19 22:12:17 -03:00
|
|
|
|
2017-02-28 02:33:59 -04:00
|
|
|
// @Param: ANGLE_MAX
|
2016-12-16 23:42:40 -04:00
|
|
|
// @DisplayName: Avoidance max lean angle in non-GPS flight modes
|
|
|
|
// @Description: Max lean angle used to avoid obstacles while in non-GPS modes
|
2017-05-02 10:37:44 -03:00
|
|
|
// @Units: cdeg
|
2016-12-16 23:42:40 -04:00
|
|
|
// @Range: 0 4500
|
|
|
|
// @User: Standard
|
|
|
|
AP_GROUPINFO("ANGLE_MAX", 2, AC_Avoid, _angle_max, 1000),
|
|
|
|
|
|
|
|
// @Param: DIST_MAX
|
|
|
|
// @DisplayName: Avoidance distance maximum in non-GPS flight modes
|
|
|
|
// @Description: Distance from object at which obstacle avoidance will begin in non-GPS modes
|
2017-05-02 10:37:44 -03:00
|
|
|
// @Units: m
|
2018-01-24 22:16:01 -04:00
|
|
|
// @Range: 1 30
|
2016-12-16 23:42:40 -04:00
|
|
|
// @User: Standard
|
|
|
|
AP_GROUPINFO("DIST_MAX", 3, AC_Avoid, _dist_max, AC_AVOID_NONGPS_DIST_MAX_DEFAULT),
|
|
|
|
|
2017-04-12 09:09:52 -03:00
|
|
|
// @Param: MARGIN
|
|
|
|
// @DisplayName: Avoidance distance margin in GPS modes
|
|
|
|
// @Description: Vehicle will attempt to stay at least this distance (in meters) from objects while in GPS modes
|
2017-05-02 10:37:44 -03:00
|
|
|
// @Units: m
|
2017-04-12 09:09:52 -03:00
|
|
|
// @Range: 1 10
|
|
|
|
// @User: Standard
|
|
|
|
AP_GROUPINFO("MARGIN", 4, AC_Avoid, _margin, 2.0f),
|
|
|
|
|
2017-12-12 08:19:37 -04:00
|
|
|
// @Param: BEHAVE
|
|
|
|
// @DisplayName: Avoidance behaviour
|
|
|
|
// @Description: Avoidance behaviour (slide or stop)
|
|
|
|
// @Values: 0:Slide,1:Stop
|
|
|
|
// @User: Standard
|
2018-01-22 02:45:18 -04:00
|
|
|
AP_GROUPINFO("BEHAVE", 5, AC_Avoid, _behavior, AP_AVOID_BEHAVE_DEFAULT),
|
2017-12-12 08:19:37 -04:00
|
|
|
|
2016-06-19 22:12:17 -03:00
|
|
|
AP_GROUPEND
|
|
|
|
};
|
|
|
|
|
|
|
|
/// Constructor
|
2019-05-22 03:03:57 -03:00
|
|
|
AC_Avoid::AC_Avoid()
|
2016-06-19 22:12:17 -03:00
|
|
|
{
|
2018-10-25 23:31:20 -03:00
|
|
|
_singleton = this;
|
|
|
|
|
2016-06-19 22:12:17 -03:00
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
}
|
|
|
|
|
2018-02-15 15:16:42 -04:00
|
|
|
void AC_Avoid::adjust_velocity(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt)
|
2016-06-19 22:12:17 -03:00
|
|
|
{
|
|
|
|
// exit immediately if disabled
|
|
|
|
if (_enabled == AC_AVOID_DISABLED) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// limit acceleration
|
2018-10-26 01:49:45 -03:00
|
|
|
const float accel_cmss_limited = MIN(accel_cmss, AC_AVOID_ACCEL_CMSS_MAX);
|
2016-06-19 22:12:17 -03:00
|
|
|
|
2016-08-15 08:59:35 -03:00
|
|
|
if ((_enabled & AC_AVOID_STOP_AT_FENCE) > 0) {
|
2018-02-15 15:16:42 -04:00
|
|
|
adjust_velocity_circle_fence(kP, accel_cmss_limited, desired_vel_cms, dt);
|
|
|
|
adjust_velocity_polygon_fence(kP, accel_cmss_limited, desired_vel_cms, dt);
|
2016-06-19 22:12:17 -03:00
|
|
|
}
|
2016-08-15 08:59:35 -03:00
|
|
|
|
2017-05-02 06:10:37 -03:00
|
|
|
if ((_enabled & AC_AVOID_STOP_AT_BEACON_FENCE) > 0) {
|
2018-02-15 15:16:42 -04:00
|
|
|
adjust_velocity_beacon_fence(kP, accel_cmss_limited, desired_vel_cms, dt);
|
2017-05-02 06:10:37 -03:00
|
|
|
}
|
|
|
|
|
2016-12-16 23:42:40 -04:00
|
|
|
if ((_enabled & AC_AVOID_USE_PROXIMITY_SENSOR) > 0 && _proximity_enabled) {
|
2018-02-15 15:16:42 -04:00
|
|
|
adjust_velocity_proximity(kP, accel_cmss_limited, desired_vel_cms, dt);
|
2016-08-15 08:59:35 -03:00
|
|
|
}
|
2016-06-19 22:12:17 -03:00
|
|
|
}
|
|
|
|
|
2016-07-25 00:16:26 -03:00
|
|
|
// convenience function to accept Vector3f. Only x and y are adjusted
|
2018-02-15 15:16:42 -04:00
|
|
|
void AC_Avoid::adjust_velocity(float kP, float accel_cmss, Vector3f &desired_vel_cms, float dt)
|
2016-07-25 00:16:26 -03:00
|
|
|
{
|
2018-02-15 15:16:42 -04:00
|
|
|
Vector2f des_vel_xy(desired_vel_cms.x, desired_vel_cms.y);
|
2017-06-26 05:48:48 -03:00
|
|
|
adjust_velocity(kP, accel_cmss, des_vel_xy, dt);
|
2018-02-15 15:16:42 -04:00
|
|
|
desired_vel_cms.x = des_vel_xy.x;
|
|
|
|
desired_vel_cms.y = des_vel_xy.y;
|
2016-07-25 00:16:26 -03:00
|
|
|
}
|
|
|
|
|
2017-12-13 05:16:07 -04:00
|
|
|
// adjust desired horizontal speed so that the vehicle stops before the fence or object
|
|
|
|
// accel (maximum acceleration/deceleration) is in m/s/s
|
|
|
|
// heading is in radians
|
|
|
|
// speed is in m/s
|
|
|
|
// kP should be zero for linear response, non-zero for non-linear response
|
|
|
|
void AC_Avoid::adjust_speed(float kP, float accel, float heading, float &speed, float dt)
|
|
|
|
{
|
|
|
|
// convert heading and speed into velocity vector
|
|
|
|
Vector2f vel_xy;
|
|
|
|
vel_xy.x = cosf(heading) * speed * 100.0f;
|
|
|
|
vel_xy.y = sinf(heading) * speed * 100.0f;
|
|
|
|
adjust_velocity(kP, accel * 100.0f, vel_xy, dt);
|
|
|
|
|
|
|
|
// adjust speed towards zero
|
|
|
|
if (is_negative(speed)) {
|
|
|
|
speed = -vel_xy.length() * 0.01f;
|
|
|
|
} else {
|
|
|
|
speed = vel_xy.length() * 0.01f;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-01-05 02:21:55 -04:00
|
|
|
// adjust vertical climb rate so vehicle does not break the vertical fence
|
2017-06-26 05:48:48 -03:00
|
|
|
void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float dt)
|
2017-01-05 02:21:55 -04:00
|
|
|
{
|
|
|
|
// exit immediately if disabled
|
|
|
|
if (_enabled == AC_AVOID_DISABLED) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// do not adjust climb_rate if level or descending
|
|
|
|
if (climb_rate_cms <= 0.0f) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// limit acceleration
|
2018-10-26 01:49:45 -03:00
|
|
|
const float accel_cmss_limited = MIN(accel_cmss, AC_AVOID_ACCEL_CMSS_MAX);
|
2017-01-05 02:21:55 -04:00
|
|
|
|
2017-01-16 00:49:51 -04:00
|
|
|
bool limit_alt = false;
|
2017-12-07 00:13:03 -04:00
|
|
|
float alt_diff = 0.0f; // distance from altitude limit to vehicle in metres (positive means vehicle is below limit)
|
2017-01-05 02:21:55 -04:00
|
|
|
|
2019-05-22 03:03:57 -03:00
|
|
|
const AP_AHRS &_ahrs = AP::ahrs();
|
|
|
|
|
2017-01-16 00:49:51 -04:00
|
|
|
// calculate distance below fence
|
2019-05-22 03:03:57 -03:00
|
|
|
AC_Fence *fence = AP::fence();
|
|
|
|
if ((_enabled & AC_AVOID_STOP_AT_FENCE) > 0 && fence && (fence->get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX) > 0) {
|
2017-01-05 02:21:55 -04:00
|
|
|
// calculate distance from vehicle to safe altitude
|
2017-12-07 00:03:36 -04:00
|
|
|
float veh_alt;
|
|
|
|
_ahrs.get_relative_position_D_home(veh_alt);
|
|
|
|
// _fence.get_safe_alt_max() is UP, veh_alt is DOWN:
|
2019-05-22 03:03:57 -03:00
|
|
|
alt_diff = fence->get_safe_alt_max() + veh_alt;
|
2017-01-16 00:49:51 -04:00
|
|
|
limit_alt = true;
|
|
|
|
}
|
|
|
|
|
2017-12-06 23:08:29 -04:00
|
|
|
// calculate distance to (e.g.) optical flow altitude limit
|
|
|
|
// AHRS values are always in metres
|
|
|
|
float alt_limit;
|
|
|
|
float curr_alt;
|
|
|
|
if (_ahrs.get_hgt_ctrl_limit(alt_limit) &&
|
|
|
|
_ahrs.get_relative_position_D_origin(curr_alt)) {
|
|
|
|
// alt_limit is UP, curr_alt is DOWN:
|
2017-12-07 00:13:03 -04:00
|
|
|
const float ctrl_alt_diff = alt_limit + curr_alt;
|
|
|
|
if (!limit_alt || ctrl_alt_diff < alt_diff) {
|
|
|
|
alt_diff = ctrl_alt_diff;
|
2017-12-06 23:08:29 -04:00
|
|
|
limit_alt = true;
|
2017-01-16 00:49:51 -04:00
|
|
|
}
|
|
|
|
}
|
2017-01-05 02:21:55 -04:00
|
|
|
|
2017-12-07 00:13:03 -04:00
|
|
|
// get distance from proximity sensor
|
|
|
|
float proximity_alt_diff;
|
2019-05-22 03:03:57 -03:00
|
|
|
AP_Proximity *proximity = AP::proximity();
|
|
|
|
if (proximity && proximity->get_upward_distance(proximity_alt_diff)) {
|
2017-12-07 00:13:03 -04:00
|
|
|
proximity_alt_diff -= _margin;
|
|
|
|
if (!limit_alt || proximity_alt_diff < alt_diff) {
|
|
|
|
alt_diff = proximity_alt_diff;
|
|
|
|
limit_alt = true;
|
2017-01-16 02:58:43 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-01-16 00:49:51 -04:00
|
|
|
// limit climb rate
|
|
|
|
if (limit_alt) {
|
2017-01-05 02:21:55 -04:00
|
|
|
// do not allow climbing if we've breached the safe altitude
|
2017-12-07 00:13:03 -04:00
|
|
|
if (alt_diff <= 0.0f) {
|
2017-01-05 02:21:55 -04:00
|
|
|
climb_rate_cms = MIN(climb_rate_cms, 0.0f);
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// limit climb rate
|
2017-06-26 05:48:48 -03:00
|
|
|
const float max_speed = get_max_speed(kP, accel_cmss_limited, alt_diff*100.0f, dt);
|
2017-01-05 02:21:55 -04:00
|
|
|
climb_rate_cms = MIN(max_speed, climb_rate_cms);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-12-16 23:42:40 -04:00
|
|
|
// adjust roll-pitch to push vehicle away from objects
|
|
|
|
// roll and pitch value are in centi-degrees
|
2016-12-19 19:51:26 -04:00
|
|
|
void AC_Avoid::adjust_roll_pitch(float &roll, float &pitch, float veh_angle_max)
|
2016-12-16 23:42:40 -04:00
|
|
|
{
|
|
|
|
// exit immediately if proximity based avoidance is disabled
|
|
|
|
if ((_enabled & AC_AVOID_USE_PROXIMITY_SENSOR) == 0 || !_proximity_enabled) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// exit immediately if angle max is zero
|
2016-12-19 19:51:26 -04:00
|
|
|
if (_angle_max <= 0.0f || veh_angle_max <= 0.0f) {
|
2016-12-16 23:42:40 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
float roll_positive = 0.0f; // maximum positive roll value
|
|
|
|
float roll_negative = 0.0f; // minimum negative roll value
|
2018-04-20 11:53:35 -03:00
|
|
|
float pitch_positive = 0.0f; // maximum positive pitch value
|
2016-12-16 23:42:40 -04:00
|
|
|
float pitch_negative = 0.0f; // minimum negative pitch value
|
|
|
|
|
|
|
|
// get maximum positive and negative roll and pitch percentages from proximity sensor
|
|
|
|
get_proximity_roll_pitch_pct(roll_positive, roll_negative, pitch_positive, pitch_negative);
|
|
|
|
|
|
|
|
// add maximum positive and negative percentages together for roll and pitch, convert to centi-degrees
|
|
|
|
Vector2f rp_out((roll_positive + roll_negative) * 4500.0f, (pitch_positive + pitch_negative) * 4500.0f);
|
|
|
|
|
|
|
|
// apply avoidance angular limits
|
|
|
|
// the object avoidance lean angle is never more than 75% of the total angle-limit to allow the pilot to override
|
2016-12-19 19:51:26 -04:00
|
|
|
const float angle_limit = constrain_float(_angle_max, 0.0f, veh_angle_max * AC_AVOID_ANGLE_MAX_PERCENT);
|
2016-12-16 23:42:40 -04:00
|
|
|
float vec_len = rp_out.length();
|
|
|
|
if (vec_len > angle_limit) {
|
|
|
|
rp_out *= (angle_limit / vec_len);
|
|
|
|
}
|
|
|
|
|
|
|
|
// add passed in roll, pitch angles
|
|
|
|
rp_out.x += roll;
|
|
|
|
rp_out.y += pitch;
|
|
|
|
|
|
|
|
// apply total angular limits
|
|
|
|
vec_len = rp_out.length();
|
2016-12-19 19:51:26 -04:00
|
|
|
if (vec_len > veh_angle_max) {
|
|
|
|
rp_out *= (veh_angle_max / vec_len);
|
2016-12-16 23:42:40 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// return adjusted roll, pitch
|
|
|
|
roll = rp_out.x;
|
|
|
|
pitch = rp_out.y;
|
|
|
|
}
|
|
|
|
|
2018-01-29 08:36:37 -04:00
|
|
|
/*
|
2018-02-15 15:16:42 -04:00
|
|
|
* Limits the component of desired_vel_cms in the direction of the unit vector
|
|
|
|
* limit_direction to be at most the maximum speed permitted by the limit_distance_cm.
|
2018-01-29 08:36:37 -04:00
|
|
|
*
|
|
|
|
* Uses velocity adjustment idea from Randy's second email on this thread:
|
|
|
|
* https://groups.google.com/forum/#!searchin/drones-discuss/obstacle/drones-discuss/QwUXz__WuqY/qo3G8iTLSJAJ
|
|
|
|
*/
|
2018-02-15 15:16:42 -04:00
|
|
|
void AC_Avoid::limit_velocity(float kP, float accel_cmss, Vector2f &desired_vel_cms, const Vector2f& limit_direction, float limit_distance_cm, float dt) const
|
2018-01-29 08:36:37 -04:00
|
|
|
{
|
2018-02-15 15:16:42 -04:00
|
|
|
const float max_speed = get_max_speed(kP, accel_cmss, limit_distance_cm, dt);
|
2018-01-29 08:36:37 -04:00
|
|
|
// project onto limit direction
|
2018-02-15 15:16:42 -04:00
|
|
|
const float speed = desired_vel_cms * limit_direction;
|
2018-01-29 08:36:37 -04:00
|
|
|
if (speed > max_speed) {
|
|
|
|
// subtract difference between desired speed and maximum acceptable speed
|
2018-02-15 15:16:42 -04:00
|
|
|
desired_vel_cms += limit_direction*(max_speed - speed);
|
2018-01-29 08:36:37 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
* Computes the speed such that the stopping distance
|
|
|
|
* of the vehicle will be exactly the input distance.
|
|
|
|
*/
|
|
|
|
float AC_Avoid::get_max_speed(float kP, float accel_cmss, float distance_cm, float dt) const
|
|
|
|
{
|
|
|
|
if (is_zero(kP)) {
|
|
|
|
return safe_sqrt(2.0f * distance_cm * accel_cmss);
|
|
|
|
} else {
|
|
|
|
return AC_AttitudeControl::sqrt_controller(distance_cm, kP, accel_cmss, dt);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-06-19 22:12:17 -03:00
|
|
|
/*
|
|
|
|
* Adjusts the desired velocity for the circular fence.
|
|
|
|
*/
|
2018-02-15 15:16:42 -04:00
|
|
|
void AC_Avoid::adjust_velocity_circle_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt)
|
2016-06-19 22:12:17 -03:00
|
|
|
{
|
2019-05-22 03:03:57 -03:00
|
|
|
AC_Fence *fence = AP::fence();
|
|
|
|
if (fence == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
AC_Fence &_fence = *fence;
|
|
|
|
|
2016-06-19 22:12:17 -03:00
|
|
|
// exit if circular fence is not enabled
|
|
|
|
if ((_fence.get_enabled_fences() & AC_FENCE_TYPE_CIRCLE) == 0) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2016-06-23 01:16:26 -03:00
|
|
|
// exit if the circular fence has already been breached
|
|
|
|
if ((_fence.get_breaches() & AC_FENCE_TYPE_CIRCLE) != 0) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2019-06-07 06:30:52 -03:00
|
|
|
// get desired speed
|
|
|
|
const float desired_speed = desired_vel_cms.length();
|
|
|
|
if (is_zero(desired_speed)) {
|
|
|
|
// no avoidance necessary when desired speed is zero
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2019-05-22 03:03:57 -03:00
|
|
|
const AP_AHRS &_ahrs = AP::ahrs();
|
|
|
|
|
2017-12-07 00:03:36 -04:00
|
|
|
// get position as a 2D offset from ahrs home
|
|
|
|
Vector2f position_xy;
|
|
|
|
if (!_ahrs.get_relative_position_NE_home(position_xy)) {
|
|
|
|
// we have no idea where we are....
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
position_xy *= 100.0f; // m -> cm
|
2016-06-19 22:12:17 -03:00
|
|
|
|
|
|
|
// get the fence radius in cm
|
|
|
|
const float fence_radius = _fence.get_radius() * 100.0f;
|
|
|
|
// get the margin to the fence in cm
|
2017-04-12 09:09:52 -03:00
|
|
|
const float margin_cm = _fence.get_margin() * 100.0f;
|
2019-06-07 06:30:52 -03:00
|
|
|
|
2019-06-04 08:20:45 -03:00
|
|
|
// get vehicle distance from home
|
|
|
|
const float dist_from_home = position_xy.length();
|
2019-06-07 06:30:52 -03:00
|
|
|
if (dist_from_home > fence_radius) {
|
|
|
|
// outside of circular fence, no velocity adjustments
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// vehicle is inside the circular fence
|
|
|
|
if ((AC_Avoid::BehaviourType)_behavior.get() == BEHAVIOR_SLIDE) {
|
|
|
|
// implement sliding behaviour
|
|
|
|
const Vector2f stopping_point = position_xy + desired_vel_cms*(get_stopping_distance(kP, accel_cmss, desired_speed)/desired_speed);
|
|
|
|
const float stopping_point_dist_from_home = stopping_point.length();
|
|
|
|
if (stopping_point_dist_from_home <= fence_radius - margin_cm) {
|
|
|
|
// stopping before before fence so no need to adjust
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
// unsafe desired velocity - will not be able to stop before reaching margin from fence
|
|
|
|
// Project stopping point radially onto fence boundary
|
|
|
|
// Adjusted velocity will point towards this projected point at a safe speed
|
|
|
|
const Vector2f target_offset = stopping_point * ((fence_radius - margin_cm) / stopping_point_dist_from_home);
|
|
|
|
const Vector2f target_direction = target_offset - position_xy;
|
|
|
|
const float distance_to_target = target_direction.length();
|
|
|
|
const float max_speed = get_max_speed(kP, accel_cmss, distance_to_target, dt);
|
|
|
|
desired_vel_cms = target_direction * (MIN(desired_speed,max_speed) / distance_to_target);
|
|
|
|
} else {
|
|
|
|
// implement stopping behaviour
|
|
|
|
// calculate stopping point plus a margin so we look forward far enough to intersect with circular fence
|
|
|
|
const Vector2f stopping_point_plus_margin = position_xy + desired_vel_cms*((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, desired_speed))/desired_speed);
|
|
|
|
const float stopping_point_plus_margin_dist_from_home = stopping_point_plus_margin.length();
|
|
|
|
if (dist_from_home >= fence_radius - margin_cm) {
|
|
|
|
// if vehicle has already breached margin around fence
|
|
|
|
// if stopping point is even further from home (i.e. in wrong direction) then adjust speed to zero
|
|
|
|
// otherwise user is backing away from fence so do not apply limits
|
|
|
|
if (stopping_point_plus_margin_dist_from_home >= dist_from_home) {
|
|
|
|
desired_vel_cms.zero();
|
2019-06-04 08:20:45 -03:00
|
|
|
}
|
|
|
|
} else {
|
2019-06-07 06:30:52 -03:00
|
|
|
// shorten vector without adjusting its direction
|
|
|
|
Vector2f intersection;
|
|
|
|
if (Vector2f::circle_segment_intersection(position_xy, stopping_point_plus_margin, Vector2f(0.0f,0.0f), fence_radius - margin_cm, intersection)) {
|
|
|
|
const float distance_to_target = MAX((intersection - position_xy).length() - margin_cm, 0.0f);
|
|
|
|
const float max_speed = get_max_speed(kP, accel_cmss, distance_to_target, dt);
|
|
|
|
if (max_speed < desired_speed) {
|
|
|
|
desired_vel_cms *= MAX(max_speed, 0.0f) / desired_speed;
|
2017-12-12 08:19:37 -04:00
|
|
|
}
|
|
|
|
}
|
2016-06-19 22:12:17 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-06-22 23:45:01 -03:00
|
|
|
/*
|
|
|
|
* Adjusts the desired velocity for the polygon fence.
|
|
|
|
*/
|
2018-02-15 15:16:42 -04:00
|
|
|
void AC_Avoid::adjust_velocity_polygon_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt)
|
2016-06-22 23:45:01 -03:00
|
|
|
{
|
2019-05-22 03:03:57 -03:00
|
|
|
AC_Fence *fence = AP::fence();
|
|
|
|
if (fence == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
AC_Fence &_fence = *fence;
|
|
|
|
|
2016-06-22 23:45:01 -03:00
|
|
|
// exit if the polygon fence is not enabled
|
|
|
|
if ((_fence.get_enabled_fences() & AC_FENCE_TYPE_POLYGON) == 0) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// exit if the polygon fence has already been breached
|
|
|
|
if ((_fence.get_breaches() & AC_FENCE_TYPE_POLYGON) != 0) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// get polygon boundary
|
|
|
|
uint16_t num_points;
|
2019-05-23 22:33:59 -03:00
|
|
|
const Vector2f* boundary = _fence.get_boundary_points(num_points);
|
2016-06-22 23:45:01 -03:00
|
|
|
|
2016-11-08 00:57:31 -04:00
|
|
|
// adjust velocity using polygon
|
2018-02-15 15:16:42 -04:00
|
|
|
adjust_velocity_polygon(kP, accel_cmss, desired_vel_cms, boundary, num_points, true, _fence.get_margin(), dt);
|
2016-11-08 00:57:31 -04:00
|
|
|
}
|
|
|
|
|
2017-05-02 06:10:37 -03:00
|
|
|
/*
|
|
|
|
* Adjusts the desired velocity for the beacon fence.
|
|
|
|
*/
|
2018-02-15 15:16:42 -04:00
|
|
|
void AC_Avoid::adjust_velocity_beacon_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt)
|
2017-05-02 06:10:37 -03:00
|
|
|
{
|
2019-05-22 03:03:57 -03:00
|
|
|
AP_Beacon *_beacon = AP::beacon();
|
|
|
|
|
2017-05-02 06:10:37 -03:00
|
|
|
// exit if the beacon is not present
|
|
|
|
if (_beacon == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// get boundary from beacons
|
|
|
|
uint16_t num_points;
|
|
|
|
const Vector2f* boundary = _beacon->get_boundary_points(num_points);
|
|
|
|
if (boundary == nullptr || num_points == 0) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// adjust velocity using beacon
|
2019-05-22 03:03:57 -03:00
|
|
|
float margin = 0;
|
|
|
|
if (AP::fence()) {
|
|
|
|
margin = AP::fence()->get_margin();
|
|
|
|
}
|
|
|
|
adjust_velocity_polygon(kP, accel_cmss, desired_vel_cms, boundary, num_points, true, margin, dt);
|
2017-05-02 06:10:37 -03:00
|
|
|
}
|
|
|
|
|
2016-11-08 00:57:31 -04:00
|
|
|
/*
|
|
|
|
* Adjusts the desired velocity based on output from the proximity sensor
|
|
|
|
*/
|
2018-02-15 15:16:42 -04:00
|
|
|
void AC_Avoid::adjust_velocity_proximity(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt)
|
2016-11-08 00:57:31 -04:00
|
|
|
{
|
|
|
|
// exit immediately if proximity sensor is not present
|
2019-05-22 03:03:57 -03:00
|
|
|
AP_Proximity *proximity = AP::proximity();
|
|
|
|
if (!proximity) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
AP_Proximity &_proximity = *proximity;
|
|
|
|
|
2016-11-08 00:57:31 -04:00
|
|
|
if (_proximity.get_status() != AP_Proximity::Proximity_Good) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// get boundary from proximity sensor
|
|
|
|
uint16_t num_points;
|
|
|
|
const Vector2f *boundary = _proximity.get_boundary_points(num_points);
|
2018-02-15 15:16:42 -04:00
|
|
|
adjust_velocity_polygon(kP, accel_cmss, desired_vel_cms, boundary, num_points, false, _margin, dt);
|
2016-11-08 00:57:31 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
* Adjusts the desired velocity for the polygon fence.
|
|
|
|
*/
|
2018-02-15 15:16:42 -04:00
|
|
|
void AC_Avoid::adjust_velocity_polygon(float kP, float accel_cmss, Vector2f &desired_vel_cms, const Vector2f* boundary, uint16_t num_points, bool earth_frame, float margin, float dt)
|
2016-11-08 00:57:31 -04:00
|
|
|
{
|
2016-06-22 23:45:01 -03:00
|
|
|
// exit if there are no points
|
2016-10-30 02:24:21 -03:00
|
|
|
if (boundary == nullptr || num_points == 0) {
|
2016-06-22 23:45:01 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2019-05-29 03:42:18 -03:00
|
|
|
// exit immediately if no desired velocity
|
|
|
|
if (desired_vel_cms.is_zero()) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2019-05-22 03:03:57 -03:00
|
|
|
const AP_AHRS &_ahrs = AP::ahrs();
|
|
|
|
|
2016-06-22 23:45:01 -03:00
|
|
|
// do not adjust velocity if vehicle is outside the polygon fence
|
2017-08-08 06:55:07 -03:00
|
|
|
Vector2f position_xy;
|
2016-11-08 01:36:39 -04:00
|
|
|
if (earth_frame) {
|
2017-12-06 23:08:29 -04:00
|
|
|
if (!_ahrs.get_relative_position_NE_origin(position_xy)) {
|
|
|
|
// boundary is in earth frame but we have no idea
|
|
|
|
// where we are
|
|
|
|
return;
|
|
|
|
}
|
2017-08-08 06:55:07 -03:00
|
|
|
position_xy = position_xy * 100.0f; // m to cm
|
2016-11-08 01:36:39 -04:00
|
|
|
}
|
2017-08-08 06:55:07 -03:00
|
|
|
|
2019-05-22 04:20:22 -03:00
|
|
|
if (Polygon_outside(position_xy, boundary, num_points)) {
|
2016-06-22 23:45:01 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// Safe_vel will be adjusted to remain within fence.
|
|
|
|
// We need a separate vector in case adjustment fails,
|
|
|
|
// e.g. if we are exactly on the boundary.
|
2018-02-15 15:16:42 -04:00
|
|
|
Vector2f safe_vel(desired_vel_cms);
|
2016-06-22 23:45:01 -03:00
|
|
|
|
2016-11-08 01:36:39 -04:00
|
|
|
// if boundary points are in body-frame, rotate velocity vector from earth frame to body-frame
|
|
|
|
if (!earth_frame) {
|
2018-02-15 15:16:42 -04:00
|
|
|
safe_vel.x = desired_vel_cms.y * _ahrs.sin_yaw() + desired_vel_cms.x * _ahrs.cos_yaw(); // right
|
|
|
|
safe_vel.y = desired_vel_cms.y * _ahrs.cos_yaw() - desired_vel_cms.x * _ahrs.sin_yaw(); // forward
|
2016-11-08 01:36:39 -04:00
|
|
|
}
|
|
|
|
|
2017-04-12 09:09:52 -03:00
|
|
|
// calc margin in cm
|
2018-10-26 01:49:45 -03:00
|
|
|
const float margin_cm = MAX(margin * 100.0f, 0.0f);
|
2017-12-12 08:19:37 -04:00
|
|
|
|
|
|
|
// for stopping
|
2018-10-26 01:49:45 -03:00
|
|
|
const float speed = safe_vel.length();
|
|
|
|
const Vector2f stopping_point_plus_margin = position_xy + safe_vel*((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, speed))/speed);
|
2017-04-12 09:09:52 -03:00
|
|
|
|
2019-05-29 04:01:56 -03:00
|
|
|
for (uint16_t i=0; i<num_points; i++) {
|
|
|
|
uint16_t j = i+1;
|
|
|
|
if (j >= num_points) {
|
|
|
|
j = 0;
|
|
|
|
}
|
2016-06-22 23:45:01 -03:00
|
|
|
// end points of current edge
|
|
|
|
Vector2f start = boundary[j];
|
|
|
|
Vector2f end = boundary[i];
|
2017-12-12 08:19:37 -04:00
|
|
|
if ((AC_Avoid::BehaviourType)_behavior.get() == BEHAVIOR_SLIDE) {
|
|
|
|
// vector from current position to closest point on current edge
|
|
|
|
Vector2f limit_direction = Vector2f::closest_point(position_xy, start, end) - position_xy;
|
|
|
|
// distance to closest point
|
2018-02-15 15:16:42 -04:00
|
|
|
const float limit_distance_cm = limit_direction.length();
|
|
|
|
if (!is_zero(limit_distance_cm)) {
|
2017-12-12 08:19:37 -04:00
|
|
|
// We are strictly inside the given edge.
|
|
|
|
// Adjust velocity to not violate this edge.
|
2018-02-15 15:16:42 -04:00
|
|
|
limit_direction /= limit_distance_cm;
|
|
|
|
limit_velocity(kP, accel_cmss, safe_vel, limit_direction, MAX(limit_distance_cm - margin_cm, 0.0f), dt);
|
2017-12-12 08:19:37 -04:00
|
|
|
} else {
|
|
|
|
// We are exactly on the edge - treat this as a fence breach.
|
|
|
|
// i.e. do not adjust velocity.
|
|
|
|
return;
|
|
|
|
}
|
2016-06-22 23:45:01 -03:00
|
|
|
} else {
|
2017-12-12 08:19:37 -04:00
|
|
|
// find intersection with line segment
|
|
|
|
Vector2f intersection;
|
2018-10-24 03:31:36 -03:00
|
|
|
if (Vector2f::segment_intersection(position_xy, stopping_point_plus_margin, start, end, intersection)) {
|
2017-12-12 08:19:37 -04:00
|
|
|
// vector from current position to point on current edge
|
|
|
|
Vector2f limit_direction = intersection - position_xy;
|
2018-02-15 15:16:42 -04:00
|
|
|
const float limit_distance_cm = limit_direction.length();
|
|
|
|
if (!is_zero(limit_distance_cm)) {
|
|
|
|
if (limit_distance_cm <= margin_cm) {
|
2017-12-12 08:19:37 -04:00
|
|
|
// we are within the margin so stop vehicle
|
|
|
|
safe_vel.zero();
|
|
|
|
} else {
|
|
|
|
// vehicle inside the given edge, adjust velocity to not violate this edge
|
2018-02-15 15:16:42 -04:00
|
|
|
limit_direction /= limit_distance_cm;
|
|
|
|
limit_velocity(kP, accel_cmss, safe_vel, limit_direction, MAX(limit_distance_cm - margin_cm, 0.0f), dt);
|
2017-12-12 08:19:37 -04:00
|
|
|
}
|
|
|
|
} else {
|
|
|
|
// We are exactly on the edge - treat this as a fence breach.
|
|
|
|
// i.e. do not adjust velocity.
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
2016-06-22 23:45:01 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-11-08 01:36:39 -04:00
|
|
|
// set modified desired velocity vector
|
|
|
|
if (earth_frame) {
|
2018-02-15 15:16:42 -04:00
|
|
|
desired_vel_cms = safe_vel;
|
2016-11-08 01:36:39 -04:00
|
|
|
} else {
|
|
|
|
// if points were in body-frame, rotate resulting vector back to earth-frame
|
2018-02-15 15:16:42 -04:00
|
|
|
desired_vel_cms.x = safe_vel.x * _ahrs.cos_yaw() - safe_vel.y * _ahrs.sin_yaw();
|
|
|
|
desired_vel_cms.y = safe_vel.x * _ahrs.sin_yaw() + safe_vel.y * _ahrs.cos_yaw();
|
2016-11-08 01:36:39 -04:00
|
|
|
}
|
2016-06-22 23:45:01 -03:00
|
|
|
}
|
|
|
|
|
2016-06-19 22:12:17 -03:00
|
|
|
/*
|
|
|
|
* Computes distance required to stop, given current speed.
|
|
|
|
*
|
|
|
|
* Implementation copied from AC_PosControl.
|
|
|
|
*/
|
2017-12-13 21:42:17 -04:00
|
|
|
float AC_Avoid::get_stopping_distance(float kP, float accel_cmss, float speed_cms) const
|
2016-06-19 22:12:17 -03:00
|
|
|
{
|
|
|
|
// avoid divide by zero by using current position if the velocity is below 10cm/s, kP is very low or acceleration is zero
|
2017-12-13 21:42:17 -04:00
|
|
|
if (accel_cmss <= 0.0f || is_zero(speed_cms)) {
|
2016-06-19 22:12:17 -03:00
|
|
|
return 0.0f;
|
|
|
|
}
|
|
|
|
|
2017-12-13 21:42:17 -04:00
|
|
|
// handle linear deceleration
|
|
|
|
if (kP <= 0.0f) {
|
|
|
|
return 0.5f * sq(speed_cms) / accel_cmss;
|
|
|
|
}
|
|
|
|
|
2016-06-19 22:12:17 -03:00
|
|
|
// calculate distance within which we can stop
|
2016-10-03 08:44:30 -03:00
|
|
|
// accel_cmss/kP is the point at which velocity switches from linear to sqrt
|
2017-12-13 21:42:17 -04:00
|
|
|
if (speed_cms < accel_cmss/kP) {
|
|
|
|
return speed_cms/kP;
|
2016-06-19 22:12:17 -03:00
|
|
|
} else {
|
2016-10-03 08:44:30 -03:00
|
|
|
// accel_cmss/(2.0f*kP*kP) is the distance at which we switch from linear to sqrt response
|
2017-12-13 21:42:17 -04:00
|
|
|
return accel_cmss/(2.0f*kP*kP) + (speed_cms*speed_cms)/(2.0f*accel_cmss);
|
2016-06-19 22:12:17 -03:00
|
|
|
}
|
|
|
|
}
|
2016-12-16 23:42:40 -04:00
|
|
|
|
|
|
|
// convert distance (in meters) to a lean percentage (in 0~1 range) for use in manual flight modes
|
|
|
|
float AC_Avoid::distance_to_lean_pct(float dist_m)
|
|
|
|
{
|
|
|
|
// ignore objects beyond DIST_MAX
|
2016-12-19 19:51:26 -04:00
|
|
|
if (dist_m < 0.0f || dist_m >= _dist_max || _dist_max <= 0.0f) {
|
2016-12-16 23:42:40 -04:00
|
|
|
return 0.0f;
|
|
|
|
}
|
|
|
|
// inverted but linear response
|
|
|
|
return 1.0f - (dist_m / _dist_max);
|
|
|
|
}
|
|
|
|
|
|
|
|
// returns the maximum positive and negative roll and pitch percentages (in -1 ~ +1 range) based on the proximity sensor
|
|
|
|
void AC_Avoid::get_proximity_roll_pitch_pct(float &roll_positive, float &roll_negative, float &pitch_positive, float &pitch_negative)
|
|
|
|
{
|
2019-05-22 03:03:57 -03:00
|
|
|
AP_Proximity *proximity = AP::proximity();
|
|
|
|
if (proximity == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
AP_Proximity &_proximity = *proximity;
|
|
|
|
|
2016-12-16 23:42:40 -04:00
|
|
|
// exit immediately if proximity sensor is not present
|
|
|
|
if (_proximity.get_status() != AP_Proximity::Proximity_Good) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2018-10-26 01:49:45 -03:00
|
|
|
const uint8_t obj_count = _proximity.get_object_count();
|
2016-12-16 23:42:40 -04:00
|
|
|
|
|
|
|
// if no objects return
|
|
|
|
if (obj_count == 0) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// calculate maximum roll, pitch values from objects
|
|
|
|
for (uint8_t i=0; i<obj_count; i++) {
|
|
|
|
float ang_deg, dist_m;
|
|
|
|
if (_proximity.get_object_angle_and_distance(i, ang_deg, dist_m)) {
|
|
|
|
if (dist_m < _dist_max) {
|
|
|
|
// convert distance to lean angle (in 0 to 1 range)
|
2016-12-19 19:51:26 -04:00
|
|
|
const float lean_pct = distance_to_lean_pct(dist_m);
|
2016-12-16 23:42:40 -04:00
|
|
|
// convert angle to roll and pitch lean percentages
|
2016-12-19 19:51:26 -04:00
|
|
|
const float angle_rad = radians(ang_deg);
|
|
|
|
const float roll_pct = -sinf(angle_rad) * lean_pct;
|
|
|
|
const float pitch_pct = cosf(angle_rad) * lean_pct;
|
2016-12-16 23:42:40 -04:00
|
|
|
// update roll, pitch maximums
|
|
|
|
if (roll_pct > 0.0f) {
|
|
|
|
roll_positive = MAX(roll_positive, roll_pct);
|
2018-04-20 12:09:22 -03:00
|
|
|
} else if (roll_pct < 0.0f) {
|
2016-12-16 23:42:40 -04:00
|
|
|
roll_negative = MIN(roll_negative, roll_pct);
|
|
|
|
}
|
|
|
|
if (pitch_pct > 0.0f) {
|
|
|
|
pitch_positive = MAX(pitch_positive, pitch_pct);
|
2018-04-20 12:09:22 -03:00
|
|
|
} else if (pitch_pct < 0.0f) {
|
2016-12-16 23:42:40 -04:00
|
|
|
pitch_negative = MIN(pitch_negative, pitch_pct);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2018-10-25 23:31:20 -03:00
|
|
|
|
|
|
|
// singleton instance
|
|
|
|
AC_Avoid *AC_Avoid::_singleton;
|
|
|
|
|
|
|
|
namespace AP {
|
|
|
|
|
|
|
|
AC_Avoid *ac_avoid()
|
|
|
|
{
|
|
|
|
return AC_Avoid::get_singleton();
|
|
|
|
}
|
|
|
|
|
|
|
|
}
|