AC_Avoid.h 6.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144
  1. #pragma once
  2. #include <AP_Common/AP_Common.h>
  3. #include <AP_Param/AP_Param.h>
  4. #include <AP_Math/AP_Math.h>
  5. #include <AC_AttitudeControl/AC_AttitudeControl.h> // Attitude controller library for sqrt controller
  6. #define AC_AVOID_ACCEL_CMSS_MAX 100.0f // maximum acceleration/deceleration in cm/s/s used to avoid hitting fence
  7. // bit masks for enabled fence types.
  8. #define AC_AVOID_DISABLED 0 // avoidance disabled
  9. #define AC_AVOID_STOP_AT_FENCE 1 // stop at fence
  10. #define AC_AVOID_USE_PROXIMITY_SENSOR 2 // stop based on proximity sensor output
  11. #define AC_AVOID_STOP_AT_BEACON_FENCE 4 // stop based on beacon perimeter
  12. #define AC_AVOID_DEFAULT (AC_AVOID_STOP_AT_FENCE | AC_AVOID_USE_PROXIMITY_SENSOR)
  13. // definitions for non-GPS avoidance
  14. #define AC_AVOID_NONGPS_DIST_MAX_DEFAULT 5.0f // objects over 5m away are ignored (default value for DIST_MAX parameter)
  15. #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
  16. /*
  17. * This class prevents the vehicle from leaving a polygon fence in
  18. * 2 dimensions by limiting velocity (adjust_velocity).
  19. */
  20. class AC_Avoid {
  21. public:
  22. AC_Avoid();
  23. /* Do not allow copies */
  24. AC_Avoid(const AC_Avoid &other) = delete;
  25. AC_Avoid &operator=(const AC_Avoid&) = delete;
  26. // get singleton instance
  27. static AC_Avoid *get_singleton() {
  28. return _singleton;
  29. }
  30. /*
  31. * Adjusts the desired velocity so that the vehicle can stop
  32. * before the fence/object.
  33. * Note: Vector3f version is for convenience and only adjusts x and y axis
  34. */
  35. void adjust_velocity(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt);
  36. void adjust_velocity(float kP, float accel_cmss, Vector3f &desired_vel_cms, float dt);
  37. // adjust desired horizontal speed so that the vehicle stops before the fence or object
  38. // accel (maximum acceleration/deceleration) is in m/s/s
  39. // heading is in radians
  40. // speed is in m/s
  41. // kP should be zero for linear response, non-zero for non-linear response
  42. // dt is the time since the last call in seconds
  43. void adjust_speed(float kP, float accel, float heading, float &speed, float dt);
  44. // adjust vertical climb rate so vehicle does not break the vertical fence
  45. void adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float dt);
  46. // adjust roll-pitch to push vehicle away from objects
  47. // roll and pitch value are in centi-degrees
  48. // angle_max is the user defined maximum lean angle for the vehicle in centi-degrees
  49. void adjust_roll_pitch(float &roll, float &pitch, float angle_max);
  50. // enable/disable proximity based avoidance
  51. void proximity_avoidance_enable(bool on_off) { _proximity_enabled = on_off; }
  52. bool proximity_avoidance_enabled() { return _proximity_enabled; }
  53. // helper functions
  54. // Limits the component of desired_vel_cms in the direction of the unit vector
  55. // limit_direction to be at most the maximum speed permitted by the limit_distance_cm.
  56. // uses velocity adjustment idea from Randy's second email on this thread:
  57. // https://groups.google.com/forum/#!searchin/drones-discuss/obstacle/drones-discuss/QwUXz__WuqY/qo3G8iTLSJAJ
  58. void limit_velocity(float kP, float accel_cmss, Vector2f &desired_vel_cms, const Vector2f& limit_direction, float limit_distance_cm, float dt) const;
  59. // compute the speed such that the stopping distance of the vehicle will
  60. // be exactly the input distance.
  61. // kP should be non-zero for Copter which has a non-linear response
  62. float get_max_speed(float kP, float accel_cmss, float distance_cm, float dt) const;
  63. static const struct AP_Param::GroupInfo var_info[];
  64. private:
  65. // behaviour types (see BEHAVE parameter)
  66. enum BehaviourType {
  67. BEHAVIOR_SLIDE = 0,
  68. BEHAVIOR_STOP = 1
  69. };
  70. /*
  71. * Adjusts the desired velocity for the circular fence.
  72. */
  73. void adjust_velocity_circle_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt);
  74. /*
  75. * Adjusts the desired velocity for the polygon fence.
  76. */
  77. void adjust_velocity_polygon_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt);
  78. /*
  79. * Adjusts the desired velocity for the beacon fence.
  80. */
  81. void adjust_velocity_beacon_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt);
  82. /*
  83. * Adjusts the desired velocity based on output from the proximity sensor
  84. */
  85. void adjust_velocity_proximity(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt);
  86. /*
  87. * Adjusts the desired velocity given an array of boundary points
  88. * earth_frame should be true if boundary is in earth-frame, false for body-frame
  89. * margin is the distance (in meters) that the vehicle should stop short of the polygon
  90. */
  91. void 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);
  92. /*
  93. * Computes distance required to stop, given current speed.
  94. */
  95. float get_stopping_distance(float kP, float accel_cmss, float speed_cms) const;
  96. /*
  97. * methods for avoidance in non-GPS flight modes
  98. */
  99. // convert distance (in meters) to a lean percentage (in 0~1 range) for use in manual flight modes
  100. float distance_to_lean_pct(float dist_m);
  101. // returns the maximum positive and negative roll and pitch percentages (in -1 ~ +1 range) based on the proximity sensor
  102. void get_proximity_roll_pitch_pct(float &roll_positive, float &roll_negative, float &pitch_positive, float &pitch_negative);
  103. // parameters
  104. AP_Int8 _enabled;
  105. AP_Int16 _angle_max; // maximum lean angle to avoid obstacles (only used in non-GPS flight modes)
  106. AP_Float _dist_max; // distance (in meters) from object at which obstacle avoidance will begin in non-GPS modes
  107. AP_Float _margin; // vehicle will attempt to stay this distance (in meters) from objects while in GPS modes
  108. AP_Int8 _behavior; // avoidance behaviour (slide or stop)
  109. bool _proximity_enabled = true; // true if proximity sensor based avoidance is enabled (used to allow pilot to enable/disable)
  110. static AC_Avoid *_singleton;
  111. };
  112. namespace AP {
  113. AC_Avoid *ac_avoid();
  114. };