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