APM:Libraries
AC_Avoid.cpp
Go to the documentation of this file.
1 #include "AC_Avoid.h"
2 
3 #if APM_BUILD_TYPE(APM_BUILD_APMrover2)
4  # define AP_AVOID_BEHAVE_DEFAULT AC_Avoid::BehaviourType::BEHAVIOR_STOP
5 #else
6  # define AP_AVOID_BEHAVE_DEFAULT AC_Avoid::BehaviourType::BEHAVIOR_SLIDE
7 #endif
8 
10 
11  // @Param: ENABLE
12  // @DisplayName: Avoidance control enable/disable
13  // @Description: Enabled/disable stopping at fence
14  // @Values: 0:None,1:StopAtFence,2:UseProximitySensor,3:StopAtFence and UseProximitySensor,4:StopAtBeaconFence,7:All
15  // @Bitmask: 0:StopAtFence,1:UseProximitySensor,2:StopAtBeaconFence
16  // @User: Standard
17  AP_GROUPINFO("ENABLE", 1, AC_Avoid, _enabled, AC_AVOID_DEFAULT),
18 
19  // @Param: ANGLE_MAX
20  // @DisplayName: Avoidance max lean angle in non-GPS flight modes
21  // @Description: Max lean angle used to avoid obstacles while in non-GPS modes
22  // @Units: cdeg
23  // @Range: 0 4500
24  // @User: Standard
25  AP_GROUPINFO("ANGLE_MAX", 2, AC_Avoid, _angle_max, 1000),
26 
27  // @Param: DIST_MAX
28  // @DisplayName: Avoidance distance maximum in non-GPS flight modes
29  // @Description: Distance from object at which obstacle avoidance will begin in non-GPS modes
30  // @Units: m
31  // @Range: 1 30
32  // @User: Standard
33  AP_GROUPINFO("DIST_MAX", 3, AC_Avoid, _dist_max, AC_AVOID_NONGPS_DIST_MAX_DEFAULT),
34 
35  // @Param: MARGIN
36  // @DisplayName: Avoidance distance margin in GPS modes
37  // @Description: Vehicle will attempt to stay at least this distance (in meters) from objects while in GPS modes
38  // @Units: m
39  // @Range: 1 10
40  // @User: Standard
41  AP_GROUPINFO("MARGIN", 4, AC_Avoid, _margin, 2.0f),
42 
43  // @Param: BEHAVE
44  // @DisplayName: Avoidance behaviour
45  // @Description: Avoidance behaviour (slide or stop)
46  // @Values: 0:Slide,1:Stop
47  // @User: Standard
48  AP_GROUPINFO("BEHAVE", 5, AC_Avoid, _behavior, AP_AVOID_BEHAVE_DEFAULT),
49 
51 };
52 
54 AC_Avoid::AC_Avoid(const AP_AHRS& ahrs, const AC_Fence& fence, const AP_Proximity& proximity, const AP_Beacon* beacon)
55  : _ahrs(ahrs),
56  _fence(fence),
57  _proximity(proximity),
58  _beacon(beacon)
59 {
61 }
62 
63 void AC_Avoid::adjust_velocity(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt)
64 {
65  // exit immediately if disabled
66  if (_enabled == AC_AVOID_DISABLED) {
67  return;
68  }
69 
70  // limit acceleration
71  float accel_cmss_limited = MIN(accel_cmss, AC_AVOID_ACCEL_CMSS_MAX);
72 
73  if ((_enabled & AC_AVOID_STOP_AT_FENCE) > 0) {
74  adjust_velocity_circle_fence(kP, accel_cmss_limited, desired_vel_cms, dt);
75  adjust_velocity_polygon_fence(kP, accel_cmss_limited, desired_vel_cms, dt);
76  }
77 
79  adjust_velocity_beacon_fence(kP, accel_cmss_limited, desired_vel_cms, dt);
80  }
81 
83  adjust_velocity_proximity(kP, accel_cmss_limited, desired_vel_cms, dt);
84  }
85 }
86 
87 // convenience function to accept Vector3f. Only x and y are adjusted
88 void AC_Avoid::adjust_velocity(float kP, float accel_cmss, Vector3f &desired_vel_cms, float dt)
89 {
90  Vector2f des_vel_xy(desired_vel_cms.x, desired_vel_cms.y);
91  adjust_velocity(kP, accel_cmss, des_vel_xy, dt);
92  desired_vel_cms.x = des_vel_xy.x;
93  desired_vel_cms.y = des_vel_xy.y;
94 }
95 
96 // adjust desired horizontal speed so that the vehicle stops before the fence or object
97 // accel (maximum acceleration/deceleration) is in m/s/s
98 // heading is in radians
99 // speed is in m/s
100 // kP should be zero for linear response, non-zero for non-linear response
101 void AC_Avoid::adjust_speed(float kP, float accel, float heading, float &speed, float dt)
102 {
103  // convert heading and speed into velocity vector
104  Vector2f vel_xy;
105  vel_xy.x = cosf(heading) * speed * 100.0f;
106  vel_xy.y = sinf(heading) * speed * 100.0f;
107  adjust_velocity(kP, accel * 100.0f, vel_xy, dt);
108 
109  // adjust speed towards zero
110  if (is_negative(speed)) {
111  speed = -vel_xy.length() * 0.01f;
112  } else {
113  speed = vel_xy.length() * 0.01f;
114  }
115 }
116 
117 // adjust vertical climb rate so vehicle does not break the vertical fence
118 void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float dt)
119 {
120  // exit immediately if disabled
121  if (_enabled == AC_AVOID_DISABLED) {
122  return;
123  }
124 
125  // do not adjust climb_rate if level or descending
126  if (climb_rate_cms <= 0.0f) {
127  return;
128  }
129 
130  // limit acceleration
131  float accel_cmss_limited = MIN(accel_cmss, AC_AVOID_ACCEL_CMSS_MAX);
132 
133  bool limit_alt = false;
134  float alt_diff = 0.0f; // distance from altitude limit to vehicle in metres (positive means vehicle is below limit)
135 
136  // calculate distance below fence
138  // calculate distance from vehicle to safe altitude
139  float veh_alt;
141  // _fence.get_safe_alt_max() is UP, veh_alt is DOWN:
142  alt_diff = _fence.get_safe_alt_max() + veh_alt;
143  limit_alt = true;
144  }
145 
146  // calculate distance to (e.g.) optical flow altitude limit
147  // AHRS values are always in metres
148  float alt_limit;
149  float curr_alt;
150  if (_ahrs.get_hgt_ctrl_limit(alt_limit) &&
152  // alt_limit is UP, curr_alt is DOWN:
153  const float ctrl_alt_diff = alt_limit + curr_alt;
154  if (!limit_alt || ctrl_alt_diff < alt_diff) {
155  alt_diff = ctrl_alt_diff;
156  limit_alt = true;
157  }
158  }
159 
160  // get distance from proximity sensor
161  float proximity_alt_diff;
162  if (_proximity.get_upward_distance(proximity_alt_diff)) {
163  proximity_alt_diff -= _margin;
164  if (!limit_alt || proximity_alt_diff < alt_diff) {
165  alt_diff = proximity_alt_diff;
166  limit_alt = true;
167  }
168  }
169 
170  // limit climb rate
171  if (limit_alt) {
172  // do not allow climbing if we've breached the safe altitude
173  if (alt_diff <= 0.0f) {
174  climb_rate_cms = MIN(climb_rate_cms, 0.0f);
175  return;
176  }
177 
178  // limit climb rate
179  const float max_speed = get_max_speed(kP, accel_cmss_limited, alt_diff*100.0f, dt);
180  climb_rate_cms = MIN(max_speed, climb_rate_cms);
181  }
182 }
183 
184 // adjust roll-pitch to push vehicle away from objects
185 // roll and pitch value are in centi-degrees
186 void AC_Avoid::adjust_roll_pitch(float &roll, float &pitch, float veh_angle_max)
187 {
188  // exit immediately if proximity based avoidance is disabled
190  return;
191  }
192 
193  // exit immediately if angle max is zero
194  if (_angle_max <= 0.0f || veh_angle_max <= 0.0f) {
195  return;
196  }
197 
198  float roll_positive = 0.0f; // maximum positive roll value
199  float roll_negative = 0.0f; // minimum negative roll value
200  float pitch_positive = 0.0f; // maximum positive pitch value
201  float pitch_negative = 0.0f; // minimum negative pitch value
202 
203  // get maximum positive and negative roll and pitch percentages from proximity sensor
204  get_proximity_roll_pitch_pct(roll_positive, roll_negative, pitch_positive, pitch_negative);
205 
206  // add maximum positive and negative percentages together for roll and pitch, convert to centi-degrees
207  Vector2f rp_out((roll_positive + roll_negative) * 4500.0f, (pitch_positive + pitch_negative) * 4500.0f);
208 
209  // apply avoidance angular limits
210  // the object avoidance lean angle is never more than 75% of the total angle-limit to allow the pilot to override
211  const float angle_limit = constrain_float(_angle_max, 0.0f, veh_angle_max * AC_AVOID_ANGLE_MAX_PERCENT);
212  float vec_len = rp_out.length();
213  if (vec_len > angle_limit) {
214  rp_out *= (angle_limit / vec_len);
215  }
216 
217  // add passed in roll, pitch angles
218  rp_out.x += roll;
219  rp_out.y += pitch;
220 
221  // apply total angular limits
222  vec_len = rp_out.length();
223  if (vec_len > veh_angle_max) {
224  rp_out *= (veh_angle_max / vec_len);
225  }
226 
227  // return adjusted roll, pitch
228  roll = rp_out.x;
229  pitch = rp_out.y;
230 }
231 
232 /*
233  * Limits the component of desired_vel_cms in the direction of the unit vector
234  * limit_direction to be at most the maximum speed permitted by the limit_distance_cm.
235  *
236  * Uses velocity adjustment idea from Randy's second email on this thread:
237  * https://groups.google.com/forum/#!searchin/drones-discuss/obstacle/drones-discuss/QwUXz__WuqY/qo3G8iTLSJAJ
238  */
239 void AC_Avoid::limit_velocity(float kP, float accel_cmss, Vector2f &desired_vel_cms, const Vector2f& limit_direction, float limit_distance_cm, float dt) const
240 {
241  const float max_speed = get_max_speed(kP, accel_cmss, limit_distance_cm, dt);
242  // project onto limit direction
243  const float speed = desired_vel_cms * limit_direction;
244  if (speed > max_speed) {
245  // subtract difference between desired speed and maximum acceptable speed
246  desired_vel_cms += limit_direction*(max_speed - speed);
247  }
248 }
249 
250 /*
251  * Computes the speed such that the stopping distance
252  * of the vehicle will be exactly the input distance.
253  */
254 float AC_Avoid::get_max_speed(float kP, float accel_cmss, float distance_cm, float dt) const
255 {
256  if (is_zero(kP)) {
257  return safe_sqrt(2.0f * distance_cm * accel_cmss);
258  } else {
259  return AC_AttitudeControl::sqrt_controller(distance_cm, kP, accel_cmss, dt);
260  }
261 }
262 
263 /*
264  * Adjusts the desired velocity for the circular fence.
265  */
266 void AC_Avoid::adjust_velocity_circle_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt)
267 {
268  // exit if circular fence is not enabled
270  return;
271  }
272 
273  // exit if the circular fence has already been breached
274  if ((_fence.get_breaches() & AC_FENCE_TYPE_CIRCLE) != 0) {
275  return;
276  }
277 
278  // get position as a 2D offset from ahrs home
279  Vector2f position_xy;
280  if (!_ahrs.get_relative_position_NE_home(position_xy)) {
281  // we have no idea where we are....
282  return;
283  }
284  position_xy *= 100.0f; // m -> cm
285 
286  float speed = desired_vel_cms.length();
287  // get the fence radius in cm
288  const float fence_radius = _fence.get_radius() * 100.0f;
289  // get the margin to the fence in cm
290  const float margin_cm = _fence.get_margin() * 100.0f;
291 
292  if (!is_zero(speed) && position_xy.length() <= fence_radius) {
293  // Currently inside circular fence
294  Vector2f stopping_point = position_xy + desired_vel_cms*(get_stopping_distance(kP, accel_cmss, speed)/speed);
295  float stopping_point_length = stopping_point.length();
296  if (stopping_point_length > fence_radius - margin_cm) {
297  // Unsafe desired velocity - will not be able to stop before fence breach
299  // Project stopping point radially onto fence boundary
300  // Adjusted velocity will point towards this projected point at a safe speed
301  const Vector2f target = stopping_point * ((fence_radius - margin_cm) / stopping_point_length);
302  const Vector2f target_direction = target - position_xy;
303  const float distance_to_target = target_direction.length();
304  const float max_speed = get_max_speed(kP, accel_cmss, distance_to_target, dt);
305  desired_vel_cms = target_direction * (MIN(speed,max_speed) / distance_to_target);
306  } else {
307  // shorten vector without adjusting its direction
308  Vector2f intersection;
309  if (Vector2f::circle_segment_intersection(position_xy, stopping_point, Vector2f(0.0f,0.0f), fence_radius, intersection)) {
310  const float distance_to_target = MAX((intersection - position_xy).length() - margin_cm, 0.0f);
311  const float max_speed = get_max_speed(kP, accel_cmss, distance_to_target, dt);
312  if (max_speed < speed) {
313  desired_vel_cms *= MAX(max_speed, 0.0f) / speed;
314  }
315  }
316  }
317  }
318  }
319 }
320 
321 /*
322  * Adjusts the desired velocity for the polygon fence.
323  */
324 void AC_Avoid::adjust_velocity_polygon_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt)
325 {
326  // exit if the polygon fence is not enabled
328  return;
329  }
330 
331  // exit if the polygon fence has already been breached
332  if ((_fence.get_breaches() & AC_FENCE_TYPE_POLYGON) != 0) {
333  return;
334  }
335 
336  // exit immediately if no desired velocity
337  if (desired_vel_cms.is_zero()) {
338  return;
339  }
340 
341  // get polygon boundary
342  // Note: first point in list is the return-point (which copter does not use)
343  uint16_t num_points;
344  Vector2f* boundary = _fence.get_polygon_points(num_points);
345 
346  // adjust velocity using polygon
347  adjust_velocity_polygon(kP, accel_cmss, desired_vel_cms, boundary, num_points, true, _fence.get_margin(), dt);
348 }
349 
350 /*
351  * Adjusts the desired velocity for the beacon fence.
352  */
353 void AC_Avoid::adjust_velocity_beacon_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt)
354 {
355  // exit if the beacon is not present
356  if (_beacon == nullptr) {
357  return;
358  }
359 
360  // exit immediately if no desired velocity
361  if (desired_vel_cms.is_zero()) {
362  return;
363  }
364 
365  // get boundary from beacons
366  uint16_t num_points;
367  const Vector2f* boundary = _beacon->get_boundary_points(num_points);
368  if (boundary == nullptr || num_points == 0) {
369  return;
370  }
371 
372  // adjust velocity using beacon
373  adjust_velocity_polygon(kP, accel_cmss, desired_vel_cms, boundary, num_points, true, _fence.get_margin(), dt);
374 }
375 
376 /*
377  * Adjusts the desired velocity based on output from the proximity sensor
378  */
379 void AC_Avoid::adjust_velocity_proximity(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt)
380 {
381  // exit immediately if proximity sensor is not present
383  return;
384  }
385 
386  // exit immediately if no desired velocity
387  if (desired_vel_cms.is_zero()) {
388  return;
389  }
390 
391  // get boundary from proximity sensor
392  uint16_t num_points;
393  const Vector2f *boundary = _proximity.get_boundary_points(num_points);
394  adjust_velocity_polygon(kP, accel_cmss, desired_vel_cms, boundary, num_points, false, _margin, dt);
395 }
396 
397 /*
398  * Adjusts the desired velocity for the polygon fence.
399  */
400 void AC_Avoid::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)
401 {
402  // exit if there are no points
403  if (boundary == nullptr || num_points == 0) {
404  return;
405  }
406 
407  // do not adjust velocity if vehicle is outside the polygon fence
408  Vector2f position_xy;
409  if (earth_frame) {
410  if (!_ahrs.get_relative_position_NE_origin(position_xy)) {
411  // boundary is in earth frame but we have no idea
412  // where we are
413  return;
414  }
415  position_xy = position_xy * 100.0f; // m to cm
416  }
417 
418  if (_fence.boundary_breached(position_xy, num_points, boundary)) {
419  return;
420  }
421 
422  // Safe_vel will be adjusted to remain within fence.
423  // We need a separate vector in case adjustment fails,
424  // e.g. if we are exactly on the boundary.
425  Vector2f safe_vel(desired_vel_cms);
426 
427  // if boundary points are in body-frame, rotate velocity vector from earth frame to body-frame
428  if (!earth_frame) {
429  safe_vel.x = desired_vel_cms.y * _ahrs.sin_yaw() + desired_vel_cms.x * _ahrs.cos_yaw(); // right
430  safe_vel.y = desired_vel_cms.y * _ahrs.cos_yaw() - desired_vel_cms.x * _ahrs.sin_yaw(); // forward
431  }
432 
433  // calc margin in cm
434  float margin_cm = MAX(margin * 100.0f, 0.0f);
435 
436  // for stopping
437  float speed = safe_vel.length();
438  Vector2f stopping_point = position_xy + safe_vel*((2.0f + get_stopping_distance(kP, accel_cmss, speed))/speed);
439 
440  uint16_t i, j;
441  for (i = 1, j = num_points-1; i < num_points; j = i++) {
442  // end points of current edge
443  Vector2f start = boundary[j];
444  Vector2f end = boundary[i];
446  // vector from current position to closest point on current edge
447  Vector2f limit_direction = Vector2f::closest_point(position_xy, start, end) - position_xy;
448  // distance to closest point
449  const float limit_distance_cm = limit_direction.length();
450  if (!is_zero(limit_distance_cm)) {
451  // We are strictly inside the given edge.
452  // Adjust velocity to not violate this edge.
453  limit_direction /= limit_distance_cm;
454  limit_velocity(kP, accel_cmss, safe_vel, limit_direction, MAX(limit_distance_cm - margin_cm, 0.0f), dt);
455  } else {
456  // We are exactly on the edge - treat this as a fence breach.
457  // i.e. do not adjust velocity.
458  return;
459  }
460  } else {
461  // find intersection with line segment
462  Vector2f intersection;
463  if (Vector2f::segment_intersection(position_xy, stopping_point, start, end, intersection)) {
464  // vector from current position to point on current edge
465  Vector2f limit_direction = intersection - position_xy;
466  const float limit_distance_cm = limit_direction.length();
467  if (!is_zero(limit_distance_cm)) {
468  if (limit_distance_cm <= margin_cm) {
469  // we are within the margin so stop vehicle
470  safe_vel.zero();
471  } else {
472  // vehicle inside the given edge, adjust velocity to not violate this edge
473  limit_direction /= limit_distance_cm;
474  limit_velocity(kP, accel_cmss, safe_vel, limit_direction, MAX(limit_distance_cm - margin_cm, 0.0f), dt);
475  }
476  } else {
477  // We are exactly on the edge - treat this as a fence breach.
478  // i.e. do not adjust velocity.
479  return;
480  }
481  }
482  }
483  }
484 
485  // set modified desired velocity vector
486  if (earth_frame) {
487  desired_vel_cms = safe_vel;
488  } else {
489  // if points were in body-frame, rotate resulting vector back to earth-frame
490  desired_vel_cms.x = safe_vel.x * _ahrs.cos_yaw() - safe_vel.y * _ahrs.sin_yaw();
491  desired_vel_cms.y = safe_vel.x * _ahrs.sin_yaw() + safe_vel.y * _ahrs.cos_yaw();
492  }
493 }
494 
495 /*
496  * Computes distance required to stop, given current speed.
497  *
498  * Implementation copied from AC_PosControl.
499  */
500 float AC_Avoid::get_stopping_distance(float kP, float accel_cmss, float speed_cms) const
501 {
502  // avoid divide by zero by using current position if the velocity is below 10cm/s, kP is very low or acceleration is zero
503  if (accel_cmss <= 0.0f || is_zero(speed_cms)) {
504  return 0.0f;
505  }
506 
507  // handle linear deceleration
508  if (kP <= 0.0f) {
509  return 0.5f * sq(speed_cms) / accel_cmss;
510  }
511 
512  // calculate distance within which we can stop
513  // accel_cmss/kP is the point at which velocity switches from linear to sqrt
514  if (speed_cms < accel_cmss/kP) {
515  return speed_cms/kP;
516  } else {
517  // accel_cmss/(2.0f*kP*kP) is the distance at which we switch from linear to sqrt response
518  return accel_cmss/(2.0f*kP*kP) + (speed_cms*speed_cms)/(2.0f*accel_cmss);
519  }
520 }
521 
522 // convert distance (in meters) to a lean percentage (in 0~1 range) for use in manual flight modes
524 {
525  // ignore objects beyond DIST_MAX
526  if (dist_m < 0.0f || dist_m >= _dist_max || _dist_max <= 0.0f) {
527  return 0.0f;
528  }
529  // inverted but linear response
530  return 1.0f - (dist_m / _dist_max);
531 }
532 
533 // returns the maximum positive and negative roll and pitch percentages (in -1 ~ +1 range) based on the proximity sensor
534 void AC_Avoid::get_proximity_roll_pitch_pct(float &roll_positive, float &roll_negative, float &pitch_positive, float &pitch_negative)
535 {
536  // exit immediately if proximity sensor is not present
538  return;
539  }
540 
541  uint8_t obj_count = _proximity.get_object_count();
542 
543  // if no objects return
544  if (obj_count == 0) {
545  return;
546  }
547 
548  // calculate maximum roll, pitch values from objects
549  for (uint8_t i=0; i<obj_count; i++) {
550  float ang_deg, dist_m;
551  if (_proximity.get_object_angle_and_distance(i, ang_deg, dist_m)) {
552  if (dist_m < _dist_max) {
553  // convert distance to lean angle (in 0 to 1 range)
554  const float lean_pct = distance_to_lean_pct(dist_m);
555  // convert angle to roll and pitch lean percentages
556  const float angle_rad = radians(ang_deg);
557  const float roll_pct = -sinf(angle_rad) * lean_pct;
558  const float pitch_pct = cosf(angle_rad) * lean_pct;
559  // update roll, pitch maximums
560  if (roll_pct > 0.0f) {
561  roll_positive = MAX(roll_positive, roll_pct);
562  } else if (roll_pct < 0.0f) {
563  roll_negative = MIN(roll_negative, roll_pct);
564  }
565  if (pitch_pct > 0.0f) {
566  pitch_positive = MAX(pitch_positive, pitch_pct);
567  } else if (pitch_pct < 0.0f) {
568  pitch_negative = MIN(pitch_negative, pitch_pct);
569  }
570  }
571  }
572  }
573 }
bool boundary_breached(const Vector2f &location, uint16_t num_points, const Vector2f *points) const
returns true if we&#39;ve breached the polygon boundary. simple passthrough to underlying _poly_loader ob...
Definition: AC_Fence.cpp:457
float cos_yaw() const
Definition: AP_AHRS.h:402
AP_Int8 _enabled
Definition: AC_Avoid.h:136
Vector2< float > Vector2f
Definition: vector2.h:239
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
float safe_sqrt(const T v)
Definition: AP_Math.cpp:64
#define AC_AVOID_DEFAULT
Definition: AC_Avoid.h:19
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
const Vector2f * get_boundary_points(uint16_t &num_points) const
Definition: AP_Beacon.cpp:361
float sin_yaw() const
Definition: AP_AHRS.h:411
bool get_upward_distance(uint8_t instance, float &distance) const
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
#define AC_FENCE_TYPE_CIRCLE
Definition: AC_Fence.h:14
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
static bool segment_intersection(const Vector2< T > &seg1_start, const Vector2< T > &seg1_end, const Vector2< T > &seg2_start, const Vector2< T > &seg2_end, Vector2< T > &intersection)
Definition: vector2.cpp:147
uint8_t get_breaches() const
get_breaches - returns bit mask of the fence types that have been breached
Definition: AC_Fence.h:65
virtual bool get_relative_position_NE_origin(Vector2f &vecNE) const
Definition: AP_AHRS.h:344
float get_stopping_distance(float kP, float accel_cmss, float speed_cms) const
Definition: AC_Avoid.cpp:500
const Vector2f * get_boundary_points(uint8_t instance, uint16_t &num_points) const
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
#define AC_AVOID_NONGPS_DIST_MAX_DEFAULT
Definition: AC_Avoid.h:22
static Vector2< T > closest_point(const Vector2< T > &p, const Vector2< T > &v, const Vector2< T > &w)
Definition: vector2.h:191
#define MIN(a, b)
Definition: usb_conf.h:215
uint8_t get_object_count() const
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
AP_Float _margin
Definition: AC_Avoid.h:139
bool get_object_angle_and_distance(uint8_t object_number, float &angle_deg, float &distance) const
T y
Definition: vector2.h:37
AP_Int8 _behavior
Definition: AC_Avoid.h:140
const AP_AHRS & _ahrs
Definition: AC_Avoid.h:130
#define AC_AVOID_ANGLE_MAX_PERCENT
Definition: AC_Avoid.h:23
Proximity_Status get_status(uint8_t instance) const
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
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
T y
Definition: vector3.h:67
float get_radius() const
get_radius - returns the fence radius in meters
Definition: AC_Fence.h:86
static bool circle_segment_intersection(const Vector2< T > &seg_start, const Vector2< T > &seg_end, const Vector2< T > &circle_center, float radius, Vector2< T > &intersection)
Definition: vector2.cpp:180
#define AC_AVOID_ACCEL_CMSS_MAX
Definition: AC_Avoid.h:12
Vector2f * get_polygon_points(uint16_t &num_points) const
returns pointer to array of polygon points and num_points is filled in with the total number ...
Definition: AC_Fence.cpp:450
virtual bool get_relative_position_NE_home(Vector2f &vecNE) const
Definition: AP_AHRS.h:338
#define AC_AVOID_STOP_AT_FENCE
Definition: AC_Avoid.h:16
#define AC_AVOID_STOP_AT_BEACON_FENCE
Definition: AC_Avoid.h:18
static float sqrt_controller(float error, float p, float second_ord_lim, float dt)
float get_max_speed(float kP, float accel_cmss, float distance_cm, float dt) const
Definition: AC_Avoid.cpp:254
uint8_t get_enabled_fences() const
get_enabled_fences - returns bitmask of enabled fences
Definition: AC_Fence.cpp:91
float get_margin() const
get_margin - returns the fence margin in meters
Definition: AC_Fence.h:89
AP_Float _dist_max
Definition: AC_Avoid.h:138
float get_safe_alt_max() const
get_safe_alt - returns maximum safe altitude (i.e. alt_max - margin)
Definition: AC_Fence.h:80
const AC_Fence & _fence
Definition: AC_Avoid.h:131
float length(void) const
Definition: vector2.cpp:24
#define AC_AVOID_USE_PROXIMITY_SENSOR
Definition: AC_Avoid.h:17
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
T x
Definition: vector2.h:37
void adjust_velocity_circle_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt)
Definition: AC_Avoid.cpp:266
static constexpr float radians(float deg)
Definition: AP_Math.h:158
bool is_zero(void) const
Definition: vector2.h:105
virtual bool get_hgt_ctrl_limit(float &limit) const
Definition: AP_AHRS.h:566
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
bool is_negative(const T fVal1)
Definition: AP_Math.h:61
float sq(const T val)
Definition: AP_Math.h:170
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
#define AC_FENCE_TYPE_POLYGON
Definition: AC_Fence.h:15
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
#define AC_AVOID_DISABLED
Definition: AC_Avoid.h:15
#define AP_AVOID_BEHAVE_DEFAULT
Definition: AC_Avoid.cpp:6
virtual void get_relative_position_D_home(float &posD) const =0
virtual bool get_relative_position_D_origin(float &posD) const
Definition: AP_AHRS.h:354
#define AC_FENCE_TYPE_ALT_MAX
Definition: AC_Fence.h:13
#define AP_GROUPEND
Definition: AP_Param.h:121
T x
Definition: vector3.h:67
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
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214