Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_Avoidance/AC_Avoid.h
4182 views
1
#pragma once
2
3
#include "AC_Avoidance_config.h"
4
5
#if AP_AVOIDANCE_ENABLED
6
7
#include <AP_Common/AP_Common.h>
8
#include <AP_Param/AP_Param.h>
9
#include <AP_Math/AP_Math.h>
10
#include <AC_AttitudeControl/AC_AttitudeControl.h> // Attitude controller library for sqrt controller
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
#define AC_AVOID_ACTIVE_LIMIT_TIMEOUT_MS 500 // if limiting is active if last limit is happened in the last x ms
26
#define AC_AVOID_ACCEL_TIMEOUT_MS 200 // stored velocity used to calculate acceleration will be reset if avoidance is active after this many ms
27
28
/*
29
* This class prevents the vehicle from leaving a polygon fence or hitting proximity-based obstacles
30
* Additionally the vehicle may back up if the margin to obstacle is breached
31
*/
32
class AC_Avoid {
33
public:
34
AC_Avoid();
35
36
/* Do not allow copies */
37
CLASS_NO_COPY(AC_Avoid);
38
39
// get singleton instance
40
static AC_Avoid *get_singleton() {
41
return _singleton;
42
}
43
44
// return true if any avoidance feature is enabled
45
bool enabled() const { return _enabled != AC_AVOID_DISABLED; }
46
47
// Adjusts the desired velocity so that the vehicle can stop
48
// before the fence/object.
49
// kP, accel_cmss are for the horizontal axis
50
// kP_z, accel_cmss_z are for vertical axis
51
void adjust_velocity(Vector3f &desired_vel_cms, bool &backing_up, float kP, float accel_cmss, float kP_z, float accel_cmss_z, float dt);
52
void adjust_velocity(Vector3f &desired_vel_cms, float kP, float accel_cmss, float kP_z, float accel_cmss_z, float dt) {
53
bool backing_up = false;
54
adjust_velocity(desired_vel_cms, backing_up, kP, accel_cmss, kP_z, accel_cmss_z, dt);
55
}
56
void adjust_velocity_m(Vector3f &desired_vel_ms, float kP, float accel_mss, float kP_z, float accel_mss_z, float dt) {
57
bool backing_up = false;
58
Vector3f desired_vel_cms = desired_vel_ms * 100.0;
59
adjust_velocity(desired_vel_cms, backing_up, kP, accel_mss * 100.0, kP_z, accel_mss_z * 100.0, dt);
60
desired_vel_ms = desired_vel_cms * 0.01;
61
}
62
63
// This method limits velocity and calculates backaway velocity from various supported fences
64
// Also limits vertical velocity using adjust_velocity_z method
65
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);
66
67
// adjust desired horizontal speed so that the vehicle stops before the fence or object
68
// accel (maximum acceleration/deceleration) is in m/s/s
69
// heading is in radians
70
// speed is in m/s
71
// kP should be zero for linear response, non-zero for non-linear response
72
// dt is the time since the last call in seconds
73
void adjust_speed(float kP, float accel, float heading, float &speed, float dt);
74
75
// adjust vertical climb rate so vehicle does not break the vertical fence
76
void adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float& backup_speed, float dt);
77
void adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float dt);
78
79
// adjust roll-pitch to push vehicle away from objects
80
// roll and pitch value are in radians
81
// veh_angle_max_rad is the user defined maximum lean angle for the vehicle in radians
82
void adjust_roll_pitch_rad(float &roll_rad, float &pitch_rad, float veh_angle_max_rad);
83
84
// enable/disable proximity based avoidance
85
void proximity_avoidance_enable(bool on_off) { _proximity_enabled = on_off; }
86
bool proximity_avoidance_enabled() const { return (_proximity_enabled && (_enabled & AC_AVOID_USE_PROXIMITY_SENSOR) > 0); }
87
void proximity_alt_avoidance_enable(bool on_off) { _proximity_alt_enabled = on_off; }
88
89
// helper functions
90
91
// Limits the component of desired_vel_cms in the direction of the unit vector
92
// limit_direction to be at most the maximum speed permitted by the limit_distance_cm.
93
// uses velocity adjustment idea from Randy's second email on this thread:
94
// https://groups.google.com/forum/#!searchin/drones-discuss/obstacle/drones-discuss/QwUXz__WuqY/qo3G8iTLSJAJ
95
void limit_velocity_2D(float kP, float accel_cmss, Vector2f &desired_vel_cms, const Vector2f& limit_direction, float limit_distance_cm, float dt);
96
97
// Note: This method is used to limit velocity horizontally and vertically given a 3D desired velocity vector
98
// Limits the component of desired_vel_cms in the direction of the obstacle_vector based on the passed value of "margin"
99
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);
100
101
// compute the speed such that the stopping distance of the vehicle will
102
// be exactly the input distance.
103
// kP should be non-zero for Copter which has a non-linear response
104
float get_max_speed(float kP, float accel_cmss, float distance_cm, float dt) const;
105
106
// return margin (in meters) that the vehicle should stay from objects
107
float get_margin() const { return _margin; }
108
109
// return minimum alt (in meters) above which avoidance will be active
110
float get_min_alt() const { return _alt_min; }
111
112
// return true if limiting is active
113
bool limits_active() const {return (AP_HAL::millis() - _last_limit_time) < AC_AVOID_ACTIVE_LIMIT_TIMEOUT_MS;};
114
115
static const struct AP_Param::GroupInfo var_info[];
116
117
private:
118
// behaviour types (see BEHAVE parameter)
119
enum BehaviourType {
120
BEHAVIOR_SLIDE = 0,
121
BEHAVIOR_STOP = 1
122
};
123
124
/*
125
* Limit acceleration so that change of velocity output by avoidance library is controlled
126
* This helps reduce jerks and sudden movements in the vehicle
127
*/
128
void limit_accel(const Vector3f &original_vel, Vector3f &modified_vel, float dt);
129
130
/*
131
* Adjusts the desired velocity for the circular fence.
132
*/
133
void adjust_velocity_circle_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt);
134
135
/*
136
* Adjusts the desired velocity for inclusion and exclusion polygon fences
137
*/
138
void adjust_velocity_inclusion_and_exclusion_polygons(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt);
139
140
/*
141
* Adjusts the desired velocity for the inclusion and exclusion circles
142
*/
143
void adjust_velocity_inclusion_circles(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt);
144
void adjust_velocity_exclusion_circles(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt);
145
146
/*
147
* Adjusts the desired velocity for the beacon fence.
148
*/
149
void adjust_velocity_beacon_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt);
150
151
/*
152
* Adjusts the desired velocity based on output from the proximity sensor
153
*/
154
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);
155
156
/*
157
* Adjusts the desired velocity given an array of boundary points
158
* The boundary must be in Earth Frame
159
* margin is the distance (in meters) that the vehicle should stop short of the polygon
160
* stay_inside should be true for fences, false for exclusion polygons
161
*/
162
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);
163
164
/*
165
* Computes distance required to stop, given current speed.
166
*/
167
float get_stopping_distance(float kP, float accel_cmss, float speed_cms) const;
168
169
/*
170
* Compute the back away velocity required to avoid breaching margin
171
* INPUT: This method requires the breach in margin distance (back_distance_cm), direction towards the breach (limit_direction)
172
* 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
173
* 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
174
*/
175
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);
176
177
/*
178
* Compute the back away velocity required to avoid breaching margin, including vertical component
179
* min_z_vel is <= 0, and stores the greatest velocity in the downwards direction
180
* max_z_vel is >= 0, and stores the greatest velocity in the upwards direction
181
* eventually max_z_vel + min_z_vel will give the final desired Z backaway velocity
182
*/
183
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);
184
185
/*
186
* Calculate maximum velocity vector that can be formed in each quadrant
187
* This method takes the desired backup velocity, and four other velocities corresponding to each quadrant
188
* The desired velocity is then fit into one of the 4 quadrant velocities as per the sign of its components
189
* This ensures that we have multiple backup velocities, we can get the maximum of all of those velocities in each quadrant
190
*/
191
void find_max_quadrant_velocity(Vector2f &desired_vel, Vector2f &quad1_vel, Vector2f &quad2_vel, Vector2f &quad3_vel, Vector2f &quad4_vel);
192
193
/*
194
* Calculate maximum velocity vector that can be formed in each quadrant and separately store max & min of vertical components
195
*/
196
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);
197
198
/*
199
* methods for avoidance in non-GPS flight modes
200
*/
201
202
// convert distance (in meters) to a lean percentage (in 0~1 range) for use in manual flight modes
203
float distance_to_lean_norm(float dist_m);
204
205
// returns the maximum positive and negative roll and pitch percentages (in -1 ~ +1 range) based on the proximity sensor
206
void get_proximity_roll_pitch_norm(float &roll_positive, float &roll_negative, float &pitch_positive, float &pitch_negative);
207
208
// Logging function
209
void Write_SimpleAvoidance(const uint8_t state, const Vector3f& desired_vel, const Vector3f& modified_vel, const bool back_up) const;
210
211
// parameters
212
AP_Int8 _enabled;
213
AP_Int16 _angle_max_cd; // maximum lean angle to avoid obstacles (only used in non-GPS flight modes)
214
AP_Float _dist_max; // distance (in meters) from object at which obstacle avoidance will begin in non-GPS modes
215
AP_Float _margin; // vehicle will attempt to stay this distance (in meters) from objects while in GPS modes
216
AP_Int8 _behavior; // avoidance behaviour (slide or stop)
217
AP_Float _backup_speed_xy_max; // Maximum speed that will be used to back away horizontally (in m/s)
218
AP_Float _backup_speed_z_max; // Maximum speed that will be used to back away verticality (in m/s)
219
AP_Float _alt_min; // alt below which Proximity based avoidance is turned off
220
AP_Float _accel_max; // maximum acceleration while simple avoidance is active
221
AP_Float _backup_deadzone; // distance beyond AVOID_MARGIN parameter, after which vehicle will backaway from obstacles
222
223
bool _proximity_enabled = true; // true if proximity sensor based avoidance is enabled (used to allow pilot to enable/disable)
224
bool _proximity_alt_enabled = true; // true if proximity sensor based avoidance is enabled based on altitude
225
uint32_t _last_limit_time; // the last time a limit was active
226
uint32_t _last_log_ms; // the last time simple avoidance was logged
227
Vector3f _prev_avoid_vel; // copy of avoidance adjusted velocity
228
229
static AC_Avoid *_singleton;
230
};
231
232
namespace AP {
233
AC_Avoid *ac_avoid();
234
};
235
236
#endif // AP_AVOIDANCE_ENABLED
237
238