2016-06-19 22:12:17 -03:00
|
|
|
#pragma once
|
|
|
|
|
2024-03-08 22:35:25 -04:00
|
|
|
#include "AC_Avoidance_config.h"
|
|
|
|
|
|
|
|
#if AP_AVOIDANCE_ENABLED
|
|
|
|
|
2016-06-19 22:12:17 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include <AC_AttitudeControl/AC_AttitudeControl.h> // Attitude controller library for sqrt controller
|
|
|
|
|
2016-06-20 05:40:20 -03:00
|
|
|
#define AC_AVOID_ACCEL_CMSS_MAX 100.0f // maximum acceleration/deceleration in cm/s/s used to avoid hitting fence
|
2016-06-19 22:12:17 -03:00
|
|
|
|
|
|
|
// bit masks for enabled fence types.
|
|
|
|
#define AC_AVOID_DISABLED 0 // avoidance disabled
|
|
|
|
#define AC_AVOID_STOP_AT_FENCE 1 // stop at fence
|
2016-08-15 08:59:35 -03:00
|
|
|
#define AC_AVOID_USE_PROXIMITY_SENSOR 2 // stop based on proximity sensor output
|
2017-05-02 06:10:37 -03:00
|
|
|
#define AC_AVOID_STOP_AT_BEACON_FENCE 4 // stop based on beacon perimeter
|
|
|
|
#define AC_AVOID_DEFAULT (AC_AVOID_STOP_AT_FENCE | AC_AVOID_USE_PROXIMITY_SENSOR)
|
2016-06-19 22:12:17 -03:00
|
|
|
|
2016-12-16 23:42:40 -04:00
|
|
|
// definitions for non-GPS avoidance
|
2018-01-24 22:16:01 -04:00
|
|
|
#define AC_AVOID_NONGPS_DIST_MAX_DEFAULT 5.0f // objects over 5m away are ignored (default value for DIST_MAX parameter)
|
2016-12-16 23:42:40 -04:00
|
|
|
#define AC_AVOID_ANGLE_MAX_PERCENT 0.75f // object avoidance max lean angle as a percentage (expressed in 0 ~ 1 range) of total vehicle max lean angle
|
|
|
|
|
2023-10-11 04:41:49 -03:00
|
|
|
#define AC_AVOID_ACTIVE_LIMIT_TIMEOUT_MS 500 // if limiting is active if last limit is happened in the last x ms
|
2021-02-11 08:05:52 -04:00
|
|
|
#define AC_AVOID_ACCEL_TIMEOUT_MS 200 // stored velocity used to calculate acceleration will be reset if avoidance is active after this many ms
|
2019-08-22 14:12:45 -03:00
|
|
|
|
2016-06-19 22:12:17 -03:00
|
|
|
/*
|
2021-01-10 14:12:52 -04:00
|
|
|
* This class prevents the vehicle from leaving a polygon fence or hitting proximity-based obstacles
|
2020-07-21 14:01:53 -03:00
|
|
|
* Additionally the vehicle may back up if the margin to obstacle is breached
|
2016-06-19 22:12:17 -03:00
|
|
|
*/
|
|
|
|
class AC_Avoid {
|
|
|
|
public:
|
2019-05-22 03:03:57 -03:00
|
|
|
AC_Avoid();
|
2017-08-29 20:36:07 -03:00
|
|
|
|
|
|
|
/* Do not allow copies */
|
2022-09-30 06:50:43 -03:00
|
|
|
CLASS_NO_COPY(AC_Avoid);
|
2016-06-19 22:12:17 -03:00
|
|
|
|
2018-10-25 23:31:20 -03:00
|
|
|
// get singleton instance
|
|
|
|
static AC_Avoid *get_singleton() {
|
|
|
|
return _singleton;
|
|
|
|
}
|
|
|
|
|
2019-09-19 23:07:26 -03:00
|
|
|
// return true if any avoidance feature is enabled
|
|
|
|
bool enabled() const { return _enabled != AC_AVOID_DISABLED; }
|
|
|
|
|
2020-12-06 08:45:16 -04:00
|
|
|
// Adjusts the desired velocity so that the vehicle can stop
|
|
|
|
// before the fence/object.
|
|
|
|
// kP, accel_cmss are for the horizontal axis
|
|
|
|
// kP_z, accel_cmss_z are for vertical axis
|
2021-01-10 14:12:52 -04:00
|
|
|
void adjust_velocity(Vector3f &desired_vel_cms, bool &backing_up, float kP, float accel_cmss, float kP_z, float accel_cmss_z, float dt);
|
|
|
|
void adjust_velocity(Vector3f &desired_vel_cms, float kP, float accel_cmss, float kP_z, float accel_cmss_z, float dt) {
|
2020-07-21 14:01:53 -03:00
|
|
|
bool backing_up = false;
|
2021-01-10 14:12:52 -04:00
|
|
|
adjust_velocity(desired_vel_cms, backing_up, kP, accel_cmss, kP_z, accel_cmss_z, dt);
|
2020-07-21 14:01:53 -03:00
|
|
|
}
|
2020-12-06 08:45:16 -04:00
|
|
|
|
|
|
|
// This method limits velocity and calculates backaway velocity from various supported fences
|
|
|
|
// Also limits vertical velocity using adjust_velocity_z method
|
|
|
|
void adjust_velocity_fence(float kP, float accel_cmss, Vector3f &desired_vel_cms, Vector3f &backup_vel, float kP_z, float accel_cmss_z, float dt);
|
2016-06-19 22:12:17 -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
|
|
|
|
// dt is the time since the last call in seconds
|
|
|
|
void adjust_speed(float kP, float accel, float heading, float &speed, float dt);
|
|
|
|
|
2017-01-05 02:21:55 -04:00
|
|
|
// adjust vertical climb rate so vehicle does not break the vertical fence
|
2020-12-06 08:45:16 -04:00
|
|
|
void adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float& backup_speed, float dt);
|
|
|
|
void adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float dt) {
|
|
|
|
float backup_speed = 0.0f;
|
|
|
|
adjust_velocity_z(kP, accel_cmss, climb_rate_cms, backup_speed, dt);
|
|
|
|
if (!is_zero(backup_speed)) {
|
|
|
|
climb_rate_cms = MIN(climb_rate_cms, backup_speed);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-01-05 02:21:55 -04:00
|
|
|
|
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
|
|
|
|
// angle_max is the user defined maximum lean angle for the vehicle in centi-degrees
|
|
|
|
void adjust_roll_pitch(float &roll, float &pitch, float angle_max);
|
|
|
|
|
|
|
|
// enable/disable proximity based avoidance
|
|
|
|
void proximity_avoidance_enable(bool on_off) { _proximity_enabled = on_off; }
|
2021-07-31 11:04:01 -03:00
|
|
|
bool proximity_avoidance_enabled() const { return (_proximity_enabled && (_enabled & AC_AVOID_USE_PROXIMITY_SENSOR) > 0); }
|
2021-02-09 13:57:23 -04:00
|
|
|
void proximity_alt_avoidance_enable(bool on_off) { _proximity_alt_enabled = on_off; }
|
2016-12-16 23:42:40 -04:00
|
|
|
|
2018-01-29 08:36:37 -04:00
|
|
|
// helper functions
|
|
|
|
|
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
|
2020-12-06 08:45:16 -04:00
|
|
|
void limit_velocity_2D(float kP, float accel_cmss, Vector2f &desired_vel_cms, const Vector2f& limit_direction, float limit_distance_cm, float dt);
|
|
|
|
|
|
|
|
// Note: This method is used to limit velocity horizontally and vertically given a 3D desired velocity vector
|
|
|
|
// Limits the component of desired_vel_cms in the direction of the obstacle_vector based on the passed value of "margin"
|
|
|
|
void limit_velocity_3D(float kP, float accel_cmss, Vector3f &desired_vel_cms, const Vector3f& limit_direction, float limit_distance_cm, float kP_z, float accel_cmss_z ,float dt);
|
|
|
|
|
2018-01-29 08:36:37 -04:00
|
|
|
// compute the speed such that the stopping distance of the vehicle will
|
|
|
|
// be exactly the input distance.
|
|
|
|
// kP should be non-zero for Copter which has a non-linear response
|
|
|
|
float get_max_speed(float kP, float accel_cmss, float distance_cm, float dt) const;
|
|
|
|
|
2019-09-19 23:07:26 -03:00
|
|
|
// return margin (in meters) that the vehicle should stay from objects
|
|
|
|
float get_margin() const { return _margin; }
|
|
|
|
|
2021-02-09 13:57:23 -04:00
|
|
|
// return minimum alt (in meters) above which avoidance will be active
|
|
|
|
float get_min_alt() const { return _alt_min; }
|
2021-02-09 13:57:55 -04:00
|
|
|
|
2019-08-22 14:12:45 -03:00
|
|
|
// return true if limiting is active
|
|
|
|
bool limits_active() const {return (AP_HAL::millis() - _last_limit_time) < AC_AVOID_ACTIVE_LIMIT_TIMEOUT_MS;};
|
|
|
|
|
2016-06-19 22:12:17 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
|
|
|
private:
|
2017-12-12 08:19:37 -04:00
|
|
|
// behaviour types (see BEHAVE parameter)
|
|
|
|
enum BehaviourType {
|
|
|
|
BEHAVIOR_SLIDE = 0,
|
|
|
|
BEHAVIOR_STOP = 1
|
|
|
|
};
|
|
|
|
|
2021-02-09 13:57:55 -04:00
|
|
|
/*
|
|
|
|
* Limit acceleration so that change of velocity output by avoidance library is controlled
|
2021-02-11 08:05:52 -04:00
|
|
|
* This helps reduce jerks and sudden movements in the vehicle
|
2021-02-09 13:57:55 -04:00
|
|
|
*/
|
|
|
|
void limit_accel(const Vector3f &original_vel, Vector3f &modified_vel, float dt);
|
|
|
|
|
2016-06-19 22:12:17 -03:00
|
|
|
/*
|
|
|
|
* Adjusts the desired velocity for the circular fence.
|
|
|
|
*/
|
2020-07-21 14:01:53 -03:00
|
|
|
void adjust_velocity_circle_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt);
|
2016-06-19 22:12:17 -03:00
|
|
|
|
2016-06-22 23:45:01 -03:00
|
|
|
/*
|
2019-07-15 01:11:25 -03:00
|
|
|
* Adjusts the desired velocity for inclusion and exclusion polygon fences
|
2016-06-22 23:45:01 -03:00
|
|
|
*/
|
2020-07-21 14:01:53 -03:00
|
|
|
void adjust_velocity_inclusion_and_exclusion_polygons(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt);
|
2019-07-15 01:11:25 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
* Adjusts the desired velocity for the inclusion and exclusion circles
|
|
|
|
*/
|
2020-07-21 14:01:53 -03:00
|
|
|
void adjust_velocity_inclusion_circles(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt);
|
|
|
|
void adjust_velocity_exclusion_circles(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt);
|
2016-06-22 23:45:01 -03:00
|
|
|
|
2017-05-02 06:10:37 -03:00
|
|
|
/*
|
|
|
|
* Adjusts the desired velocity for the beacon fence.
|
|
|
|
*/
|
2020-07-21 14:01:53 -03:00
|
|
|
void adjust_velocity_beacon_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt);
|
2017-05-02 06:10:37 -03:00
|
|
|
|
2016-08-15 08:59:35 -03:00
|
|
|
/*
|
|
|
|
* Adjusts the desired velocity based on output from the proximity sensor
|
|
|
|
*/
|
2020-12-06 08:45:16 -04:00
|
|
|
void adjust_velocity_proximity(float kP, float accel_cmss, Vector3f &desired_vel_cms, Vector3f &backup_vel, float kP_z, float accel_cmss_z, float dt);
|
2016-06-22 23:45:01 -03:00
|
|
|
|
2016-11-08 00:57:31 -04:00
|
|
|
/*
|
|
|
|
* Adjusts the desired velocity given an array of boundary points
|
2021-01-10 14:12:52 -04:00
|
|
|
* The boundary must be in Earth Frame
|
2020-12-06 08:45:16 -04:00
|
|
|
* margin is the distance (in meters) that the vehicle should stop short of the polygon
|
|
|
|
* stay_inside should be true for fences, false for exclusion polygons
|
2016-11-08 00:57:31 -04:00
|
|
|
*/
|
2020-12-06 08:45:16 -04:00
|
|
|
void adjust_velocity_polygon(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, const Vector2f* boundary, uint16_t num_points, float margin, float dt, bool stay_inside);
|
2016-11-08 00:57:31 -04:00
|
|
|
|
2016-06-19 22:12:17 -03:00
|
|
|
/*
|
|
|
|
* Computes distance required to stop, given current speed.
|
|
|
|
*/
|
2017-12-13 21:42:17 -04:00
|
|
|
float get_stopping_distance(float kP, float accel_cmss, float speed_cms) const;
|
2016-06-19 22:12:17 -03:00
|
|
|
|
2020-07-21 14:01:53 -03:00
|
|
|
/*
|
|
|
|
* Compute the back away velocity required to avoid breaching margin
|
|
|
|
* INPUT: This method requires the breach in margin distance (back_distance_cm), direction towards the breach (limit_direction)
|
|
|
|
* It then calculates the desired backup velocity and passes it on to "find_max_quadrant_velocity" method to distribute the velocity vector into respective quadrants
|
|
|
|
* OUTPUT: The method then outputs four velocities (quad1/2/3/4_back_vel_cms), which correspond to the final desired backup velocity in each quadrant
|
|
|
|
*/
|
2020-12-06 08:45:16 -04:00
|
|
|
void calc_backup_velocity_2D(float kP, float accel_cmss, Vector2f &quad1_back_vel_cms, Vector2f &qua2_back_vel_cms, Vector2f &quad3_back_vel_cms, Vector2f &quad4_back_vel_cms, float back_distance_cm, Vector2f limit_direction, float dt);
|
|
|
|
|
|
|
|
/*
|
|
|
|
* Compute the back away velocity required to avoid breaching margin, including vertical component
|
2021-01-10 14:12:52 -04:00
|
|
|
* min_z_vel is <= 0, and stores the greatest velocity in the downwards direction
|
2020-12-06 08:45:16 -04:00
|
|
|
* max_z_vel is >= 0, and stores the greatest velocity in the upwards direction
|
|
|
|
* eventually max_z_vel + min_z_vel will give the final desired Z backaway velocity
|
|
|
|
*/
|
2021-01-10 14:12:52 -04:00
|
|
|
void calc_backup_velocity_3D(float kP, float accel_cmss, Vector2f &quad1_back_vel_cms, Vector2f &quad2_back_vel_cms, Vector2f &quad3_back_vel_cms, Vector2f &quad4_back_vel_cms, float back_distance_cms, Vector3f limit_direction, float kp_z, float accel_cmss_z, float back_distance_z, float& min_z_vel, float& max_z_vel, float dt);
|
2020-12-06 08:45:16 -04:00
|
|
|
|
2020-07-21 14:01:53 -03:00
|
|
|
/*
|
|
|
|
* Calculate maximum velocity vector that can be formed in each quadrant
|
|
|
|
* This method takes the desired backup velocity, and four other velocities corresponding to each quadrant
|
|
|
|
* The desired velocity is then fit into one of the 4 quadrant velocities as per the sign of its components
|
|
|
|
* This ensures that we have multiple backup velocities, we can get the maximum of all of those velocities in each quadrant
|
|
|
|
*/
|
|
|
|
void find_max_quadrant_velocity(Vector2f &desired_vel, Vector2f &quad1_vel, Vector2f &quad2_vel, Vector2f &quad3_vel, Vector2f &quad4_vel);
|
|
|
|
|
2020-12-06 08:45:16 -04:00
|
|
|
/*
|
|
|
|
* Calculate maximum velocity vector that can be formed in each quadrant and separately store max & min of vertical components
|
|
|
|
*/
|
|
|
|
void find_max_quadrant_velocity_3D(Vector3f &desired_vel, Vector2f &quad1_vel, Vector2f &quad2_vel, Vector2f &quad3_vel, Vector2f &quad4_vel, float &max_z_vel, float &min_z_vel);
|
|
|
|
|
2016-12-16 23:42:40 -04:00
|
|
|
/*
|
|
|
|
* methods for avoidance in non-GPS flight modes
|
|
|
|
*/
|
|
|
|
|
|
|
|
// convert distance (in meters) to a lean percentage (in 0~1 range) for use in manual flight modes
|
|
|
|
float distance_to_lean_pct(float dist_m);
|
|
|
|
|
|
|
|
// returns the maximum positive and negative roll and pitch percentages (in -1 ~ +1 range) based on the proximity sensor
|
|
|
|
void get_proximity_roll_pitch_pct(float &roll_positive, float &roll_negative, float &pitch_positive, float &pitch_negative);
|
|
|
|
|
2021-01-22 03:23:53 -04:00
|
|
|
// Logging function
|
2021-05-09 14:47:47 -03:00
|
|
|
void Write_SimpleAvoidance(const uint8_t state, const Vector3f& desired_vel, const Vector3f& modified_vel, const bool back_up) const;
|
2021-01-22 03:23:53 -04:00
|
|
|
|
2016-06-19 22:12:17 -03:00
|
|
|
// parameters
|
|
|
|
AP_Int8 _enabled;
|
2016-12-16 23:42:40 -04:00
|
|
|
AP_Int16 _angle_max; // maximum lean angle to avoid obstacles (only used in non-GPS flight modes)
|
|
|
|
AP_Float _dist_max; // distance (in meters) from object at which obstacle avoidance will begin in non-GPS modes
|
2017-04-12 09:09:52 -03:00
|
|
|
AP_Float _margin; // vehicle will attempt to stay this distance (in meters) from objects while in GPS modes
|
2017-12-12 08:19:37 -04:00
|
|
|
AP_Int8 _behavior; // avoidance behaviour (slide or stop)
|
2020-07-21 14:01:53 -03:00
|
|
|
AP_Float _backup_speed_max; // Maximum speed that will be used to back away (in m/s)
|
2021-02-09 13:57:23 -04:00
|
|
|
AP_Float _alt_min; // alt below which Proximity based avoidance is turned off
|
2023-10-11 04:41:49 -03:00
|
|
|
AP_Float _accel_max; // maximum acceleration while simple avoidance is active
|
2021-06-02 15:56:39 -03:00
|
|
|
AP_Float _backup_deadzone; // distance beyond AVOID_MARGIN parameter, after which vehicle will backaway from obstacles
|
2016-12-16 23:42:40 -04:00
|
|
|
|
|
|
|
bool _proximity_enabled = true; // true if proximity sensor based avoidance is enabled (used to allow pilot to enable/disable)
|
2021-02-09 13:57:23 -04:00
|
|
|
bool _proximity_alt_enabled = true; // true if proximity sensor based avoidance is enabled based on altitude
|
2019-08-22 14:12:45 -03:00
|
|
|
uint32_t _last_limit_time; // the last time a limit was active
|
2020-07-21 14:01:53 -03:00
|
|
|
uint32_t _last_log_ms; // the last time simple avoidance was logged
|
2021-02-11 08:05:52 -04:00
|
|
|
Vector3f _prev_avoid_vel; // copy of avoidance adjusted velocity
|
2018-10-25 23:31:20 -03:00
|
|
|
|
|
|
|
static AC_Avoid *_singleton;
|
|
|
|
};
|
|
|
|
|
|
|
|
namespace AP {
|
|
|
|
AC_Avoid *ac_avoid();
|
2016-06-19 22:12:17 -03:00
|
|
|
};
|
2024-03-08 22:35:25 -04:00
|
|
|
|
|
|
|
#endif // AP_AVOIDANCE_ENABLED
|