Path: blob/master/libraries/AC_Avoidance/AC_Avoid.h
4182 views
#pragma once12#include "AC_Avoidance_config.h"34#if AP_AVOIDANCE_ENABLED56#include <AP_Common/AP_Common.h>7#include <AP_Param/AP_Param.h>8#include <AP_Math/AP_Math.h>9#include <AC_AttitudeControl/AC_AttitudeControl.h> // Attitude controller library for sqrt controller1011#define AC_AVOID_ACCEL_CMSS_MAX 100.0f // maximum acceleration/deceleration in cm/s/s used to avoid hitting fence1213// bit masks for enabled fence types.14#define AC_AVOID_DISABLED 0 // avoidance disabled15#define AC_AVOID_STOP_AT_FENCE 1 // stop at fence16#define AC_AVOID_USE_PROXIMITY_SENSOR 2 // stop based on proximity sensor output17#define AC_AVOID_STOP_AT_BEACON_FENCE 4 // stop based on beacon perimeter18#define AC_AVOID_DEFAULT (AC_AVOID_STOP_AT_FENCE | AC_AVOID_USE_PROXIMITY_SENSOR)1920// definitions for non-GPS avoidance21#define AC_AVOID_NONGPS_DIST_MAX_DEFAULT 5.0f // objects over 5m away are ignored (default value for DIST_MAX parameter)22#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 angle2324#define AC_AVOID_ACTIVE_LIMIT_TIMEOUT_MS 500 // if limiting is active if last limit is happened in the last x ms25#define AC_AVOID_ACCEL_TIMEOUT_MS 200 // stored velocity used to calculate acceleration will be reset if avoidance is active after this many ms2627/*28* This class prevents the vehicle from leaving a polygon fence or hitting proximity-based obstacles29* Additionally the vehicle may back up if the margin to obstacle is breached30*/31class AC_Avoid {32public:33AC_Avoid();3435/* Do not allow copies */36CLASS_NO_COPY(AC_Avoid);3738// get singleton instance39static AC_Avoid *get_singleton() {40return _singleton;41}4243// return true if any avoidance feature is enabled44bool enabled() const { return _enabled != AC_AVOID_DISABLED; }4546// Adjusts the desired velocity so that the vehicle can stop47// before the fence/object.48// kP, accel_cmss are for the horizontal axis49// kP_z, accel_cmss_z are for vertical axis50void adjust_velocity(Vector3f &desired_vel_cms, bool &backing_up, float kP, float accel_cmss, float kP_z, float accel_cmss_z, float dt);51void adjust_velocity(Vector3f &desired_vel_cms, float kP, float accel_cmss, float kP_z, float accel_cmss_z, float dt) {52bool backing_up = false;53adjust_velocity(desired_vel_cms, backing_up, kP, accel_cmss, kP_z, accel_cmss_z, dt);54}55void adjust_velocity_m(Vector3f &desired_vel_ms, float kP, float accel_mss, float kP_z, float accel_mss_z, float dt) {56bool backing_up = false;57Vector3f desired_vel_cms = desired_vel_ms * 100.0;58adjust_velocity(desired_vel_cms, backing_up, kP, accel_mss * 100.0, kP_z, accel_mss_z * 100.0, dt);59desired_vel_ms = desired_vel_cms * 0.01;60}6162// This method limits velocity and calculates backaway velocity from various supported fences63// Also limits vertical velocity using adjust_velocity_z method64void adjust_velocity_fence(float kP, float accel_cmss, Vector3f &desired_vel_cms, Vector3f &backup_vel, float kP_z, float accel_cmss_z, float dt);6566// adjust desired horizontal speed so that the vehicle stops before the fence or object67// accel (maximum acceleration/deceleration) is in m/s/s68// heading is in radians69// speed is in m/s70// kP should be zero for linear response, non-zero for non-linear response71// dt is the time since the last call in seconds72void adjust_speed(float kP, float accel, float heading, float &speed, float dt);7374// adjust vertical climb rate so vehicle does not break the vertical fence75void adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float& backup_speed, float dt);76void adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float dt);7778// adjust roll-pitch to push vehicle away from objects79// roll and pitch value are in radians80// veh_angle_max_rad is the user defined maximum lean angle for the vehicle in radians81void adjust_roll_pitch_rad(float &roll_rad, float &pitch_rad, float veh_angle_max_rad);8283// enable/disable proximity based avoidance84void proximity_avoidance_enable(bool on_off) { _proximity_enabled = on_off; }85bool proximity_avoidance_enabled() const { return (_proximity_enabled && (_enabled & AC_AVOID_USE_PROXIMITY_SENSOR) > 0); }86void proximity_alt_avoidance_enable(bool on_off) { _proximity_alt_enabled = on_off; }8788// helper functions8990// Limits the component of desired_vel_cms in the direction of the unit vector91// limit_direction to be at most the maximum speed permitted by the limit_distance_cm.92// uses velocity adjustment idea from Randy's second email on this thread:93// https://groups.google.com/forum/#!searchin/drones-discuss/obstacle/drones-discuss/QwUXz__WuqY/qo3G8iTLSJAJ94void limit_velocity_2D(float kP, float accel_cmss, Vector2f &desired_vel_cms, const Vector2f& limit_direction, float limit_distance_cm, float dt);9596// Note: This method is used to limit velocity horizontally and vertically given a 3D desired velocity vector97// Limits the component of desired_vel_cms in the direction of the obstacle_vector based on the passed value of "margin"98void 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);99100// compute the speed such that the stopping distance of the vehicle will101// be exactly the input distance.102// kP should be non-zero for Copter which has a non-linear response103float get_max_speed(float kP, float accel_cmss, float distance_cm, float dt) const;104105// return margin (in meters) that the vehicle should stay from objects106float get_margin() const { return _margin; }107108// return minimum alt (in meters) above which avoidance will be active109float get_min_alt() const { return _alt_min; }110111// return true if limiting is active112bool limits_active() const {return (AP_HAL::millis() - _last_limit_time) < AC_AVOID_ACTIVE_LIMIT_TIMEOUT_MS;};113114static const struct AP_Param::GroupInfo var_info[];115116private:117// behaviour types (see BEHAVE parameter)118enum BehaviourType {119BEHAVIOR_SLIDE = 0,120BEHAVIOR_STOP = 1121};122123/*124* Limit acceleration so that change of velocity output by avoidance library is controlled125* This helps reduce jerks and sudden movements in the vehicle126*/127void limit_accel(const Vector3f &original_vel, Vector3f &modified_vel, float dt);128129/*130* Adjusts the desired velocity for the circular fence.131*/132void adjust_velocity_circle_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt);133134/*135* Adjusts the desired velocity for inclusion and exclusion polygon fences136*/137void adjust_velocity_inclusion_and_exclusion_polygons(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt);138139/*140* Adjusts the desired velocity for the inclusion and exclusion circles141*/142void adjust_velocity_inclusion_circles(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt);143void adjust_velocity_exclusion_circles(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt);144145/*146* Adjusts the desired velocity for the beacon fence.147*/148void adjust_velocity_beacon_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt);149150/*151* Adjusts the desired velocity based on output from the proximity sensor152*/153void adjust_velocity_proximity(float kP, float accel_cmss, Vector3f &desired_vel_cms, Vector3f &backup_vel, float kP_z, float accel_cmss_z, float dt);154155/*156* Adjusts the desired velocity given an array of boundary points157* The boundary must be in Earth Frame158* margin is the distance (in meters) that the vehicle should stop short of the polygon159* stay_inside should be true for fences, false for exclusion polygons160*/161void 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);162163/*164* Computes distance required to stop, given current speed.165*/166float get_stopping_distance(float kP, float accel_cmss, float speed_cms) const;167168/*169* Compute the back away velocity required to avoid breaching margin170* INPUT: This method requires the breach in margin distance (back_distance_cm), direction towards the breach (limit_direction)171* It then calculates the desired backup velocity and passes it on to "find_max_quadrant_velocity" method to distribute the velocity vector into respective quadrants172* OUTPUT: The method then outputs four velocities (quad1/2/3/4_back_vel_cms), which correspond to the final desired backup velocity in each quadrant173*/174void 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);175176/*177* Compute the back away velocity required to avoid breaching margin, including vertical component178* min_z_vel is <= 0, and stores the greatest velocity in the downwards direction179* max_z_vel is >= 0, and stores the greatest velocity in the upwards direction180* eventually max_z_vel + min_z_vel will give the final desired Z backaway velocity181*/182void 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);183184/*185* Calculate maximum velocity vector that can be formed in each quadrant186* This method takes the desired backup velocity, and four other velocities corresponding to each quadrant187* The desired velocity is then fit into one of the 4 quadrant velocities as per the sign of its components188* This ensures that we have multiple backup velocities, we can get the maximum of all of those velocities in each quadrant189*/190void find_max_quadrant_velocity(Vector2f &desired_vel, Vector2f &quad1_vel, Vector2f &quad2_vel, Vector2f &quad3_vel, Vector2f &quad4_vel);191192/*193* Calculate maximum velocity vector that can be formed in each quadrant and separately store max & min of vertical components194*/195void 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);196197/*198* methods for avoidance in non-GPS flight modes199*/200201// convert distance (in meters) to a lean percentage (in 0~1 range) for use in manual flight modes202float distance_to_lean_norm(float dist_m);203204// returns the maximum positive and negative roll and pitch percentages (in -1 ~ +1 range) based on the proximity sensor205void get_proximity_roll_pitch_norm(float &roll_positive, float &roll_negative, float &pitch_positive, float &pitch_negative);206207// Logging function208void Write_SimpleAvoidance(const uint8_t state, const Vector3f& desired_vel, const Vector3f& modified_vel, const bool back_up) const;209210// parameters211AP_Int8 _enabled;212AP_Int16 _angle_max_cd; // maximum lean angle to avoid obstacles (only used in non-GPS flight modes)213AP_Float _dist_max; // distance (in meters) from object at which obstacle avoidance will begin in non-GPS modes214AP_Float _margin; // vehicle will attempt to stay this distance (in meters) from objects while in GPS modes215AP_Int8 _behavior; // avoidance behaviour (slide or stop)216AP_Float _backup_speed_xy_max; // Maximum speed that will be used to back away horizontally (in m/s)217AP_Float _backup_speed_z_max; // Maximum speed that will be used to back away verticality (in m/s)218AP_Float _alt_min; // alt below which Proximity based avoidance is turned off219AP_Float _accel_max; // maximum acceleration while simple avoidance is active220AP_Float _backup_deadzone; // distance beyond AVOID_MARGIN parameter, after which vehicle will backaway from obstacles221222bool _proximity_enabled = true; // true if proximity sensor based avoidance is enabled (used to allow pilot to enable/disable)223bool _proximity_alt_enabled = true; // true if proximity sensor based avoidance is enabled based on altitude224uint32_t _last_limit_time; // the last time a limit was active225uint32_t _last_log_ms; // the last time simple avoidance was logged226Vector3f _prev_avoid_vel; // copy of avoidance adjusted velocity227228static AC_Avoid *_singleton;229};230231namespace AP {232AC_Avoid *ac_avoid();233};234235#endif // AP_AVOIDANCE_ENABLED236237238