AC_WPNav.cpp 42 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AC_WPNav.h"
  3. extern const AP_HAL::HAL& hal;
  4. const AP_Param::GroupInfo AC_WPNav::var_info[] = {
  5. // index 0 was used for the old orientation matrix
  6. // @Param: SPEED
  7. // @DisplayName: Waypoint Horizontal Speed Target
  8. // @Description: Defines the speed in cm/s which the aircraft will attempt to maintain horizontally during a WP mission
  9. // @Units: cm/s
  10. // @Range: 20 2000
  11. // @Increment: 50
  12. // @User: Standard
  13. AP_GROUPINFO("SPEED", 0, AC_WPNav, _wp_speed_cms, WPNAV_WP_SPEED),
  14. // @Param: RADIUS
  15. // @DisplayName: Waypoint Radius
  16. // @Description: Defines the distance from a waypoint, that when crossed indicates the wp has been hit.
  17. // @Units: cm
  18. // @Range: 5 1000
  19. // @Increment: 1
  20. // @User: Standard
  21. AP_GROUPINFO("RADIUS", 1, AC_WPNav, _wp_radius_cm, WPNAV_WP_RADIUS),
  22. // @Param: SPEED_UP
  23. // @DisplayName: Waypoint Climb Speed Target
  24. // @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while climbing during a WP mission
  25. // @Units: cm/s
  26. // @Range: 10 1000
  27. // @Increment: 50
  28. // @User: Standard
  29. AP_GROUPINFO("SPEED_UP", 2, AC_WPNav, _wp_speed_up_cms, WPNAV_WP_SPEED_UP),
  30. // @Param: SPEED_DN
  31. // @DisplayName: Waypoint Descent Speed Target
  32. // @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while descending during a WP mission
  33. // @Units: cm/s
  34. // @Range: 10 500
  35. // @Increment: 10
  36. // @User: Standard
  37. AP_GROUPINFO("SPEED_DN", 3, AC_WPNav, _wp_speed_down_cms, WPNAV_WP_SPEED_DOWN),
  38. // @Param: ACCEL
  39. // @DisplayName: Waypoint Acceleration
  40. // @Description: Defines the horizontal acceleration in cm/s/s used during missions
  41. // @Units: cm/s/s
  42. // @Range: 50 500
  43. // @Increment: 10
  44. // @User: Standard
  45. AP_GROUPINFO("ACCEL", 5, AC_WPNav, _wp_accel_cmss, WPNAV_ACCELERATION),
  46. // @Param: ACCEL_Z
  47. // @DisplayName: Waypoint Vertical Acceleration
  48. // @Description: Defines the vertical acceleration in cm/s/s used during missions
  49. // @Units: cm/s/s
  50. // @Range: 50 500
  51. // @Increment: 10
  52. // @User: Standard
  53. AP_GROUPINFO("ACCEL_Z", 6, AC_WPNav, _wp_accel_z_cmss, WPNAV_WP_ACCEL_Z_DEFAULT),
  54. // @Param: RFND_USE
  55. // @DisplayName: Waypoint missions use rangefinder for terrain following
  56. // @Description: This controls if waypoint missions use rangefinder for terrain following
  57. // @Values: 0:Disable,1:Enable
  58. // @User: Advanced
  59. AP_GROUPINFO("RFND_USE", 10, AC_WPNav, _rangefinder_use, 1),
  60. AP_GROUPEND
  61. };
  62. // Default constructor.
  63. // Note that the Vector/Matrix constructors already implicitly zero
  64. // their values.
  65. //
  66. AC_WPNav::AC_WPNav(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control) :
  67. _inav(inav),
  68. _ahrs(ahrs),
  69. _pos_control(pos_control),
  70. _attitude_control(attitude_control)
  71. {
  72. AP_Param::setup_object_defaults(this, var_info);
  73. // init flags
  74. _flags.reached_destination = false;
  75. _flags.fast_waypoint = false;
  76. _flags.slowing_down = false;
  77. _flags.recalc_wp_leash = false;
  78. _flags.new_wp_destination = false;
  79. _flags.segment_type = SEGMENT_STRAIGHT;
  80. // sanity check some parameters
  81. _wp_accel_cmss = MIN(_wp_accel_cmss, GRAVITY_MSS * 100.0f * tanf(ToRad(_attitude_control.lean_angle_max() * 0.01f)));
  82. _wp_radius_cm = MAX(_wp_radius_cm, WPNAV_WP_RADIUS_MIN);
  83. }
  84. ///
  85. /// waypoint navigation
  86. ///
  87. /// wp_and_spline_init - initialise straight line and spline waypoint controllers
  88. /// updates target roll, pitch targets and I terms based on vehicle lean angles
  89. /// should be called once before the waypoint controller is used but does not need to be called before subsequent updates to destination
  90. void AC_WPNav::wp_and_spline_init()
  91. {
  92. // check _wp_accel_cmss is reasonable
  93. if (_wp_accel_cmss <= 0) {
  94. _wp_accel_cmss.set_and_save(WPNAV_ACCELERATION);
  95. }
  96. // initialise position controller
  97. _pos_control.set_desired_accel_xy(0.0f,0.0f);
  98. _pos_control.init_xy_controller();
  99. _pos_control.clear_desired_velocity_ff_z();
  100. // initialise feed forward velocity to zero
  101. _pos_control.set_desired_velocity_xy(0.0f, 0.0f);
  102. // initialise position controller speed and acceleration
  103. _pos_control.set_max_speed_xy(_wp_speed_cms);
  104. _pos_control.set_max_accel_xy(_wp_accel_cmss);
  105. _pos_control.set_max_speed_z(-_wp_speed_down_cms, _wp_speed_up_cms);
  106. _pos_control.set_max_accel_z(_wp_accel_z_cmss);
  107. _pos_control.calc_leash_length_xy();
  108. _pos_control.calc_leash_length_z();
  109. // initialise yaw heading to current heading target
  110. _flags.wp_yaw_set = false;
  111. }
  112. /// set_speed_xy - allows main code to pass target horizontal velocity for wp navigation
  113. void AC_WPNav::set_speed_xy(float speed_cms)
  114. {
  115. // range check new target speed and update position controller
  116. if (speed_cms >= WPNAV_WP_SPEED_MIN) {
  117. _pos_control.set_max_speed_xy(speed_cms);
  118. // flag that wp leash must be recalculated
  119. _flags.recalc_wp_leash = true;
  120. }
  121. }
  122. /// set current target climb rate during wp navigation
  123. void AC_WPNav::set_speed_up(float speed_up_cms)
  124. {
  125. _pos_control.set_max_speed_z(_pos_control.get_max_speed_down(), speed_up_cms);
  126. // flag that wp leash must be recalculated
  127. _flags.recalc_wp_leash = true;
  128. }
  129. /// set current target descent rate during wp navigation
  130. void AC_WPNav::set_speed_down(float speed_down_cms)
  131. {
  132. _pos_control.set_max_speed_z(speed_down_cms, _pos_control.get_max_speed_up());
  133. // flag that wp leash must be recalculated
  134. _flags.recalc_wp_leash = true;
  135. }
  136. /// set_wp_destination waypoint using location class
  137. /// returns false if conversion from location to vector from ekf origin cannot be calculated
  138. bool AC_WPNav::set_wp_destination(const Location& destination)
  139. {
  140. bool terr_alt;
  141. Vector3f dest_neu;
  142. // convert destination location to vector
  143. if (!get_vector_NEU(destination, dest_neu, terr_alt)) {
  144. return false;
  145. }
  146. // set target as vector from EKF origin
  147. return set_wp_destination(dest_neu, terr_alt);
  148. }
  149. bool AC_WPNav::get_wp_destination(Location& destination) const
  150. {
  151. Vector3f dest = get_wp_destination();
  152. if (!AP::ahrs().get_origin(destination)) {
  153. return false;
  154. }
  155. destination.offset(dest.x*0.01f, dest.y*0.01f);
  156. destination.alt += dest.z;
  157. return true;
  158. }
  159. /// set_wp_destination waypoint using position vector (distance from home in cm)
  160. /// terrain_alt should be true if destination.z is a desired altitude above terrain
  161. bool AC_WPNav::set_wp_destination(const Vector3f& destination, bool terrain_alt)
  162. {
  163. Vector3f origin;
  164. // if waypoint controller is active use the existing position target as the origin
  165. if ((AP_HAL::millis() - _wp_last_update) < 1000) {
  166. origin = _pos_control.get_pos_target();
  167. } else {
  168. // if waypoint controller is not active, set origin to reasonable stopping point (using curr pos and velocity)
  169. _pos_control.get_stopping_point_xy(origin);
  170. _pos_control.get_stopping_point_z(origin);
  171. }
  172. // convert origin to alt-above-terrain
  173. if (terrain_alt) {
  174. float origin_terr_offset;
  175. if (!get_terrain_offset(origin_terr_offset)) {
  176. return false;
  177. }
  178. origin.z -= origin_terr_offset;
  179. }
  180. // set origin and destination
  181. return set_wp_origin_and_destination(origin, destination, terrain_alt);
  182. }
  183. /// set waypoint destination using NED position vector from ekf origin in meters
  184. bool AC_WPNav::set_wp_destination_NED(const Vector3f& destination_NED)
  185. {
  186. // convert NED to NEU and do not use terrain following
  187. return set_wp_destination(Vector3f(destination_NED.x * 100.0f, destination_NED.y * 100.0f, -destination_NED.z * 100.0f), false);
  188. }
  189. /// set_origin_and_destination - set origin and destination waypoints using position vectors (distance from home in cm)
  190. /// terrain_alt should be true if origin.z and destination.z are desired altitudes above terrain (false if these are alt-above-ekf-origin)
  191. /// returns false on failure (likely caused by missing terrain data)
  192. bool AC_WPNav::set_wp_origin_and_destination(const Vector3f& origin, const Vector3f& destination, bool terrain_alt)
  193. {
  194. // store origin and destination locations
  195. _origin = origin;
  196. _destination = destination;
  197. _terrain_alt = terrain_alt;
  198. Vector3f pos_delta = _destination - _origin;
  199. _track_length = pos_delta.length(); // get track length
  200. _track_length_xy = safe_sqrt(sq(pos_delta.x)+sq(pos_delta.y)); // get horizontal track length (used to decide if we should update yaw)
  201. // calculate each axis' percentage of the total distance to the destination
  202. if (is_zero(_track_length)) {
  203. // avoid possible divide by zero
  204. _pos_delta_unit.x = 0;
  205. _pos_delta_unit.y = 0;
  206. _pos_delta_unit.z = 0;
  207. }else{
  208. _pos_delta_unit = pos_delta/_track_length;
  209. }
  210. // calculate leash lengths
  211. calculate_wp_leash_length();
  212. // get origin's alt-above-terrain
  213. float origin_terr_offset = 0.0f;
  214. if (terrain_alt) {
  215. if (!get_terrain_offset(origin_terr_offset)) {
  216. return false;
  217. }
  218. }
  219. // initialise intermediate point to the origin
  220. _pos_control.set_pos_target(origin + Vector3f(0,0,origin_terr_offset));
  221. _track_desired = 0; // target is at beginning of track
  222. _flags.reached_destination = false;
  223. _flags.fast_waypoint = false; // default waypoint back to slow
  224. _flags.slowing_down = false; // target is not slowing down yet
  225. _flags.segment_type = SEGMENT_STRAIGHT;
  226. _flags.new_wp_destination = true; // flag new waypoint so we can freeze the pos controller's feed forward and smooth the transition
  227. _flags.wp_yaw_set = false;
  228. // initialise the limited speed to current speed along the track
  229. const Vector3f &curr_vel = _inav.get_velocity();
  230. // get speed along track (note: we convert vertical speed into horizontal speed equivalent)
  231. float speed_along_track = curr_vel.x * _pos_delta_unit.x + curr_vel.y * _pos_delta_unit.y + curr_vel.z * _pos_delta_unit.z;
  232. _limited_speed_xy_cms = constrain_float(speed_along_track, 0, _pos_control.get_max_speed_xy());
  233. return true;
  234. }
  235. /// shift_wp_origin_to_current_pos - shifts the origin and destination so the origin starts at the current position
  236. /// used to reset the position just before takeoff
  237. /// relies on set_wp_destination or set_wp_origin_and_destination having been called first
  238. void AC_WPNav::shift_wp_origin_to_current_pos()
  239. {
  240. // return immediately if vehicle is not at the origin
  241. if (_track_desired > 0.0f) {
  242. return;
  243. }
  244. // get current and target locations
  245. const Vector3f &curr_pos = _inav.get_position();
  246. const Vector3f pos_target = _pos_control.get_pos_target();
  247. // calculate difference between current position and target
  248. Vector3f pos_diff = curr_pos - pos_target;
  249. // shift origin and destination
  250. _origin += pos_diff;
  251. _destination += pos_diff;
  252. // move pos controller target and disable feed forward
  253. _pos_control.set_pos_target(curr_pos);
  254. _pos_control.freeze_ff_z();
  255. }
  256. /// get_wp_stopping_point_xy - returns vector to stopping point based on a horizontal position and velocity
  257. void AC_WPNav::get_wp_stopping_point_xy(Vector3f& stopping_point) const
  258. {
  259. _pos_control.get_stopping_point_xy(stopping_point);
  260. }
  261. /// get_wp_stopping_point - returns vector to stopping point based on 3D position and velocity
  262. void AC_WPNav::get_wp_stopping_point(Vector3f& stopping_point) const
  263. {
  264. _pos_control.get_stopping_point_xy(stopping_point);
  265. _pos_control.get_stopping_point_z(stopping_point);
  266. }
  267. /// advance_wp_target_along_track - move target location along track from origin to destination
  268. bool AC_WPNav::advance_wp_target_along_track(float dt)
  269. {
  270. float track_covered; // distance (in cm) along the track that the vehicle has traveled. Measured by drawing a perpendicular line from the track to the vehicle.
  271. Vector3f track_error; // distance error (in cm) from the track_covered position (i.e. closest point on the line to the vehicle) and the vehicle
  272. float track_desired_max; // the farthest distance (in cm) along the track that the leash will allow
  273. float track_leash_slack; // additional distance (in cm) along the track from our track_covered position that our leash will allow
  274. bool reached_leash_limit = false; // true when track has reached leash limit and we need to slow down the target point
  275. // get current location
  276. const Vector3f &curr_pos = _inav.get_position();
  277. // calculate terrain adjustments
  278. float terr_offset = 0.0f;
  279. if (_terrain_alt && !get_terrain_offset(terr_offset)) {
  280. return false;
  281. }
  282. // calculate 3d vector from segment's origin
  283. Vector3f curr_delta = (curr_pos - Vector3f(0,0,terr_offset)) - _origin;
  284. // calculate how far along the track we are
  285. track_covered = curr_delta.x * _pos_delta_unit.x + curr_delta.y * _pos_delta_unit.y + curr_delta.z * _pos_delta_unit.z;
  286. // calculate the point closest to the vehicle on the segment from origin to destination
  287. Vector3f track_covered_pos = _pos_delta_unit * track_covered;
  288. // calculate the distance vector from the vehicle to the closest point on the segment from origin to destination
  289. track_error = curr_delta - track_covered_pos;
  290. // calculate the horizontal error
  291. _track_error_xy = norm(track_error.x, track_error.y);
  292. // calculate the vertical error
  293. float track_error_z = fabsf(track_error.z);
  294. // get up leash if we are moving up, down leash if we are moving down
  295. float leash_z = track_error.z >= 0 ? _pos_control.get_leash_up_z() : _pos_control.get_leash_down_z();
  296. // use pythagoras's theorem calculate how far along the track we could move the intermediate target before reaching the end of the leash
  297. // track_desired_max is the distance from the vehicle to our target point along the track. It is the "hypotenuse" which we want to be no longer than our leash (aka _track_leash_length)
  298. // track_error is the line from the vehicle to the closest point on the track. It is the "opposite" side
  299. // track_leash_slack is the line from the closest point on the track to the target point. It is the "adjacent" side. We adjust this so the track_desired_max is no longer than the leash
  300. float track_leash_length_abs = fabsf(_track_leash_length);
  301. float track_error_max_abs = MAX(_track_leash_length*track_error_z/leash_z, _track_leash_length*_track_error_xy/_pos_control.get_leash_xy());
  302. track_leash_slack = (track_leash_length_abs > track_error_max_abs) ? safe_sqrt(sq(_track_leash_length) - sq(track_error_max_abs)) : 0;
  303. track_desired_max = track_covered + track_leash_slack;
  304. // check if target is already beyond the leash
  305. if (_track_desired > track_desired_max) {
  306. reached_leash_limit = true;
  307. }
  308. // get current velocity
  309. const Vector3f &curr_vel = _inav.get_velocity();
  310. // get speed along track
  311. float speed_along_track = curr_vel.x * _pos_delta_unit.x + curr_vel.y * _pos_delta_unit.y + curr_vel.z * _pos_delta_unit.z;
  312. // calculate point at which velocity switches from linear to sqrt
  313. float linear_velocity = _pos_control.get_max_speed_xy();
  314. float kP = _pos_control.get_pos_xy_p().kP();
  315. if (is_positive(kP)) { // avoid divide by zero
  316. linear_velocity = _track_accel/kP;
  317. }
  318. // let the limited_speed_xy_cms be some range above or below current velocity along track
  319. if (speed_along_track < -linear_velocity) {
  320. // we are traveling fast in the opposite direction of travel to the waypoint so do not move the intermediate point
  321. _limited_speed_xy_cms = 0;
  322. }else{
  323. // increase intermediate target point's velocity if not yet at the leash limit
  324. if(dt > 0 && !reached_leash_limit) {
  325. _limited_speed_xy_cms += 2.0f * _track_accel * dt;
  326. }
  327. // do not allow speed to be below zero or over top speed
  328. _limited_speed_xy_cms = constrain_float(_limited_speed_xy_cms, 0.0f, _track_speed);
  329. // check if we should begin slowing down
  330. if (!_flags.fast_waypoint) {
  331. float dist_to_dest = _track_length - _track_desired;
  332. if (!_flags.slowing_down && dist_to_dest <= _slow_down_dist) {
  333. _flags.slowing_down = true;
  334. }
  335. // if target is slowing down, limit the speed
  336. if (_flags.slowing_down) {
  337. _limited_speed_xy_cms = MIN(_limited_speed_xy_cms, get_slow_down_speed(dist_to_dest, _track_accel));
  338. }
  339. }
  340. // if our current velocity is within the linear velocity range limit the intermediate point's velocity to be no more than the linear_velocity above or below our current velocity
  341. if (fabsf(speed_along_track) < linear_velocity) {
  342. _limited_speed_xy_cms = constrain_float(_limited_speed_xy_cms,speed_along_track-linear_velocity,speed_along_track+linear_velocity);
  343. }
  344. }
  345. // advance the current target
  346. if (!reached_leash_limit) {
  347. _track_desired += _limited_speed_xy_cms * dt;
  348. // reduce speed if we reach end of leash
  349. if (_track_desired > track_desired_max) {
  350. _track_desired = track_desired_max;
  351. _limited_speed_xy_cms -= 2.0f * _track_accel * dt;
  352. if (_limited_speed_xy_cms < 0.0f) {
  353. _limited_speed_xy_cms = 0.0f;
  354. }
  355. }
  356. }
  357. // do not let desired point go past the end of the track unless it's a fast waypoint
  358. if (!_flags.fast_waypoint) {
  359. _track_desired = constrain_float(_track_desired, 0, _track_length);
  360. } else {
  361. _track_desired = constrain_float(_track_desired, 0, _track_length + WPNAV_WP_FAST_OVERSHOOT_MAX);
  362. }
  363. // recalculate the desired position
  364. Vector3f final_target = _origin + _pos_delta_unit * _track_desired;
  365. // convert final_target.z to altitude above the ekf origin
  366. final_target.z += terr_offset;
  367. _pos_control.set_pos_target(final_target);
  368. // check if we've reached the waypoint
  369. if( !_flags.reached_destination ) {
  370. if( _track_desired >= _track_length ) {
  371. // "fast" waypoints are complete once the intermediate point reaches the destination
  372. if (_flags.fast_waypoint) {
  373. _flags.reached_destination = true;
  374. }else{
  375. // regular waypoints also require the copter to be within the waypoint radius
  376. Vector3f dist_to_dest = (curr_pos - Vector3f(0,0,terr_offset)) - _destination;
  377. if( dist_to_dest.length() <= _wp_radius_cm ) {
  378. _flags.reached_destination = true;
  379. }
  380. }
  381. }
  382. }
  383. // update the target yaw if origin and destination are at least 2m apart horizontally
  384. if (_track_length_xy >= WPNAV_YAW_DIST_MIN) {
  385. if (_pos_control.get_leash_xy() < WPNAV_YAW_DIST_MIN) {
  386. // if the leash is short (i.e. moving slowly) and destination is at least 2m horizontally, point along the segment from origin to destination
  387. set_yaw_cd(get_bearing_cd(_origin, _destination));
  388. } else {
  389. Vector3f horiz_leash_xy = final_target - curr_pos;
  390. horiz_leash_xy.z = 0;
  391. if (horiz_leash_xy.length() > MIN(WPNAV_YAW_DIST_MIN, _pos_control.get_leash_xy()*WPNAV_YAW_LEASH_PCT_MIN)) {
  392. set_yaw_cd(RadiansToCentiDegrees(atan2f(horiz_leash_xy.y,horiz_leash_xy.x)));
  393. }
  394. }
  395. }
  396. // successfully advanced along track
  397. return true;
  398. }
  399. /// get_wp_distance_to_destination - get horizontal distance to destination in cm
  400. float AC_WPNav::get_wp_distance_to_destination() const
  401. {
  402. // get current location
  403. const Vector3f &curr = _inav.get_position();
  404. return norm(_destination.x-curr.x,_destination.y-curr.y);
  405. }
  406. /// get_wp_bearing_to_destination - get bearing to next waypoint in centi-degrees
  407. int32_t AC_WPNav::get_wp_bearing_to_destination() const
  408. {
  409. return get_bearing_cd(_inav.get_position(), _destination);
  410. }
  411. /// update_wpnav - run the wp controller - should be called at 100hz or higher
  412. bool AC_WPNav::update_wpnav()
  413. {
  414. bool ret = true;
  415. // get dt from pos controller
  416. float dt = _pos_control.get_dt();
  417. // allow the accel and speed values to be set without changing
  418. // out of auto mode. This makes it easier to tune auto flight
  419. _pos_control.set_max_accel_xy(_wp_accel_cmss);
  420. _pos_control.set_max_accel_z(_wp_accel_z_cmss);
  421. // advance the target if necessary
  422. if (!advance_wp_target_along_track(dt)) {
  423. // To-Do: handle inability to advance along track (probably because of missing terrain data)
  424. ret = false;
  425. }
  426. // freeze feedforwards during known discontinuities
  427. if (_flags.new_wp_destination) {
  428. _flags.new_wp_destination = false;
  429. _pos_control.freeze_ff_z();
  430. }
  431. _pos_control.update_xy_controller();
  432. check_wp_leash_length();
  433. _wp_last_update = AP_HAL::millis();
  434. return ret;
  435. }
  436. // check_wp_leash_length - check if waypoint leash lengths need to be recalculated
  437. // should be called after _pos_control.update_xy_controller which may have changed the position controller leash lengths
  438. void AC_WPNav::check_wp_leash_length()
  439. {
  440. // exit immediately if recalc is not required
  441. if (_flags.recalc_wp_leash) {
  442. calculate_wp_leash_length();
  443. }
  444. }
  445. /// calculate_wp_leash_length - calculates horizontal and vertical leash lengths for waypoint controller
  446. void AC_WPNav::calculate_wp_leash_length()
  447. {
  448. // length of the unit direction vector in the horizontal
  449. float pos_delta_unit_xy = norm(_pos_delta_unit.x, _pos_delta_unit.y);
  450. float pos_delta_unit_z = fabsf(_pos_delta_unit.z);
  451. float speed_z;
  452. float leash_z;
  453. if (_pos_delta_unit.z >= 0.0f) {
  454. speed_z = _pos_control.get_max_speed_up();
  455. leash_z = _pos_control.get_leash_up_z();
  456. }else{
  457. speed_z = fabsf(_pos_control.get_max_speed_down());
  458. leash_z = _pos_control.get_leash_down_z();
  459. }
  460. // calculate the maximum acceleration, maximum velocity, and leash length in the direction of travel
  461. if(is_zero(pos_delta_unit_z) && is_zero(pos_delta_unit_xy)){
  462. _track_accel = 0;
  463. _track_speed = 0;
  464. _track_leash_length = WPNAV_LEASH_LENGTH_MIN;
  465. }else if(is_zero(_pos_delta_unit.z)){
  466. _track_accel = _wp_accel_cmss/pos_delta_unit_xy;
  467. _track_speed = _pos_control.get_max_speed_xy() / pos_delta_unit_xy;
  468. _track_leash_length = _pos_control.get_leash_xy()/pos_delta_unit_xy;
  469. }else if(is_zero(pos_delta_unit_xy)){
  470. _track_accel = _wp_accel_z_cmss/pos_delta_unit_z;
  471. _track_speed = speed_z/pos_delta_unit_z;
  472. _track_leash_length = leash_z/pos_delta_unit_z;
  473. }else{
  474. _track_accel = MIN(_wp_accel_z_cmss/pos_delta_unit_z, _wp_accel_cmss/pos_delta_unit_xy);
  475. _track_speed = MIN(speed_z/pos_delta_unit_z, _pos_control.get_max_speed_xy() / pos_delta_unit_xy);
  476. _track_leash_length = MIN(leash_z/pos_delta_unit_z, _pos_control.get_leash_xy()/pos_delta_unit_xy);
  477. }
  478. // calculate slow down distance (the distance from the destination when the target point should begin to slow down)
  479. calc_slow_down_distance(_track_speed, _track_accel);
  480. // set recalc leash flag to false
  481. _flags.recalc_wp_leash = false;
  482. }
  483. // returns target yaw in centi-degrees (used for wp and spline navigation)
  484. float AC_WPNav::get_yaw() const
  485. {
  486. if (_flags.wp_yaw_set) {
  487. return _yaw;
  488. } else {
  489. // if yaw has not been set return attitude controller's current target
  490. return _attitude_control.get_att_target_euler_cd().z;
  491. }
  492. }
  493. // set heading used for spline and waypoint navigation
  494. void AC_WPNav::set_yaw_cd(float heading_cd)
  495. {
  496. _yaw = heading_cd;
  497. _flags.wp_yaw_set = true;
  498. }
  499. ///
  500. /// spline methods
  501. ///
  502. /// set_spline_destination waypoint using location class
  503. /// returns false if conversion from location to vector from ekf origin cannot be calculated
  504. /// stopped_at_start should be set to true if vehicle is stopped at the origin
  505. /// seg_end_type should be set to stopped, straight or spline depending upon the next segment's type
  506. /// next_destination should be set to the next segment's destination if the seg_end_type is SEGMENT_END_STRAIGHT or SEGMENT_END_SPLINE
  507. bool AC_WPNav::set_spline_destination(const Location& destination, bool stopped_at_start, spline_segment_end_type seg_end_type, Location next_destination)
  508. {
  509. // convert destination location to vector
  510. Vector3f dest_neu;
  511. bool dest_terr_alt;
  512. if (!get_vector_NEU(destination, dest_neu, dest_terr_alt)) {
  513. return false;
  514. }
  515. // make altitude frames consistent
  516. if (!next_destination.change_alt_frame(destination.get_alt_frame())) {
  517. return false;
  518. }
  519. // convert next destination to vector
  520. Vector3f next_dest_neu;
  521. bool next_dest_terr_alt;
  522. if (!get_vector_NEU(next_destination, next_dest_neu, next_dest_terr_alt)) {
  523. return false;
  524. }
  525. // set target as vector from EKF origin
  526. return set_spline_destination(dest_neu, dest_terr_alt, stopped_at_start, seg_end_type, next_dest_neu);
  527. }
  528. /// set_spline_destination waypoint using position vector (distance from home in cm)
  529. /// returns false if conversion from location to vector from ekf origin cannot be calculated
  530. /// terrain_alt should be true if destination.z is a desired altitudes above terrain (false if its desired altitudes above ekf origin)
  531. /// stopped_at_start should be set to true if vehicle is stopped at the origin
  532. /// seg_end_type should be set to stopped, straight or spline depending upon the next segment's type
  533. /// next_destination should be set to the next segment's destination if the seg_end_type is SEGMENT_END_STRAIGHT or SEGMENT_END_SPLINE
  534. bool AC_WPNav::set_spline_destination(const Vector3f& destination, bool terrain_alt, bool stopped_at_start, spline_segment_end_type seg_end_type, const Vector3f& next_destination)
  535. {
  536. Vector3f origin;
  537. // if waypoint controller is active and copter has reached the previous waypoint use current pos target as the origin
  538. if ((AP_HAL::millis() - _wp_last_update) < 1000) {
  539. origin = _pos_control.get_pos_target();
  540. }else{
  541. // otherwise calculate origin from the current position and velocity
  542. _pos_control.get_stopping_point_xy(origin);
  543. _pos_control.get_stopping_point_z(origin);
  544. }
  545. // convert origin to alt-above-terrain
  546. if (terrain_alt) {
  547. float terr_offset;
  548. if (!get_terrain_offset(terr_offset)) {
  549. return false;
  550. }
  551. origin.z -= terr_offset;
  552. }
  553. // set origin and destination
  554. return set_spline_origin_and_destination(origin, destination, terrain_alt, stopped_at_start, seg_end_type, next_destination);
  555. }
  556. /// set_spline_origin_and_destination - set origin and destination waypoints using position vectors (distance from home in cm)
  557. /// terrain_alt should be true if origin.z and destination.z are desired altitudes above terrain (false if desired altitudes above ekf origin)
  558. /// seg_type should be calculated by calling function based on the mission
  559. bool AC_WPNav::set_spline_origin_and_destination(const Vector3f& origin, const Vector3f& destination, bool terrain_alt, bool stopped_at_start, spline_segment_end_type seg_end_type, const Vector3f& next_destination)
  560. {
  561. // mission is "active" if wpnav has been called recently and vehicle reached the previous waypoint
  562. bool prev_segment_exists = (_flags.reached_destination && ((AP_HAL::millis() - _wp_last_update) < 1000));
  563. // get dt from pos controller
  564. float dt = _pos_control.get_dt();
  565. // check _wp_accel_cmss is reasonable to avoid divide by zero
  566. if (_wp_accel_cmss <= 0) {
  567. _wp_accel_cmss.set_and_save(WPNAV_ACCELERATION);
  568. }
  569. // segment start types
  570. // stop - vehicle is not moving at origin
  571. // straight-fast - vehicle is moving, previous segment is straight. vehicle will fly straight through the waypoint before beginning it's spline path to the next wp
  572. // _flag.segment_type holds whether prev segment is straight vs spline but we don't know if it has a delay
  573. // spline-fast - vehicle is moving, previous segment is splined, vehicle will fly through waypoint but previous segment should have it flying in the correct direction (i.e. exactly parallel to position difference vector from previous segment's origin to this segment's destination)
  574. // calculate spline velocity at origin
  575. if (stopped_at_start || !prev_segment_exists) {
  576. // if vehicle is stopped at the origin, set origin velocity to 0.02 * distance vector from origin to destination
  577. _spline_origin_vel = (destination - origin) * dt;
  578. _spline_time = 0.0f;
  579. _spline_vel_scaler = 0.0f;
  580. }else{
  581. // look at previous segment to determine velocity at origin
  582. if (_flags.segment_type == SEGMENT_STRAIGHT) {
  583. // previous segment is straight, vehicle is moving so vehicle should fly straight through the origin
  584. // before beginning it's spline path to the next waypoint. Note: we are using the previous segment's origin and destination
  585. _spline_origin_vel = (_destination - _origin);
  586. _spline_time = 0.0f; // To-Do: this should be set based on how much overrun there was from straight segment?
  587. _spline_vel_scaler = _pos_control.get_vel_target().length(); // start velocity target from current target velocity
  588. }else{
  589. // previous segment is splined, vehicle will fly through origin
  590. // we can use the previous segment's destination velocity as this segment's origin velocity
  591. // Note: previous segment will leave destination velocity parallel to position difference vector
  592. // from previous segment's origin to this segment's destination)
  593. _spline_origin_vel = _spline_destination_vel;
  594. if (_spline_time > 1.0f && _spline_time < 1.1f) { // To-Do: remove hard coded 1.1f
  595. _spline_time -= 1.0f;
  596. }else{
  597. _spline_time = 0.0f;
  598. }
  599. // Note: we leave _spline_vel_scaler as it was from end of previous segment
  600. }
  601. }
  602. // calculate spline velocity at destination
  603. switch (seg_end_type) {
  604. case SEGMENT_END_STOP:
  605. // if vehicle stops at the destination set destination velocity to 0.02 * distance vector from origin to destination
  606. _spline_destination_vel = (destination - origin) * dt;
  607. _flags.fast_waypoint = false;
  608. break;
  609. case SEGMENT_END_STRAIGHT:
  610. // if next segment is straight, vehicle's final velocity should face along the next segment's position
  611. _spline_destination_vel = (next_destination - destination);
  612. _flags.fast_waypoint = true;
  613. break;
  614. case SEGMENT_END_SPLINE:
  615. // if next segment is splined, vehicle's final velocity should face parallel to the line from the origin to the next destination
  616. _spline_destination_vel = (next_destination - origin);
  617. _flags.fast_waypoint = true;
  618. break;
  619. }
  620. // code below ensures we don't get too much overshoot when the next segment is short
  621. float vel_len = _spline_origin_vel.length() + _spline_destination_vel.length();
  622. float pos_len = (destination - origin).length() * 4.0f;
  623. if (vel_len > pos_len) {
  624. // if total start+stop velocity is more than twice position difference
  625. // use a scaled down start and stop velocityscale the start and stop velocities down
  626. float vel_scaling = pos_len / vel_len;
  627. // update spline calculator
  628. update_spline_solution(origin, destination, _spline_origin_vel * vel_scaling, _spline_destination_vel * vel_scaling);
  629. }else{
  630. // update spline calculator
  631. update_spline_solution(origin, destination, _spline_origin_vel, _spline_destination_vel);
  632. }
  633. // store origin and destination locations
  634. _origin = origin;
  635. _destination = destination;
  636. _terrain_alt = terrain_alt;
  637. // calculate slow down distance
  638. calc_slow_down_distance(_pos_control.get_max_speed_xy(), _wp_accel_cmss);
  639. // get alt-above-terrain
  640. float terr_offset = 0.0f;
  641. if (terrain_alt) {
  642. if (!get_terrain_offset(terr_offset)) {
  643. return false;
  644. }
  645. }
  646. // initialise intermediate point to the origin
  647. _pos_control.set_pos_target(origin + Vector3f(0,0,terr_offset));
  648. _flags.reached_destination = false;
  649. _flags.segment_type = SEGMENT_SPLINE;
  650. _flags.new_wp_destination = true; // flag new waypoint so we can freeze the pos controller's feed forward and smooth the transition
  651. _flags.wp_yaw_set = false;
  652. // initialise yaw related variables
  653. _track_length_xy = safe_sqrt(sq(_destination.x - _origin.x)+sq(_destination.y - _origin.y)); // horizontal track length (used to decide if we should update yaw)
  654. return true;
  655. }
  656. /// update_spline - update spline controller
  657. bool AC_WPNav::update_spline()
  658. {
  659. // exit immediately if this is not a spline segment
  660. if (_flags.segment_type != SEGMENT_SPLINE) {
  661. return false;
  662. }
  663. bool ret = true;
  664. // get dt from pos controller
  665. float dt = _pos_control.get_dt();
  666. // advance the target if necessary
  667. if (!advance_spline_target_along_track(dt)) {
  668. // To-Do: handle failure to advance along track (due to missing terrain data)
  669. ret = false;
  670. }
  671. // freeze feedforwards during known discontinuities
  672. if (_flags.new_wp_destination) {
  673. _flags.new_wp_destination = false;
  674. _pos_control.freeze_ff_z();
  675. }
  676. // run horizontal position controller
  677. _pos_control.update_xy_controller();
  678. _wp_last_update = AP_HAL::millis();
  679. return ret;
  680. }
  681. /// update_spline_solution - recalculates hermite_spline_solution grid
  682. /// relies on _spline_origin_vel, _spline_destination_vel and _origin and _destination
  683. void AC_WPNav::update_spline_solution(const Vector3f& origin, const Vector3f& dest, const Vector3f& origin_vel, const Vector3f& dest_vel)
  684. {
  685. _hermite_spline_solution[0] = origin;
  686. _hermite_spline_solution[1] = origin_vel;
  687. _hermite_spline_solution[2] = -origin*3.0f -origin_vel*2.0f + dest*3.0f - dest_vel;
  688. _hermite_spline_solution[3] = origin*2.0f + origin_vel -dest*2.0f + dest_vel;
  689. }
  690. /// advance_spline_target_along_track - move target location along track from origin to destination
  691. bool AC_WPNav::advance_spline_target_along_track(float dt)
  692. {
  693. if (!_flags.reached_destination) {
  694. Vector3f target_pos, target_vel;
  695. // update target position and velocity from spline calculator
  696. calc_spline_pos_vel(_spline_time, target_pos, target_vel);
  697. // if target velocity is zero the origin and destination must be the same
  698. // so flag reached destination (and protect against divide by zero)
  699. float target_vel_length = target_vel.length();
  700. if (is_zero(target_vel_length)) {
  701. _flags.reached_destination = true;
  702. return true;
  703. }
  704. _pos_delta_unit = target_vel / target_vel_length;
  705. calculate_wp_leash_length();
  706. // get current location
  707. const Vector3f &curr_pos = _inav.get_position();
  708. // get terrain altitude offset for origin and current position (i.e. change in terrain altitude from a position vs ekf origin)
  709. float terr_offset = 0.0f;
  710. if (_terrain_alt && !get_terrain_offset(terr_offset)) {
  711. return false;
  712. }
  713. // calculate position error
  714. Vector3f track_error = curr_pos - target_pos;
  715. track_error.z -= terr_offset;
  716. // calculate the horizontal error
  717. _track_error_xy = norm(track_error.x, track_error.y);
  718. // calculate the vertical error
  719. float track_error_z = fabsf(track_error.z);
  720. // get position control leash lengths
  721. float leash_xy = _pos_control.get_leash_xy();
  722. float leash_z;
  723. if (track_error.z >= 0) {
  724. leash_z = _pos_control.get_leash_up_z();
  725. }else{
  726. leash_z = _pos_control.get_leash_down_z();
  727. }
  728. // calculate how far along the track we could move the intermediate target before reaching the end of the leash
  729. float track_leash_slack = MIN(_track_leash_length*(leash_z-track_error_z)/leash_z, _track_leash_length*(leash_xy-_track_error_xy)/leash_xy);
  730. if (track_leash_slack < 0.0f) {
  731. track_leash_slack = 0.0f;
  732. }
  733. // update velocity
  734. float spline_dist_to_wp = (_destination - target_pos).length();
  735. float vel_limit = _pos_control.get_max_speed_xy();
  736. if (!is_zero(dt)) {
  737. vel_limit = MIN(vel_limit, track_leash_slack/dt);
  738. }
  739. // if within the stopping distance from destination, set target velocity to sqrt of distance * 2 * acceleration
  740. if (!_flags.fast_waypoint && spline_dist_to_wp < _slow_down_dist) {
  741. _spline_vel_scaler = safe_sqrt(spline_dist_to_wp * 2.0f * _wp_accel_cmss);
  742. }else if(_spline_vel_scaler < vel_limit) {
  743. // increase velocity using acceleration
  744. _spline_vel_scaler += _wp_accel_cmss * dt;
  745. }
  746. // constrain target velocity
  747. _spline_vel_scaler = constrain_float(_spline_vel_scaler, 0.0f, vel_limit);
  748. // scale the spline_time by the velocity we've calculated vs the velocity that came out of the spline calculator
  749. _spline_time_scale = _spline_vel_scaler / target_vel_length;
  750. // update target position
  751. target_pos.z += terr_offset;
  752. _pos_control.set_pos_target(target_pos);
  753. // update the target yaw if origin and destination are at least 2m apart horizontally
  754. if (_track_length_xy >= WPNAV_YAW_DIST_MIN) {
  755. if (_pos_control.get_leash_xy() < WPNAV_YAW_DIST_MIN) {
  756. // if the leash is very short (i.e. flying at low speed) use the target point's velocity along the track
  757. if (!is_zero(target_vel.x) && !is_zero(target_vel.y)) {
  758. set_yaw_cd(RadiansToCentiDegrees(atan2f(target_vel.y,target_vel.x)));
  759. }
  760. } else {
  761. // point vehicle along the leash (i.e. point vehicle towards target point on the segment from origin to destination)
  762. float track_error_xy_length = safe_sqrt(sq(track_error.x)+sq(track_error.y));
  763. if (track_error_xy_length > MIN(WPNAV_YAW_DIST_MIN, _pos_control.get_leash_xy()*WPNAV_YAW_LEASH_PCT_MIN)) {
  764. // To-Do: why is track_error sign reversed?
  765. set_yaw_cd(RadiansToCentiDegrees(atan2f(-track_error.y,-track_error.x)));
  766. }
  767. }
  768. }
  769. // advance spline time to next step
  770. _spline_time += _spline_time_scale*dt;
  771. // we will reach the next waypoint in the next step so set reached_destination flag
  772. // To-Do: is this one step too early?
  773. if (_spline_time >= 1.0f) {
  774. _flags.reached_destination = true;
  775. }
  776. }
  777. return true;
  778. }
  779. // calc_spline_pos_vel_accel - calculates target position, velocity and acceleration for the given "spline_time"
  780. /// relies on update_spline_solution being called when the segment's origin and destination were set
  781. void AC_WPNav::calc_spline_pos_vel(float spline_time, Vector3f& position, Vector3f& velocity)
  782. {
  783. float spline_time_sqrd = spline_time * spline_time;
  784. float spline_time_cubed = spline_time_sqrd * spline_time;
  785. position = _hermite_spline_solution[0] + \
  786. _hermite_spline_solution[1] * spline_time + \
  787. _hermite_spline_solution[2] * spline_time_sqrd + \
  788. _hermite_spline_solution[3] * spline_time_cubed;
  789. velocity = _hermite_spline_solution[1] + \
  790. _hermite_spline_solution[2] * 2.0f * spline_time + \
  791. _hermite_spline_solution[3] * 3.0f * spline_time_sqrd;
  792. }
  793. // get terrain's altitude (in cm above the ekf origin) at the current position (+ve means terrain below vehicle is above ekf origin's altitude)
  794. bool AC_WPNav::get_terrain_offset(float& offset_cm)
  795. {
  796. // use range finder if connected
  797. if (_rangefinder_available && _rangefinder_use) {
  798. if (_rangefinder_healthy) {
  799. offset_cm = _inav.get_altitude() - _rangefinder_alt_cm;
  800. return true;
  801. }
  802. return false;
  803. }
  804. #if AP_TERRAIN_AVAILABLE
  805. // use terrain database
  806. float terr_alt = 0.0f;
  807. if (_terrain != nullptr && _terrain->height_above_terrain(terr_alt, true)) {
  808. offset_cm = _inav.get_altitude() - (terr_alt * 100.0f);
  809. return true;
  810. }
  811. #endif
  812. return false;
  813. }
  814. // convert location to vector from ekf origin. terrain_alt is set to true if resulting vector's z-axis should be treated as alt-above-terrain
  815. // returns false if conversion failed (likely because terrain data was not available)
  816. bool AC_WPNav::get_vector_NEU(const Location &loc, Vector3f &vec, bool &terrain_alt)
  817. {
  818. // convert location to NE vector2f
  819. Vector2f res_vec;
  820. if (!loc.get_vector_xy_from_origin_NE(res_vec)) {
  821. return false;
  822. }
  823. // convert altitude
  824. if (loc.get_alt_frame() == Location::AltFrame::ABOVE_TERRAIN) {
  825. int32_t terr_alt;
  826. if (!loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, terr_alt)) {
  827. return false;
  828. }
  829. vec.z = terr_alt;
  830. terrain_alt = true;
  831. } else {
  832. terrain_alt = false;
  833. int32_t temp_alt;
  834. if (!loc.get_alt_cm(Location::AltFrame::ABOVE_ORIGIN, temp_alt)) {
  835. return false;
  836. }
  837. vec.z = temp_alt;
  838. terrain_alt = false;
  839. }
  840. // copy xy (we do this to ensure we do not adjust vector unless the overall conversion is successful
  841. vec.x = res_vec.x;
  842. vec.y = res_vec.y;
  843. return true;
  844. }
  845. ///
  846. /// shared methods
  847. ///
  848. /// calc_slow_down_distance - calculates distance before waypoint that target point should begin to slow-down assuming it is travelling at full speed
  849. void AC_WPNav::calc_slow_down_distance(float speed_cms, float accel_cmss)
  850. {
  851. // protect against divide by zero
  852. if (accel_cmss <= 0.0f) {
  853. _slow_down_dist = 0.0f;
  854. return;
  855. }
  856. // To-Do: should we use a combination of horizontal and vertical speeds?
  857. // To-Do: update this automatically when speed or acceleration is changed
  858. _slow_down_dist = speed_cms * speed_cms / (4.0f*accel_cmss);
  859. }
  860. /// get_slow_down_speed - returns target speed of target point based on distance from the destination (in cm)
  861. float AC_WPNav::get_slow_down_speed(float dist_from_dest_cm, float accel_cmss)
  862. {
  863. // return immediately if distance is zero (or less)
  864. if (dist_from_dest_cm <= 0) {
  865. return WPNAV_WP_TRACK_SPEED_MIN;
  866. }
  867. // calculate desired speed near destination
  868. float target_speed = safe_sqrt(dist_from_dest_cm * 4.0f * accel_cmss);
  869. // ensure desired speed never becomes too low
  870. if (target_speed < WPNAV_WP_TRACK_SPEED_MIN) {
  871. return WPNAV_WP_TRACK_SPEED_MIN;
  872. } else {
  873. return target_speed;
  874. }
  875. }