AC_Avoid.cpp 24 KB

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